From 21cd2940a91ca19aeab9dac4883d20b6608dd5e7 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Wed, 26 Feb 2025 16:22:07 +0100
Subject: [PATCH 001/171] 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 <simon.alibert@huggingface.co>
Date: Wed, 26 Feb 2025 18:48:58 +0100
Subject: [PATCH 002/171] 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 <simon.alibert@huggingface.co>
Date: Wed, 26 Feb 2025 19:02:15 +0100
Subject: [PATCH 003/171] 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 <simon.alibert@huggingface.co>
Date: Sun, 2 Mar 2025 21:29:35 +0100
Subject: [PATCH 004/171] 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 <simon.alibert@huggingface.co>
Date: Sun, 2 Mar 2025 21:33:22 +0100
Subject: [PATCH 005/171] 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 <simon.alibert@huggingface.co>
Date: Mon, 3 Mar 2025 18:01:48 +0100
Subject: [PATCH 006/171] 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 <simon.alibert@huggingface.co>
Date: Mon, 3 Mar 2025 18:18:24 +0100
Subject: [PATCH 007/171] 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 <simon.alibert@huggingface.co>
Date: Mon, 3 Mar 2025 18:44:15 +0100
Subject: [PATCH 008/171] 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 <simon.alibert@huggingface.co>
Date: Mon, 3 Mar 2025 18:44:39 +0100
Subject: [PATCH 009/171] 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 <simon.alibert@huggingface.co>
Date: Mon, 3 Mar 2025 18:49:40 +0100
Subject: [PATCH 010/171] 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 <simon.alibert@huggingface.co>
Date: Mon, 3 Mar 2025 18:53:45 +0100
Subject: [PATCH 011/171] 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 <simon.alibert@huggingface.co>
Date: Mon, 3 Mar 2025 18:55:59 +0100
Subject: [PATCH 012/171] 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 <simon.alibert@huggingface.co>
Date: Mon, 3 Mar 2025 18:58:54 +0100
Subject: [PATCH 013/171] 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 <simon.alibert@huggingface.co>
Date: Mon, 3 Mar 2025 20:17:18 +0100
Subject: [PATCH 014/171] 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 <simon.alibert@huggingface.co>
Date: Mon, 3 Mar 2025 20:17:54 +0100
Subject: [PATCH 015/171] 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 <simon.alibert@huggingface.co>
Date: Mon, 3 Mar 2025 20:19:23 +0100
Subject: [PATCH 016/171] 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 <simon.alibert@huggingface.co>
Date: Mon, 3 Mar 2025 20:31:04 +0100
Subject: [PATCH 017/171] 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 <simon.alibert@huggingface.co>
Date: Mon, 3 Mar 2025 20:42:48 +0100
Subject: [PATCH 018/171] 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 <simon.alibert@huggingface.co>
Date: Tue, 4 Mar 2025 11:07:15 +0100
Subject: [PATCH 019/171] 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 <simon.alibert@huggingface.co>
Date: Tue, 4 Mar 2025 11:24:05 +0100
Subject: [PATCH 020/171] 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 <simon.alibert@huggingface.co>
Date: Tue, 4 Mar 2025 11:38:31 +0100
Subject: [PATCH 021/171] 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 <simon.alibert@huggingface.co>
Date: Tue, 4 Mar 2025 11:42:07 +0100
Subject: [PATCH 022/171] 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 <simon.alibert@huggingface.co>
Date: Tue, 4 Mar 2025 13:32:58 +0100
Subject: [PATCH 023/171] 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 <simon.alibert@huggingface.co>
Date: Thu, 6 Mar 2025 10:24:27 +0100
Subject: [PATCH 024/171] 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 <simon.alibert@huggingface.co>
Date: Thu, 6 Mar 2025 11:46:06 +0100
Subject: [PATCH 025/171] 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 <simon.alibert@huggingface.co>
Date: Thu, 6 Mar 2025 12:53:55 +0100
Subject: [PATCH 026/171] 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 <simon.alibert@huggingface.co>
Date: Thu, 6 Mar 2025 21:31:35 +0100
Subject: [PATCH 027/171] 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 <simon.alibert@huggingface.co>
Date: Mon, 10 Mar 2025 18:28:50 +0100
Subject: [PATCH 028/171] 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 <simon.alibert@huggingface.co>
Date: Mon, 10 Mar 2025 18:29:58 +0100
Subject: [PATCH 029/171] 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 <simon.alibert@huggingface.co>
Date: Mon, 10 Mar 2025 18:33:28 +0100
Subject: [PATCH 030/171] 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 <simon.alibert@huggingface.co>
Date: Mon, 10 Mar 2025 18:34:01 +0100
Subject: [PATCH 031/171] 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 <simon.alibert@huggingface.co>
Date: Wed, 12 Mar 2025 17:15:39 +0100
Subject: [PATCH 032/171] 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 <simon.alibert@huggingface.co>
Date: Wed, 12 Mar 2025 17:16:09 +0100
Subject: [PATCH 033/171] 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/171] New Feetech calibration (#859)

Co-authored-by: Pepijn <pepijn@huggingface.co>
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<?EbU4w~|jPRk_j0
z$*I&;k(Q7kd4vLJii;>|C~;}Q0002Ge>4aC-zzODs)PmlFAD(0GInyZ1OJEY9o$@0
zBt?j{v~`G}jsYP5p8pBPrmjxHN=kD7W&U^ize@gh{Ji?VWS8jwtLyTsIF2h+^0$3U
zucG%KEXMyW_5Vm=%*<U)|CN3IBPLTP7dHR^<iCb0dAK?KhkgHHG?#yk`iB$#!<PRG
zm;8rK{ul1}9~m_j(SI`2|1goMm9g1BeEAR4nfzaT%l`}8+qwVu-T%UWJ%uxOP*?qz
zqWvR0fEd6U;0ka8*a3_IUH~G15`gvpA<y<d@}dC8f6`t6mw$Se04spoKONzJod0St
z|A(ak4ggaC!@nsY0<Zv>{t?T6<NQzeUwB^m|HqH+|L{U~0RaAfAQ0I7e|R$e06-%r
z007hZe|S_}001&905IO^Wb9)6Kh=T#i$N_c0D${)003Sa06?Apr=#m?!OHSK<sfh(
z006`e5cog=06--J0AC3};71V<_*D!5fNcQ)0}lUI3{lb+6oAQ#B^QKd9(Ep9AW<ww
zwzRmTv6xLK8VTixwf#x91tBF6XxN_syvl|GUhMXFfdPRvYhJU6T66bq&li~AeeMCk
z_X!~A7xKQUKz%qx(5*n<=FKhP=I0zw{aZXaaQlw@neZiVAit5%EW7^_^*Hofk&g!z
zc=Oo&bpnJ^Rs8b32@pL2TbY>tf(EW8V`$%d!zw72{H)e1%>@?R1HM^-jO&U|;m;mT
z^<M$<yBGYhk8j>6{N_MUriuP1;N#=m{q9}A-KXE@)K$P4Fa@aovhafZW%w<4^+n^e
z`?32exCQ+EY<biECO8YMeu@3QxjM-elyb-XeE4AeW}NE}i9f#^Jmj11`T&NUhkqEh
z8!Ua#0TF@uAButX=eq~}R(=P-qoexI{I9$r!oz^0_pX33;KR2^rQo{Y@dwQJl(+A{
zc|5tpefc+^-|-Q1TZ+KTAlO!(SZNfPHxi5&HZ*_*p?CZcI3#=ZQ|JPTQ{8XqVQn(<
zbgs693G)>}lc3PsK9_G#bp7PgU^w;dzZpgIa^$7?GmM_CDbza#_3IuwEf!5)$(6IA
zrj|as3)r<1%S7aw`y#hRkh|r?=<aMxI_JejL;7rq1j>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_t<Kh2C+kzhQR
zZ%ERm!^lE#DE#Gn;Le}-J9Dm;9jX;QBsm9uVoG78z{-L1<!I3}KzXgmW!XnggYP>L
zBD{n6LG`>x#EOJNs7G&`3!wtTR3OrX+$R$Hk3@E|Ha_b7ju+lR>{@-}l#RSfT54DD
z<eq*+mMWMYS``HLw<P2(c_jAlAU5K~gZXdGp~PP|D+5D^??guDJgN<ByQcDV<?l<m
z*)poV8Ljqslv)n2E;#0f%LoeHE0c>ElF8<in$99M8B=~96tahs+Do!3R@1zWj9gMm
z406|uP!aU=j+M-NJIg`;{ecRSfjW(~kjuQZGHcAI!vmKRBFBpovm%ITN_yhs=voTd
z(i*sya5eEHqd)!=wP+Fga;{mY$)0&@()>}#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?JZQMrqVR<tXJ#OiNC
zaTt=ma`59I{c5^yTSBY4<ryFJ{Z9bTRB-GFH!t)3@Xu*hATD`#RLNeNK}~RW!g2oD
z7~yFLl!Ee~G$yvHgIZa1vY3r;dWN?17nHV{j3bQLq&jiGR+x9Owu1;#`>K<X!uIEP
zFPKhjU!1y9FUM<1NwEYiM4`&Y=X7?lf*{%ib#7lU1_3MxBJk!+Qb1`v`#Iy0#E(cn
zd`*>g@I7Q))-q$6ke_OiQ&`D64${hZ)o8LcFszW@^l)`dGz9w|{HdK<a6n~mM8{XI
z{7a=~p7ho(wOjWM=nyrL9niXb{W#Qxe1>NYe7E#$6kLGY?_-JM<Y7UA$IO{e${ogZ
z{j}eE(jhJVM^E#Q5sWEFWU(#0%J||*uNWgX4PhNFB{fETMTbMJE06{s?Na*zIiV|N
zi9`inbM#$FM|X7Q7kei53<3o|8q_qO(b**gJSWB-Vd9}wbzH-hh-6N;55+H~Ws@*?
zLxdRpSW8_Ki&l-25%Lm`gOWow;Sz9nRc>TI{>F~B=7ll64TH}ht(LM=wjFyp@S-?<
zE~&f)XgB3w5tLMqWczNxBXss7KL2rRo{b18W;q;^csLy!BZ*@j_~g!Y18)2xv{)}(
z91h3IKR;yMsEpyhoTQ8K_R3)|HstqnleB(u<TQ!Z@;`ZMM`&1`3sv;CPnW3$C0DRo
z--!gK+QNlD6~roPJ`}dG5?LBG&8r4jx7e(4KFE8f%uyFIK8&IMnN;LZ_0~$B4PZCB
z?bUuR#~}OOM``olBftN>G~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%@<Bo2DVK?Oe!&ETHE)QqjFGJAXHw1krWV
zGoaPzp0+Zz6WK4rfn7P4YQqG@#;COZ5k<Q;0b5p3Lj5<ZWXyR2wwe#u=?z~E7@aiC
zI<wZ!Ma}sfq)T@+>(@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<lQr;+JmrWhFfaL?)=m}Dml5e}I
zQV7O~4CV_K0>!ZvrcY?&s@9+1S4I~CLgHCzb9TcPTGk-mw&^fGmStj^UBSB4<Pa53
z>$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#T<ph>7GB$13fnDJ*C$vT<~Q0@W%T3Qw_Su?Xo%@Esk<ISQL%9Hy2Ld{>I%gQ-)`p
zhZ(1&EazUk`9qbpmkjn&1g3}=HV|Tn1snRfoK8=+GeU)50UMSOp6rL4nO}Je%ie}@
zd+}nt+Xd6Yj+3rIt!dxJ3-$C{0}VO++<yisUO)Y=5~<3#vF*C4NZxDD$Azb>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@|Y<hv9ZaY)sFBwp>btM6=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>J525KiuzuY<AdTQ0VXdgrA-S@jsScA0@MPaZ?xDeb~;Z`go)%
z;~nFTW&)ZuDhMNVF$KRN!=b2JW$<)oaci90-WqGx0ZN%!VUo$D$Im{cT&YkL<X7NM
zRYZy_ox6BniyH#vgg31xnayQCw;}_9GV+9FjEJi_dLW3WoifHmg(#&1_wgF1A|DY{
zC2hXm-K`YviM-KQqcsNPp@gry-VVtvaB8)YGK@d>z;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@M<Qh2yV1^)mY9<K#-@j`eQFhIlt(;g=Ms?RR)asQTD(vEH^Wgr
zfT>KQ#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&t<znEyR98=lQ96nR}rJ!p=MI7ijb_rBlbA$c%PA4Q^Wbcwn?p^5LYi<Vm
zVXF$fH_I*3Fu91BtdM9oZ)32#sKf8<pkV!B{Qh0S2O}yQOS9-5v4uVO8X#LrX_psI
z23oMHcPhL2r`io+nNN82WaN|R3T!QB!3I7+m$t5I+HVw5uYM$NDX-`>6%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<J>^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&hQ<Mq6k!*p=Pv!GuX}G<8c-o=UPrD@f@>P+A{w8H
zr_$-|bh;cCQZ*SfR+<Qw`h=@cQz``=S8E(OWz)=t%RR4*x2K2eKAwR%t))5F`R-xg
zx|l7E5p*4SS(GVyC65Kc-B04GLA{xZB}IFMvf`I-56Mkr<7}!c&^s=EE#j7TW;cc>
zF{_or_S3NZf;rA|oCp8PtF{%HMRHEK>EN3wd88)i`UnEN1g5h;18mvs8?In&k74e7
zl{UP~ofAm$xLsA`c(2dy&$fviskxti<n9Eu7+Jg~2^IyEFZ0>G*I}-Snqog$Hsg&5
zKLpi?3H4cGtOcw@8-d`DK!-cdygYc$N)E^I`%m#Jg=}FKn!v+H2TEQLku8}#TIyxk
z3%*JQYSkq#J14K6baM12EOLs=SCZ@c<Wll+`w^32GG*-FX#}-%=PPXLU7G{YRgQc1
z)~&7{pP&*!w~})Om5@L-x|$UKmT#}z+R#V%NE9omQS5jZPEqI;w>Z3LwwZF>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=G6Vw8UuV<Tt)Kx-=2+1UPN-dtS@X$ayhKD*7vuH
z_w=kh1g$U7TbE|x-gc)4YWHw%5n$^&p13)1;T7_m@A0*8P04+|YLq)h1&T0&aZW+W
zsbrc56LYNcc5gk3xQRsx{%ol43JFvd@k%YxKQT1HX#ss2Ac7Zb!uzC@YnHF=Ccon`
z>9hG2UQ%=5GinNwM-hmk4?dzy2wJJT>*wkQjl#hBm8FvTc6uXy*HWmRjOGbFAwDg6
zvZj#_pO2P%BH}(Dw)JObTlOV#<5Q@!>bcNk>rj>hYmp^8UCt%;L<fU5R5s=};8R&~
z(~tb}^-NIWh(|e!j;tsBP(b-0FEtQ6_(_4NV|CUAEh@@~mNTtoeLsPfpvaCO%}z^Z
zKvqW5o;y{eHM!6C-@%Rnn<QfsO9!W`ehrG~7yC%dXBX3XQn&M>5~We?oJH>S^lqR<
zRal-aNv)OR8?I?i;GLJB4{-N5dXCZbRIi!+J4XLJ+IIFWTQH<&hsn>28d3t`v(-2n
zSq#Ue2D5$>KlfcT=tT<?=pmEwxB7=7(etpKd-PAPE{<<q!e8zK;cNP(e8PsjBNtc}
zemw|X#X+*cUCLtMEp_cV1sv|eQ(kPP@@NyrK_AFesFbV8$J<0W3aGQpDMPt^GG}~F
z3ucHHR%mp@_Z8T5`ee+%=;P#MH`6J|9}hz$8WE|L2Zea`G3z)`_B)l=9XctMVSlCz
zsjRvU8J@1KFPw`$%`7aPcb$jr*)IR}w#<vk;q-6Mt}lSu!gC84mzn&L8^zSGnJ}2`
zrK^6FpDcKFbeDpy7)nejx^BC5a9_%la@}LLfgv9<XmvBQ(CykeD_~2T>|~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^`L9M<oK5668BoeDc{|&&SYI73
zMmw9^d-B#-3Sfv*FY`acf+7Ag5!?ymYXwzqqWdgn#)T!YqZJ$bt?G@Sv_e9Au5Ss?
z)|cx`Ww9UsCw#zcrdCqAV!*yos&XTh_ZXR@gNJyBW0n#=KUMi5=O#ppY!$IQY@X~h
zUSG`h0%vnO_7uzzrkRK20Yg;@J#Kfk$Nuq{vTRNN#~UAuC@jSWD=<TIZn91TRoWQQ
zhwKIlq(=cx!DRHkrPMor{rN)EJu7TR><C_PqG%N?bb}YVFcxtI-i9d|$ftwV(T2AV
ziHiu$@vN4qwS~Q)5+~zf`(4Y_>zptg5)3fOA%v>Bs%pory-aTyOB+t(m7OiTXKo&L
z9j`n(A-hMzL}+bFH#>=LMr}7*s&!8j3gq`993K~o&E2IS!3QQU<T+35Vfr@3@5L(L
zro2dyhU4$i@<V6j8(*NXjYtcEkYaFwqd)G$?dCY7Te7x5A)^bTi+%3z1111*)lGK$
z3QC>T<Go+nH$qABnf~~6j@m`btZ4=9TORbw?#rD?Lgb)2oHWpP*bP+B%1f<}-ZvYH
zKum_|lXfzj$rdz0QVoMYBU)9toEG2eeeyNa{T`^V61hicPcTEDPt9#Lzn|6#^g7Nx
z-6<CmiR*RmJ0;IA>9=_=tc?A0jUD(ORfYP+v|b$L)A$BFAD6<D__T?q?%wqiaU#rO
z;}3RfCD$TU9>{`l6c_zW9oK;2N8{~Dj(c+Kwl&<rFndT6STOwK67-nn;&V{oY*zjR
z^pK5gx8?fUldwz!g7DfRslhz<4`+vPrWY6LvN1mFlO~?1ToV)faKe^+NLEDN4a88=
zqtx{0-x#z!50`6`C;DxV&YkN=ks9~RUkX2J>`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@D<rBR8bI9=Xex&&^FJrG>5Yo$~pZrvdHQ_~u
znHd@pBFRTRPnFRhB_$}DUr45lm?x^fa-lyvoonmI%tFY(y;R7;zOlm&S?-<pB~|SG
zFXJ7ixKkm0bihBcMB^6l9`d6I2)1*ireW(Uob3x;(uQ>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(<u9kK*Ne#o?1>w+>K!Sw%L`}-q;ldIJ<)oe`(<4z+h|D(_Q?(;7@8TRs&v*-
zfs7MPTE<ASe5Z`bpvl^bv_P<|JNuY?wWq`-lfDY9hc~S{$Gn$^Oc1=ZbWIS?-*obT
zx<i)BTEY|YLzH~qPf1Lt9V%w<d%xcn(<#6EyfF$zB#Y9gY;{q7kZle<cX1eNIyqk=
zpcta66XsdM9ap3rK8Sy2B0RF0XH|ho1VC3POhyNa1>f69NY>0YF?zIbN8c3V%H0Eo
zX3ryTHyG210}4RKjN~M!0W*FXO4rpfSszibi}D1k5Vax%qVj5OwMR7y)fJX36yO{u
zDxZ3PKJ(~vGSb@_<YYHW=J)8<>9v1V^zqPufF+|m?|TJcMH><>SEC5T9K&h5>p7g9
zrzrBnGdz^Th2g%I3tuo$KSz&m^}n>?<zygHt9Lz(Jn0xNLq>QLznw=2k#*3YVGtSk
zVWIn+fv|rbIFqU7#orG+p^E5G&U>0qv2m)e(PA%`Vk8T<`}@MDj0r$+!!~(vobB6r
zIG!Q##&<A8f;H>3)T4b3`cs?}>3(QM^u@qUlGL3lsKZikVG&R>f~8AxNBhiHNs|=W
z<kNaTnI}PGco0Ie{CT6X`Ucd!s-@(PRwRrJSqxV}AA^8=x72av8N9H8+Cm@GKry~V
zO@wzoeV;yDZSQP#QYdyQN5;aLOoBB_m3F<>MP-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(A<rW(AH{bw|sGu5Yxf>tQH#~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`Zm<o}JVcwiQ1Iq8INxYv(S<$V86A)L%
z_Emo%P>ZM2*=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<57<r~8CdQzI(QRqylhOc`?sC^#-!Q_z0%_nd#kK9Mc|!R2>ggXOR6`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@AYR<bHmV*z2e<r)eh0LZwtvhOsGNfLRYgt!YqLH
z_+ot5JMQ!WlPl-=+m7Z7OwAHNV#U?{FBt<c3RJ`T0f6aMPIB{=Pjd2|`n#rP>aEul
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?MxTQvYXU<F@-<#P>C32}PW-@UW<=sVFEKa~u~yf=U1+WLX{_>?keh4h
zjM<yF2c4Jm8}IST{!X6OA{q|eUJTyN_+AUV(f7Avn{eJzDf9K+@B!U2aw0za`JX84
zb(G(;;|}u55A-T{TJL6;)nq1zPQRN!WNNaLOVHs4ql?|aiH=`KDsZAc(JiiKo&W7C
zvmzUVh7)r2)y{UkL-4j9+B*Ry5Iya(0!*5q$S+PplPFGQGAQ?yF!nGW$@%riHfLQX
z;;#fH1$E}iQkhX}?+=x>UtY^?fL1DmIjiI+DjOCdnD9C0oet!_Rga)4;V_4A1M7Ny
zEiZ<7urY5%7omNiP`DM^wgSP<Th-M$+o`=U%lrHB@AfXz5q#iAd<86dF^C`ASqKKG
zg%wt0y8zCd!ht^A_usoj+`m7=z#R10!O3PcmL#@bCX$!KYcTqjWbW_VYKkR#uw`vN
z5c>5TbBPRa@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;u8SW<D7@J6<!
zrtIRm<-D0#Grr2F+0m|&k@PuEOevHEO?#2psiHBZVWCYnIx*l48+~6rE6O@MT!kA1
zCZKoq1k;ublv)tZ#(-cwj%&TU5sNVhCI6!BS=U8|w!BR^z%x&*pZrI`PkAhl>LLYO
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<U@iikn+_*ns>_>BS8xVoy2GV~HCBJaMMi8e0CZERLRa0!pGPYViNF!<Rc>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<TJCzf`OD8Q>!;R93F`C#H^rTtS_ehyBte*2@hw|)8k1w8$270
z<WnlP#Gz_$#}di5kvOK*b2C=PL$tC<HgaGF6?g{Il|@U^WqKwt9a`h=G~jd0_ga*<
zR8J5tu=gGJT%WGi`w=dp478n}R-3y5=RGdEj`Mwa6IL_ywjM#(-}VqdYc;F=B%&9t
zovb%%(`Uys%!soe)}{385ofEDnj0Uzp`cmKGSo-i=`EnoS)Mn(ty52GTQEJHGfq~e
zC}q^0w)z~6M_}*mCeQ8xVP7QvR%soPRvF7pkj=6TcPW(#bIU!IlJ)UIZv-M{+k2Ui
z+AFQ$JG3H8rD#f;AmhQ{QY)x9r>0Bh;myTReHE=&XDP<W@Nlcs7zds>#MS<x(mzpI
zJ0zeDuT4X1Gy8Yi+Xj&}5eigAZPg1kpSe>A{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(&gtV;>lb36
zzAc&(-{TK#y|3n+V)-jv566rTDM1Mnd?QA+=x%gAG8uj%#0sfVZQg!|;^c}}Y(Zur
z#o5|qIkG3hL>TQpE)B9R(!l|F<jJ{Wne(qG`(fOv#`<zZ>5~IQkl)OA1gOC68!Pm8
zf|@3}>Ru{){d)R+%rE$%gg-3W_OdaVR+`J76s%%(q4r2xqmDMDB-vEx6HB<TS@B_$
zRi2v9Lan>8+RTgHB&#az{%#ZeQ1s2($%$nq^WM-%JRf+rMuzn0duq}?6`=zs<syOE
zuW(jX(JTiyLXkBUr;sO}=X6Iw908rbf-n+M!I6VCu(Y^G-p(Z@;SMn|F{4Pv;mKgT
zuKL_&wzRH23EMIDXGmk3WJx<mJJ(U#?};ansa8d+-GA#IdV$vUf4ors`r+IOgH)<1
zwLF1Z_BN<5#^4am_j<ZgiRdPm@z8R1-Kg~Mii<GD1IJ1g<@sp%W?3~Bv5tx2U^gQ%
z;)NW%Da&CSXEKXOT1PFN0_s_&g;7%M_iXuNmKBRa4QZ*4KmN#{#8@R8oe{i#mHxZF
zbBrX+`7l+-AqDwRHNSDc3fGiw+9J8J$5n@A)bzN0BuL3<tT*~>|1Y{tBZ|2c%;|nx
z`R=kYOi@eXB-T_i$JN8hXDiX1wGML!G4l@z1sH{ko6<tfl>GqdLTKxPzc*x2kJp1D
zzI1%z-yEfw9EUJc;bTQ9L<R;lxp!=Mn{On#{(NC=ID1xUH^#)N3!C_;_&7AC45`-o
z(Rm{|l9{z@Qoz+_OW@b5Yr{d%ORu*^)%yd#N!0MDozCBY{+kd@!2bA0NjQez<q)g7
zbx)p_lw6bqavF<4FbWt<5vTD#_sFM9Q4D=`<||pet=1+?7yGGywiMe^N!k=5X$aL@
z<ah$2F^Sk;{Nc~^4&>cUo8<A(Y4RbS-vYX2;mEkW6lpLpO5_uCY(1sLU>Okfek#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;+wQe2Wa3<JAs={Vle#|DE0vk
z8llS}{X#V#95*p&P>U|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&7qm<pp~jUVxMC&{
zqD%U<td==JZ}~<PX(p)zwevAqTb0jQ{3vws>lFeVI^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<ODwn~i>#3}jDjCp<b@a1}qwR<${UtE~s0D+dfh
z!6C{D=4h$lwD((c?2L8A#HgEPKL(lM8dPC~S<@c#QM$UEPs(gFEB=%|4V@zxiJRc^
zq1*&4ahy4wc~U(X<DWmXg!s6a`Ir%_a7<;M)G_5Fnw>OLyzaip1{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{<utgB!$(Q1?Il@cxs*6vIe!{`VCPf8u57sPQyDJ9{(jr@LMa&0%<dXzrJ<%n;
z^koWR0#}lq7Rql6c0E9DL?@ub#aH#;5orWEAgd?v!jUNDpAYLAaO!PhrObs)wa*~Y
zKZ{*R2*nIb>0p1t(D!7t27xlG(uB^JFEDv|V<ZmrPHdUZcy3tGs)-m+qARl)c|JTx
z<9NjhQOs8IKM@3P&p{ode{Vj~2h{UG8<^E{cj)$8Q6kGp*&9Rd<l^n%W=rSQI_rnc
z+xSSpLkXP8N(=m|?UyIx^GWgCWl*uRmiwEyjJNI;)c*@zlAT5SLyaK5lGc_PB>Uby
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!<co;Sd1UUC=cCLhwaM!p#n02Hm**|*hMI)
zs~O4$#aQ!U=x}&5%ufW43<p2u{6<~j_^sxSq{|XgMRaQIEmF){4r+~Y0T7v1;eY$(
z3kaK?nli<43n-^8ryAN;cL6i^LeNAQ@#jB7d|Gp*FupQuaPm)?RA!P`8Yje0w2^*O
z5C$>P6lsHv%oX+QDSN&K?&Ud)2I0^6J|rrrs#K6_^J^xgJ~pavaH>+l!jRJu)j6&x
zBQ0*7rLEz2V&*vYp<I766te08QAwUdU6LCjjpMai|A0(#OUss!+W|pJg2vHp&xH{@
zym$|e<x&pUo~$`+Bf26bQC;UrlB{2(eZga;p)kL$u=}D~gb~$ni{uZ1h6yU~SAFdc
zfflE;lzR+K$Ox%liPqSNTfZ@ga_8jRvtPJGoXV5Kh*#z45BWe;3CEc9tGlnoKb0m7
zk#t3OxAH~Lcj<@J$*J+(XNZP~U_}4aKFPm&PE6FQRMki-Q|}bft?;B5RSogDT5fL*
zfHbv$5eZ%#n4tH(fiK&avS$DD`KtCKiBem}UOC$f%6Cl4SiDyOOF@EhMy%&~NzMX_
zb4|=|EZb-rkKzU5mL0K;F?hpO`nViUDxM4VHXdWJ4Gc+Cpuf2c#xJdI*~R@_AQQ5#
zE3%LJ9Z^V~>hH|vs=-o)<(!=JLqk&7|7kd3g5HZN*kA<L8*NSlkBCrkH6UIQB7J%b
z4qV4U|KJubWIiN%us?5A_BcAf!n<U?HV})S{rXvp>qqAodKhfd<6mx&V$t<yBeAWk
zVa`Z}6Y}&vN_32v$AT&2WncT?AsLe>z@=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%<NhqPyORG*1hR&g-tG5n
zkI^Rjsgph9Mw2Yz9=>>>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!&<e3kaQZlPD7=m+e$nc5!`JP(
ze>hU;W>%dm1uK$Dr+ZaJM(=m8p}!Jy0z0aBW-4UdJ83IxG@o5cSD4PaD=IW^ei@J%
zymvW;^ooi|*G3h=2n9XN*rN!9U^JX_P%^_pn3(w<gT7^tDlUOBsqL%ti$y42^hz`Q
zLDOt;<Nx3aYi8hXe}l1T5m{}Xc;Ei_D`Mtf4;d4L?Fik-D8b*UjeMQVj1KxvehRBv
z_vH2Xd9$(QZ<KufKJC=mlQ{c*0qnUiqg%Oo5>Jc-NqfAh&BGT+dw;@GzbTZj4c;SE
z1Cy`|%CxPk?<ekjMYsJ~AI(CKL9k`)O1dR_@2}3)KeD_)lbOaI;3=}M+P6s>0dtVC
z4Ki}C_pf@c;kr}f9$<LF1+tN`-sb*Yf5IM`E&RYCaF$e7u4tr9cLo9xz~r${qqfbu
zp2@Mh9X-1XCSCjkN^()}8#iUt+=caB9(E@?;jCC)TB8jKLg*=vx((NYZ>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>#ggDzg<s;jH>ulnFf|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`<P?3+;y-F{lc?QOI@z_b26r{?U@eo+u=i9BOe
zD#3@HsbFN0weMwaZj^W52T=w>Q=^4mUh%^P<LmAt_}p=3EAh5MsK>e-mXV~S@DsYd
z#?o_EG99`^qaHD*k_gNEqpKezoiKrWdH2}Z$w-%I?^z<GG&?V^@^u(TrdS(o_Q2wj
zNX1*6SqW%4Sek(qZ8ixd`H^r4mN*%U)uxOz!~(FC5TcFzv#mcMw$9sJ5NZQ|^m?>d
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
z<kGh8-o$OToX%M6n$KJg=$U_~jVfOEr1$#bkb`xcs@_H*iXz4Fi=+hTSwZW}B0p&R
z;Rj%{yqhM?TkC}FN1G)2eobNEw;ngu&WX1s${Jp2NZDS|mf8iPA{ev(G??gM4G-X(
z6MQ;O`L&Dk*0>NPX6(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@qq1C<SJ;c3a6S>cQ29JA2Yoofaw~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!<Lct;8ujg{+owEm)A6$$vesX1QP>e<CY4cRLpv7Pcxxj}4FcxLqi!(b^WtslhV
zT$}ejo2qbx((v-^^T&Txq<?=6gCl$IEx#d)wm85-bG5oykiFmuc*MNzCH}n)K&i97
zJO4|<abAQJjHabNJ?fg6qUC$`17%ct-DVQ(CP_n5S8P6Ly2o$$R+X%kM|1sB0e*vy
z`d2Rrc-QMENgy+~R!C34S^xWM*-{4?MCLZPOQ5=nvulO^{yUGnMaVd%F=s0)nlaWq
z=&C9$+Xy_G;<9`#ZUe0rqm%#X3xP;?mg(>V3s+b~Z@OOm$-or!)jUrKNaQJ<DFist
zIw#jUen^OMnBij1WTSi5xUy<<)>XMNMTqD2;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<wn@$vPz+F?V-r|RW0_$J-$|K2qO4ct)U@){
zx-Dm6QXG?@<H{s&v0J8=8EL$Fn@}^u&M`QuY}2Y-dS@G*>`FOl!H+yj9JmHGs3Dcf
zi@}V`k(89!*fk$rINFAv4c>C1$rRWBKLAcZvA<tFzFOG(QCPGrhJBBf(QA}&J4F`B
zh9a!3IZ17cu!HZ$vDzLD4S^{^@^B3KS~KjH66zBny~=1~%$KnY|5O7Kjg9fJy#i_C
z5mdwBm{{sUvNSW?SD%ZfV@rLl?ci(BaR-U3yccNC?~ax2%T5M<H#NUZS2Saj(KF|<
zQC%;S6#v8b<?1yhx78uISp~vJV^m*=0g%R-_zCn?sJmY2W?Dyjo`%xG5I*W_^DaU<
zEUTH13o*{l2TdnbmjXDoSB|kSjAC-c7#w33h<15BwZgn4x9zDUL3nQFl<6=!@Xq@D
zWY=SvSnIITTNoDA;YNpJnUGWN$UBvX5ecn`(V`y7teft6c`8F^PkzRwhwj~IiL9Kw
z<9vilkM>xVY6U7iIF3%mkalD1#4y!DJ-`(?bxvXSSXSQjJ1MS#a2|M1Gb0>DyL;hx
zblGOhhIz@VOT>?bpGnPU8m$dHfsl6$VwHuOh??sYroaJ@ZNqPbb2J6;L$P_&$0we8
z<sLr~|FiUm>Bf#<n|mtq!D{NmwZXZ$E8eTMk_3)Ti-@!wX8KnL?TMSFrXW@~Qa1p$
z*MYFgvv|qaP@mxM^_LK?X9Nr!y`?grH=>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)(VfdR5b<xdj)Y%OwJ*2Y?SC_+c!Nmd
z7)9L&@-sGPRIp;ul&LJ(-I(Y4XEv!vR;5;^ecdEp0~FutQd0~XHEq`{8`GOFJrL$-
zO{AF-j|+o?xt|>MUQxc_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<LSDV{PkeWynCk(d%os(TRL=W78Fb5Tl<wdW?
z+6-P-UlAVL(qrd?2~N8!P|j$q2}S*Kxd3CGL>@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<-<q(9f$Ys)HaSZZnpqeY6$rqI}zqeW{
zrs5WUI~-Z#3!=x?{!Yg`o7fN5cW*u47#krmA(DJwW3_V0dgOlSld!WNblDWJSMzr&
zk!DB=5!pXIp=eRru%ikj6a{{e1m`IOi?(B>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<<a5i3idc*{q{THm74uuMSq+W6<T4zp1N
zB6=)f!Jx5fQ9Hukv~7!aiIQ8MfN<PxYArU0oy~&8MTDs*!{zCY0?m*PQ9Zx29u~A*
zV)d0F#EgMy5lYleNF!(os}lRQ3Otm|2OHdcoo=*Ga=06L6m-&JA+zus0-Jr4i2744
zXtp+3V2213Mw)iO^){nNnVD6KF^e?MAo>!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^Om<dg~im37^j`>ui`NhkP=)0)p
z60Wdadh{<!_B`XYzR*(-CW84kprU*FBC4`_-Aj!DbpRs9_`aD#B~M6)K{or|`_j1|
z{(O#jq(>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=fdkE<a2GN0~F1vwV2qzM>o
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<AoqHC~t6@+)Hw6t_?i^X9u$^40e^t=0A
z;RVMNarOD)t+-ix$p*4s_s_Md!YF3QAWB_++yF~^#zRy9G&BwcO0<YJR7$G$!#9|~
z)2);c<+YmE&VZES>>)}P1=Aq+aY$Y)uYvP*k(3iQSb>o~m3tWXTw3#tj$lpkhV77f
zMM9T4%lvMYOUlXVK;9zaUd62bm4Eq9xWn!^A5$S2aCNvl89S9k`5h&=fsHjo{o)H$
zCnMoODDRHN_Xon<O{EHo+4dxy&=yR_15ezVGyJEO7b|*lUvI?9jJVx`)=U{p48cd4
z-&!Uj3_5t7p|Zgl^(9>&o6nJMj3aT1!^K*aIWxM&k6%OWEMA6OxlFWAm8AFtjQ@Do
z6)_(r8$M_GX^vVBS|9bkHHq1ZE>7<a&)q#lQACyCZ6HfVGl|})?Gb@1$GtkVF~7X3
zO*!8DKRcElgmCaGRX_hA_B53i```O|n3u`V84fvun@6JqlM?pcw&|7f7N$oDe+~Uw
z+M#01jWR;;wz4tfCQ@YZPxBG&A_WmAKVmgYlfP1!lZUc$(=QCi8{4F_nNCoTftMmA
zb|V9@BGFGf5{}F4#ii9fLG*L2k))FHRwx&nWHS%IGck98Rm1nvC`rY#SWCiMc-5v3
zw>cNkN>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#<R`5E=gQK0kbquKfi1o
z|LPU29+&Y#_@3pY#e(Q{P|Ot!^USO+0*-K&I}{Tozv<)>6zSJAyU^>i+3z9pTbH4k
zokFRt4PTpZiAlU`75RuOW?GTIUE*u~dDON3iV)yRI7qD<#wN$VM(1<em7-v!*wBUx
zSm2SP&GH!`Oi&X_Eh;zyL`xY?*tu`Z*k)_lOUV&*EsB{Va|}!^8{oM3{$oasGrL5L
zft)!)eL%0%MqS~xKt_jr-f`gkAyeTpfD%WQoVGhShdl2`D*Jo+61<K$5jXfJ!AAAl
z5|N;x*p45=#32!1Y_YM^{QaB*P~6f^-f@<}xhD|KNY5sHC>YC3Oh+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*IuY<IQ4l7g)AGpVS#hRy+_-zH)@kkKp
zqrar5a@4w@7iVdA1b4e{OMrtN>sQ2d>a}4uiYW24$<gf+raK5xCjM2DhuJHhICipK
z;Ef;)+yHMsEa`9XMhh=jMi=+SZ>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`2d<dkbhf-2_9Gw-8N-L1
zy^qZqw3d)An~Y?c_^JJd`f{%!y@mpbfy~!TlG+<_aG1<UWU}hHl23`oPFDfv1%ujE
z+AD5CdbLMwY<%%@O9>2P;)h9F*{{9eizi1Pt*|h^TFE$Q1ci$^bBzN(Gwc@P=}~eE
z@9N9{-BqZB{3^l+<fy1wy?VGle71X>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$zmy<XYke^K7r
z{wJ4_1ZxZ+!f2tEzWk+(>31hqf4Wxx`@bGD4KTqPXQQsViXPVXtIK=R)t4VPAf0RT
z$mAU1IQHes%~c(JR}!VrUURdGODcbJPGr(!0P!bS^bP{<wiVhVB}P|aS_2t?Kcenv
zD@NuDQZqNGd;dN|Qg424znDr+p@^k22z<EKWM4<Bez_CvlQ5{9b0Wy#j=MAKG1CVN
z>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
z8i<H=$TyyPJVfnaZC>1avQC2L`Nt&*%Y;|EjI#zSfH1_0m-W-xL8=_x8nGNkmfCJS
zG<n2A>|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}-g<dbAymdhI6h-XF&w*R=gX=2p_|Pn`iw*4(X&pr&oAjc`ZRs_Ldo*}C=m
zmxIC(`g^){V(sq1Q&xgZP!44uJ{(_$L9njqDTWrzS4)!^d4EJ8BfnwZ)uB;VsY{c%
zy?f%`Vj<L)HXu{pP~o~6Wg-h9V#C6$$gmhw!n!@4&A3r9e+>g@?r|RQNJ+z<JShTy
z=CU-)?o8r_;~Z1?4^cn@#r*rWOIQ4WUMtES8o~X4+QS4<wtPKzuELY!La=dI&6uaa
zqA-7NgJDvY_ns7L<AICp_F(*>{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@l<dIBLMvXH5<N?tz=Y`0Y03$ud+1rAa_2g*{eji2$opA>qu&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
zqVa<r)Q|jl*ifG<9}&_GU=X~L=fI_hPR#r6ER>p}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;<Sd=xXNB
zI$3T@DaTL@J;!d;!FA7Kl})_QXLKMVHCkZKb~2a;eUlRH<`VN5<|shilh&N}%cTSX
zk=;AJx4G;n>HLOH`e_B?P?4MO1iyd4`tUFR9E_R$dIVO<|5<&6qYlKMU5cs(>RvJ~
z2)Pl6I2I|0eTxpFNH1&x&za<Hf^{3eRRcJqgenF;ylw^@C)C#QUAj7dq@q=c+gGPk
zESmM1<L$7iP3#uBuOO#jY39VBn|sp^_i2SaBM7FH!83N-*y~yunFC|l(&|HDc~8|M
zrfOeD)H3N?Gw<!>-={!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&)JZJdu44M4vD<sSV0@|vl?8jlfh{xbP+sXT%n8!R>90D3J
z!ULxxHey?oLv2H<kOG3Enh(^JpVppqk=Kxt(2Zq9Yt}d=bx)7QjnHKiKEM9a0*V<1
z0FYqF)CNQutMxtk-Wi6w3<>~W#?IFNavN;?a1nJm{tkH=oMig*nX_VQP%waoh68wH
z%Ax(1uKz)YVFC2Bw9>`;e|7<Bxf?wYeyPnbTk72NgMS-(((OMXL4ol)YORY3^__Hp
z|6qq_Yna%yBgx<xgGR})KDfv#A2xkMqH%M{P#Fmb1V<~OD(-$DNjuJ6siQQ7*nINV
zdi&74z$&C4qTw(3$^1u=x4YK%RWOoVR<2lLcUL0nR$lU>F_5>NX*7Pk##D054RS3B
z^A+X_W6u%3^XqW8Q>J}T!dJ7v6X|vR-7Kz8m{I*TEie{6<d&q2k^a}&%Pw-iA!yVP
z6ItI=%eC``>h5enr+pi~Al0*qHU~p~ijbHPR#-J{rx`Kq_w}ga2R;i3t=0Pjm6h5b
zm$^wVrGNt-ZZfg|cmSvv1YDQ#OVn`s1&&Zk(<b0Ox*tsyBuwuqk_)OC(|3bMbLdiG
zTE1LwE@OJUN&g0<1ELe?m6YGhs#`&1M^GBiRYD`-D|mdrHgk?;0Umz`&KZZP%71fh
z82<B+BpQ{y#Ta?ZTSe_-1RiEk--9K-ob6tdSY4YvJ&<pI^~pF`is6SQF{fgBA+`VI
zv*Avli^EUFlGkyfR05iQ5xUrKH|1hTMJMSRhe^*aXR0(jJr$HhxG8Q*i09p_o#9gy
z21z$P><%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_A<P4(I<FpgSmb!W6+z2()+9dwINW;ig9T4KaY|1YZ@0!}<I{cX>H{e<gW8kE=
z8Jo-UT#<%>)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<ORYQdw6sEg41;B`v_6PT8bgx
z&J0AvXO54F(ulDu1qA}Ps)x|9#jhOt+WojO>&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`C<gYFf}nLTydM6}>Y18ZSDB;+wyNEfPbi#mLl8kyA?8`--tS!c3_pbfcm4X7VB
z>Wut!#nSUJ*@!?HvL~6%XBj@c=54x}jxfQNe^-I>Y<R<v$Qnh}6^Z7)`cLfCmBKPz
z7!;^qP?~sYFqTe)xARL%B#Yz7KgX^3%!nG+He0IRZn2(5F&HR?ek?yGHu!#JUoI{&
z8O%=fxub-+b$Gsf{usZ+arR=+93r8#b<-6w!@2T3#8iv3frl=v^-s0QLV3bfo5zq#
zR5vkD`bLo|UdGJBQ#b-sxUmxYuD`KB(f|7%^qt&8u4;swmpqXws9#+#a+dSw5uyGC
zFUP-XN(?Y*=uh~9DqVD>%%DF%-$yy(sr{8|7)Y8z%#FTGs(iqgT7apNH-<YenB6u9
z@v9?N_j*bS0;S|XB*T-QzgZ~jiv;K1faEWPjun}lh$BkGMTJ?krH)QrlzkY7hU8$Z
zYHv}{6txB$HCZ)&9tTihML_Urr9XNT6biB_CHKY!%K%mQz7cww2HTkG3J^EY+)SRR
z94}xdTy~Xj;%`Y=S{9B<t<6ArEvEBH;qU4+?M<b7I4VBX#dB8Os$6jX5-xM>9w*Qi
zgYDF2)H5o+)w(s#d#Nh*;PWNw7D?l{vrNAWO6r#g5c=viJ?z?FbesOS9k)|AXw#)J
znlIiK|LYGLaO_bl?<<YajU2j<ZPnx}V8Q!Qg+t>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_<u!YCfRp_PpVmSs)4)qIFAnoOSxvsM(q+M
z%sci|rXi`bZHUL(S|N(s8^LKOY0oq~)XAhIka1>c*ynW>SL+)3SJGD41<kgp3HzS4
zSgLU<!AbAJzhEJyu%B?J+msz+SP1f$CWpm7QM|JNZRq%wOFi#xfR$aW0M;%?g_$W=
zhW=Rs{%7&`*<O+bD1P0aH~S}}Ad$fix$=Tfw5)d4PQXrrMTx7@Q;)4q`zjs}+lRx;
zqdC8Y_8}!h|Nou;0rwVIDb;t1p}<`}Y`aDjtxDZlevaCV4B*gSpAnX{`DEsP8+Wh*
z7i;zUk{Z9DIN>Gwyl#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%MIWZ<v(cnv}VgORm
z3u13H6n2ETvkI3c$4qqT@jaIigxF8kDxMk{T!5jSE%eM9`}tkUm`OkNkhk?Vm6YKT
z?!G^;EfNiF)q!D(!zbF!?ZG90+>JRbAiaCu$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)^$<kztni03;|7i{U&
zK+BAi=z3D4=?3QUM>(@m>MU!HjzjOffs03aPe08P;--8?x;J^}%ZXg`(!j~R^wdKp
z6bn-XVfCDop9ra%2>oNd#yhMAl==Bh<!+ga`{<0%w|_t_1`i!vFXpa6jbQo`N^$Ph
zjCarc6ndNu1=C9galUsJzoJ(-JL=k?5n+hI{c*dZrW+{IPQUetVgC)qZC*vk0a0zP
zJL;UmIrP<Z9#iRxZv}8JDX!Hxz;ms!YP)pOQk9mncNU#Abt75rCZ-vrXxbxgm=w8G
z$)W_^e211#!W9VTu3>TgXv#(X2iCIZCZBPvzvi|^1X&*+Bhy)}ahTrh1|{{wcTAsg
zXX)rz^$J{0`mN;<qUzbfOg(L{NM2bZWH{yh!7$e*D!kSfQ!E$#Aun4jCnv=5;oG|N
zcwI`rGzbo`*Bvh*@08AL#9i_%l3;t1d+@t!9Pp^t?|RUIJ9#seO0Tx?r7>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@qQva<dxywD)|E58L6y4Jy@gl
zCAe(%>3Kvf8~=G%OJ+l-TfJ-u1dyZ9<gyiU4PVCl**z7cDmaWseYiMWB1C>MZv!rg
zaYvolB0bnAQ|1z08yCLl>1FKvl%F}c0|N~I^~X%g9QGJpaVi1e<~_v7cartx_aMaM
z0Qan-0a|5*OB`mRCCHQk$dCc0M<G93bNgU5JdAbHdZ$E~Yy{I&leUy0A0K)r89;e0
zM@A#vwt`Ai0*oc8D_1Eq3vX(<U6tSNB0M-$Iw?{<5FycOKMrk2&Vpe5ht{zMoS6!m
zLVf~Zx0*s5vcu94M{hx5t{7;doS|zzkDaF#{*j=1_+#*qWo)eKoHzPGD~i=^bcBpk
zcRIQAUD#-EVIzodkIOzvtq0q{!u5x+T@7}+H2*x8(@ql|Y2oeJJX@PpI?#4C8yBws
zalioCYddQQs_ADwix@sOJI0{GoV{z|bR4YVO&_JXKEr?m2pJ~Pqki}`0)3tJW4^fb
z>M}kwJYx_4HOD^D*~O$!>2W@!!*g7^&|Qgh=6A#ePml^jwKCZQAp~TnB1J3h#sT_w
zJ7jYN0~tQPGM9rTrvGQch|~#i9qIcC0Op|psb=7R5<YJtu?w(5i-j$Zjv!c2HDIZs
zhH}6f`5b^9J|{{m#<cdR$ykejhK^rP%Xo<^kRR^*>b(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^oV<v|qtH<W}(
z?$MKAeb_ue0;Nua26qRJX1PsuH{a#wO)kK=AWVg8j(LVSdUYuczWmz6!@<dl977J5
zhW?Qf{8;=tiJpgZ4_R-pzPeTJd2-cUxm2!+%W83hPp`Co>tS|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;v<Xu7|>RMP;4s`(w
z)^wtbeTk1SodR5#HJP_!`cC-+I3gA}frft++|gMn^6o`8C(QVpT}xIDx8KqQl#X?E
zY`y0rMI<k#<16tyuFQk@`B%A;pW)Glaz~!=$a8|TJx$ng7v(OC7Wo;#7tLqvCB3D|
zOZ-yvhu<cxWH$r#kylbl;$t_U6;u{)QnNNg4~Ik*TmHR^BSeJVQ3rYxX~iCXJx8^t
zvxly0wOpFCYQIa2J@bBsQiK)q-s41GA<~9wCkuXNYwy@KWq2KKycN%l)_H<?z10#N
z%Cb6(qBMe^yK?@EfVbvsWJ^7J&wZQP9mOX4vAyGBy=$q1yIbsqP4HU5lZqYg4$%w5
zB%}qz32Sd{>{_~$aOUBKe|lQ0hUQe>r3sSBk(t9=YiM}vW;wS{N$fj&Qj~W<<?pl&
za~tCx%vcJjQ1jYPYD}GRLf1P{N2#|kGnC?lFbG4}^eC*6Vg8q^s0BPD%I?3a5Mn(L
z`3!ANYje0KeR3zefy<?4EPOWIXz<X_(|HTFWFM0pK)!bO+w(6FHCBsn++Ko5-_a&$
zfk`l0X42Pwu7n44^1#x_4zw(ErzzM!frcQvKz{`K(*gAKN)ElGA6{-ZL7Y!H8Lf(c
z^Ott7mS2tHmo7lz?urmG&%3VrnSC5eP5oU3FZqNl>6=*d>LB&&KKP|7qGFoKp{*ex
zfg=ap6W?le3QAj20J!619784bsYh{>s=@ezh;TcI9euJwtZ&pKJX|e)$z;)%NXu)4
z2&Q&>LJ2DzA0ZBhq!<VmFo(oSL>9bHAogJ`vPz6SqAJ*USCVkGM1qdMV@xO6=yF{2
zbf(tFzxd(H0GoGimrzZ^D9}(REXHJwX}HEA^*~ot<yK$P>-?pC4yr`Zh;J1e0^jv$
zq0v9RZ<BiE;;Z6ccmdqsV;i3cW}GW6DyWOBP8PX+vMQ-}o@e_|bD|4`+r96(aZD$A
zH^H&o7aEd0+dGsM?LIhtiu?AE@X4kGhs|qN(2F$MB0&be@Ku87Hme<h3g%$hzga(E
z{cW#*ZTzLe-RAno0FR)cjnrcuY5JF)*_2I!drA)v&spjz>v3z^3X7l#^Q{m9kaH8q
zFR=on?zMVIJXwgh81Wuz)tpD-9Z;q&M5<WdGS#?=FndNDbGq;FWj;CeJbtP4`}exV
z6MGj{OEWWantw%j3f{1D+0KNps%D3MBw!s+rfK`3cta$EfO_rs>}r>z|2@d7AZ&jr
zmK}x(0_~<jRV2=z%i(><^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*<y?
z=y&FYn#}f@S0QWR_&zBK>yVfmhwjPpPp)A2?&nU(-;<a#?q)GM<>~KFArLh%;=9Dp
zjBj4V!yJ~x>ql6orP3+snV5ISAX#L=H$I{ZY#r}l8Pag+bGQQfoZvKvU!K^U&e&I|
zwxn&fykBze!GfXMF*v8Ao<Pp5hQ?Gn#z&|DoM}{3w>hZi-*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*u8JDLo<AqO
ze0e`QJ_FrOu)&_=`lSDY#BZN=&iEa7qaL{8DUJdGQi^~HKL9L(X>bEufX%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
z<dZou34T^6G?O?+OLuBTFf3X~Kn`UcC6DJA{PwrO(u$MF7a2pQ%N_xu^WmZTnLZS;
zei<a`PRUxwPyEM2HPdKpnFC{Gq7SeYKL_37D(4{vVchtN>L4I~_(5zp#@pk{HpR2+
zqqMs|^Uk(j*Z)K7w-0rV%K=A_Z~g++pA@b?%ltVSul^xLp6g~tkAmc%fdy_pDzJ26
zQc6<q;b+d__3jdl$}$5eoJqm|M0gNpfVqJa^2CUvrQMk!>noh35rqgu8o+)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#?<tLA^sMDrus@Pxv6Zo4~lE*p86={c*fnYddb0qFZm7Tdb{N*rzbACH>oNMwY
z)1p|pcBfa~YM%KDlA4rc6Vrz<+V9Zv)Mi6M0Yew(NNAbxnRX$VEz063rv%Exq`9;c
zA0vyhM;;Aur(h5wt#Ff3(~-4B1<FuJ#W~1cSq78eISUq!>>`!7-=E{1{z=`Ee&J&3
zIoC6lTLjeb^fkU;Fw|bT<?Cll!dqRzMQ}9e4wqR(Q}XnAL`!J_89h9(^vm5{=IQ?~
zhg`qqb$!L^4zDS@37M>Qo_}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<CR6ch9N#zsi$KUc^W^{hyp!vYIo-L
zembtkrxLj2<$<ea1|v7CQ<)5xSc7_$^rKFHOxYO(r<GUgr<UKNs_as-Lh}hG&E15~
zje?Q7Qb7%R^H(hJLBC>;%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%tiOa<kN^<vCvc1;{&X^8p~;k5ln>0?gs&utCOMx~+o=
z$%EDE_deN=X!B_r@^+q)<FsBVYbD;Ed%Z#lsrpQ9=~C_)-J0EufYv3)UPFkYoF0cy
z=W1sb@q*yEYG7&BV|V}l3CYySqCTLrK{%wU!;95REB0u@hgsS!Bb$Hp4olaDrB5{B
zVLq20@*me_KVjoz|Dlb#>YHwScV%fLv$Ka&SCKL)<BYzux?EVG?*kZRC>-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^Bxjjp<z3sNfJK7Ub|ySwK5lc4t%M;l78AY@8*Xnxas;YD`QZKIq4gYWIQTlRQP
zE$)5{r1%=@%`jnFel0jK=J!ZCwNu?$76PN&HhfXOY<uVotI@FSX$8dKP+~EdLs%z)
zrEm+Bw<6NW^FIyE!h4?0|A$#L782kpK0#2V7*NMW+D-tjCnx+ARh;47V*(bK`D_vN
zhJ}CN-D@X0XL4C}aM-6IDy#dLWv~Q8A;Tx(OB0)oh*S`nOe?}CTlLDLYy6vR%~3~I
z(`1O89Z_*R-G`F^LDc@_4V}|Z+w;7t;MNH%N8%OYaQE9N&`X$u?y?uy+df$l3N&6<
zdP+E}63g41E7)dN6!>TE^~)yL#MOB{9F3aKC?e97$(<=_vvCvGqzdAcpZhFn-OL3B
zAk=`OO&@#}U5@%vknm?@-$obhX}qaA<pyPR^KHzh9j#~tuMX)%JJgPI3a<L)wCpk0
z>H)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##bj<Hl&*67;
zJuM`A9PTA$<x^uYk9eJDvd8lO?l(PDK&bLt`LBwt&R89^!WHlH3748-t^TBo+o=2_
zm0C|{$7L8*_>nX0GLKL*YgN5_1%I5K{7kPa=kh`!#onYU8oKiw5@KHMXt<<j1O2+v
z%@Iw^>+J3wrFl8$xrp`|%_2SLsD6%K04$e(fRK1XAcH=qH3=IDY!gDMP6w9I)7v*K
z;UG8eS{s>LS6t7j5cSfS^yPOxg-TTG8)-ctc$a#|4g$<R{wXS(*krSUz#X6%`g)&%
z(vM6c1?y_4F~Rhs>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)m<WiJ>9l
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&<KAJ$qsEU^iSH=RkK#F0ZXY=?{kIQIxuXx;A4ZsvxC#p<7G8P
z=gt*$k9~yZqPOeSr~rAjhTV0Wzq1-sven3GNGr%(#^hm%g~-x^M8&Z2C{k}+{sfW9
zT{W(@L^E~SC{sZGvg?Os9YDY^Z!&-%F0J+epGjWIv$z;IW)NWbbw?fpI6iG>@hYn}
z?i__V9l&Gy-_sb(@bD7vn_dK485!b<lkY6Hn(VGc+K2R81o(%?S^7YJgRhkOB-GZd
z@-s=Sypm*AgRr0xItAH@eET_pLKmLEb8o1xbZ8#xu))7Kq);TZc~*UQH8ws+yrh8h
z-{%Mzp>ew&6ACeT91Y}(+qPgsbsO-DqLFRdfg*yENV3NC<~IoyCwfdW%`7c>GJe0w
zB)zC&^cBPFQjy_%DV63ziTf_E7F|o2zS^~!<M5jTT90EQXZAKqf@<|!{7gYz%Q=Gl
zL0|aiw~{P|LeEmGVeT4^xZ2}L#3PEq!sAIll~~!O{0|%<U0jdEUQmRjY##a(Mgq~(
zLN!sABlJv&A0SYkok70**dOJ<v0eH|mabqr@hby(4g{H??ce<70{RWXukf^r!I0zT
zAjONNMVNg$>`nqZAC%6l@0cf<3>`m>L@Zr(%Jcw>WXYHAn<vsW@d%Us-}>s$5ixQA
z3MPuXmIoi9&KkKfX-y{ZrHJyFJv7f(HAa{9>aX4oOsm2E3GJhQ4K}M(3u)tXjigD)
zOzb9ocQBMOOv6i+xD@i7`m%PPIbd0rQMM(!XHx4mbwMG^LY85K)=9lb#hlLaU}1Fo
zCX12aNHn<IUYUhUPzGvns}t*<)mUI!=+Hw;R$n-onG7~zGu<Bq3|e^RSzDmmBoSZ2
z)(B4{BdX01=U|0DUrep;NlLG^`$0<f?n<e$FqNlCxo$8yD(Pps1(V%(VBJbH*@vIA
zMVlK^*Y1EmP9%=fX?NU6*_Qx~P>R~u^r^Mj>@XKq%~t(J%s;EEU1?hZgwD;zSf0IO
ztR1M32&W*v=w$aYhqz%2D$^o{rR?^eDEBs2(uB3<aR2!_ax;wOv#Mva`q(GcsTC~I
zEkX9fKIO}EV^l|zV=|X8$fX~VbUQCr!j=Lk(Sr`g9M)aBY>=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=3B3UrhVf9hvA05d34X<qY?C{Tx;n@vLIR2Gil-(2G9T&hQ;Qoy8
zi<(1*0Y5Hga+9BY9yg@b^CF)8F9l^76r0kZ7?jjb!oA(63+Bk|;N~r-+r<xLlRvri
z-w5eI2^rh|)LVYq=_5eM2q2$P#{{?26Gaf=?s>bRm-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_#<WjvKXUR*y#5u=QSB
z>g0fC|7tfcnQfm_#{Wd<&y1{PG(gqR7!Zgfkgh#-)QEDl5oV{;V-bj9vL6?0Eo9M}
zJQHOgWuNYkFTmyjy2tqgL~Knqz+av-nUY7|17I8kESCWX&WlUlx`8+SRzA(?W3+oN
z4`DJK<hxq<5L+RG6hp0GcJ0T*p%Hk+EtHEhiOogL{@_P?bs}GJSZFzLW6h25Yc}xO
z9F|2R<0M-v9J3EbBAJ{Cnn-l)GeJtE6L>gixR%@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-<QrJ_`{#l+ll%_o$;|!IET4t-zCDOJ1CFKfY(L*3qhE5=(e(enapD_{2dPqoe1w-
zI-Jq|aGLP$iXb>)@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<o1zu9ZLdDE(Uf$kat$Sh
zWwO;-<%to5Fh0lQ2NzHOj)yMboT5?oDVP1XB;5C)QCnU!yCrX1cC6dD@=4<=QW+Ck
zIW~iMX+)>)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)
zA<yruv#{6%Fzp7cGp+}(H^*+qmT4k{;`(EWYSCn5#}<G0_zg$Ix$UXOy#8l<t^l}3
z!&CegwF5g-EltCaCDHnV;Tl<T<hx-EVI%OUbh@VBM}f89ZWE<VzoQBh_|z+9B<v1;
z+w7eVf)J4jbvFCx-)Rw7L+q$Z{dHpN;LC_XwZc;FD^GL!_;uWP$$P%hBvlXgPZ;g6
zlLZE<&$a<k<PY6AopM{P)JRd~86nsg$QoP-1rf{xsG~`yRdF$j<)=rxWK3TL=OsR!
z%Dc?CWOPQf#1)?R36K7d7g8!(YU7BjKt-|JzFbIE`q(8xkpq>W{3sS8*72A<EIsLH
zZG*V36)w@XG{uHuN3=mxsNibT5-0o+hw3T&;qfS3&s!gsVx>+R+m@lS@iEL@V3ZPr
z)A!LZ_2PrY_t>0ULWSC%Gt=SzAOW;xQPF3~b0F6572y&9b4`%jWRT01P`J4tq<X!u
zo;<z3In|gpmKym%50z0imXo827v);4HY-Vl)pSx07VM99XI*<r!1RTUal<{`=)OC+
z3Ba0N#h<-;Uprq7pC*s&b7YF~tylSbqOZ(2fecGSm6mVwvqHm!cK-U2WuU@$k@C~{
zpi0{b{VvJKW+8#WEm<?I&Y8HzKv{hpGh$&a<ghR14HJ7c+fQ_2<U6kgl1<yQ*(2>*
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?@`$QKxr<puftc9iInH|(ODQ>woyKEE##q!4(l#8LS<!++XK0cxaNKl
zrMYd+rB~I~*+y9u3J`3wdzZ4%kOFV2?v~+kmh|z+WjR8c(3C3|9!_8-UUrL=ckO}=
zaQhj_GLgBroXwEGA|;aO3Ll0MtEf^NuPfy&L-DIg>XQtpo$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$XjkZ<O
zrP(F1Ez@f*o_8UyZsKxzOT0`#>g+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<YeP<N<E#n8VsN5tfjP|#Mm;X^C)
z4}2O8_|c};qI5<#)A=<7rS}!7YstDG-(0&&FC1l6${q=RdLE3b%|5o*g!nCM#ysY4
zqzfp9smevvu5N)@_pkz|>_e+R3GWfSM71i|0l0qD>aOu`4BTfqquBV))Fk3Bnj-P_
zT!vyGbaqh9Z3w;3J$CF7n87150aYDbz5AB&G8sv4ym@Y6;!5}DkGZ{XI-tes*fqmi
z!LU1Vpc+B!^Q<XB0g#hyzO$rUc5zJgtSIm$LiAJePVPTzl{wDvJ+W^YEVC8)rEWz=
z$Zal0?Z0~?9+Y)22&vvW^c7s5d+;`fOsnU^7^`_f+a?!+d?066XHYogu*f&6W3_pr
zs>lIoyS$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`<zPg=q2KFw<I@_rY
z4OeFqH#X<u-Oe&5pv*4(V^Y>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<VoYA0_EcHc4aEfNSr+SUdhw)&=cF_+6A!dvSAY
zsVrp7nYt38(MD>?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<MByHd2|y+X@4o#tKR;U$f|emnLJ5InXOTba6+1s7>}n>To73$jy9!l%4w
zC})}Fac3wipK%?eTvHM@tx+{Ti^UsfwxR62HgBhxM8Rcp@u$vO62S|euoHey6BTk<
zbyUMAHd)u+m<WN59W`%m@%~4bB}^Q5Ad^cP$dB{Ha>57KX>H_7D4(8!h;JB%o_ha4
zxG3L~apkLIB3h5DGK9x|#nCR^2<<Wju>_yLGPpaBzPv=cm{Wi9=#JlH%raB!ry!)w
zfqMXVKo%6sBcL(lt#+g+y^SyY;>EDTB+;<jiEO$Ktf-RrzX|e~k6_6?Xyx73m;I6#
zGxHssCEs%!Q2F;&4hrmyS+eZ{#$D+mTEU}><2lKscaa$?GHuEf>sGvmw>v=F^#8<g
ze+Y#b%lrT=a#Jf{$>A>LL~?n<37~P87k?^<0HhEz<vI@hexEI-ylZK#EH)1fgyA?#
zld3e~Y_ocjZy`o`o}*Je+5>5@_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<NcJG6{s|x*Zj|3y@`Y%cNO@)Cy0Ql4;>`I8cOyJdUzNl*
zuvSO^@6j8y=)Y3<n3!)BdCq8)7@eZ-*)NuqFKRbya+L4^JclDpLShbyjH^>5jH`?W
zYQKhT{u|~|cP~*_<@hv<?bL+k*nD=UU>RM{`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<ZEw^j(jVTDnDFb@Cu?ltS1yT$NTC&fT3h-d!WItqXWLE8Fo8T4
zzO?X5C`2FK8Uha;7}57C+3Iv0A9NO?8$bsp!+u}PmAGwSvJ(|Y%k-D)T&u_Gy?bS5
z&}l`321Esf6>;<np}0@GN*mZsX-QHBbo8bZ&aLT<+T}*AfefN|LQ{(?hhtExSL}tM
zJ+%Qhx$!Y_ZDnbk3+l<}zOa>vYrbYt3Nf&GbTT#*y<ZEp^x`PsSIi~tO-Td^x+?+I
zt<6_T-&~=^8IVB;j<uf_=-siHWt8P(Y9|RM6hLMkAq5N3hmWM)Hm5y5+j6!&p@18j
zTsS|R^vRE<eMugmtMK6uOXufuvh9pehqTVyraOYWRj-#?qj@GImwd%DE>o?@CRy@v
zK8v>bHOy3%x(%RuO->O6D~{fkDJG-rUC(1~s@J&*pUrhq3?A9jNzUismzdG{z@WW{
zmkzhC#(Atvfik(1Lz4SJaeaI)6xVTOm2g#0EADTils}u#gDTkL74jHFN<jsRa2%u%
ztrgY+E0Daws}a4-a-0VteydGCEy^q#lda+$I@k*G-KAIgfFgeyA5B!bQ&MaI;<a2X
zKwT&7xj%A{s1`yfmy6wcw?}g3PZ(9?)~OQd7i{;LuevAL0t4#Wf%*)R#T?M^Y<eHo
zv7ZiR7KW3;8pbJ;#OjYRaRRETspjnilS{x^uOev`gGiHqn#UMWGYvCGN&ee6cpiZF
zPQgE2Rk1UlF$UzITNEv&czN4ax9;B|>uC7-JZ$XTGUom$X4ypToRh<Mq~5$il$MgY
zlxA82a8b*GpEyiqyS(-my%L<3wM}=zYTwq(`9KPhdN&e(?3<o-eo1BbrFmZGgEQZ#
zH^g&zg4KvoE}svffviH|cqlIN1zI)Cr~-C_!I5)VN=yx5(bS|3G{mg0C~SdO&pot+
z`dPIJ(uIkU(*T}{%9`hPxoeFyzf9}*m)aA<$S=kX-CiyvtWzymVbmK@fcgbpxsP_!
z3?4cCK#!^Y>~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;98K<Wlx0z4fO%A`7dOGnn60dOixSMiAQ`qo3$mr0I
zv-rj1MnjFWU6R*8p@_DeYjeNfZ5A!X$_DapI^WtcLp+D(C|?lh_DvQm=8M$JiHlIW
zy0jA0S-8y<SZX|vkaz@xXKt@Gf*Pf4dYy_f{j$IIkJx8ve=At|ctF0W^U60v@VK_6
zH%&SXI5bO7hkNedywrha-^|TPY%JP<b5T=d!FN<>YKJ979;4N$9EUab+oj~(q@?k&
zRkDF@*dU($pSbd`Z}vx@68Z4prZWcCwYyh2B9;8xM&rCuj*ko9<ln-G35|DJOJvDS
zXnx#n0AE>o?w*HCOS%G<zT54j-<{Rfju!*7t$@~LTvT7dGVn-($octgI>?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#*9l<t^TrS+tAE(tF+7e>q^
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&iN<sRl|$pn%j
zcOs6+;`bZP2L<UUHn_8Bj_0#{QULt!NETCT;cFf_d?qq?rATww-TJ{WB!OpaeyD8`
z%n?y(<oZ;7Gx;apCdLj5zVkr-7Ab#h6A7*Xwa^nWn?}O<(M%ZBVlWnmJwCq#FEZs{
zS)YkAzBd9G5U&$v)F5#^r{iUXUu%~<I~McC{%tV+#;JB%`0a*|?dsGUPbnol=H27w
z@XzMdZ%^}mU%&4D`$4Rxe?qn2y3Mq|d3HA;R%wz_Z7o&6JeAc@W0B7)0-&TVKp2)y
zX|F>g4(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<?sjfsG5e@6XctMv
zaAY`xr6+n}=8wtEV`6z~fpre}d7hrDMV>*=T_^Fjm|m`AxfD0$g?srGW?Ho-e+W%6
z%pf>zrfhx9cxZ#^sWplgpIw<mgY8R2rYT?M(>7Rj&@jkpBauZ@K07<iT|EH@51&0W
z>!GC{MyOeDbpqmlBaYnVh37slNZtQM5y}}*8oI|$MLD^BD7%qESEm+w<k3b}xjJg^
zWJnPBGLyhL{0Cvi;G^m8#bxnVejdK-1c21oS^dzJnuS137h2|3Fz;Q4Gsp!kf3GRb
z3WApK$F-~?C1bxG9X|4VlYL?)`$R>v1!WsW(p~I`Pe=NON8I2dtr?*NAX;WND1XIQ
z*j7NS&1Mg=cLUpK`%LGQPTDAs4uwqIZK!KO`%Yhf%>t>v9#7n<^><65k?szn+dYC2
z<7O{sk)fjuv<!<JzK<&RV}|#9M{CI1UB~g95OZoH1T-gQ^Rf#j*7up9rmjZ}{s$*G
zcw@7cwzQ&^fu?%DtbxCRVmvX{US5Hx<dxXUn9W<YrNxT)tJdoZ45GI(GfeaxRS0W-
z!!#FjN6xi1R*N?p(sHlJ(&@)GX-ZVL#b^fJ0s08?lWRzA3x`IIa&f_<yu*YKkaLCO
z=cd~6c4d;d@OMh8!0~XKOrvw?VHXgh6?2LyB&7Xyu7%w$N&YuUA&j5QWw40NSF>M@
zINGO@^jr<a=s?1IDrp4DP>c&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<p-lt95F8vPU<y5>(h=lf6sC#d%ao><h<c3zPWmvEFc0)NIUO?dfh*opN4&^=p{gC
zEvTkLr$1XQK+{v`^I(|{QWPs5`*{9{E4>;H=}DfE5#_6^v`pPCGegr>KreW3_dHrJ
zpb!Gst}=res|CfC-R1h>8cNGN;{fzW{}>n!ZCgDC=h1y<T@cu9%aXjQ1L$4}p#=E|
z6CrpPCwFxAP3>m3RzFN4TJGUo%CWleO2wEjn-CwPbX-iJPG=SbN5K(yaHa9c$}_B(
zF%_V4d&OvcaWO7l23MlU7A6@zT02dmX}4tc$Tqw2=)Sv;o*j*Im_fqm%JW<O+R{4`
z%)y5HBH@m4blt^;!<|*PrqU3AN4RQ-Z8Y_qz^ofLy&Ig6w!n0%WCIzxQ|Z^^WPys`
z<6J<oW2D_uux%f(@a^v-h$2+j>*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<P(qZ+eQlNya9)^7de?xEIqOKXvNJv|)SQW0#
zy|*^!!UyB-`HL7WByoUf!N?L1eNwRaQhsL%O#eoh6tjaFjKF)2%h;0zV7PgEi0zy>
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?<F7;YsXdtvL1%PKQbiWPZGVXee&y)GDE7ICJU*<A(bph60Iu8F
zxfb%6IWu=vzjZYQc^JK&*{&5F8cJEqoJik!0&OtbVGd74_41aQ?R-tfLxM0rMPvy7
z-=Kt>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$?<!2)$V)ZWRofJ9wB
zhj2wQui}QS4TM(U{;wAZr$asJuPmD9YDAbP%>Jy%WnAy_;qn#gT>hE291a`>T8i~7
zRv+;FQc`KOBRCa(TOPfS4Mk}kTmeKl`yFd5yOzdKlst2kkr?le$UAqkL8^I<tHV$6
z4#Czc)9~6xubz`5bTO1am=|##Z~15$Dg_=5s~Ret%M|07M-n4jp;sWYb4{3Es_xrW
zwM<D#@=e5PS8ZE><ceFXzU^hYse8Z2Qm{D{CNXX%YnV3}qj2{M=G_dkUnB0R&!qlO
z&S&HSt;Gr~-fkVS-~scc)g@GgT9Q0nVgPrS(}J&FqHY&L1({&nZ7$O8Q%{JQH6k^}
zT{b3bBFFr7C0jr^d<C>mAQ)Ag7yY!7l@{-Ccq-XAGmK)ce+f<H6rJ>bVHOs}y?fe;
z_LSueh(yg9<-f5*1a8il^V)(gaoR(Op1dXKJR|5?`qV{@`V{b`&=<K;9U-s?*LC_|
zCtGToPA8bh2LcOwWhNFDA!zrTH>$f~UaCnqkdaRoCd29|cy6H<s8vON`16w@X3kAE
z8g7TZzeGl>)*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%`<p9#AbQ!=pEkfF1jBk1$Qr4>4Zp5G
zWJ|qPyrnMDi4^9}Jj}V6eIZa3^a>5&s*l#nR=?!8U%A;6si8pO16ls3dDO39<Zu9m
z5@&Pkib=$>;eNK8ouhAOeelqzZ2k?JDkr1$sWfoo<1JRKM$Ig!X#?g`Art9esk-_R
z{|L6~N!x7s>e6Ue*_FlN6i!VN+3H)%KbiK-y*`!%(Bkj<AS1}!d@p~*kuh!I4>Rpx
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<ttfwMrdbAMgR=8@vd3+08}*m`NR4$e8V!E>(O@8jR{6ck&gMKmeI8xzW><T
z-^hiA$(zKoC>Ml}Gh0AEk3o3P=;;m6Yut<grf5<kC%f1ZZ!hSm0N6xf4~Ua2egaz6
zdB!@4d^DM2&BMQx3_6-zt)5x9HmP4h!JDPf4fvIrw_h0R_1k?)Sk}6UA{ZU<&BWle
z03SX*J_N@{!Nl2vZG!eJ`8Qq;s<fts?<418$Ri*amwNRH!44h-+K8U8=<Ol`o`a5!
zfq@|D#ez7{JfB*IVwjI%&OzGL=#kP~aM@Ym!k*s}(5_QJpeAf~48sj{Iyez9FBw7H
zX{q>P$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^<N+z^O1^~sEh{(x%C)SX^0WT+rxTF!*TkNSTpQ)E
z2P<<+lw3AJvTMEuyswN-1=!x;*r{gl2>m~f0HXkgNuH;9JKnmtTa@BkUrx@FF~ME>
zs6EgtSuOfm7EU2D5uo>6SwtgoDpegt*piTeILv4*eLQD4?Fz=@Eikw}Z*a!|Yo!^d
z+pOzs9<XEKyOe|QlRHV%f`(Z_H2nk>r}%{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;<g<pCt@U0TSc%KQWNlZ0?SAnN(*E^-Z+t(rI$&^n)N@S8D`*NNp!ao8n$hL
zB9!G4U^}AWfp4kU3`djJ8;T;9wsAc6c!UE(&J8I4Jp*0JbGjElBn2E*R-)Rd0w^Ve
zrt&PntBUN@Qu^CA+DVZVU}cWo7MDJ;S1uhNuoO8;zbAt2TT}gH5d<<4yd_p9RXQlq
zu`aRYKQ3nK#chbxP|`VfD>qs#Qvy);OiQ(dahJ9D{jBM%T3AD@Y>!1&#R&vt`K<2h
z;FH<}Q+NCL;2Vn%67_~Xn|<zX?HRHzQVSy@qq<*S#U36I=zSYg!Zl0cN+g$V!T1F;
zq%Do+OWvfD`-(5lru;ckLu0$aNZGruFclEV1xqR5cz>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<h05VC#=6|*GX$cc4N+l>$1BK`Bm`RPEv
zgHlMyM>MtE#5cRi2lfOA<zP8+<(6r;{9adZ*M{5(6jlGtSP^{j4>rUxuAyD+x28CJ
z_r7Uh(MyJp*0^?ImWfgo)?AIoMPc)!+&1&R1bU_Mbebdy=jz$WJ(J^xHZrEZ<F<=Q
zp^T$U<Qa>rctxVGa-O^T^Y{m3-)A;7w~fq<AvLLhtTG!TKwc|@-0UCzmXwd^u8&ir
zgT~&o0Dyd*9z&Gt^{BF>VO;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!dY6<!
z3^21Lpe2d$E#`5RPTQz_XXOULbShU3%<1MDRhcJ@?}K(4P#4~UfwVAq+W)AX(!;jI
zQKP$=_`2n|ZtR!d{YKef{D{rPS;w^-DoEGk=xS>aKX-HMTngX>!>7<D9q>a{<9JWB
zr1OCz^c!Gp{A|BZyW<e5&!QqaWC@F_xo&c`dt6E==6Q0+c?r|$;b6|SE)Pia+c`BG
z|F`rm_5T}~xLKq6A!L*omifMK!QKYO&kaBZv@&VUypA7uWh@*b{eKtPB0mycu^pBi
zBC-)*R2@%xqpn;-ngrAv?)i5qJ_vD2^)uc3&01{Ud}#;=faRkGQFwcM=BKn(KgX>r
zxwpUZ%wxrz-ltWpO?0UT$-kqBU&1Igl%)8Kms(OHsUH7ogk7jWEI8bd-5N}wLOve{
z*rEnrVv6Q<_xv-svz8%fka8(^mB%rXQ2r+n2bayh2K<bybKqkzc`ygi0^7l-RTFZc
zq?ZgWL9{Y1enJ=?t2qVHIxR=V9`n9Kqr;s!zX#lVX<-CGuUm)XmJU~Vn)4hcRZ<+x
zCsk-lPPdPn%BVz)((&RKAa@HKJ1@F_$wu$WH&mB^IT3uibIcczEXl#$&iuXV#p=mP
zQXVVoB2wqqpsr&9RyzxjoIkB)J^)bq!An!m?Chw(vY^Gc$L}HII(nPoXQ~=JnioR0
z$BbK4fk=#YD?EG{epb;Lv0u-cJ7hF`=O+S-rBJoSSBoxy4s0F9(i&Au+St%VHWpeb
zB?FE*VH95PEoEk~Ha5=DCm$9^fEPNvdvtvv@Q9>Ox_tkq1Q$xR<M~cI7bEj|-JxmZ
zVRBvP_BTF;j8Au1vs%GGzPQp9tujUI;v%mT4_7Y<-Endkgm})qZZOQW3Jnzc(OhGw
zAqvv**+8Tg6nHOu+aAQ;|J6Rv;}CZH4-S-D@oELs=TX{}s#9>hAqM+S_38rTaDhr|
z6=zcY5_O<^HtO!Q6olhMATpp)S_^KS7lR@|0nV)^c`LNbHW=|gv#!Me-E*w`rsxjD
zTkw(6_qS<?C`BT}kHxvzo1+hbh!~)Hc$fx|t=t4ZxoKh&?YOy9k$W&a-XDD@wG(mz
z(ZJ0!7jnyuMKRa0Sw|Rs3ppZ|4QT_71E5Xg`c!?GRyHWxTivIEYIrz~0k17r&r|P2
z4TPa@{_)M;bZM634EC5udqR_gEvw2W3-6RN55dTK`5rd7@&s~Mr=>SWlSK$ABD^vF
z&pPl!qQGx;yi^iuqd9v5HWukEDmzBqEuW_Hsy@RkJb(P2ac8=Nj^WFH0{vl~A#}+o
za*?%OY4Fl|{pw(=MY6QzEk*Hyksy2yTi{X<TZfGb$cR@Gm2pi;-hJZu5C)AU>5P4Z
z%1Flk#>_tsf)^dg7Mw#gS<HqTx{@;vIoLH(8~q4Iu`208mh~@~YSQ`WAgTOkTNgnQ
z;*3lsFk)ce84%BkdyfY`TKkx++J!s(UAubGb|y6tz)<5J&g){e1!jc(Eb?W03)EqL
z^(r24>yASe$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<T$Cq&l^N-l6VkFO;!&Y{F20gxcjLr-FYqNZq3JXvC;FInW83H-}IXEL$}a
z&zgsP_T-hQc-1G)qCto_LEJcr4DRkLgxaIhB1Z@Cd5ZbgT@kOhuS<z=J}Mc0)XPns
z_pmSJx>)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=#;d7s2<E$sXiscO
zYNJ6Z8#QN93e?a))ydCcjCbw}0g@0LsrS1~71KKJG%koYN=GwAUnjgI*gvPe>R<<v
zKYGU9jpm=R)l!C!#xywDgJcCbDWz)bA&&!lFrN5(QV9h&|Ktm3wH=PgOObK`H40sL
zy+5{h(f)ka86NvdmRBME1dJehHZeIl4F8|(jj@vGjJ+St{XyPQRSy$Lf@#nkIa6i}
zj&;<^uW}+o^H0eac+T)<{gjq;xFD9JeI|B0I8y|Qri8$D>nMnoMs<Sp!z@(QObYQN
zthKJO3#t<1A@kO(qbWb#%Ll#|z9f1xhw17Anu1r!g|1szkSc})87a;$z%1D-D9-_P
zWijR%!o$oITy;mF6{U4eX}e~Qk0|kvuMfoGlfNuv2B$q{MtJ;-2x1doAq+bcLA`1u
zbum;$Jjmy4_Z4wdJu;LWR#=|(_snU@fPm5U9}64^zcW&%DX`M%Z(jMVEhIC27EOLs
z#mto#XO!Ad+MdfqLw`?v11Yg-jNP!w?E~@2aV6tZd8ok6j^@_}i(eV{){{{~UYW$1
zHbd0p@Mc{cxu+N@8ZbF0q!(3No`ORB)f_S*odV<;FHQ2pHZf;!QMD=FExHmTn<a;_
zI1I6`E&?DfoC8)842q6}Zq$(mwo{zqi=T-eLeX(Qp^VF9VSz;^!)mLJ(bN-1H8l4g
zeiTg&ysmyX9Lr`z-fA|1HFxi}yTh_1e->=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`p<W~CV
zO9t!2;(88ceZnBqH=Io$Mqp4xZ;H}9VuXa3KI|6YYubYus;W<1QNB%4O=I4diu%kM
zac0@S_F48_a;{o7jA&;H;R@*UKHVT$R=Tk|P8k=<SL-CM8gCLS;1Y2h^u&A?4vmeh
z2FOa7t&7JtIFAsZq<_JJ^ndq5C9JDk>FS@$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+31O2<Vhn)gX7^+qS#w-QqCx8FDk?+qnitZ~j7OD|D!AAX-|>fle|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
z<u)I5etzM&zvOC*pPHHfs~<>VOU<{NW_o_1U>XRKN#F$YP*Qf`d0MpT?(jbRoR@$)
z7OWw+XgSuhP|SIy2V1CLozNQD464Q2_BDk>JO9=7zHR+?wzXI9+S$DiXG<kdxY^Xo
z<k%gXs=*FSid(BcA(s{mfi-pu*0Rnm+ls9wxt!>=>Erpd=oPQVlbmJsU$Eq4y!-a3
zRtp+pKoasjC!3zhL2?sm_^}_?E=&4<fxHH-rh|%=#7^vA*n0?y{%pBJ6bV||k$iRB
zMtn!V$OO{lPsX9gPexzSlbPVa)jldu7#(e81S}63!QY@XIYP9+Ia0vg>n%{WxL`B#
zriVk@(m$1t1ioNyz`XfXiBviq7VG`o{YhwEX~DO{4*02EjS3A&G&YcmGva-9J##L4
z-BvI4eqpa(Lk7ldLVd=IU6b|<hfaPG_hdjNEXXi}$!_Lgm4@K=Y1j=o4CO83Ib;*3
zWv1iPb#?J!!1lT(!GP!8OOedCJ{rDhk3U+Iwndb9D2>SAgCH71>stU0@EvK)9aJca
zLjS5&3{LrV4@K5R6E7n)>V}u^&I|#{69_z#Do$P+y$g8%ks4|l?<s9H`6D%QfD^lp
z6oGRj!LD%jTniI3c|vC-Y*BM86JA(F*P<FB1jB}Hpm@DSKC^f|NR7Aup6m}!yI`6K
zmG)DdjilC2*Kw~#%I8INLk-e8{dumc<*OdGwZ6|a4DIY12B1S6DJThzPHFv8klxML
z7M++Ve0SG8Kz})kOfI8l)9z2J9uh8o{Y(1g<Z>}|y|D;jRk;0Cq>xwJ9K#VW@od00
z$$%gt%ZwFRJVj)b?aQ(4<A_lwV8~%AT<ytCMCsKPfe>U9us#@j(mR3h=2sK1BJI@^
zm{IK__1}<;$lkV{642ACp<BD0@GXVnwCZ#~w#*<Ezd7J5z)St^FqZ^|vKNBJOx2N*
zQ#s?ODCc%cgRj0%<XooAl6Ue+Z>7yOouHX=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_Ld<tBjQ%HW*ejViubiRGSgk+oZwkv{a
zsGEn<AzePogQ2N4pNH9(>6~*B7Negs`0pe}TPo0l0F_@B>^4;95|2mB4zB_V8Es*h
z^cN5;O;K$eVWRPl&c<#+aPkW>94H#{+uU<E^PnXk#TW2ZV1^Juu@W$dkrAw}!cyHV
zF6Dvy!1WIG8*qoAlkEKT1hFgTdP76E#OqT?6EukcW4PRTqM8d=7;DHY&&1qICCFmd
z4Fd-M6opLdbEVw$NBSOa1Ib_h@F}l*8)o_1U>vewid8gL`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{NVJ<dVPwwx8GRlkC
z`QDv<vwo0FsoDZ`{G+B#<n~V3V=0*hj;8>4><c_!2=zU<g%~A{Nm8NRh(U#q)48Fa
z(#sybd1r9Zf#~2X*S|AiM}wqrPmFJT`!6rz9rTrl2W6=+w8#GH9x{m(^UaxUh@v%u
zCJ56j7vZA&neIwf7W2xi&fDt*?o2is)MEF3KUhu|OP;~6G7bmy9rby&BicJnDbNCp
zcyArZaq*7Mde8aCjD9er?d{TU8$HudIOFTiH>x{Ed3p1hYixW(T$ugsIOfqy(5rEi
zvdBF*k`aI%y>49@)u!QoY+saa4|nBIhfeyQ-Pf%{5KtR1?2$0>X^q%H!b%ip@Nt0c
zLCLEiWB9VYgpB<e@;<j;=6~&$<Cy1fyrM&$Sr{98!?iv2<s)`Z#5@3AW*VlT(5Y4h
zvqJ??QHk7m98x33yrBTCt|++gaf+P_fZObQ&eT#qpvCW?jQuSqK54V^GKsZfY*h5B
z=>v$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<W)OS=;A@4Sd{%4+x0dn&MOGzOm+kJm9ZHFH`j+`6dQP@;
zq_wCHlK(7lx8A2$(Lo@yse%Q?_v#k)__uKc5@}j^08jEKU(Z25Hfu3j^cY@rj$MyD
zy5<mkLzDcW*hrK(UNt75PBZv3-<Hj9OmWCt9K6&The`qsK*l3F?4Nu4j#dlS`J7xb
zA0J*sBAQ4z(Tzozg`QIi7#5*5ctQ<mh6bO+G^El^RfA`}3A^3yg?gr}Z(hHh3bv6?
z89OjP-$Lwl_9R+r3caJZs}NG$Q=zb&%-@hTKT=_<X|Jr?7{5sTH%FbhAkZ)K`;t<z
z6w;^?!~`0jWIFcJ*ED(>&h(A(r2YS6Xmf_BjydL*cBJ3nWPt~?-r<Y$#vHLpy<r6{
zJ7HKMYssx`k;2<L7+`s!oVG*f6DJDSXy%w5)Vk=hjZo6C{!p(w5!i<wD6MA&6X_J=
zOG)w3tzv;5oQV{*{%7lkOD>l^CzrfotMpYT38iTwU6Y)yU<GS>_|12WL}*gwRdYrs
zdYN7j>1ANifm<Fnu&hqG?dl34k|A)|J;C+QYfxt!KE@vnlxpzn2wn3yCox<;uHVl@
zRRT&E<UPopLX9_{7@P)H&(XmCc+b<#sT)0hfzBjX#NYF(wCimujk5m)l4|cPEH3dR
zvEHpH(R&qq8W?sC&kEp-LLLOCH>DArjVTgHTl`}-RpVV*BN5udyNHYKRUn!EYGk2w
zJAokAfaZPB<dy2s=n%=vA02<&m@-3|ufw4QyzIG%Ep}9%Oq_nU)BS(zPkm|C0BY27
zAKU^?V|gQfxce9!n3;BUWtSB@Sv-EO50~d-Lh6J_-3&V13KaksFuXG?UvVzyl`n8K
zYvq30|6KNe+|>c6(cF`GAxLR5T%4Q!CC|4Y*;^;CV(hAn)WYE}`2a;gy1xm@-R$Ow
z2Xb=H6aFt64^rol%7VeM3sIn_pw@%c?reP!1Wmdr7+<J+iQExGurhY^VhLI@J;e)(
z+$%KgW^CfVsPTq2r{(KTy4Ia;YTftwZ2B~k;v`(4he-HzraEMDa1eQ=G=%|Op;z4F
zP(nC~uMJUlWPEk!iBX2W_;X2<`MQ{^eILj&;NLAH=hv{_%>?3SLZhVw0jAs^a*trE
zA1uh=N3LUAxgwG+*vDv;$tNOmE>ev|o<biQP$AQ6MY24;r4}h8S4n@MT87(+cu#d2
zy~=v((5F8wf2tT<GT3r!NfmgstS{KV@i9J8_c8@pbps|k{M%l+OoH_C7CZS6HQgfi
zZx{dY98}qYP+PEImL>I^xQ`NM#xC0IUs7WU(0U7O$(E}Ch}7<1bc{1Jz&yj*Use0I
z65<|Cf1qLh2#Lt!h%GOcL<cuL5?y;U@SlxqJon#Jvz@&1mpgh=)8kzNUspogxCy7g
zaqn1cp_vHE!PEva%81%MiU0Rb_x(p%HP5wP=JzPuuv%tTEaBEt5s<I`0p&$4oSO?W
zd*eRlRSaIZ+x;AY6wv<5pV$(TLh0oKQy-Y-T?uUA^;{Xbljd*Wb~tS6o!ng|%sc~7
z>O`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;@<l<zfzwc&zciiwf#hP{=7=A$Hk}=uA73YU1FwDLD+kz
zpez^8O>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%SciLSN<LhkzUwik9&OM
zPTu|)=|tMf_sY9R|0muKZw2Q<)U?P>71eFC3mv<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=g2<jz54u<0#3m^Leq!iF<P@
z6+D-L=WikgeX2L9^k1)0O@Wkrmz>cz)5s}JzU_-rfIj!rU3|baTogM#J}^i4ZrRO`
ze3teO|IJgvk!^!}$(3Q)sD+ik(Cu8N_E_I^L=#2Oi3zQk4jfh@d=Bil2g1qt(<uLv
z%q5T7AvJxBhwNz8tCP>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!<%ktA<llx1;6kbgUr3ZVwAoU~u$0rjv&wL|$AZjSEpbM8hO4UcW-2RQ
z_XyW7rPU(DMh$!{nIX7dpSlefmSS}1GNyI70FD?(mvqbg4-0+uvW>1>rX2IBw<Bag
z0+tqp=Q8cI+@(a|nI7X|w;>l~$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;r<w@FAmey-
zE4LB>XdxcnY2Bidzu|D_!lBOWLq5Kz?46t}_Vat5;NFqHqE_dW1)QGbp|tr+nqxvw
zV1%Yr;V=Sr`Vuq($FQ`_bTFgd#YgYvT77<oFN&xi)ATTeGblpzp;{w+dQJFR-R;b)
za^%Fih-R<<0*<OUg*em#{GWESH3}kX1sHd6g^&kD`5Aw^e%n!C5`cgaUm6$`A`5_1
z861_J4jYyHYtc04Aa?iz2c)Z}%&sTi{<ugvffCB#czwFz&BD3U(saYPBB1+(UM^Et
z6<?7_2&TjyO8VNo8HHjw>LU%uj@Y|8v~77|fBPeoyvOal-1)~7K3i667N6kz*tq4Z
zPxgl%*#ANgak~&AHKI~;zzaKfo#qlOS+v3Q+g@B!?^52Mnpjo?;;qFkH(39eSyA47
z2<fo7^GDhiA(DHFnbJ}M#(DCF*<s%xCP$7CMPcL;c-<K^ew4UzJ0a+WdI`NzYV*@L
z4{)muA%VP1k6WEo!&td~BbX^|Va0M3EAO0FO-e=N8>~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|BRS5<H}S>6lcKatt#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<eCKZ9m
z3p4_@DB*c%$;R6F=^ddFg{(Kd;$*tUL$uE;G6>+;d!HR(?Nw4x=B|@ir+a1H86jhO
zP1_E1Z?Z~!`;kH3SZlz{C1Z+&_ar+~+xFNJbwvxq7YcgROCbr`e86}}P<ONg1Qv4D
z7?`{mMh@))U7l%nazg&vlsZJm!vDe2?iY>r8C}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<!Na!Ue*~u#zFcU=HJ9mdmG<V>>pK?eUPq+bOiNLb*=(R
zXel~8VRIHifxA|o69%bK967MSxBq>zVj`uGQ+HisWt*;=vGB|@cQs}ReOY~~%w-bo
zy1A@>`(gU`kPJIck%%wU4{m$Zf|<v$z4m7CLaQoHK<kD$xlrjrGllQ;(A8^WaV+wa
zRa+;z+cLcB9myY-7s=awlP7SmNtRFHRPSl?2xYQE^(fg8%qc~a9l^`%1szf(hjKi2
zXLuMYJA<hacPB)kpY%LI4Hq=V32cpd(BR^W$*?icpDHhpEwbHFPN`u?$sUUhP2k|j
z6U}3|(rkS0o=M%#wYai^YfxA<?4?yQP3_9`7FCM(PxD~|se|@}a+h28pN;aj3bMR5
z*uUYq8G6^n$%)@CuUGind~4OHOo^pdSoC45%!bke<`AoBgGZQToU#i;`<H+%;5axu
zp!xc+_Y|mm+wMU5lBA`J6I*8<&;bU*EMOHQZrY@`yPJoZ=d88AG}@EpeevbZGIO;R
zuF^Be$baPez6a_Z5dfC1cXTT(dT0CAHsTTkAWU%6mnT6;7(bF9$6g88XBi+72*@S8
z3gJ-5`~N4n|3Pat5zw)&Ft|Y%0u3O5QrG#S+Wm{-V<~>=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*g<S^R1Y;vhsRTsg=L^5TUp9QFGIQkg
zD#A^~RG~$&%rKR!l&$hp39(WFN1fqxkNsC-$JLB}gGJ8lY_~}qS^*27x727dqtbzc
zmcuGH(Z0h$tujoC>mV+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>VJ0<r^AsToK|yy?Z^+5&!L)V^Dayz!4mf6%%xgO?DxbKmMLl6I6B4)McDMzzAqdz
zL;sm5U!{odB`Ap;*m4VnFD*!3IJ}yB?cx@y6@YXKMrN_kmw>y7M59W^EKqPK^GVy`
z{Af*BONhZMk3ha)^<><EeW-AcP7r3<k>RbLLy}4>TSR!0k6bA7p%h<Q@ep?-$-?xQ
zOQt-WF}2%7NpDCW<!93YOJ9|4(YcYjgn2z_IwLB&>+87UBL+WwP|KCSs{?FRFnpBW
ztO;8msES-P&A%N7GTM8m<W~HeL>b^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&<LaZ5aDr*!=Cn+zw$JYoF|Wn*NJ%bimEX#g4CaIfBHSmTr{vU
zP#c^}Df;Q%TbSPNP5ulGwm<BhU&ZCiMRM@^>PP8@KEj7iR%r1LAOseD4;ju?bZsEB
zZ~ijJB4tLf7*;6HJ@mw&>?e^_urrP4pfx4Ze6*XN$Pqb<jOs$Cq6e9MY=Nu7B`i=C
zgN>#dEgX50wl(yyQz-bc14X+y-go=<W+E(>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<k@#rEwiJpZACT+x
z-T*>}gh7rea-zyOfkq2dZ7ae74$wymm$y3zi!(==aO}u=;4s{$mO?XL2?0WSdVdrw
z2fshsktelRu}1X8J>tG~Um!2c3g1E7z$z__$XT_wwMP|wL5J3!!6A8fSKt+i>mw--
z51<gd2S%+@=Lv!6soCbMI`6!2L4-<19@@9I{3}&uUi!pXr&7sQs8fp`fms(lRBJZB
zAb@~c7CswRurDY6BB!nUqxF{FBf1kH_X}Z~>96pTYFhk@;Hpo9Wsuh{ic=5rFPLj&
zvq*__2{J-YM?~%dGTiNjCuyJ2c&#5XMaXkuI+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<DEmxb@Y3#cT5+T4-FwJk$!b3TdPv?4lKuFm4}$1Zc)A*)O~Z4xw6rk
zTvlqx3cL`-i4evqORneT)pem`!PqH=KgzO(j}gBQR&v--1_a!6{CKIT5m{%_z!UW)
zaKjPSJs8QzK24cya47SoWP*o|#oEF*l!iPt^V>({y%u>p6Y}bE0YVNzC)%_*M?f(e
zsi!UpDL>!uz367lL|v3+5@3emZw8&*m>|*pp-<q{-CSoAB*iq`zV_z?pPt>@tQ66N
zC1}x2#GlAlvapVll{UARD|N)tB=woR<w;F`ujOu5`x?59i%Kz_8|&@7`Rz7^3F>=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%3PKsP0<NlO{sRlhU_*RjHi9sC&s|{A$u;6f!J~Sk5<u-q}=s
zA<zmDA$Ix9QPQR03IStZ>KVRfTR0uN2)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~
z<AYh@5Hf7bcM8)xfWXb}s8^?y$p)pA-hQUwczW6F!xFc0w^pS8H5N32HXApf@RiHb
zme$^wMBZx&^}KyRDRxh!a}LZMtb;MkqqpS<rQ7E`z}C>kL^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*U6<x4BUnQYcdPcRZwIw^_&Kfae>kO7@Q>qCdt>BQJOKY^~o@y!Bbg$cb}YF
zK9oPEStFw-mC8Ge{Pg@{f!rbi_*&u8MqQnAlT_t0vC!Sl`5iTORERccI}*B=FfV-$
zi2@EYhSWeixrcNl<ZgZpOc$e?0<CphmIokALu3%!xgO}GBk9$3;S6hmkbj67UhfVK
zB={c*`!?m5JNKf*_2c;a7~n|gqU!4%!?v^drN_}PIVcuhc$+%AM))oPQd=_C<hpu9
z*akH*(>>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<b^k;q1^8a4kmoc7vxcmj84nFgGfj8N;XThd>(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$2ntY<JA-~OSehGL*0RJ_c#2xf^P{%}d8Z*<$?Ic0LB4mxA4y-=P(Coh*7
z`7VdQY)N`!h?=dyI!Dv|`ucjeDl2T%0pJp}+%empNyj9R7oMsI3TnaywXZAA@X7kO
zhT+iy@J``x8smUyH{(9Ka=Dd|jwQZVe(c2!L}iE+)<OHcyneK=jCF&U7uG-eQ4ix@
z16O|Kk{UG%U-CNy*6Zs$FR$l+!?ftwBWV)KEwn5s+%4d>35EoyqRJj0JCnV`jS(oF
zY}&@H(UDPGM0+!;E+U~NqZ%{sPgSAY$<qa~LkoLlVefKNqI-hqd0EJHqauz#g*=?<
zn~4`xbrgwai3{?KI#~X^_x`wwRch1{NqNs(pb>v@Ky_HgIsHHGBYKrgp`-B@hlO`~
z=|62zdmggPl3v=_rkK*1D!~_zh2`me7Y~|{&w%A9pS!$3d0a_l<IN5aQ{oaCEV{0x
ztvK)`1yo<tm9j2}3+0(%qicn5gIyr<>A^fwZ|PV*TT#jnM|EoXJ{_}Iz%)y~rtd3H
z%Z$8<VrIqq$vVQI!kOI;)b#NaRpc8sJL&fO<v(?{p%}6KlsS|ESa^vStsxv3b3206
z4~0?U*gLh_J`b+B9_H&#(%ocjo<MyxY7A#W_2m<DiyrS}7bKp77Emb4ViTmli{fFe
z+ES;FM9?Du(8d)M_*{qgw;WYI*eG0V{%Mp=un8urO$YAMq|HlHJTR?(4b&A#vh^UB
zDqK!k&|+4oh$&LrIXK$Szd?>TJse3T>G{r7?-^yt6&C11J^Lr7efF`f<Dgnw&r=tS
zt|51J(tQKBOt}o~WSf0<#(^225QpJ1wq-*{Pl5&{C{eJ%iZ39Na@P)Ob-TMKaRtO2
zIn!NIYHxp3T|7jPUBWn8-H=-xG(uuz_38kQueegh$_bK@m&~1xr;Jvi=$w(TS)21!
zrZ{TR)OT+LS4dX|IB*6=Q<jBIRkXHm!Tsp4t1r5*&9xY5k6zQUB6|{r^(EL{zGIp*
z+W$>fW^{L)jLtHHgpM#dF)wahm`kg@NQ-|F6@<Tm1P6w1MH^a($_VOZd{MvA$njNx
z@tre=A<4jro|2sIS}v`{1Q0_D!O3v&e!-x?MXX@N4Oi*fJ;8#QEjV(Fo=t4dzl>?m
z_eg(`+>l`K+GVRi!vk4?HQZ)0Jm_sU;5V>?!roL)wqwK%)nufcKu-hO{Z2{JT`_lm
zI7sT8TD{5pE*OCu&0k*sa@0izYS8DV((<NIJUbXQvxu^`?qf4dw*9Z9U79^13V1**
zL99ux37#5l!tMRuT%}13_y~Cl>0Q&%89^i_Z?TI@Ao88{D2w)~l>F{}kc|k8%eC-L
zLYXnF1ee)F@XnU#cOu|cGJl-IILZT}xa352?LBX;uAL6s`wdXmx@Hv<l${@Krfm`c
z6C{<g<hcB`3w(~5D)|2-3kX0kIi7*dP<}T#)mqNZ%?jG(GMDE#@=jsAK9_BQ4~P)I
zRJ4dxdG+>5VcA2O^=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^pxO<HGI$iZqb#KI
zI6($93KwtCxxH7^k1vQyHc^o3jIh0AU2(P2n{T$n{`x&MyK&l-t$>DHPQe`idasuF
zhN_*Lt9vP;th3EU)=w1i*h4*AVmJnj82Ot^4lCYvLQn4*2cM_<l!mHKe;T&@>6l6i
z$bmdn>lXLCbr@8Aluy_bmmVN7jztIM877|r{%!ORh*IcBhFkI#kehybty7IN_k{63
zY!AS!o~&iYw)oo^?goB@EbyM?HlbQDv?+%9Zw2JPA%9k1%uI1X8i+~ZviGvIsls7Y
z<VAB)v@n<v0L5sQ6wuer%h~U$!>ev107X%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!bWtI0c<cU+d1e;HO2g
z1+CuPxiK$hlJ|fD4BkaTn4a8q7IeX~F(6UG@sDKzvG-$4k{*qQ>t{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_B<D5Dbw)7bxi!>7~fH3~boPMeFDTR^1Y(G#K-k
z3=HKE5l}S8Q;;7RFU&@fW;YK^9}*ry`e7WZhx5pbm3KjMZ65dL89uz~Ttl<wXBj?b
zJRn|oWV*#up_mUK0rxEJ%{OP*rVd4Q_w~7-|1-aOut)R*-6c)w=PR;Hu&P5nKYGZr
zREr>?p;0*L-Ar04rY4iCmhA;{<QsG}S&6?oOzi55scbIqyD+AmpZg>~*X15xnTbFY
z++K^c<bBY%J}w`oFoSs;N;90~$TL!x*cP&`)H0p2PnvPRFBMn6n^@RI1vSd2oDOmn
zkhOqP-yh6ATqg8W66SC5r49WLYx%-AX-&(t9M{`-_^&L&O)HPMP+1JI$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=<J!M@Sp?l#Y*Vgx$5o2
z4{CJIY+~KQLi<lAXq;^xo5+p+J&lo0?CHW4%FDalhwv`_w&oB5ohcZd<vu1?L;l$g
z9WDz_P7m_MLUi95bVu%8t(49;$r+bV?xt-zLD{yT(RUtaE=+1K@YWRjxvI#e!8=|6
zudt25nsM=Bn9N<SRd>THVu0wMf){JXnGM&GFhRUzEr|zXZ~nNkybxiHid#e&#$^$_
zjfxPBB@O{1#3D0-<z_bANT^&uBt*T%eKhDn2!@W+b}mQ4N^3Yc5U`s85+u>-P-DK&
z5fi`ojh<786>}qq>EQq~m)5>A=9I1faSfP~4k2oc_I_M|zes#?*%#~F6fFw1pyK{!
zx4J_0Ex<?jvaqyft=g9u$M#K)&RVD?L)_uYD;)S8V~Bz7Oy#D;5D&xwk}xE#f3G;j
z4ogPJ8qS+Wv|z<1Gdc=7Wux|(9&u&fD*O@oO@uZwrr8kuuKF!_rCMm(B{H_Auw?Q*
zYgUbkQ-qs*lrKAAj5AcOeHP&Pu-x{LdVF)lA6JO_SI+eWk%4tbXzc6UDeH5eT|KNn
zX64^nr|SLCR-`i}8{4ML5-rZx-+RbZc0KuMb6i6$uF=O4c1La(+vek`BCLb^`=lzU
zKN-lc;UQN{yy|?V05M4(>Y>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>3<ux#Y`yQX5Oq7(QcsB3~mHVplR}R0mru2lv}XoRN;{$T#Fv{7ne*CCt6q&
zdk~Xxlto@^G^ndBXTO_&I)Rs0x)0H_6p&!|J;;_?+e5_eSsg+)3SPpn0K{JDNDmz)
zDRdyhe6U}(i?8_i!RSr)&Vcq1&pxqyAelA9gLW)gf+ZaUYvl2B89rkCMY<nhXrVg4
z1+1zLg{yXksfEd@F)_{Ms7YQ&wcOGJLo{v7f?1OeThNoTKc#~?o^c^23XhX~_Ff?|
zXysJ;fz+A+R<0J7B!t26@QBKex*f@adi``90Bcr}x(UB;7=(+hwotLh^Y@V;;0b6~
z%J~PJ18J8+2OAa?gC@VMvqUFa!49R~<7AM__If@5Fc2>G>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<bGsThvG>%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<PBYl)!`_ebLmUh|CUkz7
z1l8PgkSN)pXt3{7j<imy^W;3vtMjN+8Jv6>;c|h1r8i!&Q-rScSs>+uKz14wA#z3P
zkL->tB!^ug>gAwNv1o*4P%A?^QeV=&OGpjYPP%uQ@`!LPT=pfxJx&7aYG}Fq56^UL
zz^$y<lL-F}{AX`GuCAi>^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|<<gYJuw*!4<b({uD!xN4Y@tI$*?d4qZ)lWwZ#j!r8U!=$()V
zrwZq0uMC76u8B5LZXdd4Kn_(~yMml7;35TIw0Cv@{`6B^V`h4ff6zenPS)?3Kf0A;
zL~3~WQ?MnwHw3<;-d?4ZkV717eUWANDvA);<?ahLis-M#JZJk_r`Z7w=BS6;dqoCT
z<G8Y1c5js!2m(tKGBEW&#QSAVm)>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?<Z!h7j1q6}R#(?~(|CKNIr|u;m3QJYpJt!B*Op)u
z)+%GoU}kc|Zd{m`xDI6c<zlVyxV;lJ%C|`!rL~R|OjaVxSp);MVu|W>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-<P9`&<zP{Blw~R*;$yK}D`>3N)JA8)eIS#d$3D
zro0t??D08aI@R{)RHyo1Q=uWm9sVz{E$yl;QVOEJWA<JRVSTJpCUP*rHH)aZCCe)E
zL_RX(By>i9DACNzSaBTPYWH^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{<ermA$}fJcbC$>%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<v&Nq)PLCZhh7>)qlVeH)sKOzN4DKhBEs$95=|^+
zDqW~<#VT}>*^Ur*k&~9XwI&Xerl0?TpeAbYro@uXp$0X^BzFhao^tN3Jq_ubO2~Y*
zd;p<Kg-sv(q9|rt9754UYx+W-c)z1V=9pVGQ@vkpR=IN(al)8mj2f+%FLu&3n3V}m
zx2?sAuxbCv*bKwJ>pTHU;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>=^?%(<V~?t`7n~w!xU^2?(``FRAi!R^Zw0EHzO~VU*r-SA
zH*E+-Ut+GJz(@W4F@l0AU%Gf$OnQE}t15`1%&5oa?d%QAz6!1a*qbX3o6#t%(Yuk{
ztN|-HufNDUC0$>2Ict}8PdmyhCE4-sQpKx&BSbX&>qRdo3rGS0!_8C*)iYZo6aQ}6
zn7L+Xjt;nRfgxLz!7Qb}RJXk{WvfTIFLJY5w+A8jpWSL=bBHd@OKP+Sb~{$eu8@Ww
zN-}r<{J`LC6|snX<Hf!`)9QNa{01TlTbAniS&HlfQULVYjNA!#Zd{m`w=Nxi()-;8
zef;svm>S;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<yLf}!9>=;K`^
zqBKmQb~F}@AbG5W`8UE<U{y&b79jeELnr7hW61@;;FhUgvJzE=f&qTaRX)L@B|t>R
zykcHxx^ih68{FZsldUf`#%t^Iz=oj6f~(26Ill6Ele?R$%FV8ee^RFqpr9{(UPY9x
zIc-bzM5I|%Ul7n`R$(QA#G-<44LIGvTQoq|;|^=nEIx<?m5i}1p(yKitwp&wy;mU+
zl?rC4-*?c1!fjPvK^ty>?WH$gw9wV(WvIq=<?@E3{BNUt_)YQMLOO^=-Nkm#DdQGS
zG$BIKTRft0EF1ev80g)T?5@NcrRqk+!Q;K<-NG70#fgl|!^jnNF-u0jL|6-DTfCJL
zX=*I=<d-UDPR3{Z_MXxf(JQEW!(E~jBi^A*SQxba&{ZsJl-%&aS`KhF4B7<dK!c|Q
zkVn`<HoauW(H3`3G%8+!P)>L5YOQh)uB=0cHr3*%tt)e?#!n?<J9=RYiyP!YcIDg*
z5A*B(-<=lwBsrJjSdTBWUgSx>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<i4p#
zKtSpwvY+4DIF)-YyXBM37s8vi?Tc`p@+A-peK&hql>^k)j$C;So<NlPG_*vB8TaJZ
zmdbW4dS_ziHkmS2&pM4*b*U9nYMhFClUh32lnX>b^)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$+TfLLLCRS<b-;buoYr#fXyJ9aEU%SwZGRF|`!Uhp
zsd&@rLXL9mU)3SX(5}DoCAd!BmMLF<CyajHdR(L3Ft56o_j_l2YN<?QYGTBbiTIlb
zAY7Fq8{2UegTK)v21E^|DFVu#US~8DG3>Cjj~(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+$!OE<dcZ
z39PdP*w3#i=kqUSj)zz#5C0Rsq^zsglO^W1PyafEe-0dJK*j}xK)8WuuSWpEeF7?o
z5OD<F90<E|<ix$Xa35rSRI}EBebw$Ge5BenPqYDy4@O7QLf_HmtUaIV>PnSd11(^V
zJ~7ol+f!<pY>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=<ie>iD4Tlr&dLY
z0rdUfyG>2ZcZlasm+u-3^KfIeL`_Lx0zWtYAQDFMmFp|HcXYi*`0eE@A5uvH64Y?@
z>5kx?*|$C3ubNI{2!V@q#&xD`bG(W19|!z&LAyNifQ3F^J<sW83C9h)63pMR9}3G5
zpj!Q886t;$Q^}_fLezU+oQsOTeI%gzo4tcD8=5$38-bz^9ulafMA;L3V@m_5cc}>B
zwc2SafHtP|j?kU@@r<wSM4Sjh(=p^IU8v))DBn1vn#7rj;o(RO#kVwo7=6+Ll_I@A
z+pZCdfcN4<KnvSx@m4GbNk|B_Q(w8uXOQrek6~8lwb|eWPJposgL2RsarJM0j{;@i
z#`!Kk(ai<+%r!FQ%FSy7qxIXkLnrZ>hR&mzbo6jRm%MTz{>b!x8*m(>2Q69~C{B1h
zz?$gg2i|RvF?eE{qtHO*NnrjET>6sXQ}9|k<o?IM*yV&pc<eiR$y;;B@nVLTYok5+
zr1^r4K^AaJa}x;Ari3WB57#cRFZ1!UxT7c(n&jKrh!i)`0>0`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<<NG1;(?`Ad;#`2wU{-B?>>@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<rC%GV8PXlCs@jxK(R)fwe_H7Mr;<=!2Kx<YcofRW
zH6<btZb2alT1B)b0M){v(kWfqNwkb#T~n_Ohf%OA8K%mS)tt%Hso-vp$8yKDZ%40q
z!*f=;&Qd_hC88WaOrx*VGRCVCUTT!|5bme?Z<u_Y40<}VOq$;=pnS?SNf~R0SQcb=
z-g#+16x#jw5OLKx79<;(?S00DtS1&HSF$4<gXH+q($smk)I$Gh{u=IX(h%<T`)bx+
zj;+YMnaWG;D&p&c6z}oe4crD!e@6<v{q6a?IeuHPru+PO@udt6(uWImpZwhv578F7
zb?tv|&3&<z)QqrAg=|mz{^9Y->;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$<k+pr>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|8Rk<HQC{vdUNqfy!oWqCaWYR#ykT-u;vJ-C>vJ4^9P|K4KkUEJog
zXQXO_L}{^_;tJR7KOAbNr!(39i`fu_G<trLsS(C)6fVH^G!*S*+TBfkYEVu9++VN{
z$xI0gs(@5xM219t?5jcF00t%<aEEKb?-m)zBC?^CUZzI!gVepJ3Wp6P6-P=ptNx@?
zzIF@kf-ipfbOtP^W@MnnLXhL8E*?P7wE5jtjLxM~R96B+qrEgA+PmTX5CV8&(uM@l
z;BKXrXh5SYdN{*64(E5_)DAk_#^0ZX3!RiS%#9S|))n>2%cPdtHwVP7CBO-5p4_-i
z<$d|XL?%;PJYg%6Jiiz=h={JM3+PwZnN7$ipVvoVV&pEMPmJ?bY;83$HDM>=rkNx&
zmJzs>9}tp>4Q3Dun8CjRNuZa-<hO4Pj&}nd6`5f@nAmIP{LAC(HM}cBTAqZb1OV8_
z$;Ok;dEs8q7=H=o*}$L%FXp#CiF0t$H&A!LM~1{L?r5e<vFt^dC@_>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``^<lC0%&=d#)@;n@u$K%w1
z{bsw0t^sHhO?>!(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<RWX><ZRoH_z*
zp;&kgwFp*(@=&+;(YJFj-uH__$DfJdvq##fBxnlc!K{He1L1TwhJLl3hwxYZ6f(uk
zO7HN^t{_z0Wx346SP|dQZ7m#h;0(vKD`<jB-PTE{7@dxML@nUpJX^JKeO(CuyR2~I
zum(vML{Y>>6%Q#Tbm;-*1}d<Nq~geGJ69kgwA$a0n~7KNOSJaLERF2bj;o03h>V>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#L7<RQaE=swKMVL5ulO3ChTD
zir3DQ{l+<2f7YLsoEn=zK2@X8p=Ph4)A%M6b#eBwYS&zP`pB-#3!fUX#=5W5PG<mi
zO`r`;u3I-Qs4^(UIi?@rU&j*k9dD4-i4*$(?U5IJ4kBa+%ysAibj_n>cA6q(Pzr<j
zVk(9rxG+TT8ty@;eYGYmTv%TVznd;XgWOEmc9Lr11lERDclh;zJh&#6#f7M^4(4@T
zb`YV-yf1@rst@6lV@f4Rje)Qv!5INuLgEq-CcgaPXw&;Qm<PuRKD8hE23tc-QWQwe
zU9z??I+6~UQ2&Ks^8iz#!4ri45!Anm7td5PTGo6dbJH(oxaYt?2V%)PmhE*3T>W-?
zN!X3VzqbhCFe`p~)51c?4Cz1o8ftb=I2L;JZpdyNU%~pCwJ~30M3ZVXrM5Qp%II1!
zO!Hy_PG9KxiQ{7yw&DnGuDC0bS;n!f#<JWg*h*gPl@AqYDuv>|6%`uy>nobJU6HPa
zEu~UeKEN{LZ3e>FCMM*~Kcx($To)e=bgDDUidP3sbIgzKABLg?oGV@}joPO39EC2C
zxQgC~<g3g2`0A|rm*+Webe}~(MYOzgQN-osrpjjo_g}psKYg$B67D|H-B7KqqSuh+
z5DfL1HTcy`OWT(G-#%4ff$0W~x@eSb^Ptyxd`5)0eL)wK@a26-G1Al>r?Y&!r2m<K
z-)58EC>EtBM(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(<JD3B&kv;
z4-|crm-K@hpng^axvf#l$D|<T@R%}JN$qhq7s3o~yI!j0C7o>HFDk5jqsVN6fk%Y5
zFT^?=y6)n$F496xf(gz`b{~Krs8y}Hot1IQg<QdMomqFZiag-7XDjqwx0WqkQskh4
z2v|5X;zf%kJ+u8VOF|PX^;Z>Ur7J{Axk!~-THb}<T0enIPz#+xVAFK6=X2a_C#ih?
z=w?$bN2Nm)U=b*!{Bw&CJBk5*nrb7dVLQ)(o+Zv<C!ge6D;xHGa1^3+z68(BPgQ%r
z7PjR%9YzMn8QvoU|3_p0x(4${3a)H+Q?~7ag~oEayfcb^=-vi5Ly+1MwbGD|*oz)~
z2^pvGMb(Ho#Hen(p~DK{E%UUmC?sC`QQmYQ(+;Jay){WY-62M>G`;q3OZOO?|GD7)
zm|Nj+VN|WKEwo#VxT!@i4-&{ISbpS3Hvw4B@fqIp?!f$G;u@m!s`zeN&lml*M4Kj-
zf9~~P43n(HzlV~Q<gA~v!m#5-+^A?6x=R}(Fjv;d(dZioJu<Ix_{2&il|y3zG+#sy
z5N_+zm|SEPTOJnVPVzB-NW!yx4rI{&UiWNOM(DMt4y2pw+*q!O&x~eT_#t!>PFS!y
zZ%&Q~_rKU%6wK^X!X)>Omi%F0?_J-NY591Ki{N8QJ}eAd3>~@zigp8kx13ZKO0dw4
z71UD<Z%1I5aT3QphQ~F`C+{nm)ByO3Bl>raHhwf^p<pE?x6V+xfvidhxYf)4#(hhc
z8(>1S$}XeRb~O#AY5`#=>`fhdXVi-)&|bW(_O4Tqe8rG|6EN9>6%=GAn02hD4XT+O
zlGIBzDTzq`7<$-v^M~lQ;GTGc$*sYhYV3Fc6yEbAeFiSZ_w^F!aBSi)CnSJ1%T6Ne
zLv^Ot<v->F7uANS;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
zoN<lES1P0$|C?JdAgN@T86JzGFK-%S$dLfm`d4zmKA+-MO>r~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>G<ZBUX;a62zQ$uIa#x$*h0OqM}ylMpGf*6MU=;$+KC
zy;w5Z8#smL`tD+`UesL*Y!NUYeOmk2Cs_WYZH$Wm2i3SojJi%@E=y154d9q_c+>Fl
z2`3bpswY^8Zc&1(p=KNtpXws0RApW(jII4%ywiBKDPbMrUF9o{)MC!nVL#dRZ8BL0
z=k<dF5yRv09xFw%MsOc6vO{do>w7v-)+!qvF{w^}Bn1E;^KS@#Wgg|PlfB$t%UTnK
zoL}M}5L+S99QdHy#4d-Ol~E--UUo=unSZ$YsmAcbEXw$;4l!7iv;9rRd6D0Jg+5X3
zvLF9M^W!NDa<GMK1lH;%-148mTc?Tz{~|OKd{Hvu-i3nzb}lNotKvEhs44qlkjs9P
zB6wSMGHc<OFS8SW<*8_j$D1O?cl(iP2QKXQf7c+!YXFjujEJCZx8!ymEF)=mz2>RG
z4ej50(8KTk*+2rY-(|WsJsZZIFd!6U*+gw<A6*IF4_WHa40?Xrd|4?QmcO|S{YrJi
zJl>dhz_lC-gkQ-{T)IxzKiR$H`Zx9v#m`EzeiPdijV#;bhz-(`*#I*a)i6VHe`T6S
z1_x2i<~1eYlq}f0tSq88n{>(YAGY)nI#~EHx0r<vDSl9tQ~S-aRMvUTH>3nO?r7kc
z2HepGkqDhehO^OCRP>KC+qJ_UKB^>e<Eo_U@9+wtry3($7e#=aF)30hl2J(>gUx7A
znwo$;>VteAuh#Ynz%CB}s_jnQjGIDuIiy=57Jj<kE_lVjabPhkjiR06wh%+bNwmZj
zA@j;&#{*zkwqIN*l$mg!9YUqgq|cQ0Y&&KsVzAaA$~Z7NkDE5Hx#e5OxkBr}J|u!J
z2i_(@eC-Ofump+Ui%+OVP6%^|-=vF)R$kur<Q`^|%-Wftj=_rM#X2aA-sFk6w*AtD
zHD?eRmuf3M`@Q9cc(XFqpStBEGOCcTm9jN3BmS-lUgYB+Iv@p(<2b<CNbh|h`4b-<
zBMh-GI>6tGoM)s>#ka-YVd`MEqxYB>G;O^CDFh}2&mL_-y7k20LBnUT(BrsGq{-~@
z;yO8vjU2(yMH|VR69!_v)c~nUi~yLA*gi`?hsZJMI2FJ<s(?oidA}t4zuEcYkN<}2
z?>M6!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&<eXf>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)<i073zi8@v|)fafskrC{2gBDqVGfDY(uYyOUaHiZm9CG|}lW2qQ0#<^S9|qT7
zJNxvgK<0z^RL>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<O-^|)|a;m_H
zedrtQ2Tzz2_H;)@6fPa?@K!Qgi2~gzRnS3Jo0wrc;MUVzZ1feGu-@@jJBnYPNRIxU
z`#Qjxmc}LoO{%G^PoP@@i5NrrkUah%aK7gV<bdb+Xsn?MYsI*pyKwZjcndRkDDvr#
z@OJ59E+CKeas2{OiqOFNuZMdLPuR(HJ@c7YxZGa9Tcu9v4aMJ*+pU&(1lb{s|5oSU
zw%cLSDE3!ISBSTMzW;6U2?X)cH}ocEkzz)%iyb=M&lydcPv3FBQ6{HTaMEzRwZ(#Z
zeW7ri9Rte&OhF3HVqOUT(>`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)<a@u&r|UU7zF2_A1!`iEDC49tqYriGay!;3n(k2CEnuc2cQSJ?>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#qd<Nz|MSkS;3OievZYSAw<9tfeCuDW82#W>qp9=!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<H0dP3yV>
zH!_x?4*nnc%6q|y%(D?j)21$09GNB=62g4|@{OST<BnT6-omh;N%k~p29ZJd30q}V
z`kP}c*?QAv7ebg~3Ttve78&6D(6$T6>}-Rlq=tWj*IWjF2A8Ss*(*T&XN^&4t24NG
z!N=O+q!La67DXQTlTz<Z)8B2K8W53`Ky}TcKnSb-WiJZj3;?H93j(3L$*~@n=3XWi
zrc|9Sy0=F85|v4&P74hzVgq3)BDQAWq-+PjdwSLd%#qduM8?&X*%(iH=gNH1YK|eO
z)iQj<iauiwQua^vJ`fH8<;Aei)dv8e)>8oyA6?KpMN7&?SL64f{d-6{69LnF<iCAd
z57kkGdlQkBAZ4}WK5>(>dNMSt$MC|6Qbbr;o~TENhn1<LKkp5*w!q%Uw-sLo8lomS
zK!>J@Opbno^a7EJIAF2DFC?E-fPN%8pRUF1pDpklc>dXA+~~Y8{pG(h6Ir0I6raD!
z5K=oKtFElvvDnl6oiD9-Z}*=Mxc@=*c~xlA1{nzKT|#G*DhnR`YJS#-6*DGBW~Vk8
z<CIf^%P!?emmgRec}6iTiCLR<k4*}&mgn6~aYcV8_E?ddU(c$?aCx5n6(8pBd1qg(
zE7(e879T#Hpoz11c=zdJ-AiN^QZ6!1vx8z5l4J3IZnY77_McQ^mB8CkXP<JEV77sk
zJb()5MwR5zqk<EZn&AjMbcf$wTlad+a*qz@-$>b&EE}r_7i7}W9({t(Z7?n3&&kX!
zIkJ~H2<h0^*9z_R{!w}(4a(4w7(uDFGV!jiRwL$M4I3PK>|9fsd>}B+A4QFSs|XP#
zd5@|2UQX)!D<aG2LT=Qk=)C%!m`wBwIZ}c=4~E<v{}Pe55d*$hQyIX&j2mcvZ9V-s
z|7C^x(|F1cU^9-mT}h3AP~;%qfMM8wwnbu^q7tr`cV@(oq-FVp=6zW5^<iFPB3^N5
z#TxkR0R1S$vz&V{{7Z*~n!QCmXws(1ew<6!BwTlHlO34%hP0z9#(S<uSamYTwc8-y
z{B}Wre(pdSgqnaiR!h66LtDTI4u&Y53m~Ze#5BqWXvO!-K&KhgI2O+5JyC0Fy!~;i
zMV;m05G%cNGnR%-B_Sz5v69V4DpQ1f$erRadSg6iI1r&dcuU8b1Hg0^@IY!dUM-v|
zDdA#Mw80CnOI%C%0oxC^*5yb+Co6<P>Q2z$Z9fFtPfRM_I}3&|zP={s(h5g8z2gvD
zQ#SqLC2#!0C$*7o<KKR_G0+zS6O0+dVCk_6&$i;a6l|@v`x6#o)<-p@g^BO*^jrdn
z4^x<SJ$kAE(=;^DB3)z6IwUvUg;qqEdIy@E9{u_O@=1-}K#huR3MG;OkA6F7G5LJ?
z`DOktec7l13?-$uhu)*&LeC6&5xE@yRWskdT_||lWNR9^t6S1HRdt(a>;fJk!t?>i
zR2xqfclT?(kaIk6)05W-)stZji8=|q88TFYWj6MA3D(ueztzzz=`5tOw?8cXNyIU=
zJsFf?0Z+taf%uK?_;fE;DSts2WG|<C<}rHM?F`SkVUOR8`B`!netC};&-Z#`hEwA7
z(E}GhvhTmE9Z3*CgpjiL=3Rxl#^-P}Tt_kz@;xpfOJiDj<h+M5(G(Sn&eOagbu?V#
z#;(M0$Y*W}l~?e__@XJBZTe^RMN<h6qL<gIIk?NCqJ7w{>}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`osM<YJBKi_#Ryd0Ruv*W^rJm2F3GvgO#
zykt4V=v!DLDJtLM$U9fI(DO6(nk<c-F+9l(#pVz)kVW6luJDvoFhW+NuGxcI`<7!a
zOlJdNNC0NlGa$3D?Tv5adT%Kk#~cHbT^gG7ta>Dh6I})=q|<FEC6`a=09d{V6Wj+A
zq3XCnpp8R@{FHA;9i`H&I`V>!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*<HU*J-LyW@*~C!q;xVX!upBTEfVm2YpC)2Xl%(irkq@m7K-jC8-hV{
z>8Z9h4`h8?hzCI^lRPNs9;XkYKuhbF_P>E<p);%5gTJR6vw~>?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~T<U2bF|C@=jByM$&WL3N!xM@N|8dUhwp?X0
z*4X>1_t(Xs>CdL-np9ynoakitqjOCxIUwdCmw@We-^h1{8D^@WxsDC5HN5Vo-lZ+6
z$F6(Mf(8m0Ey`jo2aakbLb<ts<aySC{)$L`9J3O9pMMvzGV&R}Yo8yTD~#0wAlt<B
zx3dtJXm9e6phUu0mBv+y)c2PtK;)|n>oddFchEy=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><LhZ;~dfa
zKlO*t+dATV(C8ja*6+g5woe=d69fmwp<D;g4$xY}w(W1$X<)Oaa($3(unBsmbay%~
zyxLty#KaMH3(&45gkR&$tLRt?dp4Qqi!w|eLl5M{1+^qy3NEA^sB0}a?gx|iIZuky
zWSJpD1nhmy*<7gkc#s<E7nz)Xtb{>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~kqT<TS;N{rzA?Ky5#Aop
z1HB%56M7amUqw)gOs>eCXf?AHw(l8%3!*f%<;%k=f$xV7`Bu2|r<k$MB(cLf-^w88
zZjL8$CY$MzBbO`x0{1<^He5CG*7~8;C6w}H4Y2Jyvx2WbF$MPW1@Cv+(}+PKaC{di
zC|NJ=(JCCtI4`SYK}5gKlTau~0tQT55h;{|%EjI!h%|1d)IT#w<oo$?eWQ?lN<I8#
z<r`G9p1%kXZst0lT$nT7!20!DCTA=T`_n|*c^5RZGdgiKSF@(~C3O-E|23&&JLuK$
z>&E{dr|vA%Mu^w?HVP&}(8xL{Fmf*iUF%9)wFJ&<tJpwhG)AKDGF;+n3JEE12G<_M
zY8&DvHqM-M^foC(i_k?qom{@yzjqxolFk&_F!tQO<X^m1g@aIR`tZ@1hDQ^L;2m0X
z$75<%4&P~n4rE?~ldz>Spmsd=VoiJ*LJGQvfSnL-i=KP1v_GCoWf*uS?Cva+`ys<M
zKpy4g(fL<kxpB|!0sm8^UEHUeAqT)m$kCQSd^VAL|D@+|a-Z$!vXq+}4>VoP$G_6V
zj+^sIB0v)my21R8c2Is=vFe6{0uFrt!!!$pzNLvjuEzO9rLFjaoHTwlhjGCQwdd6@
zZ1JS1PAs2G{BRl_AcXt2MtLQ|c*4#SaKPUyBwh$;U^rV*f*oY<pODE~HRjFa4<Hlh
zP?!GtD_lFLv|YKsxwx>9_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<RICFS`YNO8*Lh?B
zp1o@#=$~l?+e7>&*v1z-Vi0OeU~IQGqw1$Ae^`6?Y-K(6C*rtgJ@VPV2YOWGJe-7f
zVTT!Z<?SkFHX%@vj+Q(Fi!c-8rU`yZjji6DGSL&s?y5Vn>FhMCbeIbu>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
zPAgUA5T97<n3h_4vV4coM~M5mwBK3O!u5mh^oY5Cxiqqv>MMpKRD;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_Jz<vH7pXEJ@8@DvPnOU
zV7h%-502H%3{tXLNryP(@V5GXkvf%=4Fz~G^6N3djNrunzy<&hX&Ez8<?3U=pQR^(
zBD#DX6`fQl`LM~DOhxXJ$_f1u=%cM@R5t)<al*}1UvE}qH6q-T{VBnsuH$~EYSOMI
zFIV*1e@69okM9I~MtCo@RA7}9S&nf1(OQFPg$^6;U_BEPz~4z&l#>J)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$c<Kj|jTAao_M3^j+nidoM41{QMUqT76H
z4rlZLH*E}yjCHVUS2u!-AcJFc>Jg;6ZIgI`r7tkl=in@STdx&@OmFA;X8bZ?vP@pW
zP+tWDn_kbY@)TBEFxw(}%nip`xcZV&rG3q-*S7>PyDWd<<|V)44BM_ox2N<cTN^U=
zH~6}g-d15RaQkm6l^=8^>ZK08T@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!<yN_Td_^
z;^m5=p1aQ*qI@O_#Ec4nEGFsn?>s+P2E-`_DVHuIU3EKdkX$%OD<jD;jM>-%8jp7m
zVccNy3}p+D3R#UN9^`c$CMeaLp`n<yAt&G*nrQXW*I**y#b!V}(Ty(?pK=A{6wh&7
zg}rpdo1u>SQE3(hYT^2PW0ptZ0a~nu=z^I>P!dzxK@S7yV9sULwnh~7`rip*vuX}-
zKIUR(&L{iDU8L=^eO+KRpJf<|?CTPfBM5IgR5IP{LKnF+_EEk!`%eziXz5##hFb+-
zq<?i@;~$ausJ5fVXBt6xjHsLOjI&Yqe<_%~1~$|rAW0L(Fr(IpRgUfr(J>abbUFUp
zH9po8!GNq@zvv)}%q2bwA(xwMGvjuNcz!YC2L%IVvxubW<iO9xC6%adr)2j93}Tnp
z^;5+2lO-ZG+>;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
z<wRdVbOZp)H@k~EE4yIlza}m>D0ev|)%?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>Xeo<tZB?_!Y$O@n`kNpCWf5zXWVHIw_
zfBiRW^N(9WWS9LrJHEo_fp8=(SIoJw&p*Y))l%h0F^Jope&EhG-*6Sa_4&U}G}OW*
zOEY0LPb{aZ@f<^yBl;}Vz{@~$JhXS(2RA=k&y6NJb>O5mR*%kA?<_Qz`t@wDn^apJ
z=LE>@$wKV;#M4=YzHq7WE&=$Ii$lCr7=}^74ybwo_&KfSIg}m1R9AsiL<v&s_-7_x
zQ~t69w0vrh$2@%->`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~=MBrUQdhfC<Ji}6yDbKUKuor!V=Oa(~#5$T18WMVztwgPuc_r9qOsKMpI
zP|9(tU!^JAJZLtdd2<xR)Z`Vm2Ay@l-FdU}3RHBf8AK_L8Dh+f+;1urY;6;X(sIQM
z^b%N2b%;(#UU#*cK7Qsws?V~OU_B(4jjRrd3|;8l>Y?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*T<B>L8n4
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=<sbYjC1)8(A5hzEEY2g>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!gUrx<I)(XHMYt@%~J<;k>8l~hcT}M
z<KkPSh!AMi%1)81ChL(AM3|Q5D_B~<I~GHC12<nVj~A#k0o-LVhNnWI&Ym*@wcHO2
z@!3DkD&}#jOtZbr8%DN69x(UBkdKUF?>S6mpZZ@0pbrFs6nXms)d-to3IW*ti6iK$
z0GiV!TR_dIWq8Zz38v4t++(UyYt%I+T4uY|&8aozV#w^_vRX!~z1Y18bHlW2DSTv~
zg|L>%Rc<smSpV3*aFKf`>xy&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<w1vj~#C#ml0M9YI>%MZK6fZq9$%LJUQvenmRTO1}G1bres_%
zN&lF^!LBUwSV13&3hq!6r_3Z;Nl_f$cMM2PZpf$X!j);@Bqm=<KIVK!u>Gf78}SWQ
zXzH1x9#a*i*Jjzx)mp@TKA)A6m3aY@tR!`?eLKc^p#cC>Kev6jT()`X0@(V|7$`Ty
z<ADwoc9klXe~qMF44;gA*ed@B;j{U}8A$)5?wd*c*GZ)*ZH>tx1yP8>uC6NxR^gxl
z84$c1z?T{B)b=S}(}PlJq}Ih;GfvbB&OkuIiP()C-2acM0>=)gvyZ><g?2m3)q|`|
zR?)yA{)#wr5sexW&>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<l>)%shpWt(}-~&t$%l
z&)cX$Mb~=Fq!3S8D8mbz7%eV9I%$EH+-?USci5aHnjvEOvWTYA0{_8B`XTc6UN#ob
zbU(%lNw=Mo{x<!Sk_FGHeBwgiVd|UgaDk>1zfDZHXdLfdNYp^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&i<dB8{Y?&rPsG?64bn4G{T|M;a={>6vcO9jRl&e4Gte9t)55Ak
z+T^EeBN5CVoD%{SpvGT4Xy3W3HO$rF02?{0o=>AB@-74+T<DU9-hg?Eg5<WtE*jM4
zk1XM8eso$y%s-8_6Kp;S0gm&TO>$MHO>vfO5kJ<qsH9+LK=Qd3{+jvLg(9{tdVcw;
zVQHYJ<?r>@$ubOb0gH0av}O4U8Epdx?l&j7@m3Om?tj>}&amsmWh+y<Q7=4-zEqzX
zoAgPD-jdw2@Ha8#AB+|N?qpZ_W?%PaGvGS!eV26%PGX+<eqb3#en_~SP!v*EMo_rS
z#mx+6y;G7`K6zuE0ST1PZj}VznDl=P{8`O3h#p%a7!JZ1CW`YSqp9Vw2!FSDY%gM~
za?OF^YLaQooc7s?a}uhP%~)*tZzNM1$nB!4trga_f|z8<Xwzz}sCZ8;d1n-d%Wc8u
zS}<q^-S$}GwyLvE{FUgYkI%Ow4#qmDxL_mV!JAJ2n&<z0PB7mp1Eq@T=#EfHo29M#
zV@feML^^ZCz$9KEH~h%VRG1*-Ofp3|TIkGckg1<zD7Wl9m}{_ZKm=G#`rzF83d_1Z
zULV0E6#RUiU5=TnM)-R4&zMCbF}_|g>66*`(K9>(@M&rcm{j^DgSdU%TeU%<7#vxW
z_?N1S64V1Zz<Wso1+c)3t$)Eq&0MZz^tIDeSLo8wvJEO~lfLQ!t*2m)fnG4uIe{y{
zy4x)4_WcfxN*SL&`~~+>s>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><GCFk1%Fo?V2euM32PK=(_W^#<~NS(=4S)_A<J%VuL
z4+>#@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_O<SZu55L6k*)t$b6W&!Ts;HNLKF#b{t^G5hKM~>D~f+TDk`JI-y$XiBy
z2dg;#Z;zy<zoXU%`e7h$W%_`yU(HXFL;1mPbrzF8peRtp9=K^Xz8oW4_coNKS~<>M
z7VF(7%AC6>lrYzm<hS{23)pbi8a=B%&4Dwua7#mXgRg+w3YcUvSSbeo(<PdJ^Yx~m
z&Wy~+t-D5_;UYa6t+anU@T>wNWMVJlJos#K*Oa@S^TjD+{`p@C7Q^mI8n%;lc1de^
zi4cR6Q+LO`tc`7$(hIleRYSLu;;(}lL(EcWgsL@NL~szLPrp4N{B@o33<IRc9RF_E
zt3TlLu>bGhn6~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#<<Uh8oiKUX675NrR>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`K<yfpo)h_fV=_As;~Hi!8X$jkaUkfoa&!QE|FFtFqM?$7e~#jadXoY{TroYXM~wy
z{#?1#iKoTEYXk@OYBA}s3`5;`^6L8wm9cKHtNooq!yTlVpXm!(LexVM5lEhop${x}
zP&RU9VKGH0FtkY0V_rQjpV?ilzuayg?9vYCxa&R(f>OOv!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_z<JCYx0`48$Ih8m2l3OA3lJb0rEQic36<2!Jm))-0B4
z@p_qJ7dSgqzOSjc{z#WZ#FL9W6pn~*nM2(dj;G4n6a)c^nomj3k3i&U+HOYs5;VJl
z^nJj%>ltVAa0IJlwWNN**d?{=WTz6nmov1s%81=k?jI^0!d8O5r0f@}Vi;Gla#+K+
zkPwc+=<%c=En96S_g9uiX7f~K6zZp<Q^csxuVelu&TY(SZwP4g9s&>5wFCy{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^<Z7UZzvYJb+Ekw3TAI
z)(-s|K`tY3I!Yf)RcSi=Y2igl_DeHf1f6}gn2hJ67rN0&Pg0jpV*we}L8rmAm<89k
zi7_Whez2n5EX^RrUk6!`Xhqs<Sk}T5F47sxsU6pCuTS|TL#%-}Xf?J8YI$$^cR5K?
z=xZwaG1Qx{{||M5LQ>ZF9OgOUEv=gr8#Q<Jh7ZT66o@%yoFDVX`}ck=iP?=S4QQ|i
z_$;SA?gYUJHh(8yb4%WApj9%PorBlz^9?KP#_XoAf*AuaXP%IleD9&O;$B<ilr*WG
zBQ6`Zg>!c&M?{@-v@p?fHSbP6sPY#m2IatSrDMr2scrg9RZKASS9_)7tt;BWnYjKj
z@W@@0j3a*k{<y+4-Vaad(CB82JjC;nqzFpI2$)mbB5&mab0s6?XBbo_bFy9eXuwUS
z$1A`Vvnbb>ZMc7qgi4ysYC)QDKd9uE>SvOoltmORxQD;4_CV=x4p!p;bnsq1J?z;h
z05%1(nn)*$)rGlZHY<!D7M3}ZVeBaJ906ugdjbyRe*9v*azE5URDOTJO^6A<`HBH`
z^JnY{#oS?HOI@Y1Z2#AVr2IS}+Es{d^W6>r%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^pzJjGLC<iLz$m8Fk>5z@ga5cnZ#D$*7*~{{2sz
ziZGD5Y`Kd1#CFMb-S-H?1zB0Mc58iyupC$b4n7JqcFk<pWl{4~i75%l7x7`<J@fCf
z_}AgLswN%;?3uUB?U~<>i}^iW8?^J4p$qKBb6VpwvOAAYrS3%fC1a6<+RC)(U2*Fo
z=2#2<rNtFb=KmoR&%fs(1nj$B3-`+4zd*e~9%d(}!7q+Pko4HxMpaxE$t*}Fv)GC$
zIG#I`S{5a77{6>qeEt8x)<43-bWxffpd9FPyWo+992(o}4FioVPWzv@9CKSQwbL%5
zVhM84kGYuSTRd$$V19zm?mjBgdo*0XD$>5iLWn`~Yq^+y^GW14iapO`3kD$+z)bDm
z4oci+lMTbb+k`>GI+E<Lb6IioBYClGzKZFVbl!FlZzE8*`{CC5Os4V_0m-j1&tYSn
z(b>PuY@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;<?Z7_;i=$(&p~;Q?8QrR{_3_yk36{yHXUzhTS(S+`
z18P4#3~{De<<M)#HTbls3}h+s`e7#8WQgLfCSP_4hc-%hpfZ;%7(>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<kf=(ea`<vl;-ygq7$~TQlmI1{>{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;~0<aO4Yd<;Z04!yK5nQyb43y~gzjbk>wb#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$<D+
zcTA)^`yuKYTzk3)l`R8x!7^LSHn_ZdZHlhC&$U@Pdr}2TIpdN#2HRV;SO}qlKW&&)
zyNvD(EdLvGYLWa;f(d`U^}O7De<;cvlc%Q8V7U(-K|t>s<J{Ogi()39rO#j$PdkSI
zgbHq5C1ZCCSn`q3PWbnoUK)qN6VsjS5Ids|Px%`B!c8gx!>vqu>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#0<Ss(<o9xjhM5ORgSiZ|gN|DbkPc|yw1&XflNQW@+V{;>tZT`#@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&<p7(6h<diN2%U-hw))hVyk<>X6
zn4CG)uAyDYnfz<HzaQwc`5%q>MoxMwkMIdFu2=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<Bq9RLV@V#eTSklBO}lJFL%J-*CNq!o<$-7j(l(~2)6jHj7K
z5{IWxmGD$L-M<yD>$wU`1muA@x%kZon9zFbM$sMSETP|??@d2_dDHOXVn{Y+r5S@c
zzJ=Rd7zm%Grw&UNxrt+6A&&oEHQ~b57dBN%99H`xCD%kWeJOeP7LA6q2CNS&PH0nU
zBzw?&xS2I^CutxMK<UTLL+tRhRz%A6O7p5Kxd(mb%e5f?7drLe<Al=mjaIAhCBn3M
zQ&dmU`s5(CYIWRi%wWLoV3Wx8Dj||gJ<MlPnHkt|RYn^<9Y<5_MDXLqs-(Z=(3YGE
z#$30G(K)VYHE6jMb9IrL9@)sKku$qK;-Z%Te~n1TyRkGlNeC&Had8J}T%-`|(;L;E
zE4^@dY%soPed9hs*aWz7PRn@N#t`G~(~&HPX}W>$nt4}uC+R*%In^WiuV0o&A%GP3
z5N2ZroW7d_C_)U{rxdtGu&3kbvG<ZQgVO}B-Nd_!ODtIX5+xraA_t9E8b1&j=m|&w
zeC!z6k{d3o!h<Lu|BYpxE;p@gFG?|rCn}8BwZ%e@oKi|yv_2-hvMPKXva<2<G_#^~
zySnGav^U1kK;UisO{6)sHA)CmD2*K!*-I{Sf%zME%fUO^k;4>sWTG27T`lHa%+63=
z%8PtDXqJ1j7Wh%qVlE@V4v|&W^@{f-#C%PYVo<R<{MiS}G3L-Gh$%P+O=T3y4obXJ
z;{~_4lpf4G>N$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?<HbIX;O1B#6nV;turs_u9a|l8i30s
zuK3yBuZSS?K+Y(gYaW)x!)SU|DWWSY7|V(?X`!Ykzwq(V|IlD1i#J$f?{^jD`e{ia
zc|?qZbo&4+M1YU5N3DOZMt3NDC1w$nQjywMJ-a2&0T?c72n|H!^JDA62EA>wg@}QN
zh_f*mF#3wG7-`o4705N*aP@^xHiTrf1TMEi#R~`ob7B6&DQ7I7>@;$ki9u$(CDm=D
zaP^@a=rx?_%Zt8NOQ@TNxL^C<t+(I^UX4=2vzMyOdeyO@9k+n6t*#X8bR$VzJqB@z
zwaO!`Idetxe#0kJUKLw4pcdzt*iYP*chRo*GhEl?g>y3eENkFGI%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<lr
zdD0jx^)pGvF-kkM#mTp`#(k0{s$MzGk(2oyaLI5YbHdo%LewdS(J2GLv$d>)kJrl?
zVew9G?}@1WPv6lzh#`$rNj5!VT>bo#i`@$LovoIBOGANLI}inMP{HbO2A2cx@*XZ%
z{&)uD54m1M|AL0=Zb1Vq^*&zGym<rsKtcHl<PtW?O3DCK@F&LmF&%XNC_dq^+8ngk
zksXPfO@gKr`NG{edX!eI(m|(|2>1Ovq22e(<r}vk!>=T`!T;T(?6t@wh8P&w(il{e
z3LFi1N+^mE3yrroV4c(o@V?p>brD_@wJWt-SCcrJ+6Gw1T=IhVq;oSeMGO0(uQHj6
zK%SH^$7Ag=?<XJP1>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+_w6<hduXMuqsd!^%<=7#mCM2wJ#44
z#9XkG>rL9XWc)>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_@f<!!zXX`F;8n5W*V=_aT$VGE3cc1WTk
zxiTKy+3gZNr>Ma7QAh_&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`<Y-eLJlXcg7FJ$!xzbUMy04-<m=-+N++N_ne%xyf;nvDV#%;d!Qy&X`s^fZT!rM=
zG<x=s;Qmi}q^0R%K!CKC<}1$d#_$I6a#tIf0lr0R^=m&%-upzp2OJ<zlV;0X-Abm$
zp3uJYbfc&D)&;JpG3^Ne`!>g07Ja?+iS)ES@Q$WT|A^Rt!5vjF57)Ez6z%h7P_#`t
zV2wN)@}wcYm0+G`9$F|V7Z^F=Q{ctoPk2F&fES(wXHv<uA2L7nn|q!qa5009fw;F(
z8Dc9W>`3yCUa+cV0|xh~Kyona3AoWlQ1X*sLre)Jk7|{BWkY!sdjV;%{{D)f1CesP
zPH2&ruc1z&U?aahU~DTVMVWI`U+6pxXSQhk2dVJD;JR3ED3oz>NNbx55Y%?_c<E0Q
z$oYCfvJ`;(f~eFz+6-i;B3ME5-wl_lOXw!SsM;5gf3Q+&8%D8$VhK5kcFK4sh(4Pa
zaC50L>Nde}aX0klg6GMGN{BVLupu^b0yi<fqDZ6YU)*y4JqdC&Fs^ALZFnQqkiYF+
zoCt!t;Q3z!Y-DAnY7uv7Jh-xW?#tSr^nsGVMG}5hzvZ&FHhS!`I#J@aM8438#hZB%
z9=yEtZPGJ}(-IM1^4X3t8*5}}jHV=}GZ<CJmIc-+54p*>)GHMk0aeha_@mFYcK+`s
zA<YVb(wk-Y`Md2$IMLeitK~wqDfn=6G#9&3D6YS~^&0*5=$?bqS66+Pti<w%P|J}P
zBP2M(UTB<&bDsM#(AyrLZ?6=lwh_>Wpwt}Z7Qu^IS>gRBXhS_Nb0a1s!S|iHpJJk;
zhaCJB0V^(mBGLvv&;3*$<xLv|6vjQ$Ffte<-@~xCFc%#AvMH1L1+6c;39qMMZDIDB
z=k@y?tMxJKqPTi&xc~F9T~h<O43Y1yq%yx@%<qn|p@_`TxAXOQF&Cmv<_k52%XS*K
z76ST+4UsnNF7oiOHd`gx2hK7(|2@dLM`lw+xQUy|I%d-q`C{@>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=pn<O1^gKmP4Ql`guigCzFdf(3
zaaDzo5M}~RUNMC<uxXfwG5fAVB)F~Lv+YNMX)eU5g=i(XU$-^SeR*j;MDhU__b4Aw
z51!ukUO<pe9m4auUUbh3@vE%v(N*S&TqB=P$$@L=C<wfY>v`!l_~}v8NdyZ2uv9$O
z&{5%#AlsX)R_l8%AbslM#|vnpJBRz;&<dZQQ#?EqG@H>2+yLuJUMNs4)6*9%k`&+U
z)ii%ZidSe?tOIT4yo0lDs1vQOYT13Q`NseedD{n7<yGK?*~wp~m`NxvUSDgk1L`P@
zhiLwiG<B^1R@6l-Elv2>ME|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{YsDJlQ<RJ#TZxeC7U
z`n?nNFqJ`V*aam9p%&^OfWVd+9%L#c=?v*iF(P7njZa2zvs4X(A7dXkmObXWXrYEW
zDY8OHo{sZeUV1W~(Yh5BPJ_4F*vN<_c&Ijbd#GLNLEbvM<Vbot1Kn~pic?Esv{mLn
zD`aoq>6Fj7b4E+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?E<rX*Um;VviRb5_f6afdo?2%Z$Vfht&mFP%`dyq
z6$ubCE~JWIk_tXE(--Hz(}8sNZ@blZ%?N?U-DB}M_LAB`f;DyN#kmRa$b?|k_Rd}(
zSK+Cw-qyj)tvH8uvJ|W{0Du(p3?Zt03|D%-jb)uokRJH!V=zr(w^`L^JvG|Dtic_f
zXWz_v8`=S8GqoterS`rfQh)q%E%bxf3Pbf!?_jdB=bnKjK#vHN;|6i(nBOE!E8-x#
zXrKPH0=pltQ4|x&`|(bLtVcKf1p(+mR&GRf(Zh#r;LU_R68YPBOn~u+0%Y|f1jCCu
zeM4^R8p{+N{ypAEMz_VwE*AwCVt)L+dpm;Y(Eqgy$_pXfupAngDVMa-^M&;aZ^cO*
z;sWv|9xuH*NxvfhG*1)RASRh$P(v5wL;B7#b_k}KG~m%aZ>Pi#+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<QdbojP3J2IZ5Rawu>=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#<S&^Y*E(yT
z_5IVa^Fpr}oVL(zJhthvKW#&|mkV0mdanQbN)w~yece?J-pK*X;jIVpxeA)*y$eA~
z?C_48I=tQC$t{(qsULn~$rt?%xWF`>!FVq8IqPJF&iG>PAk@~d-ok)YHg)C-6}hdA
z{PltYdTD^k&BZ`IqH=mJ-<!aWT<c93{Tq+Uz#Z}8!Z;<=^n65HH4O1o+*f;euaJ~3
zXNLk~Eo4?bS}rg$uGr`9MeAoFL-$QAhabufk;lsij9oGf4*g&km0fiXTN2rRLrm)o
z+t7lHyqC*|bGS2{xKZi&N0yqMy4yAhOIJOxxi+MQdDc1hPhfjk;IVO&bzG2dz98Qi
z2u2|iRA%}#?@0#HqWT((hm1BPt+&Ma1&oq7<5mn0)85I6M|}TCyCf8x)F*uQb|aKv
z5FvdY@o#{{V;x}pG5-|k5*ePXPT-e|WE*$zSo{$%vbMdqM+oYLAAB^^(Q!2rpBQPI
zz@57Hozj`d3_Z;^QVXbPfOXk5DKbT1M*8uuF=hLf67v)~D|Fg=5M?%nqr?Za_xpb}
zWR3QvJ2RS}^|a^BD15NQPjcF!Cko`3=W!#pwa9J@eo>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&(ZzYkU<x6uevfXf0}@QOp&=
zX)rTMY$prUHw}2_({=LfS0{iA?i<ifp47Xtumt&Cw+^!+6PJ?RTcioL=)S2%VTKWo
z7ZlKIA)~nKu~Ub@=|N3ilVdH8+&7ROlE3Lr0*i&JN%K+#9v+k;aVh|dz|0BGXUmRl
z_=!fygCy<_c&hGK*+HOpqYTohTOOe`K!mb3Xh~%kvaInEXGizDcVt#1jEtg9trj!p
z#->3oYNa&&Fc0+ZH!lnlY}x%_^ksevG~`a)4!?@OmR-jfkXJ{Ttk6JO&Kz-#*vp{P
zze$1nFvtQW><1Wv!9OI02N{e+qRlkTLAL3bTgSn_Ua&Y@`9o|RXrX<QU=2*_3cY;d
z`~0|BXzMrW`3{MB1E`=!(i!|it_JP*LwE+;z&8c<`WOc9UtB=WbecbIo99$wX{YWE
zC&Kp?%p1;~r(@=XPD{`7r+*Rq#r9}lRjrB%XJ_oLwpl+buv#JRWF6X=ZWFIfWT@OZ
z9vTprMCC|?UN3s@S*-AzsK%}xax~O)$Qemo-P`DI=tj?VJTAK}L>(6Cl<Id^+ihYa
z3<EB?@igeas}(*uQVK}Adx0mPpWl{zzawfyNM4{Jc-*VMlMaNVdWPRq+blls(S5L)
zig?DU6kvA_$1HfRqo8~q$-0a`@+a<%H`gHzesz==CNvH^r-qIB69X+2c<s3h>k)QV
zwV(J9;<w!%Qdf`$*{$1Kj4Wx3hefzN*v!zDGe@cqG@+T`e=N}He@t=RR!#-(ujG`)
zE|JZwXLYeXcmlT<cHl+T(u)4Ru8W$22vhXtmgFVbX+q?MFuJdWFXD0s_-|rN)U}g3
zF;qGdYgI(6GY*{d1(5<T5VIwKPR{plZ!~svvcwkL)H+x0qKxBYf9wD>UsJ4+|JU2Q
zY0XVZm08MC5~htUm$K26IOy(u2Nrxx$yZbec8(dC^k8!vY8AsO4XY|Sf1f={&p}|+
z@SGYCK|-;eJ<`X(Ms?r0j5){ScS1maP1ixyNY20x$!{i}A0qsDU<hT{*o#2w^u3F#
zqloO=qm<b=$@pl<@A!|usl3R<U_PIo7V;bxq2bha=#%HQ4B`&5$1JO9vGLO#qiMef
zQLl=C1&_FIKFD9r$n-$x^m{R>h6NrzPd(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<B)E@I@dY(jb2ZZOyY(V%O0+9GwB%#+=Hki+*R~MDl#UHnm;@3@tx6_3
z7O&kcNayb={9N7gwQCSxfyIPj?a<}E`Nv@@W>;woPp#6NuB>ey4+W7pg=DwZT;p~9
z<ycF)?UO_@+37{{WVL*8&bWZWb~at@G1eDjH+IOB&A%t7jv2!-;7}mV2^JWuna!?U
zi;toazo<qb2uX-MehaTb6U0;v1f}x)(<B9RBD~>6mukd-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@<TsT8mB3BxjAjRs2b>dEF8MzkOcc!vNqQKi
zw8Cc2I`Y<fy8*{tuERHl27We=9l@H{f!3o18!xbLnql{Xl7U;P8EE;)Kd!O*YDUze
z$AbBqf}-EsHPFCUw|tMxkK7kWG|dmS&^*x6=5xPbz4d`~``I!waK(PTMGjgD2Tmuf
z&@3KtdCiW#vF;T)=*|*rx!!bfW7B<WqD78vsLbCai}h(fXC_x-aCSyJl?skfhXujJ
z?m)vtqHHlN8NyhKz6Y_avSw?*lC^~<Dr$4vp>;;*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(V<d
zljxMBjYh4Fw1Oh`*vPMmHru3c&#5W4h~T7QN)RuH0w|?$N}8#_L>gGAom+1~^__K)
zB+NPL6xRfgA20jv-;C!sC=?xvqJ(qUFVi?Z5WkOl93)yxDq<*=i;2VQ)gY<K>?mgC
zYJ)(`h?e?TkB|AVN@j5i&06@?PHs@2ttj;6GNmWWn6{~hWJV*;T^moe4DC`HDIK_c
zPd!Q2e*FdcF@aK{{Ju{YZY&#3hk#>dqD)xIkHOxUxRgzIAl`3oglU&74iN5h);5(>
zKXZl=08~`3`~+8;FU;<b`&1M2n9e%A+3}X<83}Mce!3x062Ga``Rw=}YB=@RNO-@1
z!K~PvNaiPo!j~BSuwv;AkyXfvt=3dldafp<asQErPW%0S9tlRkh%e=b1=wHP&;Ojm
zB%|W=$Cm_1hLlVao|p#e`#%4~Q9IxZ`C%ck^zct2ZQB5N#2_l^byUIQfrq!#_cyNh
z2<XhN5w#Q~N~zM$Q=>M{V3}xK(zq7NRsHReZ8nt{hcc@zT7h*Q?mWQ5OuG#w=oqVr
z;lbPhrHLD(@<=6Mh#p>Er31A%y90Rb<?=8*Dtm-*@NDLv9n;tN&9}<cxUn;`yX*%U
zHnv1klB-1hV66+mGpX*>TCXO_t4*}!aX1R0?~{I)a7$@`N!%7xP2~g(sr;sJpf2l@
zErL;_kjq`&;yLoX>l6zL$y!DF#2l7c!^^2Q6Fwd$HYBK)gg-D+mxYr{XIC5<b$rf+
zWzGcyEYA}W2yz`3ZO$ksE`ycb8v269GD&K*u3#n>-}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%;<Fwsnie})!
zHIPR-9)DeJt{1)Ij;ymskwrw2$%l^rjx1Q)6Ob%*^DF#wHCP`|%Gf_0eRoJ_ezHxA
zF~vwqu$Qqt|Ch1=woGxHq>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|{6g<nP6x{3Vx)ZC?X>3)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*M<ePi{$QA*epbq46*-EU$@lp8w2KWIw8yQjd&=W_0jW`yq890dkEe2n&3#oSwfN*
zE3v`Un1xko3*CnuMu@eQqopWa#6ndyVCvC3ngh6g6Qoa5!rBMb^^Yd^4?KCuyP}x`
zD`~8St`dXsG5$Y(Hw~;|kv+7O9Z9qsRd{}v^e2I!A#vsO8T#tz@`Vr}I%7J)3-EGD
z!c--qAtBKf^nO(W;kv=lldADn_`Vm?B$Z=^mZ~qCaUp@4zxm+-ZHp2h3cr1!YtR8z
znnOJ~qpT=F$g&~n9mykaPKxr0chW2KAUHXJHXn&{wk2P@{Fx?HckEhO_+{3R9ee*c
zF;Zs&T48I!DWSmJGF+DoY=(F+eC%K?Gj-Ju-t;!VbF$sXnmx|L(nFPWI?a86MG1eB
zrD7zFuZ5jIwk4y@0HW63HAqyp%|{P{UqTUHjRZ091UU?fbP~0*#^{l(p7C8%nv64y
z5}LzSD42rNrg%y}1O1tB?yu#yarFL)x*j{)^Bpf-Rl3XjQ|m*aP)aw-!`xceyD$58
zQL)nW4mDXmTn^s{4tl?H{&L#a<Hu|}53Vh+=n0EGvh9-o1#pQWb9O8G$?&BB=tMN=
zl}`eep&_Jz;|KmBm2LB1(vF#-czLtlk`&Cx50r1~!hhrK<18-~{=O>lo=(~XDlmG1
ztgjTNW3iJP*-zrWGbTh%J);}6myCYHVpDt|o${vjbT`>5?3jhB%ZR)litV88OetFl
z?ln~JJJ-FpshyGrZ51H{_omrms59%%hEV!#9iZKVv}4P<T*riz-L#x09phry13_$s
zAf<rd?TdQ~Wh8%v2s-k~W>cJvS>IfDDN<lV8Kw3%YZHm_z+w+4gO8yj31J`>SZEIh
zR#C(83qRDXR7m7@054OUV?U~6A&Siqz3B9~_?$gFne$)h$HBOZ)B6A0F>^C=06L`W
zVU#M|;n6G+O<TF(GZ5~hK@4_L%a=#z0<E~-FLI&wQ_Wz+=FjmBuFSbUTh~>T?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&<O|!MQr~ximG2YTi0aMjvA$VJ%-zM}4*RC<xHzkv3v%7O$R1
zLeO;RZM&<_35I$2ovS^UtCE*1_YY)9BTv1EQC$wuTCZ#J&TCj@6k+tB5CIIZH2BXu
zGv{q->_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^5aWoDw<k{X_TEmyV@Iwm
z%EZV3;A_-{EwEAw{nf>gZR?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`<Xi8tk*3hzNODcFw^js`^3g?I9VlgCHQnti_M}tYm?-FoWbUuPH=oF1
zl6{Py2IW4zk0Y|b!7;_!Y?R8(8gff`aJX__cW+l-tos5*t3OOhzjdO!Sc8@^rUUo>
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+(<Gl?zbl!(hD-LFfsZT@m(iKZ`A)NB3*kvk_DuX
z@?02E(s~^971)vuDEhOZTK~_eY3y$|6#x^nrYqTJ_SUDpIfZVI(o^$8MQE_OC*3eg
z^-4%2apj(RKdte<v$gmmMt=@7aP9x$06+iStpBm{{IpMQsy(<p6*b)tg4+D-L9%C%
z*cPp0T_rLORU~KS&G^VsA;JpOCpbQ+g|9V|L!Q)@gOld^$Dv!v*@_qT=kYQMXefSp
z0aO(Tz1iJUeV{q7@SF-UUZi>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>=qyz8<KSiUifNIQ>oU?i@i-`2Il_l>L|#6ZWsmwyCD8r
znv~p!L@PH($%W4UiJ2!|!ntMj6?fSlE^gv<m4A+_Hzo{!K7<FQBH|Nc1Dbt5q9AC4
z2#jHiaXz-{vu8*P=KOPlGwQQ~TY@4GDsUo`a>UlC>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{<PbVDn`3^
zdOe^>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&aOsLyFHD<bkj)0W@|LLW+h&
z#vlKnGi%(&{6{?+?U%9^M@Vi<4M6S<NF=iidDxQ_f)AoeR`N#z(|AoLga-nxFx4lW
zvOz58L5Z32L33MryId4aGSg?~vKvpO^e78?ddc+jOKugJDz6J8_p`6=b?5)4(Zv`{
zr~hzpS*RinS5&)Z7jIc6n}hFK^PT!@ru|e*PX~F`=7^smJBn|9y5Wbd68{LSA^S_0
z-|_}U2GGv)hqaFVQQ95HmfxhdrLVjEhBn6VgixT5pl~I85|i;8;%N6sJw{8FW4ZV<
zXjA1vPc+OaIe7(++4h=wmiW0fX)=?Ko-<m^kT>uK;}-K(ND(epUUD~x3QbbcGFs^d
zLQ-9)@)0`4fe056oby6a18PORt}nAF#u0l_D=n(A;beVx4b0)m9LdQzT{1*pJ8y&T
z4rsL)?nL<yKrkcO*4E>T0=0nJ%%1OD)g7-5Tdu1FC*1seq)e~c{uonfUv<gf1sC-G
z0u=G%0r>i9h7B+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%{<yJiD4bv=92;R0<_pg|6yqbVJP)8
zkU@1pI;e&jSp}Dmb!4(X`lH4>7~d$WP0$&l_?)McE*AmVT`{&0rmukM>m~THwvTZ`
zp)Aa)k@9-*_MzKbA8{Vf((Y+aMUxQ-XDf{r=w@bH1ynjigK79&&2CdMd3cH$tqm<g
zFD^8G`w!5B${1%1Tq>gSP^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!X<MM~S2o7VMI0a2l7*zHdS7}ynRLzOtqJ4k1|}qj1Fsg|ILTWR7Z-WN
zfzFdO;zSWTTw~$mRamRwy=t}T#hLh2(kL=h0rsxOivNAfxTk5xLRsM<?n+zeH>J_n
z#J3YMTpghYIm~qeXenwLV=0O%jhxF*5@UaUI%X0d&S9{rMVy@9P(PayrE<g{Qa|3V
z)Mh^U-@2Ap-wv9vD=_rJ*~LcE|F}sbG1!rp<4nZPpC(9rY8Z?Ijfdgj<ll&tM@Y4t
z3fnt3YuiG}NJ)t}E^WmXn^AceLHDs+H?)heO)EZXbIR4`SzG?Za6V>pL25f!$9_)1
zTQo_p|F$SXO78<Wu>2%72y^8zjBpCV!He5p2e%bAyB?}r0dFFG#r_G##vC%Qu?6pb
z){zmcL`>klRwpnH1(x54_<55T$g{YH*W`xlRg#KTqyC4&uVFtY_*3|$1P<!?Ebq5i
z$)xHA#?<aDQ<lE~q-T7KLlea^UQdyt1VAZkR<qIA<;eDLyP?E0t@x`oyj{8*L8%O(
z%K4lV@LOH#t)uXSbEe^c_F*zIL-!Kolf9_SRe(@4GPS`&35-QS)h-LEhCghD9m>Mz
z#|g_Vl}1NsN2KGA<tZA#Np?+Wh^|-DjFC=_f@y@aXPFVt71J=bEAJE@Y2yAs%fY$M
z4JO7HH?VFVS-0i@#u7QtMtCuVL>Z1h;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
zW<Zr;!rGDuOg7t~+>kBUYpg`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<P9xp>
zD?HArl%vcd5%`Yfa+K9$Y~lG0#XqgEh@%6>=*pFmTj>0N#a<d0R<?72v+QAGWx*P-
ziM2hiMo0If10p6vEm$#{@^WtEMc%%S12ua}Nl<Q$G!XyidQZp*S;)i+lXr@v-4J{o
zeJwLMCdHFQor%M{@N$Kh(+={k7(spAaYsRXO54y_k!8BC>f5s`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<gG|PZr9g{jLDm&O_P3XyN`B>&uV%BDlu3cxWm3SBzI|E#^_=diRc6D(LPw%(
zse%{#qs%UEZ;D{6IiJTQeggBmFL<TO{Aj!{X7g%zFlIlY2KC{U?4)02dAIpTPb%nq
zP%@6|p`=jzciPq75viE!M?zG<9L`cT<Q?U6qb!i9c)Od`gq~-eeqYele-vWLI2(4z
zZ2K3nz?Lx7NsO`gESOH6<5+Msd4HdGIMQ(yvat~n990*i*Ew~*KPKZ>E<y3RrR&Cr
z;;vHvIO<Mc<7$3ZNmBAwhsuH1=Q6Nr2PKd!JNn8?gqes1ayO5PsTa{!{jd;2g7J#b
zmfB3GakW?u5`~htiLRA6mUp%ErvLIJ0o*pN1&UowSW@Ua2WtEibB4xI@nK5%?87kK
z9=F+4gm>!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|wCE<w`Nr`d#Zj{NyIAZ{P-6jdyGaN=xTlY$6zf
zVQV(D5sqd{^EsR77QJ=7aaDx`lmByFiehF01iu=8*9uUX7fb|ne=C>VA_9NhChQD6
z%yX!VMaR{UBx8}4G;fgr&33gYNQ<-N7?UJ4Ew~;<(s+Vy!F5H&67j=XNQV@p0`NKT
zBhu<l$#6Zk$)$yc>gnc(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<QIPqGjH>>E`U$GHmC!&<Kw6?lUC{xPa`CzQV;V7<-IZgzSZTG<1qe?o$M~@k
zjZtJ-?YA>geG#l3pv_2xAFmN5-dgpBn6nmd2)Zg&`e+|%{r6~N?|8<;b;3LWAha+R
z_`sTGFW+;24Fs3cYi-C8K5<iIUadn3B&BWY!W-B@9q&aGG@A}M!^?uCVtE%++o)0G
z(~27%i{8e(CHi#_xeMDB2ht|KBQ`W!DhGHYxv&ef2pFI*S%Y5;jLCk?U#VSq&dIw2
z7@e|zlPh21Y3XksD`mY*$wbj$Potx`m<5;9re<?-6aS&Ta2R8eX0LswV6Vrk-yHd=
z+D_f1ucQby``7-6pG<1EP{@7)=`iIX)h_pOx#14U01G8my!kMir6vU2EuD3Kov;kz
z9^R|_bf2IlDFZ{PII49L@4U&FOlNazu%|gji>tuBX|cGffZST6sfPRj_*jP%`Ibs2
z!-(x%XJC?@`4A)oGZPz~hTa6cw?SOLPL{ng_(n(mpCd`O;<J&57t%#*e^QV+`ySWM
zTCeG(KGB4T8!P>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&
zGBs<y&SvB4i*1eQ{2mi$qz+&)kBVf|>F>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~OC<dOk_{!?`$GUtJX-9ejVJbD;h3-W=~GKW
zfyKJVJyIO!X~(aad8iGedM`epxfymIR}-5rwq%pOLsc*+6F~~j3ziS!Dr(PJjUOKV
z4ZhslD_#0aMCcI5A-YhJsXKH08*bP{LAi`SL8+_TTJhu*x|1-A=pPGR2C7CEo7W~U
z!h5PxV88E9;NbzpEWPMepbMeI%a#fXVW{e(y))OT1BcXH?z+fETy>nkp+^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~iQeY<N}i|H-DB*_d0VkL-plFkMSz
z`>e8j`|wBB^B<CTGc(1UeY)t!g|xwqY%?Y>&X@piG>-GIcxTrC;`qo{iBC?EIfdZP
zaW<$gvd>tPh;WXR^s0ULE9yk7`R)^Q2=0kI4FdEZrG}F0E`^-nKoo^VZ8PEsivL5F
zns*9hPCzbJ)R<Q7N@Isiqs$>s7+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<P2^&RWpp&!#l;ERYu!@<bm#!$4c
zocFj|KI_4-7VZ*CUFN4ElHo8p$Oc6g6g{CqgzR2TE1eEjpsRuAM<n%rmDt3;*7a*F
z#<jH`;dT`rtWA-7?qeU4qZYUZTO?)IZRcg5#MPP3jmO5@2BQlt)HCD5PVwb86Onj3
zEXmm3)5j`sbfpR+A^k`OQVL{FZ5CLjx^8%W^}>|^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~<Q!F&rc~(0e4Fxj!>n<Q8uSM=o
z%I_E+H_w==(4#bfw!zbuOh%BX(Kc_HPIJcuh>?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(h<L6!ck^T1d8dgr*=xb<?jy)d|X_T9%(PI
z?E4zfa0fGd7^@Y$v)d>FW|0sQ0<C(dkNR9ND^TQhnn;$`@|$&Prberc);jW*y76-r
zF$6NBg6_|s61oaQ+mbUu8hJnL^O(!fMSjPC$@>6QU0!<j%;gc@QNU`O4ulzZD2q)s
zY!}M6nDNOULF<486(~rzJddbp*QY4XoO^1u8NV}>A(fT_mX3hEh;ALkWx1#6Ld7qT
z<~6egb-%g1E8o-LUBmak4hfP^muUpDCtHWo0Flg(qtYnuPMERCsw>|i&yE2>UNVc=
zEnp-pqN8VoZd}PBm19>FeRU1G9Zoytkv9lY_ec*I<7aEe6&Vq~>s+7aZ<AaZcy&d;
zeG8}5Z;rYWb(;U+;JVV24|FKgum^te(_F_2M-R0WZG%e_=>R~HCV%Le-V7nv_@Nr=
z25OFW2jlnO99PK@^kW(#KQES4D-%K_i59ZGJ1wc9wO+_4Q7Tdo2Gpa`4mDu;tfW?s
zl#zR+MsT2Swz1t0Z#wl=e;9e0E?|y~O%!Q}nXlR=RRMvHX?-I<e1I@=6`XUB1<{6~
zL0jHY!*S}9hEQq+!0do^0B=J+3lW17_q}#D2cN;4@(sxsT}&$-v1vhG#ImCCj9w$a
z$=&0ZwI1Is6#U|1sD2T+rPHnqw<+#U7oI4{H>U)`MnZ$M-xV{_os<#JB6_ofA<(#|
zCzo3|xbI&MY@h~qa0(ibYKxzWh6<Yfb4tDFQj?G$ewaLPD>~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<R@wjgabKTeKj<_xH_T%1J9b|xJ2M4{X5jF`N-_SATlX-x1n}?-PM_{ttI(D_
z6HbJ)$m%BH%}k`AZMu775ze2~*WRWfu!C4ib()UVYoNV8<`ueFC~vR@TFJsj74$@|
z&QiX*z}tsx9;yFi76rVGlUT0Eo8V-hTe&~}E|0_G>>hFlg4~lA9o=$Ql{YoozREgn
zw7EO&(*~%z#igA_zQ{8r)fZHQO<ldFq*|LNqQ1D|E*oaktt`YQ<ux)hyb7o2|4;y^
z$z|U)(v~^!gUJCfI7xGF_@S>v@c<gk#EKObo%PnIw~<KwJd^o^wW#JAsiK`{n7+zn
zki%vl(&X3kL&f3yVbCk+F@I0~Su9DHAw8EEnd%<Zboh!N{^b)MtL?$ah8^^2#wLTX
z?#ceM(fL=`M5pfiwLMNbpV4>$|9@8#w^@$3mmZmZ<C*?nI@hq|6wCTw^JQraGfgtM
ze^9_>+D2Oy57@*9j}pP2*~0ELTW8fe{Wi1vjJ_;ayoxiE(PyMum9m>s*D<R|7sMDT
zhh@7K>;`;NPRZg9siTn054}KR1(&!$Y??vz=VEUIBhew_V(FA4QF8>Uz<?Pxu(yS!
z4>SPFP>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)#ImqLz<H__@^G>w=-(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=<TSx)B0n#92w%%a`(PiB7>ZA3my>!YQ-tXx?&q2m@degv)EfWW3(IE%Tm(0Lt~
zOWTL~fSG&^h&MO@QsBzdA2mRUX=e2tS5amO;USN@rTCuMMdVs@eSa32j6%GViQ<?L
z24j09WNtFNI7<VECP{u=zFK+icM@WUT(=$<g<1_9iv*f`8g%1X@4tTo>=67aMmXOR
z1L1nOC7vBsqtagK(<T=s+NRQntTSh6N1Sujomi9~Ft%b00Y-V1?jnCUCZ<Ug*uOiW
zn)w#td&Aaq%tE%DLs8wAn17JT2Pl?%^li9|Qs;B7AAIzmG{#_iIXiCVMcp;GhApR~
zcCyHZp*TJYS;gUDKr}R^*x~m@;&MzcIu%K2u&CDJ`Fi$-O-@}Bv)NbJ27bAd=rV?%
zMt0tTl|?~)vos>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=7oE<XRrb6SFz>Vc=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-#<kgCV=_^d*Q?V?z7nqQfyV
zmBTztqRE2}zpYXA#a=eCusYA+2(5Z2RAwYKs@GLV@+Aa#@m10x5F9o<$>#{H+Ny?Z
zZWh^na94Uw<UUZ-Nn#4z@cL={9RWlsYMa_bVi9jL-=^Sy19PVG=ie8V%WddCoUtQi
zB|}omUosDa5)g{(r;ezbxJ2mWn#7bqi<&-~(B{w)#4@Y1!-L{N1~~9>w!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<RWxq1aWR_QgRjwl2_z<Xk54m<u5!*lw`T
z6(J@wo+SniNe$ZhFEkF><+k(mv<q5D<wdWnXk@81P$PY1TeRhM)2(V>S>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{<lS@4lKk!-1nuOFHYI)iwo0*a5ZkB035D<k&zzlPQ6u2iXAaG1IITtG4C9
zoOez;N1j>rh(oIk5g#H<#JDUzQncL2zY9rltZA|hO}8iDe>c&kR<uF{?-Ny=+Kt^<
z(Y1OG6p`~Y#-ii#P%uz~91w~{kk02bRNXl!vKvVIZgvt)aY@7fh<tOH4oyX;Su5Rz
zJ-9?3G86R}-4Rb<)O~;+;1HpG>^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?<c*r97KpaB$TZ3TJ^l*oW&+EZm4GEGCTF38`bgP{6`gi_K2!ob
zIFoX-BS&?Q%C2@SNwBm2Xz=dS>3-m><P^2e3aAupUx~r4hyDY{7l#0N$Ve>}q740u
z8G;k~^g<WwZImrvZn)OW%M6SQdPTY%)>a{Trm=(xSvRwDJq#RgqkJnb<x>D09v}R@
zCEy#l8FP7Y5T*L1%1tOx1fqe844p!m?iX_V$4jU#9q~FQ!IZb<Z%Jdvu<LM>$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!Ete<A(Xm)H5p_35Qs##SR%@POE=k9`pINN_ZK3Gyl_L9P
z9n%1al;;Zdsj1kSgVH#+>aW#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}|L<sq!uKneMRh)r_%&AaFXOk*`_G
zO&jRGk#(YdD{?k}s>E*yQOY_=1fezY7uOt4`MW2_q^8|`<mjs3TecFJ%ao)O1^u$F
zl)@!;aX&cQT9J076?L66*p4Z4=C2$Oo}_)%eX6(>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~%8<CEc{GZ;IsvOcpIkam?cr9DCpy=m)P(0v`7uR1P8KpO*iug)K4m
zEGlJyK*g~OO2i22WEqYpSgT7)ExiaBLUx5%Zniy`hH&ZwSX7Kc@qVxCaWFn@!+Jbh
z3BUmx`mwdeu}&P{+-SWUz}ZC*pW)wvI%00~KOOK0($}2oktMK5S8VwbMzGcet*()T
zwRcd_Bg#*$0f@Ng<1(}6TD>cfRNw;AKxDX#QAtLh=nnY}v_S;!DW)h4F2sNU6TV!x
zw<M2nDdFm)^(Hoy1Hn*@J4s~$4DM}3HBuJ_ZH~mLe&QR4@01RrKb+9ZTz*Hw8y{>n
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*Xn<L+_>kl
z9$gt(Tgd#g2rm^ffyVc^h)=N@<!n#xvi-0}n#chE#o&cC*uq)sxYeyvo^r+HiC%^g
z9~+c1Y-6Ii1{4u(H3PFOK~7+P!`P7WqN_=JgZFBul75cx2ao1a00`MWVgtX)A&yoS
z)(y=Cq}q6erO!UHVcv+REQJRxc3U$pW!80tFp*RNzrckJwxXxn2?OjI9L`CMmZrN+
zd6s&7tM8AQUqsXTU+IOS0XqsXmdLR^4k+1Zah5wHpb`I^7~O2{+mgabXPP;^SJg$5
zPU<Hgd*S(7e~>j}R8hW?3SV*>oU>sR{Z=oEUR6n_vWn7~a+mwmmWNe{Jps6t%M!Z8
zw(aWIp9xgxFMf?wELX5M3|;#<pj$K(r5&=Qjvp_o@!JK~-c~zOOR8Nq?~Y;v;o+Cv
zj^0c>WHN7G#HAw5zR0l8byXg1cid2ph&=eY*XAK8@N@N27ZaH>1t9uLJ=7m^Y?ujh
z20r4j-TAXLp1M6Vz@etxz<GUB4#7pY#ze(qMwcQoo_=&joAB$?J_^XqQM}NaFVV~D
zWt)uV+vxO;l0a82`y_;@Nbx<WN2aX8v{s9j2+6KmY{}Fa3BCrjiLHO(?`>xF<Y7iF
zgT!nlp2klBP-&vt)R!I0o>F(EuU4YePePj8qC+L<JH^zc0Q7`aiUZ~gF9Bd~Z~>=b
zgu}O3h1AvYrA7scunwqZm+5??k-<(BeYYtDUMITABKx7?a(l2NllWY}X(>AG_K+Y5
zM5>Qgf;M45vISM<a0o+A-`8xVU!W?11Y?jgGt&P_k5HeQepK?(KqBf2$Q1CSr2Y!3
zVE?swYFL{lQMz^BLog~4Tx<uj(9^E0x*XGWVcxNq)?U)&{Q=+gAxvE38-dSy__$o$
z2Q;UJ#I&Da-WLZV6+~qtLT#)Yr7+1-M=23-o7kMlziTl1DtxVq>zFf;5%^GNd!<xz
z*79Mp#NwC*={ea#w_-n(0s|A+F#-?M7t4J3C(qr?a>gO<14rVL=_r-7)far!7mTcN
zeuCzZE{Ueypg+i`Wy)z3glhx>vm!2Hb0Ul0m^y|i9B4(SADqeSUgYZMw1Zgv-v`8y
zDWtp)!LK)ggNax4O*OK8!vhCfAv}<je_bubdCgoJG>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^<qu710Vs9JF5@Z-cmo0VD(XXj-2yzPhh1w
zVc99q#;UsJfQ~4B&yaiLEM|I}(_E(vq?|aA=zf=>(I#Kj0ivW?A&nIv_SuL)5kd2p
z4oZT3e5(q<Mt3SSwFWMLq$@#1rwTSMaow`MHExq<u4yCWe0$QywAZdgtRMa>D6LVq
z)u})k;;_?G0tdggE<fe-kL>JGXJIwSq|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!01bGNIZ<I^j0ROP7~dB%98+~6zcw=&0I<bQHZl$X&anNw
z(L%zKm;xx)c^e(VpT$tU=hsoIJ&@ET0HH`w2JGgmTt(F&NF=~laH!>8O(?BEJ8|CV
z2NP)@i|wcMnPJ5<d9@bX{@e-MpP$=i2&Mq#3CNKbJdB+MPXHgl|NW1WeEA?Uk}9%d
z#Z&H&JmC%=)?GVG>CN?(?`|**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??4UbHm<DyEB;0nxD#OB2XHNo
zpaI5IfCAL9o;}U%)w2A^$dUfDY|T6H(6W+r^xkCnBi-$4_`vTg@s<)vJVQn9sR_m{
z5Y&Pwb3avHkUZJ3sSp-LwEYXR93&D2V9l~C2xY@<ZMhwb(oF=Q*GSQt@+4~X4R4;(
zmCW8Ruk9bTFc#|bDNA!Z<Il8}a7ZIkjbJdwW6C%dhDUt<FScoqNLIE09+VGX#4t>j
zy9&PHje+i5S*A*uy~E$TG@m@U<wBwdnbD(&vG!3^Kn++MRSB!PP{`VlU`n@#BS-c)
zOKtZ8<4@R;{5XPNP$eb)vU?KJWk*s?!yp{uHdMdPfSOCC_2}ZiHii&6;p7*K+|pI!
zK~}~k7e@_}(eShg%28U5jUe09v82{9WUg2D%@%MVQqe!$?{a-NH4WgFRrNv$tIf0>
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#g8a0<K4F7~x{e-fE)?#0FiaGTK$9@1n<t?)>VVWEV_
z<iu<CHth{#DvVC)rS{i6bV*(891_`|KSmYUEHf$=8Did^wyR&)w(;CaTCA<@nM9|;
z$&O9pPDB)^jbhXVd%%Nsjz{1geIRO%)J(67AOHirQA^muf&EK`vS2zmI;uE9=~o9r
zEA=!&iOwQvUN~JGtGwo>E!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|LGJK<rDfH~VU+^)_!Qe;)Z<-$jW693|Vr=ZZgL
zB?=JVCC&}<qJW2SJSFN4&J(Wu3Q!S)*Pzd8E~v~Rht>3>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*uDE<J1fyu3xK}lSh{@1Puk?2ahg5$W{nM
zbOXus5x0L4Fvae)yFph2nOCPY=H?A1t11LwD&c=9R70?<-1Yr}WiHH#!`%rabq<k#
zyVEUyjS^XGrV2MpV&lpQ<^x=M7hnzwKwW6|^WKJk1lJc4X6X?ZIBY@oW7bhjPy{WX
zPg%S~ywa(<v@S2+o9jY^$Ki`$<*qxV-2%At*(QuWo2T~}f_vYP?44SGd^YsNu`s<5
zV67Uc?mCa8p@nU;?o`6erH3toO3`+yfPL|4@_-EVNcJg!6hvk@==*&jsu6$y0O7^m
zS)6_Uzv}iw;2lcz1D%8(P1vrL>En6?9^?DX(Wrmx8!MmOE+!(%!_8IE5AY;;*on!q
zZvUtJuBmPkr4Hs3%fENWq`Q8@VD|c}5v+a8UU^MX)X-v70&-^){tX7=%aC3!LH3AN
zX5xjuK>7K=<!959y?Nq}u-4}d0phLg4&%J*q9+AlVO*Jq^Wq056FPm~X+WBziUoGT
z#0G%aI;{-<K`I(`);c{y%YE(FWV4F{f_jiVF9u7{YX2rQ1w^mec|b(adC5gq5<<#4
zLkT|J)b!v!ONdUH*++B888{}b5Gs0g_FVE2UFj1k3@(!-{xSI=3Q}}%eCK+h9QomF
z+Ue6rrKhz5=l(cN-DZS3mLfyRG$xmzr^Fe0Nv<(^^|w4@bDU%nxP~APLGWm1;GqP1
zw}1%aa&aEKc1+4uW9{bEm<_28G*inOkot^18foTG%K%48HndULK?=AQF4x>3y^<IL
z4$6uQ4U}_!eKBunjT++1eS#!LwtpUVW628`ZO5-K*zU&Moilm9GxZ2Mg|6s@&~7lw
zyi2*a>trCxL5e(%%=iXR+xnM(DGVaqd<OFhIsP`9;x8ZIUw7M1RTFmcYAAnMdAX9V
zyK`QSejJ2iP&l?Xlj=4v4+RY!6hk_T5$J?ZtcSBZwS)+8RW^8_E|W_4>L%-Kp6wT;
z<Z&X)C8BwP*uGKcFo1;&ps0y#*%TfQ6*G`W9qj$cE+?29z0*QA@&zt%rHZ;s_&u~y
zbxkA}4tF7UT`9#UpfFbV>yteYqEBDoBYi44YJQs1JRS^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$<w-TUHRCHW;6v*R7R+Fn<AC^XVn?|j
zIjF0=$PCn0@Jv?!JYA1RLpvjHh^)4<0HR9Q(IxKr$+|UJLoMT2@7Z$?<rD-A%-9RT
zm2r}`uCS$%)@mYhe3~=({@l&knpzeJZd?HVo9~MId<i^*++*V|wGz8azp~7)ye5cF
zA3doBhS(5pyJ*!Rkdmu8PLo;Xkhiw+@|+sWqRv;aa4W~hbubqQAIH(nBc5f{Q7G4g
z5ktDCAHbK9(7`4*0`r0bDDVq!3I}BJM9;2ovlp7dXGYo!=To&60rtJs_5kLKEP{)J
z{Ou&`Ht?>v2;<wx8&=8&4XTheeThNF<zyb=Os}nfRf)4PiwTSTc}j>Z7#uTYp^Nz0
zrQcthph{b~#(wt)u`|H!4$wz<u<eh;D6>ofW_WJAO~9q~Xsh0?g-NqcrSi_gszsP2
zfI(S2UQkfWF4OQDlWE)|>hg1}!t&z?Jk0GL1wo$<9Sj<!oQQ)metxABlokvP)8~K>
zsCaHzQo_781=dXEJjoY)Q`6Sh$b$kY{?CVwlVHqBc@fsU<kf#!MM9cTx|v}*F!;^!
z)W4kJBVAP5cHyP@)VlL{1OO^uS}t+P{L8Ji+lrESGp{I5jfVGyhAy4>tIK{)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}A<s=|N~%sCcS@+0yy7^(5XZq~UL$bfrziHiJ>J9nEPrNvlGd7CFU4Or0H
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^DlHIRngWBkeJ8Vd<O^b6<UG7)?>egQvxt@M*^f_Et?KfHW@5bDPob)!V;jpVJM6
zRvpgT_}4LfJ2VrMc(p%!NX&)5;E=BinYS1hAha^Ikz<NvuheR!+`yd5CeFU9opO^1
zH^ms42Q(Uku?Dm6X^K+2aGXN`B#dJ9m?f4eh(N?qpX+Q{!xw9Dy_ts(ac7$`;f3$}
zH`t`Wn@wNwqD|`{ebz@8+aoH_*pEB_N`OGFg9?Q3xd5DhIWmEN%^^RKdzRUWpF4a9
zwmTAZOR=4nK(#I3(okIGI5gh1GV~Mq3LN63E`hg|d5WngsAlQ+@2=YG``HUHCd}gT
z%;4g#<#e9BuP<59aARW$<4wt6?L#sJI%3<bd$QKUgT`Gf;9@;H^9=-wd0k_b+w4&P
zn<QrHB-%hVGi7Q<{6mU+IzwPcn*wk(m1)2x4R3wz&+c)TTr<TnB&%V^8xpEU<VFw#
zSiOd#zfNaTPm7l2PIlxme1MHaUfy7r%=-+6iUq@H1!yq@pk}DHr=e|vscwo7cGP@c
zFJp0sHioO5#N~fzcs#@^$yb{_g^ZsyMi+Ac1Y;Uxa@w~O>ql0c=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<HL4aTBsh_Du`y!4!S
z*3g|Sv<guCEUx(FFN@W`DG8r0_KLl&Mv~LB%G@oBUtr~MfZoNRM!*1A>{<a(tQCW;
z-IXZ*6;WrN-qTBi1l}2+)ICDbw0kMir_GtZWg=IQ1C$5O=T%5M-FNbVZ9*;9s9MOM
zr}$_PbmC@47KM271D3^G8nuT+a~W|)AGIvmxlm($d|74Nko`aXKx#uS2s)d9sFSBd
zgcTv%w6w|2;J5%SKrVxvx1g|dGq#t2CN%gq)$PrVGJrX>b-P49K`>3C9M|(3fRV#C
zH0r6(yY`gjooZdtcW?Z}ffIIyGrK-p0BnI1Smopd+Wr<ZwSySIq>q)oWo29Ffg2$p
ziRCct(OQ59;B@;o;z7~RU7x5(U8o8zX(3`g;=uLdbBzaxOhCjuO+14-6hD9draoG$
zz>DM~7@<Dww4uT7vnWU^4!tYEqlJpqmZk-$MpN*9D12bCD%1Y$peBd)q@BxBAXyfJ
z#kE~~snE-0bqo^C^EM#bhC)UFI~4d((6fz5`Ao=BtZ-a5a{s9-i_E*bl5kI%6FZ36
zyH+<JDGM5_a7XF}z_~NjnPzN@%opq5(WI{HxLderhA;{9k9tX@Zx%8X6NXCR3vnl3
zy*D(G43!;)$|pUDUE-cJ>!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<)+<vzpC^1dQ}CI<JK*g;;3HJRX_1WAbmnS{7&A(_ic?OLxDpfUf@20w9@V
zM<yjWPdv17pVdM$`EAm2a)C=RT;urgUZq|sch8pWvE*pa0rA<oAND?!PlnkCuOVjz
zK4KX2*#I_U4qFAQ9zzO3l&~iF8uCVpxFF$A`}Ee2MiJ9-=iAuyaMQEY2NZA<=h?`U
zU)6_hWN!(U1^nk3u&!8=-L-xDp<%lI3O=X#<Bl?e&V&*u;K5Y6En1<};$T?d00|)n
zpUWt^%h>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<n^B2SWxjJiP~)RU`o_9jIxUxMsuR_q(nN3fDbYlQKu
z@;I3t$Q@$^vC~#*EX|KET1*fm<;A83q_tZs<*JZnY}yCk8WTwI=ia3ggl~f4<d=51
z@OG7kRbx1X27<qy1hkB0X9i$0m~omcW$B2s+{?>&_(^7uwF-GO-LR$O@XpDyFUNY1
z6?`@Xl7`N4aK6mndZ1`g#p?VwMMfy1zTrt*j3&s4YRS)Z(Y>Ka!aTo-r9O2MiSkyW
z!bVE6i3tZy^}rS<iBu_+_$=#MXo#{dQG2pIOuRj?8~n6MB#3&%rZ2M|aSw74&#>PN
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`{`<vqbEyYP3OtARx(}
zQ<I@1f{x@`bpcl5gk27<Os#uKzG&cWhe7vhA?Fv7^lp!lOwplR=R4okY$!@PzQWg6
zf{eXrdv!pjC81wRDC@Io{d!NRj)4N<42+(I>4lP`kIQ3mf9_+fl%&BBXB|4uybus`
zPkiZ`wWEMNVsE_5Q)HME#MTWB%wEdV&J(D#_?RK)<Qd84k8;u(SL>O+CgpD*MK~F5
zQPN9}j;|D*fh1U~;&u&w?NSnf&CDC&Xq`FjP)?E?dB&6w>KKvY^WJaXDO{;eAajl1
z#*$5H<b{{yhV!*-S!GA&O8gPA!%4=0EtC0<h;!FN<x(g0*pBdCCaQ#p@`fX=YmWS*
z7N(wbDFiD8b@rq)4cUAd%+A{sDo2TKB+wBMCfjVs#ktTm&pDBkkueB2KS(Xm90w2>
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=@s<Ly
zVBiVbCkqSW{yN)*n-BvkTTr`x=Qa6W#7KkXK=`tuQZezS^zm|2RmI#v0zs#8sM4yt
z^exQ03fzI_3##Fnaf;l-6#0VbSC7_eFR{8)786WlBOu2lGeNu`9}Ko@eaP~ZnKX6m
z4EXm!N)4y`VrJ=M0{KCW&if6M0)cYCM-v9aU-)6vGN+{RWPV?C^i|ee6HJl%m;<WZ
zK%9AtRq8(KVJ{<`xr>mb?lJafoidCN>XK;g0MK{v4>?JRB%z>0N!e>alZj1zh96fg
zFfFf@bFF8GfhRP6{52qibnixgC5_R?5R4%4GI&Aevq{WouhcDW!#h9o${$oIP5Gjj
zdk`PnA%=&~6p0ZD60s~@abhkAi8*|FC+^<V5?RXx@Vh4J<63eSBA@XQ$@%67|F)k6
ziYi;7qRYR;u6qmQ*2a`IJ$?gq6gLjNZ^RtO4d*3u5`-^CJ_)=Y7(9t$<D&R>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!<Y7J3n)}ad>!_Sa|!kAWN>pFV4tV(
z;A8ToNpzF`;GMrcWd2hIGGJm%GNU+t40k0853nwEjq<XicP^aOw;ee&IW-H=W*6&(
zc7pI)`lOxSlb_2t3;xatjMbTg-lw;j4Kp;jK=GAbLo+BN=2XUR_!A2i(ROot1Y1*s
zf&>mf`2YQZ<~RnO-eaYlZ#dS@SRoO{j~#x;!hlh~d!nw#S<;sD=$D!X2?qG_Kk8{>
z%CHh{M|D`eo}Rbc-p@I<lw1vEWjK`$kd6&LBSsepES@u!4p*H9)%*pWla1#j;xPIO
z+t8i>4dnhTuy0RHSm6Y&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$Lqnl<aZ9b
z#OAcn1fztydYmvBXW$GhXpy1@{Nki!T)GJ%4|_sIBzJA$E@QCmq>K7#N;R<jU`kqE
z3=<HEN3HoCjkZMtk)7`Xpd0rjTci&JxROBgwW+a3<T(UA0GGU=lsL`QFRaO@G2|jk
z$&mwvyBt#uYzSVXsE)S8(rK<3H@Z9QXVSm)3BLXcehRheX4h%)vZ1zaFAZ6yfWn^#
zvr$BX`9MVl{&Cx+QdjQ&cOwD0dqsiRy})!U)%Y(X;3<Rvs~i%cB*l*rLWCBtD#S$u
zkx3p%o6lN#l`f`|s1G`1ynq&0NjauwObTgg;P)m-2)m?RftYJX5%;OA3_o#<uAb4q
z<<7jEK#KH2RuX}8a>XG_RV)Q1aA<o64}Y=B6jVky6Q4TWGQ=Hd0J$7NB7dzB0e!f+
zpnM?@sZAGn_c5zpP-g-D2L~hMb2M*r#2lXjEwKTe+d>481(|(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?<v<b3)LJw!_Z-UYbM8Vm
zIu=~irY2Wd27B~BAEb3KKL9#F#lQW4Mm^3qcRNIm>F_^%$?7lbyjMNLyp-f}v9D4!
zhl0X=PBG-3Ko{1?+qGd-PJz^22Z0r_?r*&L4%X4fyNaF2k-zrdfG;pv%Nua<vbvBj
z+n?q*EDdWX@Gu#PI)JAFin2icR*d@H2du)f&P4|<5KS`D>pV!4DK!!n8`T1+@@>z~
z;^30E=_R|*De*1`wYi#$VS{9wu<g^{2^<VDFJ)1E65&Iyhn`TVNQ~ier{YA(c+`2T
z(u$PjR-0l~&hd*2;Rz_(#43$1NMK!sl|YCEMmhDL19TyR`h<Wa1G%yKfX;^7M>mv<
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=9sj1<w-c7e*B2s*6IDp`64RHC0B#*QJ%un^+ADR!lt_TOSGx21y0VdF~|zV1w=D
zY}wuiy3j(i<47Mo?5gpZQjE0PI*(pGeO(~lZ3R_LRb56g>peUY;RD2vZk^JSl(1OC
zI)bt~NPz7PIeacOl6FWqqcq18r;KO<k$0>4J0MJ%>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;^2KTC<q9@j|f4b+?4D>e;))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!ISm<A#(<3j?jh
zi>bnY^~(XDa-zu3T|7bHs&~Bsg=5MGVb~SA2DtzzY|`OgFYk=fHKmK;u8{$Cm)X|`
z2?4>_?@av391dLHsay^@AENA!#!5iVb*jmFiEbT~;fcE1+D*Q(QBxF@;<b?ZDrLMl
zsw1X7L@SX@bOhjz65xQN&=I?95Jiv+TD!sj_NP|ra6eDojL&o$($-8!x7i*>1vET>
zQh<I6xsf_gq<c+*G5B=;?~j}kk7o6z@y;0%g|x_B2;c&McC^u)E4iB0xmkrhf>Gn?
z>ZIyaB_uP`B~xL8lZW(0Qg=WjUNEY*<CT0t6d1ziIc{?a80SW`%>)?{HTS3i7Nns_
z)1eB4R>~F^SBFAk&zZj)XF(K1OPDbAkgKl|Wq6w;1mopF<Z+Giu3|w>6%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<qXM;gw{ceA9K43|Ojnu{O%@E)LF%kM;Q*9>
z_rWp3o+t)}J!}sNm2Oz6<AC*o`Mq{86FMpe?H?@58(s`2%tpJ}lqnKRERz3Cy}T>0
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<MF1
z-KD^gLbQ>-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<T0Q6$u|qd1NyI)~J)F5{46%
z9<&Q)0MyFt60HCLQf5in-do=q)KrV!fXNkLt|53*gxMG%s-|R@c#iWERY$q#&k>$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<V}}nw
z-DDWK%Syb?2R*^&?l5OoN|TBVS+vv6*`ctw3a(@o_|eAU4^zt2$GtUQaV`tMWrd;U
z7`Ex3wF&cic9M1LITB{l);zP&Ur+$&0(6dIuK59b=N-nQ&1zp{r$mz6va;Jcf}B%9
ze1+uJGaqkZRyQ~gf%3ns9~}0;Se%C&ds$C8(^>!$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;pdi0wL<y5zY
z`^<x)K51?4zdHY2fECQTEPyF#jC+8%$jTB|`mj)YW{uE?i$E|+VBHdTE-JGUITh#T
zbFApgnI`Z6DP@y@OP(RY%&1^L5vS|1@SrnVC-kFt7!oSKV&NtOGsSado6AglJ&za2
zP)i|Y2$j(hQ3txwzH7KW5cmbkxJpPQXAO==32*`IwWuS}0Xj9gYIng$mJkj0=g>CR
ztjE&^svP&nY=ERE_eck*)kLDGtRdAw{Ziozbi#|;N;txFRQ{Q`r8{7eSNrGH(=xfN
zrgwCbZf;O0Bf76%-}T-5s+kQI&!Gi|()o?>i<v!`M{?l~5!awf+rDd|ko*s6mG#Vh
z{v2dGfX_O=3HAUytkdZ6x<)d$0-hu}MMH2YhX*N)1yJ88NF_2hm#g8c)P(8UOj2MA
z%LE4T2G>kF%d_KS=W+wzc@rF?r80v4+VM&0B0@wus%gfBA+=EQJ1?W33+!0{7%LwU
z<u+x|m`D3?P{NBa3RN0ATd|ZzNoOurN^RZ)b2j?$X(K)mK=g6ZW|y<K#42s=WH<qq
zZ8p--*H_rSFg~{c=u}$GK(gwD9Tpa|CJRcs44%9?Lfk$|3cFj{33;cO3>>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^<gN&X|e@TY+L=a~A9i2k>5O!QFDA0*;tYots<@mso=enlmEIq<ak*;$gDy2Fm
z+ZNNBm8;1R`^U^QxMO=nd1&?BoGt#|p5Z@`3M%0!y&cO4NE9!HR?`OWu1*}6@KxpM
zgZFuRbRp?D_iz*(vnoV~25)1ksSooichkU=u-*mYX|1y*U|zz{B(|Oq2K8|1tw9b;
zR$?u8BsFwOBHq;P@Fczv4!q5XGC$A(M*I|D+Qb>0j>??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#aY<nG<
z2?9NTHls^0t$0o~cmM{o<H(Aiaewa=5g#ltIj)e#9ajWoBzA388z^{PK8e@p{CetD
z5K8&xbeQ~hvcHp-6_r?lT{?&?_;llPxI5UG`;d(n&1GK;`k)^uN!yE&RfR_2_O4a&
zJ~ukUit02v?=pJ&!VREup+cL6g}smf-e_)iso*;kxGuMy7d}@e7~HIp<7uU!%4rB;
zstnpH05wF=cXd57USy>TR~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_o<k>Z#I2DM@06mGS9lyuWS9z$O
z-DN4iSDFW}8OSjsawE>k5V9i<hvhSEqg<I<o~kLRU3sNAJp9DU2c0VhlYEFN!}&}r
zN8B=MP6P1NZhJG+R_@r^O0blwMDUX5vxgb8P^CgqwX>!$<BgFqVi3Na>)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^0rerfjYsu<KL8hZtFis5gLk#!79VUYU?BENgj@(r?&SnPQv5Z0AD<E*|F`S
z(N0$c9xHD%@{wSCZ?fr}S@~Y*5@ZQ!U^-}njv{eyl~-z7Ek8WDy@atIo1jP(MDl*N
zoV<obt`7H&@s-3Q1VexT-Q8j@#wphtlV4179yaFI>D_YwGXdW3p_Gt;00)k#3OY!i
z_^nky<L^bU+brb2=E;%c*};)3MMA4@ha$rCpdOP&wO6_gl71!(j=>s1-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><R3bqQ}P4h73yPQ1t^RE<mmjT!?xaH0`8^qr1bO~5D|
z98cCREkzves6;Lqsqq~e6>%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<PxwKW((EM;=~U7OksIP{~WgCf#ChmT||&L={?oZIiIZPYs4
z2Ohz6hm|(7VMfRlM|h1aQfjwhO?3m#p0w0ZTo6xe&(_Lfy4Q~o$i!B0Qo|THlnPz{
z`&=vEQ+XE(!uYxfB$P{vuKl*{-xku?!iP4#j^%uxEjQ8boi6+Nk!(#)vMwJ;+~Kg*
z8YIC&Kl_GAY<UG3{D3E+Syl#5n3CgxHzoo-NKKyY4O9RFAzbJwZ4zwjs0(a{r!Ohq
zg}~}Zof9Le$(P%=;HGHSk3YSF0Q%nJBeTt|p~za|`)fv@8?R$#D6(HGI!Co`^41z>
zE=cJ`h<u2ET4T(o^KM!rX@r~L^hJ4xx?NN?YG%Y_ZLMMb&ws+bAXEQa140jF?o10k
z5~q%O^)oSaI(+X9g8*72P919=bC0+72ys<$ZjjEKog6GD$o4bUS%L|YNV7Ls8(US3
zM<Gy*jN$LOpZH&>oZ-S3UhvVfH3l8oOD)1aV~@7eYctvlH@ufJ@}74;u};?W5OKq5
z>L_l6wgW%Asc<P|H@!hRK2g+!b>r`)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<H+sL!-U%Gx;1xS>?`yFCpS~;i?<ofIiG1`nl^r#F$DU#l&yx#F8R!fp$B7G_
z=l3lA9sp1@!VyT`B*gK1zym;-abUd*)i=G!T80bxl%<nm(!pQ~5h*d?Q;dz3{f-{e
zc?B%<_Wox5{lwZ=<k8|iL|$#l+M(k*m=F?+GfxRN_Y1lvc%P;~LKu<BZ(vo1?XUOI
zd&FJZSu|M>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)DdaJ<?`U}wmXY(oo1M%}oeCW!`*gN0*X+Vd>Sh2vG`|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{sH<Dw2Pd~Rb6QA<{t2tG!>S=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=4Yl8hQ<JK?F*!JVtbO4@*l7s(kdU}^|au4c`clu)@U^jo;O=L4M
zJ)gRa6EU$Z4yX&UnrEZr7vQcYf)cN*mZSLi6qY>g5t>yX6ksPO6v?%!?g#8$a5<Fy
zO2^t-6`&oF`3r3&UH^t#H@a9;x3#{+y8MDtg>y1q8kK{zM#rAZG^_-{H}nziN;56l
zO$XI32fT`cW<!=zHRd^@q7dT_M|Gl3#Uy+`?{L?q<O!LSVxt;ysB@bjAv=H$6ikhT
z<7i#2`}>DY8vo?Vpw1uX#-{u!>y|O*{yoeMRNKHvnyd&zhW+PiV=}qs8q?!#Onu|0
zDkWa}+ej}n<>+915Wg3z;;m)0W`5LP)iI@J<<wQ(t!i-FBTf!j_xwXvp8?sBr1JUF
znE2oK9sG5Q0<t!dd3i!O*Pdrhr`UcvZ)Kpr@-6IxX>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+$
zZcx<qYVw|FC+J@bsqHsdx$k5@jx6?FL?=|(%r~Mv-t#g0l0@|V*%<k2L?$2r4;$;X
z-DzEt2Ma=RM}{6#Rsbj(&aqDuJn@ERBj15<1hw<P2WaoWV4%$)#LG%==1W5UMm9HJ
zUZk%9RUkkGB)90wj?WylGgYHZRN0O8`<tj_a>oq^eqv>t3<Xd>Z>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(ioreb0Yi0xS8<KLzJ%038IN_9N
zECjd?Mk-3=HwKgM(@GS!9D9Q@?A&2re)sMWfo{7ZX?u=HWp?C=Oy-xX8~{+sL2DX$
zr)9;m7Hk)ghkf$#sc*GT@X~0u12NqT%M6Cj1SDz|j@kV6D=;ZKDGOBa_<oMO8&=bx
z1jMR`T%&X%m<*zh`l7Xt*}nI{SIOm#2r%-29S1Pc<+{(Af|~Go>S?61?g@OAic0Pt
zgw}y?9vj4LKJY=>+JH$n988n_=sZBu8E@^c*5|woumD=~@Hi%Mkx1)dvlVbjdK?I5
z3{u~Z1O=kuIkm<D1f4ryejT}>g4q<mt`@H89#c>4<PM2MM^P*6C}h|8?7;UH(N}SF
zhz`au>Rb&FD`=mpmyD?nl{q$7`9Wae1aO|QsX=*oLxwRUH!H@<Czt(3$dbbCz#-Yt
z`sum`5%BzKOYm2zbE6F$|H3iniKMg8_}4!_EB2!ACbwISYUj|?rFfrlxS;bwZlGg~
ze2;wwLJuO9XrNuYNI{zh&x9l!nFneRC<To(q;KWv0MnFubr>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<M13ZtI#1tFvGLxO~bxP~QdG8M%SKneiE`pb?t~
z`4O-6J=$+Kea>{%mM|q%Eoko|NTvXS9RguJuYB^qmWSk4$i^~0oY$|qnn8pR=@TN`
zEg2Ol9(O9woz8Qtji#ne94NSUuJ<s`?k&?L7Nc*LAeHBz!qa5FjG$TI_#RGtRG;^P
zRCs@!a7i>hx*WXKl&9li1q3M-FM+9EJBVgTHFOQXsK$Et)L@axQ4kYy^9yCGU1yxK
z&nVH#{sZ7PD#5#Z!KnP=J=e&@H&q|8<`bh2y2bB?Ob`q8patV(<cf{{8FT@+mjfBj
zFinQDwuHocghitHf2Ne`@6n1S>6%N8@a(eXEsQgokv-&rePI)TX6(|HZw)eKifY&t
z&z<_Y=td_+R7PPjGFLrS#8e54Ki;GTNSF@i)|L%fzyaZBnR*RY<Zve5^t}M}gia8Z
zr~q@BQ1?8Fr@cBO26%|phfo+lbRjdoj$88nvwt0XuLVB;)3DCTlw>K400{KF@A0xd
zmfpNWY9(PHrTcL24n^@G5rV&dfX;^7-e^-ppF0NLoqY8ebU>jwndad8>eE_Au7;^n
zh&ZR{9LVdZi~Z_;j4mi>1VXy++x}ap+O{pRn;vbR<X7>F6YRT^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@<P6k$>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<bg+NJA($?zOo0Nd-|y{{(mgqz6r;rdL=AMP6-H_
zy9CTf+fRrMo&o<5QNxWY*BY#YwH+L5aOz-Q<slmpclWjhu1&lH8q&<o-8=XIq2Sqa
z7Dl%?>;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{<vW?*}W=|KLIcZ6B5wBuM@&5=tgf%zT(u!UT>;lWDohjT8y!)!E<Ouepx5R
z)|uElb&SVm_wx*nN%g!ICU|(9WO=&BXN*=M!E^o>4tp}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<C>%7Rp04JK{<)ul1@D%7+_<{4!^C6rdRLo%WptD}P4h4V_
zOCW}oN13Q0ysfTf>;#tJ++Na)|0!&nL9!)BuA~o<q`@OYpX7kNvJS=<D{iO|UMOR*
zy!;@&5Nlwjz-tWX_vHV;qbj%J7Q#dBpTvZb4#X}sOb8_a5Lm}6VD<d)Jya~q8@(pU
z@v~X%5lpF_EG=}qSdpoQuDx@ViVg(4OXuGQ`tj)RMCqbVi<AP10ulipyk~&z9ch6y
z83YiaPDVnbM*$O^@%QLdA<%~Ijt-=XDR6Pt%f*8f9j1{c3F~SJM$q=_XnY2mNzhuu
ze=GQzJ)YsKYvdG9+%8kfW8M9&6UG$OAZ%>gUZndk@zQFYsCamfS8}>W2JR30znmrE
zLz;lhY0V}T1fQ^<PuUK>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#<eXGFYyyue^>NuQ1T-mO^ihTE
zUddT`5>?qXFWj-Fv_xet(<4+Eas7a3<t^sQ<s4Lzu*@LRGqvln_TUJ~Fp<iMpP$M=
z)-BXhuycUQ8o6$ElN}gIp++y(?3;=TX_3bMRI|xV3^3f&H(DqBqe+qsFUUvk{CSJj
zw`v6E@OFYbZuomDQwhkDBRC`WSunRKxV=`y@rwZMTY4p-U*ELC03zV*hi<bNy96Gs
zA1cN@y6829xyY4SEjhFS7i{M=eB!b4C=X&)=x*X;t?t&2L#AjkF61imQbPerk`dhq
zirV-9_lbTLI9~=Q1jOv@7lz*DxgHcncy{<EFQxWzyO~K7aU$-Y7PGd{dy%V1R@VJi
zpG6b041ceNYC)P3LeW5D+)L3c)vF}3Y~3KgHR`FZArFRKm%YH0;z2&ML_S?>-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+<T0pf#!2mHVeAsjei#N(jbTQ~d
zUTvJE@;)_EXcf8Lodnk+*B@AavF8!k;I)V61~484iUdI_N6nBH7!)mE)JSiIqEbFI
za?yEzly9pW)xz~Cx2g88vb8tFx$dwv4v*5=6P77K8{8;dhynhqFFNmq)waOi@5^A%
z{7faQ>86~NUjif0>|2Zoqus0PQ`7dWg25_ThAF4jF6wuY29-;K<zNK6?|`cy$8%X>
zEn(yvXqnx*5T>h+_#q>R@L6bJY!_bn>4fVfxW5szuSfACPT0lWVbHa3k8_*_NmwI<
zNSM=u!}bX-_4uHy+pOe1p#;N057W;DI^lcElM*<dy2t>)<^YrIAz5FQ8%ipWzAy{J
z{cckAXaP)(7s&Btw#+HGBvk6fbm2W4pnkgTh$W1xUi}I)JRq?_#LG#993AbPYZ<t|
zGZfoiv>Z1mR>0}yuV#m3#V5yB0xhY6f>}eoi!`_#Ka**w<x^gq!>ADAS3hG4blYO-
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<!82_nFDYrvU=W*V<C_8B2=7HRMe<3
z!8{oD1E~TYQRcnQn|qhgqvSRY7JuHM1*?gHydAb4*fvoCEFo{5N|b28rm8n|HCRBP
zxud&@uNl!X42+<fhX%5>+eW(t#a)_ep%efsk$lQFVtK0J()x&c^-bJxp3VrZRg89a
z8F}-ld+k)Vyt&<Rn>1((VM$jo5fqXW#&8^R6a!UVhsY%Y@6a=q(D}de@?k`sIT4Jl
z5AZ>Yg*r6g)AbgIv&Y+LQFVkKcT#i<N3n%5rnF6Naox#U4x6(U1x0<ej(5|&XLTUD
zs@y6*txs`5$yw%O(s!c|SlEAc58;2zb?f;*qsYlVqvq;|C6e&VI*jTYZo_UNtHE2a
z3>INpQKFSaut_0=Q}#%+AG8k>s{yb%Qfa6=*1APN>x+#Yr|*4<K54QcayxKb!#*0*
z8jIpBFTrNu_T!Udmf?V)hk=Elxj&-R9IG3+5&c1Rs6t7_-yl=T0XG(7^6yOm<2?7q
z=o$BdL-By};!H46Vwi!{eAj|Z;;{B-O6p;ut$_3;VW-ZASsMIRPw>n3#A!D6`jLu?
zLpBruzV-1o#pQ$i7$u>AQeTzFu?H~PJHPV45FGxzJB74{0=H)+1D{HTJRc3FCqkI{
zX^d`KbWD+ytfAo@P7l970VD!RE<hI|zQlW^=7L25rqYd^h|CN2wKxWPU!|6oR|mt8
z9N$L0Rv~L>RS_7Ms)($xP<x`5Z~^<+$4gO7iQ;anG;Y8ULy&^*3A)llu4ioSguBh-
zk@^K0A!RrYFZLrti%sW694AMDrk^vm!SWk{R76C03Ee&#pV{<w3|)-Z58aDPXI8D1
z>Pe?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<PRyk2oqK>#M(?s!4*@I*}gq(1M-$oh^GKB{7-;
z`D>8?8k&5aHru)ai0#VBjh>ZA&i;oD@3zt`(<xbVife&!b!;VHq6_9Nf$b{zN?@T$
z6VpA{!cO*w6Ccdz5WQPoJ!j%I-Y|3~E;=wMeE6As?G6_srqP!8^zauej1nRp23Ro?
zJu@F`wx;!)i`FQ(1cB%dl&p|}*GK9f8Y-dkKmQu_VGJ=N68^#deD=xaDaXqaFox=t
zXDiz%lEdr)VP9@ijO4`L*G=J1ydSTOlZ}`u;p8>26wXE;rmNWn1CS+3;V9g{GuaHp
zan64{Mc`u<!*7)}Z<(g}DURjX#@^5eI*Ux00|-}YFE0#!_^ErMSxz<<petfoObY5F
zSpHmm%6CpjBgA*RKN1UpM1J|`CR;v+5-AjgQJYTjy^pnqe$vYO`kZsUMPT8xv4JQ0
zyLeF89ALy1f!2=km+xYInuY;*7`u%5vZtY_YFgntVUc1{Ot7LvQuAICOeBxWx_`$k
zx|=mzE&N()$Sh2E_`K4PgS<$81sNy^5h0pzU9zRUj=0JlxE8CMhs8Y~@zNLvGgLI@
z2}-MCb4u1r0?M58>9>)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=+9<p9mM`S{8sd6KyW=|S5$
zzxI#^TK3^HbYCuO%bJ@d=S3Gn70h4d&F`HEQ$Jk7H781d`|Ykc7?+X!FLe8D(;WJL
zw)`a)<mc)J6)dc7NN7P_2XGs#qH2f7pg2tBkzC6-+TTs{P*<>c>;#<KjbMEpohX9i
zNRV%3!Y|r9yGkW2UFphDj<sq~MZkk}r*3{Bt}2~otXl<n$|BQCLHFiiO?xZ+OQ?o(
zOO$>_S!7+oww#&B^}r`q%g!=LfG{;znuIF}eL#xuD_d;Z35h^dAP+@g51K}_&_fZ^
zy%WX5sZfyO)0FM#36~T`+Rl@Pv=zkErw<a(XFIL{ecwo8Jec%%LGuXI8<2#3j!rH^
zxQo*Dkl3@OP?j@MUC83$!Te5BUM=fwygwzgvB-POK^VH~m=fFG&c6HvmVez|uj{6{
z4XJ66{8RR4MW=Xs90Yv%%T?aAD(X@i?5JDFGRBv2^wV^3$3%JU!;F2OCB0Z-F2lrI
zs}MT#l(XjlJCu-OY|Y^vM{PM#p*=8LIxc6)`$PvZLiiEH;{!p872KQ<AkDpfpOp=u
zCE~4Qx5_JP6JH3?m~U`?_I=*b^78KTY{FyEmTR_748b1nZAKgRTMXq3+{8IJDHtmb
zS8SGz3Ly4FrG+lT1!JR;jOcOvO>_BwOEaNl0p5O8&ST-+4-_TmwO`Nia2w8<hO*2Q
zK1-xlQD#e(CtI0hk;N4~cm?b#l<b4^O>m~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~*vWZ<vj3^ct5*tTmXIy1;u
zsGSI)h$Bt%4ZW51d7P+u>bA0w9yjyriV!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{<Ezv
zk3qlyn1q2U8_|U?!s?b@yEtPEOa`hv1}yZI6DQ?$Uc@u%hhSCmNMfB;m|46$-CGDc
z{mvv$9+4}Ns4(k5OA^=%!B68*DI&QPdfw#fg|NN0fPoIbu6-qjj@NyD2HZP=@5&ZW
z*pL0&hvSFf@1v%ww&G3kgTEvAl?)*B4#KeyucP1aqnD}t_Q&!AeKDnu1!=ME1eI=#
zO!lyr0XFyllJGlDUO4T*dP1GUW7+bB;I5~Y;y4Op$>+;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@
ze<s~A=Hg0cCSxTyZZY7}Y?PJALHGTcu5d&Lu;Ty*_I&j}>P2EoJqY5IoSc!Gpuwpt
zYoANCfEQvgWc~WoPZ~Vo>e$%~FEV&KS?cMCs;TpI)Mv!SAu?^Pzw<QX0v_%jM*K14
zWP?Zm>_<b)eKo>ZMZ>BAywKkSgTflrQ0dlj#U3L<5I~LV)8*aIuEGzCmzhUUm76>>
z8at@8Qg6$S?>)z{^JzeqZSVs6dvAp#j*p7#=gNlItDFaf{1iRPO0Boz=ZTWCgIX<r
zgY-b!9RK|gMKI0sWkQ8%3TtFCAa%(L>`j3I<1y#JqxjhA^cBnlKP~35Bsn&YBjiV~
zSjdosg`AdD&4BOd0`i*lhoQQ<4uEukB5#24oyV&YFl)y_q&_Jxe+$vMS=e$<s#D-G
zgtlT>LwCOlQkidfeoOH6CkOZ?3y~Pt0WI^Uy(kxAY<nTLa*lk@l+<A)ZI{kg4@{hp
zCzP?O(phb;#6XxfzW<)*|8+lCzaaPS2P4RH<0iQ_rdx;=YU?4I3%_0Lt0(5@qc)QK
z1G6esESXz3y?wWx2V!us<^{zd001WQ-6G;1ftzbvWqrK-4d{i>MSeV{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<k;o{;HgM``wc}iT*eE
zha=hpi@`S=S(I%5GYp~dW2ce9YI&OFg#dzvQWN~Tt3YRTiVtvM_I*$0+>+{CPKH~p
zkmcRDwxnYA`T7(-_dW1&E&{aYySPO<PQ7PX$9gCAuj3$&-eT~y*W6YL_nJcZlN!?V
z>pxAxdKP~%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<Xm&H?^2@Sg<86e4exlGL7of=QGNs`l`m2Y>=Sw9Xn)Q#r73B
zG@7xsN94h@pr(2+JMqfQlUDaJ^p@(LgHiO%jDy|bu$6?eDLMnzw8%8NjFo~gqT?i0
zumV_}+?lCZFIB^=E%#<thB})~vb8+sg%iWXSIEL}(7f4>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<wxs#r-8&MqmvrjTnpqhYg6igZ@6}!y;`LzJwQiRWRfLPe_%&c!1UHd$c4j
z&W`JFrHgowy{=7`d15y=8Y;SAk3n9C`OKpSUR@zutVaTLzgv!H??UzQ2*?_Gxly4>
zACO0m{dy)J%^AbJzF1;ZgZ<Hx`{FXtfoHx(p-9=zfFTh%n$1iSrXH$;abZ*@+>5ys
z*#Y+QKIuV<eZ(%D?N#VEA%z-0l8-DJ=E+&}Uk>xDP2te>ZJC7qcV^a+EHgcZAMwr%
z>bZav!l(7J?Uy&ArE>x8Xgbvqp&5j(ACAY9fV*gS^VqDjRW<nt%h7Vf@Tj-2lEm$q
zJh%fcvf5;(&r{|bdsJOi)(H)#x1Hl2=mo^4b5187-jj00FE;@<cP{g6*3^dGNk~=9
zQcY^9bq51f9l78D+{usIZZ>^&We!7vfWt2bC89td49R;t2W5+2+x2LHyCAtNS~$jo
z?3mlYfB*pZ^<r`ak(b<P6kbXLERu0HC=|bL^8f*Bufu?mF=fF&!aD_rCPMOEUBfq$
zpw22o1kh!<<g+n74<3={ZWQStph4ee=yZy06YBjuIb75-FsqJR*rD)_`{UG8Q3*Q-
zSkDah0RBcyocND&Al@&jQH^dG)_b$@qK*G!8~>q*HkG1sQ$zeBY>imhLDLKOtua!x
z@>q~@=(PYG=*z2G6nY2!<3C#dem}WRK#GwhQ{O}TDVX#gPPp5BsMD<e@n+r=vU65K
zr($1`$&^XF-y0$yrw*89k)@d1zA@x|VE*qbL4;k&(^EO80$8>_rrF1=#SB+otjNe!
zQFb|&^Xlt)G?5{!x{$PqW*P<HG%co=#hEwY=>_A%&f~rsvi?ql3?C}dCg#5kRG`Oo
z!>W7Qqf|(^f0a+W`xqRdWcU{Nr@lreA(8IIwTIrUBwYnSEB-8@!E3<B(+5A5#`Yd%
zyslE=otECT^CfUqxMQ@87MC?z)=+25JYw1G{u3*yHTTr6Vn;v|nq&mi@vAmb{}S^a
z><`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-KYbws<P+sg6XA(O<KCdyTb_cHqwK1iW;0|SVsXum0
z#kh%^1$H3JY^(9Mdhj%Oj6{pAeNZR<jDB*=RV)DF`wQ_!G%Q$Wm<58LYDPQI?2fk{
z!(36vaK{gCu;-ZKw}}80r)H0nv&Z-h%^QRxO;U;q%85ggxo2D#Gk=Y7+|)8~3hhgo
za8xzLNV7+cSUBXsXlf7iwb7cOA9Ndv|Cq)wh;F3NgJID492XVSnl>mHQp9ED7vj%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%kKc4<qmm5
zxIQhvx6rE;=IYDJk@edZ#t=1NFq9p`VnFbeK(XTsJKDpZ3vxYb{7dhY?sTiv!iwgD
z_z!<29q2)VH(6tUm9lkeA`EK!vjissq5XJRCF6cE*ss>gYSzJhy=1}ptW0H<nE~JA
zo9k|Ka0CDcY%&N1D22C2Wrag$$goa^1H@VC5%Vk&LT>~}*6IUy!gKucNu|Op!V83X
zPn%Ey%@!#53Z!-H26RMHP2uO)D}?=nN(F7WRlaT2H#V_j?P(509}VeA@(>TLQPO(}
z5*zM9<!~fvNjdEvkQi-b;Tce1ePWipx;5dLU^A|r)<Rc+V#o^S(N_@DCV6d4kBRXo
zlilOiNNngjQF;K0mA_5wIu)|-um}Hf&j=bt7p`~+6Rd%gL3g)^hO0@UDSz2}zH_@%
z-4CP6RN#%kl8X8F$D#9lUprve+)(PTA0-U4TtFT05cUW7n5&%8rH_5y$o1nYYiG1z
zk1j#ctKLus2zoBb!C$N99Xw-i92lbU@T%$1y`%Cn06aj$zxuNANpCn;td2=Oir(GY
z?#uU+T_|TgZe=JS#L2}{q(mbWj(Z6cM{oy7MN08ESo6#DA-z;dhqz&u2T^|g&@q^4
zX`&8R`CMSf6H#4A{jtt%Y}A$$pto39$UbkGOG_??iUu_s?K+BAqvgVPal3R&EB}~V
z*ya;0_|6IeVcd%$mSRs5gI7hbzLfnf%j2t#o3CAKpfjm(=BZ9GS#h(MfE{(ga<e3=
zt$&3Y>AqNSsT44tySaBqE$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-SGtYE8IDJ<z=Uxt24pw)
zFA$wSJBcAzUfzdH6`oJxAO8YP^X;P%K^4nEQ(umy{NVBu_6R1gR)1>9S_itaPN7<D
zm0@~vv03-5z8)ZqPRHA$*^d?CB#<yrhd2N(T86Nt@&T|UivBDjVYKBJxq#wWTc_&N
zJ0b(!tjEE|nvFMU6eBbg<(X1&>*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
z<n?kl$Z=3G*+8ZemlgV2glJ=fYZqN5jED_QfCL{$>r2SQt)CUmpIwzA7(X0&Mo$&9
zGGw=_DpI|?4i_#N?eTYwhjKhFwX4YSOcrWQ>8MX9C*^wvO1X2dqD<>b0K~y>KL`M*
zTMqN|TAlxeJP(<v-uK6{NUDUOn_q)1D0K2`J><*;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+<!?;A^X_8
zn%evRHW{+}#@ki2#Th1Ey$3F@<JAoHP9mTwcWZ6vO2@&X>2wdOk2PC4`@d2n=$nv<
z`t=S)8fbF)>6)LdQ`f!dp(^TnyN`Bh+YZ<#&$QC*g@kSW<!G<}>JCB(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$`QAP<T
zAXi9x3?1odMs-NyAFaP)A(R<#udc2eo;(qg<(bIZACXV}pyw<m#}U%)$2mcqoEmSG
zVmKNgz@PKByEVK>I)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%Q<aG3I
z!W8mAC~i9PYYIy@D8ODko#;el>UN?U253#XR+fk`uVr%s96RCrI>7x;fOOP=va-EE
zeCQa6n~SB#a=KhNo>7)y*KKNWgUuq30p_5pD$2kZdx?-`HpvW<s6VpITLoNd>yk5U
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<jK-F9bceLL`yh)e&r5VuS1ecm(*%?0o{DF0=<&uRp{3%{26-U+LT
zhxmn!7#5v=L=mvdF5dkoMT*T|gRKv;9!$Ur3bwb3F*Q51<`zJ~5<zxESM`HhDnqZ(
zo3)bN>{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_15<Q0i)hUg)j0S^In+i{EMT{R$rY7^0hKrGuDqN$rN#UG2
z?je?U2)k#gdZtWLs9I}Y1d9iVzonh9SS64T;sW>5vo#C1rf<?SnETl+C&?fV6aSj`
zIK@^@BK^@$ei0&K9MaS-L6p*u7Mz}NM6fe~Wd1TL1$eMZ^_cap=WKzy;QhOsa~SjC
zF_5rxs+0?@`0?QtVIc67ne#=o=}7}iZ)&+If6kKecRA?D7x-eHFhz&k^l(n)O>3IM
z`Mq=+`!>BH{i-6Sg}a+@-C{k|T_;j{P@0eV9~{>$(qEdR@L*3BOo*|C(qKW{@shM<
zRXPSw66}XPzzw<BWJ)s;oLQgT(45deg+o{Ut0l#ybEt);J%am$vKAN&6Gp5X48r!t
zb561#Jlh*t0oj|*1>XvB_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!<_F<dnwG7xRJ?Rv01UkF1@edS`|Op!*N`K
zbk>b%2s6M@{w6M_P8<?VABei8rH_xm>oS4X%-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#0yQdS<c=mjxp|la-%GH)BM0@~-`cwf%*qwQ;
z?kRltxuS7?U3h)+?hB<D@yRB#0DtTD-}6~c76!hfo9B?Ia5*h}bhk;wCE|5D323Bi
zFZiTXnJT5e?`$5y@sGG!S3w`q@7Bodz<8L`uiv~K?rpjqYm{rQ0oE1B!Gb~TV3SNR
zsMy3d84o*mC=7c8(go1nK-Z#2FicBhq7OB2LZv-;z@gNJu7uTpmqiFNZHOx+gT=?5
zzx%#x>tqxy)fesLPKN-m7fo<teR;GtVK{2asoBqZtK{#)>=i}igg)Y^TQLjT+>32J
z1*R3<nk7{wkMoz(r{&(NN2%y+(|XV3GR(Ovp8v6)DG;{xtP|wLMT(l&G-W45LOoZ{
zCp!^Gvi@LwZ_2D&Te0HU=3ZndqLxw~4Y^}k_9rw>ua<_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`<!wI$d1W_QTX??2zGlSj2+r?nFNn?1(`$_jcg+B}%~Dz#8ZsW~SJ
zP%6lE%4A?I3U%FQ5}n@KT?^MJ<XM1h8;@i5Lh(D)#jw`3-jy3C1;n4iiEO-fK1!g5
z#t4UteF)=|vR>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(<egcBkel=uTB1~T>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-<jSUw96zAPqT0%lWPvy`Uoe8*Y|C
z^a{WD3}huz3yq+LiR95wZ~Q!JFvy^kZrb|;+1(-#t^`fmkfD7m1yGkHc{TF_Z&Lb8
zn2i=&5KB)+k^)NVsbO=%66yy)0O>C?b$xfZnD7!&9Dq-xd*o^P_Q4}nYzf<M@l0Kk
zNxmuzMXsTi!nF8$=LdQ8jZSI!G=Qlk#qh<@+j*&%WWYdzV;kLeP~Ai$0<pkjrT%Z_
zT96kQVKj>)T^mohJTR7I8Vh!{?74T;6>t+O7(F()?Mk_RO;*4Aw}61}*ruz$OU8rj
zKl$~`6`Z1E@k2E<M~2ID7Sr;3J&%vq9o0=}VzPO;Cusr@sw4-u)-k2jgp_UVheIEv
z{Ue<p5j8wo6)d1RB}j5*BX7WB)V&$_T+!|%_FXJ|*!;D9S2t6p_3GtpE1JKlGy~?Z
zn;fE4G)YJaB52Zh4;hA(1YZ<xUoSTdwEpt0GC%>SFBtPMZ$)}%!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>G<R%47bjgT%Es3)
zKB<X6D3h~GEuM`UveT-=dd9ZR7Vw5x9_kL6-c)a)q;I-zTN8|F*IW&6j5hnfbymKk
zaP12A^xR~rbqd%2<>et)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!!{1<Dj2hWlsmT2k6~!T8}hi--m0
z0002TAOHX+13J8|`y-$i;VMu((HE3Aw2A{C+04X1SHT+%gDyUgT1AM=i3W1f{mz=q
zrbXtd*A33-dbAB093KFq(O75C;AqUD{5(;np_Hvhu4#0Zo~YCTXq~PNC!h)7z$k*F
zt)IwhtP;fHAf-X{I0c9f=sbDp!hZhPw0HqFx9(Z}<};k&!>68@4<O;+uV>jgMQ2fK
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<kG<-STxjO+vF!%6vQ%6lRD-Ys@&Q+wB9
zbn{@ITdHdRQ$Oo83t{pj?%%sYtfjI==7FdN-?azoqw*XkwGa}?&s(i(t2(k*!whPh
z#hV8BGJNvkRHPXWfNb|9e{P(7NW7(PPbaAtjmJnFmk~wIO>}lU8bPagQ=r1S<qZ~y
z-S&dJ$4Yq`)1d&YUrf-{0R-Ww{MOus0hmM!zxdGZw6-JXY(ELWu6o<Lnm>)-)C>DL
z6m95ey|}D?UWlw#_vyoDzo7j{8xg<B8ZRLRfU0Pg8c8Lmov}Y-t@p10XFAuHB<s3P
zQ+5tYAnxEN{RfAr2pHy}kHvaKMvwMrk07;|C(f)=z_xNN@?pQ%g%n0YDJ-8*T-*@G
zBs0s*zhMLnS|Ifnf+|uVSQYpEucT&5ha+fYSIRPKjdHVnQ8r2TR584E4P_o`($cH;
z&AN8`_5RLnfx|pSBm_pHAOf$ZdWcYg49=}A003K`bQ2>d6Pcc=APAcKB4fG>K47b9
z#bs0-Nv^=MCy}e&Tg(IeZ-&v98qj<Mv~JjxD}Ww=1(-5qE&w5%+5P8I8CQ^I^vCPS
zGWoJhS-3w?jX=(VK}Zx$WX3z5GwPVsjikTg6}s0btWTiLB2u_k0@8F577#mCM;_!9
zr>83$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%3Z<x-4#vo2xS6*O
z;nWfM9Y!UzLD3_73l$9qa9CaIXwG-OYNZWHnJs@<VZ@6`zGIgQC2B5=J}>fg&d;Gu
z;L#U*F(Z$&1~wW1({9`aDFe5`UpFQWo>M-U4LXuWitZ|gg6Of!DKw`YX#fG6;L<CI
z6bKv~2s|BzW@Yl1c~dU+^w(rc^UG(+RhJYJ{=!SB5&e&*!YCM+rtrz{+7*{&=Q;AQ
zGlr-m)AcKjDAU4pp(cAhne2wMbE396R11(c_;j!(qYG8vr@3Di0SA2oZs&D?*DG6S
zv4m3Gu((;_60nWJ+w_}>@<sDf)<AM2x*~~ygBoB-o)`FaZzZYH{?f=%gl!2`%!E}T
z$(@u&476g*+FE6xGpp=!gg{onkPb0avH#S6A)aq4E-tONr@HFKn)FAadSpv7<UeU%
z8BkqUAWW^mJ!vJQEku$O&H&KezN{i%Q>aGJks$4T{udy%3ZzT4Pjo_gTE>$UvV>;=
z{+w-g;h3||9|@DhJ7w<Yr&sU%DLxSfcBse=6l2g7gBhp1ody-9>d74ocNyu4cG3H<
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&1UUGpqp<fy;vS~1
z%y{L1o76O#7Ht^ub|B~2>XOtx$-&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<H(`$5WDofbO>=i3mIYc)Hy)y?XPe8>q
z4Zb={y1-tc=&W=hmit0ZEKON@d(UV#qL<pp^y-!~TZE|rR&br$QzCvdqT8>p#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$ce<njH%+>J
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<KEQ$tf&`>?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&EW9uCu<PB^I{2rRf?BzhcMg*&1cZ<B9j7D_n3x`Vz8Zf9$F
zhSe7gm0$&4dFByd?PUODYFqGU3`Re`b&y`3w^*ZPg87_@;p?I~3W?astJOC}VfC_e
z0O;-4#~Hy)gl4F3(MLzuW1xzFHTX$HEPe&PVIq?s|NaA_yLaK@^lkCl$+99$^|qgk
zsur5+76AXD89Sbi;fL}ubwAK|;{nDKmOxF?_m?J6xSecd+s1_;!o{ZELt85FJ_Bt8
z0)7sU9$pj>IB!Ho`5)1UJ<ouILrf(p>3Ltk4A88vFGl>_z=lbdHWT}yk;NRlPA@9^
zuc*FDikzbE9iXky=}qZEdwmY$anpMQTS<X6c5$$yj5K$>H&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+C<l}1yndc_%)4g88p&$
zB`Q38wRG!MDN5Q;O(zU#1yeTJ6zKEA_HEt%TLMC6r+%q!v$rU--Hylv^QI3w8o@^w
z(=`Eb?<_n|pd`uyV`m?z@0Sz2Fnz^4*(yk=sJ5~&erjxf$Y7ARtHlZIF2Tx!-EKr2
zPp>xg`pg_3i}DmFD>2oBmvoasG+Y%l(p%jJMskKXdNUKV!}zA3b<i8gGd}EBsgVp2
z$Dr|NnKkDbpK3r1>xqPpR3R!YqFb|6mYDH-kHA{Yl4^)ZoSJ?R`@3Vh)4dRhtF23y
zMkt_?zZcp-acMEp49ocLexji5;@S=8aV|9o?DOR&ir&<G<3AS~`>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_((k<EkV6n
zg4=1`f9QfH<>1-?03`4$C6}F?qE?v#5DRimM*yk>2~+22Dso+S67*D6Vj7v21*a*$
z3?tPXx;=B?$o6t6`!!+?*4;C}ZLp*V3MPm0<T!6XGEGdOP?<LT1!k5(PEJQTA?Nnu
z>sMPI)mV*$08a3-irXYCsX4c)9pr!o*F>?THAnqLgT7LZxkNzvtSik}M8(O)9H@NQ
zfF7{0#<Edo^Km0&YN&hmfyM}OW+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<u)Z?;DPdV;78WyfyHP1HaTw&CvROsp}W
zM_YeJ!h-qr+J4F`{kC89FfUd;Dg5inirE%1HOl%QO_%Js{ApCd#S7gY_j!5VGV4pU
z8W^0cK)o5P%uwN(t1x%Gr>;V@KWA3zLYJDCSe{P!fgO()<s0RuShRt8#Mc8_Nv!>-
zvhrz<NpxIus%Urg?n7^Aca5Y?7G?fOkJzsS_Fgn#bv~ZK_OWW(+KK>&u6{WRS^&B5
zzMuMq{{%MVcv*w40bgEqy5I^E7SdExiFRpkhhe4{Zau-VcSR%kt>E7a66Qc^zE$Dj
zDOu{04z8JXOi~ucHN}Qz`5dP)v;c?RU<yo^^AVSQA4>v}=N@_rr6!Lf!0MV*l#*^g
z-)i5G9(7#rM%vp-A}wSDzkaAv`<j3uYSidPTZInN?6|gEJon%fXLZWI<Bkj>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<F
z>$&<&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}?<}iNAx<W`5D~0^U|mNmX~|U~nl`G!)L@tZ_=DO1%#^0;4HG*cKJ!qiweji2(k(
zm!>Q-=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-`$A<q)Bm-@#)-w>wXMRW}o$p5bO1{g1<*9MsE`dOk;1`Xk*r2VR)B}iHZ
zb!<qI7RZnu|Djw+m$Lzlw(nEngYmh=agbq#_>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-pD<hZP5{=pQB47&@2ii^CB(;LdB
zrhzwJc9WD+G|)|c`13#k6`Cj|n-lJ_W}f;bf~0ep7=3ytUC)Fd(V}qtA0?a18!}jp
zRs+LEkC6PuWjwe;GjgQ#8Syg49%N3zt;|O=sn#L5%8qaV^BG+#{lgBS!0kGM4H>V2
zJ`KEHL=ya=Nx=-O6lR)g7Hkym8?Yo<onI`$bj;37BPWKmgfnEkrpCCP)MJYfH#W=&
ztKOE{{ro6c&mDZpPLiJ)Uf|`56NuAl>-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@nyXoL<RQ=))R{zy5X@dsUSj$n1E#qR5)&sQl%@
zE&%{ClUJ8}J`3>IOMg#IIf@yv=lgyk<1ALkeG#>}#y|)cPLFK@@hf+LxA@!Ins1&m
z?<$eOMP{hr<ScqukT0Idb<#oP0m=WMOONneu((@vojI#-p|N?^&1m>k@(j8rkk3de
zW~H0AgE5d*SWB&WjiZU?$+NOdj2vpapE4Hj8tWKs`2j!=E>HPIQXTab;80fozYuv*
zR*ha(07WZ<NdxsH7CS6-TGvTK=T{~vJgo2X7LYik?Cjg{cGeG)Q?Am#M)0dE8g0HK
z0t@ERNW{1#xMl!V9mxx~)CVl|KB~bPCQS~Hd%a5W$2?m)p|9d4$t??!-!tB4gi%)2
z%Yz`m68-pgnC&8*0QuU1QiOLJXcLHbX%m{N9i53W;zs<5L2qZpBnoW6L)R@sEX`zV
z`|U-O^JYufEbXMuf3k=&2WmG>sHtAJ+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<nreM_o12vYX*{?T(~VGII>^CEX@*@jjA)%
zKv3;=i>PYIpQ$sVovoHo-m`j{f`bi({9MWj<U;VU>Bbv0K?)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<v2rY8!KUz`v4EXBZ?5m0AQLct-s^_vPC8@!tMfJp0#4CPLT-v9*m^Y
zftMWi;cnw@Gq#WWL(G5_6yR%SaeLNW>}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<xOhG!-Dw$6w|gz63)8jNllM{Kh8_Pn<qU
z70a)*v={hpTUdjHUt>?q7~4bl49-~>)HM$${g$gV=xBcI$${H4oT1=bv;2LE7^_j`
zy&<OHvpQ^F2v@frpog~H=C`nu<8Vk^%)30@9lNh|6r!6wYFu+p!*YtX-5%1K@>$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(!<EH952>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
zhlaYfCnsw6uH4<yhwy%GzB*moUzs*{!j%uB36?#MX^-7J*Z!C=CHT|!17p-Dpaium
z0FqV1x8uiPoaJ;K9S}-&5fd7tMqss*3_0I|+jk0oZS)9d4;jHl*q@E2BfT@9i=0w%
zC*9)CCSv4=VXqWb$~gj?kRY!(2e~cr-G^!xBDIN1Bauauwo#Q1Bhrj~EEXw_h_uFZ
zrN5YX!mI5HMJ+4*y{{#)fbfFn7<;YxCvmq>8k0KLD_Q$*4pbAQ42rorNnFHTc1=te
z>jk0H4_tQCnIky@<Dtcv3@gHvkGx?5VE*6kWLqGWfo;Hq&WaAUHd%D!h^I?f0L#<D
z5eE-}+fiW}GKK>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{_lR<NMg9DxspnqB!
zz?>hWGQ;%6kJPG`5BDEF#o%8;-LD`&%4{S$mNTM`AfN~QAaM*Z)gw)3(ea~L%V2=d
z2sYZ5fT+6Blvnv7oTWb5du&BdP!-Do5J3&AGSN|K{sswtIRi)<TFIUuY<vl=WY3rZ
z_YF!<q#$5t_yzv*wd|Hv_9D|Y<Skw6%dT2!8~++)-d98o7KKR<Gy}RK`Di8_@xA82
zAU{*@GK1mpl$eZlASPin8RbXJ*r&TBmDy=Rk0STxe*ZaJ<OaU^poMA(Ti7f?PEdk6
z7nNYrraid44icRQoK$=L!^SD!)KdhcCTux(*@>InSN1tZK3jN%am>K&=Tf3U8Z=GB
z%|t933u-^A6~-I!_dhv^H68<TfMCp~4Rqz_LJ4A$_8y`D(a*ufT)%>|UV!C|eHqf8
z6&d8}fYgAdz*8-_1Bjwa_EFP<|L2e8=^-zRM?m|gdu#+Pm4G~brYZ<?^brPb-`=Cy
zWpdpfl@M)GwQ&<|F%n7*bzfRMGJ;OnPC@>(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=K<g9
z&68JMr70M#@10e9)HWY8maT`|An*<!kmD@-7$N-zWZ=jo>OkIbQ58c<A`Nn#q|ju*
zmnMtA{}NUJ?#2+_ORg~ddI;MIqT<^0Z9N4wsP^mICMv4oWthxJE;dw_NYZ%bEr=hN
zC-L&eKI?2JIb>m=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@YizW<X6R1!w@uz
zu+e{Oa$pCN)`BN#L^#0Up=eAt*~=s5H)5Ng;^@eY3|5;B^?OADN4AtZBp0&u=J=ZC
zFlPhY29~G;9{tdJmqEP+o3jIdTk|OZRxe+(f(he4B1@Hwg9fJKVqw%?Dduu|Ya}j<
zc_#p3xo7MM97!LVW5X6c^K~>NAi#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?6<v>hOm@EKUUUYJy(MUQ<k1<7Fb0S!NA<Yuel&bxeMk6A4a3Tne6y$QL1-7z2Y
zK6&E;ZH3|dkCai&%kE@zba^|y2m&SO+B7x}8VxkvSXmG_nBxfP!){Tm)d9Asyp7j^
zj9;)rs&{6_p>Qu7ZWzQ-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<WTB3ME)_LE7aj20kzZ_X~+
z?0?#RjEjrXE@eItDd!$c5ey2?Nv<<^<%TI#NOO)w-9=zaQQ#vup~vVgK3xjo6^nur
z0000008I;J+V~(QnJhCz01-kyfDy@DjvtXq&~6$xVEhFSJAn6m#Y;o@rA+lieimU(
z=z5-oOnh@kqyjFuiY1JVW_aIS?;^1L9*y>!*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+<XakwA5*gxrKz_p3xqWZjIm_eWv45
za6dw6js>3HtnTp2{^cn$H1EV*#?fQBl&gxXPo+io=M<wIutz8C%JM?UR$IX}#1NxZ
zvP5i#CyPLN#Zdn)_cd7MziVj5%=wVD`)`A|Os86eR=&=8;U4(M;_eJ!8gaz;5&mAf
za&(K7MS=m(X(VZOhBM8pyH;TPD?r>Y!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^QCRMm6<B^lKRu+L`=
zSQ*`M`TTN=ENUG~TNX8({{Azf8MR-pkctg>HPu&ayX?^D6`U5};%gt>C^GM0WVkF)
z8j5WCYZa51k~+A~zb(+<1k<hFzIRMM96<jMA_`@;8c6_57Sebt*B{NwRF0@?(j0IF
zr;05WEYd=f)dbEON6=AD5ueHxWNBhEj>?{D$O1SijxI9qeM~!YirTQ^c~@W{IbTT|
zNRV=w+}6%<#TDQSG+Jco=D$ZPd(??N3lCgo1;g)rwfl4O$0KD3j($Ggv@FwAd<GsH
z6c*r|b{6iN$`f=QwM49PvGAeo^go~jO`ON+g@efljT8rZaL}H9wbI|>Bb}Pw!~hgJ
zGajTT8>+pcO(q;%yVSmsT9kDyAxBQ+zp=L{|KhP>;@<U)_*snYh@~>@(tCm5^DEC1
z5nMSpGIYzrFdzTO=^my_A#LKDzI{-dRAUPFK3Z%1m-O?KX=MOZoowL<?t?i6`Jx;L
z=SQ%2MbL1C>}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>W<?fiME{1<iQn`;zoBxSD
z@r7;ZwIX%OakJ>SXr!(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<j_hIA
zHh?Yi7g0RdRjFT2b4860kM^P}G_72Gmc%mjUg1n)LxiZ}NqECdtstALQoI14IiQ&T
zQ(P=8#8qS}{ycf^$huiOiyR-gkPS5UzUj~c<#V)N^b)j+Dr`x%wEEHeK#t~Z=1M#b
z@+4)L!J8S})Qd4lGsuK&O1mV3o++7A%WXYZS3U@{25(xb1rVcJ*ad++Pj^<;gqX+K
zEG1h_w3G-XS+*6!)sdhT@K{`F>+&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-J5<a$@<V(eVDUMw7K_?sjWdpS-yt4T)&lAikg6;T@~_nHB;
z7trgj`>TOOcO2ROJj(hD8<gT;?45s}{^0^==jr2^4OO@ZCMtJTldIjy3B!<6jaDij
z_~~+haDsE6R4JQ?Mnn#5J?24$BjlvT+P@)vR;HbMKp#sbuWwxy=hIQUnbm@aC5$iB
zQ~MS$gkCj`fJ}N@&IUN!20bs1@K~sI#e#hxI`Q_<{hFmG7CYi7OoELP5r%&wu$c8~
z8=RI*k+_={Qk`2xP$(@=l6eP8;sphQRG~#aGdC)&4z#zZl=-BIg5VtBo&fOI%uU7N
zMi_PeVfGj1k>vq|{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+<ZD;R@07!
zi?<|h@7W2N72;9p)LJJqe-tT%LG}B0)q>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`<SqVpcFZYQze1G
zV8~~L>O(aXy6*SiA|>xaI?6~Y?K};Z*a}^ynms}%yg+fFyjsCZXbx4SxbPug7$#lV
z*^<aX!y@UTSiA||00UrH1@Rb0Eyd6>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
zsO<Td`HyN-Xou;q(yx}$?AmS{w=7Vo&HX*)Q{VinRq7@xjIzahrunG7Z4XpCppAz*
zbe~pjYT+x*U8z8i4cmfuPsIH!QO57vHXu68k*}ztyUE&R;cdemi@7&WdSsr$+6yEA
z4fZoIy9CVrra?yfi$LX?`SguK1Dj)+zY9Ul=1x+;mTMf7r?~1|XXO$x9T?vi%PHKG
zc%}H++rKk8yWhao`w}D~&akK7&o2SKXL`Q_ec=KXP)2L?+CMIOEHVA7QE>jmSre&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&|<r(EXwvyB=9ZN04F=Lrkzhst|6^xzMZaT{vjNKDPt
z0BCSFPSKq}lJGTfxBPFwst^DG000<!Fp>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~<jLp(j65OA*l(wCC0L}wZx!*$2XXV&d
zM1e<r!Ctrs?aj#SVYi)a_cek@Uv4j6tp%-R`ErABG}a?Yz;=J;>-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^|{
zT5LVPd<I_PYGT|4$ErmN)>Y5_RQC)^r|I762c(a@DcxbPER<LP@dwzI0Nacwm(BI5
z!xlAb^Y8<j0bAxttDVgbyhuZ7;L5f*R^GH22p`d^sV>6|z_m{U$Ruc}<$;~nO5g*{
z*>oPhi#fA28fANpF<keW`4c%BJNa&-s|FmH=qwpCvf(^im}L^T&ZIC+N(Tf-V4lJN
zi?u)`3wqom2lw)vzfnbB*ViHXqkhyTOFv5ICxQ8s(e7u^&}r}s#&bXEPl)k>VBq$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<Z&!{l?0U9A9>}Ls<>_g*34MHcFR7s^twM|?LXT5dm
z0xB!{(?Dje2tN^O5seDj=3Pb#&FYfTRSctGBA?4AeFYSGq;)$1=^&HTdR-<S-?M+Y
zqZL-Jef!V>D5AcwhtFr<F)kU8FCpoS@N=XpBn~AkEl@kKFMG)<``B-_j{QA^ah&b@
z*0uV$ugHiz>kBiq^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<fu`r31o
z{PnKZh{L?eW?|f6p74j6+$2)d*k4?nyGJ%|;0k7Q4N~f-m3~7K)9U1Uqc?8EQ<J%0
zpQ7eV0-!R_ED@*zUGwV-bI2^I@@O!_PTe6A7IzrY{hJ3j!g!1M0pxRo;BiKH@t%;t
zq6-?zwZfgd2wv*itvFe95SH+eJwRBGhd+yEbRg_mMF`*s!-yY+g3(Jfpw@-4fVu2-
z$E3v`gc6c)gp{6<lCpUn8@`~po>`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{ISm<c{<lLiL-!e26FfmKWkSD0_#m1)Rp;Z_j4h(
z3!7!^8wL+G>P-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<g1)o
zU|Rw&S<8gSpL+=;+o|SuKmkPOhW`xrSeY{R6Te<+VcgVLz6c1tNZ3;389T29Bp)C1
zAiyHP08*c?RsBKdaF>%&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*+<e4a=;gd}WaC;GkW
zAu^Q7JQKF|EY7~eZm+Rmcb>fNf{k}uuxmkR!9`3+78U(!ds;fd^ErGDs?84!7z$Ph
zMOR=SxXR_%A^vfXg(V6NTea74`Bn2#R=3b3Z*Kn<xz<8!ACMF7_b1UW8lfYUrM0(2
z!(D3<#1~HgJ|laOa)yb!oy`>`ZT}SDt?opU#Z2=I)xQ}z*4V1bqaO9$Q>I$I!5RnR
zy~OTMs!0Qi#-*OlpAG^I&>Et6RK_3SZ;gJz$r_TC<qvv-Ij$cpZw2@*ftXlwZortU
zq}B;(HwKgdSFi6aF7LUsc=%Qij+AMJFCWSNY1IM`;v(QPMh%1qf5>hF)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}<BY
z-;y>0TP~P?WA*{^A+uSiW%*XFbRi1d7gl~iv}_AyCY~#~W-MGCXDQ;d%+5N!hTMCP
z{NVBRb8PcvZt36c1kD<E>=a5F7j&Zl=Ewf$!b+A=gQc~-8#u7p5l`#EvUTYu8>3R6
z_W+fuT6{*184B(1jT=@<`=7FLvv*!YJ5pbyx%W39eq;p@>=+&~Zx919;f@i2kOSU|
zzy{A`<GrPdI2p>O2L6P!Fce(l0CgX7bmR+=JE98GbQ!!-;2YVI<zuYuK=U2l@H`O$
zj2yv1I`vk2M(xW<$>+?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;^Y5ygovw3F4<MLF}*?i2H$@)Deq`~vJ)XZZoBP)x{h_6U^ra(0?KM(Lv<B;Ot
z9Hy)d$jtDykW!l@@O{QY;Tg!9qUI9N2a+;|=(E?+AL}LiW7o7+FS<K&JzLwos`Z|F
z02l)D2pT`u6(FaUqIoy;G7kHIk)SF(85?S)Vt0amYPqaB7ja0#jml&~U#k50JRYM$
z85A~DqU_j`hxKFk@J~={O>seBMTnhNN-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=FDwsblx<ZIeO<WU1iZ;m+fT$
zy{<%5&^kBvZX-T7cAezn11f!5Hf4obdA{mrukEFy1<^TpwjdU-(^#Gz@N5>HTIWhX
zip&op6fW?Lcrk`-n|mNIfB@@wV>6+A891Mb9#x^Y6i8=$0BfbJ$|<=jznot-n-1bX
z+?gmm7Na$V{gQzAE7hZZh`gk6kCOF>pGRv$96S}thX7USF334CY4H6Ui1BBx6pq%>
z<?Ww_daYGhhl&BL{2sWhh;t%<h@$*RJkbqOEN@95DVgrU!O^1o*;1*>rdvHPA<RAS
z$I>XX9QBQV*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{55q<TC_IM}N)d}X1O|-j^
zn*5#d@Pvv&bgTg+Pz2E%f4lgc`ZWpKG!@yGAY0y)byzRECKKArW0QDkLvkh$u?Lh6
z>Cw_}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<L*0k|e
z8g2T_oGOFLUCSCm2c3PlnU@DV4lN09(^o?DN`b?tY-f6!>#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`jY<lTe8(;-&$3P*M+YHPlFD!x{ZoftY1X}(IXlOKP1uVf2X*YE1c9q
z!AH~}?ykT|fRWMNbZctGDU^Xlpr#gLm}*4MiGn#GxZ~urSSXGVb~=4!!ls4Bu^)kD
za3Pl2VV{YgpHX|<nzvNQxq<mE$VB!FUt@Gq(JwEWR2WSDQqlHP#7I$LBX_?hr>y@U
z^5pVc7mEWT%i!Pf@iuC4qcdp~4|;m;vU2W?ljBbsmZ(2{+pZIeJ?#Yx?qXjrYJl)1
zZs~RUkMr}dn8PLxmjDg?4O8oVON0oavIpdbQU<Grc@<NaG#7YaV7#w2C@D5T_eHeX
z?%+2{#<w^fO-n;pOif@Z?aIjNHHVr7@p!_WCS#8LXR&w{wpumnteg5i0T<ENF($ZM
zz`p>E4^J>uM?0<bm2u%53>Hq3+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<eQ_+Xp?;#
zUI-KkU$gPuigs>-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=)<?67bEcGfA0V+ye&T@g#^<^|Z>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*<eB8x!K#y1D@3p4A}ACdacah
zUJQSVN`qv$zQTqgK#wos|5E`4IVa>;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<HOsy+32_?gU`ce(l_B~GVt6|K}egQa0?)rK=QC2o&zDQ?M~&-#rkI0O-;Mv
zL9{*LI%_Rm7Z{4V?jW}4ke~JlSwI5Lftyo$Z2~(;PSTvWnCL9G|Iii`7Y~Wh1Lf2L
z0iK8q=8KOkGjJsZTgdU8NP53bJEL?9@^xvom7iy+B~g7TS39b?hu+JWQkG$L|2%*w
z=2CZGG^f26$u}QhXf3;&b{E+J5f%0isVq6NH$^R)DL1{nP7oVv4#@tn%&b?H*S!@r
z`%2589F#P-YZBZ}d&{<!r~pYoa}h>$3q<mrLysozN#&{L2Fx~CSg2L3gI{p1z@GXk
zdD)kUqfPqr2@I0p1o$}>1HUN%d!p!TlF$o|wvBb?$i%<ZcuA-jfTUnDyv+C`-cWhN
zHlVa`z<__}(QC%RSsYHY)1sU#uDOd$$0(rcvWK~xsa1?bRO}@Avt9r-LxZ`@`&ddW
zE6aLjB>TY1;hg?-^!!N4x>3QH=+vxauF!-cCmOa*{9LDbieZ3hbwutAK7pKh<Za3^
ze(Otdu(laVKVfm2*<yeVAuVMF0Y?MGb_j!|PuM<6GgK~I4(2x)_XC{y0dvqZTi}+_
zslC5wF8GP`H>!+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|<X~r;j&Jnl<Tdpl=OvPlQJ%bi_O_Viw_G^Ov(B-dMsIRU4)i$V>
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<dM
zN8Pi3DT$YRzrq;IJ=n5ov)37}WHr~XYXzC_72(EK6~cQ#({Z8;z=D&S*^yPV0yG^<
zyqtFs#kDD}LPpr|0oSX@g3~C+681Y%rKKrgA+?J=0y8O^3;`j597oG~U@mPV?V)xK
zfQ!eE1LrXls(#$9VvaYSH8%3B2mofbYRz3EfUo=<dI8ulcvzY~>`sdr_EGQJmymK{
zu>7CS?*nI$CiW*Sdd7|#-J{(#KzI-b5l?Ny6puzn6srs5Pw6m|iFd<QH(NJ!!BQVx
zkvu!1da`VSUclqx9kjQ<o#}-KQS6Dkj!Bj>z}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!%p3wMKJDDd<gi00<Duq#EKqOvx-;L42rB!%0lPc
z0Q1;hcVGrgtXYr<K2iRujn!W?%RC%s{*>1W7br=M)+O&-DX{Zv{#u^QGZg;+fF<z@
zpS`?REUWZ9nLQbix7Kmi(BgjFT3TYM+46{Zm~m>8k5b#!kA4ce6@?(WYbKr1K|ExU
zp0_CchjmwiN*|(SUwnaoy$v7W;&642PRk{{E%rzh0<7bo0e~P7G6^vpo_l65-6g>$
z8dyujI`xn`wW2Jkx@rR;(U1=Hc$cQDlbT<eF3Gd9NES4t-j*)xm<qc-{_`EouIi@i
zQ4?7(qTZ8(6F>xkmoFJ&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_$R<WzoM!VJ2u2>gxR-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-%<JKUoZF!`lBiVBVfq67gsbSI{?
zb`>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_<s?VmijTk1heEYXC$>1Ymq>`MYrnAUlZQEw*^BkV_KL>n
zI703+*pjhvnSM0>-}0n#ivpt!2<5$4dFE%^Ke<d{1@3_4F9|0^Uk<s1i`(k)*3o>r
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|y8<eW+YMEHc<{yQCdA=d?whc<r6F)q@L
zes^T8w9xW294s~%0ZbF%u`(&zCuu~3iaw!4&C?HbL?G)x1+`Vg2W_{C`LwmLe_ik_
zsO!7G&2t_b`#wkpP4D6dw7j!4_>L$bmh(v)Ks$<rJ#iX4Y&3P21{$!P$C)`scj-3g
z<_b-Bv>8l9%5`P51~k4U7W6b5sZq_qe$$!5;gsRPWqK(|-Km!*OE%(HbpfFD-q4>t
zai|D^U_RoL_Nf%P?v<hb)5%VxT!ozYE4jybLPI@7^(YVjidyFU*z9iakk|)VyZ?4z
z=C)6bC!nv@)5NpZ{qql~fcd}M|CqcwSA1V>E4C;P^hraYxKJW+D}~cZ<N4Nz`eIIc
z$?!_;Ove+kY}>vH_lkBcvDY*>Ss5TDY1fDFqBb10r<+9b?I5q`DKi`l=GHg2ON&$=
zx2Qawe{H0MLWK8evex%C)Xm3@dnnKxk(VOG7d0hbye}7McAj#VGW<9Ddtt>RM%nYg
zNK@mce{7A<J0)nXc+~>6^%i&1L5Tu%d|t9{L>gBKs?b2H?yFmNe#N>mgq4#OPCj-?
zBHgRr<xNMg2HPG6^Ng0hB18{ym}_r+_a>Y$l?cQ-{H_<V&Yegkfz>#uH<iH##12tX
z(tK`%wvrLB*`*x=X^QeGa7k!n4Cnt`Jr0)eI`JG*>^;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<X(pX|gcu<g0kzR;%8u8$}6SocPn`
zrivWt24aCL0QYf#nll@;s5;29803{~RUNBftA8vX^fYOvRsP7QhkKB;`524qVl`Bw
zds5ZHRP&ppz#>+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^*R<yd_FYM~&<-4{s&+ITg8Hn`s>f_sb*IcItH@AA5HSuYM#
z<q}twB>Zz=3JsB0MC?<N`7jSA$PrTvmXjJrZWCHE3krVSR*4v^J2`<M78wVtkC7T!
z?{z!}bV@T?X1luzjH5Q57(#N3?B$)m&BVU?Hld%{0<AI#{VPfBg&13oh-Evbs`Jbx
z6UjyGI&uq!8rHd9zr)nLu?e5ZE-DZ92!$9)sT>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=R1<UMI+%&+R4@XLk<aqy5#(SRu*?@e}iNVa4yAM!__;89iWK9`4LeTDged?-~
z<6cCPSy>M!-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>^CIM7pb<q$L#DI2MdHw=4co-MF%~NN09XN
z@Zy&b^p7kq<ZeO0A1%Mxy7^~!VW=N|=(G2X6N<$*N!OK_tksmdzmm^MPp6yxN7F!w
zMix~rjdLf57P?E2u>5==&v;J<h59`)r-4ge+*}<+h?r5AQ1o|DlhQRKoQ}*Wn&%UE
z-?^~uZH)!CI0hs7eWr)Q)|ZMHi#A8L)$A-qP}JR1raR*T-#d~Oi~s-OP(wkl6SF5&
z3G&E<suv}fG=jlmG!$+<9^zG}@8~Fch56JrcB{>({h$B<QUGSWW;-lfB&ClJD6G>x
z>6it7^PXuUk^+09lsJC$J&ETfYZHJ&0d#9^dpwd5-SU{vxwpF(lvEAX`d%gJ2bCkW
zQD|BC>5^i<x&2(aNFYV9E(Q~rVD^Fva%r&{m@b;v0-;F=ujpu_nP?M6G+;+C7CC`F
zG-W^x;t2&9X;j!u9yfG4C(#mS&!)DDvgPA~@LON~*?R7}Se5tm$+9#F_F_8l-Tgfp
zIFs!X5HD|4>s6&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#Bo<RtkKM6iC<!b#gK
zy66$qFLb}>NghY(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&=xxrcJh<R>Y9LoEfy&s^Um6nEOI{hGgiY_pB48B^Vtm#
z*UVRC8n6TzDNuAhgc_A_(Rc9GqAdg#WQtOq@!rJGQ;dZ?lLcgU;v`+_55E-bM$Yqi
z)Drn#chzZ-NKB9$8eg}4vd3%<WS76$P{F+kNY+ZLkxh3f9*M~C=oSEpq+p!z7aA&(
z$|O=<)z&Q**Fy87uMIe~+6bc8vf=ppJ_CGZb;rgk4rr787J)`ult%DODt<OFu`$Aw
z;3&k12P{aOI)e`;cep_HoMUvNvvbjn6*Nih3b95+HWqWi*odWq5+(mQa>cgqBKZqb
zC_0(4A>c&=5H-IAXE^RSwMi|#{DQ$qbSbX=y8rw67HT{Bpz_E`*qN;Gl1=2(ut_9(
z$<qe}XJoMS)Mw~Tlds}T9T98lianVmkZ@{GYXb^=w?SC_+P)3N;VhO}n&Vr+h#0Bh
zObp04)LXU%>|R_pS(fuo-`EfjA%(TD`k|h;2K6ZFyyDE&4%j~e5M1fKfWiLwSz;_-
zgwx~@+#Ky)aDrs6$`0+hcyoJ<B~^~{4Ll9yFL}+P>;M1-kN^=?(*k_%R9IY)I<4Jt
zRj(lb;XV>;n}tY0T+ahAArKxCN3UMFY8T(^(wz-LD;{UW01lDRLob2QrfxQY)vr4a
z-74a=U#o*}Zq1PT;hq>MYm4S<cl}n1=t{jsX}6wOP18M0Tc8vsPH+bMNi~awg;_AR
z4AkD<Xv|c6V1F!D^_6OBsPpp;aL-7LQ)kB8C8Y1KCb%Scf?$)m)NlS6f)g5h$l#@n
zA~UV4arR}qnFrSd$^1?eRJ8of(i$c3X7?ti8K%S69yQ6!9nPw;P@IGAF#x#mwmc|#
z=!Dt#I*OePgx;%Q`Lb;Y!oZ;N-4sqCgR!6R*$u2MIQuj@FONQF0q7`+K02iiKT8XB
zP5YlL-xxtrVmQsXr~`pWBHP20>Uda~!I_v;NgnR*?DSOm09~cY-(vN+8pagNm_<bN
z(&YgJN#>(%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&PzgsEjr9w<yreZ~B()`9-)nXsuhE3#3Yc*K@|UhPz-_^VAbQULJ-Bx5kL_^Nmj
z0QRbj&`Rf4?;e>GbQ;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=KNtNh<M#wPI2BGH%w-`UX2hrW)$2*Z=CbH4zZnb)
z$mU`=)ZOxq5wl86WJYSjpV#{^e8={A$=&2%s17Uaq9TyKDrCzsd9m`6vS<F6*B?p|
z&;z|~=4gjFSI^FCnL+K;#ayoY8DO`UBsig?A`CZuRLZ8Z&x#jltQ5#Iuoqoxg?pn+
zJ=v_6vXj%{_(Wm;2m`kuBTCuI0Ic-ECa>B$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~|mJDzmxLY<ZYAY42-@{UEH48sdKxqH;CFApGC@Q8@<mzU)S9PCN5t995M
zmo9LHMS5_u%RCFE+tPEj`zGHnfE~d$SOjdHT@vXx-G^e&Ase=CTYZFvw+Ktvacvzt
z6agZD-;jHtSVeICy#~vp5jNRdd)A5#`)&<WbpilM6OjcL>ep$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<dE$P`E)FIO5B
zY^Z~_R;rwSZ};BztHCHD_ptBB1zPXUQVg-ig5xhy)v9h@WM6C32>=z1wdt|bT(t|J
z;5jAwW^jXPOJrM2ZmQ-+7D|5+vM%ZhM9%qrUKF`@h{X%G>?)Nmi(<v2L+=Lft@FN3
z<$*%TPMAv}ez#^hLJ{rk)o?N%ge@QVDWxo4l>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)?<vBb$?6OB6o-llj-{kK;T62;4IwFiv3=vA;3+eC#u7E%REI6loEMRPF?35Z$0
z#V@8Vlsa~w$|Q4}+m3h=W)91(_brwOgLXW|063ncT}-s!TE;Q@fbqHArf>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<hiA20uR6wCuFf&^eWk{n;m;Ew%3W0$w@&YIU;2u)FgC
z#SBq~i{JA4D@B;}(6<~ge8tB;wC=}nzP#=M)QRC=e+{n4r|Ki-_UGmQ(6aZOaJOTo
zJ+ILhp%Z*UXA~!qJ`?qF)dB;WKn+%7aNeB)Me-l~E6LnXF0WUTcxWjErQKfHj^j%e
zAcT?Pu`XR+E;da#)1kp|{Gz{PQdacuLLtX}UiKF565RBIY>`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<TJwEx9&I;);LMWFg}KYx1p~R5uUM=jnNVn?{1!k2O7@Xn9yi2C
zK1|Wpz8x{L9&n~}-BlCm+<IeEJXq%oOaL4#4-73(yLYbjlyqnDC=}bVP?-&HJ>#TO
zShiNvRL)5J=Cd8tFTNXAOkxDukLr;AX<@XQc)?O*!asHXZu6B&de;xlh%oL_Wm1QH
zFOxXs4B<?;(&%N48TDTDb%Ll1WdQ~9*Kei4vibDEaK9gR{LRVVKO0W;&DPPMKp!G%
z?&MD|*<Uecwd`b0Xpm@8Fp*>96xLV4*$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?bX701pLG<p=;BC+p!b1U(Tf>80-`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<QLk^mk=$yM|$l1ynyN{N^1jU>=$C%-9Py*<jKm$VZ2(urSbIYwF_dT_)6lQyG3(R
z9vx@M4~^Xj@AI9qbwB_|gW&HO9WetQ(*y(g{5+Z(ZbHatraX{)_G?Q44()Vkh@`K!
zWI%uP<)3#F^uk=!cZhUoks~nz380p6{WU8OT^!WeZj}LqM1rgWQUI0!xJZCxV(CJi
zO}Yu+oKId<YAF0Xm;9A;tyT!!uY2|qTSJH|atpoTKn1>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{hMuk<l**VLmE=ryURZIarT7$`)^<#$7Xub=7KAxvZxo%KA
zjO9#Q<9TYB)e`aRSN|BzAf%l#RX0RLw(J-AjBxeN;qAt4!-dRKT6;$sV>uC*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$F0<dUxhc@7#*5wD^GMDrAU-
zIM+=VlY!|Y`M@jrsgp<^lu|<oqC@;iOY`?Y{G34CmS87@w-&zUS<cI!$AokaZF!)~
z(AU1lH>jpkMyfIx<oyt&!+=M?)IK<mRU{*_Zid?HU{y#g3ur8-G{PP*rt)F#A+(jt
z?5qwHoEdLPqO!P%<XquyA%ml}tEW8Pkq2QZ{gN;>KA(9Ye<G!Wd#(ukvoWzGc9m&D
zV=9pKN$RT<yvs&6vE;GAR}LW8!daok?;WpW)#d6tgCrfi)lTS#+Otzb7W4?G6fgiC
z1yVo&Up6tID!>RbZ1)$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#<cCuBbO+$(>vQ%pbt%=`5GL1nnT%V
zI)pK1rv=ArH>tjtu7ry0t%1}yO})&vnx}>mj{lK)!EB4F8yoZP7llI>796$#8Q;`O
zLKb<qh5|WffQ}fAGqGea5ar`X@?7974H5tv@=){$qKSxc?u`)ME=Kb5`A#<Xe2n7H
zTz4V)DIph6E>z<*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<k<$LOF-G1mr#1)NAR9Cd$*$s
znENzhfg^gtZjMBKGESj;pmi;njC^Y*x97(bu*+VEH7&QvOk9A+ghSlBi21jv{dKY~
zR-kxBNMA5-Z3^LzGZ={+E~n4BK{(rep&$SS&#K~fqOQYaW7Ir;g{CU=MNsu0dD3v4
zw{<W|VrM3L(n?M}9EsbTx3w~THAsS5W3SF8V+f*{82e6CCzCUHXMC(h!ioP-wVR03
z>@o?C*!!v|umDVG;7u}Yo2nnte#QZ53{2q0cV@9Q9qhy)Et#$SzG6o4v#IX1*(qXT
zM6ubQdizzVl~rqhX^_r%a~unhy66KLk!}Iu=<6)6OBOXSpVV^pMZf5f7hP_d&pQ^)
z<QK`Lq_UGuXtRI&;G{60XJ(btaDB}}on1Q`&&=b1z^b$*=$XtVm#`G(rH@#k=e;Ao
zi8lDTkO3hDxWkd(X3(-uacsH`s_mGjOAEvRkX&Fo^x)RaIOhR#>FL1AbufG8s5LZ!
zt;Bs8#t{SB^H>hj7RvhNQh-r)h*eQvUrN{<7h1$JVFh@1txmUF#Zv2)H5Abl#lliT
z>W2VjE0u%<C)2!Cug|UVgqQJjgCb`N><XtWIbpE{E#9*_f%deXmm4Llg>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`&<uzp}
zudCTTX53A36}ztbE$-Q0?<Vd;sOz|d(I@be-(>U@ZDHqa>CLiHumm4^#^Y>t^h%0c
zRTMV`O7Wkm(^GiH`limOgTHcAc!9lRw<K3rj|?retlT?rMfnw?c=w1n>T)~&uwal+
zdX<sk%T=Y3iIf2NZa!!}&17@^%+TTzbFuN3UTNp4ON9vP!mp4!WivD_=b6-2L1={5
zO{mj%4mJ_!t=ez<goN&j2u|eV<B<mbDXkxk`w+ERZD{azoQl)0-kFpSL}wIN969z+
zMP1?|ktQj!2Q6C(HbfbZLxpaVP7A-Ys%sxYE_R@c2)l4dWauXF+Q*$xCnt0`$ET~)
z9`EW_qlHrHhBV~Lq6~WO8v6*oK`73JL;dro$@Y|+Cxn)y;;fKNzL{!)vnrw#to6%T
z!>KcEW!-mRa_8mw%bOIx;@&xKck5vr%_H{6V<U=BfjLlnYzcaI$ipsyN<p%;fbh}F
zT83kvFZ|ZOHQl;w^>XUR(R3-Af3HV*vvZN&L03(<(+_jDpypBEaZ|d?!{IwIY>`*B
zh?OZ4Hm%AlmF<jONf%3Yz|n-qPC>2BeSiP}9s(g|?veMO+Fvylr2KgDkkOzW00@bS
zgraK(N2L3hQSaqm5o-LquNtgl#YyuN8=;_&Yoj7v)M{&BkXAL|t><YK7NqT6gi)u;
zHlI)v;10*5?5CI4XFn6PrNMD6Ma1%fX!IOftNFeeM-%!Dl4n%kU6&qUb1^ve_RG7c
zAn1`*m4l#K-~@kG!UbDc7egI7ShZo&Z+S-PAYpTnc#F=yzF|%~D&`4SlO&qR1Tox%
z30=S2o4PsQKqXto=2TPV5w-aHE2mb<5Tin?c!p!u6dJg33{iHxJC;1O{dtetlDOr}
zgHSsz%90BrSZ?A@I(c=pLn0bfVB`IG>c1}Pl3zJ*Y}%@c_;7J;TFi)fTr$&e&yBcB
z{0?xR$x&)ln6A#5Vbot$I!+Qoh`*K`zNa-InshRpF1Jn!+6!#bj@c<k`$2yF<u#g%
zb5MG_ZSor@#6!mI2P%YxQ~M*YSR5G(DoG<dkahib?WrvEXJ%?#zt3`RSt-&_oYqsx
zz~@WaAb<X15kO&R>*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|I3j8<F4m9WG(rRa-e4k~aNGt5TXng(@q6z(fzuuWoy_<CFTXmOS
z&=-)1MS$3)95^o4P8IPae|guW0M~ykCOBHEp}qcl+^582c;jXzn>oLT<-_oaXe417
zH#kEnmZwWlQ&da<-9Z}+L^9Ld$c!_=#W<)ghpi~A?iYrX?~_1{L>=fRGszu0|J*nH
zP3F7_39G<Edn70D=E40iktnTZ<c(so+zt14aAYS_7hqtxRMy&ovxm;Dpda9jQGx`{
z7~m+qU^Ls!W6l=AATm+5GKcU%6?96Nzjb!#>|<T`3E)6Q%Z*8&WVGc`EtWnE=s@df
zf5g)4Za+m$T_uaXA!Wk&=s7hReT_;2CC7KW^=g+AFg}omuIKP>`W;vQQR8DtQ{t~?
z$X<Z)v>f^>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<B1d!7U!i9_Nhg~521X<?>
z_VD>(L~fOn0o-RrV3M{Ea%8z<)KSwLrm=@VGw~+}GN#OD*3a_E>gDQRK>S`6T9M0$
zuU6Ro%<kayCQ~F}SI=*9BoRaCwUpwsKpYDZ4$90@`I%L?=$l2pM?=nL5@g1FwfS6k
zGDCkSDp~&^R>#r|Ao(qn*8xJ5Oz&DmDgjmXc8`@lk4S{@$HJ&>uDAQ2g`EB}kIfcP
zKOVsmnABYSzy$=zJntpO3`5Xv`!D%4SyfJMK<B>4AX&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;v<lWN8(>G4CQQ5+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(<CnG{1J-K#@m+5nYyLq5C
zVg`H6<T^K%X>awPX42_dY|bH^sh0N>jCVLih964<U>cvZo=gOxl7Qno+$J<E8M@+@
z#Dmn`qQr?_QO1Eb9N5*V_R`&~lhb91uju$J?<+4OmW0q@MzK!n4}gFD(2;XM%|KE9
z`N<G=W%oh2E(ODGC*z139Wc**WAgP0tS(GGV-+MGRZ-cuDrQvz-`=BV_Y^ny+bB0E
z%bNcF%W~Z@&ex5aP`==~QhitKtDTg`$M+|=IAfyK&F^HC<qL1c*ZkBz7x=q&3Tj&<
z7TidQ9~+{b(#I^U@WOOMr7YNp2%z#b!yk||;*az5wi;+2dHhg`yhEdi2oz{`=!{kA
zLHcKUy+!(>{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<*CrUL<fWW`L{~-(MHiN84m7bax5*lrQn^8
zp{NW7(kfYtzk>Xu{}o0mq>ylfr7~-)o26CXA1OUk1s??ac)Cx1@U}VaD&wR;qK#Q<
z6*$iKCN%%L_A6-ef6eZSwYn3M^>$DlPTO1?Ya{EnVrC-MH`^zl4~s8<j;g0UC_5g7
zz8+A)iYg2?V#WWGwp4&A9*0PU;*E`RjaMPjQd!FfdfN?g)4uiP7sfIB5k)hYEPgM~
ztorx0Hpc>@oyY_48CE63$nfPAYN9kqe)z5iusDL`Bd{e_;nufC(ApD;wb8yS86S=7
zmbq8=a;_lSoGM6b1DNSFR8FSYN+QP1vYM5_zH-eh>?<tjaT<^mE>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)<UTJGT#Of+8a`;dsbh5@edBB=SE`Nf+s
zc|tdM66^uTq|*B?%*)wa&;wQA!=&(5tVeBDcskQsPW|JH78#i>F<<DR&M#KYOBNO+
zQ7vEzt&wNSwZnY$X9v?W=-ib&qB%%Ri(|h7&DHPf705on50_(^xkxt?A0-L3HfBn~
zoP2aufkeX3#oMJ)VzI{9hg=*tCT!%}w&{lgKPH%V@f!NpgZQa0u{uuKY$b))&YM<+
zbv<d0tWEX;zfx>HH9+;KSfx-3t?As9AzKyfLV(hnd*SzEOay>&a5L<td|BQ<2zppi
zpVm8!e{<P;VnFQqucRNNc4I@UE(;9sh9>-cV+D6eqnwbryTR|{T$s9KCwI<vzA>^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`<o*U=sUc?)bC3W)x-2iOB?POwh7#{HE-o^V_{i()
z&ZvGS$2KzaO&IK>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`<HJX^RIeJI;zD;vM
zO4Xzxl?opQZn$2q_sPycGEnb&DIsIodc2EEDuP8_-Y2;Ihk)ejL}_?whbR-$O?LzZ
z_xj*A-*rIK)CXVrGhSxskCt#-Zf<12gCE?iPfWoKhS=3v=>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=<ru={a8v$Z3Fx3GzhLH3!a#hCe
zRT3|+FnZWq0lRf692FTzdsyMMVJJl*Sp8~#VF>J5GtDx<7>H)T761SM00)A)Kohp#
z(T~69tj5rn)<q_0Hrj|BCdREH08YL_ax?%G@SFVhE47;S@egUyyC+as)m$@4U>6&%
zs+D<gC8H<02w?He435?;H^i8mR8Bf=gsM#s90LOVetVz(QH0foR0ded%};?~0b1S(
zD|9d(K;~MayX|hG4^lPQugLzO!v+e-%jHhBzBb08=GiBk@-j@af)7~@CN|de7)f26
zrAHciA>-{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|<RJ<314g$ts{{+JtOfiJKDHXrK8*6O!ob&$+~pCM*lFxWpoy_2rk
zbPQ^%1!vq^+o(dG7u(vtfUbK?aF~h{eY5xSAU^|A9RpZO7L#6^eIug+ayyAWx@=&v
z39V#wz4X7fD2G)Q=J&*OQ<OwAX_WY%(9Xtc9bv}cbD<oj;tKONw=()fRZabxRa2sq
zo}H{j#p2Q_4Mf-mN4)+RCD}GR01OA4kB2=3&|c6ON5WDu(#cFio*?fpogla_VVu<4
z^BnCTkecO${**7=ocvShB@Mim*k`Iu<Djs{^KXD;<l&Vz^USq)z+dGTx3Ilg=mjW$
ztFw3ZM?z&b(z@;9t~-cv;gQIXc)s<eE*$n_1`;4xVN3T>_#%NJ;%BohFbcDgVg#(3
z9{SWx{K)Ww+9(pMhIjE8pY@ps5gH>UM-ptu-k8oRFeY|-LXy2u5)VrnE_dj-)OmI(
z-rTj%(QliVBx&A548GkB&Kw|?`^OCl34<uqu#9iIJ3GlBFLyK`e|Ngqeljy)sD5ZP
z7X!@-AGbOdmwDgYaPABn25!?qTaDk24qGYFB(tlwW!hlP4_l*uK%jp40g+Yvbg{Hm
zcZJdiy7=C-5!W?Q(*UZD{tReKd@vFs9=r7YpCYXwq6qD_5IcLB1puEEqE6XjICxD`
zYg=S;?^6n#pHl|h{HHqPGs;g3j9HPOt^hyMj{RA*HdsN1JAOnfS-OYx&}=rUohc*J
zs>k9Y6*$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<JS@z0GNb@2<Lq$m_)&R!T32Zp8Tnv6o
z?y}@@6>{V7G9Ks}({W?Su<bB=H8UG$B67o+*ZWdI%PuhE15hZAo5d)EKrxwB)#pQ5
z#Hu+3s;Fu9-Et*%iiz%9j9<*`bCe$#d@0*yr`Xm$OaTq(O-yKu=PLMM{yA?I_m<&$
zxSau5Kio{zLOEgmGN5M#Th8pW>rs(4dOuQ*HI0wGVT8q(-%mLe@ump^Xq?=!<9o*g
zZtx<hwX<9KASz=>Zj+xz_P2X6{ci91#AuYfVvRwJYB>yEM52DtCtxAoJ6i8~Z*s#I
zcsy6C$or3X0C)X1dFR~2|El#AC<xSF08!S*oS$0kD4+eC9{aCbXU0V;9%7+(!{Huc
zTAQWuzR36b?<g;$tJ-OPs!=d4qN+$ts&56$<n)_Jp2|6+({NDj>s6*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<TOI#NMASPN2N%sL5QSMa~j{erD9?{DIsGa`;WKMz`nSkr!o`P;HVkvezAU(h)
zcR>&g(LVNpLPF>cNJ*1GDWYfyqaM^FWbG<Mn<L{Of#-_A=9uuSy9f-X?`q?wt+eG4
z-aEN{*0Ip!?%CcTrzO}lcB(sbj&2YH1wz7^(r&d+splh-1j0|S07hiIXz`E#5;bh?
zgM^*oQQw<he;S{t<6pXYQ5#BYkw)?cC_R$HtHeMtHYv9vf?K!=#C2zN-7W1Va^mu3
zA{#&5*CXI)kw!d=A9GUZt_$<%Ph|10QPB;?<;tFi!0kDn2rMhurNFo0+yR?qh$;|9
zmW5tyg^H+W+hs?29WkyLXWPSBb$0O2qD<kSO+3!e)=Q@{6iYk@am=9U`<CvwY>&k|
zKn$^<r;L!aFxwEn%qeQzYvTWo-E9@xdmYa_<&~yaN}@JDvm!wk0UW4L1+X%_DK<~G
zkfLGylouA?zu_F7TLFufR;z;rx5X43(WQ<6_pkl96OGdGcx$RKaR3xHF%v)y^*YSb
zL;OQ@SI)sk!$E`>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<Z5Z95~xgW0>$o_!IhJ2|zu82IUH624jfcvt^-I%N<HjybK`Xhq=D
zs*H%fi7jv)QlSBdb}taKE~1<DxFP{n|I4MXX5PAXS5|i@Mb@N*G-RrkkaC5{sK^^E
zX}n^tzSp17_#crhn@F{<-1LDO&~M)4ocda5X6ZE8owZx-_>O09j&~qjZTmj`n0fMb
ze3r?PQGK=<dvQe}ocFAe*jg?RddsZZ+76&s8Pv!HWA?zZ;X+WR(RR=3i>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(58<kI1I##IZgp7$7`e5;U!v}43+U+
z037|04ga{6_j7$xY=?E{JDttRa*{}*bOmWT_SRKQvwIxn;&dNPBTy=OkD&S$O)dB2
zKxGPxAqUr4c?BWqRn^^W8z_sDT!%h%^YRl24DW1D$b||y;?><FOedZ$3Ww0F@JB$q
zc5R)#EBxa_t!QYPXAW;Nr7O*y^J-TS1h;>lJ6~*pX%#`9Tr*E&bcodT9qsCd(-1Hb
zhi2H$DeoQ&f4PmZgy2<U9Lp`Hq2WH!;~d@0;UU%?D{Q@&bKMEwmI)tT!~`3Y1=lRz
zz7RtFj7mpISBY}~!bqXXb-}dWU_$vJpBlh07x(XlW*D-djxLy<=Za>+@GIQfh6)~_
zUH5hTe#Xw4wN}ltu!*FTw%^m~bY!I~?uac({{QpDXpiMQ1s<CbtSJwiJ6E7czW3Xx
zAjqbAt2B;F<t&&XW=AWc$ST%gm#An41<0kIA^Nr+iUP;>P&hV-aHquJUgr4f(Hnfy
zm^L7vx;0gZ;kVQqZB3ls5z8X5w0OB#oR&HfAoive5L4PH{Zsnn_|AY|R9kkO6zLR`
zgizKcC)&R^g0kqlB}RVqky+<bE4ETgWhS8k0=hQ1sXZ#YYBHMtDy*eX%)3}ok+G&R
z)-aVlDwS$l02KajyvMD>EWcEmI@nL|pW#*IFXXh4K>U6Fcp+L3+hB<g@eC*ZcQU6?
z2mi<%TTXzD+n{Iq&qvqBwlO*Btw|r$u6(|fPsu}e1TEh6x4d8gc45#58ZXRF2VfD~
zS!R~`(2E9*Ul0PK+knBm@5G1PVf79{%FD@`0_@>x5uUciF?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)<fa<H~y_Q7a1)J=3<X#jE^#ww0Fk`E}llztp8o8okm<e~&bLQC?)2(^&qh2@1r
zvM_s0kvtr?@fDWSKt^<{<ZJs)P4y!X<*;nacux1m0oh+~=aVUetTCQ^sXs&M0U9-7
z!nD>K`{5Xk=d{U9gp=Sm6!oPL>6<t}!4qROFc;;u3?@prj|Txdh(@t^H159Bo9he!
zsI95I>qc(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$QS5k2<ZV-;9mNdWek>sRm$o(p^srH#(~62iq4UVh60UTAx*bT
z#^VFrzW(UT^L0uiN{F}dNQuqA2{&D_ryx|)cg<XDI7Rpklg>>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`GSV<yySx+q`wViU;9wvfv-PZ=utW^(#nM@?07hvd^_i~ECcUlGe(dw0_H5$k#
zy!TGEW({QkAXyMXbYSAHoH_1Cv{pXTW_Calhzt%q3$ynKy^v5WqRXB~T+(SF*hnDp
z_as#Fs>N6mg~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)
zx7rM<uJ{BnoXbG55nXXbXHizM-JBR+csK_pdBbf+Wc}_ewM;_fHx;AB3))LAt?zs|
z5RWYDrUipAvx7{|18%Pt3kQY4hXne*KTAPN*Ur9EN$5~dDj-SIr!cQ@UpoA3>v}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@xbO3<z_3em-mZ3}I`g1ei{R_^O^1EuPXyr*+(!
zeS?Yt9n&Kq-N$-+*`7JkKLS!|73_Y1<q(*j^NVoqz@-Gi2)r!|HgiV%>8h()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#*=cmy<Z4<-6K;EX3ImSIOA$w{=2r
zZ^?8TMzUD;&}{;v;ZZPvvxdAg!i(8sQm9cX%c8u}`DkpBq~y{nPtj(0*(|8ISI^T_
zxT9-fm?{JA_vl#yhll(=P<J3;K$y|Ru=5Ck5V>q+N=H#$1{URuG=C$>?zyqjfkP9+
zMy_WlN*sR!Wfe{f4Bpn}1Xn3LLAw~?(Lex5NVU$V##(&v9~eL%LJ0ML?5~Ub3G;|b
zko6Bx<K4l<a0-F>HZ!b_rK2**{s*^#pw#<N3dA$VGNCnPRy>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}<COO03zXB*<6J7^9n6y*m4aHD0sBC6(6
z+SDquJEdiwE6V}Liu$j^REcm&45<AO!{5DLzhjRaNVsKqH#?Y0G3Quzsv>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-IF6wRJD<b;Ai$z=Q7ZQ
zEv6lkW`9Xhnv69x6HHni8Or!tzB-pBn(ZPxq6*6aP>JjzDjdFtNy1CIlg*gYDmVWq
z^XOY?O-{F_304WL^G;Cxj-*hM)tGMEX|pZ+%E>(<Y!vobICeB8;k8~l3GO*sD_DBh
zeFmQ@PYq+cc!k3ZE&x{xs1Yyys0@5kl!eEq4w+GeLuRSEnNauFXG4LPAUW0s2fzrt
zqc%b?)yD+GGOlK;CzLxz_yC+Q6NPjW)uMq0rJJBnF9M>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%>d<UI+&{o$<%KtB-(kCM*)}$uj=4+m6bi%zc
zs`UkKk($tEO}ks71IFK{m06{wpVnd!9Ddl6uy5F-y*5q1O2ltk4u_>C?xiTYEI}@x
zM(MrX2LiTvZkW;1tK~Kwglf<2Ju2i5)$RJu0~bGADb!r;7t`ztXZ@nC;=p&Knd{ax
z(~-<NyJP(b92vW*?7UY{KJvJorzW8eqI1m@HttnD6dxnPf*wmW8c>G5s7RxLL2B<V
zJlU+Q`RBQ|k`mi;rnfYLeoCj)S`I$AF8MFdo2B)3j$!*<t)@pbPp+|U-q1KzejFmQ
z<T;F|@ux@%N<~$q_FnG`-C^T-&GFz(MxlN=%qt_od(L<=gwVwA^g+#O;WVEMgk|*s
zQP>S|bd;($^Q<Wp6HU@QGPPUl=lms5{;^^ecDUAs1Z4vnz6~zsVOgwO#T0;&?06ey
zM`IRcjK<Xzk9y6kbja>awZU!CMd6)fjzCCyOA1ayk^E?psX-Sci}C<sh;HP=i?^z3
z4gr{C1ZIr_h38u-or}K+A0y7pF%Z>g01Yy$$;4$|LM>YEX?L43I-+^Sv}|;B-<!js
zFFaruiQ8}`S)mrb4cJCxy@6kcwk&B)vZJddy%9+@qdJ2LGC24xqc4|f=q6z7RU`!d
zAuUe)pP9;!XZavR`bQ&%jW$aurWJj--{q?d3}&<FF_HpA*vi};k^WI`K|;-GGDD26
z<`H%MM2`hJj8@qysWar!N!8@+oY6+(4re2f$?8wcG|TDHg}(HFM#u$3G|Za?YrEKA
z$pItCjjVU-n3uvRi?bglM<y<xVvpROGAskl0peyFDK84Z`*6U1Q!NSH_}O=8t%Srv
z$Ov3^HA0czDZ}uJ(`m$|yEwb__^BN(<t!I?h=l}U2il)+Hal71K~|{Qt&|KB#m@1>
z2R`Z!NEH4jjqYtsR|t3Ed?Z}1N9%!T$DDhvi+feN3U+$-;9H4c)OkoehLMR80DK)n
zUoduET<zH-FvlUsEk3$kLaT{dV;;2<0fak}f(FgPG56d6Ovi8KTa+}a(O5j`chR1)
zYAO=tG&!#XJ^7!`OlNU^Fl&(Fc^GcH#;#ln_?-#g;#|luEmxTs-U*+=c2HHHpGyf+
z)@jb-y>%d|-b>S@!5xG~z7L?Ctr;E{Y|{^;-`$XXS?>e*QHpyL%}<FU>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!Hl<Svh+nbkF%frEUeBfm3KZNgtLem&b-DED@_1C^Yy;@tvh1
z8y`UtRv3}HiydQF>piL-Tha(s0JGa{twO{u&hTuCx_ZXnKU4s7&?3{_65Zx;H}i2|
z<QV5QRa5r|HsoMFyUTrSTNYpH-5@(Ir@jQ8r3BiZ-vXk*e&3+C4YT_!CR`{i2=3Jn
zg9;y+*OvxeVet{&g-jHlq=fTiac22@&&NNj!HS!A+xECNW<=87jAhXms=jH**WauA
zikLgJ{<2nxK>(J=hsM!j!Q8L{<E_JEkD&W)8f}D`lPaDAovc@7v$NV-;rcD&;FqXN
zF(t%c%W`xh@oGo!AHnn9r;GD8g3@Kem+(KXPun65a|f0bu%O6Fzn!Z$qBoYHRlVV=
zoqe1=wK3L1UhzoL4HH5ba<gOMe>*67D@Ny@?2cnXXF0UXSJN2Zsy3`Dew<h;<!rpR
zMmc@-(Smp*H_d^p3@MuNby|wdo6-+b<|U}Z>?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)-kJG<sNKkgK2v!JLo{E+j5fQV$
zA@dFE`=y0`N|yNa!2|UoQscz;<xEo_s41@47p*b?hFz}*P0)J>hcyZ-@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<}
zG<x`hu*VipkC<BEwEWM^O&fnv2e?85Cn9z>e+cE_v)g)&ExMtyG3PoSQ;o)N+Jesf
z&Cfl(#0PF;^x^o?Rng#-e?5=tTHuSg0V}Qi{&R%m8g%0u8isBmB-v=<k)G29y!koY
zbYOt%tFwh#PCQ?^?hS3*X#w<`Gg;QR$BZ~3h<FS^8&laFC;5KWMfIkM8R1VfbN{8S
zwVxVaXoK@q{RHK03xuaL8!+*Fo0<;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|KJG<umrhHXJ31JqlU<oABT1sQZ%;1@%4Lnt
z03~g88#Qs3KH*mMe+CPx8YuWM$_M28ClY=c*ws+^{LzTTSwaPc(#6^cMP`0NJ*y`b
zX))eC`=uQ5(^SqnEd@E9zL!eZaDgPRPuuz4v!Ol;@n(^L!&*mQ%V7ivl^_p|6HOtJ
zYjmgMv7m#ulQ)S)k|fC(^2#Wq@q@Ig>g+UJP=p@;)@mpS8Wa>T>FpYrCrKZvilULi
z&~;$os%fEQ3<{1Z16=Wp3T(Qxr<k}u{9R}BqY))X8VEy=hlQv-tH1tE-Uq7w3rO<F
zBrPt=5(!g=&&78R9kcH6nWFu71$qV>B#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?6<fAv6K`58S>GGBcLv&oQODBCqk=a3t9IN!sOVe(z%BQ
z)@%%gAd%;X>7UXb3xk0B-<L6g!cXvSMcXS|z~C)pQAKt1o<AJ0IYpoVD8XnZ%F1O|
zimI9b{E5p`DIytj0H*)|22y$e6}@n2K0RS_Qb&hkm_H)GD(X0TGPf{I?D>$Q>`_PT
zPRk#MbZZJiFf9NOTV%7(@_n5}fXBNIy-~@AePWbw-Lm12(9_blH*f;G7y<fulPM#{
z9z8y9U<tuHo>IxH20&L4H*Q3rFkK1*?a!3F2Gng*^T2<YA0m`=fz}2UT%STng)WV6
z1zsI`klWx$XWKxfaFHb{+J8PW#e3ep{STzZMc96P9!(RKxw_C~smLYzp|No>;=RJ^
z-FPD9cl|3xk@>PxpUhYC_|Aus^uku|wMmg<HtZoAGxlhJS8$OX9t&kZ=;7ji*pLJ?
zFRnY>>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?<kU<|H~DHH#g67FS$yQ%)|(U2(d@8=ztg
zdY#l>a!YKFQ932z_c6E(1FM95CLsAb#n3G#6+5G3#C4Y;DDfzFfu(M4i5W6ZI9Cz!
zk|Cg#=H8j-OzjSzHM^BgWffGxUKvqN2v)^^S5EGK;j{6(Cpt=G@@ir`k}(q3w~<ob
z+}{ujEuU>NT{=aaVaEl%Q#5LzYPsO>x0O~2Tt39OYm18a(iSwVVXR4LP+o<SBV4J8
za9Qu+fNz?u$eoR7w2QA2GCl^z3|YR0SZr+RprWf$|Mr5&faa0K;xAo$G(H!<#cRi<
z^&a3SWBkI@N^o>0r*5fe<s@~)LOm53;;&c7E}wwY#S`7_{wbwKKALQ`VsE1#-b-I|
zs+pzsF4=4|mvf>&O6d1SAhy;KG&)$u0%BfcEfIx|xIEe}f8LdNQQ2dLrNI<vEKLAu
z7)?=8t~M*ip*Fppp&0<tGWE1tnO2a#>$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{m10g<PNiTkMGi-E(I9kl3q~##7gQL+gAUS
zY>rud&cSg8Bn}qzg?+8knR(gbVA+R8ESL8I6i<kJ^=4JUlTGwG8gK*c*2A#2P_=x}
zERow(>Rl4wTrWk*^=1`T?=oUIP`4nkQxm?J7BXbq_1=9VmR)@4bMg+kCwTCy^I!S4
z%rF21mae!c<^aYBh>__7K<xan(-ajPkrtjJGM8vu9FK+egM+rl3k3_`V&KkHNep-d
z5PRXKK+yof4@A6SKP>YO;}n@lkfDnGVS4Bk?J?PmGa_qVz!`l5Hw5;7Bn!*AQYB)N
zQ`YVq>T`rnD;2252FF+PegQU-+56&<a42CEHyJx2T^`4h6|$}UVci#^=NQL#h^^;l
z)4K9r4r93cjnDRc7DSpFI;giX#<opS3&fa0wr_*(C=JYDOiS}YB$7P-1XiUvQ(lWx
z)+F447wSK~-gPSS;+&^DoHeV9xzs}bt^podAzXTqA$U7)k3DnM>@ylXBWWFh;8-=d
zSf1$`F)?}XXoE8e6^V5$!$w*lp){jy{H+gvta_@SHxy-ggnXFq2XTU~x9iym<DFNO
zWMGz4?v*a^#atEe@2i(Cc7*%MJDfp_{<5%@*;G?J&`^)~IVAj}o5j_et~-Q!QDBa<
zdGz{pf5z(JF?Bc%{o_z0<Jqp~AN_|YF*$EKo*bQ7+RMcNMnJj0qmE_+ZQl|O(%5MY
zrQZ3f5P4(#;(OK0R+e8lXd$${=hsYTB^K|By(0&VUgaWFui!f?FVsEMjZx5beD7T8
z%v9___{pgN!|=SPg*{Aq&XkgQ(&);vyWDpWV|^YEFPd(OS$MX*mR&0uGSz;gwHi<K
zig&0Sa*@_%QR?g@g<k?EHo9f+KzUh20u&&1MVm8#G`2ZG2lLmLEin)J`l!akTaLIN
zPyh~@(jURJ_`p6IGGbUh!u7c-2u?UG()}e}hFtx~B&?FS8CcSIb(Vftua0$FHf%nD
zRrl~vQ5XBshR9A0Od$2Ne~{5nHdxf;U_tvGe(%0RplU3?H7S4q4IM3T83KbMXyC$8
zVhHa`0j)0Fi7{ivp^tEG8N}jaV-^62y+Y|e%XS{bsDjCDxKxC_JGI}1ao%r&o%z#!
zf{U!!5uV1TTy~cAsPbL6js$FWBQqBVMUb7Kwx;wbNAix?mwOQ|l!g;oBgag@%X-@R
zkEvotE34eUAaXi3*O%p4z~Fn&73ky};zoB+X##gk(Yr1Zmxo2*Ax|q&8>x<bX+w9O
zW{r8%T+bDfy$kyH7h|SH1iL%=?#6crWVX^XGN($gNRgp3&I516Om_%noHFU_ltv78
zP48qF8AcFU9ia>W!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;&;8o9<K|Lv?Q73K@swT
zNE;xpvT#y=Bw7&S-Ze9nPj2q}SI6XO%E!HGA$GVmvb2K*xOfwP>J0cz@O<MqAtS%I
zN?E%r<0AS4FxUf115J0fdR$LXNbXKu{0fxq`2i|uL>G#)_=^Iv5obWv_DNmCKAs0s
zBKPR8gmV$$ISW1(reNGqH(+|`(OZAmSGa1(&uR~!P{3MO_|HE?6S)f**3$GZt6@GM
z#JdR@<F*hlsY@O{nA7Wk1XLMkdj+D?)O#TtNrNPjlc5Jc9P|z|2b0jR)7oq7%+IMA
z`rdj};JYET3|6)SI+3!xj()JJF5A|(y0xCVqHDZ$4js&g2f3@@@>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)WIfDevd<ze>gjW>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<Y
z83!?YD^)whEgo8PR|3TrMYs>&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#&{_mALoZ<r8y&-+2>r^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&pO7<I^$_7Ixk)IiPJDWt
ziu>sA=@`JILMCo?_SXM~R-Hy<N;-Q}+{1qBD_`4q_sw&Fq+}?Jt)v32s}OtEcNi|3
zK9vsfyIK>t#3TKX3M;Qh`AtfNtT11Y08!|OowEcl5Z8RDIUqU6Wlu<Dh)iJl>%{<o
zY&ws)0O%*})EmMLRFKTc|2=8m>i=SH5XFWMa+#VPYSpH5Jk44WTsUi^cS~B?D&X&=
z^M2N28$Pk2N{d4VT+qe6sX)kCGOlfm5GiVf?K++0fb+<a)?1^!*p#|dr;JBe04vZZ
zH41LgIn?PK>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<Q#|aj(e}n8Z=6VKDtz)k&ifS}
zwM|(|&J)T1Tet7@k{W8R)m7xcju8NbsiQWwj@1XX9lZV;2upB-=5y~?&~@<QV&{yZ
zkBslPtN>~0x1rrvc~pW?Du1z^@##i%t=u^;Lp1qUBRK*Y2=q<c{Dcwz9Aw9vkX*;#
z?lk`#9hBZ!AL=UIz26r%@>p)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$<XEc`Qp5vd7wm*=><LWZ_XTCH4c&Yf~rA6tDzTDIbN$<O<nSyDYxiicOQo
zonCFh<8MXVC_+3M-#7byC*%yR{B~gQvj!LKLdjxZtkBMpy&DAD#k+F!wa}v*FwUGB
z0?0dNo+zk&m2busWzzQw3#a86@cZSc?SsA4tQm&@vh<k!&OjZV9`2LP=pdlL)x(Wn
z0tHjDtnXTaO)p~B_QIYJOSg*Y(qYC@jV-RdRzh+^reDt9mzlo}Y_J92svcUkaejB*
zK|KqKVXI>@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<qg
zdCbHv5Qi!H-PKR<9lSb_+xEv1v4!Pu|0G*`Fn(%@*RMLth=<u_p%{pCu+sB~MRa56
z<!m*U^rA%|lH_lm8mxQ_|7tsyofY^fQo#o`qG-xh)q=PchKMx|?dul0*J*jF^NxAp
zxN@XH)fQeNKDQqWf5iodOK;dlp%@Uw`#viQR@>{nA>r9@UVuZCN8NqvufLvp%L<JN
z-J)ci*301UJ(oH_Rn{u~B-R-yW`4LAZx!px`$ItJLJ}}X$GBd|2I?}gJ<FyW=CZ4)
z_)qU6FiFvq6oWaVYb;_s!eu(^bx*ER2@bH^Y}K8yPVL<p$mR!Vze&3*`s2RLivZ{`
zZ)&lpgCQXk1m(IW=uoqK(W%>hQC#z=iPWdz!20Qkj^&yt=sA$J73%}_OESgeS`33q
z)mbT$qz*z;JKAD&7zXBG3NOOy<q#T-FQG7*VZuCI1t1<OD|~<mHLp8c)X5|{Tn+WW
z`BV`!0<{%eAVc$@TfM=$+lhIb?KWWABzQLSh~YC6J$d_9j}@edvZ3+v=}wFTEZ)CW
z@Ja6a>3bPwOUfL8Rk0{*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_fxSTIsLjUX<aXQJTTe#%M2Wwb5HgF7
z&b-?D+S3lwwo~!uQ-J*oe&L78Z6(}@af3Px3XnhxuQ=u;ggv;=u7*@{{nG0ljOsd#
zdoK4E#DcI=;k>q;*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?<D
zF46egMSChHL>6SoPz^(D;Tcm_cc;GKPu0eZfc*5CDo0}(IpDgD{wTx->L#zmPr$e>
zjWdDpkH<?j&$;F_RaXZc|HFtJ=&9>GCksy$iC-K3HtarY>nHWIdo_eX%T(TgDe?2l
z>pY?}WjFwq2Ifl$PovhGuKX|UB$ap|&@y6lcs=2odyExE9t$C>`N3=w<iqoy+aovU
zAtrX<_DbL*NdpiOtb7#POh(&c&Yxp>4imX3d9jNDdO!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<MV*Dpc84s;{Pj#pgMS{twTzBu~;k(wR)u{a8xu+F`b@
zWPk)h%4ie}Yw~w{4K6rIb2rT9Ck46VE$SzLJ*u>{^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^<XuwJ>5E41fMQ9<8@R1EmCB3@BO<bNk703Q%o>$#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<UTdP8Vr!Zwb~x;L{g8yvpjhB$(FHR#&LM!lZ$e1oJZh%
z3~o70RTp@@!%ij-n%zXnTJYvsAG=Sj`!dueE&V>+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(f<xOfR;<Dgq>O_%4R<4X%_su@r%H%m;1MyhY{A^1dK<#zL6+Dv%jSk*J<pB
z@5=23p1{`~72gXq%0AWd0^qsf|Lu$%h&U!wD7tW(H+>v!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+$Ott<TA_D45&*!?iVtdmv<?emU;W`o*+q&qCc>yI
zc)Yb2-|^S@kvtjGX<e0Z%l<-(xmefC%=;pcGMIsGSomTxr&m1sNr_@q#IE7F7Nar%
zS-e~G5(=(6#=GCGq)TvA$!PySXZ%J-M)MI+jsaCf$qck48ta81ezjma!IBAf=^6ib
zAhzzS$x4wq$k^ZIk`1v=HOwd2K?iU@78+~Us9UnEjzj=3lDcMO!l_0Wz0o-L-H5v(
zEGwP;i_g7*BB;HH3AEwNP7wEiongMksP_VGnsBW6d{$7{s4>&e|0E;ZD=H6~Z~HIe
zsidEBY#s+nFw_g!;JoNIdPzV+f=}2WLu@U?QIFqYWLDW`<sCU8hwPTqOF0z!W$G+M
zcxT6ju1Pr_FXYO#v%0-nK0H?iWQ3Zr(RUyLgtfSIR+ds?&tBOfjM$Di|H6R4L-SG`
znV|&$@_o^ySNTo-pQS6FI(#rErkaU*Rk`ieN_m!*a$RFrzVs%xO8Bila2L&rTe0O&
z%3}fKl8jDQ{v}g{wKF(H0gv>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=W6VkKMBU<e{E~
zS&bM?R=Gb8A*a%#H#!Wb3>0bQkL!j;g!;$_I_;Y4heNOaE?yk*89v9;*R96FDkOHC
zQ4B6$TPkgY-XWuNqn#N<b5@W)YdYgUeZG~EME+L81$|VP-;&nDl|3i@vfM+GY9@>3
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^!by<OMB9JS6dBmAOkm}z%NX(HU9VC%(fCo57nW{Aa2OetCEVp#F
zYr_Kg*F3q?Ge0PM>1`}ympGSj1Mo8!VRcc=HK>#`<O;kW^T=$OsgB>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=<TYP|hmnm4#uIYB
z5up-yLmgr}2w)LE4-YJ7mYerrD~c)m3I3s<oJhtuyn}+bx$(y0F!Le%Hk}(I)Ld@O
z;rQU4HZ#D(Wd*lT=MW3esP$3${wIBv2?mMo*bk$X^p6=mu3Frcm`24sG0=V1f5&Ss
zPVkKh#M=H+P>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*<iw_*$P4E<TPL<&9RnvAMkXD(Hg{n
zH)#s(Z1&wh8qZZ^GgYzu@enC))BM_HYat-MDKXRKg+(tk_KtLM7XLT9D=o4C!m5$S
zKDgC~-xyzrvo2QoO`cn|kI{nlI#U^(FUT*_#2wE>Qx#wq=l`1vdmHYGXAmBIJ(%WJ
zRm08gBt!gzygKm7c<W^RTJ-6Db)p-wr7!y4(yk|_oce{7ff(tDBLrVHvRM1to7xzH
z8Z7<1CYs{bhaz`+X!+8Ln@>#hlU~ymZUXdJ*L0mIv3_XIyiFM;4m7O1Pg9iqv=*FA
zA`dESasns?C#ZMy=lhlP0Ry0za?kd7x`AIoQW-&;Mt0c*J(`(01g+E<8R!WVV+k;A
zg<Que?6K0Cv<fj+8K2A=>s~+3NpiRT9Y!g-5d}%M4q3#ftrW{z|IdQ=TW@1rK(|Gv
zMHr%XTrk{#qnn5gtxm(YZL5NVx|?dfbA`dDRc!j=tZkAQsuO2{@x_j@THFZ<-R$x>
zM0+MLl<WI)8C&l*N%~3$dnI`ko-h0t0B6#(#hh4f{ue@lc!dkiE?AOQ<axLJrvO3{
z<X{eud-l`?EWpd<Tt$f92BVX!2Za5JlnH}>h1yoVicg7ZqO`H4h~Se|ZA##<s-#r;
z-?2Q~@b{|mG0&u(B;?XH8aG@6`w|TFh7s1NligTyWVrxiEV#r1K@{|UWn&1poVG9V
zLJ*4H#E!f5vx;ZYQ(Hs$N!Wm(i4~VPKy+YHB_bj3qS1uAirc(5yF4LT)(2L$9SwN~
z@ux7t@RSx8_<0XSZI^AoHK+7&rJf@NGEFKdr}S!^IldezXGF1Dt`{X3#`oss{M|Ci
z_u^!o*IXON1_{$#!;d3W`qUhTZ#jRcc-16_jX*@pxt*{OKixd)0?9ZaG!&sTq%|Kh
z$@+!#3N@}?3j`Tkxfm$S!t-_)uD0h$yVH3!0rNV|Ws&aTfm|a~-}(4P7t4Pk*Kj=A
zwG-RJ9gaoe546eK?vIA2zVxTHb<aAbe=|Qg`8+`Ze=@y-M}>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;j0S4Nuk<uAa@mNKdz!WydRR^9U7H{S^UsW*GG&kyZ1%L
zK!QN)H_G_HG2bdNT%N9pUF3fCGgLDeLrMMir@3QMwgJiR>h{hHV<y>BGP{0k#rW89
z9YjNlc-_x~MU%q^Wdn{nQG{Kdggrz(X9e$-3+4d_D5VCW<oITljw5J^Vgt+0Iy>ES
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*4YglxGhts<rzPb
z^=S-|S(V>V0-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~<ZFaK<<p8^?YSQaL`v<NvSALTNPG>q-$Lb<<=0q$v
zN(R}dv!tDjUfUZ+v61Nb<?_>E&p%ogg@6fp`hONYi^ga!_HPk?sdE3Gks(S0J3F)`
z$kLpIR7r<wCr7Se^TAvmi?%sAt}$ttf8->lzH~_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(^Be<O-L5L^siXt0aKW{K^9uKCp$~;GrzKy#rWoJnSHwN7Zb#;BiR$d
z;0q7Ylt?$|4agXkLCKnt38uc<aPO)4#8y|n%e%@I%h$6xN7jqK{~iK+6=mL@x%oAZ
z{iiBOAd-k(aUIcmI?qQ|!`2vv3kH6AN=f+kA}SXAX;u9QCSZdqvYgqt3@M5uAh--1
z@{!rm-@huFH3CeI^%L+>WEW~_V6mT(7{c}6Xj@{<IJKtWpbL))6*#R}RQ)>oE67UB
z%JP2PsF0H-XL!*U4HuX2-hUpjYMtLp|E10jM+@=tB;<MGi$e}DcaEeJYNGIJ{0Q$b
z43Gjpo1Nm=46zJQlOwP9ARI~g_E>rw@Dx?0-1_+<+h?q~*Q<?}xJid)WKGuG?!#Uy
zs#i$%#4$Z#dbA4P?_O@D(OXfW(x@1-B3e~eyyg1Sp5yC9@+@N=xdV>!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~<Og|~k~(kjxD29Yd6O@H1Y7A&qSkr1*Bq|Fae{Qz0MY4=
zrqg3Nz_{^+Q>_^!!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<V!HSgi}b|hd)7kXh|SW}V4;-}
zS|FBgbS}Y3FHf}_jilOupq{=!&Kf|&?4kQLm}}hFK(;ZBl)^Xm+CeUbe1=<YLJ@oT
zB0%6z^H+qjlSCI@q|tXZTXZxdBt@(|uW&r02#XI08;W|V0;{fF`x)TIRKqy@Gay_C
zTs+Bh{p+EvcgO<?G~rHQfyW(C1{zqp>(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=)W<yU4&JYONFuFK)nj@GW%zp0^_8X<dev5X=HjJQPtoC@FnvPesi=)Z5!VI
zmcgM&bwI%9kZ{JsnDZ@!VQyF6G=p1blVjPk8GpKEEeHcM4%*(hO{gTbis_M7k4^%#
z_AdfCWEm(>fJmOBg}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<kz@-M(-8q|1<z&RO4HBxC_Wz%$Tq|XjkVr
zXQ@eZfL?;%%}DXg$7qWYZ_qNp=Vnj&meY1}ZzI4>*XC%0Y5A91Bus{cIuLYdxI^RZ
z(8;s;S{+9A|M51y$1h7}C7B!s%(b}1LAK|9{6d?D3Lg2Pv62?gX60d7J%FI+i!<xT
z^lH7ZF|1F|MSllH*}aFXX>BHwn1Kt6R)1OP>gIGVa%j(_)Hv-^Gn|;V%*<4T<%1;}
zctG+o>zoQdH%|!8KxXco+_<m<#*#*?xz|szNvnn7P|DZ-^*Gc!tqo6U8E=+N3?Pb(
zTGfNEhi}a#;(p5_idn)g|74TFY(QFKfvAs50kGc|B`hw9zXZun1mw)z3OwSuCNcZf
zUGUt}`8iBvFR0z<uzfpcIU+#<2=hu*cXVQSA!Hu@1d$bDg9Gad?yocq_~0Wb3&iQ^
z%J0OR#(LU`cxh(XsGIVS09vA_93~my02O<9{MlBgMcXP(>`$I^rS=i1W=<fn8D<zy
z0uiqAB}4RijsKDfoKjXnj(mUpLW3<~gSQejqQ)gkqNj)4(GHxEjWXTqOy%UKwtWT%
z?k##oUt49+M|w<SUA=jXp+<&2E2N_)966rlWNMCQW8gTn1MgPo0cT+G%4C4XKPGsD
z0E&L1lbUHEM3EmJmfx@Yxk~v6Q;nco6`F+^2(F%^9;+L7hy$Bn#kA0`0c#Md2M6+B
z{&Ql|A515{?`z0)P)2o(?zQsdJ|l&<xy8*%%<08fj(LhRfpdQRxchhd3U-)oemb09
zGHH^4(~}n7xzvR)Kj2veLUzaBMML}M#pQB)Kl!TpD%7EpEW0g%dM3&mMwD^=4>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!8<Zl<{EafF<Cv)u*DEYSsS^X?@yiHkh)az&-sWXyP9whT6Q7w<u
zSPXNCLVc1svFlx0WO1Rvw+s0^aEe<uQVpdyzhK9xZ+XqxqT)YuXqK}~%%Zqi9$zh(
ze&AorLrBX75NAf9mPlHE#ySeufn3#wI$BmC_sNH!eSf??Rdh`+kam3Pekuu~j4|lp
znGW8*I(4tynq|RoVKs;~Lx1rF*_%EE<co6oWzq7buf;6-YUaW6d$WFY_+%)RvM-!O
zTpp#R>tMNhdXycdcjpd@T`+Ft%^*U3jri2EFe`;@&&vaYKbq09r4BZ5Zgbo<<M`{(
zzhIm3=3Et0#E@v?3_QA@PeN6*v{;Z&9>k>;zFx*RaDjD(wWtJ>Vq)xQ@B``kdt^E#
zGA=h3fzje04-!qvzRtnhR-f(3ML07N+}m8TyZ5|PkGLNG?Mol958>krM8x2ZGv<h#
z?(nc|?n(!kgq4+{A)g3tu{iGl(;@-jR*dC!1t(Gfb7JjHXR?lfJG{W3mh0_{`FGwA
z%?{<(0O)xq;dg<t&aB4=3|eT^QY2&Egs<g3JAn+1PWhe0?KfY-NmGqxOJo;TVoT!|
ze=3TEg*59)=4QI*3<P{7iK-7^#|#g3T6P?P`fv(W<Uxi4EPfdB1r%qTXoqV~%4p<l
zNC^7xspO50lK^YQo3PmBrnJC$Hj1bRuGPy#ULtsyF?S4D4zJQ=6gAMAKXPQ`gbvi5
z)<dd{9>QpH2Qejr;g5hP0MFj?z^F4>dPbC4E9Apqq%`v&j^MJ{69)mXslz=;`s#56
zb@+dgXuZ&z?W5=Sbk9KGU?&Rl<vwmu!1yWpY))!|em#q6FVR+Zu2czk-+1{Yd<c!_
zuvo^a?ud@3QIWEprI`NAn~b^rFxk&+0m+_2CBex<r3N{XxNlK3rkSvvTc&RzpP2RN
zuw>_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<nWcL
zRNyMNFo#o7fw5zNew0Q0$}Tx^kUNteaT`Lfev|Hb|GX%q-3|Qsf}50VQk%bPrG%#c
zX7Ue(oMj=HeTPBun>|<E&>}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_5v<I;Wv81YpT1CM@YT`uDJK)<m=
zQmwX=9s|K32mF}h-nF5n2lt<1T*G7RMsV=^y9hPm{;H@A;%7(<?~-H;G1&mG>gQ`#
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}9mZ<lv@vezfUh{S%rhb_d9zhV5{oR-#S
zc$?-vHHqDTB;*>JZjLOD6p|~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$<o{Gi-
z^nc^Kxca<vh)-{|_AdLfmcpznls}N=zkIDvcb1y@>un;4R3w8UeNeNl``!z&?9yIR
z8pj=HXP&9Vi5161AUZv=1<jjP&XAtQ)P9y0w{dW4Zdv_Do`1%tNQ-NdtOhI=I96EG
zaTidjD~^JewE_#JT(Q$wm89a$#;RV?$i4;iIUuuuHN3=3V@!WX`_)^9C)((lV=7E+
zZhpn-HSjAQ1-Td>I%+d%o^CB;q)7l5$h!re^q|_9{D!tvc6m>ka_Nb9b_RJdS9WcX
zzg;-DSZ+bu(3*xk(`65<u~QW8!J1M7WVK#a3-?<p^H^X3A=VFO#Mq=oJFfd0OV|Qu
zNc2>j6=ASv9I_2^#Y9ps<dGlNejcL^LW59{yQ<1y417_H6Dx1?ZBtZ8WxL?N&#$7x
zKU`)y1Af(m?AZZD>*t!>M#70gb*A$QNEwwRXkVp+cYkYcUq4wk!Z9i}NBBbAgzMY_
zYz%#K4xfXwLB(_sf<S)d$!l|xQczg|Cv@YILVjitzXn1E3<ZNH#H+GKYQP^vqo(R^
zFO>{l(KW2ZHMndPFr?rud-BG$=5Jp3lCN3%VQ3ye8vi6|=Uc~!2w$GEKte57A6TlA
zb|<EA_C5)z^NRMClZxx`QQELdwP&vCf6k1%MDGI4VxG4c(bBqD7M5-<qWxQ=eII=(
zX|feq3pn>^h{s<)ueX~G60O3I1|wPPI@87b#BEjEpM2<zf3=CTf|1jYt4Zn2N4P%$
z{ydFKIAyFq4H#Za$JR#}wb(dEE~_4G6Cj!3zX}}U(@<`1BKfgn3nvFrF7>iGGOIqw
zW?#a&V|>ga!1b`S0W!OMoA7EB7~=8PH)9_GVY{(dsK?{$J{9vpw^)Z6SHAcc%jn{_
z1Ey3r<r`e6jP}Q>3@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*=ZMR<dVsQ)2287*fE+dR@b1tSNs3>rMHxb__!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$Yd<JF5<z^%{c7(_
zVnp%Om#a0b4^jM2uDPuHW@Co#9Xsk%rx780U{&Rc*{hRCiCV-N>LyD^==_+|^;`%Q
zbd0gHck4kx{O70ljaFDXJ0~3-`bs0b4V?R3pa}GOZ%3r)f}%)VITd3Hb=$#S%{(wI
zccc|?P<f+GcpdGS3r1AE>ZRekB_jH)8suY)Cdvt2Tp8~NRM-i|(|!t8E<gJb(ov4)
znz@@rpS&W49$AcJk@YQBq31S*km~F}Q<lp>L*Zd(qRJYeMQu>GN$Jd&lY9f7I`^s@
zw{jR=i3@*#=#+YlNSQ@?IMuMHP08@N<Nwh`|Nk;J>MLarMJ}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<fgN<O{GlsQRH3z0!Z{m;e+fKPJGT}`&Zj>~?7Qz)8K%azLtWNh~>
z7Yj+4eJ>h;T`<h96-Ika$etzBf{{0X${qQCY`C}h-Z+YbLVE0qm4G$D;}n3B_n-TZ
zkdq}zI3bIR-2Y*j;NRN453foL`M6hnjXyHSaWsY6KuL0k^K%{BgsvF#kO8(*%5`$Z
zr~1UnZ&WJ(^OrmaNq}*V%E2{;0boR@V@cy6>l6<W3<jW20@%D>s-Y;7Pi+t{{z1IS
zs%SGwNSRfc#{FEWsj+?R06DgFXafS8B;Sn6OanM}LA;)%P!fbd;p66c=<AjFC5m1|
zJ|P;$TAYKbq1xiH6z_nBZ5px591q@T6#<(CmsBYQ?$=TMc$6328LAzr!54w_nRv+I
z(z%<jRe159_@zw6fbx-%SJ}w<)kos<N7{?qIM!!??aD0V`0wVnIV;IR{Q$0clUAO@
z%NlDz2{N9}eJj_`S=kE19>Mnhtx^_(HMEcepjQh)r8yd|);7*+C%}cL)~)nKg%ln)
z(7-aG(WC4>Ts+E^hf8a&ZwZ5XO3*Syn7sVu14)Xxe7qrBryJR5f$7P=)*l#u7L-<a
zc4?*pk(rZ`PTtT={JXQ6s%nBdFY}sR0o(S1G&KKqWX?j7|7c3n!+GFtyM2Wb(b<Nz
z2SiOH<_4@A)S>3PMcIS1efKa$PcT{HQ(04U+rW!#@w6x0c;hu|Wd^irWx=vV8sK^y
z<)Rn*tA;dAclZQHDvS%`K}8pMqn?QN;L1^sT{C}r<eBFfx?AR`(Nj^hiA{E;uDBEr
zus=bo>P~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<aQDHyD^czas`2JR>$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*rutBF<E5OWNIfwxUFW+*=m-SRaSqohIafkU&%duUZ
zK&u;)l2OGtOgFRHFwIbw3g<jQGbQ#(yG`nMiFWJKV#W*EniKrF*EwlM<96Ye_M)#g
zuNAz_t%>PcDtl<Yr12;$Puqb(qd&q0cqh@)76WBQK-E1QB^*mxD~#dd1ZUVqhQMbb
zsaVC4&`U4<^#|l=3q6w|dz>FfC)`M6AFLvuR$vk0JSegExrL)vzYk~C0VJsS&P;y0
zgov34o7cU<f;gC=<XRw}pjsH6dAu#dOht+4Ne-3dz!qzcCfMr8nwO3n?HFzh6972|
z1571`T#%cF%&%;+4I7<kCJk@M>;~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><lciIKdYx(EfxzDZ33NPQ2aqiNvbn
z1=?iW^}d?nFdgp1+c!+bbPC<GQVyRH+Fj*^7g3uz>I8kpssm`i0d7oZ^V9C|IhJJg
zAuSS=ft7n$VnBy!awLxkPt3i7M{NV|kDEgS%s?@r6r)eHS2Vbgx-|9j6J4(t?pJ=Q
zeU$N<Pxj$0=Sn-u7*5+X-h!g8al7d;JL&|Fl;9xCtBICT@3*U*4z8xZ>2cAygT6%1
zW0Chf#C4TDf@lYVJOITk48$)`4X1OlYua2EcuXrus%ukhk&UTy08AEyEZ5}Hzf(dK
zbDTcV><-+giBle%RT(!z**JF!LVx&3R^D@rdOW|WguO+|4AcQT&*BT24dF<u`xK4#
z_Ww?y?3jOU7y;m2PcOYw9bwPImP>r7>n2deFE$aiL1~2k)Oiiho%irI%x^TmSkRo|
z{pBf`9o482M|^;gT{E%6#vSY@{d`M>&~<p-aUT;^VPergx!ji>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{j<fiFshUtj<)K+wO5UoA5gIl2B95?j-kaGc~$cZzfBa_(3F)QWc5M&rz$ry$fJ
zKBk(zElQ44M~&rHfKB-yjwn!1y6rM}wR1_6C{WUNjs!>EUtY*m@+%R80!kqf!c}gt
zD81jNmD(@eWMz#<UMC3VDI8p$OG9Y(AqxqQw@yPa^P3A@+V>pF<Cbh6>C)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!<dd6ZjNz%%A6aUrwnlW>hhNMs
zfI%{pAL66TMr8m{)6{5$Sel=QaI8U*5igsRF9{;7EN_!>JHUz9*ZRskV@9@<sj)4X
zhw(Nr@nlXFU!4Yms06??!R$e4gph`kB>n^mZ@_S~^Nd&cVTu1-_J;(R2C&$=Nk+yX
zo(|E*!2qUehJbn{HHi~UC0!k@=U#qbL!vMRR%Dn>0m-aY<y*Wou)=-D0sK_Pz16<p
zIZAX#j3d&~D5F(2%26CHuz*gaRL%{1Ya=<nUT;A+q*>}=j?h(+VJpX3mn%Ygw)X~@
z+e;43!~EHI-dgt98XY#@5BOFaWxKCaqSl^s95smr(a1tS5GV*RX7Iu=)i$k12v33x
zt>Zfi4lx}(C@TN(F$<_9VQYuZ*g#2I)<pH>&*P+7&kDt2=d9|)%*h1o4MB|HPaEFC
zdBMIHX!b0>Sto>LKBQd1*0l^Euh*OCZ-N?zoOmy0msmo$B)^bbAlXk2ab{W6HiJp2
zxg6~SE?4b>7A`%atn?rB<qUP?$Tc*Wec_*CDrl5j&)CY-$1(G72-M4$DI~Ri<cfkF
zQ1t4fGj(!ZZG^H}HY<<x7;fc04@BybpCV2<IIXnqa<QkmQMqat>%`15NAdG(*=&pl
zS173yQB!ST{289=T;E4vPY(=NFwNbzkY7MN0}^J;oe0g>A2h!S1NaEzX0nfCkf#EW
zW-D_5QO2kZ=8eh*B2k#<{VDd5N%@gVJ62H9t`hX3j%><tJ}$`YoDYjw1lC?kH573p
z#%0TEWTFTr->}boBOQqZU#LtP4U$Of)Y>FbpB6aR42sP0gaX+$_iOs%9hH(?9w3)B
zY*3H?vy#qjA#L<lMLiDvBxMcPq<V+n`%U~k((a?due2Fo8cqP;y0K#IG1$rd+jK5`
znBW*zD@TnsN3H7=Q|WfUi7at)gRx44-Qm<L7y<FXvXIO0WahxiGYs$ZN0WL46Hb0^
zPLd1t&oBLP=H~utFB(^JvL7Fe`47;_d<eF@5kRZs6~*{RmY2vZ#A&GqfD<eIu+vDw
zP2i*969}xa3k}5pURq<kkeYkQmKzDf-=IbY!Ec8?!Pm6-#XXmN8RUK}_11yEw&Cq*
zyMIxuQVgB7#oVaurA*(kS?u?IxoB){fwqVz7l^DYt)s(-F|)Xg{q7vLdnS>|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;nkyCcOYmHjP6J<zIf8No(p=+`y|hUBY9&o*
zFl|2Dn>rNFBjD4w0Au!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+<hH281VzQOQep#_Z@-l$N9=0XZ46F0e)J
zUW<j3AQR%>@2_%6l)L~}y|=zPZjOd#yzHW=R_;K715%l$kT5MvB$Md@t63@We}=IZ
zZwyUL|E}x9%mT<H%|JajfI#i!Ge52#D62h*Otzs!g%U87ZO;O~_w`H4(VbO;gqmMs
zk;?bdrdYHX_44jV*`uv2#%-bfSmHG{c8UFuHd+j;csQ=|__n5}$O78T)_qPxG#tNI
zT*f>cR&#)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?*(xNai<FW;bBYA4h&}v<doZ@z~<<Uj%<-liH`NBsElHblX+7%
zzOHvOrk>e{?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*7<g8o|ya5hkV1G)z$@Bd?coFo|ydt?E>w#DKvD
z8B9RnQMID<!~MtekVbkVE;<$Y_cP;JRxbg_Olngk<1e(w9sw1bC*LV~sLcw4$wal?
zZOC4#3l^6UMgjSZDA038^gp9BD@ZUqUt6bRE8|>y6xwGlfmpyFkAeikq5v<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)S<M2_Z;QR^rd!HVYF()i>ox75=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>cNtD<qw^j267WW^)rA7SCrI>foDN-20oqq>oCGwyI$1Gtor&))ic1zKncFFAYqQ
zqBa1)&d>aBka{|PNl(e=>q(Q0$_o$swMc+|Q)aT&oiHwjd34-TU<nhr5DH}?oXQ=W
zSP#f7x)&aeCitQqq6D64Oc6VId~42fQHm5o=hNGU%lH^G?RTW-nx{LNNg73C!0=P*
zEgTkQ`px2FmJ<8u4Q}Q+e|`lrHXga{nAe7wAJHCxKeL29wy1A(%6Q~m;&RlRvq`N4
zp4LEOZi-3ols9D9A^)o{XU3&szlqL)tT50LF(u9$yq8)nWYU4WX;*`B|0EW|s$npW
zKLgGo<bh70jGQPxMS2^6e0S&<euJXooE)km8hOPY7IJR1G1%+HM^tL=K%w4H!3PS<
z!qC5Gi2ZiOts>$#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>j<FDZ3^
zT(lUQgZ3T&lTG@b7G)QfHj543<AsIEt*ws-w6&~-;P@G(sqE&U{ruO}NG=qS&W2`P
zQa~U<vM~B~TST5Gx9QS7xR{i~*6wZA;G_z$RIiTD7v+i5(Q|@9yM-<fN6m_Z!~CE`
z1u-h%i*{H286{|~tMiOTNwCvHS=*VdAsp65x_${QDb$&5dZ#_#(VdyxgS;uJkr+b#
z9Ug$JGPlT4k}3;CP53;r2)EMm;DFSY&Fh@I<;%Nb*hrRBo{}Z^SPY%@v7Ga+XL2Q%
zdiQr2^MyI*;Ol<o+Dz(qlDRiGEjbu}&9@&|8N7kjBJ>jRxhBv%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*t<YmsuekMGX7$>uktdE0xo;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<JVPrIEMFLxrO?`C)ZVVMGtfTrsVD3!I+`&}Zy#veS0n~`W)OzLM
zQsryqVn0V_Cs+lB!8KX~UhET26>#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!<bHQV=K1`rmFR
zm6T2Cwu>bC*?|$37FzG9`5^i}%qfzo^%xu^_ztA<c8k`SAmN^ZOX8OT%wI!)h5M;2
zHMqgo(l%VCl>-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%SL<kuy^{F`uQ%fn$k)?^#+?bgOnwYIyzAiey^Cr*HtbpUL}{sS9kP3
z6oFA1!z1DN=_?m2gH%bhD(5fvV2x-t)HfyjNQ$;dr)p<@7QtIf=t^q9=-avyDPU`<
zI5VvhuFqbz@uUtyNnn|xO~SuE&3nCvBWW$Z^@nXfbaGrZ?JI~#u#`z>KUpr@Rwc(+
zr)jFeu9TiZkQAHiBM4msgEkJ~Yvmz&lf=;QttZ4gJlu{X91w5ZhVv``8uV;zR~mxh
z{^!6F-j$yCVX97(YtIZ+NkI>X|GrC=+=O#2?<i4sF^KL5c3f7Q1Hz<O9XY90;MbDo
z#w1#z>UYDnjfpEKK1mu<xsx&3wdxybE{<?nM<@19n0CJg<_#3$^fXVeg8Ws)=b9QX
zK|v*TN%DmRD2|4A!860>MJj7#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^<rv+24{RE{~Ltf0u1Y=>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~Q5VNRUb<g&q|JsdDLFB}*sEfqe-pJ{sVYaE}eUR>M(>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<SqAyN&(+d^iWS(6TIsGd<
zw_7W}*o7qZ7jq325*{Y5&;TNv&HZg?WSioHN@sr#M@D-k46*X60GmX>#El@`+Q7Sz
zkfRUbkT9$T`XZL^eS0E<JtXliaSAx(lRjt<Q}yIUv*TS}H?tdFQLF1iGCWGRS$>`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${Zn<I*`c&}JX2%j+GfV{pR@ar?j-;l12u=v2-Q)$Z36&*XMNC+}{
zk)#c_C?;S0wuY<5GAndr8ej*+wGUGg*D|H|%eKGiMY>dC2S}^34v+yGe$flvS_aXb
z@df${555Y8-_PcreR44oP<p5VOd9N0+emZC76G>Th|*1H;x|HMNH59KRD<$yfCW^G
zK$QT_6mSgR8p41VL6XQ7nvd{2xC5s^f{si;iQWAwZ3<!=e2)RfPNhuaEB5G)2$joq
zR+*HWrd2(yphW9%@j%o82D!kBe!=W6%bW@x{lkVZKR2r#M;&En-_=2J{YR-KT1m5O
zRA1OL2uxDzA9+eBW0#5bG&Yx>AYsbqn^(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_5<hw94Q<U4ZRh6ZR(f}l91U{O_h_&^7q
z{+;m3?4L<2#%8ZNEFo-pF-UT>R8P5t3Q;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`X<DsqpmCinmg5lO00gO0%V3)HTZS&vzitm%0#I
zr_Gk03bm5)awr1w-~J3G0{nKS>zdMl5rBE;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!5BU704g<b^}p+(ikF)a6df>nsvkc>JG3pD
zMZA=M2#OoZa#W@JLlbl^aKMDJT`+P#^fMqD{6jP~jrZQA%E#NsFcpT?-t%``W^GXf
zZ(l5ZF2Vv{z+ro|6<qD!b7D7SxBCM>QvHOysg(;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;<B-=U{<X0Y<u-A53#O0b
z!dC$E>KGVMR7c?tIB$-_l1ZPWol^8!ps&U|8tQRhLRD@#19xJ`<G%~`5EUScO?$aa
zx2zVKUDx@}tc<0&2}k7i3gyZJ?CzKkPk3n5-xTW3yUQT4Og1Hy!P@r-al2~Clxr1}
zQq8OCB3vI~?D?KS;x_Z!ImTkX<M+K~n$j5b5Kz?M`s~Q=RX#EvLcE~p%e;9&t?}Lt
z%f-xRZ;r{J%;*#ABb6{Q4}2?wJm6z2X!I-8LA>lulff<O{$*lroM%fJ|Bd@t<WUk9
zEh$SS*==Iig_A4g6mn*^=xe4mwmi%GknY!1ZiZkqQe=@i7Ay1D!op2@jlv>s!&}5u
zkUNN)8-fFUW-~^jsXWn+ltqyAN<Jm5SwJY1AL_vVX7LSQ`MUoXhd#X^2i0E+nyo6k
zT(ua|5idF6NtDf6*0lg+v&H?qu4dn~ZDT4<`0Xj)!l~=tskc4CE4unk!|!*J)!@zf
z^Cgfz4a62x^tAU?WyueslGdJLA$|8$dQcPL%O4JSb{5U+1sc4z^!;Da?5BSfo6SF?
zlm9DD;0?lkda{xw7qHuriU;c|jz<3%S+X?n*}DYxB`)hi3rxW@?eUUAL}_f>)JC4O
zp~&;E>H9i_ZYGI)^$4jPFcNKXP5l=jr&}V(=aoK<AunLw<MpYA%7?DMu9(NjGxbaA
z)mm&sxJqa9k=E$N&F%M+6u^B6FL^a8YGx))Y`k?#50Pyq?s~YVo>j^y_%?mADZVx{
zL@wmvkuA<`vJDN3<Yqq<Hf7iG_e6IOmd}_XYL0H%@+-}F@S?^-Q(*w>L0F;@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&#<B*P
ziUFI=+<3t{l?|wyDtcNsuWq}nW9o{H;mMLK&>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_H50jL1<oP||ye{?EnBP3QE+pB;U
z!K=A5#_yL_*!XAt_j<m+@6aJueHM0$XodyN(3LUM;r_Khq4y-U@&jWTM_d@HFVg+H
z>R%*ja?()Ax9_KC{x+hsfpc@eLw^ZBJ}hwT+yY8C*^B}xzWw1j1ji{-YCjcQO3W2!
zu#$}W6dSO#;oC6snjVG+;i@g^F|t2kGL#S<CDp_drQ#qy4MJQkSjiK@y%TTSAgwHY
z&IgdTr@}qdL+z^5_?5ejs-E)fvJY!5A7`8rZctuH88t^aM>APou%YkJWfPy%vs9Bg
zgeB?<r_4Ga6r@rHYT#s7|H8b03XaYU6nh%9{f=rxWDHKJe%uI3tbH{M;a1&5GGD4>
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=7Rb<Ui2y~&plWDe?B;|@bV
z*0!7zhR7U8$yey;H#pO&bIMHMe7H?@7IkD!W%Vi|u3jI$#W|K@^~2SJ603R(s9&rc
z`H93xkNHm!`fVuDKj(I~FV0AtE2*_2F8uV94=)MmyI~m5CrMBdI$BbIy_2@!ZtM_E
z?cTJ%EFnvcdyED&9d}y9L|3Tbuozi2&>blx9?62`5H}1)W^b0^DwEc;apirPq<z5F
zqy70stEG$z&>`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!<q}{eb=?l2&9-e=TDW}qe+U{RbScMS9GKc+;HNkouK<r`U;1n
z&AG2(yaNm;**q@vTBNu!a7o%F6tIm$D%MWqmm6~9I%N^8*PN)`OdJ5Ggp{MJb}K57
zESv2<dT>EQeYYY0SVrgEm!hl?eovU&lkt;el2C68S<}b~pUKm&r2EnU$(72M1X>M=
zF!$Xwd4;2VaOk<GOOYw8yxJNo)f<?64~EJAQW7WowHaWbP}`ECjFowVu0}EBb0@{_
zXCMg=@<u)XvWxL#wx0qq;Y$<^rmQTBGT8uUuxgwzVS>vTa%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=4<Fx_yX;raxz;JC4ZMp{lB|pTtsr`DV2f(Pk;H%5yQLR&WmhEu<1c_y+d^
z>Y#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)l<XSsTD+2Kt`J?`;2MiA2-4Ptlo)!)SW;RtCp~ilGo#kA7Ew3M;Fnqku*O
zn*$hO(?Tg)ynt?bP__!kDM1VaI<kDEteDwH?{<;HH=VK=(bZ%xo)nDGn<Yz@dG2tT
zT8L813)FQ8hKr|1NHdiA-0W`b0enK-)|2nWRcxAc>x$VE^tGqi2WRR4bUBuiPysej
zzz`2Z8N;MWQjzB+5GbFrLGmAxk{EXbXwgK4K<oIA*$IlL379kd0)XUw`IR&1;lvu>
zXNLSFbHVLi7xh2FnP|E(V=+c$|8bySFqwf=dDuOq7L0HHNt=#}y>b|VTFs^Wa#&4}
zNZ7DB#ZVOEuPOyavs~eGa|>X6G8xh^ZC2l>qkx<g<dTLcSr9M5_@yT^D_&>h_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<NJU06G=vKik?2QFl<6@pv<S=DeaRZwHiU^`2`_!PJ-b
zajzzCp~cG$5KU?_wT{#rZxpR$)<|%;xT(M+nBT5cn7vL?xL*V+ag-@L_Y!n;E0IyT
zISjo$?O&`$)fHr$tN0YXLTe;Pid|Rco4u~79p8nR1t2D97w$Dkt9zMil#H`9pb&;=
zpf5JHKI)L=E8#(4ZiUAe93ixB9t;p%D$Ea0G9)#(T8#AQ;fVcmdH(YzQD4p3vtV#$
zn((<rStCQ)r)K)uGQMyd1UV0C*z72udTwHAB4f8<F`U~m`|eNm@yrh~Y~rE?&R*zK
zA>-)M&s3Eu=5E*5!N!e{vdqK!5i3k0SK$#kcu)4hrc#Jp8uy-x6d*C_e?HbDi!kuO
zpHyw+-2R*8*Xqrh5aREk)<IMJoe|3uNk+awogni}HA~{RZTd>>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!g<s*ZG=`C}SLnaiVLFCPs|Z4tYx8;n$AG96qtw(`YPKGa))oRU
zvdoJXjq61~;R99J7Ysn0k`uyYPtmnp<QS4={e>E7TTLVT2ZIpA$>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<oi57h
z54Kg;><;#Z-M8b6fUC$1g(Ah~u2+gjNs#N_aWc2uU}|B!10VfzF(E1@V!XVHfvdRR
z(OaR}WyVFaVjwf`0L99Mc-a<OV8I_OC`O`TiWN<LYeTYDKigz8H@)=-H;^)a#%N)H
zminMLE@jSd0kLWOOmy5f@Xsbg-Q^lchS1#ya;51@EUou!@e=vA@j|m)rUZI%9h&M1
zl4$iCT{ufI&rc|jfg+^VhgW#vLtp79f9PCxo<i*yRjKMQTwmxZ5pgu7_I`DC!0oY_
zuDYU#3X-OoC^A4?vA^iaNvXCE%`o+UVv%qRH=L}BJq)-1%&q7(^pAG*?KhHLtPEXn
zs!L+Vs*P!m&l10GT*4qdojq=b2VR2O59Tu<SGgDgG}*i0RB+|4__okB>l@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%&gYmz<F
zPQ#n-i>6C#7Dhw%<$>nWXFN!}aU$lY5pkzm?!zG$tx6Q})+CZfG&#f+$&Ey(E>CVy
zzcZg<Z10+kAG|Tb`kVEQ3)NvD;^3P2z7ua;E45%cLi%Q67;b_C0y($Uc4f@K9{0^w
zAc!xjA_45z$Gw+oDzvhx0aFr_lVl?R9T|W}ir0}=m|m+8pHbaud=P2^XPUfA(EdM7
z_3jwn7$IKKSng6rovW^*V>ri^CrolC#0NZ*GO5kj!`ByUWIiP$!lwCJzJ55C7WiM0
zJ5{BQj4r*U^l2po>F;0wmhY(XU05Z)z$)jm<gu802Bo7DGdlZ(vJ^u1noEfD{TXLJ
z%FdBRLkP^4YuaI+XZ~6BEVrHyf!=qsu&mf0fZ{O)Pf>;5OcR>f!1<g~y5Pz=76RjB
z(w8%C3eEVJbsytlcp8{HRp+Cm-#N%JpBu_5sc}F8+vCrd>&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$U<LChU9$MS-$K{Md_9gO)Wbm{&b&h?y(6Wgd!*^TsGtp
zEd|{CKmZ_zl*z2dc0knh!zi3<+Fuy?5#5?G#TEMh(?2-+dETYRgMCtny!IrlWWv<h
zjy#(CZbyK(6mLv{Q<liDoXF9XL{mKKHr!{yMs=Xvk!F`Hs_H!i@y5>L{Z=n4(^9ww
z8U*9JSM5O$%9b!eJBX~I8Kd)OK<!gVO%jzv9KU_H`ruQ{h=MCyT?ND|()i9^>!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<zA-w^Y4_JoRaj2aC;-)
zvj5$ONepl0AyQJ9xcU0|>@Pbv?Gq~|a)aM&?i3{5zTnU52*Ep4=o<k3byHw9$RK0%
zPS5X-4RT<BR_1(ecgEuxA(c-fL+mg)aHE4(h}w}~v6m(dx^H-BamQHlTxDn_RWSA!
zvGl}wMvmNoU8!IKM(q>zSEbi;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`@=bU<M4Sjtk
zD;X;Dov}{`waA+P%|`9#kb$VF#uO4C-<(OADfK*%f&^H7)%PB2=>Y_L)StIvTA(ew
zYBhKX;HM3V%{Tt(XVOx}PmaY|<UL+uqzPi6j=VwnOuvt`2q1FCGj_5Qlrk#TEukhb
z+KAgtDUzHi3*VxHvpK#bZ-EaBNuu)lIRc=PZ;(~HwK{sO?E}yeYlNIl<09kZ171-I
zd~oC8?QjN?OI9_5dPfmR9USHoJphs!pVk}ZkPaM?ldIejYKJbPZyvOvC36PNL(4~-
ztQPdxGgj7WHi)SwEH-$jp*l0w3(G?9rV3Mt8?*l=IDH3qOLbfxQvue?0MX-8!1el+
zC5nwfJvZ6|3VPcS*?e3y#RX>@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&%5z<u;G19rpHR$AgFWMx{mhIh{to2x{2z~~rI
zQlMkYc^6)5NU;brQr1E^t6_SCgz5-d>eTAVb71}{Oe0Q?7o&fia>FV%9JIA$pXuQH
z!ka0mrk|_q6}pXXR6GeGrY?YoriYj4<!fXRyx;@pfDH$$E%R8o3h<&5!PjZc?|N6_
zemq?0VzG}>@RhC7`wdZHUcRpxsMT-^Y)aH<rm0vI`fS+gxyHM~_4XG60}T`vB;>o7
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_gl<rer4w)xspQIL3zCi_D5wp6n*EXTBOoC
zwuXJsNio8tl@*lxE4zT0wOao(*hz9R0ka)r@x%h6X6UYl_U$s*X*ECv{(vx{O7PW4
zq{R)Lep`rV$#$k>0Llg$QKCi&D@jisN+zc7HEQV%DW+}GqF!Dt&lr5g+(fkxl&rRj
z*<XtW<Q$<>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<t6xPz?+dd
zLP*?8R)8j}?zaZt?9nX|0vSl&?WY}U(i^LL9(xRHbotqjZ~X$KIEuD*t2{6gho87s
zgNex7Lhnvr@8qY;CnFONyom%ACgyi>@l|)0CATr{sbWaR9}1*W1o)x8G`(n|=yE1r
zi?g5SIcptmE!%HJSjZ71lNjm@oTk3U1%wxP&u$~xnZ98bE%<fqKFPgDZJxvy#>$Go
z8kEH|H;TtcOnAd&#PPF1@$4bU!jHhWe|be|p}JmxbdIi~mZ+~bm%Yti?S;@{fG0Iv
zeOTn~N&_)UaY`ouk%V|>m0u<A=R+KmA+VqU=s7>O^{0_wE{o!aI;^zXL7j>RBY;0M
zH05>xG!1jj1P+K~)9(?=sk-`NCgg3=NEx0dZO!vSyRAvtR<rJCHvfZsQ{=6iMfn3w
z`toa$Zb?yE_zm%vf4t1_+rY~KwAHk?>`-&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!_mQ<n{
z6Fu<&v)oMh_qF(>lf-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<T4azc&}kK
zO>~J5H$ak5%r62zvow=*LoGe8;g40tT#+ZEIeiTX@dp+Ce2n~>01VSKRGtY+B#_YS
z4|mD5&U7*%iGvIHwFn4gfoHQZexq@=zUdhcj8{&&r102Rf|QxR{;|w)SpF)iZdP41
z=<D3$$nWhxJ>7t>JM=rxXE`V|TG7r#`Um-tS&&XXgIF_<WM13TF|EKL690$cnBn>H
z%S_BOY|<=zr#x5imR0y9S{JW+036?7)}{CJbkw~KV#Hz<M`-;5&?OaaPE#Hj_1L$2
zkqiNWM9(*tu?eSV@MS`N(!9YpQyc~PS%*ZzEg-GW-N)W-o1;e#xVt9S)E;1wrM!3!
zp8XmD91}F@SZhjZ8N9grPaxGsCohT20TSd3BLrQgCZMRS1d!Ml9_qdmzmdOq4}bxT
z$JL(gc^UHqB^)@(Jb?W_FP6%!!YZeON;>DmLca|7*O+qN$E$h!V>;pJ&1^_1!5}?4
z3q#@d0^LM<jf_l$79l2j5lq2=19w>3_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<ds^u~8=+IIntMGj=DY~|nQ6C&6Jcb@galr=~
zyzSY^SY*uU7W%I6U<f)HTC<_Mxv1l`RxH;!0#J5fboZk9Zmbys%RCgPGmG0C6EV|x
zPv=tj&sO0oYa6O0tLp4py87Y$6sHEQrd*lCv)U(0l`#tLc)>_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@<T5Gp>EOPUP
zX%3NE(mTY(Z;J~MwAmQ&r58yKP$cL^&6RFzfamYnF_81G)#E=0`ZZifoFn1TiqZsF
zKW-?UK-|hdZ)tFte-<r>Uxxl`a)63)CHW%Gs`dz%SgHU9G%|rrofld4Sav<Nqu}(K
z^;Ei|-b}jVEkU{S5#*xM9DzN3U_?F~;OB^tFt*jO(xKdg$FAh9!K+fdE_(tKeqG8E
zItCIIE?h#<eK}H?GhZSLSKXrT2+JLbBl^FMj7niS?BWshUxB?*&sW;VSA>(MyD76M
zCDK_lTs#)U=^hqV#&*;TL3qk;prRJGLelVFZ2e^BWE<swjZcOWtH-jAVeb4A1x`6;
zep9NDvg9?FC?dOJmnc4GBKVwP0%q@e)`H*SKl_O-jh&Uz<`mYCQ>oT+G9&U>@7`XP
z+PkG<*g?;j5pUYF(H2J+zON$OUOz@{1v~}O4jBc|p8LI_riw`IPH@SKt*oHGS#j7d
z9S5P7Nh>_viof+F<bC)~myqXhtg_Im8bZjZS|KVELWWC~YGq|JDDDYunVQA~_;2i9
zkbTyw!NbPRIx{r0BZz52fLy;#`)NsY<{-K84hrdm+hPG}(%FD-wfJu}VIk=gVl)>9
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<HH=O=JhgP7{njlzPwsbR
zvA;||O;XUk+j<#dt#i*obhkX9ac<;c+n-3MliqNs44;5DYSKph)^J{Eli?{7(d$};
z-=QtqWc_JOE86t!!_DO1u!ZIl*hVe_81v}h;i<W0ADQ+6H%zB~e2Tc*fwyYh63r`W
zcYZHEn{$7S?%FU_Zw3i9ekoR-ype^dkY#}1Y{rnnHt8*$n9NYZi=n<ocWolB*hB4_
zfuEQ$GOu*ztOq%!G-(D=<3vql!h4*-bZ<jJ`x(kq)SF8tbeMG3{07xjK)J_gJ3rb(
z;~-$2_PLNde#B=uqKA>$<T=Z6d94+oXQ=Y>*T0;TCg}7_ZcMIQxVx+)tK@wzq*%9_
z*5I5)6oTwSRK-PjBnf&9BF<m$HQbraf%AzVs=zk91_Bz7kk^Hv{&TrXs!8q(_3CIo
z1QFV#g{TPSKPG~K6F}h%rw(V3GHD{t;`?nxYu5+xmwBSnXF-^ySOs_h0?=gOLkEX)
zd#`pZK)YY-YSdgnbE;j4EA|v#%>n3*zrEq5xmF=gU^AQdy+rDN0Dh(g`s73z`os<D
z$jzdvcTR_50R3gE{*x{je5EeY^#Q$wS4OL@gX%S4XTjtX@2QBJ^MC+f{y%PawjV?k
z`g>`=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_40uNhhLGgV<g$U^er-DG@Ak|_HWdwI<B-xVyyUx6+!USKLQ$=Ggccn9wIwb0^y
za!>M9oEC`$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)m<g=wAq3tJEVup`?0!__KoRXjJVlqjyGf3sAXyTo%`wUY16NPvO4ZMne&?8RGIrR
z$9NvR^wh*)=D$Kxgr&E;U|qVAdJ){mUy`@OmW6|mEAshzvYw!T;aPY;nj6g$gX2~<
z*wOq{9b>7a+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?A<q9$0(j#8ZFqgM
z4GSphYw#Tw6K@pt9HwVSc^(gbZ6&)N;!iP!|F9&B+!L>DL`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&3SV<QM&E|CTktGFTfO^XH;6ck_&o#3maQjRQyJvN
zW$Vg6glxt{>O;gGblgfw6gV)mDc$ZOUgO@*rI*<VS+M2qc=fX5t_t2OqD1w3`{*w!
z>O{BAz82=`u1Jr*DNuE9hc3gmEzgxcJya8+tkp0)6^+=@<@%@6{Vu0<Thk#|+re&k
zV5$)TCw38tsG*<MKNSxG1TKyO*maTyWqBk^37&^A5Z*i|1y8Yi=M(EoUZUw8$D<Il
z<#;g({t5k3fhkrn@9%))Qvi$Pv9GXO;2;NRPgCBjx8Q0IEHuB9tc7!xZ<^OO&VCu(
z9x{q?HQ)-h1tGswZ-Us?AaPb7OXg@fMtNwzz`j#F^N1;wu-yO|P#Hur^?<eaPx_Q6
zNWOoLC!qnqEGA(|6=>_Imqyg6x80#&P_XBmk#qv~LX+j3E_Oo#dBf<eFXwf?)1A(m
z0xBTC*%O{SJ;y~9xV#F?mrJgo>i|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#HB<FWG>u08Q5rXt8jIa-*<4GU$00^8%6c-OSV7H
zLI%?NLdz^EQdE{^z#NzWT<V>yjt5^%Fr_genAY8pkfMzLBVCYpQ52yVMEg1QG}I77
z&kqips;QtDzGo#EmR{1}55@unIw$9hM9_Vd8dS05=Qch?TDnq_H!IBXsfVbKZeojn
z6#QpsyXpG`vm<l#E4c4HU7){EQDsS}*>2lycmV?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+<G^1Vw
z<Dc3H56IP}r%kxE_pw7aO59g$Q?7{ZqJ!wV&2{D<mjg`dYS)VMcP$01F@9wd&e9|n
z3obU;<e2KHyr7niyCoJ8tvTnD81P0NeYGU*thwFkWz98<-ezDB#>9(y12zhhgq-f<
zN_Ij>J$53z|H|fU)c2DFfm31^hbfaCojRvEkXgMGWpej;ZHFwg*t#w77#p7`AImsq
z3E6Clw)XWPxIEuSss`_!URPx*mCT<<FiPdnc&|Fhi^F)ACG{J$>tg^Y@>D0HT!=71
zZCWIOFe};JE&k}P9YU{oFV$y<91$h0P3+J`8w3~A2f>W$7AqKX#<M@U25qn6piMqK
zZtWq=3K;td?oa4=>1o%0ru-)L{J}#5Uj5Gtqu|5vEp7fsTomdhs+z^<@(~Sp>b^Ox
z%%zdqze5+~LIJg7pvi^<aSt%IUqKIScADu)uj}2(K_^%mmE^Jh_xoy>+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(`{<xj}eE)<_rPOpRD```2<4Fle@-)Qg;TMw<f6)
zr`oCt5J$OVGS{m|*71@Rp_YbG)bJCL@@YJHXB+K~!u-^utI>!EHqZo;EcLFd)VC*S
zzCTkauSAL6qh|mITemFy+mEDMg16L+43Bh#>-r}U%brcKHtZ%4Sj_Db-ft!bBZyx)
zY7M9z+HM;WPSUqdU0!olnESkHi*QUsh6<OvNYW4*x8VBM{d%hiU%Hm>NED81I>&hQ
z!?>@XQ;dqra}CF#`jzPN=hM5}VAp_fKhm@Z*a?Cdq=9l<!O%+c31uZt3VYE-_wbnb
zSxrvh3al_virOyrtuluI&u&Fl-ORNELG9usmv6u@!x{Z{cVGuMQzK>N3Ck+IVxuwy
z5?|1AR|-P*9C)N}dd-w^uKz#u3MS#uXjC;jkiy8B-Vugws>Gn~pg(UoZPbk*<!+%z
z<fZGAi<y&3A<p){oZhpH$MIf$%%=t)bDjw2WAjcX@yw98YA&f=+b|nB{Rtgt7PKJl
z%OrO$4e2>7nmUw|mcVFh?e&e8<aM^5Lh*7q^k<5O<fnLvP5KnvC^uk2a6&L`_>-v&
za~JYRSRp*4%M_l*t?Nf%EZa$*1p)iU$Nr5Z?p?H=ufaxkO6ATq9{S^ueGF_y?~Ryr
zv<Omh1S7`>1z)J-Hyn^}g`keQXJDGeHpkyIzJ^FtTu6P2^7b26+50`{5bVI5y;DKJ
zxu@ln!T&`eayuz+P`p}_j0x(-iyW#B)js$UN<m^6*O2Ys!BJM!8h2)V?2$CL6{Zr+
z|AwXP<LyR<@Zhx7zY99vXiwX|#T|W(6>baBEW3!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<Jl|w>*Ls7=}A#
zKYwgjh?|F|LU395gsQ}&_WsH$#wV-dClWqKDmdIx8>$dDozp+4I#%N)%AzR~ej@E>
zd!P&au(eX<OlIX2D%1(&<5E3ArjmCCg&p@?{89a?D(LNaCo~dJ>~76OEzjjSMlcEA
zC?JGjB>VsdK_NY4OO1S0ti@UEgK(vFHS#Ib83o)bT!&{C@S08>$&hct)|y{(s4xw?
z)VzcbSi<sEcx3E=_O8z11g#mAJn6>Y63Eql)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_lFAB<km47T`rpq
zLZW3}wIC6VMk+eGQL6bteMbni79Rvq>N;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(<vz-4Mjl77M8S5Qc9_j^hqJoG9vRU+f~EPv6ZzYmit+z~
z@31mj71?8d2V2e2WL_SFQd1kcr0H-D8&ecfgW4nAnm@BL@tC9$XZfStcgYmP^`CTj
zfmcX^9Kug$U@6>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%6GuobjGl7Aqqm<kz%d{<!N%e|_dRo!I`
z?e%Fyz&aQLfst;+;tx8hr6Emjz??p!Hg8?;{_1!t<H1D{QuYBmk1q!EnC4>Fdk&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
z8s<i*=-S7ayjUI6Mnv=+gS5jD=aiy#0!rTfBNH7$n0DVFvfmK(*#nn-z+R*>oaT3(
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<gG8F!xlQe#Kh#*3;qiQ(xhv;cZ_`raeT3FpHMM77M4&k785BoiC)LIu>%#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|C<EJWg>WADju9m%J)2dL*`%1U|*E
z9iqwhqzS+&)M{0fQsNBp1X^TjCuqKWx-F?(mt6ZR%hPkS=aAt>!d`u9jRVFd@3<pj
z@cY99es;v26KP{-lvhD8wYynMvv0xNz1T~gse_>ff@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(3<USe8KL|{+R3ikST`^Ga&-bE)r@|Fu+Z*
zqn&bjSGu!x=<V!LSV|Z>ho;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*PFq<yI<bMtS=d^Y;U389mre0MvuxnN#UNFBsw
zk+s!{wgwjwn8iyj24(8x5vV_5@~ME;-7V2tV^n8<ya<pO($aqu{**NdyNOAwBr)1a
z;@qN0V<oZ54zbV?uhR6gIX*)2C4>a~k!H#?*=Q9VLv@A&_(*Yj-hXv<#4k;#zW7|J
zT2}6T+FKIlVIh%mQuxZ`cV=^)=EO{~u<AM-hG+hYk!&R(5s$Kos(Dg!%WbcvxRWwC
zrc1D4r|}8SXEVXPMFmQMs$XE?c5<arzV+=E_j}{<&p&WQw)w9y6mkxQbQfC=KEnEY
z*0RRdJrNCFg7ZHE@|Ef3>>U^c2fck-=zwG9SNP`@f6oU6q#%rTz(v$9+>ddZ{jn<N
zi32L2AdXXstyrWis@nUxhrZ7#Y8plg+T9!B>=~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@`hzFP<I5|4$`j{ZVC
z%Wi)YX}}<pbu{}i>86r{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<qejtXJ;xTc@O|bvqv)>%~+d^D@hGB
zGP&m3M#!;_fGC|0oE98>G|Qf?izYJ25aU<CTrCjB{yo!_V>!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?bpL<R}y%4@!<?|ufX{@O)MXWz`qSbJ?@RP9kC5Ul8z9-4f
z2-Hu6BPaXk$;ywPG^q3yR;GlHSs}T$=b>D<O7LN#h%1g*I&27jt#`29ocJ7PkL|QX
zizxuborL3{AU<O`FI;!~Zo>A^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|^o<BCQs81~23U44~qg*=i
z`M`RrkD!y&=yFBcxw+Wm-4lbwoZCQE`)ptS<Tc$U8;I*u5q!J}W_Bhlc1mUo<RXAx
ztTPBz1#r)!fi<^QM)(Ol`~V_WxQY5FrbaI}Q^aFGbqjea)OI=i4J=uqp1yv(DonDW
zA7~<CUe=;1pM6cMs-*Z|G(%cMyTe*h<(GWgESv>1nK75`9I%jAJ71=|EPe;xLTS2z
zqJCF$G(jI9?!uvn)O;k{b=_&xBdx?+*IDgwCigI_7ROgR^2wqRFe6J@&&yFp`<To8
zJAEbO6z39CsV7R|N%23B#jBv^r2m%-JXwNKPb)&QQsAS9qBe!Z`RKS%Kt|R+sOR4c
z<!M}HF*Zx?KzvQZ5F8Q21^Kq$B{a#%vun2Z5nqnZkr*Q^{cvGtsYhJA818d{jbl#5
zbv+untxQa$J}`1MeiuBCyL<m5)*D=`gU0{`+@>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@|38W<gG=m#(zYj7`*}_<i2rO5qNcczZhJE+1
z#Pf{K^yv^W>aMl4GJ0d9fbK{MC15BgK?~Z@WlXV&0pS3t{|-R4<Vj5#?U94<IuD%&
zXp;UPit0Aby2|N1LcD@E=(|qTW#9XIu;MjBI$v7q8y(?ce*W|h7o_tPgKC3aA|5b8
zN_>6q(+=e{frJr-R+7MuQR{ur?Q#PA+|M*!CN33ZJMAq@u$vLdsoD(<U2m8zBq_R1
z^c%yVe%}*sQV=pMEMXJst9Rx1>tj$)&`XU<I_qi=T1%|xR+Xc!XK5X^$308rF^6xO
zwIkx4>KHTnLU*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?6<bg-G3A%u`?j#*t%oo4b5TbQfdvGeR~yI2p}H)~5Qo+;DVjKMA>E>m#i
zMDuBj{zYF-Hj7(uSJ@>tIrm+a4Gt-Tc$<(<YTmBtv!3!0XpUQ59qdA1Bl`!Av(D?H
zszd6-hDH{rkA2F}bWeolOXN;WpliQf|Eo0TPahO)&*6J(<Amhu+<1`|YGjd!EzBOb
zqmCp7fhF&-a1J1N96|U8%@{}a59p9BqhV)2+pe{z$;$l6^$Cywqwas?<s(bee-FkF
z@5t#cS1T1QE59<(hj7ha?d~rPn5=QP-2psU*lL!hQ~ZnI;#*{%>)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%HrZnuw<VK$xd`lPr5D<ES&i>V2Xp)y6~4~d
z)cYMlFBa{7hs?n$+WswGc}e}nY%ln5mX`DBV1&26tFef<gTvFu<iW;AD=t`ZF{Aj<
z@>CfV@#_NV0}PybA9D)ndP4g3G%s61I68p!KYE|^_AI@)G&Qp+?|{1NjqI);Ie#*?
z1}bcMq>V1F3{Wi<x^JMgQh*g;6L=mCHgiAb+N>R4)cp@pg<)G5n#NksW|Z_t64*#%
zr5}Wpdq+4>0QM~5={zC<!7nnZ*s!K280Ts9d)QWlkc$~9x2H=$e7U$?NRMNi=<tLs
zRq5dv)ex(Y&)JkAQ}Hv!^LGfEaCHkYkAV}--9>;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&XP<JfVfK9nmyk^0LL+F}A=IrjEqgL``|;QH%XV_gjp6+6s;
zGbMHdY@2XOJ<QPn0E)z&#qeyq5pak(<6N;gg3xc@dSA}*0g8b?a9SYCYr1?k5`biV
zWy44YlgWnPlO%8)`qLn7gYjCJVYd@qLRv$fUWB5XMZ-ti+w4LdN9@vdV?rWiSn-M-
z#iFGtng>OumAurZ<HEvc;v%6JQsW3xnlhOEu@D$rFdX|4`6dL)2mc=5Ll?k8`*0J)
zoaTm_RU7y94`rb?$P$cwIxDKhpOKfCtF={tM;3T?`~dyn_RNI$5p)SV)L^QL$igW7
zapd+nOVd7X3Sd6-+i_FMWV83rM-+Dm>%doS?Z~5s;ogd{wAoNnQ042gk(7mF#JQSU
zH|+n##uZC6dmv7TZq<^;UF*`UcLn}^@?E+ylFSXk$T<dM;wi6evkhB&@gzj>T}nn}
zWEy(3Y~x{P6nX|2`0G$WV?Ff_=XkxYKB9=zv2^#F-Iq=wU<Q_0Rr}Vyw84@aIto1#
z+jTnQ){{1vL)Lhf=P5bUCZ_%jiklxl1^Lwtjjyu7t$CY8BAEkwyp6(1RClUd2dpJY
z7zuRJ-dgzh5HHlD#0P|G<VH?JE;)Gw?<HB;au&vpBkdUjbmZo?o~kH@F+r38ffJ(g
z*cTPaTef1kv)P*}<kUSJb<}YR)^N$d+FZk06}O0or?Czi9g$&z9D&6?o<l;q<yLYM
zk*@lVkWvJ}hI8uS|Dm1O>a+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`V<tm8)`}?G4{|+35KcR<a>algV@*oRgHr1-FSdFFMfyPAZs+
zfBSU0-WAg+s~TgBGG(cLebO8sUpjs9{nH)Pc<J96*Cq+wNFpv`HL14<55kB$vxY2w
z7=X<ET(RTuw4aJ8v0!S|%^)uF@j;uV0eD7`vaCLTd7-qMWYIyzxh<?=b;k53y*Qy+
z|5ImQ(|L`Di4*;`1xhx85Vg?@muMa>tl7_zHlMo11fs<bEq(S?tO8v5<x3ycqH9OA
z&_P=wN!<EBH8>oR5yMB4zkuUVmbQA>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_NEpM<BmDod?fC07&l$r8KxQ>m6)$+O
zc8{cOu(>Qr_SYZ@Di_@OHms%{5<(vSX`+eI9I$$55+z4ZtiZ_$CWXS=!whiAB-N4z
z>xke$dl^QLh^utH_tWh+#<>E-QH37<<K!c<^X2;AoVPdEq1h9klH4iQ{YgO~wKG;V
zfB6QGozkskI|~iP${eVUc=?1fir6Aq(Q2P?i*3O&eycQH|4?5QHgWg7k&d(qyU*{o
zkdF*(3hhf#z)TvzgK4?U3w5b|5nzEM)(X}QNGx^x4lT$2^{&%;JcQFpb`+O?pB~Z7
z?KWeEgZ_M`6?RmA*PWz}whQW<dVTu;FXPj*$ns8_{v0{YDx~77q}GE^##VMIvOJuu
z2l`1k6ZNt*2H2CH6?^fdhT2Q6pzsU#*@A9<oBea}e2JL8%o@+A`$U+Hp^?tjNzNfv
zo_H!ctm2XtCvof^X)XA%V*?AUeZux&>4bd@20?|o)_S`&BXqMC<6+wz^4Tr0bbL>0
zR24Idnj<=Va}aCGHvt*93^+d0FZV7ZIZ(eDf560-PY5|sYPz-w{lEA)XInVGPr<dT
zz46;xjl5x8<FBkpjMM!-xSdc?15C0AjD%!+%l`tW1Pf7q&?XFfA^2Kv$~4|oxhJ{n
zd<EJ#J%;88c}f{?7o>+&bm`%T>Jkjli!22%G~a|5J2fy|RLrO8mO)qyRwstP0h@%~
zGb^{Xg-`LoLV=F!$!euZoYgKA5DP+RaoBQni>t~c<4FZ)1!yg0t<{p0#LAo1DUf<o
z&>sKv1+ho!7C==@0D2>MtGy_|XGHGpXDT8gA81oW8S7Fhm1l4TqdQQXkH-+>F2iy~
zu)MUqu-tM~E*PWTI`3)l-WbqA9bzqpWd&IiFT#!c&<ensiyoO~6|+sDcsQCqnACbb
zO3>B(|8%AZV2Mcvk%#h%lIkuM1yET>U{O8hCBl~>dCo-}$>nB8P>>=*c!N{PA~_b%
zTlg0EK#Ap5QjA*nc5d-#)bwj)!sf*uQ_$u}<!olpNjXKn#ExLLni11AB*pLt3IR7R
zXrrs?^ot9t%I)#WwRNG!C2K)eZ}4FpkxF+gApHM9^BZo=bg#>rQ^A_Wpv;-pOJru8
z(51sV6>cb=cX+6e7L0_Cq#8=bywiY7;Y$<kX*c6)Ji3%6g4@{Zzr=9usb-hx)$<#-
zBQnLQzGitls>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?JZAuGR<aW)JdS3^
zr6PQ=o%Qt0ESc4K9kXD}Mz$dl@DU_%-n~2a$`zs9TQl(t)Nu;IBuC*y@f^OWiENgq
zAy8;j#GLYV%-=b&#0y58T!CjPx5pl3c)pJ>f@#(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)<x>&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!J<m@y5+Om$36eV``g2$W$8jZ|y6t*-&7^B3Ig47XEK>a=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><VfNKd
z+#SGNa_%zBjsk0RaJX}bZfb5%&FY#gZ34fU){^5sdySl?n;{Zg^Aah(&$3{bH7{I%
z@a5@O7p05I8T2o;3g*_a1CFLw2E}Me*I0nhrZHSf_jn=fCn!;;*>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+_<KBCBJJ$o(yDsFgwYA?>c!`@yj8*l6j3)MS%Z6|zh~iMpV1!&$C<jxy@g
zGHf<Qc_n0qUCs%hi$<cKJzURE+@`!^hjvu}EF9Rav}AzE3jXK9HCrBbw6l{42lln!
z&0XtM5Ds)=-RW|y`i7%(<X*J8`6-V3p_e#Rn#7$-w2Q3@kv2WA@`PXSYnq_=g&u8S
zK&eNQR1km@+#iH|NBvjOdj0m-u0SLPQ=Wu8IRIHKTm{yHa2hf<gROEjk4Ef;erEnp
zcqb>{VY6G5fA+c}YnL56ZhHBhB@HTFV%D<DcOJTnMHfP)V-HeQd$}@Zm?_>^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`<g>|c;IYk-Qr+s`Jx$%LXK(zd|CyT9$k4`<qRp?bsfLA<c>|I#cO4sTIPf|
z2jUP9p>y<6Cl;02J4sl0AP4J_006DavGAx5*}3xZTNF*Hwb^plu9!aJ;X}0<o3ig(
zP?NqepDRoZz2guLkFv3H9CHH#rhgl~ojC7E3`gJTB$C@xy~ypw#v68Kn16NwEtRQ1
z(q4t*HgUQ@djQp`KR2@ITmh6^FYrfwJC3v|2(=sCG#5>%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%NM<slb0Xw3)NR#mMkbv$K+&xn#_#1V@>O_&(sY_QqwNTmym0=p^5FS
zmrbM+-I-T6RJGi|ziIxDZP#t(QoC(`E?Y5waJXqMAcbe$9x+~$-+Do?lU9Ztf}J<C
z66^(9ZcjF{vn3I!2`|K^hE+7`f>qEqF1AG8zDL*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<g7<tFTPo%wotpcdu0*`(YQ6FbyxcKoRg7X?O8udpwo`9_2+Ij4o6Zorv
zHR#u?+eEJOHJ1DM_`-Ya5QPcq=Wo}UEv$ULr?O*@_L~r_^VaD#Iw<NwR2b@7xpIy1
zm}bV8kA=DTJDt0*sF&A4!}UGxTH8xRnmqk#rGFLI`;QVTTz99!IP<7mOIA72cgu4A
z6wT*%@qm!+kmAAwt7#C9{Ox0-RGM0@0+5_Vz@>$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<U1cp`xz$Be
zFCrHov?plj!SS7{bN#v!9rYI{Ebw7SejM;XiBhyB2x)p77Q_iX@t7lx0i7_m=;H;K
zTb7iKA*}>-$AX=B)_|<}A@26X`E6`&8DP7tZ#@F$ySfO~uF&kD<#eugFHsn}LjZ#T
z#%|>`OF@W21e&v=3?0lZl!y=(W#85<R78bxBs!Z|#3ruUHA0O*j@8a>Zh326N_z$_
zy3^Qj<dA!CD*)-p+MM1o)Al>GjZ{?Ich;Q%K!hrvy>a|KIVGx3-T3~BREp7RsQ~hC
z4&+nRs}v=kc0#77Vyk$c!W~<sKNr_x!T)MP^Za`fBZr#Zx&+C4CcL2dK_5w{k$yBF
zXa+s2Rf+|A@7zdl@xwHvd;EH<_en)^e+Vd?^=tI>`dLO-l1FYU2(sgm2~nq)^V|cY
zeXEH~VV}yeV40ud0>-}sBXWQXRT9n;8uwu=`Cvj?-1pSQOo3npcEVEbPl2Ml5t;;B
zP>!~ZOkStoF_FB|4In)VLq#NZPK&yh_<nqJFun7rdLnt}7-Kdn2W^?_t9bc3{6?zx
zQn_r7@K_wuKBwu~?q&+rqf!kXEO|9``IA%W%_ulj2vg0$4Jq2F=pYVhOu$rsvAIrA
z!zb}AzXk4hco^P@B6U)ocV#D9E=W|H<;6E!(Xdk2(EccpP`e-fecK($iG0lcjC{5L
z-4zCIK{$d^r<C(pV=W_MF0o}K;!priUEeO-dQYMT{+y_r_92$vkpCn{CDqrxtJ-L@
z%zx42#V4$MLXRG>7zf6xfL}U}6RnY|)Q=5ZE8hZ~I*z?prc#vnbi423yA3evGdrWQ
zn~<!sO)J7<Q$v({G>2aDl<z}G4|~ze9@umgLe$=aOu1P69c0V`v}u}J;fE1(tJ+9d
zy!SL%FR?SHQm}g~t~IbXC@q%5naHWrOqs*2lipk(y^93@VJNAGnTRD_V8#vV<s%nD
zhEShg)r#4c6H&ULJhr5}eZ8R(n2}SZl<eI+mS_p1!tK|XFN^uONCGBn<ICy3YmYr)
z*IyG9r2hAyjBlu;XVz+L<Hql$qnvz9YG7aVe(Ix<0}tT0-NO3T-xhK&g=`(Cc{{Q>
z0B=&>5;>C4#<lDG@ncdF@laSpLTlysJHL)_U!Z7TY~;ie-Y9oh51&xL4j~~bGuBf_
z{$g&SR^2=fCaq*v>qk+gBZ;aL;IkMj#z|XD*5_dO+1?Bxg1*lS&q{c``zmshH>gY9
zT<i|#5a>-<k3a@Kuin@6C<2)!k3BWRtRKBnyFwX>1(NLo`8|8eZa46w38IZe9FQJ>
z$p|Y6VgWsLX~smw@F2q$Xee^Kk;2P#9=S^2h6K~8kY+IO*(gfC7lYC<kO}i*XVtmw
z*u@YzMZ#8%PX30BVZ_GEvhY8&NkOUB7J0+3Mj2~j<PCW!;vG6ZAE0%}&_}4RkkW7M
zVzFPbO?gf2JKTOGUrE7P8LGUp_|JyaIz5>RV-tIIp|}iLC72=##6I*Lj;xA<91|DM
z88h{;K^#&=+|Od66zl<O@5GJ`7tO>`4r%k%;TC7n?w<LdNn4qhHt^M<z7&3~9VNoM
zyaz)4`e4zntMX18_~=6$IP-c6%lvY`NIoLk^kKIYNG-c>Jw$Qqdu*psI{Gi`X>;k<
zkc<R+WX%u@H>EF#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&hLCB9iF4E<AEj|
z)4Ii~OP;(0X#t8I03>38701xN)P8Ek#l4S|Vd;C7M0TN0vL#PqKB2lxP{mE+!gZAX
z;56YFFS+RpS<WF0a;ML)v8+CpUG8~B9$b`!-<r7nWTaC-Dn0|B-tD3q52e`bRd*C*
z)T9PSy+Sj=Q-8!z(`o<oFm2*V^q+;{7KHqqNmwJBeKn*tynvE0^+w79x#JQR7l0KS
z-9BJCvvVZ|SjD|S|CI8kii7c0o!PWK$?SUq?;>ugSBc5<gA$?5wVIMkL>E><lH8hF
z7@;f|y+cr8e~M2p2<zjC2O&={`%aRAp7b{!SOyEqb$SjS6<Hqj`49HvEp(;Oo-Kg`
zUUN~=OfE%pKnA3OJ~l@GhH3SE^jXJA>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+<d#>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<Ba>!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)<p92f}dW4JOHp+{P(1;t3$VRowfx
zbvH_a-^|Q`3c=_v8P|+2_C8YvZF$vzX{46LXd9S-!3lvqTvzXYQup?sXB3u=fEhbn
z)X`hfN~{7J9NU0?ZqaN4hs}%THkyz0D|3T^na2Q)WcEf*t0{2N++T%OB7vePNUjFD
zNy%@sOwm><I^g|08a_A7QyQe@E5ZVzv^U|yzaasDERo=H0g&e9U}%%oD#E~J@GY4v
zk;w6$9^_|v1`IwCBKGIY?=_Y&Ohs!maZWpWM0yUGuojcGEWP^(xHfSdI9)AUk9};^
z!OqgX9qOhf?y>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#%sSs<sE93=Y>eG+X%_>uC^qUVBy{*TtS>nOM<iC~Xi)wa-8nMQj{tT_
zHH^%WK#@4t7#7uECEZrG5-YKFNnp`(kjo|J?e-HbQG<5$*)6B%9WBu+6&VtM(fI%N
z;M0?2xsm<EtNJJ|My^|o|D9OE&Zlqq5jnsPwbiUgO(0e;a5PB4XcH$87B->fbYn|+
z?F`rJ{&&#ZCBz=Y3=9vBuApR2+yV6)a5Oy5v&H3aTmi<p>PXYU&C$G+Eupghci|`m
zV>V>^jKNd822nEl;6Cil>Z&bWw1x^z5j7fggA)3&$9N+BEy#yT-*q3T=2sFUvY>;5
zjT}GC?Pr2mVpq<bq005oI~bvIaFkr{wEFYLG9h?$67?Un#Km%(V+g1XJvOTI*52FM
z%5Yf8IFC}Y9A-f8c7_cgkHngfs=p^MFdZU4;t0rWVhU^JBqkgKH4OkbTPgnkbaUtV
z69Rz4#YUT#S&3YW3{C5+F?q=m!c+?lxNu}*Rm8nk)*0v&W6~p*N23a$IC)z7sX$eh
zY?<*$HpQ>Vjab=;cZcIzUoD*GIyxOlzS^qpUtQ&FvUqGBxP#LkjrEZ((_Q@aUX8sv
zpK+i^3la~7_*r4P{cJmGw^=`JEH7py!<Ej7NJl%6tdHSx;w#kvGg@nJCldJGTWWJf
zNat`tAExrVhdy%y-=K)}Fdv|z^9#lc8)VltPlDZfmMXme7y?O#B0w|F8dW(o*x8zk
z(Z$@5UeBCYvtG(-x`-{n#prW&%7(pZtip3O#<SNKQ;D621Ejl5aP@$o00P~gXqOC(
zea6)NcFLAtxF>X!(Cmjlw9k##R8XwzA)|1=2W{O|t^Xlx>`!AGv(^&8?{=kFOhF-j
z!nT6^YzbG9OPapB%uNbJn~Kyw^U5HL+!4SQ1ec%Vaqhf(BU)<am5}aW5;-)6;vqT)
z?-oy#Y%m<W?<!WjsyP-{ZS91FqC54Em{$~0@G2cja3qLm!-p$zo7>-{`--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<o&YNv>+2CT;TXQzAAFOxD+NByz<!
zm&i2o1cA_$Og7!|&!O!oLFE8?=8Nk~3_v<XDV)<#kNvtHw0I#vN?25e6&Ykg3ebc;
zYKZuwHw5ke1nrsK{sdqzcw925V0o6e_@)ulg<OLpE>MI>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|xmgQq7Q<Zaqp`%?qEfq$XiK=TyS5tEt7QJk9o>cy1n%{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@y<N!>Vc!Xw8WcOyn0#jDgsM}Ug4Kt-14WOW
z?U|qHD2Bd1EU&L!JH`dKKb=v948$6%;YUCc^y2&4iz<RrA}g(lZyBn=W7?C>RdwY2
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#kLzwQ<e`*
z2lv3gx_MU98MDF-D7o}*vi!YI_D-`Ioj?AL?t9%goC-yLE8CWM-n26v!*&nLG%G{E
zqF25M^3|y_MT=Ghd=iHvCqyyD=(xclTs%#s$GV@peJykohFYku^gCWt9QLFLfo6;o
zx?n6quQK9;l%)Cl3q`-hOv&yuOVJ$`L-^L*4b=Hiaq_ydy`1vjFMFlAW$8V=*5M3|
zw3dF&yr068ju-)(HOZ7)xU<7C|B*jWN6{kI;m`7qqF@+TL%@W)Tg@s<)JYImrS~DU
zu}U=uN&KJ`W_)ux;F3kOn|*94uDKAIpT@)6JmUJv;V!HjtZyvhGE)rfPa9P7(gx<B
zrA;pvQEm!jyT`?y-f5l~8PgmDkp)Jdl~7GJ`=4w!2UR(&hQzcje_*cIDLd^21T(|g
zIb=q{3Jg}_>3GaeuNMknm?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|_<HHWrRZT5#s5NUVPn3ALHExVY;1r2Q$=rHyY
zK9LZ0vmzVVW6^gfj&Hmh<FJc`QVx3;Ozcr45$ul_lM6M33U9bJSVQX^)$*@giQ!;P
z8ZCOtw3Ge|%7w}|p=DSm_y00XF=9KbHfE%<NCPXdOwlQ6xuwSfpc)}CS3{x3;QR%^
z&aLMT7UDp<5J$LUR6ZTw8zB_@yFDshpm*cC_KQb6z0qB0gL1%AMiCaZP8W&<&=u!2
zc<RmX@&PWBTk|dIj!*(v`p{|#-a2M>Xb4DP*o1{^CkdI%dR-WeteWa*l+r-Uo`AhW
zd_%G8I|ZR<O)M^{>hO=#u5sG~1HeXN&*GnoL@C!tbIqG<<agQ2eCW|-iEPksz7gZr
zP3xM5n3ocY3m6J&YDu2U99(Kby>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<Yu>@jBR0aF)ogG^J_dHikxuqaoZlyLm>HqmXBs?0|(W2GX;
z8IRyP_>=***bCNX$AHGT&}+nDwmBJJ)BeJPh*d<vUuSMVEttk(wBu3@SL)-c5tz@g
zq3K8HkTj#ieoFIL(^yLYReLT1K(*R3+`zphCKbA(GB&H0QSMRVk=Fs)-1%oB!_p+k
z3ir%R18M5v8zS>;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=E7ZSDl<w+}C4ICN62rnoz77fJ9f
zLJh(ABw}Lsy*^3N((IeTeHTrN33P%OB|tGRdepfQXwmub`0Ls}or<UxBK!vIbNDsR
ztep0!U{3eXEeb<At~)N0O}QmV`Y;oWQkOQ&V&YSsij>fHBk2RshS}U=mP6~B%0i#V
zW|leB89@vJT4eNzR6ky?c>WQt6zF>0o-NqqjkXAjM|e$uRE<!&!w?jtA8MA3v+hS8
zDGesBq_U}r$L)`%mj_*iCLO{6r{`dPa3b+0)2(JpKdV#J<gy)O&6MW$<#;)9-vHvH
z7EI`@UMA{TaY=*=p216f;$NZd*poyk+SS~NtLwt=ItRI>lND6YIN-_@_#r?|)5-fW
z?XKh2*}`v5N^6NJA>aWAw>9{xg>v(aP;hV1bg&x}vB1?t&(PhSf3LU|lDMUhEm3rh
zV=nCcX2<rOG+EabzcLfxz9Dt2X)p*=<igi7TW&UkbONIUA6Qd5#h;h%PC&G+@_lBZ
z0VjwS?p!{;GB-`2I#{9uVbip^vgaHH4-#oSM@CR7w^p@e^0-KGMJ;Xuvbf0j9eQ82
z7IlQT^e;CbDC;|qig|)2qw+GGS&kMmA-}Cj&tyw8WAp0|o>pQoj0Hqwts>BYNUDaT
zHAU!l0z0Qryqr{O<b(ilJ;Pj-GHw<oO)>XcBH9+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=4<z^2Ep+aX%xC?UKSQ)3cebm;6Wl%iBkV@#A=MMKgd;czXn
z3HCrifstYoFoY4fDfGvN@tR6>tXzgg`z0qNUg6p%I5Q-^n25c|&b~tM^-9)-<Q-4H
zz5-Kc9da&u7AQf6d{z7<payU(-o{Cfgxf;i-QxqVJPIF{n-V}+bP<+EBr4UFU^N>a
zXQL6iaAzbB2SP;=3gylm`RO?A!&CNLlD8_#r&Wf2)51WM*i!XAI%<U(6%d&w<9QMr
zS?uF#-HOpUkwfdE;}S+9YC!=L{N0l(6V@ZT#VsG^{rI=KhZWmj<r+(b*+Qj^P@vT!
z7+EYkF${tqv*CvL8d07}=);z;E!0<^Dgc!s9W1_?SHbCL<8a&(Vz^Fx@CU025@~P0
zhJmmAmZyYz;m}7VgsK20K7L{W>>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{w<V9(9lDZAOVTLe5}`o_ll&FF(I_CX#zT_&yccL
z_cYSBKvCmPT;X(sOO}LTSfe`1xE2vXU?m8)sUX)1^~&|?E6SLem9alSaY-)Wuw7Pi
zNE8|Yc+-Qz@Wt~Pph*fweV)%-MDP<u!*|1Euv{)>QIVud&MT!%SQy@Wl(0al`KT9R
zK=aONUF(s#de4O>E11yJj7=xJtHK0u<ijDf1{8#7vk1kDY6<prQ|v}nP$#U{H%sV7
zIQc<{t5OgX_8~cUs89wwsh<`zYUa7BKt#nTk>WI2=(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(&0<o8xAV6SIjYWvB%SJ*Au#zv-NZ9zy(IX>Vng>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+d<k^7OoO{p-1Odt^(I_xV+j#a}8}w_{Sy
z93@fGKYhYrl`o=!)MV^%@?&2r))9dD%<(+Z3l+N{0F#aZy@Bl_P>AM8!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<r
zKnB5pb^cI8n?d2(HSq}q6i*{i&EeQ0Jl9d1f46ox^JC+Zz)ni1_Y=)*yg4~R+mwi{
zbJVwyZFCOyY+vHNONyvhMie9K3283x2!%^H1Mtb9(BAiu{Nn(kGE5aI6g?6XpNrWp
z)u&OKHmn*X4XE{50-^`*8!}R%|0uX8L#r8^W?DQw<Ys*@4dv3(a%8jIZ=-Gm$i}&G
z4k%Vf#-n0RFEwv$DUvcW8%zS=f5u}$<*^>+Y5-21Xk8ou&t#y<JB87SZq<F$M9{eq
zduBLu(`3dlk~E10wrE05?WT3$mBNQ|iyE@SkSO@xF;bwW6G%9NO&&b~tXupt$*Fsl
zC|<@_5d^;wtzWl^O)h^CNWXi|&gjqx2u(d_Tf|>6d|4n34Z_C~@Et!<WKnDOH(T*Z
zq&!1zoz9?Cpo~AH7bB&aiK}q&i+!;n^ID3C&*qFif1$Owy^%rh<(adC+s3|mxo2rr
zG8XJGhU~Du)%PODLi<D)T`_a~D$FW4G~Nx6X($(?<aGUGH=8`^WbbEu0`g+$L*XA9
zOdy~;Mthbvk4wS3sI5uc6LR7KFn>|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`}fiVQlX<ze?X__?lSso+=AtJCD?B!TF2S*`;s-64d0%VK_oX{>G
z7H4`9izECqUgAq#D4cz#mcms<L@FK<lex@U-lwyZcl{vD*c%cPi<H7f1x6G#c1Jjt
zmlF(K079*3pHcft@mzIrPINyh7rnxBN$6u%#;x%*op1faUe|*Bi_n9oGnWq>H*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)`w<y?4ut+=~+h7*^GC3=Vj2WOIki0{+vz`fr{?@D|<T
zcNGACJ;M_57Usph&6E*3dU{H6M*5tT1nF)^erVvaK*+s<d~_@)tQpio!jk%$H-Sf5
zuF&*>I?~^#(fb7`>AJcXva)gFDHAuECx9dQDb4H#Ua9fE*dzv=<Z}|$yj4d+`^Rhj
zx$O@6)%k^Q00e%)d1{&=RI_Jy=wJbTaOk^qip?6p>+)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_2cS9H<CV~l^I(eeuc_bM;ClO+pp-t=I*^UWe4yww
ziGf$Kl+f*C9RaZ=*E?rMJa(RJnMe5xOGcYD)K(PQc`n;0%Z5nX)phd|oQg-(x#fZz
zJm_k8Mh2tHma&f3%6l^j8(P~@OMJIE{BF@^Js>q!%Ii<o&i{zyfi;cxcuEVB<A`?l
z*i=OFiSW_3Kjj;^ZTv-6L3*xkt7-RVY3+T{VXLx>4S?O@)^=Gl*2n|lR}3foD3-~n
zJhM;<sIf!DoY*zgxYRbM8yyK%=ew^KTJEdCSphkZR8;(#W9+0G=$qSk4v_J*e2kw4
z=ZKm%Fx{ZKCJFk%4xJ4*JR>HRIz0ov#8^1s>zI&v&XMGmzBTnRJpSfe^V!Aed=Vko
z3Zouk?I9Em{<PH4NlBAB`LI5)L3Fjdm{p})FCF|!a5L=D=OJ$|)Z_8C2Ns+Y(0i>$
z&bp!a0io0LPJN}Rhl+8(;oGD?zi`lhAsu~mjm982WE9vt02zh^i2poGPO*Q(9%;O%
z*4W0}xe>rDY<ciAW)H7XMva5$-GQgX*eFiL-i?c)aTfE!kFC0g&<dd1NKni?zVJKP
zX0H^gy;AQq3Ih?sI{kj9CrrbC2Qh-2eLZ$23HWHZ<A130_T?UZrz=fWgx_{Gkv-H9
z`g%zfclE$fr}@4Qu1gB9;G(MQnjcD`0R2%Jj)1#8Kz65`W)Q<~ey#E^ZhThfaD_>N
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<!qY*zk;Pk$FIK7?Ivj$<rxYij;RB|Jb0gg;=kGgvp|vtu9)>^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-<QWS^fnYwZ|PNqv3Fs@n57zz?0BG90ioLN=bY9<aG}i
z%wht{39Fk_Rjw*hW4AZ=UTHC9p-z_tPUo9VD+O}(2hCJHm>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><pm!IMW5{@}qwg;Vwx+
zz_Hm>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%M3<ym0#u7s6lo-gKggD+v|{vn%VvDLyiV*pzR$HYJ5Jke}h>Nlyu~
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^<aNS1xdvP9TWN0x3kiMg4vTu_DL0X9RJk9RSCfkQ1#{jh
z&d;WgdmvW!RSMe^9BCAY$w}q9^Vkcj1<ke*I-%JWR*<(qv-vaN9tK#??0Qot272&V
z$?7>{sq{~-XjT2<NDfg=g&=n!sAHew){bfwQQSq2%cu2toVz}xxSl&?ycesH3+PL&
z2-@E~WNDcs;Bi|guqIzN6+{G1t$|y^u{x@0C%}LeIlSq2gEY}y{)Y~SV)}!)u7Yb%
ztrf(Aua@SwU*LYiAB;$X%gKT2kI<@lWMj9&ucsBh5{)Ex9UBrdwEdVF`k3`w%b2(V
zL<TmUn>`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##RN<Bj>Z5{%eshUU#}YRJXnDofmFL&HxB>e2U28&>ebM>)8R?9oP@?$8;R
zX^MeVY#G|i$huH<>Vy#`3i%E7|HxJs>sNK$scs}~@Iv>3YG<F^S8UW^1tyT^Z(}z%
z3z4>W>~TR#K2i<2iG}sX#T)<ubx$&EcYGpp<Do!|?h%-dho3RbdzH!D<~*81giI4%
zq@F&-ZaESYMYeCrHs(+_#ziFu+CbQ9^dQ_^eoB@ChZBMhQORiBi_YaXW6j~^C$v-i
z=@3)Hs1QWq*iI;vpf3ohImNp*dsq4;4M6d;nbC5!M>+h#O|VZWU4M8r_yFmJsmVKJ
z0n_hhPhMq6{6Ra<X5W^L3*P-I!~kh>AeMkQ?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<nABKNT}p#>#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`<vD13gs^H_UgJ
zvVO8zY|kw>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#ZIch5z<QSH42+)90a;er71
zG4>1kVgXXFZ+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;+)-<ps5!9GU6So
zxiW*8pcoo@xv~{I!Ehv`_|2=E{I);_Cm`<74B-MnbQFh8@aUf!v?Ij$W=LLQls^op
z0QvDr+8P?M8gbz~(Lw$%+La#k&^nVON$89!YbyI#t7xon-2#86z8>^N(twZlV$7SF
z=p|45_9OfD*WG@nT6q$%{yW6X72=J|o8dR?Y0~B6jWJbI_>$B<%M4WE?Z`Op+NQS^
zot1p9f{8o3pf`KSE~ryPcdD(B<E({PDf?R>q`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-q<aQlDA=lt6h_ukp_SbU_I~P*{(>MBf
zie9o<UHY5V9Lw>0ITu??|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(65uli6<Jr
zboben2RtZo#)l$~55{;izm4;ry!0pGk#Hq)n@e32m${+`QljkkK(Otsd%}TJHjs(Y
z2%o<OPyTqPKrw04m*I6sP5s&Z80N6?;R<sS9myQR7k1G8O(bZ3cSu848no;P3HXs1
z7jD#e73K-195a&jUL&1~%}lm$t5x0IaUUoJLVpi>6Ubp73Rr{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+`ybX<TM4E=Yu}
z>3K+#Q&r(iLK;^AzX9l@+~D#jYPer^vWytLcFi=zH5Ws^0!9*mvmwb@yJ82xYf@HU
zy(MSFpnXG7R{{JAZX69It+Qg<UDII&x%oo1T|U>ZW~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{L<ED7}!8n?_!V-EV6${<htqm10MHf`fN>gO&
zJymz7Tpt1vyx&SWxI~<Yv#b@CNyoRWGG{I#HaoFlgYFUS#kr=&07%S%B7Oil+G|Xy
zIe?^yd=u{Y+Uc@V+WbQF4KUEK52Ip#gCdw++l%<2bhaj~sjGn4!W`wJaCd{^?)7-$
zZ<qJuV-qDTaXtf~bnHqJ=E5<#L)iI{zuWPx9UM-pEwUIUk4=3{&(H6`?}wZ+^X~a9
zX{__P#Uhypx5jqTp-9&#E_dV_kx%4;*vS6jdHI#Ec&|?S)TL)q3iP;|NakgQg0UaN
z{KEb-IiXp2Vhs2|1HacNaVI$j5MK6uctb^p)`kuI2=%&7h>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?z<SQN^
z!_t<e5Rww`ojis~9s>JfTN}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>>^euP<pnOmqPJhd<HUY(To2
zom4{Z+33QxQuRvszNOw!5*hy-sX~K8&#^P+3MN}5y+(iB%v*c0y%hqwd(yUg4IaMV
zTRkNQ6O@7$*dc~PRg>1d8IU9i3qq;Z+usVB<I&~Wqn3T>AhB}5rm%hL<UWZ-$ZG+b
z=OR%Ez7Eepx3ALmk4}eFn-Ek816We-UJUG_|A~kBb=+kp<wuMEJ-L6uKdcZ|?H#>M
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
z<sW!IFCw3jxNY84P<2msjX!e(%LCCk14k89m!n%Jz%w3nr6kp^qh@VEPk&)ky#yvz
zf`+T{K@)#QxA}MQM%?<*ycV{vbzz9g=_UctMxy09Ca*B<@^h=chOI<r8T#N`L>oWd
z(~U#Z0=#LQt&eiH{HvROSMARF$2x7-JRQPn46f=0Kr3ykF<i>Aa+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
zsz<G=jg~-AJG*>z_!l2^QuW%9q-_$8qGcq`h`P_Mcx*fmrpjJFN{5jy06knPtDn|O
zL#J(NYME7E<t5C#>hq?ZoqfB(H~uCzpnwy6=m3L;z*i*<@e6H|+DyA#H$-){Fd3o0
z*fO)lZn%?|A#<bL3n&Fgj?PKCkBWK6(51?N#sZ)d)ca3U1VtgdIMuRRPubbh-ROG(
zi0^cWWdQBlUTrbg8jp0U(>ia^%&laBOpsgG+FW8{gY+x}Hk*1S(+i_6@Zj{xdAdL*
z5<b?X<och!6g!I@xM10hHBa|U{7P134$fc&94JR}3;k@KWqWiT1)rph`-yWC)@9G<
z6SS;{klsA!xpmGpk=U#jMBls77HujH?W7iJF`#S7^+oIVSPScPGG98wENos%c>QWv
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#<wVI0$`|rc*X#)mCGAa;TduS^w=>F
z?d6H6K97sXV<FqlOpDVIo^!Dl;eB+wYhWc#`{PdMN{P#oiqBK=!UdTI)*V&Gko8`v
z(IsC**V=e=bm6`bH;B61OJ-4ecVk%6%g#N3hVph-)c^c-OgmT~lmpPzXDWubF4aoG
zZfxipohYO5<T)WlCf3UiZWrlV_DlM{8mXPs#i3J2AGbBpZ?p-jOl35DFS?Cgh<Q;!
zb9=nwsNQP9d0!&@hyjWsGdw~MKcK!L+x|p9`sl>J9BdL}u5m1Nt>Bk!hq$At3JwKz
zYzQMcnxw?az!5}65#|exY4+-4&Q4ao73EFJmi&%<z6H8&b*&=H#?Vf7CQCvWR&(hn
z6u=rX=bkYN$~L(hKuu`5LOfjZ*v0ONC|HxC2(VLCc!}1yj7Zi0nJ3{kgV;*o8cq_{
zr|`>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~~<Msj3T4W_NERSxIo2{{&{wD-$f|3>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$LzV<DY+8=JaGVR!)Wg$F4^}ZcK>0VftYIFn6RF
z{Ub}_A=`KTCS0y=xr?kt&+uJ?rSg_<DZxG#kY7GI-KPRbFf+1?ZxD7$+`~y0xrf>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|<kj8hWA9vC~^Bxvl>iRlFUS
zU|I0L?~QRU!%Uu*l69xCzEvvw{wy#<VF&|d@vi3bLv1oy6nYw_bJdYO7XFc64CbH&
z_*=Sb(U6$|SSEON-|Z@Xz1VUZ2UMRV;|RXE&HQPl$6bln*|l_lVq(qr!n6<`vzT*a
z#<3?k_vd%7BV-Xoc0`QR06KX(Zy_54qM?6f79D_sNUcA@(e{&O0iqIS@PePKZOV@v
ze33{5MI5V0gxf!3L58h9gk<f00U^V2LhWYiILSEo@{+bT&K7i=I;3{|nG>B1{n!KO
z>Io8Fo?GC4?w<fLEL!i}ZJKOWwS5tBLvl=fc-y^~sIyFIGNx-Vkz5LiBNw->iYw6M
z)`SJ)L>X>pJ7}b8KOWe2;bur6G=H{z40iLkOD`);!r~2%IU1HNQ#Kr}xf_nBdz${+
zJM`rySit<DozvhNf628`wj?22w5_Pmf~AUQ9c2S<EDqO(qAKn-W~L~zd?a#B?_{Tv
zuoJ=!JAtE$Q95VsjYm+$6f}Ju`O_094Wu(U1&2i+%11SlSEO|rvSQM*{UYa9UBkew
zE=It@#o>h7sg>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!k9<yo_<>H1u?E~f0xl+{<<3$S+HX<
zV2g#QRn}`7HJ*2;Wi7^v8<O#yhGsk87brDAdfPFDI{B^6gL+yT!l!SpOSUyPfpUn>
zZ@RG>1%BhvC8V|hb8U{4*P(9ebgl4ZCrd~u=m&NxJXMkakI5z`0s>Q`H|?9@WL*Wv
z)!*y@7aA{|5eVWL%@7<H5QWT5e&=YS#%kwQs^3OAi#=Kii~fJM6eQq<!ft?tr61EO
zJv1E>LjagS3kk1hx9}n-*U_)Z8`!wi&Ba>V%OMRN{Xx_aQ`4qc4aC4yl<Ax3Th7O4
z7fvM=(_S;0`SFwUX-QiznppsqnQO?rBc^@|tu+>JYg!%2opcYTnyjabn@i78r63UQ
zLgP)3FMSH;i<pK^^%xxA&12dpS_N+pez_zX_SHgkKz1ipV4$jyj0W!o=*}n7ZHx`a
zqEjvEsvXH$9{eP&wsyOq4$1Yy#L#lXhsz-E1{WA|-LaCp@J>}`GO5JlVQjRjN7nm=
zexC7<VSW(;8WoggWURE<`qR&J@CPupcHv*OL}R^tPTd4Bep9oZq1}ipSxT>}flj4Q
z|1wIPbBL@@_~U!tN?u2U%48*y%clW`wh>aHH+-Y<R&7O%Zrh2~uX(P;^C?=<l8KJq
z!u}QqE*A#YcsA4aGUa|guoOB(iD3w}V`OKBHvqlAdyjvN72CLLekXeUte&YK)~p*C
z+PFU~Ot||B|AZ@Pt6a)e!`Ff#EE9ICu=Bcq_!zSk*3VCK_^!nuDtyMAEXb5&pA==`
zedjhL8`M0I5d?7Vt8V!mn#@`lFCj%5-gW8PE{lVvKFyFdD?rj%d9M<!-~u~#2Nl>y
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;<naX?9vid|EvtgZKn$#
zbtijtniPz$5t~!|MMWrkF9DSyDv&yIR}MS3>NO0&cyBLVKLR?@iPJ!d<UQ1BL+bHI
zFl<MWyOf>3lO69(7Jpe|ObXl7)7Nxk=n8n!Wg(1hLaZXa@aULV{W>YFwyH<y_^lA#
zv0p2ThHP_9B^jG{73b@5<Lx9zRCsloMX!aGZx*R?L3h=3e|!db&;BPecTQv5yx_}Y
z^)g@i7sY2?pYP_RCLvd4Gw4z>#RsO;S37MvR3w(T<KigVc##ghTE?^f-w_PTIO>EH
zE85>`-1^-<fiC<An`NtC$v30K?<i&-ojF&_<=<%IxwGdW?5$KgyR<a?hXG{mbT_S#
z03_@L5wK*#rLW3pu_--txsW&^db2*dvUhQTQc%Pv{$%VJoID2Tu8}tpmlRT+;NX-K
z(WD-m)4U%)cVA;5OY}Xe7;>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+2xL<j&i!xC3|cY1fPaZG
z#eB!l78=;_tDt2hOl=w8>x2p_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<P$67xAVsq{l^I1qEs)$H|d7A}Sb7V3qq+9`ZpCI-+
z@QXm}?ps*={`PE_H(JumMSV!%x@N{rK~xHS5x&9IO)T!QOySP1P)_a^59F4?1Nq6|
z(dV^7g>=vEU8Y~t&)(GWn6aL`KOfVKy@P@ajLs|J(<bX9Z^E|nB9}TbqO(+UUw6eF
z;tl5(&eK7BqMUBP9BsqdF7gK+v~*u3z6c&5=gMyT{NVXxjcX)sf`uOsg^O07<mElH
zCg2#gOG9_Cf88KQio4yN2A=%(@|nmQ>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|_Mrx<tP%=bMh;2<dGj=s{|?7S@@_}seF
zvUwVt2joMSwkmTLjIMw>8Bx>8qpm5}9MIV*ouZ%jAzmveL?3wkF8kRrcl5dyzC;iF
z+!{WTOO?XmB?S%Ud$m5}(;I7Ph4SWi;0$!HeA7Uq>jm*<XHFfh4Rw8ocbhm=kysss
znvct8qs*nZ%LamP>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<?-5u+afFrWU{erCIYdIJBGQ|7T1NW#U|5
zFQpACxU`wOF`i-l?^7&|uPA$T;Ysj=koyq@SrI{m$eJY}L?T6`Ca@q{Qi9W7T*XEB
zLfwA*9K!Jktkd^#T-P;_?lSn<Hlcge1x<E$u%^3?fPC(sA(6QEg%3Grw?{#@cu0X0
zOOYB6^HfngmI{gJH3Rohbw3nV496${#ng~MCr=X@;k$01RFuXN$w&;CzR;qWZYr=}
zS=4KBo5k#7S!I1@d5s4j;gJdBXr%ew4QCqrS(p){c{JTB`DXXy2(m$HEl|g)6Rf1|
zPDm|zhk}LhY#_{-x<sGzgfcc{=^d*#U45{Lk@WJGQ~CgK7hENP@z1I2q)dY%?Y?av
z#9z*OVioMoUEo|E1`KG`w~Q|40yu2$!T{=v59yc#7hFq<KzY)T<<<J|L2kkNoT|Jc
zl{%Mwwq@wGD<1M$()(ScPCK@fVu*jbsBFL?i&K3<(hSBQy3md>)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)+xpCLPd8w<XcoUP`#P?Vd#`ott|h&I
z+jLPRUGRF7`%IBRV(6Yz));g1!kQS{L(0@!gmhU+T>zjF*we8E$3$G&6donqpTKz7
zHs>_Ve3e|4HO#-s<aexWog>~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<Fe5$Ww>`5XsJQd<UfO^lqUi+b)iE!f5x?Vt3%Ntrp`m6+ts9D4Cc7CV
zKRUE=s_Oe?ZRp_{nrjr|Eph$B0~czmRs`g*87?&hc1BqewyvxQ-hKR_6!JsOY`oJB
zWD!@Pk%u&UgyjzRu$sAIHTDzey^l;o%^g=5*5Wn!HshX+1dBZL1d@i+@pTZn2X|Mf
zTS$%?j?vpFMA)BLy^!*61%wQlloTXX@qW&H>`hJ^H={hN?M7B?YU2!vmA`Sr<S_LC
z`gf8Fl;w#gDOCj=hnmnB+F>F`I%nuc{6L*M5iZJnt$PK(i`)DVr8`xsp2EA*)ifz{
zvCzTi$bR~gkXv;GjT<K^eZ-4T;Q%FQazJtxQD3vJx|y(MlrpPFpu+h+0C8pddA%b|
z{_qxLBHIV;+YmCLiYL)RWYl=@DCW()=zif~Rh3}zfyEc|2Gk<xjnR~NX#X)k0~0iv
zg6O3&%JlN5D5MjT)7LRjD|+Wc<gEgq(P>d>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)ev<A=<@hN>koky-9c%=a6<4&5bg;E&<XE0+7C@O~S$U)y47TSsOrmMq?wEWg4$
zh?pn;5`X!=?~c;lVzMv5GCq3#-|^Y4&lRV*WyZ2j`m6jqlt8hY`u%l&E0C^FZ=TV5
zmk_mapY_k~C`o+uD%`Q6hgr)~PZ0Cc3jI8x2TSIp(<@7cpZ_QSz~WForwziPMP+sT
z6{N5t@Al|!%nF}ndlqkeq%q1;osY*@IU(7Kgc&T*0sXZAJ9jy?A(M^y_Ke+?+bzQs
zRVe%eL&KaaPo}5fk|5eLNPHC>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-<P*CA
z!&Oa;es7;kE}ZU)$_3~89yUMLW9^seA`cmxC!Xk%Q1A2Ex=`|XkdL}Wt6X8DzeOs%
zIF{##*i8|h4Y-3_p6ZmII@pKTC54Ij#Gn7V`VtZIylNhJ-<ljTl`N2*%VOFFI$EiV
z+=fA;gwTmmzf?C6B|5zBL;T~uluf{8_s^_C2{z`+eo}apLE#uO{IN@%rWFp<beTxs
zLhx(Hfm)7?ATcD$Djrm+O6SjOWEka?J{TFFnCV(_6_k#^e?Z&>o_r6yMgmL8uoJ0&
ze|h<1lmm>U<IV+qbFxriYb1EeZ8%1OTA!K@<^!m>UaAQ6bFjrkj`!Y4lY=uKZ_TGU
zw%1QESzVtO4PcAzXh?$|WV*^HqM3$TF+{kWt);UJYIw<Ba610$Z%X0LTO@#UA|%p%
z+mx*oDq}Zkk{c3dAhk8?fu~LyTdPKoR^e~ASP-b5bf1662=R3Xb%3!d-Z#YcOR2qO
z2__3VpV-pDfGr@!G?yrlU;OhO46%##7Pb^@d-x|5dnjl?SU<BC)E_G?9d99;+=PD2
zIzG_XcK<qZ{z}fX#b{Es`sl)#UtgjzFkq|BG)KEg6u^pq;<Pwo{%<oPl>Zm|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^Yj<Ya`k!%n+SWWippJM7#~s!5W^GO8Gm08
zvI_)c2427k$<C0+<dxrL;8+#9d8Ucux>SwYlF)h}B0q)>t&^i<!%Isg<2q%sAOQbb
zW%7ZwRS@N2MluO5wKhzrB{pW3zPHzsdy2mLW0W3wlviI?nu>y~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<g`)y5u2ZO!YUynH=nfz<SygCUO5iG
zZ5@N?5h_~BCk5Sz@i@}`aFc!8H||}-yGb|*3h!jNHJCS2zCVKbsWN8*F)Z-%DKn-6
zZ)>^qex|0DB4zr?(C*+jN8XsgVEq_NN||rbKvdZmRSEuc2pyXAiprnGN_+wkS<Mbk
zjTjjuE7uosNN?oK{wRamsoChD4z=c2OIV>uM*@yn^)}brOmd%ltG0s8Q=4jF&<rdj
z)3}LqHR-_~<_e;s6EXQQ;DD+oAwx*GMBVucwruq+kqiJ3^q%}^<#e=!P0aG4S_!J}
zq6?BOY3m}QQchDd@$R6dr4ZjF`Tb~KINL2F$_1ss)NcvO1vN$Iy96uCQ2V<%&KKWV
zS^Bb+!E`1+j#D@8a^f)U3y$*V{KV<3L8hnkOoOicM`HQ<lr7AqGqs`e2`5_F1PKad
zwdAR{Iju7`OiKYP<PYR!eUdSS-`Yi4V%@4gkLs~nZ!u8hCy&`SI!MPs`OlZjd-}(p
zif|^Jfc$ICC7)+bum_lDk*bzBHvebwBQ7y*2{VKAhkL;~)+(I<%-o;dRF|EzPS7a_
z@2ey`A+9&8C_<z*!IUO$T%OCYS4v^fX^;qt7xm-4%c%9YIER1|aO~4H42dJU@va>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}-pZl<Ep_!_*n-E_^2JpI8xnwazPdGIyN8wVH69dKn
zMp*48!x;mz`p92gbvIWxFL$k@;t2B3SBzj}z@;*Z#WDfO)}KlUh>b&7YSL37TSUO0
z4Jilkr4e3gM!!BET%?W)pv&#Fux9~mTqmgmEy-~=dH&J}3dj>ZqOO2-$+1c-Flay&
zFaQ7`J_RBvdw%#&_QuJ>0!7mfNUjBv7CnDPw*&T@oGE6<R!m_+7lN2=pvEB~o{i&4
zjlOGuDS!J@zpCJ!*Zbdp)#SI#4bJ4eZFYs}c(!8fNklD2GKdLIP_mW};%5?ubS{b<
z8LiZ5Y`DAxzl5;E!d9CLqcUP{zs@==-i%teu@{C7Qd(UEt<QN>lGY>=he7o0;>iWq
zsSRuviX=ngHYT$y8S)EHFePHJ<OtMP?0$uYpx3QIe-!Meb7S-dN&x`t{G<19e|EUJ
ziX*p5<f(euU&N;DXD-XNU!!WS<yEbW8xcHN=#SBf#XzR@ZfRns#N@+>5>=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-?YINq2K<lUuwSZ~r3{$B
zEzljKqGn*_h^RRrw!g#E<(Eev15S2byt=}Uqlevk5i1>Ki9hJI+{E9zU7VMdA?5VC
z)~|9WtYI2%OzVBJYVJ?O6(~Y?2r?frj4^RSqNApU9K-R!D%#H!U~BDc`5>cVrmimx
z3cNH;&=k4--RZkYmaaB9HM}+im1pc3|Bzw%<go)rMuug!a{#7`o7vYhvor^i56J}P
zx~=$qCc%rFn<j+Br^;oqOU_Ix>*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)4F<ve6{&{>dtl^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|R<gOYPtKkD4
zbr;qP=EdM;2fPkmBx@9^!43sOgGGnyJtlwYx<5zrH8MfRg~OiDtY|lp@@`}gM8iF9
znv_}~3@=S>M3|juWu1zJqUrOcN@sIFSd&=3BW}iQxcWotnBrKQH*bIpz2Ad3*Wie_
z>)whb<rc+gQq`6Gm3sQe2}3uRu@bV$dMJ1`*@W~Qh!(a%0$yW-Vc*fyy_XaVJd9qP
zQq<EmbTsBBAh)U87QJDIh{_jHv$|#gmh?>*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<?mq`T9#ekO?gBzPb#xzEWTDr`d8)t%*qyPPbSTUvve)n(=$*-M98aqIC
z<|mp}`I)9Bon2QY_w$z2QC1(VaVaaZ>)N%3b9$rd(ge7_glgq>y?dr72pC7AKfV^8
zUOiT%E}oYv(DpnXU<W}im4MT@qfu~n?e>)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^Eb<PxC&YyI1>e1O-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-@<I1#v
z0005TnT-!8m3DWOhQZ6)Mm{>@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$<nL(18dh=~LZ$WTAQf
z*U6Z-1Mo>u1u8J)5A3WL3+N;{L*tY5RoT_%;Z~`PorGBggtO!(1l|9^pM0+X=o{`C
zPZfb?Nh;g;kOAh~xmOiD?IJ+9)Ub7mq}u9>O<QXwBJ2X<=ezg)&3y=zE6VT4%{p^<
zAb>VhySNs#)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;&<h*pIfXnP|WnAfKd*hi7nBCEw6etwsvJPy4qMZAU;C*sqOv>IH
zgaGMT%{Qa*nnCB%5gz4dvJ4iWHV*-!*(xEXClSdfI*hbg7B9Rf>4g9UBGphSHGx_g
zEg1X;id;bIsE4d`l}F6;C?USp@B%TxD-IBG4rXxg;EmpbfFhU(-rm7<a@ur6roG<~
z=Rz*|d5qV-)RXvrg=O`&00C%$c*t&T2bHWP-X*PnCrpYq1!FjMA+@ojB<o;Nkw~mG
zAq=senjm}4HUrB3i$^7IIzYUXE?jA_4nJQ_1`4s9;{Jn+^6iRfeIF8dJj5APB*jF3
z=rnKj_?7!}=BMooj&t=!D{;R)MVsz4^*3}NdjwB=iV~F@as$xhU%eqEHgzs!_=t2U
zK7zdgzv(pF8$Z@6ID*MJBtTl)?66E+vP2GP)$$BGt^>ednv&$`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$$^O5wp7HxpHf8<av_B)f
z08rmUuu0!Ou`3bF$)h>W<TYxYqYOO}RaB&z)5-BDp`T1S@5C`sHro?DYOMv*1N$H-
zGGBNVL;z=i00CNSgnJLVpS;fjungs_T?1IJB4iTp@d00`_bV}2Y5fhtVFPB0DnW5Z
zr%-)OV98GalMD@nfl{TFq?1HT{3nzh^Y7%Qh|-i_9vgfD%n0|tcWY1V$Als{!&+{R
zY-O$=ju6f9R9G$zhlFEYRtPE+BA<L)*egR5_HdL9n~7VE_b!;YDz3lk(|vuO|Mox<
zTA7e_L~`}aVS8dO|KeOX1pY2=Ri{;6$m|=anPl<*Ob-+%@^{HyUtCwK2<}F|pQunZ
z7=`WW<EwFVct1GE*iR9j{YV5E#!f1WKl5|@q5w#PIG@&FVqH3-G7(qsV)vPEO4PT~
zo9QM;)i{NkTa(Wv0{Nfns{PXODsYH9ha|=7Ad~L|jPlZqP_U+Glf8q&gGR6-IwNZC
z8|Qk^rOy?Ag;fUL9g|8Zt21zL&$6ihOa|uXg_ur_Qd;Y5Y?G^Qw9JQmGO1$W{>?g}
z{ivthnq?kp&roua+S5u3KE-h_2bJcOvrs_Q){WnID3_E)$3O3$6!-~zEP>LO-JoPQ
zz^nECg{}xabz^np<beOrL@CeGJuqWWA~w7q3xNNXjPn3(BCCx0Mo9djgFB2=guEft
zr4u)sTd|L!jSDy9i<7a_FvOx0^)5$Cogg!!*13o(CDXh19n7zx4sny)e8m~uP-kv=
z6YCXKeQKbfqu%?gQSkZn7NwHB8XJp{FKIVXgDBpxFC`4%jN<|Ni^kn~-Z`J+-yq`5
zxjsLYl%A7MWXk?|-K@G&I?~N!*C<~Db;OiB0j%ce8PEmOr+e@o4KF3LKPD{5WQ>P7
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
zT<m!O1cfkD0ssI21_Ev7s?+1NJwhY*cG6!K1^z9;RuytM{BqUONeNM_@R9v>p#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@EIS<bbd1hI*;22&?1_XuzM#;qi%o4c_7T8sTwKRRYCt&azxX5j|1yuS`oT#
z6ii!aFJep3X5ZiS1*@npM>f2fy^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$R4nc<phqR|-gwQ@r;X3!)
zy7`eo82+|o-y64k4JColc1<9ENc|vsx~MhbFdE2T5xGpo7A=kKGtOJ`_}$87nUaov
z;J3N=kKhBmrePJMorDB@R=v8LJLU!GsHt)$QlQFB$^=GL3uq1nj5;e%8kd_8F)y|z
z*oy*sZSXARo|Fe<T73*adGV^<-LQs6{y1&HU}8=`|MM`of^K`Ahw(Oeua`k1Xu}8s
ztOA%A%1${nfVU0eOH15G-&CF`x}*#OA+U9DOCyZN94kSX&do~<bqk2-<PckPQ1V}f
z0LQNgzbgIB!mJ=9iD(9ithlg|BGkN%Ll8$t*=Q&3%6A+o<ou=p>tTu5Vy?NZ<E!)I
zcy#A_lj_Ju%(4#~Wm9WvDCj*=3e)poi{n@sJ*&sZf_`%}gq8@k6(N$^Eq%~xhBR^i
z6Ix9KDC5LP%~agG{y1#5Exz3`U_&+!Nrlv!>M)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-(_twkU<f+Z)681>N@P>2eWf>pQ<8GX{>(4|?O1g#GFwCYyt86mjrN^<B
za~w#d<zAq9i^jMeBYh)mhtA5*bpGh&0&ZLynBv{&G1}GgKrvMz$3gDUMS9)Uy<R#_
zyGRRAfM~Gx1!HiS-9h#FJ*~u@NwRWK@VtKcH(Qku(2#N&Cyq}LQB5b2CYLH@juL;?
zzVtPVkkm`V2WY}nBhOf&PknBPihTG~p=t5=_~D!NUsM46<(k>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<qP&wlo_Fzbf*@(x0dL5hQfi`w~
zCpmVqj(P121q}V!j_9oHjFrhtMtf|~qG6WIqdK4i?owBmc#YelB1qkMgCYIEjTV+@
zXW(ZjWA;aEb7HDNWHvS8$aS1EwkF`-w{#Nge_olVU~I1oNTDIxSxe|EutzjXbn;O{
z*wV!p5n|-E>^}_dfDZEh!hQh-E5HB{qyP;yHbmAH+LnXEC;HOcvGzAHMU+efQh~a{
zVG&MZwSsTMH26_e@rhUIxpnLM5?{AuYjz<xH=$saHc(lO3oA!IT7rJ>j2qo=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@V<qs`nm2^e
zPZ=Y7S7}U~`u@HveBL9Wj>IUX8t?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}^<Mp==8F*8Px*18ySg-AtaLI>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_
z4<e$}m2TBbdR;!wV{&kTTG8U=OKa7L(Km!`9O)A`7<(?)s!Zng=|VValZt#7DJyo)
z1-s6dl5Un}PUl<cTH5jq%F8-FrEKUN?F=1S(ApidvMR_+8k_qFQ8eqg$!n$M+%cNz
znA{Ed_zLTQ2x&ZDj#B6#r&FyO%QO+=75D4M!BVv6X|m&$HIEaG!41P0TrvsO9!)QS
zg4$>qQaGLxa98LN&3f8zFJ!twE27^4@hm&{!dZH`arJw8Xux&!3h1M%$ak}dI$bEc
z1TynCcC<Ll`DOdwXbk$a0<9oZI{zJy(d&yMo<lQMwM+XNE)=`lJ+#~WV3yYCp8620
z%6A-V7)yO)-=KEkkPd3;;J<y9q52MN+C5l_<QWaZV+$8UINB54bm-Wo$7BAwF@lt@
zOh0#UWmojFgK``czSD<W54$NQO@dr1;S$GIrM~I82DX=bpL@2yjJwj_!13Y6woqp1
zqRUoz;_(O=GtYcj{e@YC$@}&i{q}W6P;GGSh-S$Z6ow}evGAo#Ezi?J!!H@ByOw_u
z9ckehx6DHLt^pScVJ4=u0*(e4000CWaGqnq9ROyPlVSNHyERo5008u`(#FMdxm7wS
z?G9san%|F5Z1#jdrr`lh!^@ig(;jpFbr6NnH8V;(AfN4=u4NI(2>5<jpyHnQxNlf<
zk0h=_+zsLD>_TN(7+vRb<D^|d%tHYhr`07Xr<Wm9euC8pux7{`q)b)d%EZLJmh)LH
zaohQl+X{=vF;J%IF0QdR$OTR`m;#>etzIgvsV9ie&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
zeBYQk<Z#uFz_R+&N{+;(5={(h2<VE8o9af<&Jg_4(W4f7=*iwl0(_Va0}r|s8Ir72
zuLy>jeIN_@m{kYQv1M{;(*|O_$*}{UEFTc!O0pS5-1;{$Yh>~@fo?)unuT1guks_w
zguriAC`x3xX^`dM>z>K^AMv;TS>iZcd~)94@NDjymOX$G?}wXF;q<bl{(xIcLTK+h
z$~Y=G^7Wrmx<8<Tf07#itnCiS(q93@G8vyYY3F7M==iGFc>BxtPL3peoso`KiB?XC
zf-Y&ijW1sIsB1FEr2T9-swHiCcv%-q+92*f<L~{0RRD0K-GC+-)m`<nLO?Q2&F~tq
z0008Iv&;T88<=39PvM407cWyGnqi?5Cai3d7cy=QeCd%EJ?4QBEMVyU?5}nF-+r0o
zT{U25253zf2GGyv_f>%O<D7<pG7aMVijzKH?Yt04gLNp;rJ(euaSwfO7o2R1qVzv0
zx(1p<{4}qiEX?hEpW@|f0$S(pC>~3Qc^;s{52AZ_4?52bX?dm7!?%xq`#n3e;S^JQ
zJgxTXQOh-M60*D~6DVhfSia2~D!j=5UfAYF5QNM4k1bx1D2q90brB58DZOrvYwkVG
z*CQ!)#PWfJx9g}vXoYL1W0lRV<ka?mM26|sZ^YBOehe<apg~isv~h+RRHD4~ER>Lu
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=<Ce
zpi60WN6XHu7(o{Vh9Ea%Q1B66(NEBdTJ){g?Jt1~JVAfJ2N~}zAS4oh1-9_Pq^9tt
zKVR?D>5%s6kYPBd#l7GDZm#5h^e{*eSD4m;VI0Ao_D|eD-H@8(;r_T8wY^)o>f$8+
zzMwhWj;v{1u0UD6eu#j)Z_<xqK%qLBkaj?@+~y?i-{Jb;K6QN+T_J2zFBP)?+hPEB
zx0lJ}OR8hV90Wj8^_*!9oHB|5{%gY%OOr}x57y@-;o|XOOB_=u-cFuB#j7<Yp0Bjl
zsKYl%gwbH{3B}T~%GX9yTJc?*@Q3gdup4S7hO*hdgp2-GJCsc&_Os%j2NIs)NeBML
z#c`%!#8DSVRyCfY;XPOP?;g%zy@@zvVoOsR#<Vg{dJT-t3`^mKoE`zWeeeJ_^D?bL
zIiR=MC*(rhD#zI2$h#Cxev<oeSJw%O8A4$Ygrt6r=>^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<L_;sZ!10ds+ls=|Lhb?L}zAPcj=1M&}0!}7STbFQpBPhoO
z--)oGeuyG!2FCyZ000gqzTi30-N^6H61yi=1b~>;N=BII0Q~Hj<^Or<GKsNuW5P|0
z`|Ii)?6{<zbP2EaL~^rEaCc0WL7fsxB`XHp98ZQTT=o+cLEs#2?CY$__TD<4^oE_c
zNsuQwO0QIGH<%wNZd9xhEwqOB$ob$lhR|b<c6ms_I$xr@70>_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
z<U5C!RrAIn-vtw&9Dbgb2kPE0nUjljW7(4$Mo*l&7pK-8_>vjRh@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<Pn*
z_)Np%VMyClX>=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><a%{luw1~GHA`f?
zbD9qg?JBV;yksS)jHFdb?T1e@%!I8bv$*^AZJ1lO?_sYfPKV;QQ_~t-xnCSy0Ntm$
ze|xvn*S-}??rzA8!x*)yOJt>_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^tjo<DMPF_*s^ezZ1Vq*s~>fmR>~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!0<hNHb&*b-b
zDC}w^i+(8FjJebIYJj-b#vef6A(V{X@>5<!NFv;00wBy&tp;rg;?OX~a(2)c^B?PI
z9xJx#mf-BMhLM^X8@zjZh=2gN^A_2s8J_`_(8PB1O;d!_ZSE`c8%;4^=x{f9EbVa$
ztAD0Qz4V(|p92l&7fX16kd44CpAa-0_$~*OTAB}r8pJO-CC{bw993BDOAzc4jr9j#
za|oBV^ZZ49>$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<m?#
zu(e8Jdxxcb!U)o@AtYvEVOdyCRHH2By(3niK?-<UL=XS7baxK!L+AKSYSR<S+QU*_
zm2(x^z0C{YL!Fu5e%r?SE)3hA=HXJ&-90Nlq0BF3a!q5)oT|;-8g6?z%NjkQA!!E%
zS!!A{^xX-%XzC^ne2?t?m4_Sp-jOe$b2#evwLq9*u;<Vwcedrh3VC}q*oY1%{Bof<
zgWU~nv0bn+I|n8Jad!Urf;Dpcup;H(op2%olHU-d6Vk|8ODz9#QAc4^^u1o?l0aUk
zUKXx<wIvN1Jr76**5QE!ue$d?H>&vex}OMV-Nv3>0PnO$W6Z89G)(aFS52i6%ARbr
z?Y>8u;A(aN00145AS^h1;rBQHj{&zkmUX>#%$JhaJ|z{#U)T4Z$d{}#Bkn%G?<Nc{
zU#e48tBok_e@HAXeHQQD?OuW0b#iZN|K;-%sRxb`rau?o%>|Py{7EOX?y;HPd^-_b
zxk$+OLB40rb+(0Z8beuB)i-y~psytW#yh?SNFqRq=87Ld{Y1mlRlUZckFiS?H27JH
z5T<iH&)wI)b~kRa9?pbOv)$-scLK9soYyiE=3ztHCg$}K59UuT1as|=%}HTug+_i}
zjQfrdOCm+A43bXs=fQUEG14)?tlGexR51j2dM6ihCgN1azBEzEMidAkmLcBb99=W2
z`q`G9#v-swh)$6Rm}GHNC-OK&JNC0(MUu_cmQik#+jcXi!XGb1)7qfi+GFHue9faS
zj96zOWdBN@X$!nkDJM|ayGwt3x&O}(ZwYTF&i7gZJf(a{17xgeEf(w$8;5)Kwg!)H
zyhvtDAt*5Bz4d!(!MJu{VSxP$f=cuSMDDXa3x+Xe`T1?;H5^wmdiwOPTdyh_-Q--q
zxit#JEi8L$lvM>SEX(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>><TAoI=r?`KBOSxLoF2U_tCPl2&-TID%Qn=E2?IWA7!9aGw1QW%b
zS_N+CC5>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=
zFUi<kfHN9jObGeA1WW%A1USlhB)lJ2>o8(2SAy|8xT9o%>?*Rg+iRFz)PgDG6df~=
z<WmfIo?xB;h-QWD;&E>C8XnDaC^>U#`TTU}JD5~zsd%2I?eF&};6v<cSGoO^<dzc+
zxAGN2P_cZ#5!O+|?z~Ld#tGIyHMVS5y&c}J;;}{W8nnoyx6MkTJu{+rvM@B4hHT<a
z51tSL2U)>MEy{z~?Mh*p`8Q9uS=XOZq_OB{^W<+T)RNom-P$s0mf@s%jx@Yj|1*iY
zs%DhG4I{m}IRc`bu=Nh_<#aVW<CHr8>}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#(<TD-!13NidC?Ej;PNo_R;ZX(~Vr}esyxdt6o}z{o
zlPNEyxn`$a8#{?<aO^yuOr!5KLb?(Ek#s)6ZeckGTRjZ^ob%p3b1+8RpZ;|2mDwJ>
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#i7<S{i?@z;DW{T@(r)o3se~as
zw)#C=zp)YOI_A`U`7jYpw<+4=YM0+*FIK0hO<)#eaignf20v1&)4o^p4alfYT>YF^
z#oqZk^34f=x<Re5R54D=cj54>PVm=|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-kWIzF&#1u=Ati~~{j$2o=H0J<E
zr=9TV`hG83kue<wc8T@ZkgvJl)H>-%&2yf00J(Qs8Y<JpfMxQr=iQe~M$tv3y_m3l
z(i-_8rRmhXyYeT_yWW<^z|9cKdpUzu<o%j_)(MUdvdj*H$8P;2A9KcEOE+hr=o!zS
zN=90y+;n<2gp7+9Di<bG9bX#K(sr2XmOA8Vj39RV7TaBBZ4TR)$L@ZNWzqP~ONlTc
zbh@w?-^^$sujG1PN)lK(W@lh$Uyj4N!>DGTUY=4W7J@-oo1!!8Lqs5fl>Z7ce@6(0
zX8^VzOLUj02h$}?0lz%Ijv}=bBJ{BCb>rLUt<xrwaX&<oO~E~k2VQY()Vx*kfqB+8
z69}~aGy)ld^XCFZ(#O%m!(J#{)=mrIMMHztp-MYCy^}A%TZ<En!jkagJKH@*J0p3m
zKR%1&=9mGV%?5<M1yP*Y9dn4W#EH`wMm%VvgK~K;JL`9##Ew^i3{i2yG5HDX*%G#6
zMN9u&&hO|);eeikK{NJ)>FWhD7|n-QNZAN~b840513;!5E}wHp`p1#Pqa{arFwFq@
z(Ok-%aXMslnN2X_RQLDI1wUK=fsTn7Y<}=>QG9XQ`=FHb3k*7~`o`!Ef1u=nql^Y{
z1rjU)Xn<QhPnZqW8LN0il?$A+BH8~!XHR|AYt*bD?-qQRaWhcD+GKjIVo4@bGeMlz
z4A03P$#z3=`$rg;6dBE(1Wm#Uo>yD|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}RDGx4w<R@KjB1nO?8$Z3(mb}1u9KBZuq_?*Xr?Tt-
zQ*EE$z<hP|?n~;AK0r=$o=QjIB_#=0Kw{ae>J1!S{E0B?RQk@Wf;%AJH#(!U>YXw2
zo1y<6kGqj{+JHe9BuZyRm{t~vG5<PA479@}fS0$XrbnV4Lgo;J{r5XR^=^|bKcWYS
zJ(Cv8s&olqpB8nq07*_c!S+&YKtd{l?JPnB*B1GTF!Pf%;X>$)t-mPlJNjBVevfER
zp?_|<xyO6Lw?4<uc|3pQNj7v%EZH%Q#4*1i<;S2@X&Dz%W6DFML-#kazW%aZ#hNiZ
zJkB$qTXNDq9{2rALCWmNjTYF)%-(A-FbP#%EmnY{NSKKKZJYp9udVL~sIGPYEgX62
z2!geY9IU7HZc4Q-D|n@E)fV>~G{QDUbWI%T-GtouV}&)J43M+%2*Qz0=W<%otF|Ua
zJNi|Z@qgGB<q5XJLApQXM~RZSaKtm6Ld!>MX;@v%dL_$3LHOP_u*&XiaSSr~sViNL
zoa}fg-bijW6w&TUSAx0}xC>*bgIF}L^3-ik%D^=+%4WRa?(=lil|JU?VC|!G<r|u8
z9kN;JV0#;j?4Q|(3+97bM<)5NQIqfa^D@gYDC0l6d!YnyBlTiJE-vdg&4PONIldC4
z3T@~)tS`A<7pL}d=?dYN<NI=kRlU4JDcdZLa4-sn4xM^<D-c*oMz^T>6_Pu-kF4@#
zS1w?_>NFOs1KiP6bH7K61Am@DA+f@qEsYi#t-?Jo4Q|9kA<Pff#49muvk0o)>j3N7
z4N4$9)dt$*)R8C88P1gO)~-Tdb~k$K89$F2I=C(g9&R1GTFC~nstImxqS{gQya+?E
zS><K}S!cMU@`eZ*Ora=QJJw1{D;C?>xzkHWsjmTgr7R@U?8$f!e?T9JbryBCnqWkY
ziPNUeXCYN<`pcW~@nyb2p#H%D6KHApnN@?m)OGwy7ZRJxf;8hU!``~)u76_|?7-9D
zmHNK^4h5+>pgQubNgSat|5OB}AS+<RPRa$X6{A&9QtPb;6n=fy3_mnrx91K3(`C92
zM)0Q#lv2R7+g;vTr+(@tG@kK=%qUQE@(XqVH?}gX%U>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&eJXI<zKd3B2eL07mKF=|EJ`4Z{fUs11z?{?+4zKU
zy#V|W(yH^i0>Sqg{#v-T%Pw8)gC^#5-{?b|9}#ng<ocvm$LEHDA_VV6_yo9H;&#Ja
z-x_@UJTo4mcwXbCf;v=Sv@>FM-@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}9<BN0jsT4w}gp6@+tploJCfjCox*ndcH<
z08&jZLq*eYcDJ{IU*ZCskA`GZ+-a|WN%Se{)s#89%l;?Bzj{7;6jyJYSv@KHCGf>W
zP_(Xq@>wBpbYYBNJ)%FiWQ-_Q_x%qZ7-1Q(Kt(QxRj2@#Id<WUm&?qPWo21{4ZUp8
zP!YfRo+tU^b>c?LUux+?f{GrVD?eXODXq~crbdxhjzQDu5LVY}Dm;?hWm&DNOTumq
zjCjq2X8fkL$St_A{9yfJ>iGpVzn?{Jddy;<KItb}Pj_Dr#Pi{a%m))+wuevJVZFj%
zs24qkDss)D2P{0ihXI!QTYocF4S3~;TgK{{`ZW}nRtl1x8G-^_UKXZ`2J@DbcN#>d
zDpHJnkZ>Ca;%P-(=`ok9Xwzm}%bZYB)j3BRctf-wEWis;)5?d<n2PjlpZOkkF45KY
zS7;e^@$I7Xh0qQkgAfznAybls6662?0SKqvg=m~_^5Zkj>BkV{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+o<H~&TJoa8T}U`faxetyN4G!T1tpfC#kg%&27$In5v+!5B%bUm7T$A
zsTrY2#Rv^{hODM$;GR(j)a1?TZFf52+Y;COw3vuiV>A$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;XIeJpVH<VO
zNU|M`_4S`H;ZDJd+MPx#5*dYsVz8G5TG+ZG$c^&|08Ec3jE&}V(_>fdRWd`_^6a`T
zOCW-Y#Y!pMx;yd}Yi6o|P8cGHa2c?6vPNjv-9l_0$)cV=lrq7EmJH2=k)fe<?O_Y<
zlZYN(+C%$HN_zJ?Y7;`)S)obX3+=RtAP--ejc$&$8<T{B3J>59{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*<UfY>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>IK<q7Q$cI2D-wlAqg)bl+`m*CrA>S(e<DZYvv-+1eAE@TSDXOBVg!VEQ?gymN`
z1qW#W#(*ILi8k@bzapa|T_bjoN?g#V57ew4K+271@iSc9U-nniSY%6UmB>OPr<CLg
z=<jSn*B!yav4I3-N5k`gR<XiZhv?g&)4kc~5IS4L*xgWlq=dTD8okn~^=KyOF#$YP
ziKD2xS8Sc}dia!1g8H(noIfJH=9FTeE<>v}GF3y-FnFMlLMxwg$-i2rDeMS<7WgEY
z<UTTLhhN}HQi+5#)flNKv(^e(rgZmU8*Rz0?tk;W@5|!LZR<}Kv~vH|ahwcS2i4Po
z@W*{Lhvt_9K-8QOR3;DF15<3F4C0+7G=2)My(MY>=*WG6T@A>=GY2+jm<I)J47H<m
z{n}QwxeQJF8fS>6ti`opZpwi;FTAn=r<wN?hqM$x&PYXw2NHBg`Ru)uJ|R#pH4jtA
z){3eFgB&Br6|%p5%M_*-bD5^l;nGIqi(<d@G(wmm$Wc$SqCNnd{3i;Rp?X2B*PDdf
zX^uQK`f72B!wuzNgn73sFjiuYq0JqH%X{B9TfhY<m$8OCw>Xyg#;{%H^<D?|^;|>B
zF0R`iD}Jg*ssBR0ub?qWX*1Rh`XHuQ_|U0{d!4vR47c_|e&`S8WfR#ve;EH7KhNDM
zFu=_uWmV9nq9ketmX6uekH<oJU<e|BE1{g7s?>9Bz<Up?TbDVOcfTAj>0%eT`QlE3
ze1%cx|LB8?%HEl~CU_WJJ-2#b<d={|?hC-!%d5=<V-8VdYrKDWA$$<7tEbaP@Q$LC
z$)Z@~h12a}I_I2N+&9RXuzc%*kqyzv0KNiO)kFx4pLl4mkV2n16=n}DwmwsF-o!6R
zeGmWuiSZbzo*2s604~Aq^-4qZo}v!&s?K%jR{xU(Pm0pSGa8Mfo_#gjVBR-i!b~*e
zzelW|;z(VVOV<&&FcDjtv9VQk)u!5$Z@K+rn0Z;qONcshqm-2GxXzfRhjqASWDbmZ
z4use-FQ6pYY-@*XPzUKw99!;v)im8S<aTjHFn69jggm~^&823NjIof9P>o=-MF1;#
z$NUU_3@1n&0MCSMrYosc_87Rzik?#fPDN-?<BfS-2y$F16+z;!?rJg&G!5D()XQz(
z-J^kyq#J5>jsp2Zc7zrYv}aa<#mJzOIo5^2Z;5_@V}$wTy@i2`&bWA2tUYqXIT`p7
zbz|5))%t$Nwzv}KJ^iDD%Ii<--|uy8+&39^sIfdR1ub^Ol1J&}^1Jxr*t9j$<y-TZ
z)TQ@iw2%7P7(xa(T&(JLm{j4fa!QkK1kc_yk1E_I6>0|d?TGxR)AnWT1VaW;(jU-j
z>rCh(pOz@vc6Pb2=J;Wk^6eDt2Ja%YtAuy|6=GG_l6D4gZ_g8|q5u<RW!#cOc_I?^
zhJgH4k-NP>{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=x2NS1z<b|@#NxnJ
zVBUwwdOh*b*>mTfEvpo+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<<TC!+vRSMC>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~m1j<XyRweQee-R$)A
z>e_57Iu16fu0^WKtgExAKv07xXJzrAGeT84jKB_^?|^xhi^{ye?nhOLu9E1e##fuM
zq5J62;D+I4q7L*hiiWqj7@ndGkIHCXS_*E436*)FH5+z3>SU#ceLi{5nTfP#k+a<!
z{j26K(b(4hGd|)}QB`p1dSc~GQ0x}##r(F0KhS%bJa5;3gzO&<*yiv07DCPjn7=|z
z4>6Mpz5oCK01;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)?katL<qNs=ZP3y&4v1>d)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_<Ej#FvJ)4lskW&#Q<UlzYemhg2
zAc$+V^;AgP``>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<<n5w`1K%$K)H=W><<Z8n9{V6Z5iZ{ux|PQ_#jX&kz%R+QIUQ2i*t9
zB5jlIGM8%l2lm7^pslU$Ic|@FQ3kU`KUs^vv<DmG-lvSL;<mQ|6O3E&8BGkf69PDo
zftLhXhuyzDhVI3JF&{T;6wm+w00002{e%Dl+yYTvXUw@jYXF)6hcfq7qWO?x?NayH
zcWA2){eyP%2+OdxR67DEP&=(yyf!ili%@*HSSaML?Xuw#YZ*%|{#ZSG=481ewGC&i
z#-9#72nC1<hCvdztYZ*>sw~dohZoq}-&;-Fc^V2c0M2-rFQmp>95K857`lGIn1h)Q
zQYKs}&%{rw1{>s%#%j3TQ7Y@VDcds=ChMpo2nzL&)RMob{1Z1*U!9*<r5GFAu50=L
zNUa8pCKr~XsZ7NpSM7j>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<R{h3zVV5;0Yhsbi4$liY9de?Z
zZ7gA%>;0}A>bGBBZExojsJ{IG^-abF@AWE==LJ6pX(gxr0<Rpq5e+X#EXZu+Aa*4q
zxdSZkb2rz;n6uEZ$-=+Kw5i&HrH4Oo<?qo!6xAuc6lvS=3^zTp%D2-}aS$Ar5J|<B
zM*y4uK*Nm0gRRN;fO`G<FO)5FB{CuN(i7*y?<6*5g-I?29pZ?$Tp)Ny+&7>^a}h?1
zK~}!z*$GMzm2IzqvyYWr9?IC1?wXG<hlB0=)QVw`M%MH`q;qlGwSnDeXYbY}(6Der
zF{Hsq8K&e~qJ(b2)uF%~)R~aUfGeWmGyyR_*h8@`ujnK313;aPgFnoc^C*npnzLj?
zg(wVN+qgO^XOVU)c$3nWzQZ3V*5iu8yX+_u%PY`{hJUinwlb%*3$)DD$jziqTa+b;
zHKFi=pPEEF?5iYovHM<h^Ry7RCzCwDlY2ExrKbI>37ziGcN#$y9WLHcD*#wmZ0j9!
zYChEQs@>0||L8p;<XJK_SP1fys0Z!Kswx^P`Upf$Z7?mV{X7*vn}WiRjE|#`&JFts
z=mWxt^dm`+D;i0kDx<>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;$NeQs<k!924aVFQDW>AePmvyYPUNgoWbdV2pOSKM7geA3%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!<KHv`Ch$ZHf<A%4CHp
zFk~z2B+wm+395uEFB%bHK(pY~<gr!u11s6AM$R6l#E`m_n@CGi3GB<-;W`h0zKLQK
zb3W7|viVBPpWaQ@;N_*1WvE8w<^hJAy~d6llw7DnBYrR-dr%NFb-9~EwyR^q4g_57
zI51B=+-b}AV<$SPy#QzgiZc7)alL>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_&JQda<VIk18+{^QTrvBmXs&+FK}Th;wM-1~vzO+J
zRVzYcl&~#LZf=^R^c8C9#M~}5j}yZikG!cb{$MKk(T|sc1Ma&{;9Va_+pDwVTy;*i
z%M;Esc)e6=+o8-8fHafN&Ozu^^M`Qzoedvn&zY0;C&likV$xA<r`sP}{Wi9}p3`tk
ze%+$MaPEvTswEK*2hMHgWsCl=P-CDcu;ExfJZZ9~@e3N;)qCnymv{mMugXFj-1!?a
z2R6Qkb&0e)jH*~d>iZ4GsM$NA&h+x*%o0X-Ry>+aHYLfS5&?iDT=}UBPjmJR9KvE2
z8JYfUElX0q>@`mcqRl1Fw2jN-pSUJ|G2)PDvrA}fhcr267UjySFK{AEGsB<$IJS$x
z006Xr0s0HiV*mqOMG$lGqEixj-66g8Es}<!%qwTo>NuXYcDTaFPnoXVZJ$7LLanU_
zazcv|(qeRFv};o^K^3vK2U0IyLjz8RtISnX(I7}R(Ex+_3mVDt<R6_lYdOYhr+4sD
zdq5GD5?x;f8yd}*kReKVo0KTs;C4NF0S8O{f8iQNXqUq#7MNs8=kNC7_pop7%jy?u
zPFXD!iH#!NI6J)z-t@V?GvCT@^Qf?QPHma8-DDmd8S{G)r_dEru=r3|#6`O8^#S#p
zOW`#mMOl=`1}Mt${(*VC32FAS-&}_ixq3ti4Sm9S{?{qMmX6;)XA?tjT-dME)(`t#
zyO2Y>AH0K{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<LYfs(c?FYXMv{N
z|Lx#uDw0fW`Z!4aN$u}t1}|0;Oix_lm+Q2|v-PtlREeV2wev^J<K+OA>)^PiCT1#f
zaA0$c)&$F2C#Vmud3SqEFoqt?NYa=qj5%YO6Hq%6GHfez07)s-eoaWwG$*`1l_eRd
z^0bcfYzb-rT3vgybmQf&<2Sb=r;}a<G~dlq1gIRB*elI!h{B0_kRFGs7KIl}T6VCD
zU;i0?FhUw)s8TflrCwU#q5*p7x&?^SC_1Ig-nWzMpcfEtY0FjlA%-o@W^|`(p4Z~$
z*N;)-exWdtwM9KQ_>ko$+M4~WngJdgi~L4}UL!+s;Z2Dj#*rX!k)m=;i?omk^>Fdo
zP*&|{{Ymg6@4B&VZ>69wTL>!F#`!~q9hV>ys1od*tT^P7%r+)x494=<w(|tCZLQ8l
zv4-N{p4~?KWD6T|?rHn!Y*Fb0Zh_Lep%T6xVI0KF8AFz)d{V{<xbVQK3d#Hof3L2G
z6goMAZC*3Z(wX|7E-2u0h8AGfJI8$kq{wJkDE;F;JWN`g;$jJ$4th4wRfEC*BD=0N
zsQh&&AaV?nD4X^R`E?xb@-ZAM<o=-4G#ig-Wd#fq*6X2Lzkz#3s)i0XHE~}Gt5#7$
ztcE77+tHKeNUY9Rg7{M&Sj96Ta)c_CWk^1TyK9K)BrKstLpxhzTdDlEB{a|XLa>Dx
zE0cq&dDbasFcf;>RV-_Bp0YlYaIG?6Uttu48QfO((0(FDh$>;M%pqXq#z-M*nj>Tf
z*?5kChz;<l=Z&{0o!d!y_C9u{byXmQ6wds;KYU4kgVqpS63Sy57xA@*(=&JsC^=G~
zmJlP)InF~6UiY6WyLb!4G2XRY6O(vfNRNrAXgrtUfAdCyLppSk5Dr)e1#FUE`Wuz1
z?I^8<P*wR@9H_}EI+}6)*q+pg!M~=_MeNdAkYb_l!p6?#iL<Z6AI(sri9u>?TD8<<
z)UfX|99REPe}U*Z<b$6|tdMykNnweIevSgayw;d#XvTfRVIN|eSo#BC$8-kp{Kn(Y
z^u4*Vlrm72IaL*ocv84SJ$WocEb3)q?(tsW0&|eb^i-{<8nr%9__mEY4>sYVk>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@MC<q!!#5~M#^j|(XPKmK)ydqa44;sY~*Wh@JbF`w<7
z$obUe?WN4G@8;MPiY;rSn%<?m`L8)!P=DMMKLswJlgJ@c85k%O66oSzQ}Us|{frIp
zEisEBM(YS1(gt+tMmeOKf%|o@?`JJ+1a))vwt9??37is@J_FFs#!24~(HGBvXzETw
zU5R-58+ZJ@Q$SfaQ6Q~l*(mDzfK(Sk57nk?ZHOQ}N-*V#kq{<-O#!b~5SMjVjO&J!
z)r}DU!S+>rk<<^eI{__J0eZU#7}$LvxwY@A_OHHqhP1a5M+UVDoUJj8?haT#oA{(a
zm-okRN~jnN`~n-2Fpc;#8}q!8Wvqfv3Toz9=D#t&VJpNOrgB9?KqaT@;**>B@<HN5
zu3{yZK(O+^X?)vDwtCjmvwo?>YR5h`Vf+6)Bi-2Hs|z_NS(RfOXqsIctc<DNN6W`Y
zz2=3ssaPNyAIg#cMVnnx@xhJ_)myRZIhvAy7_0~3wuu>jTVN=Sv7GOn+E`8)n~}GS
zenV$Qv4;Gk5W5}}SwCQd^^nIZMr$F@xEBIsNmSsHo?lfjC004ltpvBc$m}i;N#xfC
z*`n*ay~_LxAo<^o{Tvl}Lok7J)B0s<T@w66onX=w?x~vbx7?O1*zR^LiPpj3?!N~e
zLAJ`f=bG}kDs6i+&iL34;Ho#%mr}5*KmfN~CEh?f1OvMw296$+7sfOoPe^%7Z=Tqc
zHVaSviHc0ADh*XIy=ZBL)5nm$lPH9;UfRba!FZOfUbjd(G;pediN1087!#{dZG97*
zzgK?{riMe*jh;wUf%Y#EN+_0`dP3(ans-7ft#(B_9zBH*am~C0uR9)Mwtw_Mw%UVB
zgdp52<1Ny^+6*?YT;<@|AD<&Da^=C(c3h4I`>yLe)}U~ip#cYqldIPF<m)l;M>6z`
zu5KMeVGDU}ScN?DjK>_;L)zf^KQ|j>C~W_(mqzf`-o`_43qxb|FH-U#iYj3vuz{cG
zWt=B6Bx<{!COiG|%s(BZiYpaVrX<O)y6$ALWu2aqB;aBtqFkdfIlF9vw@N5b@^Ton
zhV9JpwelZNEwQ=PLYq!|bc1bcYy&GxzbE8V*%dq-j`|CipMruXix4t^UPcEGTD$s!
z``<;1Ye7HAw?fi|$OaUvqpP3;x%tDBn6tz3T`_m$D0->e+$GsbL(3?OoQFF$%i`A}
zI6O8&1-p$gr$q$Lx%K*oH#S&u2125<vigpCyCi3xyr%pvD5;J{ZR=|)$DEXQO$?g?
zH1>bz71K0M9o0+`g<R8Lwj2>>gm=bUZ@E!w-&vndG*(k8L!>hi4V;Z(VG?un!oo0+
zLIeyOxwPm)Rv+g{_QIqUGXZ6<ZA_Hk*a+njnFSV8H!kC+cc?yt`dgB8-s~}gv?YG}
z?;lCD0y=|4^mm8TYX)pGFvmhZSMg!hX;W<IMGNBC$_R9_hWl5eCrH7nvJT$@*zGC7
z91(3Q_+1ty))(NJ;P}^kH0ZC*Uyl67Xe$|Dt6QZc!|l-xP=Z(Q9{N%;4z|-8DfJ}H
zbeFHMLwM2zWcayisORYPbEQyhuiEC^m^`&U;TA1n59TVIx$$llH$f<0f8g#$KoLF^
ze_v#6wTthGKyPrwNklYmcZ~3)uwZiZxD4n-*@BbdoKY|dVq?KA;V7lO#WN3|WckWD
z&Uq3Bqy*0^HgAfIxn0j;#_(1KdLYAmB<(xP6EVB#amxn;Bap9Y)i%TQjAAnj(U9MY
zlQ^{+j;t1?uAU3`7)iF0ty_lItr?vt%Q0{(vMNbmWE(rUotL}3(jUpAHb$s1NjuMd
zg`+ycZncr8k|n!Od0oh@K`E=Clp2=)Y^5^S7ghRfAICM-xTKP^VEA|f*Tc|q>iJr)
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^<k^rSUc
zjPQ$Kv#{dKk2o5GKEQiFG#G4oOvbCcpCRD`nr0|E%gr7rorUV6uMUCvm6Ae*<dlT6
z3iG%Q(}4P>#-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@GZYUY<LJfRMnGx?>d?9Qx@TC^#+t_)VDt31e4{WE!`BoY16oiKk@Y9@ClEKJJ9
zVwB8Aiqse_d0ie!j}e?>ECPY*ycGTM+97du&(d%V=dgs$te0|CkJPlXGgr+O-oqc&
z^8f$<Fsz(nAg|RL)R(*RmaGpx5ifjaSLC?u!`lcH{vFDsVy;z{jq+MHuX3TJQn@a4
zPt+Yba9(T0#kQOTq{UWqD~dhL6FHwBpC9^;X<#lokAPakf0aC-O*|y5YMP34+&CR6
z^!tABBY}d`9)H?blv(AND#BLrou}}EnZ6e+^{7uAf%Z-L=UvcSX)KJ*M;ndjmhk$|
zUO(a~fnZILi7(d4A^!QgmXQIxRyQ?PXBX2O<{$LC@Yu~r$ueAggRMN6d_SvlY5v@q
z*Vu<WVP}`H#oxYB=W?|ukYaG@8T~YFkq*}V$4@x>QoC1h|02uvEg;5#(C!PH)ySF#
zFbu9k8xpoZnaznlb)=<J)Gr`ZzLZsE&+C7<*e~WF>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+N<!sqC0!KkX$o}FzOTm<I+uR
zau|Rha)RRTFOlcW83G<+J`;5#%#4r!{UiC3{LieJ4o?QnuDnRMo7Je!Hw8*b#3K8P
zZTMu57)>trIemmR-^xktk?Q~a{fGd{VgF9BKmY;@%K>cx0FmLj*1DHrOP!LFPO3hv
zkwK!D<OCg<>C?!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++Z<O9A8S*=m0^GJwwVOfQhwk%k*aPB$Gq=f7eeR=ZQtvLE#i
zATV|n+LJy50=UtQTSr5yHC<0(^r^G1n`kwRwP};%f{y|UNHMAK+X9$THv#+;q5@RR
zp&edb@1attGb<ea8l}N9C{S-M-ByEdo}D)k$hdsdXhM@r%*%l_8<*>ud&J+`(s7a`
z*6`8HRNxsm8&>!Ndje<yv)^R<J6R{$KXOlLB5&-{0@)Uyk$tmrrnsj5ms7^36BEz7
zD(@*S^)=Rhh1EIusWe*z&&I(?Sp(KHS>~p=%sp<B!o20*iF)O1W(5_@Rw+xDuh3JK
zZGk&{CIkj%+cvd<CrI*6VO%U=k?8!B9K}$!_<d~c<So2{Yl_8Zg3eC-#4wPi@=<m=
zUtOntp}FF)YCxj}p8O{vC+yL*Sy-Yj#U%!%qT;g+qYPoVB`-Z?PRXs%jVexrrP-~1
z01jMiFGG^zkP?LY$&2Gmz2BA7f{*!s8IrWw8!=#zJuSrcB}wpveLzsal4#y3VZGT`
zjCFeI3HPTw(r+i!9W-T>(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<jothQ&e5<qg(;ah7k;Do+(%V%eNrB+_(GC>
zU~YZ|l#g0In00zvolD^sa`0sQ&d)<bamrJ+erfoFflGdc57h!*HG~AKsP+N?RaGR7
z2G+zK5Xj$lU|ZOE={d(m|7YtoaVV<#PM<g08aXlU852U-D78{@C;D`q@>;YlE}i2F
zCs}>7PY(Pb%2PZjCzAXBHUIokfB*w{00)$S<M!atRoAj*%fUAxGRE=khD5=4M)iA(
zI-ZYqt%Dqm)Mz$6XYxir%xhb|BcX-t$L+k&?S|P0|JdWm=9b?I6M*GCHBh{76?_mH
z(*Zou=*K>QQ__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_U6<Od|_2xe?dpY
zx?GT;<Y0nL5k}f_xGamy8=V4>7(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;kZMdSmEg<JEw5IW%4e?Y
z<1q%m<1&&}2EC-lr&xQ#pBA6`8B*IBz?S7a>bRtQ<L14p=GgV&;Ti*{bBu|T&njvc
z(8PFd?a#=j2Z#VfV>|!`=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~g<Cv@
z+m1X52Ncb>JCkE=`Du<u^~ZgpxOm0?ss!XO!|b9V2fmX`MRxjuW1pz7)d{>j|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^<q{~xYYkyR>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~D<c#PN&C`WF<2WTYq4UgeWO3M3qvbobS#y^v1UeczSPs|6H2ca@E
z`yog$?}{$3#<Zovx*~5b0*a(GWduu2%>7w0u7x%$-EqbIKiTo?FC<v<p4Q74(bmY^
zKkNlH#zR`0*=Y}KoN&?GZ`$v9hd?}=t>J*6&)R$GeuGl4vB(w*NSu=0Z7&eYdxaB9
z&#C?!7s`icA}ukwEHMxPmBX?W=DeFI)uJ3;2E!@$ciB9fxF@8H4y~KFYx;J8rec8v
z0sdo(Gl!*F2-E*<jp$UE((e&-cS;)uTjuvi9j;4r4{}cR!Ah1rz&buQhG+6l=J&L@
zy2+`@-tmI<nbLKL6PRa_c0ZIledOjiW+HS0ZNid@Z^$C>2x%>!pENtN-6{WT@y$g8
z$E5#Y<_Sno=fQdjZynbBF-=<0(^4kul@Xsug6)?XbmpK)<jJJ%`l!Xu9CSyn2Ra~B
zSu+-xEB`(u5GoM#47*+F85`~{KbLY*WKpRh2s`58i^_jSLOeC_aPe`Ho9ua8uIRHU
ziKW2zlur0#JnW8sWmH8YWiv&6=Xvudf3_AQV2ogP#YT9mux-;^<ea}<_34q)(HVA{
z5$)_)?*~9Ah><(|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{n<nRJ2@<x2}I<
zSXZ+%ML-M=+0>G(@V-G#N%(#(loU^sKsj`~{>Gy^;|!;&-}h?w;~Jxr^nJOk;^H!q
zRO>$=UkRL7xin7;_dTKN3*gqeS<I)M&Z!wzu!^O~!}ooCG1S?%FBuCeg}}`|hGrT4
z3OrpWJFa2uRnv{(oJ6$tpkE^~WXVN(>tXPaJLY^NG{suLknl}CJo3hBTu4T$1ms`|
za!XL-prm|_5PD>h2&C=*isO?<!igO`%oy#)9kX)yEa}MjqzSqUrn}R(P8?>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`Mn<sX?*WxK-N}4C^L|ndWb0{OlqC?6#WR=jOiM
zDCu;*RHdE61*w8VXTs&Ui5-hZy{p&E6j602=4f2H8FR=tWEj7!VIx8*qyCAI8CKxG
z9$9hGv-!m)st-K}Fw6zvj3s~w`Eb{L%W)u;QJk)MQlH*Ar9!Y0arD_ma_ML`%WvZ5
zuB{6^O}!2EAfosA--TAaDiVI~FfL*^<#D$ccp=!C0eq{~CViZ#E{0Fd;n2UByqkpQ
zkU%{XmmiUTd3nddW=r6HWv^`^3}f>KaZdg4P)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+<HO!(?QUT*{T
zPew2lYd^@~Oq^|%HPjuKui@{>#(wN=^tDK)rc89<cLwLH=$E3)B~{rj!Bxnj<u?My
zavtR!7!-7)r*G<i<gZ^f%90cv`5`gE9f+bPUde3E3nW+ObO_?(%TmbDkjw?N*vZ_A
z;8MxJe``kxIC7vzaZqFqL!LPttVVlqTX{;7v=uBY5bD#~NjCq-?lE9tD56w;o#SG9
z0#rb<ijz;U0ntNeu1(bMu;N~^5#8|KlU7P;69F-I;(YV=_ZhTj%HD5-X+--LjRjRf
zr9kg^D=7~M7VoorjSW{fX-{1H1J734mhh^yyGq$SUrjm-%oqu@#5Yd_@N6iZY@3rB
zfI~j*(#7PRM31%WPq=h->X6o`6BHpQvl;VQ{igz<{eclfwTUh^W1chlX2119aoH=G
ze^$ewuiGkoUsdY_>LYeVXdI9`2r}EKXq=CwgB`>_!JD5I1Q@BS8j@!pF9*c<v|%G0
zJh}Jo0P{`~m7K7S&O%nxjY5aM38TIe-QW+Dw90i&0$Gv0Rdq9%qq*F2a%d8qG!M!2
zocX}+%+(1NRPH!xv8k946feow>X^clNx)-X7_5SQDg_66z#uA+!?-Qwk7WM8F32Pt
zqKKo%^C8$e+>urwQ{;B%;PqFk7YAkBW48b$b~e<H8*R6ft&!q6g`{rd+CNV(y)EPD
z^?+k_WRIkAS(&I{sQnnn^R-37Xz!(BTTzD(0*~ub0=ndWP}hL3n~GabgbeMVLGxhe
z50Z8Haekj0VZQ(B*~1&`(D5v2=F~e4*q>}kh`+xyExeaggIL-b{q1+I;8R8FyLPjb
znbM~bkx>q%hfCiYMTX{?#+D<a70B6z<u^3F6;_DF2L-?OOuas}NHawGVAnTyvx&+F
zxF;>O-Ub8#vP6Jc2q_PK<@(1e1*k5((*OSBG;kJNhaiv~RJ%L%otAH#<6+c+oOO)?
zkP-5oqMUF7Xg?I10xF1eERAF^LOKFHTO*(@cqry4M+p6EOPj=tI=9MB3(Y<J0awX&
zj}QO=0Uv||D0Mj1I<V40uvzvB`{}fU3<t>T_+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(<NhXt0!HOb`iqcuV5@(l*Q)v|oR<i1d8aux
zGX9G=epF_DcI`m;9&68z-uEp!yy?Cfy>iqN+dr9o5uY4GQv~z+9qeydzM1X6pI*SJ
zHF)bnL84e!TNsDpKc<DA2mQoAMp!NHctUhIY{w6P000061ONrz98C24^xk`Dc-R9X
zkFCBtC^jrQO+p9i0*T@lrXxM<d)t1psT2ExGO7+JU%_*o<Q|jUm8*@UtG6*pe1$W#
z=QsX|Q+pm;(}VqyV$AW000630k%lgP+=rriC^fnk1AKr=b3^djU1CSr`lr`v$3<ZQ
zte~uThkj)zCXun7T)iZkvyBS@(UMKU3DngWfjq3HOsn*hkxdCT@a^s+3&u}i-uiU7
z>Wox|Y(2rnWb%RlYe1C0J&9moEptK?LqRV1_<W$N)k;N$|J3n!=9BB<d}9cWOF?;h
z*Xc&Q^+egwOMT;GEVZ^$XNNsBU?=vQ1_?Sp3~qe~+?smWQGIN4b{qLCbQHosY=4-U
z&>{<mA8z3%r1S;z0ndT;`mu1IlP^jXTMBGis?ToHqy(cTdJqs_0lG|<?u!<Lgc=fA
zprO-Msc%2QtQqxIjHWdjZgV%)hpIT)R?U&bO}>`^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<D
z5s6Y(6Zo#lFL|rNjz@L?2P;2-fleDVUY0BwS&Kz(a|%;Z?b_E$4TyTH4`oZGve}t7
zMbCMj#L*J!H+sUCJL2}upTo8Lh%LPK4jLAJuDmi$`Af_{o7Cnn^hEbq5TW#t5meh}
z5VEl+tq!2n0^E=nipl!<vsu+<1*!xg0thbGvE){#@8jZw5JMOWUpnLtE(CGEiyUu@
zMNnY|g1y}IOn{M~8h*PddI?$24$W&r8#pbhfdqX+^waB8v>*<r!9mWXZe^?;?8!ed
z2yv-pS2!Q#T9@m?;+lYtJEoQuwm%dA?J1-c9-SpXXYRv@QivtfJ-|*NpQ5W1AGa9g
zgc78H*k8USuoQNfgS>`@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$J<Q)|G+>UXlTZmUOOdm;TP>d{t<ySNd
z<Rm3@mP%XRIh>>d%gs!^I$;~yMdX<HnP}Y*^3EeX5-vog*9kONez3mNsyxE@Io+4u
zQai&)xow;c!?8*|-i7gi5NcUtn8oCTzX~-vw%v&jdUQi^!-e;!QZEje`B$t+ah=1~
z?cP_ytUStN{Awvi^oKUL-<Oo<_lUB<vQf$z2v8}rpS40Ty_<<w;}ttm2s~qA^Q&q^
z&kA%khe=#NIu__-gZL5NBt9}hFAQgf_A?=5ZYMuwhC&4^899dgM_!w6D01xwvC40(
z;=B_*){yg=rIvo>)*H<daNSWPV4hVV8{{Xm;+I>};gD+?OK_AQ{EKJ4LQ?w;)1M&c
zU+Eh2fgo-bENll)-PjU~@12>qb!YgjfU$j_ze5JxQ<lqorr%qC2x*)XvvN4FW%;QO
zx+ORc_W>Aho?*5~oze{vL<6ATGa<WR0006TW#VMf*Ps?imN?;0kPz*g{Ob8TW#x1d
zL?MIPHc^;#ndd#5vFgQ!>nsxG1h_{cNnQZ>)|YM>KOTq&>Sw9q<tp=Mep0*3DP!j$
zS=cT~ghh*J>Qeizh01|(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*3g8<M-^B<c^-?Cgkpo|-R+015maZFt4zb#9HlO5Nd
zMc_L)_U2f;YSV(Rizy#Q_<6A&*IXjLkN;)yu38Sz4{HHuDmrQ(1d<gA%%i`t6^C`8
zP$Svp5Di=a00001QUhE)1u{GncR%~?fUHJBUUJGUypVr|;$uCa6whYioS_eeo@ZOA
z$_3>F$;!By&2RxBZ54sHD1ltVy3|vs{69ZH_CwPFV4lM?xmq_<zcv8=<w%L8H`;M8
zUHrEa%e4S1nfbT#@?fhj-Zk_=q5vjaw9I7`Q@pZLKP49oQuYP9tR@U`q#m&yy|qqE
z2W`L(VQpDcZoCUgXVKuNfocGyujZfFB}Dcs?|`6Ga9wm;NNXdE)W-fax)ba3S$xgk
z``>wgc==61n^Nx;QGpC)2iIiKn~Oa4vu)>q>$}|eZP;21drMtR^q~N_p}tXkSZt}d
z1u<bn4~>;+NLida=m2q`@d{4LQ$qDguE6Us8$UJn1uZ;Q+~VQ%bpL^24+foGTFvjY
zY`Zo>IeLMmR}yB`kL&L7Xv<OY_)e9;gdo7ULMK%^qTlsNVARJ95?t-S!2x-rOP=K4
zDHq>0A~&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&+<xz~w0|?#KU}~Z&`0Y1h(7<CN9c}VwFLk<$j?rQ>+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
zzW8<UF6XdQi@ICedrhis{N-j2wM1q4y8IAQ!p)0~&Vc|J>Uz!;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-<Me7S|szD7}%X$E1h{3X&~@uZOYZ%-5ZlZYwGMhXzsp$*FQ{8FyIHK?2dkPFcIn#
z&cFb|Ql*8&y4oC#liCV$Wg;Npwm<9qO*D;cb}syN7Ij~O&|=3eHy-zJdEslL?B6(V
zln*Rz?WDG@dEflvW_PFRM>DR-rSz`XqfQePJyI<TJElo?4VI3$%~3WM-yq%pEEQc5
zPR7JN9G!;V5O?I9elWuyB8Sg0LQ{mu?auva@JZ19=AxQWM1jA2F^BT+u=bN}E=&`&
zgFpmp;s9wc(y&BMQs!*KRTe_S_QQ3Gl<ii5AF6ferr`n;T4&Wf289b^vvglMTvody
z4n+~b2SCC>%RPtKm|>=m)25!sUI$ler*h~`#UF=jheRGpf$(#~W;kEK^kttl(HsB(
z0000004Klz0007pGG#@dOVZs8U;z4Z9%pnGsnteTOSPY!aA?TMH|+}vq<Fg)anrSj
z>siS7sMGirK5wuVqk@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+XFQ<r)2%J-Z0#I%~Jb+9mb87f*L0wkB^;up4_kfv%
zfKDi+aNA%xz&NKSbOp-?hmD`fDj`0Hc=(FJuL0tE8c%iw;`g8~VueL{ydq34Z&dD|
z2E>CAVzXJSfP6nq#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-<l@Vy~@4XAxfxXu2+dDnIgR!Dp6?)ns
z^)hh%W1~d`zyYKpE69Aid-?<eO~fY)u{y}VVfl{!hTccgF|=LRRRZY4BpZ+|Gtgr%
zyLq+LU8qUsn5cI(jtVxGFe_R1EVmPFV?B5oPiagvn9|HjGm~Pa4o}&PtLu@rdVDB8
zaU2p8S*}-1DQ}C%cz%Lu_VjZjYcrrBBD^{CP!U?_@K<9??|V7g%%fWx;}A()t!GRP
zc*{dz$uRLmu0y3!<7;Q%{WdB<)HNW8&B74$MU{0tg=7u8Cp6%;>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
z2<k%Sxrm&I!)|85-6{e6wu1%Re`(!Dj^HQBZc8~)Wu(rYr2aRPn+`n1Lj_2P^Fnot
zo}CglX7&GIUpGV}{C;J@A9A(Fn;Fc<`OXK3+7#h88=nn3`r%W}^@rLQwskNh++M>4
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>yY3uZ4XTJo8IWPg9E6<x&z<SXj1*0_cgB6M?oHi}i9H06*rr>G7jI*R!3
ziCp?faCb|=P<f@wUw{BMOn&sOL7cLb_If`cwyw8nXO-J@jvK><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<)0C<b?wDA
zZ9ny?ynR6nb706$L#63?L0NRD%2eoNche?#uIe&phdTadhHJR<Sh>w<O}Md|!gVB`
zTp^OpE)1sgV1z9_j$pA|_3!w7UcP7cd&{kk58rn8zuF3|&&zmNnEIjAu^)YOw300;
zq3teZV4yp%+9PdwK=Auasjyc&tW8E}y`Tj^Hr}T#D6zDuobbYp5hA~+i(mBnm?6?(
z)seL6Jxqt0$PmYxy!=H$U>;MVA}1!I!#uo0`G_7+N?>YoP9utm2XqJeKs%(FjQVMr
zMo(Kc<&VugQ!Uqh4TVIh)THLa#(8VLhYy)_@sN{DXW^@g1$z9G>7}z;$41)svZm`@
zmkDyKy&3uNWZ8QK8<oZL65rYw=9)_L6=HzWEz<ElJ>6jqP2-E@M0qd<iPv7pIn_z;
z9)F%T#^dW*2OC^XX%*C78H~uyFg?V5rp0&5VV_eRp)Zeb@HPyr?#!{5{7#&`q|u$r
z-DY{TKV>E5(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<A`V1>`&>YkS9lCeZ09iy3|WYRJIODqC8)iDr)hHC_z+p7{~G<vdytnD
zhyd)Cz}r>q*<Iu|&{KlRv>@?x&Mc8NXnrz1#L1tpVoAjjVZ^_JWrduZ9Bs{;s}C<H
zOI=0Et9%F=Qsd4}vR3)6ERjrb)ecvlneIaU8g_+Dacj^LvXg-RonA~lUKfZd026^2
z=0#NcRc^T-X^y?Cic~vr=#9yl;!*!%kgtimdEt9(8tcO*ZmL)#-Uvj-`yjSlkcwhD
z%(=FRvD*JQ2<$}xiU%Lw-?d18XGQ&jzZZ7S&T0<9sQ&bCn5JnQO#}86g?Xa`n9*ic
zA9|J;W@v}ROz8DE-n{wfMY`-4#nsj-qokR3(oW~9=X`TBUE0inNn=@1Ei^R3G{-NR
z_2N=EO&%i2##s-&CI2BTh(U+FDmBz_P4JNC%8{JT_6o}D<f-$h+<0U<%qmS>D5%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|XOz03D4K<XTZo(2
zDk;1m%yZ3O*Ru8%J-g8E*yl%D{>3GynbECougkU_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$0OEiE005bQrhotdB3raihL0gmAC<txh(>qqnPYKch7PdN*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%<i2eZ7az{X0%=8I}ibS7l5JNK>_0J&|JX@Kjr=aw@_oKZt<U05{;?qHU+~N@IIU
zg)08cBOQO<@zAH{EW(vD_P0!*6n~>^e;l21F-%OrXMlxt1Y!MZIxhxYa0Zs3BAynC
zHV3H<eyEoz?0Iup`N?q{Sb}*awhnNZpYEMN^yaG&X~78btoy4@P2VA@cq4ARqS6lu
zf&_ln#{KaEm5EUSSJB2QWu7mF(zX^)0CcM*AHIbij(6Qez1O7@n5SuuB56h}iUy`Z
z6odMvPHuIV!6%2G@}e$5Ad!3F@t8l-G;Z7$<UjhOIQJs0pi8>#QM@F7)7WSc@=!}F
zg#+Y&h)D@U{p&~~!0kF$+b4%Jg7nf6cmsfnLx0EijqbcF0))LL$Z)<=U5&zyv5bFX
z=N{zB(!<hB$$rZpZrj!(J5|_uh-<}uYKP~6`H=T>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^niFKi<EXL|Qf
zGw+X11MSc2r}=5WKhstu$srE5^MZKI#;(T#EyHlpM;7SDIZ0lg9$GJp7VDV49eJuM
za8W9ss{~Xgcq;Pl9yIsO1-Xw9R=d7aQ7ou?yJi^jI97Ur$o~(`Prk~7Ey+{q9ZyA^
zLL=}mRf(4*N4tq?TV)I0i{40uBi%lfkt!}ZgH#TLvY!X=z?%xrK%-d$kI)9Yg@41K
zd}FuaP0OMKqI#^`bPOHJVO=v8Df1c+DJs~Jn*ZGRIKl~2)z<l>0gZ6)@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
zvi6by5xfZHX<HKh`yFt;JrM@1>3)6E!G%R$nSp<4S`=reL<9{q%%;}()jC6<O+(71
zo;j^Bzuv)Bx?UNYkvC6w))$iCz#q7~JNK~=0%0ob3bM*IdO2LAl8JL!9B;+yXmVBF
z1+CkxUc6CePsVIP1l1z;A4JSndx)@FmoI^G`58QR#6fecL^C-x+PJ{Jn5o4|9X<<m
z_=eB`=71c^fCsPu00?nJvOO0;b$oc(!9TDLjopF`k}#Bc1+H;?U1s)sidr2yB%dA(
zW6I<?hAFjGbUy#1!-xX{6v?|TTOdy@r2V^g3!rJt)onmHUawxVcxjMSjD!W%Z1Ccm
zG7WJw>i}oTIhJe^UES-OUoxah0Pc&BiMJSxxc;WF0~Kc+)>-=FQ!<eOw5bYLxVl?B
zf_4em+B-T?HO5;G&plV^8y5Dowj4Ad?6e#knT|wecN&(hY3jcnN9r#xpL)A@+IiK?
zxR@Ym!CK}u0n8GIW%;9!R(@>@{b^kGrmy<kYPK>H4e>cd+Vqz`{SR6xS_~W<@hY!-
zbI2w29Pk$O8PE=(HPvqWrU4Q{XSKlQQMspqb@n7h4`-4>;#tDP%j#r+y!Ci-pb)Rf
z1{7JBdOtm<T{p=q2B2}OM?P0RKL^va^jMPXxCp-*Mt+@QfA@iuCs|!yuHPxKVCeR(
ze1z2<ohHTK-paiOQe%i!%7d7VV8CEve>TOP``n5PV-(m(lR=67SN*n54Ujd(@thWv
zh4bwnhMsNQvxJMx8P9tTbF@;hlmz|x`&fsX=>;AYrWnAB?BJT%{#5r<l8B_xbLWV~
zv;KSgBy31`co2k-S%-qgMdVZTn;9A4&X)5HagF_b9l$_h7EWJCvuOaQ*0zvZMvNDu
zt>q^vn&NU^H@(vodXmc9aAPhVNTE)r8gob<QX<*$j`E6yRw@m7*N>J#F^(OsRUP&(
zxuD(8Mq^t%uhB_=aLkBa_+D*5`t(xs9+UI5#^#YOHd+}_i>*CYIdr)#r3lR53$md)
zH1KMGS}R7G*RfK#u}mSWgb<0GYQ4Gk=)r$<Y2U+33|Ng(Y_q#}UF_m<<D9<?zTpK~
z)P|cJ6!dK-E!10&qXH@5qpf#|EDmqh$45J}qKiQg4GJBo_darzC55*l!(dQw8euSp
z{AFe|^f%N5^DYHGn2qPlK;Tggyn))$p7~~}$>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@JZ<QuqSI4Rg`3iwYLG$v#R4|i22
zF;FAA-v@^ofxALOO?(A#HVT}Ar$d!By54+vfp8|V%4jf73zAEx54;**E1KtRU5|JD
zuY4-jFEY`4|AeN`K3l{To%LJLnj0Fi4vp)&vNmf$p<%tLa*_}}XptU(di!#DU&@hv
zDjGDRUyuy4=`rjXUT-A11ZHC20?Y4x=o=w62$DCV3m}Y*`b`7e3T5CS#+7<ji=oE8
z6b_O>QrZ&PDgrKEdof!0+gFJC4eF5pPB3rsD`1anLn1mnocdF)<WTs}5@f5?Kh(u~
zyXEk$sl~Z%zbciEI7e-x^BTEn&Q2GGDd?f!^A)VGvkWU?KmMx1E*Ry^@CXk<O!Q9J
z2h{oLkNb6`d?lPv>)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<xb7juF}no1JQs0
z0laM6HBj1C!X9K#{6GtQe3Npt(3^ttQS=qEQ~=dpPgg<T4Brw)35jLRnCD3u6vNpB
zTbJD{c}pN1EerP<sAdp?XJY>;7)4?e8STVQ*+VAG1;<iLiZ;|&7$$umY$0Fz;Iz|D
zZ0$W;Le?8jFYW&;gQ$t9HrN@YhQI0rZLh>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}<FSuGvvv!`3J{7uKk5?Dxj|YqjntAW{|&zyv!&aN
ztLudca@-hR4dc5;?fgH)<TO?m3fX-ees#an$ng~&6155d-My-I=VnV3y^yN&k%|eW
z4?<^}K{v3h=MU&{Igv^$m&c3<M6uV2CJzo_DrpmiD@)Mj+WaG610_!*!H!OHX%d2G
zK;t0E!kQCnYY}Ng#?bOpcOZ)w$CkGNxxu@dAC-@%9{QArpJp|L*b)nzz^4n!4L+bO
zb@P<k^zWCy>(c|%Sa2hnD>%i9h5dv<Z^Z8F3geNzR1V)20-+KBMD~fdiY&)7Bm*wx
zpaW}R9m!gwG$<Q(5G_dK<ZmDYRQ@^i<x>xfsUPrf-HZ!A*$I^XqCg#<nFHGm>*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>&c<UHq)h)_S=0@x(6b`WOW|L!@x^%{w-yW%Q;aBI=A@
z@zp-p<6i3({dk(S-ARo5*_Blf>3%=u4Gjh1>6gcFJS(Ol<7}=b2p(@alnf<mbN|4v
zFzo)Kz&=j&S0TqDfv9ktE>Yd(QPv<H^|^O6AHwh+-o$0KH=Z!K{nZza*7du3VfXW*
zLU&m*7O@`%`v~8^{U;+`IM@Sbr6=GGpN2xIYiUf>3ZE0=l9AFUqGcoa!scXvb%-tO
zvTrSA@`=n2sw|<xtyH*XZ6(8(7g>5lLyxQqh)<RiO7=%<JqO;U7P`ZlBn9A)<$G(e
zb0IEX6H!mdb&IS^y+nnV0btwzHQ94fHq;20dh)EsC=kwAYjfX!VCKdm?c1v<v%7gc
z#(njP%ep~dz)-d&04L^Oy~|knBwnHIp|ps-(CvT0e+%EEO*4}DD+2;p-C302sbazA
z;o0qQrkr{R@UjGA7fnSzka3grw^xj(kda}DBcKd^YSBUV|JSY>K5)8bCi!?2@^a^a
zZV@xt4`v*HkMCH?=UPJ%Ma9NZA}AGyF>CVf8N83j$_<JB_^HZ4wV+et24h4_s1EUB
zjn#@5?c3yr3}ltJVw~3cqj2~X*bo;jjMmUz)}Inx{YIt0)^sh}tTwVw#UasHj+gST
zQnB2~(z{8m3~59<K^Dp}Y0^+Ez0hR4%(>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
zQw<s=x1ro9H#;!&nvhPc`MQ<THC3g)Rt5JTGly@<OcYK!I<_(nZk0W2s8jT5X3%jg
zyzU#opaobQoL<=#j75x%oEIF;4cC~UjUFipJ85{|w*z^!0t>x^!+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*8aivFJWPUqPPjIR<Pn`CsG5w>RTZX)b9(uYMCTRd`sWlIoTa
z-e^MIGZUJCbQbiMN5r35W<WQgG%F6SEAKj{5LEgtEa$)J0O2<{Z`7{*Y(Bp%a~R_6
zVI5LaA<em@jMpa+(fsq<)=|Wc8kUb|95oemHwKAnmlXV6*6Et(Ga|1_>E>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!pIJ<K)D*07JsmP-hYT{i||&2`ZVO`ARJ&*4R2kc^6%
zl4b|vt3Lt+D5zV<?fBWDa>0Cw;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@<P+p)Z|Lb4(o4Y^*#ZM`pgwuoix90Ei6m@jYA#~A71j+
z?5!#{#vc1o$8}mP1j9m{_y%x&iO)oRP;8=5!c}rI%c|>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<z^Xto2*3rl>@q;1x>t>Jsn7RUc
z3v&eGG;E9Mz+!|9zgV^kCa<uppV?!br}4}f{e0@Cs|h@?`;S)oLcEioO_f$y+vmeg
z!7VG3^I?HG-q8+_%;IclAZ)MdY;Kk+Myuzp%qDCKD~QJ&(aGhbUtl{+Nj<+uO~X5q
zaS@4wi&jm#>k+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<WaXQ}xOOkhc_;y<GhN=iq3C
z!mw89A`zLkrtY9g?bc%MblJAJRv@^`pR7qqrXJ43(eGSLJEkS|Kq2>;54nc6r*@*z
zvd{Q)`W5<UFlM#jKUBj&b0ROc?=A{@@%i>_VZ26bqCqKtUcC5{QC=|gTd`@fHBnJi
ze!SegPg3}cebk^Ee^zVIbEi<RHF~GH?b|qT5ddeARfk;?Lvx4|w}TW)h!{G;Qhj21
zsuYc!dJI1T8sHO}mJ@#SP}2@P?6xI#Q9mH+i@y+gM>pv?Cw6}K{!~Wx($|HTZZ5n*
z?v}w57cK3E&On808_>+?*j5o)L<~hMePcX<-N3;yEnylS?(`cPc29WCY(PsB>^fVQ
z3Ccv<d_^Mk<dQ%x3L6KP7V&$~O8Tij1HJvn5nG?7^bW>F9M^{il?U6LhoiX^<(+S&
zmXd~Ny&-bH!_LoF6eOiMV&=jb(;+gHJc4x*khY~2Y>p`tP@)4q)m<m^UxC(6eQ|P@
zyJBqCi`01F{<q~PkQ(0Lf;1j*>!+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!<lvno
z!a7JusEl-JLZfV>t0WE?a!MaBAm<9t;Siz9<!V%JUqLtSLS){pr*pmqnPvKj%^W3<
z;ykLEApyF0Bmahxnm1YX|LM+z6^j1>lL5x3-=-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-<W=isD#s~;NnFmtjs*R&HD`X-&&Ulnhh~(pHyb75
zqG#zZSf?yPDT1ZxrckFD;dRxW41{{_q=RIq08uh7EODY$6(c4_3T*;@zaPzd|C}ZH
zLm<xT^;9qsT^+N}l}`2Ir14ik(<XRdI~~RX^6qdtdm(>{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
zLhfEiLp<WcMw`@$l6&7kz%aAbz_hIEB#;ly^4;>FeRm(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_f6<dSYG(EJFEYihfwa6Y-8)LTV&C0YFszzAa9FOcUicx$nsw
z1)nLkn<i#JLAm=Io&{{&!PH>m6nkLZF`Ea|fKyit9}hcH%MlCLMvM-^wzs~!;Tqyt
z3yDYc?wg6qm4Y~jlaav%LLKHHH$nHWE2a<QMsToy^hSiM!bFo#^09U7A`fGtUp$v-
z`ssi%G=VQ5>1(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@<KG>U6xjWkP5XD}*wm#A~=;vR;Ds-O3TLrU8&>v`6BY@)h
z9W(*4Ydm+BEhRuH9VjHSiO&qg$Rh<L8mtlZXU*bR(KI$qKvf&6+8HV0M`~pmW*g;q
zxsI)hhTD$!N1a!m&YFI%jr*>fa^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&00u<V+n3o<fd6
zv&Zse#H8)_F#7_zD?a*=kF;tx)fXR)(^t^b!-{?q->E3#rmaV<pcT1nFCW`)C*cc3
zkx#2id1B5NYa#u;C)i9@eRF5xQm>?!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!g<auDjC_BVp3f(74T4BVj*BTh4%4vZP{uznW>zH1Ck3J7a8#gy!jY
zVQU9f0C@|<Cgj&d9OX)5gro=>8!S<lY9m<nlvcnoSB%~6<9X5bo7F?TGIl*QIY~O~
zN1%!nGmb<h7^1!5@-mCtIS1jsZ5!V%#DNL#V9^Dx{`EYBUYm6@5{l7XAaiCuX?U5Y
zKvgux*OvaLCq^4Yjh?n>z9D{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<Yl!y+ZrjNRAQ
zGa*7ECnEkV&x>*=6V~yZ5(OC)3y51TGPlSB??|HSvL88Ts-NU2dut07_KNd<G^q|@
zBtz<bLMK3UoDW+&0=nq|ix$rd%7qr~{e^nZk5ZrW#HiPV&GC*v6`Cf28ijr1`5yH;
z%XVhI#6j0|m;~1^CB=^0qts}?td!*X<ck@;^chh08R^m(Xw=g3a`LrngHF(`@e<f?
zOX1qprV-3M9ORyFMcie^R*ub8ElKGb^EV`fYQB}qp$2|``WOBI$Sh!!)i>Nw=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|BE0Nzc0<uit?<qEZR-xvGPntU_2qG0T&9q
z?bjdDwm@MI6uc&ID$X}d)7Dx_zr7a8C84$n$~f^*-2Yzh&RG}gU>c6CBW96sxwW-9
z2Oz8nPJjZ%q(i^}007<C{^)x~3vs1&<cNoF8vCv&DX!Pmr^>Sa(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`<ibj#WFy<>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+<mR`Y`<a7H?#~SGOqb09{QF7lo8>O1!_(L!j=cr^j8YZ
zcq}Jpv)`w8UT`opVjFVHNRkOwGIzWblxaUTA<w()@1$;;P9b@Wr8|r4x;l*9m3o#o
z>6|5+Y5E7Jl}l<fHZswh%JRCqd=T}KX9T`4(4)vs<SCUDP2cNFpAhV!OmeD5zN)Eq
z4y>Ej=K?j$`T+vstO-J?L2q&?!(yN{A4dsN{K>tz<nTUe09#DTSn#tV^}`h(32XrM
zY?@C_I_{OuEk<)r<Wr7ib-&nd7*`uVpOlvATu7N-!7#5wE`-@K|CVVmTp6=NW&j+y
z$4LPug&}e55`thT+cz=dPK`t8bG_Pm*#Zwd{wunA^V&Tj4X<w^{7bHp2r}LHQzmAo
zF0thMQ?fQN8z@`%o+X*(&mTe4fRLXbR`;tR;w^0|c?=>P3d1A)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{~opK5yXvzDfX<pBK{3+Vad`8)bTI$R;rpc=X
z+ZIKYyL6x87Y*$4yf0!5qQf6*&XDx(u45C|zi%!t84BDZY#)(NKZa>1UXmLy>l{Y<
zB3o<9v%LFII&}MduRbhHWZE2YL&&WZo&-9tb#Y7f*LtkMzFGWgKEEpdUJ@zg5WH!|
z=6WP<SI*|clAmMUSeAR+JFtDNtkVBqsDb{fX)FATbp)Zkl2)8C`QejeW{!4f+`=j^
zvDMF<UA=FVIWP1aF}Z$s3eF5C>&79(MlXr+==CApH5wo`4?xhrqFX<5WuPl(1tKhs
z8IPGL<~fxz3ExMxqFuus$)Ox~1QD4$DBBmq><Ib;xT(Oc42!nTi^%D#?*_)cZ8<eu
z?$L!G>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#^<aj{#&6{kI%ejaLcM6C3_F<y}C=|0$;Wx`*S1-=P;5gHOo`xlY
z12z?~(wF7!B$48E7JFu!c_iDHl><J!KC@n`6|`8Tsoe5Y{V3q{y6R^a>j`F{QJlbl
zl6Tn{Z|zu7=WY^07J@fQg>NAs6Y<veP??dW?Ce8Ym(pR3BS@3=pAd2sK*KpJMbGkq
z_=l({xW-KBjG4x6uhUB0!c%7ZrHPE0Kji42!hMcDX!^x%;UX5Km%%o*ywh!5c(b{t
zaHe5`@s~@%y4z7KkT4h#&3jJnUMVeT5Wpll8t=&l&@H`n0LqaBtznsA)B|6cI&nsN
zzY@{tpvO^Nzedwi1L<4Jkmd`^Ff<XWRKKu$r~tYVJXBN>y<Ab$m~P#R;_9IZwk<KD
zWRkxOO{y$iUELG@(+^`3Q9ci2dnlp!$YlPYLA&9L!RbUr-Y0D-zJtXbmn%)e@?L{c
zK6{ZZ^t^*WmNFZ5ier>`)9BQLz^7<Vn_wd6X*g(pLW27F!fP$!2K4<VE-5FuKrfUs
zJpk?GYtV`PvTv%eV*`f>BkPZIlG16(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>t<iI`)9p{n8&UyhKua(01W)9Hts=
zKgO8MWl5U&$l`#-$+U7rrJV3j5qC5X7l-n+4&nJy;Q2XKQnDOUX?uSUzi#!a%QWh?
z;OYci%o-sIT|?&yR+>V8c~gg47Fzk4IfW<3u%4w!?GG^sATeEKJg-2YEm%K3J=5>p
z1qG=!fdcUYMU&~)Me!JHVnDETG&A@T8gNm0*Ck<Y;IM??OFR>QK=}>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<ZPx2f%TnvR*1J_}A`x(1ot#E-+5tTbCP@
z3Lzvsq+krd#kI6)Y32>?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^=<uvRoLD@05uC@`Ut5c0f_c=(~Gf`Wx!eo
zU%|6a72J&Uw;aS4`86qIaWzwoY4X(q3QTX8glM~l;{hIM%8RfIgYvUBq-=af)E?H+
zEuq8*FF?kqDW4vK3n6zZWW_^jdR7^RP*AnfyZsNe$|roBJ7X;{;8E(mM=2QDc3oZb
zWxl9?ERYJ}!1yI!pZz@du2ldVQ2mRE&^TM2AZ3R;k0kzVvSLG1JAeNZoBjN{-;oty
zd*<A`6)H-|A|y8jpt&UUnnQ=f*S5_)I(79;K1)h5IlUXDiQ=XbOygC2LqI}-CbyM9
zCg59jQ&4x(%%3~H+qVHWxZrfn3$(xGIsWJEZp&D1#zeOm*)eT%*#$*Ec!_CR;xCGT
zo`1<#FvUe_(FrRl1{Q=W_|b|J|5vz0u|kACCX#HTt<bZ8cqW))qhm;+5Zxnx;Q62w
zM4{Z)?pXNno-RIt5&x0D@bl302mA+XZ-O?=*o=05i5pqMYRYTPbux{1{>RXzXRD98
zKxU(0clhA;-6|czJbqKvn>QbaitW^@hUXZp<D{_gI{ji5N8x(@sWSXvZgkv#kFSXw
zd;8}!3e(;8A_qc)>rh1QUZ_?`<7mipsqe8nfoCVy9w;P**%aqERT<c%g~q)3sCc{*
z=NA7|Rqp<y)Vw=x2T%X3C#EVu)^BrIzj*{9Db*k`lfdOJI3Kea=NUdX`-Urp&RrIP
z*u4=x6^HP-Q&-d=+hp#M8u_Drm0war(9Y2btQG6nZl-43pP#DMO#NLm=sB2%)R-|7
z!cUxJgINB$^d1zwJ#PFas&p)(uI&kX4*>0!8y-@b)qD2S(pN?8?)D~-m@G~=cuE{&
zH&TnR(rm#MNAl~T2R=?by^ERoY`!1=133;{jrG6VbBXY<ZD({11G+Zzq&+y4k{^_7
zC;3);oUlUA<L32wlpY)^ZrS}F2y7(IsX30v2Ij7LkOU2AIAqz@_lUNtqee-v)6d8%
zm*AfvX1EzkHG=jajn^EH0CBK(^bx!VA3!EjIcGyCDP9VZ56yoO9|r|}$7muzM$7!S
zm{Pi=;+mIC@$Uv1yl_CP5L|Dc2ahC^>*r;icKr+pADmc=M;ttAK!6c*K0x<dV-DC-
z)a5gpo`MlVLA)QiGFFl;UgmZx^4mHAlvOqFifE|Wr;J5w4Ox6mWZxiCx#2A^ywEfa
zIG7Zl&Qth@q3B{A;hyn_bDNiEk-`I=;Msk^foGD|#V0G5DO)|4ov%00)dPvvRLi$=
z08=ejGEufBPEVv}S9MC)e>}|I?O%!lYw%2q-f9r*yNjvS*yIjM=b1EhoY^i&z?P1q
zT*awnD$r7g@O}8FnZ%CkUy+V}GDe@3*K#K6#iPnVmGPf`aBlbk<cMV%E(&RMD;Fgi
z5B{OFc!5xYh@KiDA_qDX=@($R^OGUqoAOv+U>I14|DTV|j<Gozl;ML~x~FP8llIp~
zwy{}=j=4~P#9lDl9srnI7Aiv6X1RK$u+xZtEu10ZSgtVVu*TKinSO{c`P*}Cy$XsR
zuOmwB%Vlu!O75SazD)m}XPI!rtGds$mQt0P4xS=D{ag|1=DH?IF4g7SIZ^w5@2}**
zn}N@yD{NnD2mixpK8Y!rbl`n*i>z*LELz-6=`eHmLbRac9MG>S&jtg_)_FmxW*uc|
zxcCn0%zLE{_yV&)r2V|;jOGeQh}R-Giu$Ov?$wu5)NTs)>WtkR#f~ih%B!;@hTsiP
zp6mLw<J81K@E7fC#RSuTgwulHki61Hn;wUgap*SpX6#lelc&X!$n9O*DXuAljaIte
z1x_U<KS^{|bLR+DIk1T{!A3mMA%XFhUEBiHdqTIo5sM{?YZ&qvP~i?=$^m&H8lz|o
z$DW4>Y~Fxq-pHqxY(RkCT=GaX0Kq>9-?2FX$D=zzDs*`<TaX^L-c`u9HcV8(M9~X>
z7!O~3(?sq-9G*f9HbRTA7rjsfTGUE!xWbL+BV!SGhwdeDenA>{<KnW~0!cbNB78@z
zp=1(G4gHAWI|6!4&lQ{_dJ=J46tkODDo!1A*J{I%Od_~kw%=Lq7jqGBPSD21yZJ%9
zPNpZ^(7z~L`2D(~I9E^uu)jB^XroE68Ak3?-Chx?mH>-<lHstMQzjju^NwgqIVy!%
zFqM>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_<locj?4K({O$qjjoQ;ie2Y<BM|*t8k8l+tj?ToO8B@;C!0JoooLgNFcKf&CM?
zJ>0X?Ndk&@XBe})A;x2+SCLY@-V_=QP+5315*$nh%kGi)$5<Hj1QUSHRR{N%z5I=x
z7&0<%21}EOE$#KjV=_r?svzagDM4^WTZM;A61?VpPPR`v<hi*Bjqts`E#tRZ*yLe%
zK}dCr-FB_$uf0s<V@tZoK7)nYa$f}@3Ya`$vW5Tv0006!jmm1py3M6ye~`etfBVj&
zH=(qLdvM5V7{n1F>Xqb<;|2*&Yzh3EjyvX2;Dd1DvgPVf_9=X1ylqQpo<<xCZqjSe
z2(>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-<Q<ZKu?$9mOjsyCMPpdv<E5Rd{y94O>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<k`+k0S+mYp!BKoi+XL9lE4r&|z^*m)KWh!U^|4fOm>?TA$lPLeXK{gHw_
zdC5%<n)$5VBp#7N-%Uq*AcP#ta?UnL+>~!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;9<w^!)%WT7MEIZXe@t+_
zfzWvlXsJWCWJvt%YDQcu)hn<^XgDgS$N4~UQ@Wb{z;3de1(r3@gtgru>C8wv%)Hm3
zc>p#Zfa5j!ou$*DAIrONU8IiJa8_<u5okn!dqW%3yHs{AHKI{iXRq%sJ9y3SvhO=0
zw}gn!wxSe~f6aw;ZOfU9Wk!;{glrB>*Af{JikE2;9Iw@hi_A0bR8<}RR8lSeKHsH<
z(ayxeks!h<q9q?ygvV1unkUVdH!N~pPkc~ht%BOlPayIWOP-J?4&jln7D*m}p1?An
zdLS^njrar}>Mn`QtZwLkF<wS2h#LEgS36ZjQs>Oh(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|P<f9@#_(;j7YBPokL=wvz1@
z)%Qs4B)FtynuD6(X~K7DRpAv~Y^CJ{%0%QS2hJI{MOkUEi{MVnW*)lbFCQO!Q0YI)
z2lFYyC&wa+?@`Y{KIMj)c^7po@Jn3U5TR!D38OjRK_yLMX?kZ)!lJJ5Ykn&|D!SA9
zn$*+8^ZF>VNQM1)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#{PfV<UFXXINT4zG@{9TQ_(P2D|=n73N(+a%mN?hy+obT+j=uO6Z|C;;*
ziox8v4d{Vy9~zpDmpep2WP2T}E~m8(2u*OFT^%hWHFOUN=;m1h7b=8$Dx>1vM=+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<$<ykfei!WqxNOx<bhZy
z)kBI~_FF^aEWM)W`HQlQvWAbjD&~n8@Dvm$?*~w#5=JA^!6p5FPZ~R5=TB~fp|T3c
zO_>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<<VAn@LEE|e4um#rAlLw1HGWlL{|Fu!YBk;=vB5Pa
zo+tDiACFy)g$Ti3{yDDV+S__VxzZUq@m}73IcyfCnVR*u4<fHsxFyJ;PJ5fCYv{}q
zJ~p{gsMtNCW6b5y@tVBrY2N!=8%eK(H8L&aP-kyLpCDDv4sC$`FV98m8PXrrbEc+T
zyve)s?@lU_p{T;G!X4PQ&mc+mqzvb3w%_%yhNHch!Uwc*y@*!K3MDqDMl_ZiGcR|S
zi0Wbp*Jnb-S=)E`9<)<oXDgo?Q?07@44N&}2VIkxc)p9%QGTUGY*L(Q*nO|1i{q2+
ztNq5{5@OIY;a4z-)y=-VDXIH$K3UWvo288G*yZ3R7LLlE_ffKTmn*pHAGabRu_Krc
zOcR@Nt|yxezCP*P-dqU!Q+LcuXaF(_sXzHQ8E*!`1vUA9#@EKLa^-KOc7X%jVPuG5
zFnzFutom}V4|zW!QLqpYnHPx|=^Wi*H>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(+j<nDS%Z$$lzS;?
zf8k!f{rNYo#;CNsCE0!qis&vc?yR8ZDy9UVnP(8OEaDhZWs{nFo)z<hcd(ET^WoIL
zXiPD^?DWhpwL5P^d@%R?2?iBcfwZL%!t-(jaac^_(U0j_BYuMI(`Cb4`OGfum!>rx
zdY<0d3VhW~hhKRF=sdDT<py$d!Cr<m?|?}Xzc{}pE{4NQWn@H1XtN6kYF6hIUVgWk
zY*z>Ba_0oG2a9dE>hB}}kkcGy8@i(<ZEx9r8t-0VW{AV=-!!CJhcMIS5<_3ZH6xGA
z0g1sI8X|4{v!-I0bqivF+9E%sv3b6CG`xo4Vj|GVDa7Sl@*<G?7sT)kA!y4;2H7;?
za)t)Ls!$TU1%~6!Jhbj9?2K0^tvo>rfWT~dCBdRoO*a7`(XYhTKJY_8{V~)<(|e(3
zzEqnvrz6A6(HTP8!pzifCInBW)2)ZCHoNpfO%)ivA0mI&p-1lXOzTP!NT&YWwQW>M
zHT)sEdB=k<cakuvBtE6Td$o<7Ql(izy&|0L1G7F%cmDM!lFe%ZWi5iSWqDyMm#*1X
zF4uCv8lMO{p?4Pv=C139)DJKKHxK3znZN)DM3paq^>h;+s&UioJId>}GNB!}4!4La
z869y}8cxd`4GV~8CT^L{Jp%hl2|?2n;c2rN#{q;r3pPC6GUg@@ev(b<je!Sc+?AtE
zJ8d!y`qlqdqXnW|&wc>QpuosTq8R%-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<NY5IlFn5GYO{{4Z>`a$m<j
z7~K5;kQTp@6Mx>N3tYC3A>%5f+AMb$(&)alc)KHLde{9|w1@{S=Z<S1N?5nL_?FJE
zc^7JYNtpl9witfVqv<biHRX_o=={vk$31prWRJ4!YLPj;mrCY1R#y^mN)`X!Ga;ed
z8~e>5vudX{gZgcW8m{>fyAQlIo!S@)9W3hO$&AvMt1wkI*w$pgEV%oH&mk{GoZyhw
znQWBguu;V#BA!fl<sJmUv+{=c@Ntww3W^MdAL;%3DaUo}Gm>+(9hFZG{G0F4cYalE
zQ5!+E>Fcl3Ax7$O6l`y^qXed$c13tnS1KLiwY`0w3+i3GWz?YTdJ4;Qb=4&rNeg*X
zabE<b!42HbHl8nuikEmTI0tOb^kS82y7r{xHTh7YoyGNDNX<ZWiCO1sP0{iK=JYH@
zsIXRpK*$io_@K)Fu8wJGEpQ7a>}odGB5&tHkR7^X{-Ra(FHZJolS))09ca3(KDY&6
zf|<)X{@9;1gd<mUC}c9@@^~sWs8OUZKPuJ8<gMKH#S6&$vkEcpq+24dwPT>6TTJ<9
zvSHpR$Gvz=p62DO&qw{XQvj;cTE0KydXPpYsSbm>|LzFYZWC7<e*PHu@J?^ZD0gYp
zBFdr87MiSiHz+^gJ>p~<VKKXhNu-31;%i>*@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}<GnO2U7vEZE(
zA=ca(PGo+{w4M2waRHV{20O|#+j|AkpiPx@X`$4_O{82l$ehm3(PAtVd}hPdU4!Rw
zow<_@_u7M^m}~2Gn4t7l4&lzJv>N`H=Dgj2XT$7)E_4X=3@mP#<!sA<kM1!1PLwMX
zB6nu|Ic2CF>4o0q(|tr8r%>4y6Gl_^B6k=yCkTpK&Fj9Y&joQj>KVR#bVs>gah|W{
zAyq6dsjnkLcr!rq5gN(9TcX^r?_Mo<fy&gY8`Ox9k_oBJvPV%8WZS^f>Ix;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<fU`&5Cv(=
zA<J5hrQnjk(dj6pVu7i1L}H5qgprQ)*!_3ulhw{@eWYA)jk7b|E%kEDD+QO!T+fyX
z#rFYdX~ft;A4&ES20r$$-*$IdK>{ubFEYycci4Ggk2}wx{8+z}^9(Q`sE(~M1U&KL
zb2BHRk1!pRXVRwqy`R%_8do0T(kPwnq3ih3-T;W6jx5=bjCa<!SS><`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^q<w`i;=G-An5*=AC<o@5F8?XKvbj%>6jGp5w{^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(<<li*%&u
z4%5Rd(8!vWvDfgLCo!*#8=I`t&<(*K-2g?cvfHOVi|PuuMyL=A%0<})+c~XPBS?M3
zntonz$MFrHFhTSsUn9E2u;ngQN}*AogI`-Rbitjt>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?{<CQx*4s7#sK9zh~KuaTUciBj6^IWY@>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>T<eb1`|G+oT-egzzkh)6vzjpX|Yhh&T$CB8au2n0O`2Q8ZF6j&L
z`+GN8oi7Kw9YxunN`4}AahjeU-gp3-ayZzF$pQ(gu@Ikwa43d;c7zv(Soahs{Xlb;
zx*-EKh&e#24}~2==U(aOWT%04)ZjTjdSdvtX8YgzSerP{dU}TW%xxyrP*#ye7bqdn
z*#U%AHs%#C07UnI!QV=DecJPXo}Ko{vv!PIHyYqx6cO7)@&fpxm^>U!=VUi!RVL|@
zyy}>L^M<&e0tBF@mipmhaUYZ5ugbY38rhshA)u)dt;X%6Dp{|i+CBQJ3^>o+Cn+Sh
zcO1J|wZJ1d7+<lRl2<h6CqXm3RCrT;lLkx2L}LAnYtkb&m<qH?NNwc-0w3F8m<syG
zj)N^62kwT3!|~!=Td#=a)D7WNv`pYy0A|8{_KgZxHJoORdW+@z9RNJic{v#@D3uFj
z#oX6}T@3eeX2<P?L<t$olB(5)nm>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=}yC8QT9<vE|tK5Tn!>a%q
z&C<QL>!XID;zpY=q27#{V|nhU4Rm;}(HJ+JNJnY<FjSG!9N91m;V2|L>MtF_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-{<Ij~<0aD5PeJ
zRn2%<f8~d{^8Wrw*+x#ik?*?+(<^Uf$J&Sx4yglSV@R0CD%q;;l-21j_@6z2&Ya$>
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
zp<o1T1}Dw0g#cZuJ>q5b$=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#<KP>|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>~UR4W<prn
zENEWwgX${yRB6`5jjPxh8c&4R(RM<+;%kP;n-Bm3{1t7p5Exad#>5N})S@GSOwk}!
zmj+Y@o4*YLMr-Tm&CP+@T7Rw?kJxd-Gj}0X5pJQdbi%#)+gn(5Wku6k?fn;~wlbji
z5CvoC+npJS5Ab<q<omL8gy(GLfPgZgWfmbZw1d={*?i)Kq(Ho$jNlt<L256O%<hvH
zDP84-(R{pJ{9+Hxs&okb<V8ayv{|&>#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{Qh<It6BrF0
zb9u7_CNk$0lgSj&I2yL1h5>NnSm$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^iWo<DoP
zN!Kvv5#Q74i!5#<<uZbfI?8p_7;GrFuMbf>70F0CMTiK%zrqdFv7(<C3qOszILhFt
zD!hlDSfK_f^2k-J#EDq#yTSxHN;L<4wQac#gdLK=D0rP=3T2!>vJoz@rooe9+Jnc?
zl2D@3R9ISb?tE1ZbWQFh=)3VKe&2Xx$5m=_D#<|eVxZd0F?!^sv$7f!XOMye%Zx)i
zAoG`w8Kq|a6OQ-j!ErKsK&*X0P6!$ad4*&raz4F_4S9puFrq<s9>QP-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;L<pl8J~@)OuV>wonJ}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!Q7ylFD<lM#WkKN<C-3-QrEYA7<7n
z>oJUWWh>;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^M<pz;+%<D9+^_GZz%F87|#4l3LDyj<edk;~3_x^UV`3>6C+zV`l
ztSUWwzy2NMe-i#rSP$dX)@dHb5&r1c_W^hY7!4NQ@P_N+<=^QpimUET<LBaGCJh$V
zMjEX(6HjQO9gxk`e?dUlRIv398lqJ&Gx+y<i>i&@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<RjYXxbuu(5s(|9)#T_%7jzr^{*wut;2pES^m_Kxbbth~0imtEaQk5@vOKHE
zm~Yb`r(UO!;60ZDat=s&*p;I^HNh?9uSI0v6(B%xf!)%kkI=kcrgNM(dr~y*v8M_s
zunqK6$)hr67sbe(W>;BD^K6RvG9HY;zJkf-t}03b%<Wo45^i<ii7S-Sp74DyPq6%z
zO@qfLI+uvT07B&t<I)p!gL9X-J8%|mn&v#zJxoLWaO@S40)|*7MOacU-$Kk3%%T=+
za%jU(x@2M!+$9Ai(i>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=T<T$RZT(*hfYer$OKhNDIXSWYrsmQW+c
zpRTdFn`M#EG^1s&8lG@QkNCLUC7Y_cq#)=t&3TTEdcpj=bjXc)_l~$0Tm_0yj1_l*
z47(M-f0GcFsZ-Y26I`D0c}D~**wOJ~YO0UnjN(-im1{RfleWngI)%`%@bCXkx0;fo
z2TJIl(^8G-zz1cyP98()XALLCplZ}>gyd9gLb5YNt|%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~0xE8Ok<HE5ipTIq!992>Wkd{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?v0<Q26U^>70x&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<piI<-n7qCN?_IOOt-toUp<B
zJ%pCCE=v-?3P(#ZRKiI%2|!qZlT$i%w-fN<IEn_AaWR7ogGJF;e~Z{1!l%ci*tOlP
zYclxUyj_!TdGT2zcmEpGpU%A-SGdYt4_YQ`mss?Xb2jQ~pBNEMMG6PL+UnrW$W)42
z)qG`Al`wp@2|VgSoUbHIy*_ipR1n1+n1yvn#z@~zBVLwNVHd&kp(Sj9RBAcDJvUDf
zx3(eI?{ogL@@=?fJ<*<tSnQPnN_60V$qKs*wScmfTP`#Ev*<Pa=`2q3)FZJP%3=s1
z@rNrUwR?N`m_5HN#~T$F&AL?%`_o=O&Xm>{88|Q~EiKwd>iiQoj?=1Ov<uYTOG>N;
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<QRtpVL)b|Rz0h}{vR1HLc<>-G`v(`%nspPrr?BlClgYmP;L{DW%
zYCl7ocZ^2{0Nrrg9Hjcre%jO&H7l%XS5Se8Ka-X*pgYql3fRtkJoHu#!<djBdQ4V7
zx;emlg2}G20eV!2v(|Bcv4^}WLNc7+uE5%WJF)%Yg!!LvzE@swR-M${7AbWd<ziHf
z3DO}yBYw3n5G24Q$dyPuS{-3uJXllW<~uMVi7jh2O({K3^v|Y!Kis&bm~9&Nu;uBa
zh$2VWOf5a(SJKf0vd$pFqWHD<f38{8{)AgyIU;#4W_aDplmY>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$<ADr?=eg=h~*V-b8L#WppuTV{D)fisopIlfH`v3$f2kcmvKm(HIM
zd~j(5C>||`0EdHbDgRbEOcG38!gRz6=(|FAvrtOR=A}%P5U!;C!ysxNAwO;tgj8|D
z<ZCs))e;apH{@Qic2HllH;FbpvapNn5OdHAmn?l8GV6>t7)`=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<H
zLoq#n{w4#<RDm08M3tXCo6!zIZrJL`F2Gd2;m1&<6+10DsNN?WJ;VdS<(gil;`|>#
z9!wp<TfBUECKa+N=8w+<DO!We_M<zCTTaD|)d*~OPa>M<*niAMZS!GGRU#|1?ha>$
z>=Y@;FUVk8r@R?EjL^%TdcuB&gngY3-fc=BtRxE~<z}^M>bDI|{a9N7X6;^69a}|f
z9?I)MfV~v6$4OYRHDA4F>nD)UxAc+f{zM<<K**z$n%z(7rWyb@K*+yO4Y1<e$p$LG
zS3<`!sz%q2W}adXfW2^t*BCB2WHsr3P^5?B#+C`E{bVbBS%y?KfO??f+pYKaKf5)H
zoF^C1Rfk&)4jhSxADE%(MplbPy}0_oX!-OR+Dt9<WD-Z4tWPWNz%d`=omb^--95D*
zNmq0qJun(`J&O0)zt7QRjo9jsrbs^MCJ)Q{?()l~ZPK61VW@Zl?a~#2UKYJ`b*7Rp
zGCmH^->;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;}y<ctNVr~J|g-4pO>wrD^<8#KX30n6G!s@kUgGS3GXx1{W5laZkYe;E$
zI$FvFklxgh<@|fGrY4TMr`8oBQDHcsv@jwIF$L~c<OYu{?xc0W%b%_!#6iVH)6*ap
zyPDbmp)txT&7h>&n=hXqrZ2eS4BoV-?)$&+IAkp$+cCdY<}*=QxOMSKm~NOL9WJ1Q
zg=ltx&z{a^gRv$U5Y1qY{mE*Hhp?>FDDavhR`#g_9l@Ys;&2h$ICx89M+P}&Q}rL(
zY(`s<tjdbpc~(;4=^a~*EkOO|&nUjNYkMnu$vc<{?&~E1p*fw1P*n~?0?|)Nw=Vzc
zCn&)!{SWFQQjWQ;7JO-Ao@v~)1=j>Mvf`Su11MY}?A7~@z>+U&?7PU6ZDI<bsKAlu
zg9OH8XYrHX@|7x)8-`4BB+Z&L>Fstmsr`eiwdFjcJw{P}icr^)u<OGKACb6n;1<p>
z&>P&hO6n3j=1icR*F;p6vm0#?)Y;Be;hPQi^E}F(eC+{c(Hv7#F<Mfz&mGlv%{%`Y
zck7v)aH96m^Z7n{9-GD33H3;3#rwQOivp9WF|##Za0RSa8aCEqg&Okd{ba4$sz?J_
z)Y^%v012;aW<{ILA}%v1F@sgI{CTw|mIUbEnx=__Eh=!uIYIdv3J$Y$L!fvmOpqq1
z_%F#7ZF8jV;mTpJvNx0fxA&<F2{e|<%lDPS|4*ME1zwh12V5&?fglm>8?>=r4P#->
zKIQzD=KZ+8w$}j!Fs0cXIsut!s07pu>WhIKC{bdkH?J1f?)mcu<>~(nzJ^=^_zHMA
z|M$w60N9D6`&-epRo5nSK|a7jOe|J_jhU?CPs<h1XY$Za-k^SfoBVZZp49m9?1<G8
zC01sG9JW<pvcKGl>ehJ4baIr}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|g<ho3F?^AwMo{wTFK=&b=t;t7op
z;#Pl>EyS!ESr-{jI;TgX-Qf57wKKVC34DF$CDG_%&9INhC1uExvzuH<zMzNHo0ZJE
z#Vtnrc~L!%EPGQnJf4H(^Jh68T#&~&W8>U8rV7oed~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<zf^J*NgOMooRa^5T%#L)|SIZOOA+uq@sB(LWPA|o7De|!H|5+Eb_J&uu;
z5(5Rav17K<J89l$zkK!n?ezHb2@f^U+gP7K@IVb1Wt_+{PB=cTX87wiVe3qsAvutt
ztM#^OJDE}}(J50IV+aJrc<;=E_V$Aly!nE}-s%sCR@i8ouE9-NDu7>!PeKYy|I>|a
zDw{H#IR-E!9A4;fsUmVB8<tch!U#JAYOmxohqIhJ+bAr~(BSti>u~M9&;RvHkLO)S
z!o!|Z(vZWKux7EYKh}sP@RD&FX}vta7GY;&WPOJ3O!>C+Tz--19AHx$JQ&Y%dhiHP
ztin8;a3M6c)V@{69O6lzC*d%s!mUDHa7KW7GH4<AjvgyBPG%a}yy-Wkt$uFE)1em}
zXa4>ZstXy(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(ZHwd<KWUfCPlFP=WZkkgMfEJ847=CM2O+TzfB*nnq6#za
zxI*b~L_Y~hC3vlCeXD%LvGL`*@Udn;e=h;G+J}#aC8g?jdzI-%kd~;zLS-9|x3hSU
zJT}5dfiuYZ7Q7OX4BWK~pW@qCUIKwOfwn^3#n<Y8P+2J&aL&6c)eBj&JkGtjxo_|(
z%^qdj7s^!{jIeWyX!ZL053onvAPx>O7{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<e{q-N}muaJ>
zv)Y2zGhpu<BQyi!ztRFOkWop@4vL<7<jIy1P?ADU#kjNV{`;Ym#uW!J0S*mB6N;CU
zdIm0#L?PwxuRY3Eur0>F^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(%<mxg8;g*8(B<1o`+5g8VkE49>P}-57TDPyUg*2o?!__e_(Ga3%{2VVH%-e
zTH3=qg6x|av&XROh4Y#*g(lTuVf<wrFkWd=eWFIe{Adr17OS!1pK3^FKrv_KOj;cX
z3f7@FNOo!DMv9v+O^F|*9A?85dXLR@yiJG(myR}Gy}nblh`Xk9i9V>c$?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>&0CAS<DCgP!~
z0xSKOA$%!c@>NAw1}?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*#%OyJY<LB%mM@cnT_kX0yl!1>EE@ETU&(SIG1@b911}ra
zndvQ!LQhO<t!EMff8M}QFAdG4o}CuXKGqHS@l=rKQ7Xvrmy<qo`dm^ulws!0>jl0~
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$LR9<M%lcFL4@B~ltb@&rktE2rYvb4hb2c$reOD+rv%$m;;
zWt*~gTu(RiY6F^fBUCvY*P3KjKIrK2LD57*EN(2ny@}f+{Yo8mWvZS^b*+?RzBD``
zeq{jM0i@oSr8<eg!cOxpgMkST{3&1$M4jX-ouyhL0%{Owhri6;bF?oUE{)!gKF>N+
zBuE&@!3NyY*!N^le;?f@Ke1wP7!PHNg`g)BW#^-zgq9%u=Pipjfe~Ml9Gz_7d*&<s
zDT69z8+rE+OX5`yc|{=vpNT{$g8okjJp-RKf7S#-fmPCv%`AB1=epX+WOj`1WT=ij
zQcbwzAzC<3#erLes5p<F@jLF<sqD}^!k$#Zfe<KG)kk=L<q)RVlK`sGxzm8m@_y4&
z*#7I$t8DiuPZn3o$=Npwe1p~d2HAm+M7nW!sbUDl?4vz^P_iVFUadC2B_OT&gSwY$
z#mRzKbMFEVO!q5u<>sD(%<RAE#P5SdLflio2SStlKeCr)4Ct7|R0uD0qSWQnR6qce
z1A*H~x*i$;mo}Kr_^3U$vfBgg1!1wYNz56wVlQgGkC#L3z}H5{Up2uD7Ml3HCsJ}G
z4<XVh^BR{o+AriU&p+e4A1L|(eJKYKPKT`1O!f#-xIh^XY9mu{LztU?MI1h)x7Mrx
z!{47XO>GkU;96<TmOa=T<UQ9^gRKKeaB6Bl7wz`{9^xHR+r%N)?DY^GWaBUV`axiI
z5O&<RsS!|O#S-mvIiGGXDMHbSB%KeZV{yM=d!8O2x6;V;-OZ)h1f%YK!7dLM8kQRI
z&~Zd8Q+}=q%&6AFsDeUM(@Fj+X(x36J2Yk)kw|s@NZ0GDQ>=H)<5%2$!4Z<cYyFd>
ztBn_Cj1ua81rm9hAM`QOI?bxniW0|$ZNGH!j@p6C`g#j(aJQ6(!4T)0c#;JAjew}z
zL_qm<xlC|TG=Eg#EQxc<Q|4&2U^Rq0Ai#sXmtnw&?8c?T2OemD0HJJJHfyWmUG<eC
z*sq$0n$)-^mly<~E8yydL3kSs9Y*9EOmeG*+!&$Z{MBl{FX7Uovu&@;#)&WTYmtNN
z1`(5CHE?J$BTB>t%^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@DVz<pFUUh)S{<fIIEart<tCS~t|SZ$C;2_V1Fv
zVT~MQa_()A_dx#+w)}!4N!bS!rlFm7q!EgXaHj<w#Iw%?T@$UVNxyDyBBus`R{tya
zDv5Goq{cxs^pt0j8vTx4*(xY0zTDnq0@#H;$N)+zR=P1nU-c+*{c2^QpS&tc?igcw
zH~npYULlY{3l-EWq|Ho2gKGcCWPVvI^Sb|uCogr*VpXd{(5sL;BRJKF&z4{ciGdJ9
zZLyE*q<8F6I1V%)-lfT#e(x)Q6Sw*LH|R+ay|F?hL<4ge(QprIn6HC~l27^ZPeCap
z6gGHLm$)sBGf(mKM4C+_2QHzrbo$q$H}S0xrbDp004PNesJ(>I{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`$<PH*xIW%{KZ{bH$3<oFOSYX~>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*uVYn<u$PQB^4l$nBROq~H!;jcF*i_fdfrA#c#_-G
zyizQfDzkr*KINJHeAX-3mnd!W00021!=_W?{HEmhH^afYp*DjK9j4cHnqU@!bqB1=
zS7>U{*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_nTG9yJ<TTRluzAPp_1A_a)qgMjq4-7VPp`2UH}m)jNxY><jT_
zWT;mWh4_7E>2*j#9v%)!i|LuDJlqo0Od!G!IQQovR?UCFNM#5rZ2;>`t9f&x4*v1i
z?FKfFEBLjY^tmDcZYtdNva6BqW;V&E{LggTIPu=B_r*?YmZPs4s-<Ww1|w>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<BHe9h3gh@DUW-{>$2Wo>6Q*;!%b4GZ8qFf`?O-y9K{lQj*|
zvhH~MGq~~L6r-!409yJ%*=TyVdv)G0j%U3?6<yw$!<s?SrdoE?$#B4H9O3N>gtrO>
zoAdS2IohA2Znl;^FoS8SAR@p-&I=%~Mv`QPWLVtvU{lM?;-V1TB{+U~LG1qWespN)
zy~X-EuIXYPR2i2hu~<cXTNqZ{Nm+oxuJ28x*YpofDai|RoP5skROZK4B`51$xEDbl
zR<t)3X&d>&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#><!gSAloU%lj85vAcuYT`XI>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=6y7koSn<i^llmA$R{Pfbv69?@%=nSZ%;#6;
z*c07?eVfXlV?pW3J>RK6CAfz7kAX1{Z9CZ+%-nnsLWfYE)&%08zy?{9q@1yJr-U<i
z1yv_V@PgCnp5M{SZ0daXNr#<l)=&A+zGv<ivybHUs8H~aMKNVP966eX#=?jD)0X<8
z91D&;7UY&E)1Hl#;q}=YRo=*#LIyO2j%r=nL@^SX2A2@iJG~&2>XKM#dzxftIZ_Mj
z9~mG?9L%l>jt<?=#Aw#{VvEia1vXgG6~ixeVHcnaS2i_hZi0|mROJ24Px=jY=WxLA
z!j^1rGIubX)4X2qfQLH9H011M5UA>8zUVgpp$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}6mmMQcrMqC7zS9IvXI<p0e;JZEetPKO}W_IACe&%1}o$ppdHQ}v-
zuW6*uc3^PwN~=CS^;`ic0d_~_EHaU3HB0$Yc`sDipyxr><g4*4XGqu|;RRWdss8R9
zS|}1C?0`YH|I|a2y7npjW@FWCyFv~u$t|W<BZNtJ)W_MjHAWq;mby~H=tgqe#uBsG
z<e+0vRzV(+`E@B|1a`Nq$DgZlK9Hn)L=<_RrLL1jOfz8+p5fo0Pt$+ePo3hYZxhHV
zj8gLwz<d~G3%PVIIcX6nCFQq!fi`>UUjjCu91|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<nDsU@u>{Bjwy
zij!$gxL70eA9cy+^96+F9%4s)#TR#Q6mT)(G?##pwglO{L>c)jMF!R;Xv?-WBw1g`
zt?C%<fHC?pOR_|{*q|#S4tWdhRYyWLH1Iz{wZ+fZ9EPsEf9U`Id&<k?x!!w=GMB0d
z)^?i|(lQGaV#_wt<2f)R_7;?N947X)ii8?P9dRBAp&KVdCbXpyn#5EuWNs1qbKL>i
zPUTj;*3UA~QvJ<Pku+yobmIwKz;q*{f1COt$4;OGqaxQ0J*q;-u;*YZ6Hp<nW}Qz(
zmn<^yQNg!<_vluUxLQiN;B4nAc^ei3Z0~n76ui~?u@kW-aRah?@@^^L_}MM;X&MBH
zWs@Q-1v#%w5mi8#ualW1g8XLr!C5eI#Z3h<X}{P^<2PNx*s*QSgi_bBa=nWViBk0X
zz1tP1Hc-zX3qd<w@X@&J9+BPZmDQvy@lB5IRp1A7>o)+EwJ9YZJUI!|Q#0d1D<<NQ
z`{JS|qQGSbHE+)#DkpDv%7j5+9N0xjRCxMp=&=KbQ{mtf7Zu8EcE@jB-GhGCHx9V?
z=I@D}E0a~-X9|uX+*_qG_)#Ryue<5NKCU;Mp8#p=uo=NF^UY`W<&TKe3_<BiY|+c?
zS`=7trYPpfqnS%=k5(GZ46B>(XN~s;^@Y{>X;2)#*{p}s);P1oL8r;Ue@XblzQ~p)
zJzw0XUJk0f#>}T_I|V%Xo4_=$jhOt&*2hvb66^x&+)LfG5tnP-*!o7<9M2TIXbzmt
z$95T1<jo#MKGQZ--i_uOBNi9p^yUG)GGA$zoagEb>;pS*%M-sDCIgEJKj;?^T>D`9
z$d!3AOrln2$;Ph7<z2yeD13wWgXxd*L})?cvp>D8p`a`xGq_zF^PTpb;jwDPZ6;8c
zr>zCWv@lIg2dA54Vq<~$jr&0I74!{J{6@^UnsMR5$Bhal8IkbFeXH5Q%4_6L@zT)-
z&OOpU-Kro9a9tDa1$<Kc%)#gFQ|8TyEPAgp{0K779A>~n`NeU30Wn`a=L_4$brh70
zyOAAS!S&I>$L54z@;!mc?~y0JwR|4Br}(-cSKGA*LSya!PqtAhSQe?dxAPiA+jUJT
zEt^Nn?D~K*;K*;iVxG<a@Kv7!oH_|G>{hj^h6J=-&=^mw4ixjTU!SojqVmWI_F<U{
zc3KnE{3ki4s<Z!PG?3rQbPt+c-yj#b>^dS^8QK{-(-6F#)7bZge|xBAr9{r<sFeoi
z;rW>bW+1&P5yVz;?Pu<b_S?YQOS(CAb5}r+fu6n?Z~&Bl_j&blMQ2jZqfP~>#t;3|
zk1!MKZ8kd)Xxj2#9n;fD)Ccat7*P6@a?_3{?&;{m&;CqKPQ<nUYo3u36;2xHQDka#
z`@DR@FW57Ap+GqYpjl{HwPD2rUiiQ-^nvku!j+kTp<6&bGYeFiy$4?vbJ>`|^Ww0X
z+sqHNfXFOAgO+n<f&>PrU8k58QounqFL_uWhlrSkW<?K0+SFxFrooea-w+mx6;H+7
zf6bK94tM(t*|!$(7e34KVjsG6EboRs_82;x;qP~~ga!^A%jwd9cOD{dOI-G6+pIBb
z#mEOXNv~ov5k4p0Gz}WQ;kLc%d&))ylJbd*s8mrodk`R`53nYrMZwRtFtUe#=$FwW
zbsxJNZvJYEqyPaEfbt&4V0Amg8X1YOaEtZxaGrtMfc^Ha{tTXtBK@cGHA?mfX+u{=
z<Df_j6<ccCN-zjlAV{L35D?Pjd!%w$wgxRFLjHp+h&KSJ`BJrelG-6a^bVUmi-B+l
z+t=rAzGH<GG;i0;rfxao>^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-+~Q<VXr@>2IJ)j#UM(^+;}5>-
zCvk-G3U8_=yiLVEf1>f*Xog*<m}URP%=t#Vp2v+OPa1O!7cWOwN*y63Kb(pkjavhk
zg4We^4<0w<b+GoQ8S>(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~<g}BRTGWf{
zM#pjNW|af#+8khh7aLbJF|iQg7WNyosErf=wJUvb8w`=M>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>hL<dQ}6CNZhPzj1$e*+=NER
z{>eq*W=m)4VAkkiSsY{HKBXB1^&oic4Ad6cqYgViD)J97m(v*_b>X}Vk1Q~@@f3=i
zn4bGbj+@tVz5o5AZKR!^<Np(H52mNJ4A!lu0Y=LsX9i?yBW&ak2Dtcmq%e0eHCI~A
zY)v%&vOD=ukecOY3O9H@sAF7IF3^1=%r(N8Vf4(7?(BomrL*18^k;p4+h0LoD<W52
zF9vBhh7l*Uj(^bB8OzGEp<B$ef`!@gB`_4)!hmd-*1x7(BOk}`SW3{pl$b<rnd3hq
zblag-m0&{F2fsZdgl&FL;3WMC%3<V4kXF9TZ<k^8l1K84^#JEr>c)D+ir3{<tTFqF
znh30P+Gk03eiQH-;5wK)>zn%5KCclt+Z8`;MSCzoF;GApnDw4>AO%T&Q9J<Is360N
z5-*<31mD*UYIlyUd4Nt*7GV-cQdqSMtr-rFzXvt7Suh@L)4M@Nt}K7|-tM4#Y}`?u
z8Mu#n<ae5j)dkyLW+2v9h%?4Vtv#10_zE8X@-T9exF3@q(iRDFr)C;lg%sKoH}(M3
zmU%{LM4ZQHLYuXV8U8<zYCg(|#AN;165@-MbR>N5xrgO1GuhPM^}RByN>V5g4A*4s
z(iCi6U*#S;72xxN90tM8(4rGB2+%BHPdJ>fx?B*?fbmf%oicRAt@5}Z3M(<S)*qZ4
zQhUMVY?di;9_M8j&ye?W{y03BXcqX0OLEc;`B~%5d)Gzo6IMi(C%CZCW*Qza4_7=%
z!gtK@jdIPb9g|7V0`f$D@T;p?9r1TBq4TCfx(g~fZnn!Brs6%j%6;>|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!<IC@zbP)diE^uiPvvJA2D
z3Vk#vh1vgYOaleOeqtko5<xD#_?*ndjwxe<w?TkMHAcZ^`b)vhGW}drm|BbV^GsrC
zX4`w2DAN(v<@!ptj7xt+4<O>^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*=bzy<XDd^#fn-Zs4o&YHN0pXt_c
zwd>Uz41i5_IO!aD2WZIl<Z_xAg^nPGdTX}I#R3#&U8_us&U+47pLEqIoNE9-sDkPu
zm_1V`?aC6*cwf{%H}qf%z|kU~4=JKwii8iymo_c;0@oH<O$jAT{`DOVmdfXP|7X9T
z%!~`|Q3*z?#k&a*^LXu*w^@;_H(+!qAhKMfUEIzERx(VW%rUy*JJV^!r@F_n1;Ym{
zLd(vhEgW%STJZxh9jzYJFr+oXA#TV}Y!C=se3^?wfu-)h#D{6H<*Cb!sL~hAeZ#jJ
zp}vA{NIUAv)|CDq)H3V6NkhqmSt=;H8N3hYL0w%`af<r&Ewb}xMlHZ|6!y)^7Y3cv
zczGwY+KTsWZ3BG~M%WF@gD|y5bcdP2zb!>a={Z@&rj|Pxe=+Ew4N#tcdWh2I!Qp1D
z6O5giwI|da90tISS*UF4oLZCTdCg!_VNBPn-_H21?`~aStt)O39w--|aY)(zouKL4
zariWak4q}+s<PT)oc~?cM-w$eJmWtmcRAmo)l+2`c}SI`zb~Qi=7O+OYO;4quj(*W
z;^=~}vU{A?X&eBM$z+)GSw61)m97+II_x>qMJxJ3ac7JivIv9J&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%<lTWcs;+Ibfeibr6+RodF6LTy6{ksUD((
zJd&yhUwsf`zSpsN`$8rFmSE|5N6CY9tApuwCYl!!?0%gZTQyiCsa{Kt28C7YyP>JN
zvP})!Yqwg<X{|#1+f(e1<(<t9{6GPe^l|0YDF#9D7#T|Jt#-zuq5^B&f~z{y4pQdA
zJ9~`@jsFsHxZ3H4pdX=e6}pJtG9nl%lmI>?;6HQ2fd&?4%14{~&L~x6(kskfsm1g0
za>@z=;vzsXGXbY22hxN!Rrr$taA~s7kQrIZh>E4bv(MoM`;D<{#y**vb7y<P##aea
zi;ugjC;B5#{0|(*hbvEotriynd}r6i%g$1KO%-nyNMy^uM&-Xij4-NkiqiJ#BQ-H3
z6hy(%!}0$hmSm(z1R!}H5Mdz$vA3(y*csZKc(T6$96gd@AB!dugwjy$ddPT8r$a^5
zq9)E~p(v%W_TChOG#|NU6>F8{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-vJ<AENC%fi
zfZGi9{FW<$hVf-HR(@sgy?9ejWKgk=7;8S;(t<(^;e)2{bR3|S8?iZaYYyko%^yvi
z%GC9W-@UftK*(WKbn=otRnMV_hj=>K8qE28iRG<bUCQ4rufxt*znQX*<#Amd7b1DA
z;cZ|yPIB4RwK6bu#nZIibqk8C$#2XS&W=K;bo`#hM?BAr?x#(%j4*u0FaG1(Ul=vU
zgRPSp8w>&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#XXPxWnPTmwLNv<y7Gr>nLnmh64{FnCvKC2=mI6|f
zALZg1VQ1w<d{7!$m1b(*tM<wD!{GkY?2n0hIe_Ox20rL~LUYB#fafE^c4}0TM_KO3
zR$=qqo<qni&cTCN+Gx_ej~HOzeDdwKN(ikYt9^odOz65*1^#1U*+)`3Pi89Q72!;>
zw3BnKpI-^PT)ZA~Z`hc~gVWyK<Y!HU6ijZ&Du{hjq?f`UlR{RtotZ}t24GulE~i0-
z$hn&&YK5;n<i@b%Vipl)j6vEQ$r~9|NSl4ynXv(6=+7sFpyJU&qAIxx^Dbl{2CCMm
zH1~7Gl1+PbPCVxyVFpfBkv*uZBkvpnYnLM;8$A7UgW<EW6WVB8dvl+fEg%lEQ>(<B
ztV3IXr59avjY6vjWOsgH#n%G`mh}W?D9hXaf%XNj<zMEvkP=ifD}$^}V~BbStKeVh
zLV{Iy$lP(0o<6!>3KM5Lb|W7bJcmQC>9AV-`<pv$=k`&|YER93sKP5c+QA)Z98Ul1
zpb+8hulC3vPGPPDUL1}eHPLjK^Wipk-uP}xhqP~}Mw^2f18oqgqIRq{M><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$}w2IbShclkOs<kAv
zspYnSZWG5Mz-e#9-`>c_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>O<xLPVuH}2jNW_5OY*t@EetOjUQjY#TR-k2OL^=q*>tAE6mxRY
ztqSur&6HtEd8ySkMQoo^Z?00bSp`NHfWDo-SJffm^cF45-@AhoDD(c}-aK_ykAl#U
z{x+;;|3)3>PwtfBd}GX5yMKseg2K`To{UsMW<za56x(Z;Qz2N7pGRfJ8ScHZus|C(
zV^7QlKY)hMy6b@D>p(cpn7wOxIj>7dhhchQ*peyD4YJ$!I|!@0NOEaoLJZV`v<z=@
zg%Vrlq?JN(e|Oxw>aZUwB*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<lODs#YdU(J#G~UW_0sTZdrp1bv?|
zmz-Cyb()*LiCX_TKVwrL%N@AN_r{lCwlNpk%%3oNeVegvT(;9Vd$O(?cPr<pw=E|{
zi&R)xCducB7>?*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<VRNTSbt2xs(I)mw;$r>}=N3^v3{(Gvg?u30Lf^v$%{@oqUZwBjHOAvHu
z7z%uuDM1{!3e&HaqnS<F{8`TwCvNb2(L^)ddZP47H;QKLC{3A(Cd@7EmNyPx-Q5e5
zjh@Th_FS6;qTbf<o^3M$LTLcTs`v|fQPY-P5<;C<;VhBv5abpFZYh(fu3~l^A0hfI
zo6~t*K?`xjco;O**xxfe^_NA|I3oSxI{K4w-1ZjfIiy&o0yLyf9O+l&cKJu!4X7A+
z$a`uEFDY8fXZn$zq#=_uc<*4b3uj!Qs2+sNO_f#r)-)=SbsG(Qn5Aty6eV;c;G&TY
zoxi^lPd=I^xUf>N;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`XfG<PZs-1QnbK=G6qKf{AEzEp<9NcOFO&Ghh0XQ>j>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!W<qQ
zY>i0txTkbNhNZI0>;N9zyA6oR!kz5OT)#>z@J<SY7AXiM1rx~scY=MDYD0I#g{IAH
zBLk%ci|d;l+~rVcQOPc$l%;(62(e8%iSqo$eL*~&EUWWhwK&=96n<lL5R#)j^6nGp
zrK?PZMAX~6OqJl9l*^=X?F=Iu#Vk94zgls&sPI7<bOC}6$Vq0mKmf-~v){h^BgGwa
zl<}ZcwaCa9P+LB_Du%vM_AO=(?C9Oofs6{j@dq8p8RRK9@3$>s;yNhh^{6ZS+ohYx
zfeCJZ0jg62s^}fpNiMsJ1J_R0bYOS)xD)!D;&0T4%QpM8u1r`GZ9Q;4NT=wNP>N4G
zfUm)jYXB8RGYuBAN4u*RZWl(;vvJ<?Y-!i<n}`e%BLr*)E9V83ud1=vC3VR?rD~Dc
z_DBo*CFMd!T~L0JfVU_DdXD0GC1H@dU<i28Z(Cn)(!`JDokPGbztGDR6F_z85l8nD
z3r5!Pim;3W64|LBjhBmrjld49nvAA$oMa&R4e$CgUqHD#u`cyfnHhp0gi%$Gu|*9*
z-VuI|c@6SVFs?gb<$&JTo{tG`XzX8Ouq6$IA89{vbzU6l?ey=<oz(UV#%!6uj$6QD
z`jH28Fr;*IGzh!?5OVnMA_$gNYMPp345{B91KTq;;=+MCA{ypXi_0kuiA1lxS*EjS
zBBf+mn0K0yAw<Q#arp$t8vZ|%DMxq?V3ZM3i%ZgY<t3B6o++h)DEB}h-fL72tSM7t
z8}!{G<Gi2MGDY+h724c}0D(LRuS94n(3(`uk9<=xa{ar6f3w2H3AIs;5%v+)qNx@d
zYmbwRP<R03##1NhGDb`Vyp;87KT-7vo}`Y3c}n>#+^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<I;38-$vN5C~GZM782
zj(Bc3(72%|K2SIaTGt#aaDG^AU?m8a&yIYoevuO~b|k-(^opTwrC8kDu`F2RHZ8=l
zE6pq&<GgWIbD^n2PA><+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$<FxGB9;n^E-)sW)7r
zgul&vFc~i*>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<E#H0&1?ECUimg<Rvhk>;}
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_E<vpf5D0{-i#f
z*aF_Rn<^ObX|6ndKK6V9@}Se4eZ<lC!{QSF2@U;+>ub5!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&q<gWV$7_3l5~yA-O<a=a}jfXT<ENO=!U7;00eEdJA~
z&{svdXi$&$aG{bHW2q1m^3%GF3Wj6j>LZD9jxZ81KXR<E4C8)Yf53(K;r}xNyeG$s
zot^cHuGK8T#3?R6MJS={e?oEer-T|}>B=JY=z8<jH}iAjoj$rUdNsqNMem@`zW;Fg
zkIE}zSwspK))~rd)gDp7gRuA&sG>U@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{K<s8+
z8#5ItgnP6Yd3DvQsi9n4j?@SeJfta<6ZtGwlVfm>aLccuhOxyEe7V4K|JsT_CgD(D
zWBTI2n7E-Q`4%IBW?scxJ*>0>%j|#)1D7Hk8~)612R~$3<MZ5FBVi1gYgy~aj_idU
zG}?x6PO6{T=f?x~TxZudD3Rw9y5IX&Q>b9%cz49Oegfw?p$WW44tRXWGIrI^C+FEp
zAM}Rlb@<ILFLjiI3DNCR4O|?dKZ6^uZ_&)D{abSB_!O1<r>FmYy}HVj<e&P_>P?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`bz6P<ciN|H<L+I%%>4J
zoDgQ8T{KWKZZ!%B30`rVecieOgFMw&7eDPlCkDeg?w-4}HH{~X9)s7MfME|(TyuQz
z6%43=mq>sOp#w^FxDHqMMAqs_gU|t-55DnKNP~B#Zz1NJc4i4=7EKG<WK}^@;M`0I
z4M|B0k{p3jf44o@J(|-C8(?q3Vhd_Iu-Ojfx`db+>PwRZJGLVLbW{&4C(n%lyZh(4
zeE~8UmNkwA!4ZQVRRf7hJmde}8&fo<t40bLqCohg@?Z`!>)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=<#Nnn<ADtS2iXDwW*4
z;CFuov9f{A+n}89<?8mm<p?D-k6+v6AN1p=q}UeIl_-|Dc2)G%vaY#B>e#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(xQNRaNB<Jp(mrY#{=e&=?adt~uJAEFl*EC?2l7(Y&w<_#(Il^VE)-_y+TT<z`sA
z8;Ll7s7Y_o=!I&#w$k-5A{U&vF#uZ9SpX%XhweBPxQo6)^aGXvblG=9r)mkHUIotl
zoySGi#6Dt~X@95geUMvdC1jR73n%A?EYAAOy!dweK`}SEb{+Y7&HrF`_Q?(~P&{9U
z@w<3S{>JOBpk$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+jEbu7ju<wLB`Q+)Xj=Mh2md>3aa!
zF<*b=Y@oP$I5S<k)eusSxp+pV)SYIv4`ym_?_91lVwnDFyq8E0R<7Q%LRxMlf2*Oe
zf;Z%e|B>?_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|<NN7i9ZJ+0F
zfD_rY>(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!<?kJrw}zscI*A*~4I0uG0K4
ziTCAo(cu@jalC+M1&f8Y7gpSzdI>YWp0Wk~J!Q*NrpU6YEcAAE{cD?bE4Ur<l|M`t
zzc<aEu)=EgjP4Q<iV2Zu_Sb=h3j-I}p`i_qWoZZdpDWNXVxh{rleYkc9d!CQ&<Ho6
zvW-aNTW}2nbMSp^3q7Ok5RAe<(0@iTQC1px1%krUCRtG*Ua6YbDGOPxMp-7A6LQH0
zR&$S$N58=S*n!!4ZAO_TxhBzv6s`nVNq=SP{Y@o9Gd({^9&I53LSo<Jv*YM!cuWd(
zV2Pww&+0>cuD<P38QF>$DTycu4RvFK01-7@7&qNPJ-$dy80-!;ngpXBC!SFk%3c@<
z-u_@TbiI*5K7K{5L*q;39Bu-(<zbPy>hW0|jPIgf8?sbH1Ek&NLl67$KGIpI5f0**
zERBkX@MKoLMpxR+MXxX(;EQ-beq<U1?*2QtIlHszWccim{ZEX=^H)^ynt{e6{|~W<
zx41Xg+X#@|e<cy|$UZGe_@O0X42ZInTewW@x4HsE0Nn?s2S1ZKOnT{yq>rH+OnoQp
zA>>h&JE&%-m3<7sJ!R6><Ganf>zaX}J#2Wg5CLgTn+fH#weNmh*e{PkdbmD$K#<L!
zgA=Sr@76=V4yd%FW2;VzSe|2>KuIf<0)#>3sN=4pObV0*|K`sv_+1d<M&&<97{_BY
z$<3O#GjFPNqU~4rv7h@;SPj9fhMTsn+<@aHRKa+)SX5}_{VQS|Ar4&=W{%+$j88RN
zYQMPw(i?VB(1Pd?LU?Dx<zqqH)&W!A#*(B{b`ja&Z@rJ_3PA(V(f4;{D}w}_11mEf
zdO((omInNJuii5Q<M3EtHsy8g9HxWytU<eE#?tgJU@l10OdYMyrXHm=$NDciCFW;c
zLMU73^M<@Cx5AHX83sNhhcsIIhVsM4Tu4bV4A3`D@s-<1m|&F2tEqfG%*48S)uM~c
zmd$Z9&i$STD=uw1>z7T|%gYc^E#t@8H=fPK)MP1n=*I1Lup1$h7)jb`DkWd#=aO<L
z@mVJ;Ol#)V&_#KS!X<$KH}On<JLE51=C#9p&in)RO>8pp3Q9e=Nc?&9)UU+z=4Q@t
zZTyd;{}<Zz2^&@+3~+H;EMGbH5oK4YqM~?_nT+2oaQlYG9nNTJsn7mTA=NFs;I9uW
zE4^}1hE`xr!<>^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`<w!f8}`7elr05+B-n6Rz^P7`94ehV`1j&}IxEGE?DjRBW#L
z;JzGJ^nXZw-E5%hBHXeJp!_*9CclWGf&KuzA6vdY6khd0n&;&tfZhJ;X$4ZR)T{Jp
zWuiB_Dl`*a_i@|yD5HN#(Te6+cwWY4H1in=tPEsS>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<fn9UhUBqX78Fy_-XiaCImyAX9L+6q?V1@pxrF<k
zvX26gwz8uGDdl?OocdPr%P>)4$0~C7G+F{NhAlQJn5r2O<Sg>mM=>Si0oxN%M1MU4
zH;(pY<8yeEz1IcLPMR$$k?}y%1g{w~0m4cSF3TN-z8r;#E%19YKEfU<RAZ-k%1P=_
zselPCy29Z!#s<16uK|x?5fRe-4nEk40pgpQw6rw29qcr}&^_m0Y=)r}#+=-orM7-Q
zptGUmcbGrYor6&v%5<uVx-vwMYD@hI`sVW6x}f(?gA|CnDx@bs!8lP1_umpl=u>zR
zd3Rv4+@73BZ(R`H{*{~-><w}s71@?1SYRpZQ7=WjRCobsm+~Jjphm?olFTgGrfC^Z
zssKjeI^eFHv%Wa(B}|^gN`}WrJJfklT5m%g?~_zFS)YjM+NKtjolN2N{?N#$Vb&ur
z$pb>v2J|$tpUP%7jG;xGKF)%!t<pxi6m;chP2!QRH%Xm8>Tv9&E>vw<5w^dOZL7u(
z<QJVH->cJ70KhxG`<$C+=an|;<54VAJ7xwiJBa<wAI_gyD=I)-&5DEh3Mk`rwwU&M
zJR0OPnzbJhzR|b{s8CnRO&UQg#$0&@3%Yy?wUV)ADI8B$&Uaek1;PJjO4JLinnZDx
zF=8x8cwc|U!96<=V<z7?$lvPvaYW`c<Na&TiJ<Bkdlt*$peMcD3%_LfuU19A&Q2`Q
z@k*%1QiqR_pl7R*EVsdv4&;RN_G^k_P#@m4FCd>3%~xU4V@=+#aShcaRiAKdXJ}eD
zrK03L;v2G06@Kv^5LB?YyFW1~UL{qM`A{ER<dJj(OG2fxY<5vQ?e&oPH-FOLi5j6l
zWk~E3JqGdExB{Fy2O}OocoWO2Q2PjKBYK2OF$(+@J6RCe=`A;Ysx1zz48?-skgyRf
zcFc3Fo{XLhK&My^1?ZV<_^!wk!dH(6Ld@mR*$_Es)(bAREM}vpL6;d|<ZV}S!PpB`
zmOP-0MYtPs9$@x2ML`>Yk|T9qy`;BxPl|vSHXU@y)y>49{uBY=asoJ4SCpfB1Uhwb
zkFb-IEC1-^kjYPLk>9e&ZQx<ESphA$sx8kj19<)})An3(GIt5kXUq949$1WYWpf{7
zD>0j``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<J?xio$y!9mIO-?J}Oc6!^WFVOH(4f!`A{RzGeZh3$cVyd&>
zNw5(4MtiPs8a@!t>Y^c}4cn1|c#8{GJpiqSaxjWTE|{af6m$t217(2Z(0O1<Ct&yp
zda&Mqzzl01-oC<l^(R1)0L=jGrrNZ=lMjPy+nw|Z{DS%Uy`LwhFHTh@ML0N~;_lqr
z?`MZDQ=uvsuNfq@vL->p#ni4F{Tt@<Z9)9u5#|#*p<6l46dZf`Z#Y@DHX<F=-KGqD
z-H#@jFl*r;!Ybx%SeSdk`1{};kEGinTy06fQ>bBqF<_h9z^I7z>ieL!amvE}<MZY=
z9+1MUxr#a+H&p_8{CoZe!xj~V0#y7q0AZE)xFTEWoweX|TFDYGE42)F!XJ&g&VI+B
z!1)<iEu{3iKUEcO*Hz`U{DhoImYf|x)ciSugi}ekPS}==!|h|AR>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<<<Yed|#P9Eqm%>Nhp~W%9kF}l<P_w(R?=#E1kc`!)
zxA$h>O_vZ|pj`?P$PhMMfQkRJZ*0Ynt+-HYw0ylauf>}5<t4bbdH-`paN#d@gI~%J
zTVRMbMH_av{xX>UOh2PEHW%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!me<v1q+L18a~E5kFyEK^6heHHvVr+Pqk!Xhu<Z`y%TA1W`V4qgub~92bV2_j
zOI;aR{^;(oO9!E0IoO+n7$LhIt5^&464h#+`1;Qt(A_)d(M+$gSHWsT;ZKE3>xX2j
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<V^CKE%;
zgePnrXEsMj;pR-{RwcUNOq^ce1FdlG_wLqF49}Up<VKtnR8`lwrIN61hp06AlF6Q6
zU|++r$szw7xbdhbF@%_4roJUJ+}PJsxl#({2@fFUBDGF){qJ#{yHG8FZ|M3Kv7bq<
zyJ_=wLLdcQ<%E5hC&%S;OJyr7G+CC&B>}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=<NYRwtxXFy%#5{5Dk)A8%%K@tST>
zX>B2qg108xSQ%em0JD=adK*@>UDAWFh-s)sW<d(3OW-TG|FrIo)&Cd<&=n%RthsYW
z$}?o6k)JiifbWwBTSl73C*cLwYCfy!M)Iu#47xW8flPD$IjV|GHQMLrY&Hnbbf~M}
zf5oWHQlw0^_WH|diNII}(1H-U3YX%PkxsKu^O{;U(6!^rOI3jE(SVxo91F248>i3(
zptxNu!z6Sf&efE*J^DYF7e2VW&aojYVPS_szEbeIiq$-CK+6sv4tr%M0r+B*qyi+7
zo4QYcEyP-gL?<trml2s5bh$r&5(-YNdY7Jwhq$qPZo&&*ybK8+2xbc4hbI<bJPEKy
za4?#A@geo88#wJ1=+WA{IYt`|vaL2~)3S+Jv(>~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<YR=S9u4aS7{YT&)+UU>
zlW^J=@ehT`zKd1V+z0d%iH@k;EBj00LG^^rQfa?RnoZC97$2$iaQ>kOpp3EVv*T@;
zJbd^*l`W3`5Z(sIA~kPB!<Ao}B$HWrW9yBp=2)RwVJ+5CQ=H{UIY=;O35ywIKXv#&
zYGyK*vKZ4jhKN~%O%?{P`6Z-vDVO|go8(6W5?=AzI_pRv@-3qldvSDyaCbGs<?o*#
z7};sjALD<BYzZ(l2J(sb0felx>?zGjflv)>96ShZVF`n28!5k`P;g5+ST*N8cy|e1
zTw--Ukjqa}jyw0$RgJhx!K?zC!K?V@)DSDsi3Ddsc@!wnCh|pa9_4gUNp1k<<u2C3
zkZ`O%!FD&(%8>=iL>L8i1u>t5D)8_yCKr3fqX9Cl=91YasWp0P_Gr}27l}4;y3cyT
zbH$`eKuc|Ghu<aFNH;!L&Z8Bq*7AW1TyzEYF_&*e>WN+Pv<a1(YL_nRsh6s4gxA4e
zIHf09s+~Wp*@B$ol|gziUCt+WhA?2o9j{HI2m?<h0|%$H?E-i>$VDtfJgAm<RF#(#
z!@zAm>qi@-oAy*vXK;j|O<9Rr041#8U9)`e#DE`2i*y_>Yt3lnK>^-C(0AuLjOL}-
zb^tI3uxW%V9u_<h=@&Zp^-J6sj=4Gk0*sDtZ<FT1^Lfr6VU(>uR94N??z9<K>x{f6
zvZ<Ujkd8*1yU;`^o7y4yqbfiTU&TK)Dz*n0Q^BZnLw|W8<C1475=%EOhe^qrjvR!I
zd19-}eo*cciE<=iFFj~r$jCTD`8doKO<P4PUY)6A8^H}$-fMod+yP@>?PN&!n2u{L
zy;CFU+m~8^_xatpN^t4*HnxM_R6YTt6dFvIyQ5Numy@qrMSSwH@-~{UJbCCznhzTW
z*z*c*(HUW>GpQ3;*f<N^#=P%auLqdy;aKV^wWLfk-yedj*ok&s=F~JQz%0C0;=N=e
zT*m#w6J27r<2^KO*-&D*SN3OMW<pn{m_x7eZiyYy+~I_Aa0m>;Ak=$$(c&4)(eJdD
zGn1<`znmJMSoA74MNOJ`WM8d>WUH9%8fFE><cH=&K^A71^Hx&FFfv1SH$<~f0Vf?M
zP#n<7ZuJDN#HmMqFu9OYJqP(q0;22`rieDSCSFJlxFTm(MftWD7Lkjrmek*(ob7Us
zos6`nK}X=L37G2X7;jn=E{@3TS}6)2N7ak@EC5lJ0t&wOEkV+ss{wEbx2jX!PtP?L
zk9A{s?)xX1)xJ;FOTmQ<;}F-KuU~^$pfGV=_EWb`Lly`$%@WmH9i+Dy9SlPfs}7+!
zTd!?ofnIfPjVXCUGQEb&*jCA;|99>stH<I3RDw)wgAVTS-HfhIQfc}UWw3vha<wdz
zDw%&^MGg&_en!w1U`KtfMol*nz=OQ^ud_y`^p?IrsKQmEc11OIRGhSg2P34ha*ae_
zFPY;yfU#WzG!1&eGl#%yG$Zu#9m$CH^XfxmM%xnP=#9)o?dx?q6^QNJnC=1-1i8S$
zF$};`Omlv7g?hkuJa%S7dnE03#NQ6|@(_jiT=Ln|9<!vj{XG>TJ;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)_Czbm9fxRLJsTLE<c*`}t1{~4YX9(m7@E~CWM!SfhCWw0t0qYMv$BOA
zw$07cs~jGfRIBoLh+m}19PV9Ur8fw22|u>MO49$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$dlnVY2<J$pzqa2c_{7XI
z)b!E|2kVUybOWmTz^i4D3H-JJ74MBwK!AWmx_X$mN@)})Ju|yjVIte8RA*IXe!G&`
z4DgU&Kt<4cY;v9#wCnITtcj8kaVL?^KU)qoI)4Nd*_vcZW=8H@p=4V=vtS!hL+F)j
z%Pg)}mJIvNIhKK@!<&}tuoj~)u#4PHk#H(Y!!w3^dZ+nN_)CfLkr<B^NEcUfCJ9s8
zReX>AJ=&%ie*Ci{79)iWEXbigqvr=0-A`mqUZq^8F*7#F0-it^GF%AeLITPBETm<b
zDwjm;hS^`HNUh`;2s9|Rv6&EhwDF$8!DCs|+Mg9m6Jb}!=nu(cJ@0Q#G|;i+PM<sx
zEROkT*f0wePBSgZ9J3*AUf-HRdx8*qr1H7KTh@NF$5t_F5v~!+0KceHcSJeJEjQ#z
zcQ?)K!qf@15AfOtHQpcd{n!VW?KSpKEc^hQq2;jBWBpAwK3Pb4GSq*gi)wmNB!AAT
zKmN&^cjOBJGMpD~HcQv6U7%~nkw7MqVD(hYFQqMwRFbUwFOTiRxgvjrOWVVk#yS}J
z0^n4WXlikbro&3&E*ktbCAD#}s8P)<H+6@+aA?Z;=ES28W(u*uWGcMX%U*SW@%N?H
z)pM(wBgZFdsa20kK_$PLD}(IFYdw@Et9kVt6;LJ6FKNN$HdF8|4`aO|z_04Jx+wDe
z^u#&fMxZ9#TFTsWj1q#doq#!PQ<UukZJf#afNKTQC4axI#4F{w81#WS_71xM-9H{i
z`GpEOxD{tD$T*!U5L!z+AkOmtiY);YQ;vHJhr?sGJ&&Fc-+vmwJuq5wg&z4?K<G5q
zq5RCZ=SnfsXWR%6`hv%RSQ21~S`k9eYNQ8RunXl~>Oh*np_~`r1k}t}IxHqXV9lzr
z5+=_f$~U{YrApSJ-$apy@GENZas!-dm4dO|Pk`P}H*>~1%<jxct>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?~<Gi^gKus=9SRMM#Wp1yqSCZX%3`nR0{M8YVYY2y|LJhn8C
zWOG^Y^@a=C&Pk%U2HIPfW_(<n1zi#(=@lCDn<JOHi46FA_2<u3<60_0T>-yPLE<ZK
zc3^Ishs&|7q#4gDy~WZ2ykpMyXL3;y@lF>g_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<HBTW)ZLD<eUpz=T%yLgd2l@s#$vg
zpPBj6k?d%#(riUUyqh^Gm_Z2imWN#>=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<3m4d1tc<zF$(Q!!T8Bo)$^rKesXfMU(usJY(Z%i7teY_KDj2pp`m<|
zpC&RL`Z}~qatHqCYRlm<)<F`XW^~c#aYiJA#~Sa6(v<3Y2&k$9uS+Ts&}i_?p^+pA
z8iutkzel|mrW>gTfEfss1o<B27Y{>Db`Kq|LzYrh68_PO*D<OHK^hioi-PvB69kT1
zaDOCvWToy}AlbAEo{-c{agu|sh2H=T^5I2{Mam(#5sQNj%L;>YgVh4{_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+_lClgw0<br|EI7`m!ii!OG?3I{!?;Ib)HK2m2>L>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)0<xtx!Ny-JMHSl@tBE->hAkd5qNwg(*}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=?JmV<ke^EQ8f!zMMmYZEd-$$
zcDaB#Q&iEWC^xhp1F!%GF7|k-p<PC3DC(BgD+X|rx0Cq#A@V{h_CKEN5W94GF$h<Z
zlG%hW5*#xp%M4Yk6WuqjPj0_&=2J!u1NCV{XqP-kpW8=jB46En^PPVEk-g0!gq~)i
zia|$f>5SVD|AgZ&&PO9zsV3{lT(gmHb$KQ*pH9&z8U`ah3HxyIQ(<6qSV!T2OwDmo
zr<y&~3Vj((%aCWhI_vszQV|-&wbEF$KJ^c7_uV<;q{xVnxXOZ&2A%Yc`_A=({=~_|
zaby;j8=9ElY;Ky=^?a4i7H)stj`ZB!y(&O=f~Lm17DU~WAe%T6R5*~wroOu-ZPC+=
z9H9e#A||7sd)BB5vuLT_GD)Ud-uiZwRK_}=qlmqx{q4U9HvN{gE7KhTZ@V`fC_nxn
zVTPxphh57os;A4TmS+IQQ^+<7Pn7*qND5u8#A2JhM|f`!@&_aZ0UF06`kz~p(Cc8<
z-0Ez?g1%o|5q)3nQt>tlKj~8>7r;}}9n-eft?E|_QjK_Er3s@b0<R%{%ZVv<tSxC4
zUdVl6f0tPUChTTA^+BX^Z1_45k(W$O`YSS~zPQRZ?}EIlh&FaN)2}SK?z;CaI)GdZ
z2TaMGvoSQn#_WZDQMm_uMx&oU0RcnqonPY={M!`bQhG_wAJx_NY+(mp#4?h?LJtYQ
z97tZ+PoGpFYj#pz;I?zk2=$)X*mTe4d_By^4s{s)WuehTrdg@~Z$Eb+v%R#3cb>vQ
z>V1o<DE@kyf^-6Mh8*B;<^tN=61j7kEE$Za$(buquh81WI&Av`_COLU1$<L{a2kmJ
zy~A#41)BnOyb}rJ%JoSkDd=>t931NZFu9;dRkeyEmRc|p&~iH!zTPwK1`Y00+I9sp
zxa{|wxB+h~%$%NfqpGhu6}XV%&mP>Z<F0%mJ*-ws#dV!sveChR_SWkM|7h~=rD_z~
zHM3?~e;)$)39cS0*m>mff`4+8#fg7YDafrk#@a}pq;Xp`qseyS13oJ><Is6*7QZsH
z8&~A#+VjJ#cOyMyz~GT1enGyN{U%LgN9(upK5Pd0E0|w#j)I@T%I}1Jr*R9NKh>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*fM<C1t}-RU<h^v
zm8{{9pg*3L7zCO(2s(~Cw}T%PZi-n<GvAk@i0<ia1t*U!x?A$IJ#<r5ci9Y@!1&M7
zwoVz0!$}>8l0?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^<w1>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#<nhB-3~kid!$yH+6{ZF-fzgZAC0pP0XcC)}B=
zA!p$#Jp)zQPQuG75H=MJnx)ZT4%<Dl_X!-9m|Dvt#g6e}i-j=ot01CkVKNqXocvRo
zk%B+NAn_jJObr_`gUZ*;j18k^SDv{7YGRg|$yc+TywH?SV-kDmwj~nyoRkQgc$4B~
z3OgP{;l^1qnT;pT*XX93TR>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;<pTm11KTs1RM?|#I{lt-Ml~`~Hx}+rx(s*h1{FY2<(lE*m!Zfa373d5>*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=8kLwV<w{BL-P>3<if4d*Rj7baZzSA=xCJ
zXx|QjCIfZ-mC=1i(l?zvC20#P2u)ldh>hNS!i~Ue&odxp4(+kkR!+0s4nKU};fCgT
z{0DZ<l>0G{h{B#slbrd4%ANjDnC1o~3C&txDK99hu>b;EW_e|TRHtZ5MJ=MltH+*?
z{gC$HS3gbkX;aPfPIhI^X?@s^eH8Yl)9x<F?yK<~l?vJgM3oMaw6&OTf3z-VGH(rI
z_{a`Y4FHs6d>qaw5U{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-<u(NhvCSffDHP7F3P?m%$}@?xCOBO%+AUqMqQS|
z66%#mqBvDz`#-^#h#i{Pzn@(rT$ee~><G>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~o5yb<a3+v*z(u(XSa2N{(>aj9b(Vf%k(!P6Ut*g9#``qZ_+y97M$v~;c64c5
zsEdAfyX$GA8sUc)k4*3VJ%s1EjHCR<B3ZzN(=mShT1LCc^E<HQ9&_kO+w<6}EdEtM
zNebs&1HdwFxn|tSfZS#xmw^&R%crKWY$a#hADxPa_nx!iDjGf-L-N+wPZ0z{W>k;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$786DK1I1h<sIhn0JycH(Y%?4PfGbu%HGfXH<6U(9C=_}tG&+%*Z{e$
zitA_<xoOf7j_%)`0Xm=h+L%7zgsW37V}U`=F%Ryp@V!{KPLMgSO9&5rNR7qqXz8rR
z0Wmq8aLiB8=LXjoi-Uly;a<^C2~<d?%ssG8<a1*W@hy*;-g#+P#KY8v+w6}SSosf(
zbP1UvGDuyg_WQ2^r2g}+K#O}!iY~Ov#U4k;e6T6*dZ9xw^9sj_!SdB2pRr_;a#|Gi
zVz+jI`o(zy<vNs6d7kG@BUlDIhS&wDN{A4{RpVCzX%{oVg(;Hx3)bE{PP6G&xIKgH
z>xm+-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-S<pDRN&Ypcyb(JsMW?}q;MGwytlhsmDAic}Q
zVx5p|9P?%Y1W$$^hwjEn7qBPw{3$wg>vMZ-3IELyy<B}Locird>Qu*^6O(Bh_kG$x
zkM?#EQ-wHy0!{A?q<!o;F!iBcSD7%=6A|^}v-GGUzQ9(^b;8hycY2Hu)4e>d0yTWB
z`6?z{(G)JadEHNdg7l-Knh=Wa_@^B)`X95bZu$O$Hp|*L<C+Eg|C&O*0c43;26qsd
z!mWD?g1Ef)=RZfSz?DB3fr(0-Tiwo%_s+u4?so|-`v{6$1-FzfgbHB#)$w{~XKfk3
z<M2<KvsTG})&GGvrEo(tgA0nq44jER1?V~q_3=EImo+s>#tXntn0UeI&*uK}TP`2c
zwu|30@z(2l2P5^*&eo3A5Kp!FYuMX!vwPA?*-kbDwdRt^S24u`$bg37(K?gO9x=^#
z;lqaYt-de`&yRru)wPK<BJ5MEl5vii?*MR=IInjMX3{Qe>6R<i)fCj9Gt7gGq2#It
zK%*>4e`1b_ed{Bhon6ovc2B_iHpSL}rSY#7J0Pl(U`@?**jC3pxg4vjn`Z>{^4mrx
z+Wti(m(H73YPt+NQ%kzTCTrvz`)j@7iY<zZMT1ny;Y$fU_#Z_Xh3(NAQH4c3iIhIe
z+JP-f@Q6lg>|EFC_I$W*S)>Mqdzo083lz5Ntpa#t=6TFL3{&z?^S0gfHfDYPwFKfq
z_a0Q0fkd}=Ck;dNz=iVHC;ALFEMiE@dk-ZL=c2|^`d_BZ4JjHD7MYZf{<Ob*N9(5O
zC}gU%|4m5M@n|D?<D5v^N0%1q1!g3oNP&HcS+0sJ7U(SI71ENFfocI98j!WNU9z9_
zuIXQDi1SP6m06kJNe;&X_p^fbcTBxO^e3d~=(FRCzk<^cT(V?A7^H&PDsjO!gG!|T
zrgOaR5WJ<Q!OR-O76LlzsQSIJzIp?zkn?|Cx}rbO!7!C)AJMz)<vB}3D1s2i{@83=
zuo4SIjU~;KR_ZGrYr2dC3OHpPPgfII=;&DG4R^sUAvOWC{&#%emq^W9n9tC`U<dO-
za#D+P9k-F$NT8s45ne>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%Z3rL<nGA&
z=hL7MsJ$C57A3kOL-Th}*tr70MZ>4FsZ+&AgXr!7Yz}6n=sNjMd<bYqHpDs6T3jD_
zh+JA_)~X%RM|SqmDa+B6brTHkfG`r<#Ge*(qRS^DA%7Ab!3w*1W;i^B2GZ_kdsqnx
zIo1k`y2}HMO!BsI3>++*@<}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|3L7<SoAaH&j37LZ5mt$P>ytq=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$wEv<Ui5zgH%gPp-^9MoohA
zSxX1EG6#7OsqwKTkAo~YnyOIm4IbQd6j4;Tw7A&RN^`GP=_cOIgG!r^vZ*JmjWZIM
zUJ3|{sXK;M6IOx(Fn?5s5X8j)ov?y)?az?N|2g#uhXT7G@fvuR92qIKddb=I?P*V_
zBsTK4-<2rDCf(MM#AZ1!GuffJ-UcrDn>6At`1wgkDH&?k_>gmzNfS#ECK}eD?41n&
zbOVf91^t13X^;ah4EJ?~*<5S)(cHip3iSLyBC|t}HoKU2`f(x9LaHGLoF<K}hIC{*
z$=u3rtAn&1+~$>H=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}<y$2|R$?7@#L)5u>9tX*&fTRuS
zcrt2XWNW7h!clQ9GzG9b#!vA{6f;7;`lPoWNAg2ajGEX#016>s$Q_<=Zt?(F%wM=G
z8+|cezaXw`@p!J`_zFi{Z{tj70%B<Ps>x2d<0XtfvTN%aw4)4$dPNi>cA<(<Dvatb
zW-gtcYOv^KdRu1iQP^{`lK_r4<L8-F3ABTEjbQ%}=sB+{(w;dR^eBZOVsg6;BQ5C*
zzAXfJ1Tw-W(+&Q~n=a$-Mt@F-%BA6yol(9bsx*c%ja3T3->s3l>Qre%P9(N8tAV!E
z_AT0}y<?41%OI!Sbp8?N`C!eTb^f<oLB0C82fQMgP!fi$eXSeau6XGh<HH$pu6^vf
zPcQ5GmZY4g$f&^&j9B4X?p(3nVCRLcu$R?(%l68}aSBx_EWd0)5*eUri>gwoAX%)&
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<hywjiL+
zOT(*;?BsT*w<xRGj#)hsj<4b(zH86AoN{tknzPe);TI7n-<Wd!qg(IdP>}}x+yg12
zt?(U<m^saZ7$XmK?b^ZO^d-_zVEIIBn@I)<Txx4UM$sT80fq~$zh~hRA2WEmHt#p2
zGqPy#3@-NOZwj|G+^;yFCXlOF{H6<#Q5~U2w2n^1EOI*9)AWjE$~wNvE-h(6<LY;&
zo6Z++^Bh$E^8hSD0OpiJsL%nh$!Nl1x2Na@|5VK(0%7sa#}raHXe;>ggG8EM)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<tvPKK?vG3<bQr!jUcjn`3-tJfzlgUi#HruspzGSbF(QEOA%
zx0Z7y5uz$FMkiuF#XJQN-#-_OxisJD8$pq(i2xQ4_3ztga#D9K<0mg`E9U-Qc|#Vi
zRL}Npn#zvFr;}#C?-H;xKqoGZ-K=%kl;}yBClur%1s2rdP+KknV}(KnHAx|dXLE4&
zw?H7dD#INS0}c(v2cj>_(*la3V6^F^*7VDjnS{|-0aAo7n7CJ4`Sx~9<B>BYKYLtq
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<
zxyVc<X4kUnz~|5dgFDJJai4hv+TuQYV<+ZmwxQPL9-~G=m*JCB*Xf58O0~PqeaQ%1
zT=~t%e1$lcbtP44Oo>K@jC-B<J?_<rjaO+B#}L;67(e|2@w#%=?G{NGr<Uu&lq__Z
zJ0wSX_<sD>-PgL?;A^kkzUUq?!7O@|z$SIbP2jSs2e)uvs8fsXO@q*N-uYC_j+D-c
z9(vkG)5V1{u^WUX_+}q|*Fv+&x#6%P<G=Aos$?f!Qz)wc)t++Ux^?qts=vTvBf>M{
zbzVtu1=S`9yiYrkW)}6tWIa`t(!A1^*(L9!Nay#e5x)V2B$w;{z6)d0@^<JRgnzE5
ztIlpfBCmD<CHB8(i-{pi9bB1BQ8+ekHI`;cC{NGDq`Th;(nni_QrUX|#+hgh@%7DM
zHH>22B-77LQlFlEv+RVOrn^6Pf#E^pI2z)VOw;9=a#{wCT-2@MFaW;?FfK+D^WAI+
z6(&thC>R_iXi9l%%rE<rAuJxu!;3i-y+_q=@jQ{J0ECLcXkK-7FnzNtu^JItDr>Z#
zp?zGu+J5l^M2AH2#5}H#_Pca?37vv8{5Bnj3+BL5GaDUm@FN^>8dJ9nl$N56%bG?n
zOcEBo$|v{VqNnv%(v~Pl6<&0?g_sUeRXQsz0xJMRK)k<Z)B^&1g@)Sv&awa0)`wDj
z$VW;ih!C1Ef2n)-f}bdf!8MfzO;3$U9$!lPQ3A09rkiL3O4l!CXz$mDhH9N@V8^Aq
z{ze}D^c|$cSz?-{0kn<SIyC|u%qtYr&!0dudNH+08#D*6B*w5xkqNBumd+hD3pA;-
zTflK%CCNly=w~Y69zxk}=G@W~KB6Q)8b<2`>nbynn$$1*adR*n0yqp-7^KjkYDda@
zYlO^P*z|h=DTFx~jFcxCo}WeQ>qp1P(Try)G>lw^<h-T!K-)>U`Y<Eu-a3eNBJ+7q
zJ&s-m=Nat#YNQHzw(^IF?Fl%~Z}dmTONsUyTj-3JPpWTL-$f;(gJUSQ^cqo-4QvNp
zACr~O7YY1fQ;O%eb|t#<(8u|q$SF5U2e<)JgB1;7#Q1EvuD~2ijS=&Zs^ud^vkq|#
z7P`E!CnZ9=@L{J;<iZl<8N8`@7B199!7>OqR};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_<VpkH>>KRK#zb
z{<}ovoAuV458p=kDg3PD4yCSn@!hhTi_`Xd4KTUNqi%FH1OV;^W-H^Lj>`aDTF)r!
zFCWMeaqbN%9_^$*Nu}DX-vimF>WBRy_t3Vuqd>go%oX8Lx)-;4O46@<l>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!O<h*Cuw;9TBlHet2N0Kk$DdF03
zEv~&N%1S%7;b)DlEIa88keg|!P({JAXRKtsodx04<vihkcWtzWKnV<P=Da`rQKk6X
zMoWE4a7h+r>RA!ALM}`07#~_@ME<S54Dkfo5{B!<m&xa+NZNy?WZrqP;NXH_ub!XR
zF%3uCv^K`|Bc6P;D_ptlu8mD>pb3Se32vcQP&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*-<CW+BQ2iGt<
zz_PO>>{8PNeUCg7F>groU07z45{mMtYHE8_=1<cHoO>WDg`i`E6LnTiE2SuTfvEcg
zTJ6W7QJPU^n#eZEyCtUyk2yVHcwFRCjaZn34^VjYhIRiC6QT<-)e!5^sz!p!S5&ov
zE0$UrsC4jP2$NY?=@qb(#<Wq|F&LC`r6C<P?SfvFPPSKdZTT5YCrxACTa@8`d8>%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-<C*A}WF2ozO_5>9&1LS^L&>5Ag4
zmfX3OMa5>yG5#AU?52;L@l#d6ImJ4IN~}iG^2VV+vNl8vPAahQo9QC#lVTayG?2vX
z6W?j_(ut@aV$x3{*yFXH^4Qc|()gm=Zm<A--l!Uh(mlO`*h{e=K_Kk1mV3FRdcA2g
zOyXYcxoVQKos$(eQcT3%AVCLt&jq03?>2MT`05v5Fm4}EIzHmRH_?yBfJy=btrxH(
zze@ZsKULdX+?8YYzF*ETEtnKJ2#juLg?fAizb6}4cob*$zjPcu{cKKjbNT>F%-TnS
z?;13CFZb@@!%|K-E^!!e$!Vn3xq(HHAH<hN+F{=6=3|I(6^2i&H>2SWBKm<KLuyC<
zOaxTjTh7%w>*6^9dn-ALPQj~~G(-~wPoC>T+`JF#Ot7WA07P8GRFR9wlC@)O&ZBb>
z9u<D^s8Yt-I17b3o(UO#K>|xAcVjG6K_b6Yq^a?W6nrB|4(nVDDc_I`O+vwyrqqZN
zD!(Slv6zzdUtv0kPeM2^H+0y*;{HpM1-3DE&@2RSCO{;zM)uLci<i^hb>Qd`zVpoh
zN&RG$%{4G68&YddK#DBW5YeHbBc@KJNagqKZ+k`0(dA<@q(%J(^!l;hp!Qf9ypyNd
z%|^wjBVieAFc6=x9dEzbG`qe`$*#jytBH*cVlb9hR<Hrk90l{LNB-RYv-5EeeixSN
zr93TS<0FVpwSq(+WHWf<Gg~70pKNC76)}!u8=3fjnehNt1b<GZvRSah_9X<m!7#&G
zqd!=!=wiiisAa&W$mHM3`*x?d$JN^g(Y9U)Zjqh<lv5+rj5;=pggX8u6s(_gPMs23
z$o92$DY;C57fR2_C<Q>&!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<kPChLQ+88OgbFKOt#=#6<SU&?k-wiuTfW_OCjF9p1*K=Mgl(13ccH#<2
zQ|OA@fIn+?p0LvII>!1zu7n%+6STRfiO*2p2BQpu2vLWdsx00*c!Jlsac6@f{S$^9
zre-pE($D>itcSs!=1k*KTuO=W3Ra&+iI&&h@G<C5is=f@W>m-1suAzvj$tsn>Ml05
zfKN<_&CO0{1zc)40&lP;NK!l>&)p$*b?E#ofQOVP@XPp$)op$NCBPE%z?_gsHjtFK
zkcm}7k>qi==lm<nX|<eWZjK<?L~e&coVVRh!}V$#;0l7a2?cpb?OgQtsqd=-8dG#o
zHY@;`R`6cxnJmer3vz(i#gt~u8aAydF9_2%OyP}``Y1v?AVRFOM{$X@gFn=5%Rk<J
zMX*Lcn6F_R%h-_5QsS~VA~IUWMwoadc7U*DDwk@0<rI6!D~|qGR31Agw<gc~QHNEX
zJx6t#w+CKH?dz1oVB_4@OTSJel<up%zAiWB%>nX7fKmtflM1v?d;;SyRa3}D6m!zM
z+Je&1C#A{U*)l|<BK1=G0>|s}q<T$kM4pNekglzp*6|Q*(r<QYeEg0)DJWK|@=vRf
zXcB$;A8&L|TTEo=$f7Y)T9fx!kEPybNKg6UsxC?yP~x08v+V`Qg|xxV=pH87(I3Fs
z>V@^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$V2w<q2b43DCMbcU`5SmzU?`mA8eJc0`E0CgRMwW-vCJAnLwj`r>P;$_{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`<q^{aGjUw;?%(Z$7GY~KZ4Z_ZUqR^5L63iVb5gBCZcVl)*_OzP5
z3C^lUeNFaK#OrwEMW30O@Z>q2`G&29DT25<w6E;&sLb&*<@P-T?M?8r&RgPzw8PQU
zrUVgi6Tt+%5$X=g$rBU)scwqi$vL4dLY0y|W+sAx{d*2OR0zKTx2;RDN7RZXGqx90
zCRh?TTt3SE+Gpb3<d>{)YS*=}(}9E_>{~3mXY#P?;t?LR^p477dv$33RdWRT5G?IY
zV2rmokZIx7P0*iDXz7jhh{6%jdtz{BjBr2)?93qxl@o9(F<Qf1ju$T|P#WzTXO)IA
z$)*5{w)OS7)jP$^l+e~X&$mf>`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>r2L<f@*x{f0g{(&Ttw4~
zBMi>Kb$EzgH1+~{$+K-Ob;;5#S>dPpyKZ+=2Ub*ZhZXm81kaW;8F`kt#{EYpt0IZT
z>s~<QweM)!{OB@L%~x1QUEB~G@Wc4mjHTBP@a$@zt2Y@8A8Jfy{lZQ?G+|awhyT9;
zj?#)ybhjN<&d4u6zT-$#!Hu&o9x3X01=zR<J_e~0S>*yNM(gbpuit7%BNyG$PHy?r
zOX%%pPXoq+Ygp#av~vfm8v9&@^y4;ic7hc7*KVZ?Xje=uHI<qu=T?0vT-bgJFD7V$
z8?VHBeb~}eV=xZ7AllEu!3WhT)bF0th5R>cLBc+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$){Qr<?^BkncyeJT*)yWxYMMt5SN;HoVv5DX)(mTS998Ha
z9f39KuLEOMSgoCiQmq`i*wAe{xY{75Q$ax=av5pH9#BzuD^K3=wc;@uAq1JapfZ&A
zTN9hLi?-o%PV<j^Q`1ABD8XqMvG9#ofSQi7UdP*(I+f2u`-x?Oz%%3<H-7xG@0N7C
z$Xn{MR)!A|>6of{sDQ%A0tUi#!|d*pg_k#k9BJRAv`#0a%c}jl{#RD@sqDz!BO1SK
zpIWbyyRb>I<E2@&U;n-e;wo(J-(e&I`F5`dk@EC=(N`TyX_`pQxC;XGlbW4S|9o6y
z?x~~*$U$n&AYU@m@9`&;3!V!G*w2B{P96TC!wW?r!LG1FN~W-ItD}7_chV%0$~+@L
zRxKN^%#sEM8)DYA7SHMz5YodbwB@_Om?2QV)^iUi+;t);h4Emjzim^d5D8|Ec=JpU
zXQNw#kQGtvu5K{k=Q5iQXX^a95lju)5H0!{q_=zM=I~5@RTH^T>gJ7k(jS%Mmnjsi
zdg;G&-{rI+f_rXMVVX5V_0cIXY3}iI9Jzf=owD0&i5YHe?&;fa;He7?pHT#LuCE<?
z3h{a^W`dn?vDz3Lp5X?{ozLUs%{g*4mVlOkojBNTTpQ_;dgwcKcGxKX#2q8XtDiVS
zQfHloK2A@U7gkq{gUOW*tF%J~jBwBXmR0w{AmT$p#0jodfQOVX(jVP$gaQyFD8f)u
zjDmi%+9b<NepXW&gZ_?#VEC`(Bho$8eK4hH*V5u*89}V#L>#ogL3VSIUqTiwVB54~
z38<{mYe9pATp30~dNU<a#2gc1M0HP(x(Nrd&LN;_2(hA~k@CAY?Dnhhmyw4VT%X<Q
ztM?`lP*yq5TYUHE#KP%u<FR8!+)2}!{ZOnxI^pD9(NRFvvdNn_X;?$5#xHpigHuF-
z>-}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>*^<NO~)Vh@?OM@X+Qn
zD2@+qM4&{d=0*@V4NiMHxGMN53PaiMk?!SY*}(IBdC~T0@d)x;GidfP5aP>XdBKSx
z*xHO8Xtrut5(4!ZXto?gC<m#<%H_&4t{sLIQwaW?DW@kc6Oi+{y$3AZq+e&qyo7Yt
zsCc)6cw1tI=S)&RCuKl=TS;AjK056WA}SztzT>OAexm4B-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<I4*er=2zo7jk4Xufj-x;E#ISdrFYG(4$_u`IT_^2dFmlFWX^J>%<{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)gqf<aBsdWFZ=wK;yNGP7*wthsZ8
zxjne0O)_!iRDdd^%l*(P*@5~9=XAqsB+QD0@(U&wv5%R{SQXBmW`MH2-%+oFeYI-@
zCqn_R#Mqw~Ob1;soQxdnn2CG2&B8j1x~EsbeqJc?vr?UX%_gMc>3W$WMNT{EQ9VUi
zh5m8&jU5WvcO81udIm4OeB^=`j6%K%W8IEfdobNNu3a|NvB3VfE!#<VK>2vkC+%5j
zUb~N*tk-I%JGbiJ7$E3EO%JggOxp`KR8tB5EE$JV;!?<f@{atKk@25#dd}$8VN?N4
zNy7VBX2m++RlsOduA<&%0sgUZ7C?@W8U}F9R+^C?1KelJ>y=t)j9AB4aKK9wC}YKI
z@}?E!;zq3G4^RQW==x%3l0m<(Q{R(NMG?I*A2SKC!g^9BgtBSF1N88aMn8uMu2@ru
zoq4!dEP3DC#wrhhGDvejR+dO_<rjH1KhJ@6#W*!H31WTvDEyX1s6@|KJQhZ@?fsMY
zjYyYmVj%f_<P*a*&UYR>%@V-70s#s$Yc*)Pg;$j=6Kf<4btY&p2Km<q7h2HoldY9e
zK2yvgGBapyK5oMj$ayVO;$VUz=WzV#)@1K!a1n40I$ZbsIJ`%$ol)bF&sjav&9GLY
zFej)D?M|6vzdSo1BF94)bgL>;!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=ZJ<Uvub9QwC1)`_+pgz%4cnc90+1JfSLyjUe~=1
zF4T!8iF%Pj7GcLX+$<Oe@lk99<Zfc|W`h^$gXG;e-tN6ReOcoE$H3adX1Ok2f?9~A
z`lOa^{OveOZ%-@L6$c6&`$bXObE0_|;2RHVydt6|K$DfT{oe(lri9p&-e`2sL6MWN
zQ4*#={o5=lydv`Oq@@pScBOqr0({rd3?1@X`Mbd?yXx$^oZQ7S$DVBbMR@0sdiUD&
zm#h+>z$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&<N1S?xx<_O#>UA+@{K9-G{t1NiltpuA}g&jUL>`xdIN;71To2)1S`DjVZ|puh?a
z#i;<3AW?eb^0D@QB7oF!!CHoe&LmDvR<wxX2VsawG9}vW0nh{JP$n0gOpqWss4OF*
z@V7!f+^X9|W%(n<#Yuf}7T~+`Mddn!>JB2pT7&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{<gjRm+S${U5<$HHRlPwHbwU39>%FlkJ{v4W
ztxhhd#gVQr2|Gp|>9Yd)*Xd_%M~Gf<Ux6%nm@dz|jmM3MLlUc7)hQ7PWQu0M(I|>f
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&beh9Vv<SmiU}N%imOPq&!R
zV*trkowVpBx=uHQ1;VZvQ0>wS$>c3e)~$=@Wzd#_+8@!<y@*^KA)z|43}W3LbD{H&
z#Cs1Y8+r7W2_Wi%pwv=c*#&YHVYBZkJ^uw(IgPAg8gk#y^w07gn2(r%aD9BPjNn$2
z>L4X0orEm+8+W*sg)v-(b!~@HQk)_bJ+4Hcskn%F8ousbXUjW<<lI~aGqlErDd}s6
zV*K#fEpSi%0yq{=$z4L}Q|V2{DIi7IlY4%0O;7FH08nzL0vDMFLJLUDJO~EQun?JR
z-h}q;%Y!iu^=s;+dgtULWnBD6om6r*nqL;Rqv$5GXt#&ABxcGr0d5yWuWmpn(CnBm
zdpTR^8P#}$jYiXCR;L!HN0ot>yVc9hvB$n0gwCJrT%kXby@b~B(r}v*ua1iOL()JI
z<n}F-p3-kQV6DX)FsUDJl;$gHjNsqVmC_iJ0JzZ!-RPaRp}{m+lZ&Mpq5~1NsPKp=
z9`uDf;{-l1*k#`gs`8wZI1=C>XfbBTaNDlt-tRf1I2l9Xe$}KQz)B&s8HWkFZ}{F~
zQy!59B(s-{50R1|m;S<~42l;8#5@@g5nV1LgIP405C|2Pt&Dq^anzt-B+(3Nula<f
z*20vN;587}=2o>Ga6mygYBi><C=L)-_2p++a(>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<h*H*qe5Weot&o(Ynt5C_n(4(Kzxhz->@Ai5I;d7VlfrQI37v1JpL_H
z$f(MJMtSKn%Bkk5s<obe7qcv&%qX>*bTNkcZ;C{f3VR;uChT*hO_KD$nHQ?NK4lX5
z@VO#!U9+L-`*$2AZ!V3BZnHordmCQ7Hw?<?$nx&M3e&Jpuz|D`Y#T6Ed-o86r}bsH
zn`PX8fyS86E~4MKE@u*~P_=G>+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%mg<qc&}32d)x>Jn}M_~+&({Ea3{A9+U*Rjf7?Lx
zLK+wJnIxc<qtC%Ud=B8F|B~jOLcU5;x)^2qDx1;Afvw_|Q}$&>;#a0Y80~4t;XB&Z
zyKLV4xh~+F#e(|R=q<fp>+A1}ta^x-NtjfXIwR12=m~fOSP|!E*3!RhoEG{?oJX<A
zDp)o2h1vE8OP98UR#-ycEw>8P0ksC|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;RP<YFVhz5yJhHC03`N3ue{mO_O-ofJO-j5j%oubB^kuaoVu#efr~a
zC9Qjv5u$Vv!c{d?qm6rC8OC|o)#Yzdm^KHbdzq2^IW;#L6i>HL<`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<!&_ULQ6P_)~sDt{|2W*$cFz@(gD9oD4<2GTZ`dO
zw;2=V9Ud_b^LD|F5=8WE25-;7;+(Yu-qB;TL)p|U06J_P+sH*sf0e$%<x^86@2GJm
zLKS$#Kd2qf=n<}JFXRs#Cg?6D1^x{!X<UZ?Wp(hpgJM$%PnTc`4_9+bcbEl#C~-0x
z=c#IbNBdj?r6L<F3PCGsTC}lD5$wtRo=_C|h-Uv!M6Fy+8o2(W3`a6lR~Z%33NEvH
z=crYR1g5h_Xo6T*$(73NI7}zWVXGTZ%OnfZ>##khF7A30gd#TPDzQt2n~nXUPv*dM
zlif)532Qu<k+>$xO_E=b|E`)4)N6S<Y&KI__gbHxmJo{KrE+5N2}RHfYv>EHOM<&)
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<QT1T;BXN`@Yl6g@OucrlJq>|0H0M^XvG|4J8vR<XlGvHtp_u3EYrdQ24k9Rjcm>
zN5-R}M0VrgY;nU>DGu1hHX_HtRe6I64iWkWS(iWZnNqxND$><8n<7;r<MvJ~`~D+S
z5O$?BL<JD(B5n0?=()J-=xFS<oOrP}Xv%EU2zU)1xss{Vj3&-I=Qqx?6W&}^iMK01
zfN0<14Pmw4xGsO7;b`TI<J~DAd*BI$LXfsW%<{fQ#U3%p<8T57dmXg8+t7OjrVhYe
zw6uS0Z*`CbhvaGdv~?bw4EUD2zLD`>>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&<E<+J0QwIjfu4qTY*KO79MVb1e&geH>mQT_N@G^uwc27Q9s
zQ;03FDEMV=&LG#C(o{s&&aDAsjc92ju1h<IV|;m?yEQKh@{ihN0@}%Kz%#?Esb~?q
z^pO2tFL84X4wymWK1>$>Dr1cdWHE&ks2_JtJy;f~TWe-V4QPwV8G$eQ&#1poRQeDa
zSktg&LYALXL84@~z)6x=vI%0LQs}O$C>f)fHwSQdi!&~q<rf3jNs6v9mWa}>RXlD9
zKn)C!6MpuuR}vkMB{CAGcTFP!AzlL$B@;t-s6?W57vz1y$OvpA#vX!<Hn&8;Ox<}6
zT>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)q<e!forWUw5XX5R+pfCulDz;N`swKM=x
z5o;ww-`Q^DPZRLQ=r|RLjm4RzTz;xDb)q8g*V2Ms>r{-{rM@8b+7iA6qzCRVcGkF}
zSys}s<|?_K81;iJQm1lMzrYj93$AKdt;xVNwIia3HcS0=pIgvf>7fbakl=bZ87zdq
z;3q}Z?o#(jij}cc11+nq<XRS28Y<iQSJvM=tpDKI(u(qLA)zK<`?MGvW{RT{AS6iH
z9=L>^jM7@!06J7Co_JoJbX!+TF=!xKgFJKzY8><kf|MLkI5g%96nFzY=^k6pHCRHH
zie^nPRw?Cc3C7t9-w4J2(xl0|w1aK6{PHfSqU}nQpo?W)<<P}6RYYwaK>)?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}5M<EUXnq1dKS{ZEqivPWuTX5eO!5CMsJK>9WCVRN{x~gN$61
zX!|QNS0f!CXnAzt0|)WU<LTOv{)y{Hfe3ekFR;%A^&-2*v1t~*hmD&&I5a%{v@)Le
z^PD)>5-Es8MM>S#kaLG4JB(J*GDOx=MvmV19aVV9i1E`N31x`8!V3rZG3lqFa3J+T
z_j=!{yedc<PLK(Z#CLxUL&+Cxsy0q+4Ca8^$8KxIX02L-kJZ)NDKVJsoL5o7_ba{p
zxliq#9Xderp#8Nto2|st_L``9iLOlJ=;C9x<HAUjd>7ja-VAAahU<*h+l!S8|J;;J
zR}9yYx7Yh`yB<bB06^~!W56xXTVnQZV8ZQ7<y&HNS4DH+3FS8n=|Ct<8&@k^=8$NO
zym(wnM%IT3^r^LlDeZdG`8r>`Glsi)`g9t6X~a-4)AmUHyKuV9f3cQXGi4IpMj!oO
z<E`4D1?U0Q`?vhmGPv@p)GC$d()9%?11~Dx*;=_&P^EYtQ^qZ#xho*|aN9|u+9z_t
ztSwKV^ge+X9{t-M&)jRZoQ__UyTZ9$>p3t2<r*YNP0LtM%Ct<l7fTGkXT%T_dCPz+
z-N5mO?Ep%?Ci-nZzV*{19<sxNXm56NH%nyHBhiT2K{o)29jM<9)=0_Yf%4Ed=kMh1
z*};L5>Y>&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<Z@
zLyww4R%QR}v$z(OD3Sfc_rO~DjK9CC{0ztUl;QQ6Xv{X{U>=D|$--#pfeH{)qH=@u
zozIg7?qp`6LGe+@JW31YwGY^AvB3jhI_L9Z3bN#~)kz%&1bNU}tvAV-2g^~tCUQM2
z0eZ9l;OWzrrDMN<VHgo`qn|g#zcLb0aynhB+H!7kj&}Ln9MZt!7>jhGU11JE9VdVk
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<<d>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^bVHzbn<XfpyDBxS=L_83yMzDx+nqizU%j)EvmdH^asm}KG^
z&?TT%P7@HMUON5gv5%;@-50Tx1403PMEUau;$@kiYd%Gzz<R`e+~yfqM^C596f6q2
zVlp~6kGMLX2UfGWc_tX68XGuYO~6qjcIvV2Xll`qjD?$0xupsL%?mndeM!_<^Q;ac
z1vMc0n+XYk=f)D?qY4a*8ZMq3=(W8`E{@TUDy-g_D^q(?l-VAMRRWs`M~3v3DV6@_
zLr$%9M@2Git;LoWbC|!%<nohWH=bRy`aVqiX5;?g-t++<1q^8$@J_Z`9yBErT8VZ(
zuJbeFih9L8D0GsFfAVN7%?0?N)&9q9`!ArapKjHtxix(cixIYID?KpF23Sg;KzK&e
zqfiHyRO3a9A<W&Rk)QQ{=<%(e->0(}_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<uUjA!Uax*+cdKy^(Y&Kxq+(qH6qLb|>`(?=x?~V;5Amc-V>S(;
z*BTOR*|~-i7!a_C@CZQ8<b%`+9qEpT$}9RSRGw^dbxM@QOaOQK$nP`muoeyxw81rt
zf6(wO-u336NB-3xi2qxm?L^ui;ILLQBedLfRWD;&eQ2zAm;0#@(J-X|@`ItZGlSqD
zNF-=T!_eSmtITsUp_0PJ6T6Lk3Q%ggxTTNjuD|yGN-7&*U2m=nQpZmXDpp@22mUB!
z@yLXKe9wJ71wMxdKoZ)NjjaKPVDd@5P(;H#!IxgLaIvP~!yN%u@x4Q2azBzI{#un}
zM5Wo*{;%-Jb+iiM0HzoJAJuztwVIjt_xYoy*)7=iRElTs5f53Kyfn6^!y_EN;<is3
zgbG8aAd&{{06a0D#Rnw)Nw?tGv8+xL(Z-~{M}-efob8f6qm8ljyb!OVFwL=@3-^%Y
zq-xOqYGwBzqc1z8M|I`5B6r18ra67e62HlEd0AP)LR4?7cW1p&o}ReOIc!tCkSaUn
zkjI=qf^5YGhcTpy1Q90%KayO%U}|*6AWa0jHrcE9VwZUXz4uSurxVvJif<BdA1<7G
z)tmjGF7Kbbe7x!o=vF~+mwGr|g>60Mq9v?efoT~#TZ9euHlN`D2?tEEKVbvFMzo~M
zdWC>=;Bjr*pru-`_L9~?qKs2`>7Ms!wnNy%mPti|7P=7S(YL*r=_7MvX0#yyc6=AB
z{`oYoq<SR^jP^zD6ya~Dr&{T|Y>DWPn5b4QwnSNmvxig7Jlew>k~p}~{;?mVWxRXv
zkN$1LvgseXnGix}T{@lkR^3Pa6#i%3{m-P<qKsSA;W^z`8FaHImh!{k-upBC>!<~@
z2nEUt7uVrl59rGeRg4HWZA~gIZwZZ?fP=Ld<D-vcQMKPFYw)PhBrNvo4DB>#@SfQ?
zG=~-WEaxG><xL5et~p~E!+9A{09kelDCd{#?7e~{yS@jfices)l;f5AUqeWgTEJ*4
zB=v^a4=zIX>M+G%QV2-l>Q`0WncgJypcTz$X6e8`pjPBdLYGbv{EAQsy@&Vnm!jz!
zW_zt>IN8f1eOe)&bw45@t`kLKtQ{X^`vd;=AC2%iuqtp2HP<KfX|9f-s7k}>@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!YJhNEFRAcOn<mk29xv2I0@Q3ZaGyl?i_r9}McS10%Dz
zqf{4iLaqotH=F-h!&InRg#JD%Sh7@q%0Prh+FH+i7|?`{b_sNBsxJ2rT`r_7;IQxu
zX;_7k>TWtS?gUKWbZ?ED7Nwj)JJeZ-YevgkjJI2pao0A<2+#D(#ee^wpo9=!9J7=+
ze206bxwnv7Vs5t#6UY{2KXz!{)iPiL4eKd9a@<z)e)B?4YTQ8)rzF$)f6CF;ia+;-
zwY|9vl7*<-?)!$!U^~Ltr*y}>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&Wq8<Ps8bOUZ)(&HG*I*t%CFZIRE=B
zr2y?JuG3P3Y$ic2pwK5{=^=kV6?S2gBZMx^mDoHDOmGI7qx7L1vJU1%Qjga!%i^Wb
z;^RY@!4$aHC0z-Q!s$~y^sQHaz4b9058oN<X@=^Ae{UYua)0&W1#GI{byx(AJvZdO
zJ@FthWdx!D>TBA_8~*1Vt+_UvF|S4?fBuVF_SGjXn>$GH2c9Ji9@rU+IZw84aN-<>
z0G#qHL0?REISl?*9bOxE^gZOv=VNzeR<zTL+jqSiP+8Qfw3_gI<Z5z|xbGBx{Y;QB
zi3VX4eB}K+GHBcJBe!>EISWaBlD<S9Cj#setB8I$n@pMH&F@McfOjUziIwfU5fYqq
z$<3wyN2)eno9PdSv5Qk(O%m7?1yj0L_l8ntZDcr{^Oevht2du$P9bGZVu9cD89k4O
zgM75OJ83ZXZ9GM`ey>Ms2l0-BN_5=*fs2UfYR(w7-C9#IK9AMhl)%^xIAe`Lu*8K1
z&$Tt?dc8uWw03u@A4FQXuIv~L+ntjyMPs1v$RvL1t-CO2nhL(XnMeT#1#L<B#zHE}
zL1hoF_P6}#M7y7<{-hbZXd(j;Oa{;*l#ul9B(?Nt`(b8n_;A)qhqeaqeB+p6y4abZ
zW$RM60c=gX@<v!QI{+dPMUAv>jx7`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=3G3lK<jJfmxr|v$7m_$bASGgXOc>DUm$PgZU-Qt
zFnbmjr7t}+)y@BcMEfUZ!8yldQ1%=-{!sq=o-OGiE)7rIU7^tLkG@y4x?f~EH!0^_
zxc{_?U~RJYrq)Wh(w28JVH`FgAz<N)?@M;`_87cVh*AOVR1nWDTQ6v$uhozJE3^GW
zXbz9_{vb&uK%Vhg+Lf_dajfNvVo#cR5z<bc>Wau&9-C&1DY^?)t@$c~-|}TN^}qv@
zSHjrBXp<m;C*uG73R%8y;sT7P_0iV<@|bl1)%o&_pdM3V&7jM<Xb5#k4d5hzX-RW6
zLATR3_p(AyamB_n&DUF8hN0W(f>9r>B@FPs8-&f`5SC?zW5<MRqflsoK`)Ow)ZYn`
zCm9N6^-WG5v6TsGd&cp@w9J0X$LU1mU8k4dw~GzB1m7;uZe9F?mDa{c9cm7bpt`HE
zk$nnwhdmWiJ0*~HpvIte-2x%H3O_eCzj1h52O>75b8Xn1Il$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=TNVvWB<c(D?Y(6ldtYZ=GRwK|}rBndG@
zS4k&aY5&<hQ6y4Z`3fw3w-j}^x+aU3LSn2VJ1!{?vK3x82C(2ioH)yHzr9TV#%PkV
z{^46{k7t6v;^1c@DU@@J@<V@pK;EU0syB$&xe4OV>uD;Nbd(8%jq1zz^ix|)=s*s$
z05q`~8oXJxs)p^Y-z_YhX(Q}WTxU?E)x8<!b<|o<A=E_{wW~*(OKmxIZa9HTPvd;X
zz7absjr;(TA_+&>W`(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*N<q;sj_OQEHdsQ
zZ5Ek@-Kqg0RpQ@2gF2!hALZ87@3j|VH*B_lLaRvDDRs7ytzL3bK;Iz}nxsV&!2?z)
z4FBAhif@G0ltskFu;scOe>f?>e06Jx*Jb2Ixd5}jXEFGGUDw~Sf94_$XFDQ1XAIhJ
ziRv<V%&<G?80>SVPvv_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!jd<BC#OKGf$7G4&pt8b}i64rw<dw>mDhVg~R
z7B>M!yBsdapio1zzWjAownDYx`S+4L#RRJPt<aqdz*(r2?^bP^8xi$n<!e$XP}hYz
z;tMqoo7?6dJAD(ohA}4d)ZCEj&=t-qD#QrFYZUOi_x^^U0=iFmkxU)l*)z0rzKgAg
z;LuzGHoIf-dgp^298*|5CM!aFaP=+|BHC+5*63pl*yJ8htGWhp7?UbA2r)kKs3CoD
z=%huyYicTnjUd|5p{y75K(OD0dbn}g4I-X?Xw{#;L2z<y7u*8h2F;`GU>1GVRlwv^
zBx`;h2<YjINN?ge{Wm^r$U-Y}_8Fa*3S3`oZa|WpKxDI-SeI_)32;H2&orY?s%J@o
zK1u*RK*GNmbw!F>8(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)$((hW<d^sIbXMFj9w56rF4pUF2X^y!%>Z~h7yw{jQ;o>Ue8M#rs+oS|
zKn*1#qL(!ZqAWh<Rq<~b_w^ZDAEy^BJw9+YK}&5z1=pC<PwAH2>?sNE7<Jd1^U`lU
zn+6tdXrdA-$i2UD+V2!iQK(h##j>-`B5Wi_Ws|YEYII8Z1A}ft!AoYG-gIRGg!?+5
zj4WiVe?}U*IZeLmX?}~`l(d+~AX2TK8~!GH*z~hs?BP?JGxpQHW=KuqAb0X<=F#`F
z2n<QR-Z8G+6K4Ltq*X#{MTt3?IWt?*-Z-=S22KH^t0e;8qGaE(^VBK0ju+L`rywWj
zNbY&1pxl#H(ts#B+fTv#jK~-a+>-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(UEQzY<zK1Paw9p$BRT#F721zu=;cV*w2C~&=JL1DK!I+ui
z!cSCy;rGytp3bl+;6Yo8&kqPSnV8MeZY`x3*{xjlAg~O~X|0HiSj3Yl2jFaN<iaPE
ze$_vu5m)-z2>YC054o@mKEIJLS`1mh&-IJ}2nV3LNfOVC+t0xPNAdaef8uZfasE87
z6{Fa<vaXW%M4cIK?%DWJ=dxJ^qPTJJ0C)AK?jCsx?TaZDPO1eq9tObdPx>_H*UAe;
zobA0*xkjO=PwXRa|N82a)2uZjtfDEh24>WwDXr>*&uGr3^O2F2v@<X7o1vfYEY9f2
zuadXkl%}ML)Fe=k0D3J_@2?N$B*6k(>|${?%ojW7GdZyy>7U-M0il+0tt7D=DezD=
z%$r?!4aeO$uD@^WqPwlgOKCHWTzw@pU%9~rUzj#S?X@pMk<Ri6QUO95*&65DB&^D;
z!<eb6?!Z^hEG^CM^rHA-v%8Sbtcc%3pxX*~A8#K_NVXTXHb+@)x#v)ri>?5?^{zx!
z?qk(h7+I*7_&zLBFXT$wA0x4+0vjXE_{f>zqI<UNzN@$XOIupWpwk@TiW40av*{>Z
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!=vHT<vzNW>fZq1N4?P&hkWCfc0xy_C4F_JhA
zI3P-o^k{sx=fS<PgAcQ$Dhc7>Js+T9W{L}!c8GA>Z}J)Il>qQR$n_2-j&T{5mH}i)
z)^X?~f)6L{Z~)46$>}L@406mbF(cG+jfU<g(7?jZbnwj=o+A~DC6S=_^tP4xbcE^B
z^!ILEy_|9o;{rcdcI|V{)=Cr>%>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@OcQbz<iKZ
z!ziFY96$=(nsDJ<&EBS%LBi4IN<~hs+7@l)*Bq2nBBhD0y*(V9K#Dq!(U0;je2RKj
zE2o-b$;dx>h+f66&p`-Icvr2Y>L__07S=D*2<X^w8JM;`%-Sj@M_HSKEFNq`Aq)U;
zV(-&VzZ)t@ova<Zcg5i~MfyMGBf?QA0XOj9cS{#&ztd}(*=5MFaZIS1JJ0hz=V*SS
z?{x8!cJyt3zo@|zB^o4KJ#=<B{XtOIrWOPu5kg4Hil1GV^0j)onSeJ=AjKN_-nq(^
z;)Xxf5?)W+NmP40iLAjz@%<MJL9Ip`pOxm7XynhZ`NPpdoFF%UENUVuPECnb=vXlH
zlhmQy0W=aCy0XoOul|OROC(uTo1xfR?;}Cyr8HBwQ;~~_q(l1PQp^EeQ!O&`vNK@t
z|FgWshcUYXEB4)!$uCObXwZ%hD{mtVn{00-4ipA|_D@AY8YcQ)m`O~PMBn&%Ro4PT
zgu_q!qj&FSH(sj4=uLt>4I`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!<TyG^}|O=eoY
z74}#3o^jy4@s||Cr1&5Bj}#`!XjVd8F6!uLKBsZ2o9ebUwC%mYup*gymc2Kx_4lsZ
zGnA@#RNd{%_NMY2O2=-Bp1f^tn<{`xz++5(wk3cZid%plF*?UsyD~s$c`!U3{d4OE
zCh6^0Z9t!`J?jkG)<;b9aq1h$u72mz_v~dapJ1Q#H$T}J)hDF;qL{dkm8`*LL5sYB
z`8&S1W^R8mh!cp6Ym##W0lZj}BShq&=~nZDd>=#uI_4tQJDRY3^9#fzXz0`-Qh1Y#
zE<Xi+$m^EevAa@|G1co7Gk1~5ja(-ZKEYa;+L*!0xe1I9jWQfB`1-{hMR%%RTQ;J^
zflg(g=ZRF>#qse?ifeIA0h!M&0dvU?=Q<emW0KdY5N@UpZF5gSL2T_}OPnaMPqiXg
zyB#?x^#%~0$7%Cr`!v*$T#O@66yfPP{AfS3bh;s3*ta_^M{BBWR$n;Nt@+o{%Ul3&
z8dW-E)%s;SO$>?Fk*AwHym9j!o0Hbu(l^=9YY!xz@#Nk23JXq)FCIi{Vx3mu*J9_M
zqt5DfBCC53!|qJbPh@!c`hSVWcQHF(@vSCxm}MdXP<v6@8oc`mPQ@lwBpC0K2g*S%
z{ut4z3%QFHqo!e2K@W$Ecf*t|Ep?d*BP|D`pm&~C+R*U&)E3Oa=&&tQIg3}bweG_<
z_wQ&%y+GSq?z)V0t?tccFHt!l$D~X9Mdp`u#{E;K8q80^A1?wuQ6Ycv>HBe#;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{<O04F=$X{1HsNY_`!V2S{QG>bW?(CoK=dw#OZnYTUy)DZk+%6U`Kl&
zB2Fa3{dP=2v@~5AB7SUtO89nP%B-+i{OlpW<m~3yj*t1nkn^KeKV=AP8GQ_BBeV`^
zV%1~+TY+F?B{*wC!-mB?(3j18flc_Cw!;{IZ!#L_xP=RIH0+agqlTZmb0LC&psDVM
z#vV>5RtSc20(JNJ3(#Ks9`{nshD6ZQC~Wfv>-=!9h!>UjWfU)O5;l}q#zUrN?5)9{
z4=}{~B~Za|;7%JcWjm@F-7uI($G;|$1xSwyU|Q}Bys<Go>{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^0<Cd69YqZcmvv
zB()S$9_t~fzkRTzKzs%t&}0VQzL@zNYtJR223lc_Lk&3p<^u&uo^Z)@1g>v&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
z<HCDb)m2$mrMB<SLgT<6=XD$4Q{?PO8IZEa9CI{fF_*-LQv7|9=HjL3zpkaB)l?nt
zV@W1mB{EJYI_ttp_5wGxYB8rB3qFA=-GS@nDvzIgjTO68xuxeWD?jsbVA(x|$HiZC
zsPidxYJ2q~i*_Z!qp;lZ<8*%zCnx9($}uCU)<Ueh|8X<!av)n*^6uvCJ!Q$F0Lp0z
zD8;~bQNQ-sUp{LwP9-5eda;hD2p(N}HNj_iUT?E*CHac{VeJ@dz{?X)U;V~u%$BN*
zD!1WmoZO3}zaz83TTdJ$<1IF88Ju}hH$8tzo2&XCy*_^I*La-F1+Y_B1A-5v7EgSb
zZ!oV;=wlHhi7}s|MZbV%7iFO{XbL@2z|SJgO$kI#yYRRp_qRP!TA^LuJw85s*-%_x
z_Y+ouA8;vDf$sMHxyAzZ<(m~!L;NKbsX$y`ZK>A}?NF2@wwJ<xhf!^tWxpwQ$4)9+
zlK(kYi_#L;d)&4<UVEj0prz0W8OuzZIurUMg?|tj7T|%HyPP&TI&!)L)4H%GtpotQ
zqzUOaC5QDACcs4bDS2M=@y?@O)ZrcYZkj;Gt()B)VRmUKbWV)BC*L3Um-pPv$)e(~
zE3x;>wJBH>64ZNs#Rs;^Rsi3_mR};Ii@@5-&M2oe;<eJy^XQpux}=b)CJ&=kM=af8
z>$&sZVBu9v$T-5SYgeKH<iM}N*}Pi)Hs>PtaVYM7`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_qD<V)wBDAe0JqHP>0521J{#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@`s<Vjv
z|M6aw?e#)N;Tb@2!}K<%rZhk$uqdT94mW(~+RU^LCed1>c$zADxi$h1W@Q<Lr#jE5
z$GmUH{RJMivoK7!=y$-g{1_s~X8Fx!{2~;Wg214bJ)qi5pfP^B+BCH+GJw2d79dpQ
zudPP^xxah#jj13tN)gQYsasMo<sc0;oIkJ%iWEkVIMNi_M7&KtvoE5NEuz-@()raH
z-d_mX^hY%#7yUX9l|2hUBxgN`$>fQx=eVNQx1mlGs*m_!2|`!refBgV<Nwhf?WblQ
zx1+DPLwsUnfDEgTAE|UrEwW}Yd-KbZf;5V$7~&a4G^YGYPr#gBN8&g{Fmu$$Q>Wfd
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>2M<?Gn4&zWm<B>s>O6+)OL~$hbETh8{+jvo0B4y=~9cafUWUV>?wR4
zq}hD1us_r?P-ug!*~RC=Vv@1I?H~L^=(f2^`+?9Ku4``Xd<Zl06s=j`!Q`h+*&WiW
z3l_nbL+hB*xC>g3ogR4viF|42lOy~<Vx2SqZ4-u9Cq<4#BQTEwZ+330zp)`i6k-eA
zDDQ|7KEhipS;sXM-OFboZJq86Y6b^xI8lWtO=vBc-u<jbrCh4s3c@W=wGWC3vixtN
z_x3uZ*uRgoea>*6-ov2XpSB85B)U=|ADxppP`p@TtMQ0E*rf<m-|{gI+i!!ztb{9a
zG@7ZqjR*}*8iZKR(MRlpK=Q7p);#{omUsEa0>r9#nj&1g1PFiZFyps8CL6MV-h|Ob
zzPijk!$g`0Q$};1c9j@6?v{N<<<jz2*FSt~Gm3;_vTGXr((`J?%3m7zWO8D4+?3_t
z+QE5}(^iJWxgUG7STzn~B>_7Qk%j-^TLWc+??!I+V3qP)MA7&zyFGKzT<$-_wS?1M
zKKk}*G#}AuKo=jz!#m<VbmvL`%|a0gGr*81f{o1D+X4O4ppKTg+ps%vJo&*}XOyPU
znIa~4CD8w3?4TKD_5>#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~<y()Rn0!Wtx5a6I<rrKY^4n^;T;J+4-b(E__Ygm3CwcTLwOQ6&KZeeJbC0(}
zriKF6kUlM*j8)-oNwwSdab%#^0(xyA2F~Ul3{KDFwD%sa8HWwckYk<Im%ltSfWa%0
z^tz)qB$f=OB)5-gU;UJ#w4+CK_m*U=(}fXc@m%@umWAHa)j=lvxbT1F$)+=6ZCi(v
zoD&xu`OI_myPt+iWq&9;yUzsya~j~ZOeC>uC1UE!<F_pFN_5ZXx2Vwr@|Jhm55TY{
z@^!VB8p92OBl5Nuj=4qwEbck7>fI=|Iel+eyq&a$l`aX(9kyk+bINkT7-Ct)XHfWL
zAc#2#6+L*Y<qR2RN=mJ7Rph~T=!_*O3IysITC(EkS6efowvMHkbv>L=K~wOMOy+<c
zg$M<;B_i7%^2>#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+U<?MxjZe
zAK7ALL=R?R2}61`H>L=Kbg<Zo$Bf;L@p`6Fy*gD7dBxtW4y^1OE@IO(S;!jRCv8%5
zgZB4YgYq%*z@z1Lv7;pwai!EuUC*K=XhyvyE5>weW>_h*EU5c7v=}Mu3b+3%3u3=w
zX$W#lwdSIhN>#M3=rnTiWc5@sEV~u_fnrDit000r>m_VpjLS@<2n<bdHwW|j4R6nC
ze|%JGy9eBU*CQ6PA6qnLTpcz}DX;kXoI`#;{+6va+x1&E#-yTvzN<?q2-ZS2%HAYO
zgHel80l4D34I3kcRiR}k-V^D9=McNG!2>PpDz%6Kb#H|QuFJks`)O^m5XA*anCoST
zH~$^mVE|tdP!%Ei_US{j7>9Z+s1A+SU#}uKNvT+=q2Zmgm!JkOtP@4q+et$hCT7I}
z3>|A<_`u<!ywXS(LZ3;{@uUC=7xS=w*S2I<?_t6h${)_)J44u}?^NRH7d{G1Sp!4k
z6JuAgRay;|vYu4jXm3$#RW#$A0<M_h%gdgQN_~30o{o!<3foY7d5lhhKbWAgK%k)f
zi%*DXxKeoNAh@J0i&Lv`EF1YZMUntLEQ&H3ATZ0MCEsq93k`r7q%*A(tEYhG!qq@>
zApr1_*_(bJ7OH~9S7Sb`(ih%$rS0Cv#<T=506u`?&codEXwt)`Ddi2Vpx1mlJ{(Ft
z3#ie`@+P7Q5&MxD+UaK1SpMQ+>pHixGW>iTZt|7FVurWUJcte0b4DIbk~G_B8JS`u
z<mY8TuRUt)l2aS;8p-7WtY-h3tpwfJM1s?H6E(`w=*e2tKt^yZDw1Dyrvt+E15!FL
z2j-{<P`Avl3KTz=D-b}Qm_}9}Uz)7glg6Im*>UT#W#t5E9@`d#6O*SoY)UnBKHUbi
zfS6Q5Xu*zz+jwV^A*>+|ELM)OxM8bmSyU3*$I>YE-{`An<la~z-BmL_0N{@lYl$yM
zz9k89A`|V{YOZUDnC~e@%2gc11p?eN0MRTh?@@zO2mN5`M^so}edS>CeIyKh!)7r6
zO!{~p7fV6NhxrDXZAQK-WmfW*0|O3Io0M@O(+Dbayh+#EfqZ)kU9o~grc^pa++MNY
zV~8jC-LuV9V|SZDJ23frgNWzesPo5{K`1<RsRZ>^{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#mXxa1YcUfWZnJ<P5p^<
z7aqVq_rb(R7G>7!q%<h5OJFzO!pQCyC&KazyiSrKwoEGbafFtCz6eGbAT84-syKb5
z2`s!EFc}rw{t)QPd}f_p%u$U0bkc#eV^}Lq>CG<E^Xf~q%~Eer*n{%$MfePg*9fqb
zIK~qLS-tZ57wGeL&0+Z=P_4_MmjnUNwko7O?GL`8qpOy?Mn`ct3D&`J21NNbI2klz
z($&e3`+FSw<GVNKw_lYG+^#5(k&uLasYh8_CcI+ydQZW6sa1uC{nG03XkAj*7<ymt
zc3e*E%t7Vf0a{r8eyDR4;&db;n9K1uDuJbiq|nY|<mcHX*YFc{)GfPsyQheMBzynq
z3>mU&7N4A&Qt8^^Jb^CSdseed|0lhK4L<jT+Yq9684|zFh8HLCMNGXcw;>CL<GG5K
z^nwn@n~L(pzUw7UoHbR)Ft>^U`L6wWWL9&9=pr3AdsH({hqaY{43kFhAMqFLl&|{)
zDv|}b3td@ba4q8{W#$=`?PUI2XjHb&lntc}crfV!4nL46ZS#V-?<!{XehY-1kHA^l
zH}qq*t!r-&K~DMSZ;rESPNsK}F-w~}$D`I*v{+MscDnQ{3-6p?ctdk*@eJY3*;!Y;
z@kBK$D`h=l1&)Hi;}?Ah;k@5aO$>%$yC;vvIuIDspWjTQJh5x<+tKo-w}x||f&<-;
zL8+E7)cEa*APlijT!<BdB*h8!v-OBcTq1&p)|bXMWI$+`6WxjCp=Z91`y@2Fq#9nX
zew*4rls<vxc!Wf)s=v|?NYa-e;%M^lVC*TfpkN10u7GhUfREFUA0eH0VAW+|lC8V$
zry`eZmnYTjU~sSpAK!w^+R`vV5D=Yi2Tmw~$qIVxHxV_0W?!tsCw^K-Pa9w9A<bLm
zHp0E3&5@r{jJX)rZ~o6qkgqq5a*{8+4^+^4m@6Mn3MM7o^ypl-NKM|;hX?-O(w$CF
zBmirg0K}&z#~Rf7zB$(CNVe<JioN{kh!E7tB#7cX7B}l6Ky~l=8IO5y{ygWTy$d-_
zPqWtSl$WT><D6`{5*#Swgdi};=B9vrEK69jhL)dl)VW9?jbbd)<1;WGj8^lu+!gMR
zuA%(<ONG0HBEq$s?eH<$T_$w%AZ&`cXS5FZ0!^C95wf*@`|HU0M@etb1*yS^s)PCO
z!r!;}M50T%Tq5rfY=&9GSflji6$aPr^BrHYbKTlwnH`%IAUUZL?rGbS(+$<qYA+)K
z)d~_KH))$o3=Sese>=MAxiN+JWI=E<Z8?;uL29&4R^(%u+FF5en6E(|6IEqRY?)GT
zBly#(9(7M^R?zH1A7f)u%l_OmyR*7mfdB#Ijpd>c8DGrw^6NSm`OAhElmAULNTr4t
z^=%YrxiwWV%1<=KVig~9Ksf|-e@1Uk?tEmMBhI-zBn`4<2CnCwbbC2?RYYJFRaRLl
z7PaB>jl)SiFa`F<gkI~lLoh^QC4rC`Cog80^{M8qCkca#xL$hHCzC2QbT%d_v!}ju
z62%<^aly}CvU`VORT&vB(<%}{*_H{VyJ9D3E=~RjgRMMA843-`GN0pZ6Azxn+I<k^
z%UDZ1E<r(SEfj{o$`(!p1TzDQIgsHm*mZKmj^!XYS4-Pv5KWQ>5YJ8=gE2xxUU|^m
zK4rj0MLir2+h6b3Y}H8UDL3i`0v)Kjk<j}&w0?1u*hVK#7gVXVaTJAIRt<=+UdnWo
z^_ZEs#(pmEkTS_ICdKtmufQrghn(YkjmdZbe9&KAu#cA7xs&+?s?M+vhTVGTjXr*5
z6%Y+{e91Iv0RQZ2LwlmmvMw^tB1Zss&7wn)MR=7cH{illSGbP1{~?%n4vn8R%g-QN
zt{XH@Xrv{J`83gmdy-_5e+P?V&4r{2EaUN5D2%47Tvy7aHK(4Ai5BQfB_P1hfd#!a
zvtyRf9U5UC_proL+Pb8<Y-V^HvC@}cnQtR?`{XNVPCSIUUvLvLNgbhBn(TC1yr;FT
z^liZT`t3F#A9=kBB~T)#De|&SOj2fvNvySrjdYE)>#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-voxuW7<piwF#<g@?jUW
z2&5=?WQsv&YsUHfqP(hyD}nu9#ZXrXA=$J?{x<wM9O!kC%k-t1WI=YN-D&H`_Br`t
z(frh2^on`AK1;M)+CS^}&0k8oGoCo#1e>ow7WH9Enc9%j6=CDQv)67DWe}|k+K<&A
z$Vk90J~f&)-Bb}FfjR0s{tct^L=|-&cItqTyEPGSH#fB9Pp#H!!>UXiR(7kj25m;*
zXNF8$c1y!#W?Gi9!-<tnozFg9TR9WU?c?r^2fV-*58FzVXDG3{Mk@$WqiC+g$^>gZ
zDC=K3xr_0+_d?j~tY?cRSDHmZ4Gf-sgg}UornsP*qb#f0VRqSH^9%WI9wb|5^^<ZE
z?p8bVfhZr}y-9Ayp;A*Gk=W0SwS)VvC$D}U^LQGw`VVefD-`$BA{MSH4pRSv>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<Ne_Gr^At&ROb)z>%jo1F
zUSFzR!-&B?7=ftu-IDg@LU`r0BbGJz!e-#VMT>rIJho#aBENMyJ(y=#C#<?*45TaG
zY#w9p49{>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<GhA<=D*rw(%$w8*gEwG^#qqn6YcwP%5>!)zZlud}VDwm|yQ<#E=4
ztd0n<Fh?4jaSO_evRl6nCUTz5!1dIpFF|%nT_X+^mIB}x;mC!+UhuD5pkYqqeXX#t
zBCU4x#!DUQa80X6&{N8hL-C{yJr17F7#ibpu7+RK#g5;tQZEnrgHE-<L$>?A)~ERm
z!dZqi355f2$M$1w>qtydI|W3t;kZlUq7q1oyBU+zA$CL?j99H%lQoE-<BON3;jp_T
z^V1^csmH|s+}xLJ$yjR)1sA3PZcWDMhnbThqR+#7YOcVj1AGgECpNwTflqOajytd|
z?8eL)#xb~K!VDHPyoc-pt>h$Jw0V;0F|igS#w5U$_Nb`~4c*R-`=M|5cbjj!sB9D%
z7oDY+8+K!<L3XQxZjBKsV*Ll0g=d%#Wi{bhS?K<NPD;YF)OaIx%z<g?C@r_Prb|^|
zu8Q*jwR{Y?CsZlZX1lkHK;Mq2lv>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<}Tkg<H#CG#Z;^2
zgXHzlhYwjWenUSZC@!sK8}he5DP;c3VL|>u1@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)<P62^il
zlF<J9RT8f|;)c`D43UB?{yuau`OSelrBce>ftFyCqRD|qOj`zRLiJ9<ybbAq;Yrn6
zF|y*sE1;RXuQ(J7_k>&)VPuMh|FoGjpEFJNge*Y=L<BUw4KT9QR!jy7iLdZFPeSbn
ztNq7%DF`l!c{kNU;6B)ayutiGRAyZ2j$6^;*?*|{3&FI^ag4&Reckrox@$bEG(Yoo
zVQ%$-IjFLXd|n3tJUf4HqQe^jBRh%4kkgve+v6z>z;acIt2>lBC*P;>!v<ZX*#~I1
z^MVezhxS%PDoHzl@tIEiJq~1yB+7sjoB=ttxW2!Nmo<yfS3_rFsR!<V{<Wj2=)ZB#
zCCjC}OFdkvYI&Z`2X4MDLt45>nQDaCA#rewxTW2q4%|MT;r{p9cu^zgK0BHaR$*f+
z(H_xylWgX=fUL}h{lk2q5yywmhzip>|J>$U01E5$$i;ptWkE;cwUc}i40G0a&$|q_
zX8N_HlmqQ=5pifxevUxfwwyHlK45-z(TNQOtbgkQP#L1w0<!<XkTpOEpPSZE>Jx29
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{<dggpJ_|E
zK~2xiLqfsEp3VBJtL~%mcFgo@j+YnQ(E`*-XCUI5xfDf-Mrvyrn`r+<Wg>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_za)VickTZ*mS$-FI*rfG{9X6MgkrA40h_(~-F8
zbM`@q8}>*e|3_g1W^2=YgZWR%=$qHJ?%K8Trf^BnTN=ok38`F>n>F`W<Hq3^PRQ9(
zaYD1l)jb39f;y<@E012x`EUml;!0PltVB!b%KXcI8`?&haizHOZAFN=h4<45obsSH
z{d1V5WRAkx{lb}`+Gb9}*7zzWV`I4{zlvpeoSvY5eVwO+&M7-y=dhD-p4o{ei}+y9
zN^$oT_4W$l;XAZdhd|t!kx0~z<F1bQbiF!pm(x&z2Ew`4b$rN;W>)eLp6KU*ylrCQ
zxX2gx71sXf1$z2=BMmKLq?HMQby-d{z;Z{kp4z<zeRGy5Yti)4cwRugb3H|>4#`oC
zZV9pQmlAUZJ15Z2dAmugc$kahE;ht<Vk}mIu?k+>lNyA~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{wlQ<I^ae<i6lV@h@@+d&8fEU1Rf$^<e`*%8WJs<$GEze$KJ0NcRQ
zdBrf#ehhcX=%8!<e!yKL#7E4%)QzvBKo#!#&M~-Tr(kjxd$cy#i_2gT?x#!?%nJ{e
zf-K?4(4|lAOP@y5v9S!hX+^iRflBf#fB@;BC<qcN3pb^tr{$O+jJhkf|4^xaw8U^E
zhXuqKIY{+`%Z!C-@J>miaj_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>A<ICyrY;;`jAbT|~2)_P;)+R)8e<Qh<IHVMuSb%un@8Hj*IU;$EE
z1Xa7j?>Gsg!+lSrw~7mhLj=qQ(Td9kgP~mYeoa8Qeuxlj(%%#o$-8JKbao$a!Iu<j
zma<h%A;Sy0JQNg?Jy)@S%@a@w@ScLbswdvB^p|6WdQyXONS@=RZso79=MDClltq?U
z<*n!}E}dsd;c(V>H#~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<C>_p_*HK#RhGoxK}dN0c@6~M1;P<tEj#I<(M&5d{HeI+MS$91E8$T?Nu<YK?tsU
zgZJr98jnlgHj_9{YEHn!wcb_JVc&QPp{w`(!TA`I<<j^8EjpPA#dC^LGht$p%mt3f
zhS(V}Q+E-Yk3+_)do#YjKM8orqOvHD<*`pr!r6bmi|Jdc1HakK-Ue^$?`)-CRedX6
z%z80R%^cC&kNuJp!`^1EDSRcg3rI}~ztdi%qymUpQLA5|b*iFD3FwB1EFTA)!Sb&&
zCB>^ouZQq$^36`paz<2*UzPryx`mTgPDIOSQi2T|`U*-@6X;7N2qG@$@&E!|qkPM4
zk7YU4)qC}y=-L<FVfZz-1wDj}9&AzZx9~zf<PE)_=el_7CdAm1wMeEF``C-)i^Tg+
z1KO8->+GG0OvglV8@Oe5lE?+z{-!4+nnBP{4neKuu*EhqHWwXO{1KRt8q+L2wsDX}
zi7@z~YjzHVYes2$9kZ?4@8f50bZ~k(<8uP#Mjm*_R6TyL{9ZPhU)l#MU<u0Lkdgb=
zdHFuFkY#gXae%|!0w<3fm=1WAxJlNJ7_w)#;n|BdGR$+iHy2Cmt5tl_5{=!SwstOQ
zY0uVFi#+v2XLoLqSc(i(fV(H3K)>KLZTry?d&mj@MsZPi6IeWbk+-OB_mprwYiN68
zg4c`Z8Z#m7Sz)Y(7?I&<_f*#0B}~^b3POt+Y!<%h<DQX-n@t~06|oa$Olu+5rwrX_
zZca|h0>`+e@cq{WS)88{L^|O?@eFsO)k~(v98gR(0|r5>$JpoA<n3pLr}*f!(gZIh
zkR72+7{3>UNhciv9$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!<sn?0^vH3{X9oiFFNe!>DHPS
zwbWc)TiQhI*Wvidug0cH2q^4dp(MmssJ0PXgiM7VxbTdP39*lSr7sCO$F?Dik`V52
zqt>vTxZUIK^?zUuVl-dLUw%i^*K8>P__=4|NiWy8z^v$BMI7BpAHm=U<Chgru;r4y
z6baw8(z!%|kbH?!%4`>X><$LCb8LLj8jJpySN9TT!J8q`&<=E)BV2uu$kiE-&5uar
zG;<EI?h-RTAj#EA{(YD9=;ZH$2wj-UQ_?r(s+!4-MttX>5iy?b@`-7<cNnV}z`goD
zbK+gD;sqq}$qa|l0svAh%i6l<;ZStK;L8N6Nx$njmn+Y#GcQXBlqM+wiW(piotqQ<
zR0r*)g7Ar4OLHqQOjZZ1{uUVyi{E8E8V-`XdlwYiM`4#f1hf@kl&u;;`g-65dfXcI
zSR6pwe+f;Y2r&U!TspzOhj{rGCe>Y)=;mK?>#vHm{f(38_qfjM`#NUYAj-IJDP1&q
zk*YdQTosyJGv_h1lIxDxCp%lRl@Q;YZjeFNo}-!_<GULTKx+q=G_MQlXNR|I(y0*j
zWjLXDzph6SqviC1)FT`3SOMJup44UWC8Q{9j7nnn#IdS5PV@@Y7INWna+#JogEet&
zR|yaQpj3AFbTTC|2h59C1HwJPvlK+HHh>@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<oxM|4H`xx!|2etK+L^dvRmVqk{y*$_*st+Bve#bBLWMe#T)%}XI)nus$
z#QGa3Oy<1MGaHvv{JVsCtxMr`M*|C%3G-&bQ6jMJC=I5a-Zin&$hwu}v)d-QC!k6u
zQlxEw1Pg>~n)KzH_W5Ri-UHQGS|w%eNEg|Am9>Lh5v@I=`yCr_=gqyj<~hdfbI9-)
zFyN%mE}OlEe|?QBY0XBzV5bw@%XvjwyOy0g$FN*%K)~Uyr|-vDkX>w9NsQ)W<fqd#
zHS|X4zQOaRjApt<m+X(}3r|p`V*0fk+y>R}9;TqX-N`E%L@<cz5L`GOlmoGnGp0`F
zKkwyqT|8;4*nRPR<2u?0O=WZML5FB3!BZZNjIsKDySTRL+)*OOJpeahRU*5Fo?4Zm
zG4(g4z2<;CPKV8`sT>spx^h$IW<4<FY%ZlE^~jGMORh_!&|~Yb1Ei+B<FazyjTij_
z_iK%am8}~6J8uKrO&UE`!*QNEJ{{>-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;e<g~iyJNdEk4PJQ><F}y@gtH|}z==MHX2Fv<N~UI=ZB$0$+DKPX
zGcYlj#2u`yq1#GHZ5dW!gD}fop|W{WL3sL3gK>FY*ilW6O)-yYJ}ARUu{^q*YztZ@
z_~_<d6q#j~w7711JJ2|%v>yaV8DHE0^QtaXsF0pReQ-=<5fsPY>MkbipqT;j_X9hK
z?I%f*A3V)<n5Rn0IPv;Jpq2vGv1OuXj`>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<XrH8ERRDYLr~Ch@P7TNpASJKk4wasQ%i@`)NSZ+CV6NUS#e6R{n)4B}
z?ioQ*H7*CTG%Vq9PwVPQUst!Yq(~-eRMM7!Jf{UVJsmDBvuze&thIJPARXs#R@=C`
z9!y+eilbEr#ZHFdoQVuk=9940iY}OvF*<_#8cK9HhBJ5n(1u?H*L`vf_}x}^)GVC@
z?e^hSigL=VB>;VQ(u=;DUY{|+082o$zehhQEtx=GgzNQS;6(}y)pLDOmCj>Nxw*E{
zEn*Ri)tD5kq!^=Trq6=^QS1zc#CW0q8R;S<iTJrT)i=vAZOafZ-i7}nSQ1~TZ{#(<
zi~-Q#{glb@ukCaM-Hg-R`qZ=pF`+WlExfEt{Tzal$h9>Gr=oukdcS0^kr}ujEj-fU
zkg_KTJ&d962}FF;G$f&NX*G=WLc;z(er3uZV|x3@(PTPvU~Z83UL*H>b7uR-97c_4
z0gI_snxu<GJ?*x7QVj=W8bvBs^)Iff=>~P|`>UZuyTn~{>^mHH=RiGa_E?c3Y>~xR
zGsx+bHTbZl&(_Dv{n-@XNA`>Z4>mqhU56}j2(A7oi=wkxpW(2zLvHKpO3FwAU<3M0
zg*GR<?<q_ZG3i{E2J1?uDYhD$N?3t$#|ThZ>Q(!Gl5KC1fLxXn;}DknZEDM}tq|%m
z#SY1C4p<qIx}9`+3et__o=XPUE*i}!PPwGGjx%8&%btS<w%LXrBIKV^AAMpHvw!?h
z`~*_bX4FR&^~1%v7M=YMC_UG|E(dzYl{I3kE`Qc6s(>`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<V{#fRiRN-<Vg10E*l-d0Kv^|UD4B-IL2vY1!7>{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*<N!px9bWN%!J7&Sr=Gf<yYdjAV6jCcn>;`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<L6guuNKLcVq%*W-VfYiDW%i@@!x4|}tFifPxmO)q-K
zK?x#z;fqBjDuFp+kaHvSvUZH9;tm=#)a4QUxJ3+P5pzyr-~^$CnBW*{bk-z|n=~Tc
z37Epsf&(ZG_z_!40zIS3%7;3|GPpLsia_}Pz6_QpVOb!tuxjS61(oGWyVot<OpeJ)
z-W&&i0P7eJkIe{T@&PEUO$@tnbx8j7zj-P7j%<^-T39|nHV&W^bB9w6JuUeTlxycE
z$$>+k>NZY^7;e2(H?#YBu#+v5RpXG`dr6mK#SlSI)5d$Z=y=fteP{WmB#`W6q!mo!
zD_wVlPa|dz-W<MEylT@eJ#>jTbf{o@mn|m#DwJFFioh#Rd;iF~o0#6<exy42rlZw}
zKyuRCdM1i+A#P7*15ogQE8>C5@}-X8R;T!(^h<IAX;M?+6sE5YBvthI7c75=FR;Ac
zqR3E;GzP%JQaXDqw-IM>Te;LkZ+;!L3FdJE4fyq=?$$<X61s<8&w*nob~<&+0Omc<
zacbkgWFbWP%h9+ioC^a`592bkF{oZxhgd}jvz_nCtE$I%%xXXc-UVHKC!zrL-KY9B
zk462UHN84^uRt|A)WXgttDLt%NUDwROw+F^xc^mA1VOfqLTCzM)44rN6vj*>VsNE#
zU^ZxnW7;}GkW`L73w$A<Ii=+-Cc{dQ6)OgFn*WD3^&8s>mi5}mU|lh2K*34f2j&Ws
z<Dx(RS3n4>`4d~c(NatIuo8o)S7s&FE20_4K$t>}aUwLC6&SWwp77Tq{j>k^UUo`E
z2<tD()xFR+uA$RKY7C$F9ojzYA(e(}@#XQFKFG=i8?(T%UN6K@)C~GH@_~5)1d)0H
zEWb9A#B2!%=SX*%-0FB8%%DPke4VV#57ypaW|-lij6=OZJ*^}GKGr?3L>`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%<Ky>E<fK(AK4BTFIUu-vciy|A_V&xZ#8<{51vEF<dghU#wOPj*g76$H=
z`T^v;+KbriODLl5sjUPUD0=G8N<zkqS9&WTx{1bQp0219H~^8-HlElM@V*sB8@VL_
z<ezBM?0AcY`Wj-dX(Q+#t*UG$G=VOmi_-Rmd@yZmj8&z@qpgdggDI~J@eQ%;_4|){
z>9>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<z#6LjE9DgCg_O;#j*SEfAm@A;8C~cB&?Z;#Ujo0U
zm$bLd5xFK`^~+Ge2whh2;E|FQrOF$Gb>*I!m%uOQ{lH7G%?@f-7uN*Zls10D?1*r-
zEiLj)VAD_(4gBd?>>Z+=zdVFnzwd>Yo3BG7kA^H#j*dvvCsNJHw5RYWn<E}C(BT(9
z3d76Nu2P6=yB;KE6;!`^*xNC^`?<dV)hUITh;S6o+q~Y=YwHHEIo41JV3KeNAPU@(
zy|0#b<j}S5685t6hQIWZPYu88Ow6rQgFmx0+irxM@ROg3NylvQORVZy15E1|lWG@1
zUNJ;}VUKIko6JcfCQpH45mmvMMsG?^Yp?@;2RQ;Qm`Ly{u+H03VEVAJ&DErX*$I5=
zcDgVHsjE($Hz+<+YB=|P7?$@TB!!l93F9ypQJ=Je!XJs(FBGP`D#x<a**d$L0qk|B
zrOhtf-AyKzmyV$+BlF6gM{vZ3uZStgTzku`EtjS=%7*BtGC|~4l<)2t8OC#?*`YsX
zS8uY`=38%GvoJM%E8M6IMyssBvPFX!L*xRLBTeWg{*ZtYgRkJr(~Jbv#a-DI;_!Fn
z7qskVO$Feb6~S1a8fBh1Q#9b>L+*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~<JBA_ymhBhtv6
zB9l6qEN~*~K2=?2`SC*8)5Fw9>(tc5VpYRbvr2AnmN*{H2%i}dF&>rXPAxI0zyc$l
zwQ!ar60)#A8}J*t)cBM6m0<RM#k6Zo1W?BZ?3YF6rffb$<y{Sl1M-O`76RkYNC<ix
z`!aj3SJ@Q8OD(W;w;5D#XEl4cCsci>kNI$raZK#sJ+Sq?KIL0HS4o1VS{_BqZOsQo
zc(v*TUinlGLKzfNo}^6#xdCIY-;ejO$y#R?zT;?!=|<qEe#h4mGY1qT#G<fs`(mN7
zosY(L8=G}=zsj#lkwg-?74Dh-G&^Xj?0ZKHH-BwG8h=|YwzD`19PL=<(&xcpX6jOE
z%<wR%WIJgc9?`tN*6KyaW=)qGEWd07ikc_!!783gze431CWHin%H$nJWda8l3l2(`
zY(J}K!Ppx5bR6fKny;a3S_@X!%=f2Q<wQ(qqk97=!xDTZZaxBrZ|uv!^UaKvS)%(V
zFXRPGKU$*-j>uN6OuV#<y)>r}<hpBZ%e+$%6o@gqZR<BK<rSQP79|*(RBkUF8ljT7
zdceX(+|6EG@|2%s66E3YVX5Uzq&=?erc*cAd0(IVMX0^ApTYc+jyHaeHrQpWX~$jq
zXZ~&!549~to15D*T3{95X^E6Ks}Vb7aBC8r#KVRgjyDlx4d~7>LYr2U=V4*1DNC!b
zaM2R+_!*bK?kiig21{Jc1@^ddpU963Cbd>p>WU&hwPqNhiCsfnIDH|lD&Y@*v36EE
z3`3)MFm{>6KRPDHpmL7!A__1nB~>nmq<W|xFPAXNW}8&9fyLpMkHdNT{?6>XG>J0@
zf<^$^gW}J2z_}2q(XgtZ%2zul@pv&#BBL7Wdvx6kDLIFHs3Ioie2tXE^W-L^EV%)A
zxqWKMFm3czPIM;<QV|-)zF$RVwk0=clORhDHa&Wv*V~{*@c)JeqQD4_*0gxjC~aJZ
z2#R!&it5x~X5i(lz(1JC=l^%Ph6?{+gOpGeawdCL)RH9;Dz_oLEYc=Ih_M+~P0k<|
zt5F)z&{uYfZku*TJY=o>Dn9+TxBHY>atICiq1X%hAb|WzU(igLDeM1VzJ_1hnpO>l
zU%r9Q5(KKYNl2CVTFjP}?0~^xG*cKLYt||XSqZbu6`UI?q#B<lzRVTi9w}2U6EX2@
z<#L^^r=&s|DGC%p+SZGMYs7Gx_O4TRYJ@opdD*uqIytwyJbN*JWBWOvwu?xj&g0`*
zc^l7(mIzre&CyF4<)#+q)sFcUnQ`%Y!3yvSjt&e~d>2s<XaMk{c<ogBz$T~E*91<C
zV=kxZVBq)L)<3lC^e|4sWjqbJ;R4qk(#E<m-@fXFe`6z^Z=2b_h(O$*rLv!0IzkXL
z63#Dd5r&Fo=KH?`$6NJlBj1~rYx21_sn^7NNEE0T%%ajCoXj)(7A(X0Q=xF*MaEX}
zl%e@udCsC1hg<S@X6EyW3XhGQFu_q=d~DKaX9p-ii(MLZ3Fcq>isb2v+wvpb#`eOZ
z6%3(`<BujdQsP730oiq`V)4<6S3Ff4m0dfACHyF0y*NY&g?wl`>T;;A9XHkdU&e^s
z!73!)`6I*bmNUPL#u_1YpQlv0^fcixrGm+DWet3WuNX%@ur&s0j&*Db<MYvIHGg(T
zY{{I*iJC?w6wVIhdKFFWQlK5|DM2c^_{q!YGf~no6iJ;HLW70e`x21zOzh%WmiOEi
zoG=_Ykk&q=0KpM(|3lS<$Xu~w<APJeufWE)vARx*U-hcAC3fJVr2Kl=)6huZEJ_h&
zhP1h|z+x`wm)op3?aqb4-8Hp%{qrpcm#b)V=*3^d;Py!kVRL@oezT0{HMcf&{M2WE
zg#pLBv^*b-Hmh+~0~4z8r}=r0xaFIC`@FATjSXkZOO$$&ap~_iXJi~<6g+hVc1jY4
z#<q=nT$!xQ>SB&%hc0#7ZJAPnWSFBW9(>t{58@YD){_VI_SRCo2WAeSdzc<}EWSE?
zh9~_`pgyepX_;8MCjZ1ZF;QlC?nO8raH;aI<jh@fcqThJ!?KYFW^*9bxvkrA`-P@<
zr6kO>czEL~#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%Dz<Zgm?xLmC%DpGs0+XdU9k?WvDY}v
zIf?@+vHmqrK*G=k#?+9m=Eu$q+8|5Cnq)EiICR+&EG80|CPGIGDHLV34Mt-p=-o+i
zQ3+)qhX2AV#<5aD*a_U$&O;{4Mbeiyu$hb{uM^MLTA;*%^Y{j@?2-LQ<|B7{^O7rd
z_$e$+DLeq6AK>d<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!zFT<feDJcm1~rdjnm_l>AB?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?u<qFQ1f{IM3=xB9}+@+
z1GjsYrUni2SME_e+a5{zJ*i~I3n>6`g#Pt}X)|Dcy{p(X3ek@0fsJh)D$$2VczvOC
zg_s-n$YK|p$8C|O>5YGS%gs)EYY9K^rD=@2Mtl(s5~7<S%NK=L4coi1%73omAhD(*
zi-B#Ac$a<jJRH56j12rIxHp*fF*yv{TB>TCqoMjvV^m}~Z1V~vj4O<f8owje!&v3=
zuZIXz_70cG_=G~O?#N;X%L?z-UlCO`f~-Fh{<sW~)Y?)bVc!Xx!e<vJvc$5Oych&3
ze~*L(sA2j>c8Zv~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&tGaHNKps<D@HH<9-W|)F#dc{yMkcod$Kjik9}n1lHM%P@gGTFEB)h
zxtobXc5`~7m*iiv2oNmwpisHs$rbk4b131z7J>bLf*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<v$#(YK_IB)(@xVLzb^O6X4&%@qdUV)Mw8%z7&)BAIo&cgOZ&Q|sJ#Xl4
z^!}@T(!aXBXuZwX+QtWg!sAujanxn)Ki6i|pRd354JYVI;;=DDeA2GZq<ZYbf`M?2
zWI}-C0q1Oi1lWf4LJX?O{GnaVVRflRKfC~d;%6{u+8~S<=7w!58XGkv);3-_*rtC(
zmW*bn_V}liyiped0P_s@pffPAxJUO94AlQnQ=AV@W`>-?RMqq2CbgFM2)mJw`wh}9
z)$L+d&HL%kq@4dp-Pdi7<g!`dVm@7NTDMjTS>Wv3d^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<%kr0M<r-^Au@kM7RBmx;FBJ}
z6-$YhcPOVb9XB#=)1FHzF*k2Tc7JjIsqt1pH1E+u0|(<p!eG9ff?K)gmtvxUeZwnq
zx%w96m&EqwR&HDk4*`wgtk$6b9SSr>OR+uil8Inxb#ZW{@Hmw}aw`!sMPUdls9Iyn
zKQAsoynROu_6QkM6=nRZ$w*MZqvO<lxGW-!SB)T>0HZRJnXE9P^&-X?PetU7)f?n+
zRXxg}iU@CBrQ#SIiYthMUr&deY4fne#iwS?;b?p#Z;R#<Wkd0410+0AoqAS4T`62Z
z7i-?Rlz}MeV8n}!25Cn`?|1hnG;YUFG$l&NSV-K2DQ5+eNb&60sGLAU&vzrHU!1u>
zbFi?4n)el*Lp~wF?J#vU38uJOQ)};Fmm4~3A1+?ag`V}Z!PMRplQFe4!J<NWMBVN~
zidpodBuCRgiEvw6Ip*Rq%@~EXTQU>lQGZXlIdtErnDy#Lzf?d<!UFfNt|FH(&yr%z
zDG{rB?ZY3<v7Z}{J+2|0s!&h&wU@(i>kMI|;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~47l<mMyMr%y>9Lphb$`uL=e^$$91~LOEIw2I4aXfCLO80}Es}DhFnM-G=
zEZT;?yMQUpQGFy8a<QvQNyWnJWx&p=gqgf=)4j%jgx|ryN~jkT=r;D3sa&CA8Egd-
zAqnPGOlcG&H#0aEzH2{GM3g-N2-LI$4pB89CU}l=JZ<`>?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<wuv(qs4qIr>$?5*mCSY9>dK$naVF-@JgOvKFVuD7~h{0a=
zrZJP|FuAUh<<wmqOeL!PMOgMYZ4qtm@k-sS7vnVsIc`n5k%e8cQL816#M?f<5BpdA
z;l<H{c*Rd$n2j4yLYOPT2@iwzF=<ZJLQvPNEjr~nw*LlTGk|e8-16ML?^nLscYvWy
z&_7jv*qr17z8wxo``_TN?#qoc>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<yffr}81qx6)
zGzW1u{CGKZ15#F_%4jI}2q<r%5r*{eH+DT34gcssK20h19yCm7x?LEU<KAs^Nz6=p
zS`LeuvL_Osw`#;**>&@ARq}{Mmg&_mkAhp7B^9Jsr1D6k$-N-_v?mO@<!}&jAW&a-
zTnIbNDc^)o+{UJRPwJ^2{tXtQllTA#sN#b3#d`B}O@S9P2~3gNhmND3R7qlx+>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@;o<Frm{WA;#{7=U?)X_wes}*b|Jh7n!mn5A<nnM?@k`f~GV^_9Y>OUCz2F7O
z(H4qf+0nQ&<>c4iW?-{}3cio`TGHa*T3cBP0_HV`n_6#7Su~`hz;4+Rd*x)fO?)91
zP&QgWQnPwY&;p5ph%(kDm~^9<$j7<pQBvhWrGgEnWsJ~k*F^eD8*r1hT{N0|?fFfg
z6u_-}4pB8c)lQkiA`j2haX=#Md7PZiDqLtSj~%az|CET~`gK1u{9{>5>e`4r%Mz=L
zhCk{R-+x`+AIY`ES`|SH#2HxA+ti{OM(iEyUi~R}g1<z3Gg_BJh3a?qya|ejjr(9C
zbLoY0;Eco4u(!W!l$&G}fFg^jeL8%XZ|%|4t=HsSa7O`04y?XP-CxwJ(cKU2sa^SN
zwUo*sKaS7mOgLg|#4U(_oUOE{zHb5ZqDdleKQ@nS5L1b!^Jn@kV1X^~THqTAMBuIE
zMrxg0Wz2(=?`}o{joqr@N8x2I(M8s?hpqJ7@`w`h9jO9~3i8Ev{D$?!>Mam*t0Q<M
z#Pbna(WLN$anqHHe6FHjf&JeQyC9RhW2VOhUO_3lZ$)INzd)of_#lh&05f4nB8XEB
zrECBSxIpve0KHm6ae}V6_V2wKRys9-@CyDQ6LEFQQ`w2(bsF?f2G}Qk$A1KqD)YGy
z=`&^n@g}MJ56}X_u)vzfk8u)2=rqO!-8*-16+5+f!uJ-t@;HVN!wjcbp?S1nT>{mT
zo-QI-+11c(6jaw3ua>4naIz>ZhmU3ayfvX~KQuBag0p6J`q%k)VM%(DeFTl);)XE>
zPa$18Q`u!A4v}i?5Kx2~#|e8mBm+$@<x{KOi0)`n=hQv~cVW<F|6vau*!_W8XfR{2
z8OkR2d_z~71k9jLaWuu8js_5XvY*8w-d|~>+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!tb<u_U{upEm$8;mNou;phv%X>WuMy+SZ?p#)pN8!W-jX52jrLmq={
zvove$wO?kk0Xim53+S>Tnys22IMZQpExIBhcN>TIL`f$_p~jRx>0ixYsv%&wW(IQ8
z`pczC8x@BTF4xqjP=!Bxu)z9V!TD>JP$;-X<s3zIbxalp4YF3-Axvt&nZG2BCBXxP
zf<}!B1G4M?tUi`SRH$<&sg5k^v5>w#4<ZEZq3yY!Z6{H6^{1Cn=_}h@pRA=47Ik==
zKB-el!b2~q$oK>-qv~KTLaD{~E_&KLV<Moq++|Oo;Na&H*@3;~giU0xiSsYD%yV5S
zX&B;Net9wan#i;0KA;)szD$A_ckHbyOeD(&hv2Nzh*!mr#7+4NKE2}1XnXgfrXPEU
z6?ZVf-lay&-{I-!R`TuuF}&Jne5f_KZrZ1|XeH?EfQ5}FTn2|<udYt8L&!gVyPoL%
z1I{%zzc!?HC^(+%Od6&OPd)$vNHB^8gNx>^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{SN~Ikk{%i>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`<ZFl;PR2OT%QHLj
zgz=VaxtGX2m~LhPu2L3!(94<$na@4@wcs6l5R$LthRuDs?0JBc18}G61it8Lze>z~
z2&afW6)xWPFbE<cXjggW*m<ca&q95Wm>e>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<j=s4n-Ce}X~SGT&|*`VXQeIaAuoabCu;)2F)xlg$59eBI*
z!|U1Pp%xvEy!aJf>&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<dmSo|mL$?n|j0U_?onFJrq65uv
zkP5qdiM+hrQM9A^iUZDEu7mpF@E-})cEYKGfZKU$$0Pe;V}(rKjiWrPewOR``lx^D
z|7guoiVT}1%{;T0rP;o9+gGzQ1yKuU45$e)Tjm*w-}b7%#mz^9)%k}XAQgPKKdiR&
zKFw@m62_iDgyqL@DZlH{{;N1LF4X^!Pu=;hbmvaq1$F|bx(z~QH6rb5A(emza*5;@
zfM)8d)|fETzK+kk<j4>-_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#xUM<eW7styAhv?ke-oZmBMzcYARe43L{Qh9SC`KIll*F8Q`;mJ5%5|Y9e
zd)8suFUB^2=CcP~J~?MsdX}?St?{h1Aom2c-GGW`GX0Cr^M0;|Lt<>uJT?{%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<qX@1IA^$F_@H#GEdU4<8bK}h@35~fy%3>+cT{VWpJFe
zZaG7?Z7cM>X-&UBoD<hs0X@UjQ}49-p9<odv`B7L^($-qf1!{IeX5+)I^&Vsfvyu~
z>@0OiLfNf%#a4Aki~kqb+(!mdpgZi5GqJs8UL;@NyNu1L#c5Fa+6hJSy}7}ko@81)
zjSCnLeYx7c<4tOf?b66A*lGE`hTLroSv!^6({E{|r0Y9~q)XF%JW>AEayM(xOScxK
zst<Jti;RrimC}~mx3|i;m>7=v;j~t{QR^1^wfYM2Rl}4UD>lq{hP`o<?)Z&6uvqJi
zO5w+7Pg&{6Dv+`T6>bF6c0m07;p6eDcVg1b9}~5GLeUa4ti~OQc2j_Vs*HZp%Cap-
zRigP`u6l^4`!N=ETOhv%PcEu`iCy&bzp);MkpKyjjXbHWLKUVC<Ik~1D^@654x9=p
zt>yV@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=<sl_*YSd{T<Fayr8bP<$ic#r{21h?iR
zDSuR4CE9MTvw*4kd7sRLgQj_OJbn;MeoKn!&EHg!6N3F~LZ6QCNV7z@G5fCL)c`YN
z65w<xeb_9ysR-9K^}5P|3w=Yh96bQOH<5t3br{_t&nAE+#uVkHU*wzO$<M?)cH;%)
ziG>nsr;tz=$!UVPG*US6RGI6kMDI+_C4ck<A{GNX`S{^JB=i)tDhb}!Vg)CyBk^ml
zEeg7%5GQ-I9!X}Hay$ay=cF{*$BmF!WbP%JXyV5Ow_^6bje|x_Q47$<s8{$$G54vv
zqb`OqU4gS&1RT_Abv@Fg!78U*O=DeN_97#Gg1E%q9u1ql3>>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!}<$D4zi<GubIfAa$We(2mrh%yMQs+cSvbm8Ahl4E~luVh=tds
zbydh*n2~3NlSAnvwP<ykQMNY0$Ih{7jE3E^y6<VrUwp30s`kvg!Qldq(d5~zGPxx@
z*R7GJ=g?sh@|AZ-DC3DD_9b0}U7Q?Vp|#p=#pTq)L45R2CEWqZq(P;h7llxFN<r>B
zcXM<La{|meT(Vl}SA5Bi1`8(j_S~heu9?#ThrpnUwV&}MU-Uk#Wvz)TbqwYzfU_An
z*&Q>Up-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&!KZ<I9`S#!^%7r9ruZjZf!HGG^$I7t)!OLmXrD3s=
z5Dhs6Xf8m@&wP<{z1Bj)qGN-D*9&Q$zE$lSw^T61b+_v;Im!@189{^pVL2>1(~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`<eJejS@-E7q<wu@qNOt38zMHVCW2|GEm<m><|`p(8bnYWscTz
zB1zz<C4)9)Ci$yy>-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<U7~IZ|2|#u>~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&(@`s3<OklJq&G9BcmiVi|C){bMf#D_L^
zc2!0(wZy9|0Sz&TQS)F2^OA{A!?UnD=;@WYEb_uM9XFaN$NWvsu+z~NeL{Z)ytZrp
z(Y2w}1FRAK*PT68T{!JpSML-7-n1T!LQpRe|I4FdA(>btU^<#t{p+EwcEmX9{5$ah
zp<ks8O4tL*`WC}U@P^$;DwPm%XGN?uHK}%4t6QVc5QU5B7oO6eHkyI~Ft!tyX(7Z5
z>L{vw>yS4ITjCI6-A!;Yw3pqI%m~z<DRD3=|8j|@l$ko4f%5E}RrU(wSu&3=$AHx;
z*Yv?qn7%w7y$J0ut$gnGC}h0y<es7w%RCV9$2=!&e?%wwx_t6QYrz5LcGz@?=f6Gp
zz<NcSE@zo5rKcslUt|&fUNsI(4}j8Yu>C^8VbP%kp1sBkNB<B(6x*PC#JfwuDE~EP
zjj9_!)Rj8hx??IFc!$3HXXsZ~4BL3(ZsSlU^Iv_cr4<0eZ#*EtH1$KRH!YlyrqK(o
z-Aho-u5*pM2)TRBS}^b#EkYctd>;)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{aBN2cXpkm2dDDC8tG<mJ0=qYN3_i&SCdT<xM_&
zFfL3D`aPr`@Km$ggB<$s9@THE6xHoq{uCMhpXzt&iCx?K_2Uv(i0|7z0aDiI=va`W
z?wrHB&;qavq};60B|CKf`E$BQ_+AMnU`7h0lPC*O&P+VRq!+LiO(JpKINPS$C+@G#
z>8EzsDcTRXmeCOm?4B7G+O|w>>^I{J$(VaVDsNl{N}1ugG|!UEk!qm1UoI`bS+MG7
ziL1~6=^45!HI_<vtAcI;bLC)8J>lZV;)<Jo@o*&TB!R(qGL0JY$H<xuTzUb$RZ&UU
z2&oFs*L9?K!>gQRWg}tl`Ga({g5BR@x&HP{(zc{!hjm%oT-6s7Nl@8jpA2)SOoL(q
z)}48EZ%qjNq;$3vv7I;IBvvS~3l7Rx5pxY>*!Vf@b<e`Xl_ELUt%A~zdkjZEA?G0s
zkV2bj%H7ZOU0pW;DQ_-HVp;aeaPsQ8vIpob<Vbv+0BP)Ce3yWKGTH~G6bMY;*%+_(
z1+N0kjb%xxFeC1ewM1x{j?+#LUl!NZq2xUZd-t3Qc)wd3=#6xC^{f<2K8=ty=pacs
zv_UfmsN`UZi8Df>TntJHUNE^^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%i<F`V9lb}lth22yis*HvOA1C
zoWp%cQ~}DHMl}Yba2LCMhL0~u24p*K7w6X2k*w9?ls?bP{Vl_<w+2BbOa(1?GR{M|
z7Gv!Q*nuS>iIoB|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)9<KOxigNm4A8EwPWryI4U&|3wo9
zVzX%pTqbeU@iGNbkfW<J^+I>ofciya2R6Me$l#U!)<KoA(Ry?WSKU2nG4E%^NFQ<9
zP0jME70{myL^-HQ)!ayU-}XcjSNFspytTD>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`X<aF
zJFazrgh`CEAI9b>bl}NB`)%XK9D`}D)%8QB#8Z^oVGbOroq$mLkPj+|?22%)`kj99
z*6vzKuT!IY5jb0IT68=Zh!_R0q90WrlANN6eehIqx<!VjAi*(hH!ht;d-IU&pA)l$
zMrZ^9g*yd*hRC(*bR#gww*Cs!u3qzjesyENb;LPZX@Pib4;Tm+^C(c*DRU{Z&_ohT
z2rCch4Mlvrmn0l;wURp<_o+V8NzN0#s_!B8b@XS!e2Gal9a%!cnN#!qbuLP4Z9`|}
z#YAyq49wy&$!HjHSfZG<Amg``5j+No0&KCNV-F{XVx8u2yI?9QygUM`clgI;4jWH1
z77VT-gFgU>K4X9;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{<jr}bKowj{j_PX=d$l7vz(6J#B?Uy}wtcXDYxrVOHg
zew!%SM33H3VAQV6J<a;+=vT4(wz8y?lPW=s&Z6YKorY{Uhsw1;P*ofgXZsOFdw=la
zg1Fko`?DsfF^F~<_zEe|M9ZjsuLzef!)lj6%0vWBrNY(ZAs(IfrfdE|vP{29n*Lkk
zmYeeo^<yRdA@s}55QB<L0ra9IjO^M3)eMoNS_BZ<(n9PPT6;jv&O;lcNAW_~<JhIC
z;?JH@J<oIgZ2WHre*17wZ>)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?<v*qY
z6ywGvH>?+$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%=a<o@En{{YJztxYkvWJ3QSy9tpK&!PWT&qBc
z8TLk=jtJif=jz@Aay%T+oR%j6#)@yN0ubO)DI_8VEP;`Z+lSXpGKs#7uTtY|oVP1C
z07XE$zx`~}g(m=IKbc>WuXBN*`D}gue?m3Rm}YeJYutV_gTCWm+NN>g*Izf`tKoev
zBHBD<JZ7UCTWz<?)9k$}*ts=H?F4?BFd~PE9J_EvqCo@_Cec+4EAFxm4DHfs-X8jf
zPNKn+MLN`e4a`ls`2&$#bru)Le!hv9PHvy>To!P38h0!=Y3B()+ibV6g?0K`R(pG*
z1c{A=`JsJzrQA~y^{KHUW<yz>R7<o(&Uzp~Pw|>Lc(n<fgI@ymLH4)iHI^xZXw>4X
z8FUzluH@k<DF61u`^+0|XE`Kn0ridxk;S#hnuhf}-sq73tY2Wn7_McxZPt{5OCpn@
z#8ZrRlo(!cCQ)I)7pctA+P9d_e&Uf>DN|A@oSfB%ST>W#ZnV|~SY9Q{!j`|5uf2EW
zPLVJLJQtN>mvTOB!=gaIY#&jR3!WOH?rX|K8BYzj5lhN~P5Sg<SZuWwr6=j}OsoD1
zIBb+iMWLdAey`}3dCw#R>T4O&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?<pbqg^5Glniuq@J2qvHvklWIl*uY_a=3MfCyVbk08?P+D^O_^_Sx|hR^$}Sasq~
zVaJ1_g)wjv21HOx-kbPjcv6!<g4?BTso4YSW8CE|`8l1K5dG3lxI38q97$mOSano`
zRjY1hTS+MJa>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!<kAd8TOed@+RJeE)MNccgJcvpE&W?
z`6agg6WCgIeK16)vQLjlM_HOuSRLsQyFI)wWy9mS@Q<}^)#`XOSPkLK#KG~G1{Hwc
z7#*sqM*WzyqZ-VR<#%2jk#4siyQr<%Lb}JB&A*iR$0en6X6!5&%lMvqJV5WNXCvh7
zG}Z$2)6RaPy>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=-id<Dk6T~_>yc@#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&kB5<g
z+NHJ_=pYe}XcxUGHS=5-wW4}ah6}z}a*Px_Hj-wk95ww<TNqrKu;o{P6MrIvGL8L+
zp2Q^%A;bEdh!PBSm@~Y3^gw_@5rhGJhiRU6z+vB|C=X{Gip&LZot^8H!-9=|0VyA5
za9U3kroIVf1QWkSV#OVrl5%Z;F^gC=1EMYLg33*B)jgs-jP-jh8i;e`&(_YD8TcAu
zfs;FnUjj!077<CG=QnW2MW%C7Vu2~k0+CS5Ev`^TZDB<gq>zil|M;$X#$}R-AeEa(
zczqjLVx$1(fewbYLI{!Ej!xse1F~)wn}fnKLk0`shKlP(84!X^A=zC<l+%p>JJ~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
z<d4QQV)#>OoWa=$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~N<m{y>7852<)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<h>_F6Qy6Wc!T1_k141|fv2^NXMTdslq9P`!`U7B4hQy{qaR!s
z{#8l*=Q}PypTfK*OcMpbh^nrW*q`OiC<X4&4b&PXgx}E@`8<AvF<D7m!2Jg3f6wE*
zpR0w}NZwx+xrq;i;jhVOLMn{*K?<!M*rRST%SMvnNJP#&$y;DTlDW~+ADfWxd=vf4
zWQE_;={AUq2<yA|4-A|dkCHGDcb@qT%2ymR?wycwSTWF8asI;D8u5d+lU>|Rk0!<L
zGNxiz54-!c(WZ9leE6?4OqLAmhLFU;mo`m3gXi%*O)dKa9vEHRW3Uo=co!z2bl$UM
zj`$#6;BEz3mE_o=|Afj;DBrYqk#DMX|Dn{AHM7mgyxiGzsLzax7fC=UjyoORjyIUW
z($~kKW=!B;;ZKeD2*X?%nEKoav*k0AIvNb9!et=dMh7@SJm=a!4}H;uZaiV2!ofvw
z$S$05*)9X5dJm)TqjILtqN|Le9OYTW05WgcziBH#S^S|7<uWxN7|8f-LBclctLK2J
zw`-keq7S@`_yI_ZR_efdg{IO^CMz=>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(mY<!c{G67^xyUA$I1GnS{3(U8g
z&xggIYATH}SZpg))A(0sTKW<aa(&=tKHq_UCcv0Rp0Ham#1KMaGC<S7T5v$GVt}L$
zZzvN#mXE^qCE5DL(v7)IA$1MKNnu<njW(*}ZUVg`1OjL@&l(ptrsJM2*A>RZE@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>kdbc<u(rKBqz8<OA$tM9674xV%I
zwEue0@c5U{UWS;3XwB_1EMsoxu0>h0%8<3DAaO@JnvQ`bAjFFydO=k|>RCYX$F8!g
zg)r8<n(7`AD?vL2l;Cak`wEHlCcXBACDMwhX9efCZizg0QZ8zZBV@J6|5)n;&nH}T
zE`ni6Iu6W7I@onIxb$*lz>Y(ZN7xxS?fO1Pkn|6OEGDHlHg@873RKC?1PD|@HSXe<
zy6N>RkEI?FPHC4?oSKL8P@HTT@C)#cBqH=Sf6qM(GS!CMR<c`avzl4z_qdC+Vq&5d
z^#PsXCckH0muGbaj4L&l!G|ng&1kN!fTJveM)a)@kT}G}gUFr-8)9jgpR3})4B5h!
z_k@K%3LU9Jq!~|Z7VeWf!a@*D<-$&;u^P#TAigaepm282c~9L9Ys-Lj#&U-H=p$aQ
z@zHv+qtS*#-r>*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(>iz8Io<jW5jvKA}J^4v^=(@oy78vKlBcBUl
zekvovYUvH$Ppw7Dy&Gpi&fO7SSGgA08*`Ub;t6`@{;#3acHvQELT+Jw=g_l3MtRgl
z@e2k64Zr3b>C0N?8iBw*r~r~TIY9dhEtl5ZiKZQ;MaaqlxeaHf$3HFvQBDJC&nCj{
z1u+lMfM2(sQA#AxVn?qSI@gm`sQi~Ree4#Bb<cj~&)+E}5BcedEb9pL4<`I+*N|ib
z@8&mAV9_4P<!i75%UsOn$92$&m?R44GjWdQn9DOD5GhY-_acszlg4{Oexhl4m(%~f
zd2v`-+`lub^k(mb;vIXrOK000mCZ+#B|riSRIG!o8=^;8Ip{%7o(5RR7;>U#`5t^C
z-tGd}E-_^$XP0SEIsg8dRAU$e-cjQ|510c2m!+7)oRBifF4diK>hQODtJlwT<bD!@
z#D#_Nt={M)pRmtYQ(@FpQeaoE=}<QKUc@ZTI3Al;g~?0a6!?S7zF9yyKr<3^IFI$%
zEk+zz5#2HSO?MZU4l|Wt#S8?Xw$w=Or5B1-`hj>qehZ899c!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=xF<pm4b$yBoxcO#T0~T3)W}ih
zOcjMb`D1t(kt&|mw{5r_LBreFTS{75cX$(Xx8p(J`g{pw{am)0E8|_m$y9y>w9RXS
zr4kQk^0`ikCxVf+?c~!3?xfnw=@`?vro!_&8ab!9y8{f(&McrSf@3sT(04bfNp<f#
zbQz+^_l&l`ka8T~k9fG+n##b%I6ku#a;3nBZ2cJ@kCSb&#8m^zW58`A_&)7?l{=X?
zEQ&rDM9fANt>0v`E$*uw@py(TXe$M6cSA#sIyj3H9ov<uv!aZ(&KQYdHcxeUdLwdO
zQuV~c_1$DiDCb-<RX%a_Iy|HeK5(<(b$~WM05i~snSbV|&B;fV&i_2EI-2&yXq*j+
zsUc5o%{a2ilu-(~gbi5s^N|O2K)fy=$C0OC1qiJh{MzvOFGf{^fn&KU`Slf8kgDUa
z2Lw0CHALc(fv0cdo2T7rmF{uW1VqPIJXRPE-3SAzSKf^cRJf7;DRYt!vXRowM~*=%
zF72+7AA}{a9s9H2%+ht*7O2vnATt{^NA%>QNS+eQq*SG-J5)Je1~v^p<cv;1sy=bX
zF!onZu?)`8%`K+H<)cs_FaoY~OH!Eoh7i60`P}{jg%1@%ptOKP!2=-}LFpTw<DoQv
z!?-fb#P)hf_=F5#FmQlC6Om33ps%J(26c!vcqXvfshE$;Nxr=%Un{DaijxZfPY2t9
zU|`uqlg^+hPJYf{4+(+Ds4_;WwZI#ACee@eY2AR7&d}q*kZ&e=(tf>Mjm!=|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*eN<GGK<q<2DCdR)N$`{%DH1;PmH7%PHfOqkYt1
z)FBb<pm7&X;05UB9`&RalL2Mtc}FU5B*>GL9|^kKba?S#VE8P2nyx|wikP-V0yQ$n
z?MmGl1z{T{D6mg7n?M93FSrmj8@3!3X{;a1%vB%7d;eZw;?@@BJ{RaeIP-RDw^5E`
zKsIzLL2h<fwYfXr@94nIgwL3s+zBV@Q{s>FH2B0%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=@<F@=
zb6ohoOD>ddaO`tZ*{1m;ZCtYh?H~hqvlBN4nH<v%Hx=x73`Qq=oP1Z`25>B{hVu?0
zO7-7QEp5T~96yOZAcS1~dBS7h{;N^Hv<Zd~VE&2(LkqBmvbCDj`j0=Go<TQMu0rLT
z*|>f&wu!XCz0puEOQ&mn|GS>#=xZ@)hFioCzLiZ137cN@&Ugv&K*gIo&3``*sEA#+
zHDDk7RUCBO@=0<S{-}~vm}_6q$+@z?#}#Q>Y$>-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}<tAm(YvtYJ
zCtQ3+#$#^s^JX#igtBVOMdHHB$<@L@C%#nB%nI3o{HTweSfsqK2$|Z|bx3eP$;bm`
zJdTDM-QghxlYNQK5~0g^W?UKV0EAx_fV{`O6Er#f(`?%v%m*B?`NiR6#?b(Nq8+22
zT7A~o1WlVBG7}tF)&Xa8u5HvDb?7fKvHSqJPN|&mGpkL%*=hhQ9!uzYDgDoLecvhc
zYGbLA>6ssH5buF*3mwL#@JRi(0OCc6t%$TsU)s$8+*y%S0-an-$zVkVMBWB8nkW)P
zA$~?NRdhjjOwg0SC~+e<I)8C`%=o~gqsg1L-f=oObL674u?Fo~>WMtd@vs`2Fgl8S
zqk>!~If=5li{hRFxK`X?Zxde8D8T}{^Zd!?<a2EiTrB~AqdNI70l8_KKs%qzfci1#
zyWM{PIl$0zg5KfMkLL(RZgEXJQ>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+OrU5<n3?)ZAt7>HHcLJA-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^<CHyX=h3j$$T)xhBwHNNg
zlF9fC=>Q<SLhyEYwW}ca0&7oAj7P1+r{ma>{-ojfo6ES<|0g<;L_^U$m<^V%dfCRS
zmJuS{u?nRwFZA3QV`>2W--FU6lX^ZC5lxfURM<syk-CD*z*Cv}E@?fa5PsLR4v%&5
zvJN74b5XahXeKa#%Y?b>ys|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`<GW=igD}m~Sqkz@Sh)vBAal$#&SU&g8wfW{hAIaUOpdtpC=^Lym8`GFIS6
zZd7LO@V+{#;3at6bx;aO^bDWXIO@`%sxjMNWg?uCMcN=vR86{PeJSf2@Y~pPl*ab{
zI$5E|lG|u~_XYx4lDNsITm0dkaA<~<vzqz_zKHaJAIS)vn2v?qWevY(m*GwdH9Lr6
zW~S;#r*m5JUmz00RC$KVNeptJPjo<NVVUf;z5?L$ajqyE>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$3Ev5xmwKDTE5<L4?guy4Z}T|=)!w*N+F*z~E^{L7bwz{a0I7!=Sg@^M
zI<TeLJ_S)TRoxkuv=#x9a;M&$)Sq=*riUN>ASzY&N|)D|24AszDL?JrXL=0}+qKge
zj>voNd{%<Q?Mg){Ef$FG_tceWWcQ@mxUq4+=TQ_~?0=Lmzb$E;2Syr<tDH$HTSSby
zwhT#wh3aAJuSjq*n&L`Fly@e3*kI<TyQF+o`(OT!PtrJb9@UO$5!U(%md4R8-`Uap
zIUk0NgAkQHCBlH&+w9uT5|8!7>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%|<eyK_JreTSx5kV3O6Etjy-A(Cg<V+k
zs!&Vx6o02=Vv&S&JXWy*+E?CKxiJ}k<DU0zDUA61c{pf;XHjuO7d7$`n64qQx{Uhq
zHqpXhHp%);9~1z<yM-%%etQl_Uw;tvh0<e)S1s#oKh_@yHnFUTq#YTEw7nmoM6%?q
z+|xg~aVHhgGukTA{bGquBQ{YnarQ)#9J2g@GSvv}Z{Cy`<b4fi3d7FQHqV*jOFd!c
z4IukM(y(Dmt@1Rd=mPUaxORRl$I1dkUrAt_DKV-K%=|+<WoG@(E8!{5Muw?oZT{q*
zFdwwbReT=1&w^uP5BYa^Dhbogm>5ZOq&^H3fm2qTfES7Xl(B`(@uBOuraX~<@>lo=
zJQt!^l(vv};uhS=WNu<-R#fDjSz&InuBi%6HElIq8VD3K=`&2Ck(lr<qxp<!V4gt*
z6=T}_!$c7AIp1z(GrYw|eXGGpu@LKe{iRHt2}4;bhiKNi#Bz<<eZM)6PuzuFKNo$v
zC9%T?1;crrnUzC22y((UCnwhDjk|%*+gzRcPDLMg-hc?*Nm!qka>olE=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`cDR<ESSd4
z&Fjkpi?`HKw;Y~8MFnB8=;-^?iYv8O)KQDfi5~PfgNMrc@SRm8kIkozWl@URxcgyK
zXrKwkPeYCw4F+Pea?4BT{m?5_%^-NpamPXO%Ku}Ec|XIFQ!W}EGJ=G%qq^PPW_&+C
z{#Aw%w%q!!Oh!1~g@%YIG#jN$?id>yCJmj$dnyre6rMpIh$emaeTVp8do`Q=9_gB2
z1~M;_IX0L=2+ZicWg~6&xFY?4c*`Tmdn4_P#YES$Dikm==>KZ``7gQna#Tnvz~#?b
z92Sp&d|st^?<?*Ct*|}5?!g#Q8E7KBLK+?zUD3^Y-+}EOg~Y8s*dMvvL4R)FcEPiG
zBJWQ=d7<h$ikg0}A@TRhm_n1cI-zODS>*@U1~d||POC4?U*4qF@Nbp#XBI>b@yl44
zadW+(2OmnudLOa!@>cTY07(P{Ix0#f7y(q34}cm!ZS^V8_#H$;*zpUF2XnP$R;s|~
zb>q<w=GHvazC2thES7cKa2=v2p@?~2Fa6@f9VuD%^uV*l{UYQ9FuG?FwI7#nAk=KX
z7M46g<e;hJq<N*MPVLx4MahbezixT|r^)(7p3IAIB{tc%=crP})jlf5H@1K?dcYv#
z`HoGN?lyo60Y`2hOEKpse*A>PY(QaHAb$;{2>-k)a&8Wwl9U=ul_F7=IBzKAGIMM_
zyC<?eH%JR-N|FcBpXZ#LwTncq_LWF>qh}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$*<FyD)Tq&Q$|
zv=-B9x}8<BAo<1!ytmID_BCiR#TRkt^Wi!BGv|wjYTA}4nE(H~ap+wN*9}SI#wz&!
zzH<Vp_(S7+V*xXHM&tMPQg%2aaHt|@CT4vbC;0#7)-H`*)IZ}NK)8XYmDX(<UBpWj
zu{V%HgBg~3ZxlUg(tZygz3hsiSG(>Nz~Vy3)x=eIW|yJwGlvBDE8Uu|-P{q|3P$8k
z;CoTlEq){v9tOF!zv(A&G>%K<mqR~aYE*^%=f2UfC78irr|aC%Mm@wn_>y^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>8GWT<HViHB7SW
zXs$r=F_#B8G6OoXA0^+fnpFg#;N#JYlPkiOjWvCjy8|xsT6OfJc?ko<dWis@wEIsn
zIVRy<+iR2Vg4lAKZ5w7yQ)a81Y>F3fKOPlgxt2Y;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@<W%x`vxF6YlWN&b!+pj%6DLQ{}*}mfr~6na$IHQ5WHg|s>E`@H<<r-gVT8|
zuwy0)EJ1EiQH1fI3GMyD8hGKDiQQ_(mu&P(fh~8cRp{)MS3Z=>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((ih<kRTpP`cstQv>c%
zQ8aa|hbmIZ5|LI}9nH?SUgy<m0cyIHS8s3~sC^n&YGJISU1Z#tsSXig4I{=*pk-4k
zeG_&8eQqYH4A3-&F4zInX7ryQQ6x^w9gbFow86%G(vpQ0d)a{?smtg3Z$dAP_c%D6
zskA%@7n}r@87l{oJt)_3n*{6v9=;fNmsxIjaerMA(LMBa5t}6{vQ*{}OUPQ?$K*V4
zM)`ntKhyC`VsIiUZGSD}9vv%@hMJ-%<(^=VADbnZkFOfs3FY?;3q%7**=58R22Ml7
zzm}acK->y*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*<o}&<_vF$^DuO9$
zvEMU8OF8}SH{E9)lG6n1<$*$yfW05~QzNE<?u^XpyxaR{maJ6zqk?0TTY07gG~Jbq
zQZ~hQxx(FV^OF~oq!5CbzhSUbBF@nLC*xXrfJ~3r%ra<ZbQD8~&cb35j;OMgU)Kk;
zK4srv5VUMrrbLN*QqqRGsSTc&Tbkrjs?GRYWU~5n9U=RZB;Q<e&BXAw6)Q#}aavQ`
zJG5|=1AXPVsJ=!rBIIw+kxf3W#Mt{14zwE4(?*k7X8Hl1-g1&<2`&P97!Dze#a1J_
zMF;S{f-d9<+-D1X)_&AKxrJRyJ0<qupktOZ5nK7@8;nTnD?jlpT60HX`sQ!bQ^KT}
zxwTxDT|g8#jhPxbTYB&?v&Ma&M0y!$#NEG0e~jYpm-6^X+N$RV0Kf`AH)XjCq3E-p
zh3)25H(2k%3+NNhFb_GQcRcAOTPcyI33D#VfE3b9)K+8@lc!dz=`WCwm~BpEBzZt^
zj(CJMVid}{SHFHG_6Ucb8#40wKO!`qFnRl@bn${R+K$~4_+ybu!n!(#1mQ_LjD7Vl
zuk83rGq{beTjU5jn;DC!Y=t)2X5g?|q6INb8`-E?z{79-K+zL%jRJ&t??Dv_N;AX;
zUwM2=%72t~497E=tcppVz+C$^$yBFQB`vXjaTz8%L=;dzmL`2-1(fFB2Y4!!!-KA&
z;6Qpx+9{Ub)vM;WD!6@V8b!rb=Y?tAy~yl-*|m!9qW)NQVm=b*Gk3WFm%_M}Cf-YL
zxQHTTW~A;<h3BkoY6Bu`Nqv$QIiQmrXPlxn;njN@*i!RdB^j8zxQdIXF$8Ecjz|=*
zsmV-59IcjU`|;q5vGbH7T6EL=y*}si5TZY~0YbA~yF#@{uGcT6HZJcvc#e++o3v3)
z3%bkZIMG7z!vQ1SF3>%vTiqB)pSfxua2h_W+p2fw`?yFfGV%4*^dcz#2|U6#!2P)f
z`>KOayJmPxyR6lkqBRo62hqiTHKRQ1PcW*(rY+fu_`L?DLR3IyiE7DRaEP7nukrdn
zT!s-(L8s8OB7`<S`wghAK>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$yLi<?n*$~
zJfJBdg)qCJy%af*0v$u@$i3u~|D8GG91~&w{LDQi9V@3Gn|yr!>BR`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<xJl2*>&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`y5oq<Yyw&B^!b;%8Hp1W`a?AQ=@w
zm9~4Ej_S$bh)vb*iQX}Gwx3Sq$K8XS>GG)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#Fg<NqCj{U0@@GuVBeaQ@?skZ1Z!
zpFa@kp*i#BXQi$uylvJ2Qu70XSb*P}WgB4_wGX|fNmlp*Wzt9%&YLbWDrSAAwy|Uh
zsX{3<3TIO-c%yc>Q2xB9u>83DLbMQeS0hoqvJCOUgf;yM8DP4C>d+Rnlk_sj8f~;v
zzr38y_LMM1aFZC9Zzcp%Q%Snv!X}LvW2G$Sb90%+5fm#&rGD?{XaI|R3+q4gnCw4B
zmL|j&BpiE(+U^7}#OumWI<W?Vj(o&l{yCJZp3u}7dpH4v1k)}KV}92G%YbF_j32;D
z;nRb~_#t^ojR62&KY-yad%1FelG+vB7z+u26J%R(O1?ZsXYM&oE_MaBzLwb|xXfm|
zwFfRy7(6J8S<e4N0O!Yjy9Rnp@7Tb}lv<%*%ga63&o;@nkj;1MS!*YQMhz%NZ10ma
zb45;Yj}#JTZq~Z|^ZGxOzfo`}1UaF!_vA7jO@sXz{9Fu*wf{7kovqi2(QUT<<JrTG
zlA1Rv%kHNNjBB**mE(cO0aMNDp@cvqSxYvqFP7Y#(b?R`Y!@jNwBlxLqS<;|HRrBV
ziRYg+mOGc)Oi4wvpXiT#HRQl59+R<@-FNj4-<O$ig092Q(5UGOJ|b7kIscN;i({iB
zTY}{Oz6`40MRi>rW%r2i5N`;8Z(R@X?Y80b>19cR>2z|hnPAIy1~?b0-RuSOvn`=r
zV%rxe8nn<2mDdH$ScP6mah75YUq*3^2Lg!-=GU%G#vNNuw^;`4rj9gGLE|yliSZxi
zb9Civbysc2+@}#@^(Hb<?2}ut>h)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|Q4<w=W_vN4fQ`m6jNd;48h0vlLHG)0
zOR$J#hpebjr`<w)Kcs!-+c(skAk^hPu)Cjehrl7q8^vRTsKBw|dI{-<vf@OB-X<c+
zl8e*A16^D6e%C4AlBna$P<(DIT?)>64;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)e3a<MSC2(|&&?HD#B#9kM+$oMf<tj)0ZNq>DT^?<
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+<P#MgX0Xn$h;|#NmgFWq)3dS^8IqYpA2F7sXzpqMI0Vnp}!E422
z^P?&`qbTpE@&1cI{>iPRwt5Wv$H{B<hPa5~kKDeFW9Uzi%a^|;;9lgvR^s+?b_on0
z*v3R0mz7+<725+LJd%da&9Ps%b0m0W5|l<VZLYgC@W)0$S#1>q3t^Lpe{L7696}@v
zN}*nrMs`qs;JEd0ks{T+4ZycA_#{GG{q&j3XHBu!NyGZmRQEzfmsKi%E`&OqNw{%%
zp<L>*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&<K8
zzTo(MSR{b3L)hBo?<`iWarSMOe^Z~BWEa5qw8naiR{pm8sz*5%7+570!b~ImOjG;-
z@V!H<qvo4{d&9xk{r+%Qb7|-y*4MeIDg$UMUp$?wn?}OCeE>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
z<Y;LYJ=uQL#YyWl$!=UPtJp^i_cOK7{Jj1;KEDDISFUKW8_QeT`$~Cw_hr0z2o{oY
zWI9V>BJC5B9>_BS2$Oo(IK`3ofRh5yn%d%GU?74NHaSLQD&e6_q^is})aGP94%?_;
zYTvqV+c<r=DhptW5@65gTu{f6yRU_^IniZ1)WvD?k=!5&CL5hl+ncT7S|q*;tC-K`
zmHOr8x|6h9ER?H^H-(l@_+a!Jf|81JI;IItly^jGv|Se{)%EzB{*J)jh^br;ty4rn
zKqW<Scjx79xmk)wwAIcXs!eE`ie0Ksy?}}p_R;`gL$WvD_H3BUcvW3o%q_SA(Pwh{
z1to5#2HS1Nj3EzTzV;XXv`itl56=gjy%Ox19ev`7aJASP@Go;v1I!+)layh8F@7m$
zFCNrxle;)Nvg1wBOy~8emD0{dttwMuK<JXxq;C8DSQf?~_?V|Rj|zm>kxtfqoJThN
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><V#?JZr!SJzbb)w!oTFZ-x?Xo&BX+E~wlwE<j*pfcI4(EO9iId+m(iJ0#rO9w)7
zrd$qPEt|@$Z{KNro))<DF>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)-<H(!=9cX=U+|%tM;)z%~UA!xwx^t}g
zac-I74~czw8LIMlv4VI2(P;I`-TNofNp7SMAF`}2|1>UeFB2`^?u6Cs($SyWbl!aH
z+7jk$n)FzVu5vPa_vgXW<D2(*JP5aSfI-3j;CN1US@7heX*MlGH;C7TkL}l56XKsz
z^ru|O>1vS{mEc-FRr~+X*i#x{UZ_f9sNcxQKw1s!tQxW7xq}^(9zA3KuR>msFeBZ#
zzY6z<pY`9$k{gXH-t7buVG8XJ{HlN!Z6lp)uar_D8E2U1OD*^n$7?Eso<}aX2_<Vx
z+$Ba|vWSRDS|L*!!jg7$JzayL#dtlfGE;G}-Ao~r-i|U8M*OE@E}y6prSsUO;wH3Y
z=poDEAFTEE?D0!><Ay&Es_8WEr?-k@!ZC!YlrTpuY^G*=*SO9ic8nFlaaJW>?*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<H9zXNpIlfqhq;i+kc|LNdSIIO5)N2E9xB14IL@ev58VDKgH
z4_GGWE9B2{uW#6#VWw;e@B{j3M9(t267Cpv&T$#E6#kJ!9F~*ve*)3xM?x~PR1<Jw
z?+o>@ZE;Ya&8HQYRZb9l#PkkvCn9F=t*DMSUa#wKC<q{O#8hK=Y;ya+ytlI>|1iK|
zBHvK<soEGu+b@tolf&GKR$`(BhSZ4hd49NZ^r0{DBPJ#@<jj0dpy%2Y{1|&W&?ufk
zB_Zv9*fYB}#&J4oHE(e`0Q9!(Wo4V6m)L*3a9KoCokWF3xUinxbG7_xmZD`tRr6Si
zsQ{`Ur!<sttUJ~ByUc~fP*SArD`e0L)ebD983eMl<4}XzolO;{I=a)N{UHPS_b&)?
zOVR=%lTeamqc}vA2?0pLPDlATuo54ZSj?kJ%N_jg&nIdr{@&5vC&723Je+JIhPvI8
zoFEDi;oPogZyh38!;X@<GRz!)>?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>$4<td~flj<D}em)Fn)9yF*2CSEhpjI5Y6_UmB>8MJa<wti1
z36~?X;c5Yh{b!-=+s3Ok&j<QuNG+NdYZ}_BiPRlJ;cP>?uu+*<#-~QP>E4c-%(WD5
z{3G%sLW7z8ft}P#rCg!Xh&{512l_}ski6ZMx7dmUc<XGyRU-bSMBv#tHBD*CPd{VS
zHe!Kr*KV&8%19-y-|1t+$Qz%L`HpLb5v@!2fdqc$ftV;)pJ3|4m&ze-mcLi_8aq>Z
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>;`$<FAu-~`g!IJ=$qvxd^mZo1E}EPj{t0n?HLM=(
z5W=<7Up%5}A*9I{b?yNd+%V2W8ahSFe0Dc^ja|Lzy;FK00P=)332U9_9-Yx37^*CW
z>H13ortW%34+}yQ*;2keEeEIxmiRjcsf#w)sgpL8F@Ba)=QJwC8uq{KEw`U}<h1~6
zf>%h&=+UX{P(MjabcaJohw={q<};9NHy}Y}gH%9<V1-04*Hh&^%&LTY$X)q+-~L*4
z?)WqndpS>1_M_h|i&{7{c)R4x#|nV=vd|%Oh(rA+uE(Y4(mh9$vPHqOx5tp*<afAM
zWBIS}+v}CYG1JK@{z1AAI>d=Q#^fu3!+Vw^Y7s9@l&=Dg?OLJQ%MizBa}#wD?KQ3)
z&qdYI81-U8wpx+PeTXLFW|z1|-;M4tlgoaCf%Utp(ou?k8LD~_7Hn3Bt7<wrxxV6V
zF#>n+1ssF=NO1Ox=BgPGJ-S}lqOYwvQ0qy#81Pe~wQmTVd2<79?@mK=Q;k(2twKfN
zG+*-dfijG~<xLkxM>vF1BbfH>lAm~20gY}L_qFV2gEbcWoNGu{3r{u%91VXC&_Ebw
zE-^f}aPp`LwOeWBjGn;8eT;*g2#!`$2AY4<L+M0BC+~xf4ahuvCx)@ALw}UTSknwZ
z>eeK_-aD?dWfugSp^^|9fmZ;~M-9X&cn?}*<aq%^ui@I|ZQpWERirZM9L3@6R3Pr$
z{(Z5pI+7BUC_WmsF2%g*Bpx%fmImcnQ)kUq;GD0^%4aRNy-4o9Ra~twb%E`oyKE5-
z`~W@VP~=s<ms7@#OK7R4)hBHG8JH0zGBv-{9jjk*r@SS4Y3MAfOaw{SqsYj0E+hH`
zm<%E!Jfc2j&mfEy6t?ij;fE?xY(`m0sCz>z@n~odicGdt7>SE&5Gg{p5`KOIh_qg1
zu2ESlB58Ac(S`)_z8O(r3ax`b6k7yNGC)$XXIfyQ7AiM7(S2!YZE;U16ZK&ids6N2
zVm>z<BHM{3zpjNFcJ7s|WoM!e!9hg!y^bS)2)5FmGHX?~ssrg%Erjmi3hRm$2L9Uv
zqgBTg<sKk4#+qdYEC}#D`i2a!`9iIWU;!`QIi<IKbJj11wUbnHUS=#h*3-*aH+rXf
z-h!Hq*xDfz=`@d-g^vH;w@WE&7pf@K46Fb<K*YaoHs(#&`m9TKhNc7_sQrF4)@Q#4
zm^aOA!ewE?_QOd45o<ED+|U)D!`pctyU&o_HS2@j|D!iiE5fGa62Chk6wa<f5@F!r
z{<*~CMFh1@f;9#}{a$Tgv@VdWQrde<#y)Hm*}4;F8B_f?1|Zd)1aL8*EuqXU5t{t!
zqVv}#eae09WoEC*W3JVo=8gJ<wElDoK3?9NS=_aT`Un%$9U!DcJ!76L^v4K)S|_+f
zE-)7${tb-?zp<$3V;$_|?!2=HXSF5+f`LBh3o$j$cxH$oGOz0BYkvr>o(E>Upq=s}
z)VTh%k3|5l84?v(kxnlJjNQ8D{`@u7U!ct<Q|Hd(SGKaC?>|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<pAQjllkVgu&
zQ@!ZbJ<j)`(daP&)vc)bgKOF7o0P=kVfmMtNAT}3oldYJ8){|=T5GPulUi#!xzLH1
z#R`-RNOav<-!}2B?up+yS@mNR&lS{yUP!gpdW3Ik1Y;AaeJVq*6KUli>=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+%;@0Yq2Xz4WrwgI<oLu*U^}>h6i}0+}D#
z`9WYi4o2#FFktXe<gD2Qe0{jT;Qf1ZMtc3oZlMXj6v>GoZ$EddpGjI;<rToUGTY4B
zIxS@06ox@@3ZTJK2s-4_JIA-72+_e5GeQbFSMj!^R4QvtbUgLcofwy$$1MDE{*qS>
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%<TWKL9V(9x2;YPMbB{$FQa`CV;@d52G1Db>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<CWcC+P;~S36jC^gc3|723=4~<6fY91mV%mH)T=3*VS#1
zOuCEx1AIx>)2%|ym;`1;zo#Yb?)S!$a<YQDFtP3>F+Ubm@8A9VuG39OcJ`%ebp+Dx
zwA^SD2Ome*lmf0#wtA*UGpHWVs0yBZn>jxIS|W~X&&~8rwKHdj8N<Z^1FZYRC?*aV
z)1gIbmgF>JdyDp=qj2+M0ajvZnY7bE4|~jKy-adcO9xm`V-oY8?r*}A+FTIV<W5En
zv%UKZDv+W&ibJ7bQ9m?Y?fj_>9*w^BJW==6f-*M#2-E*9OI~<OD?B<}5Z_lef%KT{
z*exgG)Y>%Ve7VH!KsT#x1U2q?l$Fw=nx=l2M|gsk!eh}7pnd8!|MFbf?L97IfDd9|
zri;ytd?;Q)aH~PVB&lmvA@`eiv8%C^ZFZ|b68|<iKJYWch8ZS{M@9r|YDO4E&ELau
z&M<^>wC<Le(2e%L0Bh~it4z;E;MzGT0Cg+I{>T12YL&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>LXUUe<rjh%T9t2OeI(pv<mj2Enbue(d<0A$Y2N
z(*F6!A0d<HaNS0&3o5CWRy=&PmXE@~0<-v5NMCZy5Mh8hmg0HA7zoiV4ZJdq+o4N=
zU;*ZsL`2+a%j4Vra1IPF?*b4(Xc!|ak)aI$MKfw!@KIe=oOJCX+Vyois+Xw26xs=I
zWh_M??xZF?zmwi4FxxrBl*t0(1zIi9Is~pPx|>CDL1bYE8lrnJk4|VNd^g?V$&irJ
zCe;zBJS*nW75FkBYTcS4RO$rC@znFt4PH?9WLTr!hYdO+G!R`ok#5u*G@2{)k2opV
zqhrZ+Kf<P8VAP+Q8U`cC)w{6*S>2+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$<PDZ`$5NgU|NDpBPap8S
zILhr%55^R1=v5=zpWAnHCnQ_|>G02yk^B#$JEfN-n@m(%D#L=Cil|yCXxHVdY2e-Z
z90iYaR8j~duBynoJR#BmDF4E|o?^@m<O+!GWXugX-&f8q>ichO0a(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#;>m<g>YwI7e_x58Z*5Tpfi4TU*d8o{&Rszj!H{-3%
zB2NhcdLca7I_5jG5m08_4RGM7{WQ#`{S|O$p=jvoO!Q#hXMoM)%B?4h8nA!q8)${5
zClq^s`G#^4zCs6HmF4PMu6<kpwTOnaK7TK%4vn1|nBWWnp<o31G~yMI+{6b>jPkWe
z8%<h-z<WWIm!QxDuH(}C8q4qu%FkJG9TABHYA|aGWL5LWIaKNQneJK4vH$=JDj|~_
zPGOD{Y-@uEK&D5V&^_+FVptPV4IdL#CK9mYaIGjLm^*|3@Xh_L$e8!$n@y)K43+sb
z<<0P6v23aVsZE~LOixkPDuSe#dejN3$y%B=_G6t>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=7c<R%`Zh;;P-k
zwalY@Mf4c^t*vD(5cqk&L(i=<XsH?>TL6`xx80GOA%}S6O~B<VRe5Ty;jpOy!&`et
z32oiV0_`<17;;mC65I&{`^vj?WT~>`%9nfgmE^hGZsnrjfwRjrLjQq=w2WW=FAS_^
zYtmn~(2X~v=9RIHMjdJxqP@iXvF9_1R7=5?rGDS<uk$(F0kj5>V<fY%$%<C|dvC4L
z0uFKA#^ZjHGdL>ST;zL3k&Ze_TkxzvI&bwQAzPh#aTYu6UXA~}bCWIsk#CwhMjj1l
za(xw7FUk>90Qbbpiz;ecpPjqqPg*e7+02jXPn@Mz<|bcQM*&3^994Bek?CrLs<P`+
zivQvo85%~jyrU&wh94aI`z-YYAU+JR;b;HXdW{7VEkT;qk(xHJ;3qpjV9>Tvb}qwD
z-c=w}y3|4DiYlse!y+@+9-@kYr0~z4qVLrL3{qn{aOw%0L|{7!0`|jRQTw`|glS%~
zxM0$?73;$hAJv?P^pP<lS2Jr$VPbj1YRAsaun5u=r#2B@_J!KdD|avW$>HVNp@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~<c^CR9r&(luymQ%Rt
z9QB~<QrHp{yb;;^3|nNbR>&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<Ze8$4r0<ih
z{yE~I33jlFHK`oD@D#A~*IaRwEb2hmf&9PD#kcHkmkN&7r<JF3Fl%&foIAgImiG?e
z1<HClCnM$yq+8IpIblW9HXMF56fW6U72Y_qDhL<Zu~rDrjGJoghw2#|P!wk-$}%2g
zvn9Li+Gm+A^rtQtN<wQ|7ys8EqvL3GTPFDY<9xbPS<h%wz3h@)tRRNaETy_OG>*+I
zu&npGxak0L>W2#Lf2}IXUZ%$y(Z&OL<rVPjnsC(YFOzZBA)6>uuDgYLH_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*<KjI=_=5}YDd`1z4qq|<?jY1%1YA#gG!qsKgBGCe6=kF(na*cm5V%!
zGn9e4DsXUEV^g`34(iKGX70CGpu+2INsG!<1qemEEeUj9dlwnWnydlPbol<T0PZjL
zuJ+u%%mR3t5Tt0DK)W(3X{MP;k<#CtKUt&subI+FD98-!3BX<H-K$!%vIV$|pYrfM
z9|CP9l1d2R*tE6Fk=ln$jhMVNlm|H?;54M`lMVfijq=R7NjCK*hm^@|2nK=^obZR|
z007Ay+TGnafB7JJ?n2<O7#xfvPd28|8jBk%z3}sTHbu{bUnxC}qPE&E>32`kC<f}j
zbJUCxB?~`()^8^8P4qmOzFwU-xg~mqSbW*CpTk$lp!g{tt3TN}eBQemZz;{Wx`c7&
zr5RZX<xc9hP{LiZU|lP7WzV$F8Zik77v?Gr7{Ye9)lvrYoT0fZ7^uL~c*=pleY$6#
zN_i<uiTccBc8YRV`3TQAYP?)6q7+irX8qVcj*z#SQ2(G9c@%}6Vbw(ZUaA3to&6)?
zCS8m8iJ8Am>kn^MSc1PakhWs$gGR<ue{QQ#Z>xG`#LK8<Y8IH+y?|*^O#!2x6ez)u
z%{xt9dy(&^03x{!JaKt|{DI9pl%Lc{Dimtvi!Hv87>zBHIx0g1bZel4bz9fSXLAd{
zZaK~iZ$*82EA1Yz1_pmZiZFB<QMG^=AA3@wXe-dI{v7gHP^{Vba!#=@aV9%856NNF
z5;e^DltD+mAK_|}dH}2GpG^usalxHPYn9mgYG$+wQ6TX5@5~zj@j!Qky|6aYaa7XX
z7K#QEC*EdDwxhj^;l%1>+%5^Wo_rF5Pf0iZFA|67!z$VN%P1oqG4D3|4TpKND(>qn
zeV1<iORYI^q;y9~Fmh|LX@2sJXo_^NWQV3w+rw!t{<8=+Z7GcyvHZmH{S^d^Y9IzA
zvRSt<py|(n+If%}HCJ|iY*6&45_b|9yp5`sSVy}<YGqONHV@R&ytbaTkE&peC8u)I
zZU31BtWjKp!5Go?z^Lq^=AgSL*`6O?syxP4A?FGE!nFDIfk*|kqe8W|T+s%%fh^7K
z!TtC(0QwV#W8srJAv?kQpKZkWr^|6VuNyPU^R9>uXmB6k9o%$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+lpo<?$KqEa!$$-wXI`1K6wiCj1G$kY&B+vkUET>Sl0Jk
z3itcp63lS8Euog$6B%iPLgq;RrfYZl(v8R3h$n!9ox_ykl4;nV3L4<y6T-5hc7QF2
zS|Bsy*CP|1^@gCC6gCUCIa@bvU$>6TijM^hQ5J(!ZNAUTIXy=<hBLNr9O#?xYIOWE
zsh$|8PRkUv2OH5;c`{;!h7*hX22Ziv^wP&nOO?|B8{ZUdN07|eH?zR|tN8e@jp}z!
zCh0!*AJzx%?NU|8>(W7{q}))~z0j?1M*6dg7}TU)=67^X?6&P1-6iX|Y^6}C<I+nm
z)EM3wREWoUe5>Wg95be3d%~=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<E(;oWl^B?=6jeswCkW2GlHZn;^pvZT!3Qz<9l`fUo
zCkX4k$+4J9qwI&LBRf#--6|C$rf7lNa+}t5TMeaD{aDi5whU=JRkX#RpVg(~Sn2J!
z2!C?Ej$wQld6+|{M)RUOCe9E8wd9nD`<vYlz5h#oN(XwX2I^w;mh(K9v&Ce5nAKqU
zOq2caY9BQ|L5X}w$mW*qSq#yKcb~sebP2O}>~U)1)XWTpT2bsh*ss<b<Cc4&yI;KR
zwbC`!j5Aexa1^1eOXAEszAQL_?WS};oUv0>-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^C18z<N}<UGwp
z0)91JkAysY{uTY?&Nojp5Wa>naS*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^j<N
zxSd*8YN%y$Wo<JXJ|t#TE$dP?A6jIaWz0r6*f0dSJCd4bKxre8_EEgh1Q&KrU0PCq
ztaAq5Td3_Jv?Uk8>EQa`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#Ozo<wTbyZ;M?(lVT`+#VB^lE^FPJD{4BsV{x!lOMGYrH$J86$M@
zp@q%~HVoX@o!r!67>s5xVpC$OPCqH7ZH}!jojYq{Dzx$7N+b8x<8MctlaYm*dHh@X
z5IWejY;FG`c&A+#%sBg0GOXTvwo)Rp6S+Kw_Zgm%DJw&Ct<t8?7ZqEO5uhrGL2)K>
zO5#5g4T+e@AjY4c3L=U-d`kfKTUWvPNqT-4W%8d%lPvXYc3dxSDI7EmiScV9(T3iL
zRs>lrE)%jllUi7{0>B?v05{^6a_ZvfRwZsa)8rGi56IQdBqiK2s<2VA4opQt2RqQU
zWDskhGr)`l<F>zp->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
zb<FTSZ%Sl1wJ%jOtK}~K{;f=B8_i<WY>6Mq+$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=Xg<nkl#*{16Cl;E&
zDX@M}2KXzDe82;*u2M?7^+Q=ycl66)vx)Uyd9QK26qP1G)FzDXZbd+mTs5tjl5D#%
z;0M7F!%kq#>nUR!$hfRoUHt2{i?B@$dbx0?6Ja2X$3_y<w@t%XNq`9cX%-ylo}4ew
zen7<_$J-IKVAADYC5XxA*pfa2p+hR2LX4&=y1S@N{eeXyzHCoy7cpu|J7fAZ0&twn
zo?J0d<o#hmf=6eQ&c~Sgq}_xo3rZGnv09mr3|H1~=VUW=OSa=@)t8)N0fvoV)`6s5
z>giO!WQMO&aPYgN!zE17+@UlUj4!lWv09C$K2VNj;NBh{3=vZ@#x|R&-bU!Q76W#T
zg>Lf)ZS-CT{Oe%UX<yK#q8E32-|Fu*2LaH9?*J&{yS8~>Dzn4LM5q4iFI3S<_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_?5<VI%8sPN!$R`zo?g2?V@Jtx9TXn
zf8hx<%{@Xkxy!J#cI#yW4QG2b9W^TGi4G?5sYqut9LZsXQ&`68)npi{#EW--?0ACZ
zCFPc~ft!wD@6;nXpPAXSv#AU{!))QbaEK7PD_YubgM>gt52m7lV%#rD<keaK5!C&{
z*zt`zs0P?@cfjW9zIs+;$694<nnu?V?_cAb8;tM-x-r=0`lPrgY_KNcH^m<AYWo)`
zU~uE!q+i#sUoeWdS83uvCK|$5ntq8V({-O3Iff*{%|+_@A_YTPBDv~IyncPFy@OW=
zYIhwV<~T7Cw|#Lt{oI23Ro^YxSafxhliymDWp_7KRn#%nhmcdNXI1n2XLU+Ru=Eu}
zB(E4e;Y6S%^s9Ep?E@FgBIIfHtZ;n)#xYi=irb*J;7I9g4~YmD>7px??3uq1hnB8~
z3^k-36+f<;m_W(VfFjfT(Ry8zegqDN`O}HLMziE~!;4FzNhZrw7yZM)&)J2X2}{<I
zvL$u$1hckVYHo4;W77DzeAIHjB7OxV-Juhgi9(nkfgo=Ht1~K$zB^=Dtw9x8GOANf
z)L_FA()Z4Ty4sy^l(D5zVLb3MQc_Zyg}zLB0~NNOv*xp(&a6On)NH%UO@P)<4W;~z
zj<*F78Y1dTYV3%LP5gR+TNzN~o<J9?2y+)Ns|3r?{Gtz}Wp0S18PbC<_bvC<p8Wa7
z)<?EAG~KQ-n8&5E;&!LJ9j<WQbpMSM##-Zyo6E4*k1v~_s+##1H;DS4SDw;g3@z!H
zxXC8V92FfZI7VO6kZbE5hPrdSR~!A+-&NdH#=WBO3;x62sa08SRsln#qtjMLdY2?a
zc$#U-1ppl{w2vo<Uo-B8+X6k9?P`U<g0upWi#z=vq~a53VB&kD5cD}bXwwZUQw;!P
zShF<t^p$K{Ra`VE;-_!fFPkO}zSg%mK=g9<YqX}{#2F;>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?te<H**@5&J+2u
zMkU>1|FKNv<HXy2b$@!NVhk$Gf%v8xmN?<xFfJwjY}LQ1bqC9-l_+qI4YYy8^?EIm
z3hmIH5~gD(2XKg$NNO1YYDA=*7rj~0M+I-rv6*)>^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)<I5P(>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@xI<?bajD<9vUuhbZmz37V25B!K_%ny7I$FShf+I
zu^Sakc$Xc(cHxXp)JNs6McSAA3N-3>y+2PuY2$4PqY)fEgFh*>BnS44bYvKIz9Bom
z|GiS3IGxq^S46-ftG$sV&TPHYwCFz}-D)3-hqO)b5oY%u9|#85FL<WkGv*V3adwtM
zTL}TfZlxySQytu=LEyEmA4M8n(E}Lmq41^$kb#2%OS5?~Y;XJdez&UcNDDvODa<G(
zMLrcNr6Jp~T*B~i8?pVm=fK(`n*rkx`G<U*F8X~<^9|c0|J-W#qy&DGxr>kv0^oy0
z$EuvDeJ9tDDQG_%AaJN>K4ofZ6?tBa9AQ@2ABPyFw&#tyZD5&@q5^~o*{>xwEp|>z
zl)<?g%?pYl1B>+!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?AJlgqX0<p((MsqKrpkMSiHaR;
zS$a3gyCENmh6t{j$lFX~H2xiU%HI@wC&}*|Rlcg1^YTWL#a937Mf8E50YF7JGBFBM
zEI+H=JfOQ0_;|~LV`E!J(BhQ%NZ6GZly-Uz>gHZ$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<0EC9R<Dn+1>YOWHh9m
z&jx|b69Osine22RP#-@l-d8#rwZydhqNp9A-Zr$tayik^fy7nCt-`ZP+#-<wH0eYt
zrXefJ*K{rP>#@?c+j$Q!5KyeI6tW>2dGVwPGh@4fHZ_A*J)r(3x@wDz>)n|+av{AW
znRyG7ah9BPqJ``=I<wwLYrZ29fPF={ySSP!-vwz3;KJ0%m<bAb_L?kNtGN0%>g14A
z8WZ`Qn~iRwU%pBH4(Y7Rv0)|c<Jfk2v60Q<<8#DHMc%)Vm5R^cxh0i$nJ#$;y7(&`
zsikTF_cBX6*zp^yO*<|<bZ!Ba=BHn%Qp$)Ykiq}Lor_BcleQ8rw>F!+)SZL?g<YL5
zZ81YYy^*0%Hc{iM$Vm|4_a;Bg0P#TR=v#+Bmg6$(m)ON~&@al(C1hhTM%MxQt){=*
zOu6Y*ORr%m$f?!SQbxe7Vxf;3{G##y$imCH=+oIXEkaz4$N`wJIpCma^ANv-Q<72r
zXx-3lH}cA+rrK`e2Wa>{c@q{zcbBtlGESB1fa9}&+8m@#Qpv?xgtqFF1ziF7ty?Dj
z{I1B@30p0<e_m`g1&_@bfinkgpl)?wvVhAa&vl?H>@~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@VRF<FH&}Htj}>n}eoin6={u~{{()cEIHnNRHO>!?
zo(a<V*{AYUKu7Tj8osiTtrIcqH3+!P31gUI#uN3|L(s@<X>3WHsx|oeZ(AkD#$JDr
zqdRtY58A`;h6!Ll1U(n=+f=T9eG(B(0HirZsR$ojej8pPT5|G32CQ>K;&00^SQ59v
zwUBuif*L~Qa?7e0e76L*ul;V=F3(|<zPajRQJbU{_1wb96{lRICfii1k`*a;@lIl9
z&wdaKW|QZss98uFaRDAU0A2p#QcqE%Y=b;{IBd#BX@_e2Lkvw?_Y!&hktsmr;ju0_
zW_ICI9K#5XaXRy!mDoI1+)T)ZSPJQu-rsn+q4}YoUqs@(p-x*0rx&bhdYBZr_Wq<$
zuFIQBxUvC#ISNt?zMZr=sn@=m`b~l(PH=x;inaeW1tvKlwvs?A!XP4^Pa%4F?RIlw
zT*@z>AOyjSlNTh{Kom?Mcyp(2CW=;Tke059HB<*@zf4@z;Yx@I)lA*ccM<B{f8Wqc
zBCA3pLvyTopRmLbPKKgRO}2{uZV2F?xM7?Cn+736sRMYIa!I|GYDGXO24_k8KH35-
zI2}jgE<ai>gj$)GK1f_xEID|Ui$Y;bsbWQoq;kpSTwcSTgPbn|0FWJC>^2I(eB29p
zVRyP{EVOU~<rR((j*Xooae?Z%yZu7H_uId<&ASaxcK^jxs2t~-{ne<yQ>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&2<IJZF!YO9bjc5)kPsd+>J+7u0ag8K@kEeC2;ZMg
z@>yT1EXfK9K&Uj+VdXxyQ5}8?$6uoJO;NN2t#k_io&+~r+QPpdR0*~yNLaIEDW6*j
z0yDRDb$Lp*s10MsP_yB1{<yG2;>*{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(L2W<DFefVjOi(I7nHbOnFVe~|J_cb)Zo>y_U~WB6*O{)@g26Q=kDi&#
zE|SeQ&d$+O_%}K_>rnlE>%0W21|9zD2xN@{|CD$GMI~I#95sEU6>K?<F4xV$f-GP<
zkGS`8HyH7#qZ%(QF=j-1_EvA@E40dk+c!6+cu!vi*}I&4PJBZ>JooEOxX1*~Eo(sI
zhUb>fFQ#RFVN|PH%S80plf|Xi+b47!z=h?SCNj-;H*A_+m!c%U!S7<q^(`2Nv5rwC
zN9X3Z8`v4sg=0Jmlf9OKoXj151|~CX)uh9DOGL#+O7J~KKtAq+r^&K3@C^3-vwJ3R
zNe_Ar+O_}$fw2XLq(6x7y}VIeeTsVGF}Ro5Xct9_@qqu8&Kr&4qZ0Ya?2MV<2M+X+
zk##pUTwP>ge01H>%L5q<Drbu8>z2L3w5M?((;NLou*G)uav#*0$wB$e{%j?nrW@<F
zrM;||BiDC#$30>o#iS7fa+&J_Gu`Wbtj6Z9ffK@F8hdidvPmMeIzcE2<KW>8ZeQN^
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
z<GdHGb4g~I@q4#L!MoWkapJJmXt#N@i)9;?u86bTzsL?dMskKk$RGFOieDOBMj3(m
zXyoHympE23?PuJ{B>q>g-@F1iS=He5)ralNmz@!bCN=|vW#D0{;`2^oIJ<(@oJqC`
zWOq>Sf~UkLD95kNTryS>KkDFI&r_<t+LcA?R#x-(Aw6jf&V1>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<yXr2EcKXi$`wmd?Hudx8
zirUj_hGnvUIcQJ550uO=J&rK4ksZp_=V*#pRZ3*5{^X>(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|St<Vc9D$VgE*?#Y{!{_+G&fWQ=i
zg6Z0=_O9w(YS#F;st`B<1<`I^H8sMxcy!8&w#XSx-^%^8mqs@#%vLGPePJ@JtBvif
zqns(;Hgl-q0>Am&GdGMRVIs(prZ1ZRodx&x%xM7i>m}g^j}x>$4{8suKo4As&~g!S
zVsRD|Oer<c7=iT_+8iZ65eRfa^!No>$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<c@#wkvp-yI>$>2qc_u`3-rgc9;*`3sX?WF9d=hZ`j(cz*C
zXl3xEHvye_q%s<WK8e$*H{Oa4GEg5dj)lOi-^|eXn1-S)h7Z6Li9s@Rth7Pb30@gx
z-Fer?;$IKlQOsYDcn<>j=1@(<3lFAKJ5L+lDBRhn()Ki{S~qOF^%vzucOfcno>q-+
zm+_*I1ZlFe-rW(C<L%|26Y4X)$Irv{T8icZu(rqVXJ*>Ub>wIlNSQut2)bkGb_IFM
zin|!P#2`L<WCmx^HK^`oAJ;pXAJVb(?>C%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<l+;Ka$8GLHBmk?kV|5S+#0LWKZ@)mvS4~_1wKV^N;86w
zuNXwt-&t1RN+8>>cFG+Tzf|7QNji2zGlP<ei2!cBpZ2??MZ<Chp%yGIqPxhHyt{!I
z{Vq(-3xCl9Fs{t%8~%FO_pA^spcTj))&PP4MM3BK`hkOLae-)wE%3nm;SO{c1h5d_
z5z8($_cJgZpcnH(NSHay1Si)#U@z2>Pgm7ilFGZvPhmHxhzGsoNKr`ab(af#N=J(%
z2Uv7Be>P+vtvK0dYj<L3IFa5Mnc=E=uKO}YIQd3X??)07*%6-8#&fB8<)nsfY#ak1
z*I1q7^GeGeCjeC-8bCQt6spk*=Rr<s9dl89?j#^D(u4I}?DN|&=oz;z1cu(L3dLa~
zNgAk2F!|_)3*u{{In!cuA}PC9BDPY`rH{z~(=18Q7rf7{U=msKnZZ|&J=rcn1rNkj
zU>K7<a?>n8Ry9;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@R<v`wo=<n
zSJoXt<#{Q}FuMxq&J7jh1126`<4auFjBr|(8|EE1eb9Qb%mIdLZUSASc6KmEm_!H<
zY$0Y)`lX&XJLx{tUz-3>KM~lTTlhvP*kDK?`844z_(;uHNtTi!fy_ZT!92jRq*hjg
z2wL}5ZE?(4+5>Fhfo6;<oGw03V2Zr>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<Zi>*sbwA1@
zIW^qEdgTd5c;pN5NPiDJ^SHF}lM72Srd2V;?`m9BTYI?K&ig;Lj_CYQq+4J<K*_#`
z#>EY4z29dTsL)@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<U~z0Clr*Hex%l@@@=f1
zO9QWVnUKwi*YX%)<sIQK8O6lRG4^cD!?s=(L>%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~`#u<E@$~{uE@I!KYmIM{Uxe(cxFDJor7?S(*<P(0k^YC}O+q6H6<`
zZ^je&J!46k2GAkX+vEdNYdYa0vT|~A+rc2?eCO@n4-KoqNgmhd@NO=O;3C68h+7Yd
zz~_lK%7l|~hwYW%EGDnUfXPxs3ME=e8WNZJ_~idEl}$o4V&oAzPVhAUd*&ANq${wG
zf()EduL9+AuSU{o+v|`*_>jEiW4wC?HF03F<kIV>E|#_*=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@<x?9J
zcA8PB!Ye@kwo8-!3z?Tsj@=En&f}t>yT4y+OJ@q0K2G~yKgb{7R^PHxny_;Av;o~!
z5%XoxCR($qPVq1+(qZq3U<8<kEYVk#qRZIYX5nst@Ao%F55WUKBc=hDmZl;A3O+dJ
zM%Wjlc(Fj<;7NXsB*e^rx1+Jr`g1E%CKc1g{xCs*>SGQYY$x4N(KXr3s?%xpWFqcH
z@Vq+EYoeFgNo^v}djIR0KCdrc*x5c*g1vtkvbPJ~5ArDK441Abm><;r2js5jR;#~y
zaB;FrmJ?-t<T<@*PM-C>o2O8lI(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=x<wFRB@+SUU7b?YJXs`rE>l!5oUw3$hMhKo4E
zjdbtmM)L!SX(>3K_Q0*w>=I+(EkOPVo@K6=*=A>-%_Qry4(Br#b=L^R#_KGkRUC1e
zieea#$({d`hEO<x2#pe=4!I$aae;%yRgW$dol89JcqUEPU~L{$#2!csL?(iTn=wou
zQJ*aZ#V6OJ>aa1wLJv)P@(1*JR?=hg2!FEelPc!Q*_?tUFgqM&SnJXI^of~X47Ix>
z3^O=KFB*xdq+Y~+!GTWHhw!&uz$x~%sp<&yw<=mOAC^}AaiBDV%|jjkj+P&A<dt4C
znxy+6#XWcRBZoh|T_OgoEm3M!0~RBatOCbOABa<P8eB$vQEoW<PV-3DAeFexfNfiJ
zrqE{8wgOv(xb5$*>X=*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&q<iNZ;lH&|ZTzZJ{iUH@(9uYgu+%icHUJ
zWkElPh3$?%!h0=A&z<`a!SVl!w>H=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>{F<n|4IRr^l?IvFLz;*2(jOO<
zFKx{V0c2|$rUBE&{g|QSh2d<S;=#bCahZP*>CI4%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<HnR@OCI!D;&h(&m-Dn
z+$*#&Okq;7G76Thlg?)u3xnoiDcOPjyXU*hv^F{2d6^;;o;_AnF1#zeu!3?|ql?~c
zdemoF=#Ui|)n9960LaXt$=1Z30!Yq~bR%64h=7#V&ME!Z<ShE~hbijH9Sh?*d=d}B
zu9Bp?`YtA1=G5T-b$gH%SEbofnZC@>+%2M3#=Bd$eaPKUANs|^VY<PL|Kr56c6Udv
z%A+%ebzva%pnNN>$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+<Nz}cV3T6~xjkQ_F&uhn#J
z_zgxvmtbA30AwFs@vDU;jMDQ!p|QmlCC*E!q*e1CK;f=&cv<YE<&CkIIdY?r?rVj$
zIcLhX#HBlLvzT={HS%Q8zpPeAzmGoApnn`%&u<~6jgiKUofdQ<L*qIAs-1M|J@?|K
zCsidF+?~WdU0PPh56{~71U~1S*!ZDm|8Tq`v<S@Rp?m@Sq^IEy`=ahP=v(DfBbegS
zW)rXf<)AgmAH)rWzoObGd?25ImvvjjH#ljD&SOw&KaR_0aai0*YmI_#RN<_swJaon
z!tzmk!0?~2blrSc5d=l}UoExmlLS^7%$4cN!+Hjs1$$mOckl_>pZeCA`LOl#v6zXc
zt`00FuTWp|MnPs%=m@tlx{6r$#T%TxN%ZxR6h<i`ACZq2#TYb;TzyeHhRCLfts4d=
z?x8B=a}Q>`TSn>`_M>4JIcpF}*zx}VJ9=MApS@EL&tvIf@}z?n7F410X3!e8d`)*c
zw@>`5Iu6iqZ70!C+HSsKvhZur6zflpwH~_>ta#P*@@UixFOLb-IG)eaA}p&7JE>#R
zJVyx<l*A!KwWqHJ@@1oCS?lopLg+<8swCG{k-L0$0+al9yh$daQdv$P%%1iaa9w~K
zEu`e;bk!p;AApD2cwQ0x5U1pi<fOy;$hcXH^2(C4vHI-?y&g!}ybt}nhifW~@~Pg1
z>lLFk6?|q4mxC8y5VC0DG>0~1q<x}^L<m+x?xnfIf~yS!+RGBR6oIsn<}|dP+@Y3y
z!$kIw>0K2ih61_0iRmFhSlsh)m|7+20lYRLcp#W=sD2sHki<(X25Hj`OZtV2wX>?-
zri9z3=*L;f<iEn!HCdh##<Sk1JwsMQLh~Y;6}68%jWr8)#yBN3HIM32!A9H3M<TJ`
z5|mzmpYB)VHN3a(1H`b3so8YE5<}Yo_Q5MS-GLEMbE}xO9o=T9c{mg<Ng#Z5ej^(e
zZZO1hAh_VFgXwr7wVz}eVPTI|BIi7p76*qPwKZYb8vZ?g&uJ9dWzoQY6Yf_e^6|)X
zh*koCuO9@e2EK=@ZR{8J&yYE{uhFxZRZ1on7r1$s;>><O>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~Bl<cR`3Y~B>q(5#wJ#Mv7%WlNUk<a<$8)2aH1HJ@L
za}6(hvaJ^)#EJ3RxE%EY(Q~>dR7@8ueC;y4-Q6)bmcl^bX`*e_JC8~%cDCRQ<XpP1
zZh2`dktaXf%ro!->zLJ*8o>9H1Td3JuV#<qCK*3q(nvV+{-h$M0t(PIn*zA}`Jl5!
zIw#j`J}^k<vxQ_Fshe)U!e_C}iWa>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;<g@W4(
zn+o(}sLaH=5xPTPknm~@I6d3l+1VVzIf~@sA-j&oeW|GM15W^_LwcyVw#WAI{KJ4=
zT9)D%<n=I6%X1>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@@T<?dk!j8)QP(T%UK}S-K5)4oyQkK9O@YJ`79I&g!32QpRk!c1#
zkKHVp->c6%95k4S9)TE)a)TX$_MxBqoZuDBNKdkK+&HM_OUsXPg1F%qy1nb*lOSbp
z=t5UdqW<jERvEelOz_Gxg+gvn#;_kXasI17qgm$Tf%-q~4|}CS6lL7Eypa07s0oul
zabiPzQvOC~9G#W83)q9>Wg|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{B<njzIKYPJ(+jH`39~Wrr~Ct9<tFjj)rOKA0){J*?8P6TOJxP-Y?8MPP4Ka
zw5*iv!$S-komp8>snk{GK%VZD8ZshQp`D^8pdibA@pk9iSQ09A38v<k4)7tVlFL|Z
zAoM1$wDRtw>c3vy0WCa2&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&<E!pf9=6Sos9D|+z|rgbF+w!sufa2W%XDx1DH&tw#U
zs@`Y3DtK*?w#P%1V)waA)1cy*_2rS&t9=-O2*P{<SseU?&VSJ^7iv#W-hbtY)(`d$
z1S0@e*u3sL6Oa8=$<<m{i#g^Y%~Aj%)47B0bO)=Y&vpiV^Q6$pDjQu10utN(y6yb`
z({|kRw8i+0u|)H3I_#Cri`gi}M-V@i%iM32WgKR0IpMOAx<1-n4_%#8%&wRAj{CfP
z##Umv%Rg6lP4oaXT6MZhCb9%k_Cy>gwF>aaXWu#>!*7Q8(#}pVvUf-lCU0%@Nh>b=
z`41!!P0FJy{BSUUj44xDttg|gu<d{T)6Tf@?~xL3z_N?QA@ZW?i-60lX!~q-&Hmq$
zv?x#HhtEo7Ek|D;xWS&STQ#q3kjqhu+vyU7;=}Rf{@4H|#va6gqT@;+0UQ7W=&69{
z8qP2o9X$OS!z#Dism$l%`i>7s52I~h^Vjb-;<RJ3xOWMGsUd|09<^&^&oDgxp^V=m
zyP#d_$JMg{sUCcAE<#x?=t;ucSoLa@_*Buc?kpe3C48b(EHMvoZTyYSbJIe5htf>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<x2tNzOQB8
zN7TSnE^6$EjIrBmAyoC!cI*zu+#&gA-?MN5Lv^~b^&#^`IbiP<1~^YPHy^O8<IB)X
z!|hf9#y!LO(|oWoP9pUh0QR<7XirX+hSD!eO3V_bcVb?T+WBlK5>!>!5wFK>W4X~`
zvf#MqEE05Z7Ru(m+dZjsPH>u}GYtSFsV{5ubJKXE=dYMMz#nQH<-xgsEP<6na*d{o
zhG(4d^H~lfR5^OIwAEGan&BQ$U;O5Jf5hPgT>zGaWGLf=t<Dd}5T6I<$kc;4-4rwe
z)8{Ond(K--;vvQI%WX>2L;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`+<H)BxU2o3}9ymw9{FdmM#X>N`OK5hl;X*v`2BU+xCO)EMw5TiUvsG>@^wv{40$
z(4G-|91BV3%G%^QBj6<o!$ZzUzdn+pW}{@t2nyB5e0=*6%^`H13yN`yWPtaK9AzVq
zEd$37g}rI`4Q!t-D@hMoWK}q_klvR#;0$Qgr)Z}20#n&P6GyoZPY;NmKW8J(%782L
zEKyhMem!Rgnw&GARk)PptBWl*H=lSb;U6Rcz1mQQ?Azq6n$4}>9}N{+W^AiZGVWMp
z@g3${!fDegha+7BIiAtJ2aoAzXqm}$6m0MAImGpNWB=$yQ+<sYS3qQcPUyDreQ8Xg
z%_1Z{b1_A|uxDS(Cf62p>a5Q?MpHIsEyHHA$wL0!gs{2M(a1dFYB@2uU8wTB96+*a
zTMZsAXsd3QZ4USL;KpI60tik#{dlUTklB`Rb-+8pf%<Ui1?v(erH|)%_R3$+LzA9@
z5{l^}Gm`WU)grB=J+p%;HH>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`-<r)n?->dV
z{DH9O&RP2dKE21uYz_Y0Rt5BUTcpxiN;FvSca?}1f0`7kW32NM{PO6<0zO*Meh(1K
zNM>uIEsh4}N#f2Dnv8L~?af&4%@jC3c;Z<o&>_2sT$h2OP)}|?$7u+<ey-Wa=Yz%~
zcS{J^H<9TX*ImM*vut#o2@2!p;uwB`L+h+;=F<P{iCXly3N`Uq&}uoe@65s|uqqvg
zqhxU=Y=KoG$dypNDqY#TvzJ@ObfGpFNKj|jgZwj0I`-AtIM%ehd0dO_iyV5zy^a%0
zmb*CpXR^ku!2h+K!8B)S>`O3Bf%SsKW%sy3v{E3(#8PJ1YZ(IG5Z8H+Jc9J%0=ZtG
zlg;d19CtUzNQbcs@iH5gL`n@UU%1YR%v|G&Sg~A%K+AkieNH~A<oVkS`j<UVay5Jo
zNhJyqg*PU-aEYXbVCcQ6I<RnKz$KTYy>%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)(`;<LVc*zMUGjw<6gq`BhPZjqrz>tu{8>=|~pNERac=M6>JS-M<qUoprU2j_Z@n
z8&BS2#bb+s<SV`>cBMC8kIo81E*~JgzD#3eH%w1T(@Gw9rC8{sC#gBP-&x!!-c9%@
z)%Exu_K#k-k6cg^e0y`P<cp8Uq(~YZX$w#FIo91Bilw?MtD9VHEKh$`K2p|bHfq0_
z4yqR&scEN@=qy{En;4=ZQXWviyLnTK*e#Ka?$%rLu!n**GzFk}er@~wqBa?Q->x$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^fug<hIv4J6B|yVZbu4MQh8UEqGg%&tRUjFjVg@w(Slq+42=_{b*;XN
z@i5tczHFQjwC=W@ZKmrpMN&|ncFj4G_tfpF`vmU6=lN^0eH_r)%0Xrk1%h#+z9tF|
z;d0BXz@?P9c;D3%Z6lLmDFyQZDgngSzWF%l9@55rQAcW5!Z#XLbv8Xgw+GUr-85vG
zqaEQYl@~wyEjtKndCCihR(Wixr<Zum7C1r+8OsRiJX8lJ`QdoOMb23f&E;hlq$I7d
zcA&E7683USA6FoS<X3FNF)3JVP*q~izwnomc7c22OEYU7kCgX_yJf;uDW-(ms{*d&
z-KtG6|MC(UqW?t~F(m&|-N*-cR_7X?)$SGiB=p*Hdc^+g36$HaEOL%oM94f0{xm>s
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+$rN<kATGggG<>2e!n;)@&*$twlhu4M8L&V9YU{Iz*hL?ziw9RV7IV=(){Pfw?e
z@o>&Jf3`84=?)3hWE|X~1D>9?_L-!!ZHWwsCft|I@Y=?GkN2Zy*r8h0VaBc4zYObf
z!tazmP#~jv<CAcC#e>nKX1ZA-Y3OA7MH6LZV-Rv*mUatAfk+rzi>SPR;AXttGu)UI
zSkeZMW7s;<pcfWfX`D)kWy64(xgE8mr4<kK)YjE8V4<UDW5Uur(7xYj;*tKxmh}bt
z$rPG3eo?$wT%v0TTRzbZov*ZP9JiS<c5i$+C7a!?qDx`VHTo$~ohn#k<BEQi{iH^x
z@l+<)&xcpYgx8^MB*Ld4KkD*>=5_zI)=Bd2o_roV*EMIw62H<VR;qVnDd~K5{ccoX
zOKm-dcuFbUZF{s@d5B-k1gbIb@vDbi#XK8yM`3Wx2ox{nR<5jZgJYxE*9B|AXWDHb
z--`02>E==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*7<deR%$t_!1bBdNM{zD2lezi0%kY?B9M+m4O2apLICZlJz}&_as9
zVbCXTw;^K~E?9ekImALKQapAvtn!&J*SuB=FBC}7MzzcJBC;y<RmbaYytk+l`QzMc
zc~VNOaHdJ7qsQvpqU6H;gV(y|xncY<JB>cwS6hQt+4B}2*~A;3NKi9teRcF?W0evn
z4YA2L`8dx1VjT5dQ`Uh>I&heEvj+UNQ<wBQC;&NG<LQlwFQ-DBbc8zXSbEc+L*AJ#
z4J;>K0=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~pSyMG<XMl>BjBActnnlW9G(nvi#VwVs4?JwTdb+3*qywNlq+<B_>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?LgIaU7<L@fk
zB0?if8UtIlmjRDE6=qVq1+F?x)hE)7DKspN+7V|t+fKI#5uKqveZ>lk$A~`Z=2)6r
zI95_VT1zz)BbGavm_3${so=+1RwbA=Le)>20{C%TSBIj|dODK_BsT$!{Y3<T7b7bT
z8uq7dAp)qyEz%rS+XB2<f7~xYH9>tVW3r+=t&y%pl0&#7XcS>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!<EnYcHpHo0%fvbHG?`{e`=nVO-Hc;_;vi$P;xblCv_NG*=&BB*?_LTN;3
z`n3?T-?xQ_W-av!n3a=Knh4|iI@4G{zVcm~j+$tu0Aw@j{;-5C1^PcEHlEWsr(G~C
z%0{g^6)GZl-pqtm=z>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$<!OI=pQ++H>G-xGQ|O(fBIY
zh%$8F<eR(VI6!xlZNl6hB?;lSH+Vi5&KiG6c<3YOz1PZn^{<<Crn8`C>Me_BH42~v
zN5C(!sT6MZJXtcfN2Ar<bCQNU+|IaXB>Fv8*efSKp@6zI4?ci5q6(etQ+f%Tj^jV!
zM<SUK@~PNWXHt>4Nu?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+<Zikr_J(Dm+ZOz7aox+MBmd0m{>Gw?GJ#S
z{m(1UKbp|Kw#fax%xTM{e?bhf3}0EFb@bNsVJ*NRh+{!}w{Fk8$oA=V<SJ=>U8@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&IW<d05i0)H1%|(o;$HS&=Y~>HBwaOO>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)#<QVxbC^@1LkO{KL3{kg
zhbH|+<SXPO(nxV#-%iKtStI;hjeo_9$OY$PJmV}R;QKLkOhhWO_~eWKqSfkzF8)?O
zb?V0-U!&uFCcEIpuX*JbGzNH$enRN?(rr#ZWL#3n9M2o%NKeQ>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<O5`e&mvKuL)aE6?PQnFc*Ab!xGt19aR
ztSV?1hg0Z!wU;>&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@!R<YYr|A{;?NN>C)0Bau;XKA8lobZEI?bm*dN}%
zKqEV?)tvlN770~8<KLo{xsZGhY$lQD!*=0iXP*9D337u<s1y~Z&1Un>Ado|MC9$hZ
zukin9_ETlWJFlGE1s}uX*SQv7f>*%hqAay#HIvZJd|7<I6aFjU@wieJ6v_Gj3@GvF
zWpMP-0Rq$)(UKq9N0UXS(R)3QbzGR`UmgOBf2a3*OtJ1=c!naoS2%v>uPlEKsZBm3
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$
zsvM<k;l~6T8M$AHn`5BD3PE=IGyn=Z8p(~<6X^?;HK;&#syJfsZfol<->j2jtc#Fh
zL`ZQ1@mQe=zb4oB6w1rWq3@bN&GcjJRb>y=)3p39y+UlGVQYb+D}v}pYe|}%(z7_<
z&`Mh|k5Z{K=ar4X5NskHH)_)@;RGVb8h!>g@|yFX<{n4Il<G@M9Vg&_AYIhkuG0aV
zZ;dU^-6<$BtO7eMiW=#oXEuA_E<yLpg!T(O%-jVNUBoGj98Mtxzuc?pZ#4D_X~Q&O
zh6}Wqsy=&TKV05|kpkUY;kMb3XZ4NA>&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
z<vFig!V{?y?56&75{4di^LDvwFAW892v(`~)XMV`{FC@e1RyN|@`6^I?FjwgSi4m{
zDC=AAaCK@KYO90+<>Q7t6IuT(I3xCum~sHuEZq6c9#t$KsLy{YUQQfxPIa#jRxwh<
z;5;3GpIIwK#~ByFg=wQGTGdX8fr8txZT+u$G3T^NR)~)bzRG}kfm7<pE&t-4p=oFf
zFA9JLthxl)1}C0tI@W_B#lA{2bXO9U;N8qFDunGFT+J^UTQiVZLuz2>)AQ(^KDkS&
zPivqsdTi#XF~owDXn;m?ng*^JN3+0-!Sgs}c2HpSSJZ&_P0O9Bpj2KwEz_KK)wSYR
zaf`TEvU=)1U-FB%$FElHK<qR&Qr6{FCTxQ}XG$w_Sd-)VzGmX1sQtzfS3tIu0h{1}
zdPvJcjljyDavK*GlMUTRUUD;6OUN5D?uNF}er1si<DBPBXc@TJp}j$kvGH?H?SYJl
z*kRV`7()RBCfG9qs(4>sL_{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<<m*xtO_dO_E%
z$59PQXpHxf?O_2G!O^75XcP>mi}KDr`otJrUrqj~H+E*O#SBKjP%5YW(pp_51@v<R
zKgA<~z#D~cII$g-R$@w_74g8%!)Rj&_`}N|;QCA`a-q#6!YWA$4Y}T)cGBnB4o3$8
zNiykvL8L}l7gi<9Hg<Cf0}iQT(Z*^!SByhcn^pT|8NP2QtPVIT=PyJ^PmA8x{7;&_
zUl43>$ai(ddx6`md!+S|mkv$i9%#`#^%}CK^&|?OjM3Hf$u=E1ziwwb%{b4~euj~F
z06*4aRdVn>5CF9Jk9(95{lT4LFGEPUIj&IL_KcVx+loB~{*x(cqzm&a<MIY@ZHH#v
z0c6#);b;H*P3{wA#y{*5k2+J#^IsHBP$B>+;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|2u<eDF4e2q9
zDpT*|)Q>ZKP{%rdzLkUp^g%dXzHx<n=SX(@(jAHXz^mTnY^ara$lNOom58y#HPBTS
zI`bQ;XgyG_+wST60Rk(|@U;`ymc6CeJ|9(ELwE9hl3$gy`$GSD==2ctClB2GRUXdS
z%%QC#+Wxf(+qHfYZj<RCQ#pjk_ylD#?LDla)$-Mk-}9Iw+I{|*7fx1Z2*`)bS}7e{
zN*$N57)#U1`hU2VhrWS{zb$i*|E!dPTl%`Ru<o`}ls-fnr@mXZTU)%O-QI5(M4R<E
z`o}PfF8Rw+*oF7UM!*51+*$Xhb}s2BCnqlII_!z{V0t$D4aN3K^Tdem(W2Wdy$f(A
zI<+~A`651WTA%*jT$$$}do)2Ud2JmV+`I7!+{yc#sQy(=rWlib6m6yXFML1S=S>lk
z77L3%3k*XLm>xT}aem>evHeM4Gb>Z%^(tln1HBnQE;u~tL?~n+L^cdk2kSQl<BlyH
z)g~wX<`-Sro&6<eFf89{yNW>9WKlwitxtV71<noqa1|H}4(*I<SM^=z$zC&MMJWgD
z$?$e1tC!fOVWYaQ2N{v3SWLiXx>Y1JW9iDh8LE0SrHFj7-1M>v7w7HMxAQLj@T**d
zt9!!-r<=uYb@vb)e?d2;$u=9Tw#H0Yz`hDwJx|4Ou!=Nnfy6b3aWG9<a8oX${h6mz
zmJAv-GZ#Q3f4LNGn?qF0WBEb$vBeWPzc6#Ed?^qpVBb#PqmApW`oeReGsH7ooK@Gz
z9>1@5pk50=u{M5Kup2?Jb=-lI1a8I5##ByNfMoni;wYsdMXfmh|Gb#UnFtB`7kk{%
zp^)o<pI72>8S*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)8<ZCLAvdBwctO#;DrD}U}V
zY<{q0sgr0&q2K@j3{nM-qKwjT<zUGEw@QW(^UAL%c(>fHy@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#~<NmThL4eTEELy*&k;e?neT&}`ob
zLMKdn1}|ogT(j|FzW)p8Q5QiQyDrsrv}NIS?}q2`5>ndbg<gAt{YN6(YIT|mVQT~P
z&XMTNGzLDI&)bhp<V3;le#B#H5(d(d$k_qvuiitunD$sXIgV(;If8j|A(3_go6RcL
zPX%QwUX^-!hbRVp1=RMoO#}lrA>ldY-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%FDlC<f$aEx&^W0{V_qipb{6L
z|DM9ttOrD!5r~5{bw5o;@Fu<-W^1I5dz#8`kLHrC5rPep9Q%P=(3%l+9}*o|^<4x}
zL*>NHumH$(+j_yXy$rr=0D{_=-NYLah^415fRgI^Oj>0){wAlaF_X`*8vsWuUEjY2
zohy~LSGhcf{#+VNzM*O3l%q`89v9-j?C^l75Y}@-Q%J$<mY+pfA;1uz=T^7wN3CRT
zvj)*h-HqOw7sqhwAzwvbgnI<3*l!D~IM1)>1KzZVgFF{YH_#YX88tn60XjLFr)th@
z%`!>1blK!_k?iKO$b<oRbV1=M()h#ikzG3I?kNBVSd4MY9biHU26Tp!YuF8jFGJi=
zu3ASCKCVJvoSy2~AMe5}6>gRXsDR1DnWu*ZKwFt?LvkVJeagJxJGIikVi=Y-c4nQV
z*7HqtTpp2xtKb~}`qeHVDpebrnU=>X?Qi9bh^G{Sj7ZN5vtkQi)M51^y7{wLMysv*
z6oT-`NUJ?@W=Zu*iEf(r73HtxXGb|8-v)$w6<J6NWTKk4j=5Aq%rjzVL808SvyT!y
zf;K>fBPp-P9=ZYF^CnRAK9iph%g!;F(vIZLlMiXCDU5#3j)y)&E54+#Fs8>aW5KY#
zzFe!Ln2rQhet6l6l{X#tK=pEKrN}Oeex8#FZZA+B2s@?(<Ei@{xO}GV!NG9z+9(;G
z$>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%r<Vl=jdVQ#_NzQNK_N)A&`<d-7URcD+GQ<)O-bqs+cmu_E@MiWQhrWU
zlBMS`GKl@&#LlTBZbS06BZ-TNsslAj#Se(<pAc-&X%HgJ^RIdh%kSXFFMQW;`eD}Q
z?Rswe==|Kwd_SbbG@9*39T!J)F5xb^Zz7?^?bn8h)4fXY;cE%dEu;O8o3@W?shwAt
z*mArl5~37Rx}C3~?m!3)=I$GM+SD5uk~c$teDtX^WcTQq&Zgh<7t+Lx0U)axpE4+P
zjd8mCvJg@h{ggp1{C{o`G<GbB_8*s8UsB777<;~xHbJo&y%J1(HU}^hiNtob>z|J?
z)Ydg8N#vFVp7<hp<G-}vFj{02?mIMJ1~!D{;>n;HuehO5S35ODH=C3*v%>U=AsC&K
zq1l0=>N$wwP)M+<FQX-H%l`omY4<Io>Yg<NUA}6@JX9VKQ{zCN7lwEGm-5(3Ivx!`
zuMWmRumc5!<h|Gu8=k{#l8~4ttC%Uz&X1nwkVs5TByZ0$=fj(xx@~4Y$ygj*9%sZ}
zu|lY$j4uOtR}s(;%73!%>G3_xx<_cPoEe|PT_Yh2Xf!Gngx3(mW}*D2z%5f9R7uo$
zN5CSklNXaD)Nl>@C)@eFHZvJ%j&XA*Gvvq%iq=!%GnDc8$v-Q^cCCe5$E&;)<ih~Y
zp8iwJK%}nJ%6O)FZM*K-DgHX2D|@_j%)w|rs9*&io8u!->hPmsGS>L4s(Wt|-niK0
znQZf@`q*!hU2G}E2a1D?ow$HkI$JUAX`AG~goQ<hNxL1H&2*2uUFvFrMo8)obH|F0
z9?1_9Y<{gz2uswT1rM|Z^!&5HpjPqzA}m(x^s3=^uGc|XBneA1Mu@{zb7kKz55i4c
zqJ0urxzWdWNcTkz7Su7qPV}x3X(BERE9KiqqeOn=&mxDZ?S9Ow8#~~J0>&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;%<XziHhtjDSD#W<W#
z2mz>Y8GSmLGZObJdVhpOM(JP+Roe{0@C1pbH{<eQj0^jdc?rCBm&IO5(??vyHiERm
z(s_Jfx1rM30KnlFr{$r&9#tXN(P}|-5xAr4Zp4cMem8k+KKHEDUK8vcceO_T8#}Ul
zO5yn*<*ODtQ#$d<(7zFB1`?D=I$OJ+7_5S-W4lMDB>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<~z<UXZ&xqF#yXEyr1^aka>oAN(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-`-wN<HF`7@*cdIz0PG@3`K
z@V}%ef6RD{kf&Fb3g`Qo?|7&bF9&ICqxz{2u`hN6-1{O!He$u2OIP`67c~+(F4x!`
zgP-fR5B>Z~>Zz(9oGOC-<aQTa<l)SOsNkf6M9LB<Iw-@L(1nyzO05xkRfnZ{Hkd6l
za7|9e@w#fhE8c|?&AlVUr^v1hf9)6CyY6ZZV${Nvr#Twg5ay?-NQdO7X>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<q17wp;I2=E#9l{S$=6sAp5l7j{|vgvK}4RwMtH3264DG
zHjsj<tqI|9DfK7rY3CX(To&NAjR9`dKB{oIbgq#@2B*iPO-<?ZQ^H_8lT)V{ZQWfW
z@hiSkd?Ca-o8ykz91jjn0BL2@4~-ayqe0o~^HgGdlvHaTCxj{th^lQJcXRw2?L6}G
zrLAY$bUl8e%20OMGK%11TAPaeE}r7~`FFKsu>*khbm(ZL;-Vi}<K8G?fSqDE9ioQ<
zA3?P4S(%V4JlqRjjI(mj=xk5a8BF?#|6OhHWw4d)P27L}z#zguJ56?hEf%;&YllgF
z$u(`g42Is0-fFS5n|hN><HKxXK&R(Nep_&8Zcuc083}|K@C{e&+6-5cMhjlx*=H?@
zzG8(0h=^!R1XT3ZcHw)Hu&)^!jKUm60ctT4cmI+H`p%+1YG{xqzOQGVF5M`S8JE-c
zT<lBT(ypHD=SQ5LA0-&lLWE=St+@#VC)84$($}yzw}?iggl<}Xv1F-HnRuY`7GYVu
z!<=_?+F|dBRx@j*oQFQ71{%L`uP%K+->{KyBo(RZ(_{$<_Re9WK)tkisD8MzA~sOG
zvF{r93T*t!6ji;#FCs1(Lp!+eXSMDiGb8>51HV^NZn7~OYsrrJ<b+)K7?X|NZ86ZN
zr+>6<Tg>Kr6YJ$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<BGddGrU`V84mCUgH77RYkU6HTv<rX7*Iy9UOwRK%{~1h*ls>{2$7&gpqeQfxukc
zc-sm((O92G@LF{kPOh$64UfRcY5*rd*uM#fWP{za)4GO7GY7y^KKK$LYR<cP{wO1o
zv@5*^`~j^F*xaeUg4Q!~Vbff=BKxl<Rd(ROG!togA2*ZB*vQQ1p#bS3@dYXqgXRG$
zKk;J0fAo7^%-k(aMoT731&vz+PBcL`k`h1wtOfPtjx?>MnfOhF1b?Mg)k%fW@Vah8
zwHpp44J%Tit%7N|Q*T2_@d6~Od;8><BHhT3uzR6sBJoq)F{#>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)&pusbTh<Ar)oHaMmch?Lu;75?oX|sozOA`mOsl<d(F?4{AB(-4F`!C^-
ze!eckrGWm~Ohr-OHu|OaUs3u1UeAb`Kl}XNcYKn-D+Ysv6Q~J`EGkh!J@z+Zs6+b9
zA&+n(GZw7{{)VtUQAdS0L&AZt7b&Z!P+%GGsdzYNIcshuB}`v7AR1Od>dgPuGrT2J
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|*E9mvm6O<rkv
z>jE4dcD!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$;EU<aVIG){%M>P><kaEfq8sDq{P=tR
zYNN(}f!eK`(aIh49f#(ml%MNv>oaXBKqk0wT@;o<M@7{JE!1m^DmK>$98N2%)VoUK
zd94XCE)g3QK*<T^uDNahL`4Ou-|>l8jLVAMI8@lo^~W5-$vK-z(#}e&I{UPT=BQuS
zITivS0kF2B{Y8OIMPE8I2z*+AXnHZH%~vHx49*X)f!fKZx$uzQh6~p?#(jiRtAZV%
zVMsA<eRmqyal|A_bhU-q|3^9}#8{LVXi&r{6$-&?0oqw~#fpe*>{DaOJQE>Zg^5$>
z5=OzDj`8E++~8yFnE$=Br059gO{<zJbw*ZTluPa*O{T(w8S;=q2l>x*5HNZ_q=$av
zX8=&Nx{?Ki6W;FH48Q@O(2^Pq#ke$0mSF%HVD$ADS6arTTe&qnls@7p)gj;!>$L!i
z<o?JWbqqt>2b`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`<KeW2FAL7%N+oXBTM-CLpV)fNTUU}kUl0Ww;-@EGg@o&qiJlm
zHGZ;|b)h#tE~zOlpBkE`>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?Ua0<G*5bI*0EmK^YegW*M?nQ=fP$v5TO+k(8^YolYwnE-PYJJFKK7WmbO7y)JP1
zo`k5!^RqSo=686YJptrk^=|oX)QQA`sfpwL!HOhI&%3^~AkNnfF}aGg)@tdaYP1*F
zYu8m?ZQ(A+b#}sY+t9JHYp;dY{ZVUWCesFK%(oYh3ytZmp>zcK0V6`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~<RvR`v_WJ{in<ru*K@7f|X
zv{o<nH+4xtiWe&G;Iycq|5BCq+Z}dkk1u#d$^NKBtwGYWtGw=x0q0tIDaJ#5M{{R_
z0OSwox;j4-hXw-@1hM)lSB?<S$Pws*JA3{CzRNPvJEcmII>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<Xx=erdg~bpEObG9R5&1
zLKDRzsQj-iPKfNV0+Pmdz3m~NFwBTATcSE-6~}jwWMq5<FyB@NO!DM8ipo_vy-NCK
z?U2S-ne|+<6~lf%gOs=5g%T_mmxz-v>;r_w$xfw=-@TLNnB`gyRA2cWMrBr^1F_{q
z=79_ibtKXp2Zc2UVp*X7?s(1|LrJt<0>S>0P;JWc($zu-hc;F=U@lrZdsBl5Qzn0}
zCAO4%<I;s?m3-O21Pfgz`jT(XeloD#g*5ey$&RMblfMP;4;s-^x4GziY<a6CnWd@}
zFZrp$DV!s1Ps{qFvELU1kSv+wnT}KvtNN_^f6uCn|AUav-1Z&pj6~c>>;W4YE|pLf
z9Hf?gKlT<Wg2yzhvUQH<eBIcOZO8c)y{6@h_9m!kAWL-eTPK>-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=xiDi<NnHEd5@GrfpI<MNWxq
zLuy!=1RIdvzG!~$l8yrcolr@Glt7D^yw&iOcel?@_Yebui<felK+wODDXm8y>eLtV
zqIR<m!r^Bgi+$_qR6hqdQn)4GlK^!1?*ZVnPWWeUCE~L(2Cpn%*?PO<DtRsK3KW`d
zas;^FOA#8wVkvsh39;7ezkX@S8w(8_E<GbjHOKP%{{LKLS;t6ErE^NDVatr!nvK))
z9jMn1ErYWrc7-7oulGom>oUs@JwVW_Kb$7o=b!2ad9NK<Czt=VZy~~M{`0BrOr;f(
z>o-jQKk&RcRy4L*=~-@o#~YFGN{f9pLyrpb5ObY@MVO&Amy2rwY}+us28se!DPoeg
z<gQYcjS99Dye1(;74J5CV{Ii~Q7`qiqHz+{?e+hww1Rxn=^fJujYt4wuQQX;$k7V>
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$<lu9}Aq3gv_Il>CJem;p^zr2SthHS?25K;;S<me}un#uWH5jfNi|L{d
zkSU2&3~hz#09G}PIAUSDevr)6W&s(z>@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|fm<x##v*REJ<M
zd(gl}G))PeDXlU=zl_SvT5ho+=6iN1rR2Vs5=m`N4c5&W#dOS3g_b$7m?0piVf#3X
zM34sU_F9^>NAHvxJZcKLvV!T}v(*zwAcfwOt*Q`)gk|KMq?BFjJ~&8Fg%#<PIkd~J
zukbOxCQtqJWAS|BeodUZ%*N?fttq$EbBg|j-3fG&LA1Bx3X$Lyzpk*)`2v$VOdW>3
z-=&*(M=J9zk=(aj?7xWy%oa8%zXfWqbZtjpg}LNb?Sw-q2p~$F{ueIOz{7Dlcb6O5
zOE|QlfO>CODEy8E;s*n7oj$#O)(Rn~g65sW*~<J2<~Y2|XdzJmDq7&Tv*75wfmg9v
zs<)s#6X-WAF%gB<&eWoEE}4`!Fj=PAi39#S5wWX=P071Gai>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#ugEyHAM<GUg%mE&;Bf&kHp^^3*h{-j1DIN2Dq5&|C_T0bJF77oo
z^&lM8(J@@|TtkxZwEIFl00~jBxs{OF$`HjDC5Dq~YVTV~d%Rvz@^z<FY!GuCNXBZR
zmxCae#JK=SXdx-$u1th*-%TQ|f9$bE?{wvv3|=hhb$Vd&GzrrFxv@c==_zupm0!8m
z6;rhjKHos4%S?O1@c~6Cq*p~Duq0aIp|CoAnuzv)I-vj$4tEBhV^m+bnZt%XnrqzZ
znr<nl4EXBpjHjGecbF|m3gcufr&Y&0f3q4~Hk?zlWb1m=(1BYZ?tsFjZ1W*QpvigB
ziNJSd1ib1zAEXxFV)wBfwx0UImwN+NSjs{V6H(f3yu&OjJODpHk5*p0$iFI1tt6rI
zu6WD!@X?Q}BQ^KqV=<gJeqeF0qA%>2#+)$NJh6COhMpfx@zTao`xo|5Y&uyxRQ=Te
zZ?|De6<YQf7;+IGsQKlAStLS$7g2cz*&mO=nPnsdre_<`(U6U%P?=Pl<7TQilg>e~
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#<T<(~1N0z`lji~n+QZhJjQE`j&!%b+O`MP668ycCp#lpYA-aB5zO;%%s
ztUh7^nLiVxkHtJBPTa8Qu<pa}vD!Cxg!dFbx4Nx{U6|wk*QE+$k)^m@Yzj)HP2{}m
zOM6!}A5LUg1rTS{p4gO7jDK_but~Bqs<%T3uwVM5Dk?5#?GP>c9A>C`ZUoUlY*fbO
z>dy$aAdtk?0Xd#>FY+qrP22nzo<H{Kk^I;#9vQSo)$*{36dC%4e;}?X4|2M{e-j^|
zIiA0Tcl)kj;3c%-6F}fqmsPVW=OO&vxVlnM2yy{vy?+Z_L5m1%ZR+ehmlXD}=myrv
zOxDXSMw57jbpypDB6fz$TTiZl3Y~m?*r_gv`k{ngwivJK(X6xGphQX&uO&paJ1mMY
z6OgJ#J-r^G1J{tR)i*3K?L4S)P2<H+qghqwhTE~KyvPObwDehcYm(nf<IZr(jf15^
zWVMqCd3+70S>HcRN!7gRGw^QlXK+Nn&PM}$0!yG%xWxWgGGgIhj2B*$|DCOn+fK9L
zlujgqpxesbB%3KMK-hV--nmU6N5Fa_&dyACDJm4G9IEsoo0rHwk=`~6O<Malzueyb
zKnYy=ot9`|hsIEhG<^0yzI3px?$UFepRnXMGQ)=R@<+d~*Pc^MCc<k5Y#pcMpNq=*
zkxN%scyV9e<Emsna>O!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{;+<OzDlSw|
zE~b=;<`_{v53s-NFFn0pi%P%I#&7w1>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_}<j~hPCi()XNbfk*59Vd-R
z{1(Zco|ngqz~mcn8^$g`58BSD+f%@wgE0?89;t7$zOkJ81#!NBb0zhj5_A;<XN)xp
zjS=3HVnf>&(pXZB5E82fQi+i^9W#1M#}jFvI>WapI4vsms(aX%KT?sx5$m+vz$J-B
z6g5hv?U`Tg;EX$T78DCMBHa1ZW$JwD-hXwpYtaMtGpC<pG9)K2zg(y@>}&@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_<Gaz)2Y4`oNL?Bl9~+5b|WF=dizz&B{xIS}uGWX<t+
za}yf$i2u`Ef;7%g{O{=N@D>2?Uf#jl#}T0+GAh2oMDzijKPALr)Iz`~VCM>=j{r3+
zTeqb5^f<vOv+b~leN`{|B@{WyJisxaB_*{Be3U2xls4)z$Wjpbo6UzVvfLdCT=aku
z8mv@k+<#un#BqKo{3yCt|1VLa<i0mNk3wzDC;yo3W5`@_zTo<Tgztk)<H#O9L-mO9
z1#J~^GPS1)dkj1$D$4-8r!obdWsudmkHf0k+C}_GnRuZ#34PrP2Zs5OBrolvKoEp$
z0F(MdGD?)hUc5;1NS!LEuJCzT)2DaS7-l{>5i8-{d^}8YdRx>Wi#5vhTI<r(AK(HL
z1s!YDbg$@`vcNR}__-K5H<^jOv{1^Gz7fXus6zM;EH1<_puxZBY}beeRvumN6F#*t
zifU)Dc5G-N)N4L8OP-T!c~vA%eBj`nH}zg=!juhjM%u>1TU$W?GOl20xuWp?M8@~$
zYBRUrK<U6Rm&Ulez^Y?AG{`;D;Bv6zmxrh^{)KbwRLE-ul^7iE!zaiezrtFk38D3X
zc$AMsCN$q1kFQKfx`?{u!>}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=<hFh6-?0l77)zen3Uf^b!}PuNHR9U&EGS?VIAkgj~tY+Opj
z^4K-;0-0Sy@df5w(Na_QW=N;{8{o|%N<@-%&VyX&N8VX(Rl$;AeW7LpC4TJ`!C{@c
zd%DN%j`FgR{eyxKZk9AZU;4|7yNq7gWmsu{)<r{_dMEZ|(<zET97eY-rJ5vlhK+5G
z+4_A_K@wRtC~AP$S{bl}VurIfJ22N!sMw@L&nh;nmjIIof;1=`=K71E)Ju5i5wtUR
zT=xR8X{}<V*$Jh>ig*^g2@oV3%T7f-Lq!>WV-(ak0wO6XW&`h^k&q2t)6{(<vZ!O_
z!bolv9rGNT5Tg$?=ZXBDrVmrIm>Asa(V>_fMQ(td4)WG~NIk9oUH_Qf{kD&bO@D)b
zOX8JGJAe<Gu82{6%s$?EZcL-1d<$rhNhXkohz5Mf-8=5$O5#GZ%QMCuz!K;5@p6s)
zHrF^1%8w-&$i3ij97(S?QX$W!wb}Ligsp;=3-pVM56EkExDE?6`-kl*N$IHp7KWb?
z?|+(S8*A2*{0(mfLfq$Bm*B9Q6Ku>VgZkJJ+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}b<hyS^m;y2!z@NQ{
zrPYChE9aQO=FwSG?Jeav@huH>B2AypE`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*Jb8<rCEy
zE#Ev+P<0t8YHec5azxLEU4}A03&SMTIAw?VL<UCVMffUdhx0EqUah$cB=gHmx2abZ
z<T*}B6g~}6B)snyv4R`^EWD7Ik60AoGvmT0vy?ADT_Fl+Kl}yP%%eEXilo&i19f1b
z735zRX^Zr!n&L?cE^K0-b{Mi}inoA<OGE5b38roo<<dwu%gzqzQ+2QiPRjh<5_$z)
zOHX<snDn~(QffR1I^V0vExB6!%m5p{n;MczX&j??Zi;2EWMz@O%mMOd?DR4JWN3>5
zK|Jfe88}SQOl_x=?+(w;-Hx#?f$I_Io%%Gplp_l!C$}(FV<oI3z_;qcmg&-Vbr@Y_
z++iJ+lUB62II&~krdT7D({j!#215#D-xSdN8|AnU#UB)|2_3S+yR14tiGqifYB{_D
zV_ioJQX+O&n#KD{@Ig5%-AV6lQ?zoX<X<typj$l@BFmp>ji6=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-^Da7yyQY<FS?z?4f@_j*L8$bDRI-s6tVXOI*AuRS2G{dw=V|+amUDniq1dsGpgl
z(X_=YNwDu|z@Lm|l#YoJTIW7ly#AVo7T90a78;L3J4##kOH)hvIm-ZAkV{Kz_4GL2
z<|w_k^WwoX5_XQ^@3OEpCo)_kVhGl6D)Cm3?<_tbwL$c_p_ue^`0Kx9fvX?zKZ*W!
z^Lb>LSKy=TTx}0`BQh{kPW-8&cVeHkUAi^UI9Xh5(c7Z93F){gV8!5;xoAm`<}Bx3
znIiJ1A;jjT!5RbCFQi9$qU<N5n>9?&*4lJ}5bmCz`ciJ&)fCTE@NB(I<EIfLMeQPF
zdC<!oDn+Xe+#JgjS&=kL|Mnn^ST|-3Pap5F(EsyMt5Qkf#HcgW%ubh$7$vAzgln}U
z(JyK}k>C1a7{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;&q<E2?lQZwZ27D*rg$TqXHDOm-R?`@{!&$iO&V`Ds#?E#`-_ho
zWGVfegChvWjOzQjn(C~kGV!O!bgvOJ_ZVUMd4Eyw8oFE>XhPDJ^&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<W=rc7GavruvN)K_n)#@H1W%^gYI)V&F6fQ_IN
za%q5*ZxvFI_j=*{lzsISgzYiVg!qTZXkFJt$vt9D*Y3Ga({ghwf2tBUb?qgpq_-#G
zB?Fw8EA3O&#h$NCl)c@}k`uyKX{0MDjV!Ogr!c=(V+Qr$rMXh72eXD1J8b9sFw$s`
z5iO@Z31nZ+>!fLO|9lyZABJB7WVhztUiE|c)P3$>9EPn#8BStyEa}@!1^mA4uU|NM
zSu`b8n@F0>T1-skiTyr8z@du$4bU$<8=I*-jQC8D9}JaksAsr+zn=P<xhZF=Bo`@0
z*tiy+I``k_q&a^kkb)fSS|Qa#j#KOWNVM5YhJIBHXiT8w!e-i@y&wD!vefTJZ300d
zF0NW8hLx0u5zOh@ej)I;0u4<1-ifw+!@m%6Sxb`R*#&THjKre*&hjYo`BVh!+M3s6
zpl4j_wtMeOB&nv235$~gw!}S%^k_@cakXPk5Lg}=ktTY}d0Uz#`vW5*4+(2ZBcJ`+
zY{G;Ovtu$`HIBD=G%HCXILn{c9EYTzPa;hLJmT2@gdGBx8W}cNT>z*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<L&1SQ?EocnC`7xph2L$vF2Oyv?s!dIQFD+j
z3e@~r1Urz~h_<jrsbh#<sw|Tv%_E<tQY8lI2J(s)MAlMH$+g@c7SkO<zX$@xW)M)}
zjchoaLm4wYKV&}+)yy!xeL}5PDxr9Sx(+pA(`XoM)+16!84m|aR-I1h%7Uas6G!E~
zJxf`&7XPDq**8<~enbf)&$!ZgeR+NzEdb-eQ4mGapuQp7R;d+`Ez@D}45#rZDgU4u
zpB3CkFn+D>>lxj)Up;1dZTr$8lO6vMuO~C>SSfQtc=&|0ly|}Y2M<lr!X6Gl{S25E
z_`e5<`SALGAz-_}%%@<6g#?CnLN(1$++2?WO%a>15#|=Ho(Yzn|G>~80Tyd?`AUEA
zpY5=0n%-Gbl`6O^4d*d66F*9O<v*#<v$}RlX4?l)l9v!H8OoUS*W5P!1|QTCh#k^$
zvTq1E_G$9dk{?XA41&t7kM$-BYt)H6aPu8vZVm9WAf-88&tm?T{LOw8z?wPDP}}B#
zYjQnD4l?WW$KZ61g>_PCNF8!QoRP$kV@Jm;I(=g!?wq>B2c@esr)886;PT{CFN3Yc
z;OAhfw?!7gLB(MCvm=5ni~jM<l`4=^SSMdwz$%kvRR7}%PqZERqx=hr2t&d~U3M4=
z&*jy0yn*!U3A{^$2s$fP%^uZ;Y@<WkBUM-thIWD2ksoI)`!xLb1L>?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<dlxaSXqP?OhSJS7O9&28HDW=5zar+6i-IiK<pci6R#peYV2RMZh#}&3*L+gjfs`6
zKIKb)-h=$o`D~naMAxSBRKgF(IcUwSD3V<phmn+b<cd)>>?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<k~QDT(&8neekMHG5;TJBm+|3
z@0o+_IBsg%7!6c!qs^l^<I)CtP8|(2YV{2KWXUljOHd%xfM)9`JCJQXskUd!?T2p#
z+AU4uQueKI21nAdv#I!st1&1tz4!wlHC|Z!uq@)*sSN*Wh7DO(`(twfp!?~B+u`Em
zEfj#gMw$x3kXqWO8R)5wx=R=P2jf6L{*vKkA9IZ+|LA`jj4re)G2-Vt1QJ1U&yP<0
zirO;-FCotbS_73=;y%JI;D<UsTULN@8h71j1d!V8OtNsV<k<T)&y-krCU<|fEcGy=
z>|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%<V5cEP#3M3JHjpI&usi)KEb`Vw^!LzF3auns&e;#ml&I7_hjALN>
z*hu=hqE~^QKAd<l69qLxVzKt+4eLip`PNz<h@VbB&|2@xNQHuWWCz2p<k<*LYs;W%
z#_ub@Dp*xN?}w(sfwX^Y!Dpm$ikZl_^En7Tt33n%nXV_;+!Nwm^Gz4WmWPvCC8%3v
z&mCZco3?@lC4dEELac7uX6zL*e|>V)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<SgyUs*X(@gfK@=%^>(OX@IuiNo<th
zOo}s<t9MV+1W1Ahg-(PUf70#v%fh|wUm0T~+#bT4^8QXP*q{=q5=T7;l{3D_`xVm#
zX0M#OU`XYYaU6<7@`EYI`S)c?`5oIANFcQmv@(;d6Ns^Re*?Kf1Uxop89fVIHf{Ne
zg>JBb-R4(<sDr8GQBE<eV7nzO>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#-oFsiGRzC<HAJI>g(CAhCOZ1FQAc!(AS#)u%U6%iUEJ?
z)S=GJI6UPh)(7-SNrj#ZmzN}Kr0{n?!vnItMn<A8);{vE88E}s6-s3?qAhC|yDD?y
z>LHY-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<XUfrx<)rAr^gdKYph!F>;cV)#*lL8k+yf(WN#e!oNIxb#-x%sH4S!_>p
zaD3{nt0&fcwXLI~_zj_UgXW-Ta~ya=W}ii}iv-k9&yOPuoC6l>`R<<ww78rRmF1>?
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)G36<Mv*8e<4L{l>b++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#C<sE?Y)AU%
zzN%3^<?OdBg7<aC#KqZ7PX1x91?Eymjs-yhB2Ry?_t4|01-;v$$35oXQAf5_RWH*8
zT#ePI)DmW~z*imdR|1CP{e&L5@4yMq@0wmzRg@lcYYpwb5g^>Q_xK+8xs2QE>d|Jm
z<qOujxUmynkA?6o)8GPkhb6<4bJP^ex~v8|dlO&`ze(*#Ex|XlQ-Q*$pJucvw&df&
zT(4?r%v~FfDY(Qh#3wZM*c7gO@nBB-7d1LG!&<(Psks}?sETf1pGHxweR^;(3vA>M
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$EB3AqlvTl<h>ILHCZTJ-MGO?%g3_nE6U^kIwOuqE4&*(wf8P)@
zFo0_b$u`&8Ja{^}#x#CXJPc^54a(4^$-onOra;eUZ0jIxNWyusa}7BOvY$I-IcG{d
zvU&E>6Zvo;iHpvNO<C1&brfM?<G&I6RE{{U>ob33<3=f!9e)R^MfHq=$YaHKC{=S_
z_FQW(Dm5#-0t!!(rv02~0Q&;^K#LA-WPmC^w8P~Oo4OG{bmHo3=RuG_2riuFe8T8(
zP!8L6ZjN{+j5bY9<kbaID5yv?T!+pgu?s<@6ON{~y!sd3I!k^ls!JO9+^k;8mwpH`
zhvTbesspHq^I;ESke%3t>AfW&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@j6q<WboSTyRIc!S!kjM7~2lOu6uA%%SW|
za}7ObX(>cE;-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=<Q~zpTdoZuycQ;tZcYyOT%uY=VGHc-lb09Sll0#4Oc@DM+*8TTtw;C
ze$FUIF&oI|S(d{a@tA=R(Y7ZiLqTvUy6vXHt5t^AUAstM*V@ygWLhkSb)=>tSmU1o
zw^y$lJ`-0i)}ekTQyWvDWS6juDG>&gew_|y+&q6qGttL<8AqWmwJM(PM^(~W<MjG{
z8Y6+J4V1{?)A1}`IH6~<3+c(OJjiDuH-U*_YkVsdDaFYr`syZI`f2iL=_Jt5)sQwC
zzau@-HZ_zT0y*Gp2;fiV7%OaDW+{1Hv}1I+k$uSz!$jMc%;2Mmrc4$mXoB_qh}P);
z4@z&0bd^Stc-T8nw~k2_jp0-9Lh#(iJtFErmrSR}3M61$p(EqUdvE_MryF;|d;vqq
z(qC;lLSf_8G|S0r<OcEqg^vc>6%q!OmU>Fll|;I&$hjq;u8)yLlm-leeG_ke3?uRd
zGl9E==G3S%^<Ud08v-N;Kvk^)US#74k?+Vza$zxm35$(LJSLxY!-MdaddusJPDJ&k
zZvJV@oGqs~o75YG6imtqVp5=Nh4S5sfI<!q_tr@j^B4LwZoj62MZ7C09WT2e!(J}I
zP1=3XpNH%X4{m(ho(pG%g>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}H<?4gm;Tm+oeK>rd#&oLp1Wz4hmzQX`
z<Ck`**AO?%kO?-+TDtt%H^2S2Kdn(KDD=#-7pH%FyRwHqi5UkSJzWXG?I;1O5f189
zjhuhjeg7KHz(YF1&Ockb$VsOWmq3WGH0Q%SSJcF84rP=WAT01?vIqQabYtb|!2bub
zzF0TwyY=T0iaq)1bMh3Wu_i|ocsBt;OD|*@XVFb16f(^V-^1Rx4S-WhtWyuU3PE2}
zKUH)7$hCilgn}pY8Ve#e-PY>FZ`+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~l<N(^tPpdc9)w
zABMU|j=|F1p{MqDmqY}onn2pR;Fg;%Qm}eeyHBP@Sf@m_;Y!P6liaY4usbF7K3Hqg
zDlsAmg!Lz#r|EbjnoqRLs`3XV1YaM}+j@A<1I{bnZq8z9-QPgGuBL9HMC9$d`C-8;
z9uE|7>w{M;qMn(m_tn!>6;&j;(LM*p6)V)g=2t#d$)%^<z(2})oLn&Ua|ntt^id&E
zRH$%CQjVvED>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<e?=P~#736ce!?y_oHGJ!=4cC+3
z(5&$LlNFdh!fMamR(lBLX3q1I=uDH^Gq8EA3-|UvSjbH3>#TNLGz5fJjB*(W8Of>0
z*88J08>_0+yXL&u!i+Kg$+8NnjIB`~$f?(>)Qg2_ZGRrtoE`2|Z~kBILUF?=)rq>r
ze&;I%sz$4R!Ng<OKQq?M&!ETJh&b8H{s5YqHIl4#NA*_bR3_aD;sVKb3i-ZGdT^5c
zrJNXk-l?@C8;5!MZNW>I>>ce8AU>00b^!|_lh(JD3ECDG|6E~<5O}rjG*BajgyNKo
z`_@q13<w?KDqe9&nI4N^K##KToX=sg<vY48#7a;Y)PDXTr9yZ1x3v7%jMR`!cy}S1
z4#dr;-ZeG`@3MNU-*+)*)r32Wc?PVri03y~w`7kZsSzW|?&SFu=xUN_%7u)14&MHD
zwnG-4Wcdf5K0*g_;hS(j?REdhH<=vB=X`@qmh;lo%P<B3)ltC6@{Z~bYy2ys4+lD{
z&X<uDdeJrs@~DGT@rJUyQOx*?I;T#GpxFRslO2)L9x~fFl{2s@5^>xevQ&(^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%<jAWekx=x?mOewD|L
z@FIKJLp%x$(_y^Kk?3XrUpRL)vJyOf%BBgILooDK3>TCeP9t%-S?{cI9$lBMcdi%C
zYFv2pqezenYOFCVA7MBET<bicfX*c;4*%GK_B9DZhZ)8g5E!>Z2G{=Uc9Lma;Bn%{
zZ;rHGbjmc>3NcUqPCrQHWWZd2_dOz$p>n8lg=ElwQwj$;gKapjfBp;+ZeVT4HwkAc
zEMYDmSx<fMS|~#olzx+%!ZSW(WjO|7QEBVscfatr{2XGyH_*X2UyLVL{fPb$g*&H9
zqlOc-^29>dYM4Zi(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=(-8VsgG<q1M}>CwP___a#pxF(oG
z+@%hqq@H+FKIB6|YT7K<izTO0&SG@j$TuQaD_@c7Xs=lS!kBSyR2(9YU6hdJ<M>#?
zueTRa0uTIU>IANacA`(Jt>9qPcbBvK&aQ#3EV-=BJF@vrB$v_U$8`iGc(`i4<a+LO
zf4|TbfVsf%$yV9`FEK}@m*s62rncQoZbAJrRIH-Bif|w-RsvDC-&D`2xUtxI4Y&;7
z7kvk38+zK}s`8eqq+?#=$#1SqN(JT9J1P*4u}jtm0y>;>zT~Vl;C_Rb<kcer(Xdog
zx)H1fJ?$ar<}C<4O2U+PX&I3JWyO~@buF<4m2EiDr`R+JWfM6(D7io{jCsZ;<_DWK
zQN|ya5^~$WQ=oPPEzJA3eaoZEdEK|_(8tY%mWkgHEqXb+qm;&N3aazeAvLm~LA>6A
z$)Q8;2EWH>!y^SA!azA&^MKR?P236S?Vndo_hl&@<uZzFK>}*~PY#}l%LpHPER^Xu
zx?R1N$P8Lk{tvV()_#OfY2mvp8Pkoi!1OsdP;Th}uakJS-L>|@fc7QLrG5Rzbp#34
zWh62x%l)(8rta<RWx<2#5&wu@*QO-hvU*+&tBa(~SS_#*Zq&FzeAUAf9e^!y^p~b}
z9fH;qrh8~HvD}j*hJzHD!M{hb0Qa-Rom=U>j|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<H4DzzPgJwsei-<_69%TU0BMi~085nBRlz
z<r4tCIXU5oALg8GKc;y*&7)RV-_dTbJ2-RZcALw60O(*gurnT0;KymgxUDM_xllE@
zK%sWRYsdUC>|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~)OGwua<Jx-kKDQ+%&~{q@EZIww
zkDtNyq@Di(lS6IK_aJu<$v#`JM4tmDF6toan+*19SgHzJv-8h)-`OVFHH+H_-C39)
z)y_jU3Yf>O;$>-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%EStS9i<CKKLXyEJhcutWI;!Wtrxfh;rvX29l@e3lc}f`!U8ut8|+#)&H^9IDin4#
zYpKpd7^O&Bih-jvL?!LZB2?%G90L_$Xq6;<ww)y`1#EBtyD`j%Gpz79&gOiPIg1EQ
z5lO_lYL^T-(DI(VOaNOS>z>vr{}x-@nzb`dzN_A?ulZ2ZrpnRv?&@1r0G!(=R52Wg
zy@h0*G1MjAeW7%+k|Z8nH%19Q-Y<j5!|DO{!F~|#n)U{NkGCOo3^l0OF|ZWe=z1z6
z44Y1L==BBV<+KEw#g)_JyqUUNze|98NMp3Ol%;j!yOf@=7?%ZkU&=N@hotT;^y~Oy
z<9DgpW$p`tTovtPX@aQ;5&Si;05SN~0-*lXM2@Ce&0DiikT8O|^Mf;1!7ExvK7vNP
zbIao&iM%4CYBmuo<bsr|fO2DXN?8x~iGt<Gw0tm}Peh9cdeb+ZUu~c)x%!=|A;t2u
zgMP4~K^}31;R->q8k8;v4MpxccrBh~bpBbI4mT@U>;9oPIR9JSifPj$tKdE-|EhP5
zmkCrz{<gYnKy3~97m$pJ57m=)j>Sgn7|Z64tFuBptFvh?@(`kx4=)P$VmpMXw;iX;
zxsx5xkL6LZfHgwE)E~*n;mlyh0VSiG#CIjBx$;JiU14XN?wrmFhNRJoWVWNtw$`h-
z_{0fAEa<eG%LJ6{<1!3sZh=tT%8)z;xvate)Y9s^KKf{GGo)Z0dm|1klr2@$7Ps^o
zq~B=N7$H?88R%nsS>4T?_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?Q3WSnL<hH*pwyh6ne
z69`;azAWKyrW8wc+_)}`a%_gz0RcnVm%yCUr1b&1#}b54Ef+0#Qb&=#&>N0j8vV{B
zfwKz4K5eadLs(eUx?WVZAA)dr(jwX%P0KlnJ28<_<=8S$WbUaE?)Vq;!z`W&^<rNa
ziaS>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~<l0gc%s`BtaQpmwjlRC4df&rWQfL-+X^<z6FwZMvm6cxAlh&%-@eSZ<4C
zN-am#Kw1ndtW?N15;wFRSHF^1l48Pk>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#1AQg<Zly47(6AiOg;Po@O5bdO
z3RKGUgA|M|#JnbBmBM`~*NJh6v<g*EDj!vgg6LXToU=#8`5CwiP;w_;4;NB9LM$0%
z#yADGpX+{Q*h@{!Tg8vG5c`sFCsnuZ+Fjk?4c+|~^owylGe{iYXe_hO^lnf|gA<^8
z_`0@O9#6kU{f(kcITZ+us~YPzH>MJq=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-koL<N%&yGlM|1zwFu
zk0f)sj0Z5oQK#AKAs>z@iwheC3&=I-gR3DfwA1n$li8L+hg*Wid8=y%$jER?=|}Z!
zEW{VBs{}?)Vz~hUf|b-dtn(~t^4K&}iU&IT(=cl$Hr{P&=QIh`ym7qJd@f9<V-Pec
zxG;NcK1r3(mwskJxMzInu43KIuS$0K3zx6uW<jve@bhmy&ah?gN^A~%9f$w>C3JDk
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&#}371By<uTXS~Q+0o0Y3z;J*v8bKR
zGUGFbk)p`(WE^9Cb<AcC4!7}cU8Q+NxGAbH0`Y|9=@Vba$PcskovZ+^#G<qgJ&7e{
z%geyKZ3~^_?+d*!<b5O@G2tBQWdP8Ztjp|+J%RyqHR3w%(wL-oi^AX~(oHw@EC;__
zZFDtUB<i|#x7!UIv5e%Zvz*YM(l&*jXQ^^*sU-vrrkZJs3t1hatYCw;g0$#rpE-BM
z{eg84{_A~!11h|0Jouu67O7(o*pz^mKlS)(2QCK4cHHcW;k%c~7d>SdFes3a{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<L3a=6}iy*^y<VT!XTTxLKz0M3ba9!6c4TR>*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(=nL07<D*Q>r@%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
zoAlxdu8p<ia-4Hya3{NPfw8;%JMSh+FPhgbgv{&s>Cjk9-!*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@wL<nUKReW~LHI+C_U4AF&CRCk&qQ*zMXTN6FA4}HxDqQyennZv!U+|>eX
zzm8koxm!A=Z-Krw%;LHk>10l7;TS1(LB}s@f*hVg0(3`uTN^S-vDOQ%#-@&XHo-|>
zWe7VBHd~Q82I!BfeEb*QT0lh|n}&$+At^y1a3Jxjhf5mlz(!K4_<TaO6A&vW6pnF4
z@GG09@K8>ty`zp8iV{9W$A?EVUM-ye!`K0%uT<B6xnO%GyE&qxge!}+uLJx#)>(+;
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`<z#&<Lg3?fKwDF#C5
zG$GwB7e#Hq$Y-aXI(WD}N3D+00dz?KG&l)YQ2!uFGt$Sq-S1mx@#g?x#%WzX`ZOjw
zw@;{?QEzYHxaG3lPejTti|HMl|Io)WB|++y)o32_jMCbBBEGlv25nN{7g=Xm^jpS^
zLoPyEh<;^R(DcQ3?a?DvP)ofQrkX~%Tfi;^XsI8;c#&zRCSU8Aw2^}O1CnNQo1WM6
z>h0rL+O27x;ske?)wN1o8;{NAPOug@mPqPa@xPZG`ZAAmcoFs1z1XHbKOx4T(=c+)
z+}>*%jj&s03cVUht5sg8s8dbytFeiDm{ormE-OB{xc-|C8p~A*12Ityov<r<<>yF7
zAGPdI8U&5h+);Cf+h@6Cf@h>r7IE_mAz0nVEPUl*94vsMWvB<0Y9>5#AV>K()N<U8
zc=*tKgnkA#*JWdBIHpMnN<;yN=+KycK8GV@hTO!V$Q_a35AjFHo<%*nB1;dx%Rdz<
zx24|#-WuH3Q!BZxo#9@Cm@Za_sz*U+KMyN%aHi-*|4GcOJ?ftrxV=+6hRTr53a&Yf
zfBg8sxO1`sUT8@v=O!>&+bu9Zj5Tz-5}`SIvFBiX`djXs+|w<K`%`D;lTuhCpWcgd
z0@b4W#(lw(3n<ZSxBD?jeZFZ_8Me1i2`2cna+C59e8)CK-3b~eW8klUVlCjCv<q}~
z7ceux8S#`Z_0U`gDBMYIyb`^0xj$H#7+|d5K66FHb~}fyJ$ji!I|G}N249GGb)t?h
zxapRt7OQ<}NEl}Lb7|!E=`BkY#t~c#Wer2W$1%C&Y$KkY4iy8Vrp}_I9yTTNWqj32
z1Ll)W;EQc-zXimR@bw4^Q=#MpQlkp31~mlC$+a8V8YR3vsFxt-oxa(WaH^7Z;|1Zw
zYx(b`v>SKKx?#>e`s{BBvj1bYn!=W9ii?c$LysEGlvPWP$(^D^qF$CZzIQWc`!_Ig
z1aX8hw|wG#T>Z(;CFe=k<%~v(--sAg&!rQ1QP3A^e=M!4(<C`ib2nLAG2*VH{rkHn
zHj!@0pXJwtF~&{)y}M?2>hf{&8EM`(Gb3<LK4mhtGg|VJ4NpC`HGj;Z3s}yszAOe+
zK~)mkYvo>Rcf?9W3n3kEr^bUQa^5YT{mL>1uwyD8r^~%J%e$LI(CDk&M}>H+pfIRb
zF(hd1s>nEEEsqD<t75wW8-d<kO=yB{G&w)i_{3>pCXqf}KxjAkV9nTko`d>UA}2U)
zLnPmr)DKB9V2uGg1*(c?be%UoK0)%gqlZ?Pp(ky1;&AE29STL@cm)K{coozQ5c<oM
zR;gr|F020bJIN)qw(odoJZ<z`=1V5JLZ22G!(`%SrFsjH{{ymkx`L%N<IydTdoxEP
zA`2md2SFXfW}{SM<~s$<Y#qfN<~}=mN2LLa(gQc^f#J`hhDcY(9r0y5L`U*bV6u#2
zj^#g_ZRy?2{qE`u)ZE+HPMYz}FLI7JOUBw*SjjZWx%h^|c`Q$#ShI&teeJ45g{x<_
ziUXc`PQ=L{VVS%;(;X}}cPheEZ0fAsyYM9Sm^=rU5A|BR8m)=seP^C+y8nAY|DJ=p
zSFEEFy-gDt&^%I|wx9akB$-(kO(wuBTAZ1=D(7VMaiDd=aDix-_(SN>@TK#bWq|3D
zl5L;a!iTa1(xj+_gMEa>7;e>(BCfCbTXZb?RVXD-Uo{(PxBp|7$k?JsC+<NGtzjWW
zOW0FZlTIO*d^FN$a(R4}16B<;IL!fu1jP~FeQ%CIBK+$cbPA7+9k9<7gD2;546L!u
z`Sf9vbH>*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<<M|5N!z}u)OQ_ohBu)nplc+_)3k*vn}M~bgPq&R>TGUg)Ysdp4Y
zFCR_r1y6Qy96xlU$J6;`Io}-*s+9`le}i)sC$j}s>`aTF+p#4nOqRc__&bwExQ71`
z9OJB_mX*ED;o<he(c}a&sqz;8Vl1udfKe`&mE}-_lt5^JOO{gB&=Z>pKW+_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^uakX<UE<_(
zyw;ma17xytw{PXn-<ICSY=`!fUpgJT3|p+N+u{c_)Cquwb7gZ#)HyFYGYM;S3}7@f
zro^!7hq@Ps(Ci9$TaE!(%zP-?#BHrj7F{msHoCo;!!a?Cni1X*C!3&uG3R?di`X*l
z21ZUKGI|UcUf`H$Yju5<4GpJQ<h(Tp9iHgR`N-FX#BvcHSHIB71pOLyWwf{4uMypZ
zcuSrge=kZ(Z<=MwPcgDJQ}}<ls+R&HKHsGR$6B@$ImLIKXxOYlPyo=PWjvqILJrV0
zYqbtlEqAdHf%n{eh-<+02EIg#7l<8j9UI+4_qB!d5B`};K6ihyE<k#H1`jqndhH>1
z)$s92G%`sa9;Dd~smfoV@-!xoGx!#4q_ZWA979vu5TrxHJ@!QcNtArCk$TPht&nGE
zqD9$O!=kNOy#qzu<Vt2dvk8pZLIGOCe!bgA5b=BHgU03**Az~~ueW&5FukKB^v14`
z$7^36Ci0E06{~-8cXnuEUtLWbzTHbPjOOxFj@Qcnu)RXjO`47J_ZgyW19IO+aD_2V
zyx1l>>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?tovr<G;Kej
zupn;w_a^7NHgT4n{9LH(&WK&RcUji|Zb$xru~Gla=ji#2UrUjFYClY*?js%veEUKC
z=4*8K0P8&YOTDt$kbjNmVzU-4VIm%SIox>FF;#%?<JbLxw`vBMCt133W`G~vEs`CV
za>GtlhkHIWyubC>@4*E0q3R-Hk{7Oi$RqZzn4oLo=;5|h+rub~X+sk=C*V$BLh-_;
z;!iw8RF33Hug;0;{=gN<Lokh!hz00{x89|l%P?8hwzTLMQ10c^1M^L`Iy%tPUjy1y
zFM;<~8#Pg;`p?$M49S!>!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<hB<gYIfix=s7hY?g}&1kTUA)#5r2`p0TZy#{jcs_$*s|QB1*z7+p
zSOYXFAUE@dS5&HnX$qYq_1&xKT`zFN*>_X*_K399l;*I{uu7W&1oeT+JzMX8bWS__
z?;<&}rN@Ys+x;B{r?#z3ZrbPjX%pk^_><5x-<8L4SDSdUS_QJ9`Z<Cj{96&2sQ#(n
z-aMIyc*iAtMBY@s3e~8)mt*JWwFlA|2>c`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<O8`a)-dfgm!$|a7{9wyRe^ijyGFN6Nh~2C#a90m+H{q3C){OPE`?b}IOw~t=5@AB
zc8uv!M;P~CIj;zT_DkmyST>)LU5u;3L+cow+k}<lM63^2HvEH$|FLd*m5=sa4=F^d
zm4&V{W@G%xde|-Sn+Dfq<?}n&l*d9EY4dDx?hDuAYzdOi{mWG1qo|5lYN-vLFZ8{$
zw9AWSsItL`=4Js1<4YPGwqp+0=lUzQ*Wpa>RZ_d3V1IbQ5pPm~PPlQ5XsMPuj|O4O
z$Mxanu~ZJ8*dzsLQ`)T+zOrK$PJ#u1DvcJd8(L(X5UH$1ZzpxI_6_UgiU>`%VpvDc
zVLAg~D3+e<wl1I7yZ;w;I{`7=UL?iR#*op~w(^^+xg*b)u`_q##hml?9S=^+N}o;`
zfZzy=pDE%ZgoWj2fGF#U&j~ga-&)|^2*og6T=%LaDbp=WPYRTL9y?XP|1hkn;(6-h
zu&tpw@9dhVZ8VNpGM}*3L0?m>m;I3EqQ6D0^b8MRse{nC!R$(ytHTYmUYTu^OyXT}
zkwo8uz3sG1uPO{FL0=+gJ1o!k6m<Chr}n}=kc*L#e2851Mz7Sf3ie()N>?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%p<m1w(t4Vvp`+p-mMhF0)6f*;6>ZG)@GX}9B_{i2Bd}!Wa#fwk
zRo207^J@2HgQa?%gc=M>-oQ$XxFdjYc!`HvI7;FtDNY6}%MGI#i<gwZFSTFZS=W_#
zmme<+0|V|V7M^bc4}#;Oy(>&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^s<V4FKtzoC<Nc*QXYm
z@AD<uL*v16)25stSUKo}%8`3V@@g}mTN@jo*8ayW)Tfq5d#UgEa<iVppJBk|NY`T{
z!%`^Y0@uSkDMs>X{yY)IW&;wxog}NwUbodOzoZRFsw9M&7%2T0VpQFL_mpW2q#309
z=IK1_Tio<X?lhjX_W;5dp|05O1fia@M+_<kymDcQ?*?t>)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>xlVkydbfuG<AqHy$1S1!qVD@$j6x^+Tm_`#xJI|)`#aUq
zr2TIVsGo)61z)onXB*TW9uq;{hpoETGj^CJamzuL{a-R`g7=Gu+xLJ%>QMk<;#?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$@__1gl<yb8Mz*YK{Iw+J-<jX;<@&tO
zDgJ$N>BoJB2Y=+(i=X9aMmA;c$Nt*)(9yczknEPbx`+>a+;r)uz%Q!;r{06QQ<YWl
z=jF26Oa0o=0Nq#{{g?SnfNBlsKEf(5tLe$<{j@269$IIUycEb+^Xg(ohYO#M1e+Dg
zqM`3+HqHynxo>4J5rh8mti;!Xn(mopGAklT>(21_Aeyc8EkCcvU*l)8UuskUZyIod
zniyFNKgJoj`3o&B1$dbdVK<j5Okl43UT5sLfDH^D)bNlp)uxE~b<>qnj`31kX8w8{
zUqUoJLVO#>Yd1TQYJ@QPr&t*uEZXEta1coGa}EIyVeuMo@IB)kD<Ti+E=ahFFl*}R
zS#!t3Yh^T)@VA}()oJ9*23PSes}Wfa2<^O!P;eJC^<ok&EZ^!Sr%z&{iVvGVcePUR
z2WtB;7WvS130u8x)RMsw6xr*`Ysh>;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`|^sk<UqlxhcT|X{?fs
zSie=}@|OI_2lKdBOP%1AOnq+u%^Mc8+T-dSvdER(F7BAEf6p&)OVqdt<8wMA{W@5n
z#&1=St1Nhu+-xf{s4PuNN5VVp8I4B@<ChJvHhE*s{zMz{k|~&GQug*ZN9!R8a4Oos
z#r*Xx-+S~8l`|l7)hsSC`o4+1g5e-rJ0WQU*p;N2nqbp7SJyFpN3YiBJF<l9I|P{S
zEDLajVj{aao2%{Sn)T6S)SeSkp3cAklbTf57xXGQUE&Yx+|VP6?O%=jd*^a`TrfN`
z(^cFCtqrZ@wR9;)SuSb}vAh0Az&o_>TwD#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+Zl<PWSFm%&sHV-)1gZD-Ghq9Cj9?SABK5#jPQ|A(jRAY5Sq;vUxj+!4gx
zb){ikzDzyj^Q4YehwV_i$m#V%mYpQ%Ud%(DPBXJ*yZxvT`?4;u*2X-5J5o}z(cK`7
zVlD%6Jz$(oHk!pmY25+lE+I1A(9f%{2o9Ss+Dx9Ii>PF*&^$U*a;_}o)!x+mV{yH0
zQvd;2x~u&ic4VbXBMAvMQ(EIK$*gNx0+D=!3G-mMr@Fi=p)ql24yrr`<W|!8`IB}=
zUJgdN@l{Y?g5fhu?6n>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$<hlqOy92mg-~u{;V+qndxl<0U8!@?
znDg~fjq_rK%>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$~LWTS<M5w*sb3ufj^F1rmjvfa_au
zH(4MQ%IK6Ul=zu^)eE<;HgDOfx!P>kgzF7rjrn#{9gH>kPH6FqeCH_@!(Fk~Q@fB#
z0;#@BW-r*RYh?C}cuVei=V;5&v`>?jip@$T<j~j=z(Klhaj}XVTsrMTJIxk9PKzqQ
zg_}sqfXK+Y2j8OB&GJ~-S@U-d9L^+3`+rvnN9uR^tBw&Xj(h!1dElU1uXWG|vmmhD
z(C#f4d@ZmwPonuX%I?8FDcimqHB|CnHZJN=iZq^$AVUA84X8>ESPoy-omy3F4>SbU
zv@C<XU)ChsCWpp;#sht)tk2nsOty+ACPIJ0Va)^{%4^KrhBub!ivsq(GOST|W{co;
zWiy#!(@q3KxOoBu5xnZ^$}^JR62xh1yc%6k91N`CrF<6X%co-ZnSXzY7bX2;7jL54
zHeQlCV@5ka*7-k@F=<TekHFnat9%<KIeCYv_jdp_H&aH*!25-&4#FjiY}<uCT-$)V
zGyoLmR%)YqCYMO5=U~gQ?>j_HHR+9L6E=2VS0ahzm(6+KPm_1nmmrpH^guIumUw5N
z*m0Lx?C&t3zaGkgifObdoXD%0Y<r+?P9pLtU4a9c1O!@${6h2J;n}2V8)RUT&<@s=
z<R|(2-0(lTp2%m+ZoGZtxCjS_;6alHHXo3qWPf2`L@m}xZEeYQS!37lpqhgtp`+&;
z(dnQ-mZ2ollPx2Z)ZD@C&(eAdOL*%%-VjM-<(C&Op&)OVM9my29%vPIrYMq7F#T{&
zWM{*zS|5=P<4W4AB5>`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;|htU2yplJG7h<xj@v3tWtCnx)w+WhOQoC60*N+1PQ1*TyA<yc`MB9cb~
zGzYP>JVx&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?<Jqw3oe;1g^pb9zI#VgP
zxGqQZLg14H-QY>-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*<tKFPp%I=t*8JlO_CGltAWsYK9HeZ_*OMF!6p7q_Yx(g);e@v~R
z`%AtfUC&#YaZDp)i=|Oe{p!0mN9;KKqumAc+RRDvZRUq;mn?}<>$-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#_>o1AD7QJv<Aj71{q*AK82&akLGRO9$uh
z{D$=sTqV6F_!Dip1a(~g*b{ER+dAW4Mk%&u*)qu-zDe;<i?j;^yG5#{yUQ$R8P8gj
zs7^-OvS|i;$V(@$T7;NZj{xoKy0O|+{x-UncX>Mw=H6lbsNCYQF?{H_r_x6a4HDX4
z^tAfVZoHM9Ug*tV0)U0g<EiM7L@hYiF{0m-N*eev<OQlPJ`d@36U+Vgz410UA|}C~
zj9kG^<iNP4*!0cP-?Q%GSdYVulAM!Kz!(H4YP#SLh1l%To7WA+*mK`eB>|<)l~<n{
z%-!ZNdjAvxoBSMPyAl#qHx*qM!(YOvepU#&6?-Awiv$Mr0hC{}-79cl{gc`ngwm9W
z2fRQpngGB9u4{nX?LWsSePh7N<6Gc6KiUv~n_Q;&^OzUXVNnC8LJ$!O5e1qe!`2us
zNE4}@%6KDZKlV$(EB&O_JsjyynW}2J@&=rAW_rf2(rW$sUFSc+)&5rFT7~0O+|tU*
zCh*Lxp<oGIO&)6>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@<jyVfIJyW}}&vDzG^>ohhh7yCnEq+$exw;`Z
zS*-$_)WfR;sx`^0u*2}*nkQfp@2cNS8dKOY0$Uk~kLI=fz7rhcqPZS3Y`_-Kje^$(
zrA7;OwswS>X4|=Wf01FRY-H1^O@f^3^vy(RP44;++<Ao#*TvqHep=Qlrr!%vzJvkR
za=z+qQ{ZF6@ii30f&EenVIl}U2x2~9J9@~tH!spEYqi$V+4YfH1K{>ro38(I94Cs}
z&8$fq4~)K%Kr+-jF=0c+b6X9Qx2Q`N-i!}9z~FXCN71<D&hksnCa`gq3%F8gBIx!6
zxeOiTZ*VpKPZv_hrFNz?h%I<%_kJ;3?)*)zWa>qDP8rkBuOBIGTz85gM-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)<?Cnd7p+eu3HGH@sQgi`
zXvVk7^XXFBbM+<ed<><o&+PrN^Kr+Ju6rr~0ZdVJmiLLlb%?ZIb^GX+Ug!y)fkt(N
z)~#%!u_l@*h=0^xHqP;)Rj;=`*m)lKGQmvb9+5lD$5B(GUCIDsi;jLfOA-2S4%>R<
zdwukK%YCS$5}d{e_JvF>V~=w!VE>0^iY!Sb<TRpixZUtTHbWzf!{~v9;8|O8#*;o}
z7-V%S^*|>O00FEQcwGb?RssR`!6Ik>Q}ccTT==cSG_n8w+JyE`9E{C8(pA0TQ}6<3
zHPrXNed8Td+HsY!I|^v#7#WQ3Aad_UI)<0;Od*Z9m<E&i62-b0a`P^Z%>*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#LnUUqs<XMIC(`LNvJe)i~8pQZF>s61D)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<a6<jz8
zXqdUje6_Xmgt!qn8bTR&AW5#15TSg4FUBM)xxFzkwl*<Bevv7S`e(D{{<Hx#bnR4|
zgJn2eUg`<VvuyN0rx`^aL?m&$*D`7lUrD@NgU)HXH!QN9AnfMh1Ym%!^PiDXm|i@h
zcIa8&lh0Xz{(TNQM)s_o2ELU98~G00Iif5OLaM9O$-!+@6gt8md*Ky>+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#fa<L(&sMjIFoJO^@kGKq@b&`XGyp>iFnG8
z;e_e`D|1<k00p6reh-=pWntIec6zcEK+r%NY#rhzL5-ZsWi6S2It*T(yt4m`F0kWK
zZM0O+K@Qbyqz4x)Hy^o|8n^4I<6l8$%HA%TL%q2#J?E_6Ts~lzTHQP<{gHARhyv@(
z!lUvlck$ee)G1qx3C@m)x7yR2Z$5PIxc}P9143L&lV5N25aelX2{j&O=JBB_&Kw(a
zQFpa-Un+4Ciii}9zg;KPRU>Z3;JMh)m>Wk64A7A*PrzZuNK?;3itcJHyd<k@5baeR
z^MiqJp)5py6})fj;69nHX@S@JZOE`!%WbQ^uK)f@`=^)!R!Eh2wupUL!+XE#=KMHv
zne2_Qr6wTm<zA8I1sjHy0BsjUkFD)?u@7EG=1edL($`YO9xYaL^-5LjnY*HUr@oJG
zrGlVksm-{~Ejt+X-T)tvQA}HR%i-0jAt6na(O{O?vmIMSy=Kyx4t7#4KiB><H?Nj7
z@$Uy-$}M!14-6-OPT-OV(Kqi*-BMK)5SVA_t$In_VXq|u!aa2J_Ghc+NZwEf00H^|
z>9`5b$MG4@Z$a*ixNBMw_Z>lcs62vPXy_82ij0U>g}=kTo%Sc?$tt=HTdLoClm$N(
zVt&KO<g7li(;<Y<G%3fVmRq@x@S(l1kIR1?B<V=sVmiqTU#J8P6Z+L{sAmIi1MrC;
zj{<z)yHBR9H%8+h2G9DU0rh8-7R0zxIkZ)L9HV{lat0ci5*gp-g@ocZ>qYFcpYNoM
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^%N9AsUZgJvU<e#@e6C<EL4vq(EU*OXewo$Yp2dLgNjQuibz
z=az2b#$mEIFk0`{{hv(t)S&tiR)o<h@DeRmnOG_|ZGO019oLttJ!v#>QRuTyCH@SM
z_VZWHC&uu)N)isSdG~)xi@J$rD6S|Ps|=>gS|v<y(AGqfcw-+2-Te<|iw~?}R0qr6
zd3g`?!xs+_EVTmvBxcjR)A4Y-!8J+vzu+6Kz2%y-l6<0sfYkpL{~GcRDk1$VF=9^x
z<Aaslsyd=yR=TI`tboi_Qc_o*dDPd##Gq?`Ge5NpPPQNZ=+$Sqi7xwjFP|cWOA>91
z1{zH<IB*-GAjF1)CJ&vhHQ!joTL}z2k`AlvM-9}va7`*1Ib9SK`Pt)0%??NyVAz9(
z{cR%U^mQ3Hp3=8x!<f0=zc`!3COMTc#9ZNZA$A&b`XtQ|YK5rW6YP?~?lu>%FU>2?
zd$5kI$;eVtv;X8afd|?cYC<NfHN7guQ0u0(d@p49AqE$S(U?v`C>S9vcu2NUmS!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
zBVt<ea5XjhD=O&vJ9+_USLEc(?K&XL1ANjPqE}ohn3JnJuO`s>lMbKo$Ga%JdPWnp
zKxk2S==x(tYDcM2%)^zfAXdZWtSCHe2cc!MO$>$u>pPwM{EI9zKs6fl9gU1@Ii1Kk
z?TIBDP}?`Fk@%|d99yk+oN{GBcd$<SFzww_pAJeTn3~IK6jU`wcT~UOmi^%K_Gd>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+L<wF%6$xVyZw8`<m47}*1_8uRAib(SbJZiGRlY5L{hK_E
zwbMgU<}&K|GI(8pMW5Sisgjvc4ZO=YQjC-<2V}kE#eFJRYP?y|f;MEgW65gxsXPMk
zOv&IisFtr8B!=Mg5c|CIs=-g!%WBA!Y2E%t{!vSGtEBV$gcKZSMoX}X<Uu)-D-1-7
ziUNOK_}%Id;lX~%xN`_}=8!9&BmQu}nRQh{b%|zH3>b|Ar`sE^kPOgqbn@1mh_u^a
ziILJh91PvDdY&Z?y%9F5c=CI+7u+!aXY2~HaTLX;)n0#!Ebt$n<q@s#AvQ2nI|K9m
zlXR{2J7je(+t$e*{}=WkC4e}PJl}<a>1>ayA>*v^U+^UpSt=55X5NO>+YN;fOzW8(
zLdaU#2qN^>Wlv%3dhxe6Ps#cc^D5QcH+GbiKnRyLexHc2W>LApzzGY_MG&kl(hcZO
z9bS6fI}aKjCo}IQSTGw5*d%XO8<w(ReoJO{SeSNGC`(4X{cHl}fO;Y(n_$VD%Fktw
z6CwtmPnZGnjjhr}0qv!nXx|&dRR})$Bss;NK>GXp0_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>F<VFh8TaDmO%=qTvC-48k@oU?E6%kO
zUB>u>UonfTvBv9g?F>Z~^P^2kwEooJ3j~Jc5hj>UW5M^NA|PSnr8w76>8^&Sy}0<Y
z5i5#O!3EyO=_YRt*Xa8UE7kBO*v*EYz@O+HR}v`Oo>9%39&O=)QxeWnKo3jJ72%N2
zq8Y~%NcGsBP@e|>2ce+Hs$}a7MTpm6z3Cj9zcx}^3u`7$wjGDT{4*<}TnaE<R(o2<
zq{w;eZH-)VN94M;G~dL0as$|*GfyWoPdj=cm_A+CHmYtXXYSQ71nKiNh2avGp9_e^
z8uN9~z2*OzMKHvb-$sXH2^+6ICnZnn$3Jo<AP|`-CBzeWZIs=qNqqib%U2pj7e^XG
zQF!gc5LSK-D8YJ!wJ}f8-J$r;B-&1vr(c9nP-+Up<oe+dz`6(-*QfpVb`oa8cZg5q
z;cSw+*fnSEw-V-a+=^v%4@H-8przCi>C2r(S9SrgJsR7IfZziUB!Xzi%7qg6eEpG3
zY^bHi-MRjeNOuTA%k`e^Z2P$tvR!KjK+EJ911RSraPD@CroZ0H%-Qc__MG7R&i4w&
zj^Mw=+UMhwfg2bx(3oi2EEFyB;Pq<yGB8!)f%c*p1peC4s(#e(gL7jxo10bZWcO4@
zpYWc_@24RyVf6#P=`om533q;!eXX{tNt=Fc(4u4j*)8+SV6CtxMHES*YNEf$>rT+-
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
zOvhA<C#St|<exB2g`C=^iyP{&nxl<uR{WR{REwl`hbqjBTyd+<x)dL_%MwBU*YG_H
zZ%G^|2y^*%!dS|WN^XdnQ>rFz^4kBDF;<!==e9k036EvW5}H5G^(D%Tw6B?5+{SrU
zccLn?6=(1i$~b>Y7LH=9Ybd~hD4{z@(k%fKJ<6N5wvW8Tt`FHhxiHMk7fvmC{!bw7
z+_ati9li08=zwa?k|fZDDaX8yLz1aT8m<E}7*E&JNxL;5`|h(fO?_H3vi1JsIF&*J
z#99SizOXudui%5XIs}huciSs4twH&f!P2+&*{xJ!>QAZJ9U$)=<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
z<ikk1iIeI{yb(IN(6s+=@%2==Z(XHlrc<sN&md=~8C+v6fSNnt%dS_0?OOCK=q@3g
z%B`>gJ2v6?1(B*}@)4!s3P7nEx}wh{3XE`+V~qB~$wswse42g>%&KzcVKul?@zheV
zEXd`Nsm(rj7~i059RCkJq&LUd<PXg9_fOx8H)dnj|NBUY9&G5)7;myzmj8r`##3)+
z@Mx~(hpm-WF%JbUI`wr7^BLp-hR0LB6rIx%L{-0a{1!9Kw6vdvt?CfLirQI*^N*bI
zk(=+l-{|c8vn$&Hx1H%n&twhNyGB6R9hc}_>o)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^<g=#6H3xm)&cJAzFZbKrS*-
zPX=z?*0jE}w4(_o<d0(iJ|oFN@uro^NgP;VLf|(KAKCrgt5H11Uwy0AG^Sg|c(j}h
zklvB@Dz#riWt!T{^Lrc#{133pLs3c7fMN0K8oF+4{C_(Yr$VFhW?YL0!8BK9ybAuJ
zqs-r-kg0Zs#lJhy!J5jg8E>5;x_-9LC85+(t^^urT%IfpZ$r7i*8K$@B$C^W;I;z7
zz-#N3mKlRqirLnIMhR$YMuTB~MLVvR->HxU$(s#rqY=Gg1P>f;tN6<!;FPl7MU_vO
z-xuf@BA=Lz97`XB3HL!eYdto22*VuRT=R%&i+AVgnC8En4{<IqQz%lH8;k(k0{&L6
zs18Cx3C~sKT>hDyAN*yTOyPa~efR9B7_|Mbc5Uth#$Q_T714s_=8K`{D@8SRKf`O?
z2;nW<cud!mA`3bYs1LKslX8w7DI(`YE6jnVWav2vvYrM|8@}!%46&D|JbArW_*yr`
z-FQ@`138`}Vv$H}38YZ;K;to|gNXp3Pz1=<93bF|=VU(sY`qt%>6!Lz(a$DG`0-}4
z_C?DpJ>*@3cYQ!Po_+o&Ec$PG@wnmASAqxKnX^qGraqr+(t}|oJPz1ShM&Yn<exMu
zLOQ=IyQh=F*`AIzF@G4<=xJ!ISygQ2bqnLPSd6-VieeYw$q*Pnu86*8TqN&9y|I3z
zUvJ!OlPRCykr3)3&UF-&n_->)U~zX7heMI#T7I(T0Ccom>#?eM?>Y3g=~(w(rG6Or
z=cQ~hEs8lkFry)m8Y(PuLp)Dkb{Y<s)|0yo(e%@g>=?TF^zNA6pBVeJ^;R`tgGJ~r
zPbo<xf^`_V@1y&Wy5uIt2qVj$_OLPzMmk7lk1fj>^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%GEINj<G4ScA15RFj5O(c+9r~yGuO*NWXSmlsCplqwVO={eP2Ld
z3}CUm5zQWFc{rH4k8nchP};nDBx<i;A^tM@c|aLctkX2IVuniR{H=krp{R>JEfoH+
zTzC-ng<hW|YG>X-<R*AQ^;=PnJIujzW1`#H&k9*xZ<kZ*8WSSUd3utn@BQe=`)Rk`
zA}l#%VT8c=om(C@vzMEkPX%1ogVMA^bZt+>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*<s%)k~j3khLvy33P;&TKrA9pZp>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=1KLM<O3H{%AU35$$){S
zn8Dhk#14-ValQFWR`dP~$>9-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_KM<osz9ARi~nxkgxVbXD|g!rmo{9ZNY3rZMXWk_;>yHz`Q=>bShR
z<cUqdLgxLt*JP2rVph5OwiHQN6BrK(5K96OnZv;>gHjJ2Obf_8WNh?DFK=>oIN$?+
zFZKw0IKPLN=TR%RTd7}H0Z8R$z=^w|m4uF7{+8#;<q6CLOZXv4?h@09TDGW&7})Ho
zT)eWMXCx{P6J9Yl-6iLuGi;}M{cYnK2RdE=PA*SO8p;4!M#yGV62jD<;&Dt!1`7Ip
zVifn$NgiDb0;lO9IR9asDg3+CUWR@3U)j~LLM<?wxr+enWW~<5Fp6}g=(38(xy%-m
zIz=HO{;jmqR1IFoSstD}e{i|&8CK78oMYd?TW$xZFLG|7H4~VVcI8Sb;v7d~%Q%{+
zfKPqHz~0Jn`m&cg3$=D+6gUo}-fbTpRRc4j{Fpc?Pk_$(C-Is`dxZh@T?T)o6UN<(
z`E>;vvI54u9kx}&L+i#iU;aGl$s~s@o+@PTQVlOzb)5(h$g;4S;6GLm|2<Lei3Gu>
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`Ik6Sm<lq8g1d(A_hug}EZ{L_+L3)mG{)}$}@*V7{=BrR{cvbQ%O
zj<`^e$<oXT8!NMfu=ip^?>oP%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=(%u<kL)eO(Z~xpQV{C8P_i35?@c8}j9Q`$
z&i98m9;wjl3R7_v^myss43+5U2pX)}*?#DqZ@T{r7ogK1hg)D`XsyGD0#(lY>Sgu{
zDE7<?iCG&@%r?=pQI4Ti@nw8<a(`e<VO8hei+HKmNI*yU@;qrBHO5NXOImjU`WIXa
z%6G#Kh&N|rIY!0VPEyu)vAWmdI<uY!kKYfS!X4#!^nd&<KR{;{!Z&xC+np&!gV1>w
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
zk<w`b??L=AFc3I=b;cl#NZc|u_2M)3K-|nqDn$w(vfsN_`LAX+4f7Vs5s+iW#gxBb
zcUKP=ux_)tZgVNdF6=_bis1c>Xz9I!6Rl%MbfG}Z7$K3v@al_g!ajmA7Oyz`ASXWn
z7$=6WS&GeaZG#naxD=-h#7x!bREf<D^}?w)lGm{C2Pt0YYOXA`xJnmV@@8*$(<sBA
z&UGh$O}VZso~B*s#eNHl{c(FUaRmxylc_5EB4|EPf>~oxnQT5MC=h~9sLU4&Se!1`
zp5qo^@iPGSrWSZ&$K%;j{f<P^JUR;9A}jy5<X#HLNYR=co%5*;mtP0egi~n|_`wMx
zk}2R;g#|Ic+g&15{@qb*7m@E<f+_USRsG7v;b!5hAyr<+(}9z;=6iy>c%)^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<fG>}<<)ZFYldt>?uTkb(L?
zyHJWoeA7fG#iRf~#1bm@)pc!Mx_R1mi(tiZfaPlDF>qvs4cK@%10afgI+QbtB4q#l
zlf?3C5{07~@Zw$yVq3fCiXcN|VoEquD>!3JqI+7<uEF6*H=w;&OJ~g_;)En7)3Um&
zyGFyP6oi_ds?M_f0=JvsshsAgVh?HOG}so)eK*IIr#SK<qNI%K_l@P|V1gXY9Ks4$
z(?yA8k`C9+j5f=63d0(Hn8u6X=+C|0@_8L!dyvFyjf_+Rq19*j#MrD=;uA7V9i-Ew
zG_<{`3GG)SW$WWwOlbC8X{4UB;qd8~_iIudI9Xa$UjiM>(1&VT{ZJHnlewcHL*F8<
zS9l(yPzTl3ZoH@Vsz)Ng=UR!ofdA%$^hyl-q>#djr_}ml_H{T~akkzZ`XFY)@K>>{
zE@w>diD<vDRYUu*h#K$9TYiCV(W|PKO*10d4ogg-2N6y1*pu~>!gi9!Zn)))xQB|!
zA+e{20p(0AQ1Wdxn^l~^-b1T8p_pZSO%S8<AcG@?aDSvWPUCIFFpVYVr>{D&zP6Sb
z>E%eENbdj8U6k@~D?G)!-+VS{@Bzace(|NCe^SDUDFlC8Mqf5%Q(@boqGyfi5;M(2
zmlfi*XF<#QxLL67l4}`v&S(7D0W@v+S5x7Z_T<irR0hJeoAC%tSjU3?)_5a9Se!>7
ze!nE-0soaUsf*$F(G0Gg73R^hT5k>;7bk+~g9~wQ+Io&@)rCV*v~O@^@gF00`yvc|
zFH}Rg@kHM4aS{0L6K^w<B(QZ(@Y|}oT7JfVp@rz&J{KFYq*R6(=eTVAtmisj)H9$;
zJ}F6K?+!ZKcl5wweCrhU<?ytol20m6-3Mw$2(g=xCw3%k@zWRn-<Hj$<Tazjt&ld2
zNT?BTd_2PXSI5(~#W#oez|UVC5S%}WX9ALS!rb}-Rz4!nx)Ge}Z(@2uZ9tf$hkOXy
z40(Vfv!^=$jg`VUAp0Wg)E;`-XCKFfZCyG4Qie+s5OVl0p&VrqxNjvbrAfJ4{!U0k
zp}0?IW80kr`Jbr?_lJ8$#%XvfdFsz@R12MeUaKK`Ds;|?Lj;%1%B8kZV30Um^(h%~
z<yG-o|AR~weH-(cHu3MG2A@}@e<BAF)+g0tt*Xr~ad;<$p11lDs|tYEKnKv8B{I@w
ztuT(tMjn3-TK4XKJ1UXIJc_1PX3eh#@G^5O>5V>V86{$NE}-`cL-e_sf^YI(fGw6k
z(8t23c>GF6I*#c+P>$7JyJBEN){v*xR8EU4vt>%i3tyf&eFGzT*6Wl!422otsAUM|
z%w=68&RKfn;}jYp=}<O=oDpe$8ksBa_>Ho(fNNZLW%6WZILSSS)QZW_8cvHr%$^b5
z0m!OF0>8AL4~YT(#7)_Hfj03GyD`(RMw||c<#F8FnxNIN6&jMDMboa6it&&iUUo8D
zg?lc<AZ}EOPGGk=XVHVQ3Eun~iHbw6ybTmXPM7PiX1%0-TlD0iQUw~ysSXt>>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-@<gH@<JyH!3g(5w{K~mra^E=GBnsiE8y+SogZra+dGhKtOBdP^{9>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)>nfkF<GE%pM;-*$4<@hw5M%^we5Ub#5$%A~_Il8l~
zcI0-x-T|e%*$kt|L3y8l4)Kd4(G`p*H+-eDmr6^@!m~|bV+Xf%2{TE7%}?j|k9j}C
z@p(`$N-Al{^Z!9Y@;ud7iFsYUhu{2s^WS9uELahGCvkQ?Xf}YV!niuZyGacQ(sHJ(
zSV^65?tm!}_BU<Az;!N^tYx#hUM2YVD(r~i+63BrYwb6<a78#UgisV!Ccycv$KK~Q
zc`A&wXjTs}=FG!S*2j9NT{ep!jl-FoV0|$d;+5Q!s^g;CP=A_V>py({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$-t<P@GtDEJAj4e+0V
zSk*zKEo<QYiN?<dY7Mu}m&;J|RnKPkt?>B`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;<Mlz1%h9
zpXuHuSYPugrjF2?>%Amv0(jLGw}xtd)$z(58KiOnHuN|uxP%m|mUh?>(VVzkH!y7(
zdZu#s7%?smH#8m&#rnnLG~TnF-i(c}6^nxsWwDv<?$u3B`xLK~kDnArAo*tbRDST*
z3z_%lD|O?lPnDTw?PmTKSPLJ|$4;6+7_pQv5@|HJ|NaAKnM1#fm<C9!^-4i3cW220
zz9}>4UvE9bL)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|<CaJ;S6v5gIFPXXo
zb`Xow1J2js_!ErH7=jD^0|6r@u7RPIu|%d-9s)0Y+XQv|@=;+Kei}>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%!UaS<xq`@>wP)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<fz6~%~PO2<dMAE)cN%EEPa2W)`
zC_(XO`7pnLmG#GL6ZzG@pTUBG@9U;F=BbLUO4jI*pa&ZPoa|v%bNvCm77!GhMc!N?
zT*s0HakLv%oj2ClLVRi*E^B$F?+!Kg_xHawSO<_j^`H!cij;*%*crZ3ipp#F)exqs
zu@@x~=D^#YH-H9M#=Q5uM8r;()Wi*Fz@O(07Yg2P8R9F_h6J5sUfE5EiZz<H+Hd^C
zcKuL4NuG@IzOFplxK%w<kRd0@*spf&adkTI1vTi%Y~B}i{)8J7^SKL<YW$ge1giXL
zpU<S348AJ%9=T}KfzndLSl+7Pvu&6%YWD#=c$wyR<t1z>!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<R3Xnyg13wSC!;H|5<B)+`gLdSNG+5V>+*vN>hvBJo;wHF_<J7}bOGd`VQ
z95=Ndr^uD01XAu!JZ}z*Npu!@>{JTFrre%c9V0H>wfnW#x9gdKi1ElRG}$%?C4c0I
zu5doKFywZ$t=GIRxI{^x_cuJByTnA&GP)p>NzT$&abwE~2T0m}(x<I2^tkOa4RGse
zO+&~ggnQn8jKHOy;ejZtmeSUUmwDA%M-dWRfUOMv7Ln^yn@;3h3Nwx|l`-OZ7iLhp
z{WFlx%F(}yugul{R7Gz<!-OK<ms6;_3Y?M!u_VHjqXIry|G7wby7Oi|R=Dr-(i;sA
zLS&~>FIV3o*YpOIC&N8Nd+sb+erDKNzT{D`5j;^%L&r-$;wFT^<{}>7A)R0G$GF=p
zh4IWgh@K7<!4CLcqN8Ru&XJ(uHvQg&pVbHu(Knp*L>gzEVZQkM<HFX$uTZ}IO4>%?
zd-A9g&#s8=??dEmS7+yH8LwV`d6TJzOYO!c4N<YztpqQGgX4~~*TWbBc1D383jn#^
zx^RZRoON0=zNF({vSwN&koT|LG^rJp5784aLZen{3T8I<nrxLtytoSS634u#&~)sn
zrLc*7k~V&GkR+kT)1S3-u=C_8EOPTqu2d-@85E~JYcQ!xuvJx7U}WVSr%@W#x4hu(
zfCtvdHhD+{i*9RLSwNtLQD-z<%J5(9!Trdr_V1PAvT4w<P$IZ1FjvMkp6MkS<20D-
z@3rteFa|PYn&#W_(j&KK<$Z?KaLlJX3L^iWLWY;8d2htYdI!g*z)tRMi(m2#=cX09
zVD%-+h^5LDi_K^773r%JCy>o-IC;MnnwrGQp!(vG_u=x6D2`Qw=a-1t4TucP%sz9*
zjTPt4Kw1Dnlgu2t<GM@iQF;hYqdV(YtrpYwM2Il{`>$xgbaEt6r$7aYu>u;N`JDxV
z<iSZj%&sf9eF$3}^J#6g?mtDDp{<i@sQTDwntbd`XyZ<!|0|-o>N2mULlSZ~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<RAbttK
zgJ;)SzxQNF)bYvD@NIgFh4)6@g;o1!eGI%jeG8)}>+?$hQWZL-Yd9Eb(PV@7xDmp5
zpv4Su4b~Gjw-<tY45-2vaSNB5)YeV4j8IvT>uLV~Y~1$~=A|cIO<-&dV-XW#M6eRv
zXPY3}=&uw)N6vA7+3zbojW*MiY@}aRM}VB_)eckFpeUVMRpAaY{z0A!g-7tE91l4O
zPpSF^@ymc0ZtzI<w-Fw#;^s+pyW+8SLdd)NpC{H%4^w9$ryO$Hl}h#gyO8P2eitFl
z7MHTK6gSvf7!Tg`xR_H|yqW>U`{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%0RkX<o?+Ij{<+FO9Mb2^9yu{svqWF-{Mz&P
z*2m3LHO3TuM~N9)BLm}l==FT;&w1u3Lq$gaw%`P%leiyr2nanE!}-hw>j#vf%K`T9
zv<?jiE<7K*$gtvgf0gk4z&Z#g;xmRb`#yqtbaV09Y#~zMu<pMf{j5qVXSUvH67H@4
zv+YySUnkSG@*_$s69J>Z6~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-<b6bX08Mwj}ribbFREvOKJ>^>jVqu_ZY+=ZP;4ZJ9eWa066K!W~}Z<n<1+02~1be
z(@H5>*MluCrO)|}ZXOLVbWVznc`bhDGJ0B<PTG&#bRF^RU+nmB$H@AGs3~9^T)Q};
zM-K#*S<}XoY;Nwnj7%qNx~xh&xqER1u()CAaX>tpMvSmpjMNjGmdJCnv04?sCK8ji
zF#WJ$1qRH9@{s|UQGq`du(>g~Y!LohM(}DIYwO*#;z!Rzw@3X}5UqR{-Y*=_L7uoc
z+H1+s;9ddm7h+?);i}iKt$?}ySXMn%Ywwi<UG540pShkm=Q@;ai^<=QS?aTI!4nOV
z1+_fIV_zR1xtqTlXnlR*Qu}wKuRq~3e6-=E&BtWBh>D*~-iiRcQFDm<_qGq&!=d<y
zm7|aISToxuW3ZqDzg(?wPDG&@fxwk-(dht1WnDX}(Q2hSUX^XrT}1Wq_ibUG_W4i0
z?RYcjJ(Bc-u<z8UjbEGgF%v|Yc4JBxgUlpd>0^H6X%V*G3vo0BK7lW7uprIqv`J_m
zj3KXotSRld2XMQnl3pQ+K6t2o^+gvqm*?Ox%}$r&uXF3{Jlmc0$>SYsqt20D!efJ9
z?48P?q|0M+x%3WE8s>bwc{#SdYTn&#im^JzSL;z2x9<VRnK!yfi{C3V?j3Hs2eJ{1
zlD|>ytc?&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_ro<KZ7y98!d_#My$naZ_ayBbQSejCaXFfoYgMM*QUOoBC9(F
zO)7PW<RtThUsqgM=n)CTUz?o8P)p;cvMtk1I;Bgb{OvR*%Ucc4LqRsmac(B=%9bm}
zED(R87<x}xTRlDn0f>PB3h5lpu!lYCO9;dXWe7!_4+*8f&h!J&$5egS*79#<$rU&}
zc|~`ho+spEUmnVLg96Y<;8eZst@IY`g3|q{IyB<X$(a{y)*yMF<5h{yex*H5$>GSq
z&hSx1+<AW>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#<F{RWhJcKb>KLWo<iYTnm2QOKmeetB#wu-TLZRb$
z(_}=vR?JUnj;ZPDsFiG_)zMRuR4z_NcEqu=J4(B-I0LHi@KmQQyfPX?cd<Td944I5
zjpa_^hbuWUCnzkhvm}sRJTy$alD4*8tCV~<d}72_$oy8&1m9*PNe->e6$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>CR4<gcD=Y?crA^c&NpZ_=jg9)6q;DbvYmn{Wog)dTig;2-@7EC}sty
zJfpb+J<0yY&zaVgm{QbFjwQ6@Tu|nRuNAr^xukjEY;3i*o6hOopAZ&qhH>LQCUER$
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?<xPNL&VZwxF6}UUiK7Nz47c7w@@K
zfUg6=$oVd58$_ZlSRdugfDsRAp`NU;ZA)~m7)===4EM}pjU~LnsPDAf-{G1h=%_%Y
z4emsJi)JmphzduA;EH<nBdvXIJ!wPdFiNCh7f{vqC+~Z<RfBgqF`YM@NX^mX(&AO-
z$WXG=cmmJae)mW$;O5<}K)7q(Yku$s%ssdXeb&y};r6>6Sp;?$K(@$Dj){>E=Nkgx
zuo7yfDY4FTxkdfV80n>i{^4@G_BoG91R91cyrYhW;zYx49T{P+_QW|a9xh1gg&q96
zRS5!~Zxf%+hV5(<al^qbvtsen!&|w^Lgp=g!6kIIoUHz%660KU8q^%&SXO%MLk4Q<
zV#sx2_VarxT3f0u?f<<C)r*>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=;<f
z#1TwG%fXT{)L~c=!9Uk8Wjc^ekH^7^g&m3Sj`#`64RZ2BX#aS9&d#o;*ebN-G0x`R
zR`yyhaXa493ixz}l#09I<o4@(ha#0cYr~Pw>5uaJB_@9uiOlH0wCD4H2U#?+dA(+A
z#2xe=Nd*2cI<Tv7*?=o4=h&sKo5=h7xkzqU;b0r%N)<0#>A65&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_~qh<rkBb?LD@sNCe|{YH>6>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=%PO<k^vvA)$_|BOtB7z1$Tq4QZ#2I+d$
zas5;gPed3fsTxLJ0Qv?h+H4yRT;+npwu(emZ|WvH)^r%KRVG3CvFXdJRDx#5?UZ`$
z-lWKTKjP=7<L6=kO7_Q%HPaUuQXRbtb?n?6+3LycB%D3x+VtWZm;I006`#!uceIVT
z4Awz^>8If72qOw@e8>O4t^_uiL59T+%Dt0N|HIo~s$xC}UeL$H>A$)W_EUBtNLJG*
zREueqTfZV~3g1rPd0V5LyCDO)p#ptre79j$+0E^k<zZ=8Q=mew_8e=_Ad5415HZBa
zh*;ETM*7AZuzPoc4p%H5#FbtaF(XpE&QarC+~qm$ZGTOllcEvXj4oas(_>lmthR25
za|l~%>!?5`-2=zDeF%!R!lNYCiG>`03Nb^_bV_IcSLHj)a%cvgrE^<aA+}#6#BuOQ
zc<?u+fX#@xN;YqEyhI6?c$XN>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$u<Jce28Jo5=g=1o=
zfDo?}kY%u$N4?uHew^sXe{UJB+r`(`ohk8iq1Ct<{nLQ^?cZz8ve54-E*BqRj)M0r
zo8Fw9z7C<V-cBwW&N&`%T4W4xa348XyQwl}^OoW2<zE~JVeNgVRKB^|C3@xn1ss_Q
zN*V2~t*suARgi;1DDPJb`6%V~f;pH>od$N@y`OB@AlDJJiEy_1rR^Q3VZ0H>ctg<8
zATr)|%r$Z)I4aOmKnxBpLeS#k=L3^!q|k^#V{I3NQplGC_FUq4|Gylu$gn>aZ<brD
z8=Yn}s1>2j1|Q0?6t}Hb92RbY?ZRUDDjShU?bayCU7;s@OVIq9qj^~Z(jco4(SnYb
zuEl@9(QO6F6O4(({*>1aJaaB<=sx<Uw|<Vtq$`M!T&uk`{t`6&skaG>lZ;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<wH;0
zPG8_w71*E-a<wVaG3cm)J=HI-O%HDHxTP*xl51v+#(1S`NyJTrTN_n>$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(hvXispwz<pb
z+y}Vr0qwzFBVA6~<<UW;IQawt>0~{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}<JB$s6oe%#Jy0u<RxgEGEY8>sh9tp3}Lb#cR`bi%(Inv1sZz#)0=aGmt
zluv7>q?rsI&Ko7U93IRhY?{Qnr(<cHsrnKPgi_%bjDt*T9T`XbgqA%;7i)KrZWjh7
z)U54x3TTE7IuwBeKxZ3%0wsFU>%?Iw8j(d`nz}18*6W<L3qf#d+J=?)rmBH5Uk0rG
zO~@|J@mr>`y4+QYGv<Zfn3?z)gZo;WE9Rl_8&}iq7>7@($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=q5EgGWgl<waudxZO^1PZ%1l~
zNx@n@e*Y7*Cmp=Pz?DD8^jf8ZN<DyO(}oPdlgN9s&?jftAFKTCr-^n{KOD~8b_Ge5
zs=C;JlbAx2WwV|*7rXnj>GRU)g;YB-0$L3ZnUKu^iQ|yktn><RGUXm|AvbB=sxod*
zWj!-Z-dR%V(143~M~nEn&kmSAh8GNjRv1R4?$&jW7o^5><}^Xh#L|&L<&7D+Qa&>r
zGpO!SJxWR<iMOwscVl%*bdemdN_D(rCUjQKWBmyuPL&+hH@pH&J*-;9X|ag`cKO=b
z8MI|QI!;SL_Dkjn=~q5eJd}F5?WYicEC9d$+`0hbSHVPjXyk$szPuPdG>N#)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`XD<m!|9E)er&v3B5+Pe0vu{GmXJ-c^Dr*COg8;
zf|}k{UK${g^=TnURq5M`!)!NrR6bcuN|}q&Y7PknhtGX#JfS%Xr@~`+p9)y9fZ~1l
zfvsn9<l1o1mVH7Dupzb4kH1Gj-9;;83%gYH942V!Yp_yG&kV4IvEZ>iEKPEblbP?)
zcV>ZftTrme+kJ20Sqb|F>mOY;U!|c=4#(T@wpLR^V4{ls^_=&S4i1Yrs~&2L0%2+w
zp+<sy&L|ibCx@Fuux!OTY-3%r^<W)cdA#1sp>owj8L2RsJwbWtPnd}>0lcLMVz>CY
zSDM7<?*}_yo6yv!r39<s2P3w#b*}gpNI6{Y6`mAt#nTjlck+{^F?ALnp*SxV`1hR9
zBdUOLq~xv=G8}}uC#76VpMW$%tZTg_f0h=MI6JCAD=Wae0M+(L-^k)`m5eJ^8;m!w
zQUFA5&daE!z%@|FaBB;15LmcoU)~brPb}cMBcVxov$Fee^$1a3{R0t3RWe7Bindij
zLuCC&`F(u|gYEbG1b@6x%upBFH4re5`>7qFDYR|q%0dxz*A*!8F;*mYNueU%%t;(9
zGUfZssY>k<`OB{i%75_*BdUqmiQ66uWc4wT=}Xbr732{|6*-srO)sl|<s$bZf21*o
zUHf~UG+h~VLVZ8*I(s!@3OavJiXszZ6<MrEWaW*AEGmN}cdrt8$90Ie*j}lr&=-ki
z(O=&DMqY^2v7VVnE@`caXZIeb*WIlxROQ~&3J^f?7c%22CV$o1fFD6_=`~$yN5Xuc
zb%JM|TLX~s1C|1j4}T1x!K5q<*erGEa`?Enj4!|ap<tZTgS(3aPN>&<kR#eUZ3Y*q
zmUChT1Z0=fQ)Bk5`&ytvtL6ZX4xu^(hFNB<-g4yaKNS@-XkGpsh3C22zxxVS9>inp
zafL%aoNkZvK0pa9!L8?E!D#c`Z>FZSHFRJ%o>O!77Zuw|#^Rth!Xw<Gg1>%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*4oEXSu<!DvJ)M=NBSJQ^(j3K
zwczJ>f)GiXNY%ZUF@~@EJ-bTet|J`QfegE5zOoq3evTB;{)5=q50F#rSPT39p1ob9
zZG8@2L9ip{Q<r;vNkN+J+&ffla32JVzPjX3kd*Ui>dM3}iIAt_m>2R~pU2jhlczzG
zz74kzVYzPRxOmzR2R#|5$vOH<kF|;_v)B&6?CHi&95x;bQ|tXKRgi)~ITSGm_8d$w
zi6Y}4cp)0j?X7-#mgm^|XQopVh0<2wj^Tv8NGqkydJVUb-)Fk5pPrN{AKYTyC*Vlq
zde_Y?Smo{CDtV!`;N!?IC-7@ku!xcV?y3gO&>6jcK0iv$&o;jBp(~|U!3{2m9D=jx
zUQYG!s{zyUsA1vX?Zzc8H(`qX{<iqk8JS)Np#BP|&5#GhZG9}UN8^h}6)E{k_^P&C
zjT=!W{H4)L>HtkZvcL3;4{tVw#eadl;{90rX=PtYXY9pZHgU`Fw7w|Twmb($VynL6
z+3A1#b!3naE~Evi?(l=#r3fgg*M7w@-3K=OjnxS(bU0p<TnprfC+kfc|Dt1*?_(#A
zBsGU()e}v<Qqbx+ExH40h*9^Or1m<zad$q~Nb5#WcN<3@H%RaRnooL!?rJ^Mnf$i+
zCwdw@J!z6CIx^L0v4G@vCv$4HofR4u-j@+$Ech><R?piMB<!u+GhR=J<VafYJdG)^
z5>A+hl2?ejIR8k_Bt5DDBDXNbv#&ql)vyrLJX%pnOpBH$t9tk!)S789G^Km$|EXdU
zsc1WvsanlVaW5%vH(bv2U@b&l_f%z>KV9*IRXeNp*+`5eTKDqoYo`7A$<hE!^s5S2
zLkD}AD=hkbk7vVY-%9MSbiI(vl7lMf>XN-;bOKNpV*A{c7*s&um_-D1<Ou_IvyzoM
zFzTHruOjFUx~x#>!-;Fi_G-=5RNvP}dPiWQ-h8s~9HqCP$%0rsyHzeN{RN&pZ<GC*
z7Z#!2pBT^|r>s7G;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}!$<r>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<*A<IQovyaL_0SuQsgAC@R
z8zSKxT7E#ZN)%MlFKvDZ1jkvtqd6MXD=AgTYM7C*fapys)Yd)6sJ!{9Pv+5K%1MYG
zj}`(lK>Z4r`qqeE7M@CeEc+FPJy^3#P=GpED<w%L10*GrSe?uhzJOi}fXRU`xu&`r
zHFe4J?#S4ktu8-AE$#En0tQ?B6Y%)fv<)ZfT0pYY5#iHgk43!NhhOi#y(1hzkT@vk
zWvs~eFTZ9>#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<1ctzK1midOU<agQ;;nD40(_qVxLvZ
z7}fSYgj7q348n#j?0(n-6s#K$qtXrJg_I5@-4nO$nP{`$5`_D+^MCJ0co)-)`^Wqt
zM)_q~qDR_bvu94NcIj~Tsf{aQKNXVq@@2X>OuSFkkV&GRF-=ppyjY1<vC6y{9YH<`
zk1h^TAD9cPn|n=<fudyneVdJRkAcFK=Vrrjqq`SkglaHlF@sjS0u?XCANU=g@@~hp
z_5qj%M=cnTKkOZ4Ybo21C`Mcqw-Xrm<PY00Zbjvt!7cXUw$wK^uALbVYpFboA|M=T
zamP_MPDI~+wL!<(6nowuat~-Iork~-Mi&(V(cgjrACU1Qr{<9rxOa?O3(RhEM)`;0
zwA%_nRSI02__wP@L%ov_{*a3f9*W1;1Sf|b)<76R=%#*F;AI%+;$#O9+QHH^f=8Y*
zWRRKe7g~sS?-F(fN`u16UXol{VolRJR`QnGMoqP-ujA8x%hL^HM*Jn`?WtR-qL@Eb
zr4vAw(MMJ<>5bt<OQZF@w|e;vW{2q72(!-a^<`4EeBROq)mh2tC6c_9b1_neM<cy+
zhpQX)a+w9!E`wTPvU<kFI!R#42LD_&F4hcfJzmJG<g(sE1qBx;Jf$r*s?&uMRDQE3
zS6u?^&!kL1xI(RHBSX%q|A%3wm-!zR$T>{OfC6doAHs5Fd{xtaGk2ix5pm@&pu|vh
zm(}UJ_CHPdA^oogI(8ziF0YG^^H94`J_M9vdj!kEe-Q2c);_$DK8(=3SHf=KbrGO~
z8^xkWcJ8&lYI<T~S&KftJj_GB_8U_}opKpjGdJEv@q>7H$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(b4<w{G|t>t^!@
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)x<tEd6%T3mGN
zElIil9*C?ig!ixPS@@PWT7Xf7+L?bC`gKx51NBvB0qDX+|3lgLn<S9@RK`$+B#?F_
z#XI8e)#ju4le2V|tz=$2ejbg7qH7=9uqxDz*VXKO{*!h;!WpDQZ*vN%xs%8np4^*3
z;@-Qm#mvT^B%u;?4HCmxD;#0TN>A9$CJL2ryN>gbZ0;~Dqw25TeSc!=@>B6{S<Ps-
zWZ9lnuY!Appj8e*JqvM8j?AX`US!&j(0U35!ljXa!;2A6<$E<ZEe`y>42N$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@<Yp)FG<6PS?RRqU
z1~y70#y)fDpAqGXyjkRM_(w1m8;`K2F!F32P>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#<a9MC6OEnN)lkwf1W$r)Nnvr
zg$4WZ7-M1-3VTmbrVkL}S!OcDN@+<bwaxOo5Tlm_+QPra-HxMNZ-pr#`N6~`u2~3F
zsn^ybVjyHzRld2%P_3`+3gSB;C!{GVWf?Smr+NbN6D-bqD55eINSY2x#&62n+A*(4
zLTl4bdINM`iP#*&AdgaK(3W@dOT1Ha_*aicUfuvKw%?fY!K7aU#8)-+!gjDp20Ai-
zB?E_z`AT8%<#kq_zjVZ9vEsb;%PA_uAFNzGTb#BNTENO@?fI8wI#Qx%*&#^h--viX
z>~<?|1I{qR7yZv#U8l#wn$9O9^+T6QsSZN0a2b5UXW2R-nkHzZF%T&G^IY3HU0*lU
zo&&t*4%umIA|G~}L?bIWRMZ_A`Z1Gty4G;wva)$tGau+*(-g~_vExSluIzm#$F7al
za<tsAj#pS#m6?oxoP{N84&UInHPt)dj#*_H^vJ1~dXH`~O^0v2_pZ)P&wiidReLF_
z(~%rZ-25hCH$tKL)G@oZlGT~J?nKN;pEeja_qoAFX5F3|rd>hs?pd^$-^y@JFeQdo
zwg*{P>k>&KBbrB!`SEG;$|uwQclsE1rkEO**%?u9KSkXAA=-;4SF@N7jYw*uX@JkD
z_;(T1^rI)iG_I+Ty<L<rqb<&f4VC2<M}jF?9_c@v7tSRTf81I7FovKeePp@IDUCjB
z0cFEVqt+d#YC&>sP{u-vvg6E&C8NP)mZX1@yh&@u&fpFtpVQUCv{4xxJvmL${iofl
z(-R517VebEjnxva_F`$`f|?vQc>o|<bM6UgTx8QM_yH0Ly+*|f%^XmsJx=vEf=ALY
z=Zh*UU&xLS>dR9v{j)Fl9;@xxK%*)pH2qin7A3FzM+Sbb%jQ8sBxYdMkN<6C_&%<b
z!o(?CPWa%BD5MCbghmv^AzXwU`1OD<z*m&%{O{Z9m?4c52^4%5nh^)U1o@V+9rJP7
zj$ZUL$eRzE@kzL;oLr@l9Y8brbOsq)ABj~@$Q!u-EivIZC&a#yr52g*lNKl|rZC2B
z;1GA>OqSngy1M0*!-X-%kdQI2ry%$pbWGBh4X+G}T@Kjgu#V3TXX3;yP6{ly-*~)-
z4#ko$m5UYNmil5`sc+2>BOl?PD%Ony-y5ROvf|ozJANpp{c&$*GWNM{o_7%<Z5mk+
zJAW~L;;+02-W@@GTwfzl?c|?ujxbA$na8BZ68Q-i1M1rbgf4d5h+)-k*;G$6{%nrl
zv&#hGt7KAEz(3~Q-IcFnZMBc7Vk++U$_%abGk*3-xbAu6)iV%0vG!70P2k-UR?i%F
zsN}|(6Jnxs^4g;Q;`DmztuxOI<8VMIJk@It2c%A4NSGdhjC2<RjpxW~L#l$PtW^l;
z30;@A0;m&)hr-^+w<W!<HP`*()IHm#s*85~-}y%u)1e#Rw_sX>Y6<t-9oo+sjl%Dt
zb7Hn?^V~V#PMZ&?UXY%&%oFg%+$4cT2jFtcQQRM$Yvp;MTr{Tp?(>n<v_!$t=%yqN
zFu{)2cDtp7RAf5=<*b?iD+{w|EIhcDDd@3@R%KKSthZ`$>t7{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$+$ht<?Mu38TaX4*T%qC1K<KSkEWEi&_#8guUk#%(yxqAiBgDm1|nQ8y*Jo+zxj
zTa`Ea87y(JNHHknn{@=2hq$(XDkL+m*~1#8h0R_n%SUB0?kmE10ggMFwUW8vvJg73
zYlxa~esm<lZ9PP`KBeRr>W&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<ki~eh{E280iFy=$eDRf7JGFErk)spy7<BiF
zCM^X^kZYmu2N75bmc68hW&-DI_2#vBZQTYt&u`yb1q*W%0-E+fzBM6MT&s+ix30#7
zYjEq04gjdiT{j=nL9euyY-uv0V!8PdtAKW4mYa^39Se)+tjncVazrjU=d^6-7W3pW
zoSJlguKd*`KOxfEM3Y#t8Z6J8%j88`Ub+GRtkLl<bMad~gzbXQk&Z)Z@!sSbAgK9d
zJp5dILzw4hJu<!6+Wmf`jsuB3UoUwika6>-V6Pm)Y)Zi+znZmv+n-8dzCSmMGPUHK
zjYL<EOoG)Z#-?iMyTq;ss0P-AnS(5iS?1RusXg_{hSI<CQ7>eSmXAt)3;<bR|Fh$?
za?t?d7x#m#*r-A8oqV7TKdK_4XAH$PRmWOiYU%U(;b+?(m8*B4j4R?5ux4-5@It&e
z=?aGmQYy+B2&=&uE*Z-(g%A8ye?5dsL(-&H8B<L!pABUw{-4>%j1-|YUY3v2^Qx;`
zRF3&43I%%h=+l0hr4Qj`%g&mE7ARss{YP)3#dlrkbHdLSOugUj&4pAYj>BXqSw#N<
zS<f`c#!VBpWYMB32^`KFl?~*@n#nRy9?#{t{0Mj1U|vPmV!L;%f$u<USZkf%Ddm$1
z`_}oKYwKf+o3%eE;p`n?uN+)-ld*1WD>u&-4*fUGI7$-y?n1eWU`&`fv(<!qFYxx%
zh_&_Ixh!!NjZ4G{<>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`RCW<E`Gw(@n8W61$K@mUwy*4ri#MFm|gbemyK6nOv^Fe2A?+1Cj
zmpBnw?&Y0EbS9+5Op!L*Hc}jFbhn$^>tUEM6(v;EGisx8hY@;?M`msX0#U=dfPqo1
zpd4BcWzHaXG5^@BI4=Oq5FDFT(Zg^uc$z3Q;*4`ZD_B6sb@+(M`>pYmEfAv<e3`G{
zi%IInrtG@3+j3uAiZ$~$sdX+YppPv#dI@s;7m{o0Ru@u`g$OBqZZ<(DrdocIy4^7e
z_Z@H99PbG&#_>x3B)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<Hp>=_!1nZ5cW3FC
z&T+#;%?Kqp0-&Z#uM=<m5ypC}Uw-WQ%0J-U_u|qNZLi}AyFkGa&b#N}Q*?Y4F@&8d
z)32t@Jw|2u)KlwqseA%D4WHaGShDkyVu7l}s~Xu0NCsJD{Gej@^y#AX@))gm0*m=K
zWf#-o?}e8EcZp>X9f!iVoeL%jY|DR}A06kOnmb8{6r0$&?cbnFd*6k;<8<nFRXW%M
zenxddp0n~h7{H6QugXXs6zb;E>C<VvA+H?>Q#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{<L~TA@a`11o3HrO=Cn+7x<hO%*|zkkws3JAC+2
zK||}nGXXE9i<i$RF`anrnR_9O)sR_0a1Z&$8<)}wh)lfSWkPu~GihkQf!s+Bs*R=>
z{%TYCXXa;!y-Z;P05rn>#}bfhGD)PM&ympg>~b*@4aD|SUf)kgI5Xwzw1^Q6XZs_B
z<RfWj)t-=U$<MgTMP5NZT*)|5zAW@-_CB^F<lRvU*(UXm{Y7s6YF6HjdrI?+SnYOp
z(neNKoN;_WkLhTGkQS;8pI}y(6S2Vp?ysxB&0FK7MGfc2%)SvQ>$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%*q<gKI_))ZOm
zW59I>d8_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><Qk$Jlc?Hw%2waggt+?N>LVE>@$$f4k<Z2O2y=^nLp}dT@8#k-
zYN`H15F#m~PFKb^)G`%;6=hm1KAA~JN&>M7IvDq=dM`$Jjg^m;V$V!1I1*t80?p#q
z2C5FL(f&LHm$8E9C@Y(Ld}0*-5!lcp`Nhs~Lu^rM;cjr<f5%#xq(`$GMjAsGQLpXc
zbY*C0?T&~jh@<37V5AY^IbPnEH4X<Q2+gC%_$&$ey`=0^eHnNDj`Q8<+#czH3V1@=
zOv+jIMX35ftT$povhhr(MiKIA`N_k<{w8aOPvY!OjUOMNWR+^tQbx-t-#AW&90~(v
z-Y~tquFHBF$-;DP{oN>Q5+0+;yZJ-`N&etzj~z<UDu_wH@$RG<iHO~y_;KI*-tDnK
z*5h|lt~7<$kQMv+g%kvHE7l^b`lE)p%M@Fz89Fhl+pwNl?P&2d`@N#c`_I0URpx<}
zdXE_8#CFV*#uY-L2?Eww>6aiKLf+oz&i`kosko9cGzn?%kmpTq#lGZ0CsW<m!N_la
znCE<kdwR|%{@^`BOXSp-_bP2Ga7A&rHsPtW=vA$FpE{!6rq?Mwf>i??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?Zsh<!*hL!5gjWoiAnb|nfGi{NZN0u9rt1;itSG+(Z85HnBK*R%Qn8(#uWin
zuY-}y5^PnX&VI3j*Vr|mUOMH@aKN>Z?^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#<jq%FX2kmE{6oNMt^c4J{O5b-_6pX9UOO=DfVqEI8g
ztUg0MB6f)IzP&ddAe^?W<o#bWOEQP-RtGO1xum65(|fgVnG@3#%QrC7(tmU;qT4kf
zwaPhQ3`%+dmTZmg9~Q97TvAXaCni1Qj;3<TBT!3(=6g`8s3cdwT5;43$jE69d${He
z?bkT&Az&eth1T<)g2ynjChrf4ii@gO8RXF%=BrdO5{(OgNDdLltvy()alcjWxXsS%
zCSjnvkKF>?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*z<lYb5yH0wD2!^M)q`+sJHfNfd
ziEx~R{8?-@WvGs#Y_d@c;`8^cW51yV5_}1(g80Lt&W#e@cqUw)4C7L(@7NYD;ek4J
zFY6SCTLa$iRt6%w)#Zh!*zPL+SSaNRm<Me(RzJFsw8L1COPX&jxbvrD$qoW(1mgCD
z@o0gv0N@W%H7o@tK#x9s;AS3{!9^6*#A*Nqh}rv^tza@Ig>nJAnTyt-q@Na4U#KC7
z)$1wj%6!4A-THA`Ckj8gx43(ER3MmyZSr+hz$lM{%CvMAWmaXax&aLF^M=rvEQvGJ
zaBU1+B4p%+Bz#~QAXA0$sXCHbHj<V%E4;h)i9Tn)_jn5E`F$v;%+(lT3rK^nf$CRR
zLGQ2YK=l>vJH*h0HEi4Mb|7P1RmVO*4?==Iem5Z=)vfYH$*ApU$Cp_8Jz)gDh6eox
zHL-3cp(tr5&PEaAC%6?9oDcl-<3%$0*+j59PLN7t@E24kQ5z!SlG<aEu&s=MlW;9(
z2IIbEj{%^8?=k-sMfsDqVk9DK2;^3*GkAw4*F<nJF=lc7nd@UVvH#8E1-4m)EV_D=
z2i0~XKsG^Fic2{!bfZLmJoE(<nIOhWGYdtTj?b6&H2yND(cAM4pzbwFXQ&5kKo-a5
zKfOD#2ifQORDY5Me)X-=`e^i$O)q59O-cCKp@Y7E%~>mL!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={&~xIH<Uq5*OSiPn+VaTO9o9S@u+PB5>4;
zx%5V=^|fcm1YCaKz4<PcZ%ZrTgg6!3(!?ntTVReCkjy5faGmF&;1KYc8zgZ33$e$}
zjIk*1&AQnlPq&~m1ScGfeVQ)q=&=wKx|#$olgNW2_jJY|qMOH3X!9mi`ZV#Oxc?fo
zd4~5>;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|!<X&CMmHc{t2!PafqZ3O
zn{FPeZ+(1G4mOGMUkZCJ=A$7ke^O!DS4Je3#sKQN&t;4)(6I2-tI3R6jA}^$loe4B
zdN|hea}N|9)^B8vP|aq+8;n~fmkI5kEczMh3frN)AgKAn03{15O+4@hM?DFi=$?|A
zzIgN!3+^&sN^gW$6g;<pG`iVst?&vNhuCgS1G&r28GiHSRc}%_8lMV9UdY)`&>jC4
zNM=W%8T{OJ?`Kl-6oz=JPEpYlpX6siuFiq^JEG8BI<Xnckq70%N!p=^JfBh87s6+G
zF(hxss()yvMfqU7;JP__>muXm4cBzf3@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
z<Z20l5O#<pS7)a(a|mpI|C9UK3S(86?w}t<xAf5{D|s7jJJul_i4AFbWc|>FU>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
zt722oAX<U7n(18KoPZ-7*x=$*pYc2~Zew95&*JZ2o)+6=7MLR>XTa=;`)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&c<U(0lc&I)I<-C8)-bBFo%m<{;6@GE2r)%*E)^IC3(~_+Hfb-&vO=
zD!@4ZkL~pb*v;3kw0}|lqiZ#HM2dq~e^B&#xr4R)@#b72>6|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%dHx<k6kv7ohHTSBEE&u9swCf<Q&I}9Y{d6wV+pH>kHsy#!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_Wjygr<g^IXl4SH|*s`EiH>nJ)?Jw+u+Jou8m&ELb&Mu
z;cXqr5ikn|w$oxy)$~Mx-95}OQQ~BOT!yL_Dd6C59ho*ubBdxLEYo8=fSYxLazK`*
z()NP3Nf<%kqQLCJE$^?@aE178`@QTu0CHuRxyCG{y<-SjF><u_ikGDm$*&9Ex?gSF
z)Eg-MIZCYZGx*(tD>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<uLPoKLco<)6v~Lg}XOlXchO%0$O{$L+O-Ul`hjG
zDt#gd-kmYe(shtdcW1Tvord&GaE~k=yyNyH=-=K^wz<(-_-dfg9pDsB&q&&ulz8I>
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)%vH<YB$9i>5rFG04(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!8<S2;-B3E?<eBM
zeKF^RdT27*+8$P@_Hcn5c&n6!c6J|6yXm_)F*lZ-)9Xm2*0Gk}^3yy408pp{R4F?A
zaR)-9Q&`M^p!PV;XKEu2HKcw424V%;VprBC%ey|R;pS)n=J@KYAF;gtHaOK=;j!nZ
zCU~xY%lu_gF<zBj>B@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><qHGuPYrIhunznI6V1=N?xHH$*u
zR1gH|p@`dT!c*ee`|-4)JSBzpq2&scrz_6;qH3qN|H1g3=tX}Y`Rn{?tuhjWlZt^J
zo4wI={^fT_OxW(ZKcl!dH`X!xXmbO%{JjL!O=HRKgg8#i$}s)NBmx3xveNrPODdPp
zki?U6`Si^%nj^e6LvEb#McBGB^+gCA*{Ac(^St}m7RDRjmX$HoC49^el(cUJ=_w26
zXDQ3E1~mb@sqlT#)m#|qmUIO-0>n2582VN?+F?QDNlAsl_&1fQ+=5TKoTQCvrC(gF
z@7-3jRa49zlvz*lsMP5<A?-v1Klq}BUdUI=xB4IVa=Ft1F=6DzA+Ug8k2vb_odg-o
zo$s~%-rF)><`}peCo|yb&i-$Q?H#7A>*_%3l^|Yn&(f8Ia0KsoD+ce>`_IW5|A=_q
zG-3hl-KP^7Lf1<mJWT3&`!_D$Xmt~W@y%)cg;51{hh^I=@Ckqu>3&Mjd*$2)mZ2r!
z26x`Zh6jqm@rl!)`Dv=Eyf_Xyu0)4Y)_|s6GzjXVcq_8C*1APK4@l?&d(P6O6?_EV
zxFIm=dd#b5<EnTvZTvbmzb_xJc#nAZLAMpPW!UdozA?|j?wQ<C#Wt-hh&Wqeson5L
z2_6kRbXA?~ISP%r84ESGPOa93QdFim)?I6YM4eXqO_3dPrfiM-#YMJL9g~X@o?L5o
z*F%h~q3<ajz_J-7j)J2?;?8Lhava|@lzaeuq|Szh(OYMAj0hBCusxj-Nbg31v+aR|
zO7{)1V553(w;iNItEAst&QJEji_Hk8|4F+r28KsR#;;U`SJ&0Yk_Wx-Md4v$;WO#w
zR4GUP5D04ZwcBI!9Hve;Y54eX_{+0f0fT!ymEHn4U&k~>Fj!^%h9%J<bfgg5Jywdy
zLO{}XpLSWYU3Yx@FJ3f)=lHv<VYMB`>-|PbnxEjs4e?W0$jr*}6HdDL8V%8QIBGb1
z2yJcogO#RuUvO&Y#5iBob=1a$bf<dU<|$Em*NJpJo`x*hef1Y8Itgm>rkoD`jKr2v
zs_Tc3o3^*e{TJ(j-$TM@%^kdwakWG(fS8Q;h_SF*Iim}YBQqWjS{}}~eLrWW{+Oda
z9{1bATuDz)8ircm=0_1q#gh^Eon_i3hc5U1o&a?J<f8BD?ljB}k7%5?o-89_RKPFl
z>o1w&JWb_R`Vb#O{s^N<$EL-0i>af+aw~2(WlxH2c?gAntDzg)$kW!g1ofKTNplwD
zjw<Tm9vqtU$NmJxqyVgdvzHDU<><-Ih$aX-uy$E6_I^%z<<%rP8f(8XwlWV>3F1jz
zrx53IJesOTe=Ee$Y?8p_E>+>|DB%NEE1cjl<P|W6g|Ww%u?^!$H{J_olt*Is<po$`
z>v-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%f5Q<y8>f(ZOJF&C*Tm|jBsi%HUf9F(^Ou1zcehh9{{#(Z;u
z;2R$#5cV<<D$IGIBAUYWXH%ckUU8a&MSyg+aLY-%kCiH9GciatGalnf7|#U7hNc0*
zJ|Ld#({#O9y0fTkR{-M+<!nQn#$21q)pX_!%U@v}y$EC#q#S_PH+bQNpR>x?t(G24
zqYnUVsCBsQ%ALQzg8MX377%MaCk`FKV)HCH_*Sw10ejx!(Pi-vLdEbQqj;F}%J%x2
zD-`?Qe&~xGP|b)ZN7y4#PrSA~+FwYWeQ*gp6<Cnbnjw8KPUYk@L^2kmv8x#RPumw>
zLB$su=)|mYcA~Md#Y-Jej*D_5s|QomFVo+ihH990L_7SR7)XRiO0e%ReR2IkS%2^Q
z8t5$0;3+DCInok(Bcl;*<Uwg-yG@m8jynDSj--d*!jkO?_6r>^mO|%Me~){3t1-Xu
zp7`<c%U=m~F3U3J4!jEceAzcE-2L?tvqAw@8%-7@tUq#?xzW$MIEzTZpWD+|<H7%N
z=Pz!;`F-pZwq!bMQ$UyLG0U|Gi>pe6#9cHAmb}ph+K!ja;?U~{%L0lX-4ih<{njF%
zs)D;x7s~Kvh8H;g0bY>~&DAPOeiOrZ%7O{vnWw{<UzLO;?^Y(Mvm)<17uW|ExZ}O#
z^#uQLE@5Q89Ri`yC3&Vlvg&7hbM`0F>kc$b%Z@7@N!0uxYrJ&OkPCw{4**<rlIwST
za9xRIABB%>b>|nnLGuMl>~)>8y06dWjG5y#g>I&UhV%g%2@so9WvQdm9AA3Vb4mN8
z4sV`OZI_L$5j3$-&P$45?r=r~Ho*|Qo?RN}YJ6-iQcC{8ujZM<O2@CCYr^e~xxm}S
z!fT{l?temZmIG&@L^_`XCscUuhPH`vdj8DCKCiQ&@PD~Ss&php<NR+<kPH3}9*w7q
z?ttKa<{t@zqy_Vj!xj#oVrvQDY>bG3zln!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<rP>`*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`mjEWP71<CT4zF
zqO1Yg+8-VvOAI(VBp+o{Eiyl`n|^it{V{ga<t-2ViB^GV+qy9yKW#8_<8GF-+AXIZ
zdg;qk6iPsRYtPd2Ez6LAfE&+W@{1sIF(66lEbRq&0|YWoMZm&{x-q@xE$#1D=S9fh
zlGDKRMozbYQ}F$SkUw(w?l*~EC(hYbv%L!Y#rcfquvh8%os+M5Un^=xn{B%`umQr*
zk|vsqMi?Yy{T6Z_)$vEUzH4Ql=-9!WXYCzpu9J4i@SW92q?Td+<R+f==*?6E_5xn6
zj#~a}<@Z5U{^D|9&n0VXKbLm-Hn4Pw44EPG_Gj%E?XR`tcxbl#Zs3ZZQEOE-CHEm&
zJN*tgz5n76EN%2(gE>4SoEix=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_U<S4e9lije+M
zfoPZ~VXXfw5-(|R0irjKhVlvyWkIXEFq1T4swFKxU%$MA)^|U{6UKnG@uELUHogoF
z;T&pqhjPY|H4qVsj3e$TnqfkK_`%o8K%(@j_1A}hb~z_xc)Y0Gah2|=o_13IS+Kx~
zd1#2k>f<6<?K@rmeYYuQ5eVfsKMtjc#21;mIORBQ_Tj=GtSiPLM#!gZhQUJ2dX+4u
z*k?jc8~H}K>EBD0N$dq%`xx1jcG<aYg0!}a9d7aGC73ZT%}5`EXimv4oKgyb>w(16
zQ|F&gFBT8oa`Z~RlUQs?;diq_0B*>_wG>EPr3Z@l*yK!G%1PU}&<Z|6#^twU{xUge
zceN7IE8ufi|4wN9vB0I<_y|?NF)%#!<A#AUE6dW@fc89JBo84lmgPNYJ3ai!R$0J_
z<M!39bT0Fq`?s!Xz)PF7RY3E&T3EU!crb>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$<Q}9;Yv6#C326k9%v4S<xC6=rrI|1~y}*6egm!KSW#jE&WRQ
zj#Y3Yi(2$L_QK%oe;TAz>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<QGw_a>}aJUpgAGrUuh?I
zLrpTXij%<~9Pl>pZyuY+3Ejbe`va?LF<CoT$nW&nT4e_qZTH?F*=~XDU57u_-~T`F
zYh;xz+s&46ac$Smmc3Ut8P^OUlA=^(78RvsD@BBoA`;5VE~StavNC?>Dn31azwht&
z5Bxsodf)SWzuvEPo@czz<GMqrf}x+Ja-KeZkmm}mb$RYf!1&Snc#&Yl^z-S<LeZl4
z#Edsu@_Ax~NX|qi1`Iy*dtjwB;0MN!Z8E9|S-SX49DYe8Jkv~JqMZ}V<^sPrCxAxI
z8x@GSDBem)8mlb}{eZrEqSiL^JJo%gJAMUIdl)(&(-4Ip6%)jkm3e;(`t|Fv`(+gN
zdoIiMcB1OF4&kAWG?gghQg+ix>+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?AXy<cv*sDK
zyn0&p>WjdbpVxQ_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<7tZ4aLL<uJ-CLNSOUhWo&CJrtEc|pp?>y{xs2I*gWMUceg1yZHfbh^<rE=QB5+|
zWpm1MFhpE@7i>E(=p3iI*~_7txsW1i9LJ;~=zDybLb2u9rM2ea^28q7pPM!Hcew*^
z@~-n)<lPbNNXWnLMPU}UF}nIZ)oXQ0QDC8eR<}&*-RbJ0v6trkj#bA-DKa!>{fi=1
zu>3{(3t-74^vV}m^V3EJ{%C40&+`k82=mM!^^*8%{^w5@w`iu2-mG5g3kz?$V;v|4
zMUMGS+6{e7r(^m0<k}+R5W60_>*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<zq%)&mMI<
zGm`MUOO4XgGmm=W<1k;P_IOYF(CfyTC-Y+T^<FKiZ*96nPY`cxMfKui>{}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
z<eGXfH2Md({h6$RaI%9Z#^tyjTwPj}a>s+&N#Go9rJGL}{uO0)CaPDt^c%@+P)ni5
z7NwCyC6Y;RScI$_<dLOjKlM1K-Ew+ncms4%OaX_I_@e5io@sH;Uh?mz>!}B=e#p*R
zdblj(rYn||NFuCLF0!6dH{}f#+^cxr5q<Kx^z!C=ay1Ksif&Fil8Q6*a;r5WGP%!E
z{Ix+{ZporuRp#gR13n(agIg6k<m7n%PfsiDS-z>XVZD0|pE|Tk@0WZxGjyL-c)Vfx
zn5s?o1KnrqPm=h2gUaq&D;hJf&xGmSd3Y^qm~U)Q=jYjx^S<Yb9))^UxH*x`>6J^r
ztWCS{EX>1}$-OJVEfL$Addlv+t#RE_HOa68TG9LB+=6*vLgrFQ)8)!4ykK{RRn<D4
zVQRzedxUP5!>q~KM1kZj`%GRvp45}Z<7kO1XF*@<SBI6`YZ0A5F1FliKGsp<wa$sn
zUh3KVW~z_Qz7O(^QBdWkRkM9BrN>}=;hH0csJ~=_Qej;yo<BY+u5<iS65>_%=zh-)
zzZ*SXvksoY?YgnR@M~``mxq<JX2+^<n(XN5wLRWHIO(c*?cEg>A7j2P_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<c-t0>)Y*mR!Qi)QsVZ31s%bii1
zrm<M^95#^$W98>n6Yb+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{<n76ZVF&W8y9EM*?gc!+dV5k8~p}avsnIlHI#m9Gb;;QEb5GrA|n<
zfwSN2^DElz<r`jSMwlfilY;EaMBYw}1&mi|v6l&n4Oixu*oR&iRcCJHri{wM7&|?<
zs(rGVyt3-;autRClzH{bY)rVoy32ffLrSbe_>++%euv*5YVP{5BzM0@US**~X}(7~
z^_Rdo-~F?ki8PiC&9`ww-8uuy9}^xNOa$5S=)v;RK6Fp2ImxN;gSx@&KgUgF&kPwl
zG<D{dE`MZs5m+<LQSrXaC+YSH8@?^A;u<ECukQpnh9c?iDD?S&3H*m_#5l)db?t$a
zbE@Br`&jTV-S+HFy5=k9s5uw0rsMJzKl+@4dThSU)o-bNe1CPie3S3V+02lyDShc2
z&u;GVoE?oMvi~fYr_jgb^sD%&QBWt*_XKXG=3_qf<Ez-c7EX%^$JC^(vpUIK+L;cQ
zR|WGHtmr+o5>8xX>&gzdF>97dVVY(PQK{~4I!Rf!+-Nb#<3+0#r=578vwc`6Q_fL_
zFE)-w;w+*>7H)eYB#<vpZAcaq|J3I*(?^5xhG<f2Z{cjQ^lLUeS^NiW)^NtMX2JZE
zH<IH?ItL<nrd~CSiL#ffW)QWjkSpb`$Ky!Qs?sTI63hl#Ip>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@<EDnS5|2g2J+7b!5mzD)!#AwWN>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<obX_pzcY#){Hj=jXW7zIX@YR7wg6!
zT`K85rSM?&koc5gDpB*M+@q)$*JQ)P5tP3S(%7m{AgO3asjl~$AvrFkjVr|PQBRcn
z3oE6X`jr@0gMiL;Srz}QO3mrFxHZjh*0?adZ@RDMFsjEe@J+7p@KycOHEbSy$FVDS
z_lQ*JYT+Li2%fk_wW8vAm|OXs^#}X@5elu76xBgf!&i;Ehn}&R9Fp+~tr_t(?Xs^k
z+E6wc3mVFHd-M+F@4xzEqT1h_!!!8%kfHs<DBq*}#bs$+_j_9eEl0BE<fNlN(LOZ8
zPhPcrtIZ=KZE`jz-P2L&4Ry>!cTdAm4{L3w=J^^-s@H24+?1R0R|==lsY>5d!>bH8
zNGbyNJCv+_d%<T|dLsFv`k6c?1*#BIUxm5xYY7^PK|lAl7NwJ^w_l2HyZiG>+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
zHo<sT!ctyYMftI&P}#y&%8ZJa^5Sn8NSlKwn-`Wlf(A2BU#q2KIe(keDyTNvDLiAw
zyQ+JtYHpZu`N;m&s#V7NfIIJ0!=vHrLD~3E$A{9>oo_{$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^<zP
zm6uyk_4%wz$@l~QHk=o8L=Io9-~>-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%<geP^ar?MD?=W+I<0T>KeZE>PGlGaZ?uRpp;C%8=PdJAOfk
zXk3ixYvtp>jU%tp1fF=OyT3IZ^?rwc=un1UA80=<KdLuwMt&?V{PiVGDMRf1KnJ7Z
z>5TM=+nSvVjVhG6rn0^X^SRx#A96CIw>HdNGkA@koFfS>*jJj0R$V;R`L5o`G+pfZ
z<sYm3FKN8Uw1z9LOLWAiPW7YY0^YgtXN$9NzlkA!bt7I~zSc8*De1P&>j8sT-`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<C%_%wve-F
zH%Y|B&U`)1Q!2y7|Gq@2z*O8p&+6mIpt;8>#m|coYmQy0r`&`3##aZ3bp+)1Qq*&=
z3e^pMiaBf1;=1Wj;BwY_z-r>GDEZ>A{pVazH)7t7JtK;1xXk1B?#%P~hhER(77crX
zGKw1RqZl3f&!jw<F;!XjcT~ORTj()KB~h3upMaF*mHLQ$8$MqaqFm1DY0pq$o1tc^
zruErg_Iz$)DSh3C<K+)<R+nv)(r{yMEe!9TDr@cVj%Z6CI$lI4y+Mf@6fWLB6(PTI
z@6yB~ed}0~#h8w~dSn;FP2N$<bIL`}PPQI?GWIe3rw}pDurNHb@5*xC{)v|k{a+=M
zsMk^h)l*;AZfuPnkdttsTPS4ZuEs<@w!A<4y8EG#k+1B;k))YD<65V?{kgRrOUp5f
zcG8)9%KRPAmFC{iZS$bASm=DkLCW7(DkrtaIwo$tgJ-e9C_jEcw|t(+z)<Ggm+{~>
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(<c*GZp1Egk0>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#+qMa4SlWMqhgMH<Vg8Q5oOm;>U{f^V+#9{$xWK5qo)@vd|9PbUOgcmC6e)R(jK^P
zC#jz<NcvVY=-vqF(k6EOQCECz?VS_HJUB){z+^Y^{S4Z>_>N*j_#QwN8u|p6^p4vD
zr!!V~NK`C??fpF7buZ**Geuwvp5j*m60e94=PBCb_Ul`m!=l{I8oVYmS9vFAyjn!o
z_)&eNB9-g$L+V8X%d<WvrbG4aA~nkG0~fQJ8M_99`U^gB3CZWz>0c)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<R25*=+k<nA>%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<LmDd_?N5s$e%~4CLJ;li1(mUwOSYLK4az31mT|M(MpW(<C
zlvImPUT!6kf9`shfM1zB(f9$%_}IDUb1{w72Zb$|1=+eMB6^)7sfQXA#AA*eFS#@0
zuwu&EM?0`r*0WA}tu_Gnk?N2Zmwud7RbUm}S${ewH|OTnCCftA`O)fqSYv$5uy2CW
zXO(+7IihZA9L%=<x)1uizvvpzPzO$TOElC-JE}Tf$RR2BmTug@Nd*ig2NxwQM+*$J
zeQ9prSU#`j@{0LV3;^J;m5!zvB>)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~hkDgWSH<hP%#EdX*+J3LcA&n4Qy
zlpVMB|A__rG!NNsJ3=7(HtLU@fQkOXB!4g~luK;q2J<0rxh=UJ7mh3P$=ld%ECTV|
z?W6zrhpq^P;2!qgwjA}J`tU!=gfZgs7z_aay#}DB9DoCGkobfGU{?XamD>O)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%6GgCT2DyO<bA?_fk4$n0Rqvg|HC
z0DEnRPXOfq!U}(3#a&DcaJ!fusBHJ05p3^Ept>suK<zKA{ukEx3m^UqYyO3`cQGr_
z*~P9vcNe38!440k4B*Ii4&iW)vIE0yEDUivFxk~dfaxv<!2B<4wS)H%)@0xSqQP-s
z3(SBq&;xXEh%f<WI3SqeLl#s5W!PY4U<5-Rfz+}BMkr?k?0^$K%0M8Z47H?S(z?((
z8IYm!K`^j}9nK9CYX;8|Er^7HI?x14;30T`I3V{yJqUq|?J@8X6eFV0mk_+B0ll{&
zl87zJ2_Z*<pmiTGMJx~@7*h~-z+vde4z&cZh#azvq$8||Bk}^&AS^H&exL}u;xaHm
zO(T(TU^s$dkOy3$%ogS=3bT<13Sb;zCrU%GFqRI?h7-2K4!nlX!f-gVKz&tI3W^KS
zfGyF75)K%3FCvO~!#o`zfeA=0iWrp!^RfYl0420r0Yyj_Y|V2}0z?pJR21qmWXb}#
zZBMQ9AQvG=?L|o;R7fAtM82V#;V(p+!HnEsOKIV-c1IXdS;!%n$uSUvgu~e02nV8u
z#DOq4@u+}5utm5KJ~-%4f}0>5@FIN3Am{)wARGEI0zJS1DF;4~_k7R^d66JGgq#E~
zU<Ox!5pn^10I@&|W{Ux*A=8XVIdT^zgkazl4M!4)*x*f*3-aLX@8cB|jKOpvC?aAK
z(miD6?mkW)LFUJud_vr;gS~v+f?S+@+|1ql@h+Y;2t5D?Py3}(H_|C&wLn*7wEH;(
zM8srqgs}vd6T+HED1`a-cTt8L1QQ_2?y|Mj^A-R}imk1*E&!@@pi(V7V&J+6$MA1+
zH6t_#kd=@M0vZ@q2~}}b4H2xgnw$t0qk$2TQ<KyX(bT|V4r|CtAC{3*h1OO{0QiqV
zzzx?l1z5vEa|sZ;7X!c^hE-D&my%MI7LmhfVnnd&7%34o$-}ZDY7k<uhq0P+ax&0>
z{0$)e+4?{DFqSkHH<mEQ&=7GygIe6%z7aB7ddB@MY-qS163YMDZUKNQ{|*3M<c{C>
z1fB^VX^>ka6z?J7<fam$;_#5*QPH8Bje*{HRHh%Rz#72IlvF$fL?}EeYBAe@Y%et}
zJrf%j&mk%KKR2V@1om!g{PU#06Bzc@Z|Sb;PG9XPQvl-Rp8z!u$=q2Ze&0voIbk11
z@*nn3XlExEZ**{=7u;E)U7UQ~0-exOqB6d|Xm>GjQ7LFe4LcRy9RTVGe1Zt>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(<V{=RO(
zPUtXSAHN{^FdVm&E8f{n9%6!6j2peJ66}rRCWKPQ2fCr9MKPinZfG6o>Mn1hq4~!a
zp5eGXgM<C$#l%8GLq$U+Me%_iV&Zaga$*<>F$oC~s38&*?icJ7CgK;wv*SSnE*x-J
z1bgBA&;*Z8&iIgE95;;oJ0)NLUAKNg@LiiQJy93DuUMFqKO8w2LW<jp{+{??e2^#p
ze^KAPyldnyuO8^;6zrw}4;(jvT@j3=h&a}4XCF`S{6`5NXoko8;JAP9`hQ<Az`J_6
zhyNeeyCLNXO231_9{Ep^#2}qwfA}Q8-HuU0|6BfL;9my*W#C^1{$=1_2LAss@XyxH
N%@6J#LgB{kzW_^Bc?SRh

literal 137504
zcmZ^~b9^LGvp+nsZ9Cc6wryJ*+jg>XHa2%-+qUhEHnzDNypw&Ndw=(zx98K-HQlFs
z&eSP>t42jyLIN8H6rd?CqNJh3r3DKB0KNeC88|=>5<ps1R0$gt_z?h#ZS3f13l600
z>|LEzBt?j|v~`G~4gny**T2o!)WuO)NlEVW!~Y!rbLD^DAD90#c7gu$S?6y*<G8{k
z2kaWV6usB68UJV0|IZQjtC@=_@Y*YIXEJqkb_D=H=zz46hpXc!?F*#Qoq>}A((#|P
z#ee9+Puk=^bnCw{YAT|@F_S==*woVaE08`1(sU;O=e))Lq3vwlKEL;K`~0QwX7=i;
zz#}?v#|MZ3tN<<mM}RHB7~lmU1}Fho|9{4_{TnX|Z~%_>0yqQjvjA8ET!Hrp1J8Uu
z!3;=C1MC5&00saZkY)ie0e6;9J_GLsZjVd<<saSuI~TGI0Py#Ge0+5LzjHD@06-ll
z007(e|IU5k0sv6p0D#dpM`LH>e~$wLzJr>Z0|2)r004qE0Dv|Nyhqo?oR#I@br5(F
z003g^<KvDJ0DwvY0N&z1KK}mr_;~vX0Dx@(0KN7=i6Pd32L;4iV&#C)%)<2|2}X9W
znDqd+pR+om*UT_hvRgw$zvBfzTuDCOuiE`S-a;MoJ~jbsAGF)_8Qa*o<$~%T-$`s|
zs{@wb-vdlf1wZ0MKcGHZ_+~Ue9G*NTKkhpt6basE!jW7*lFo(SCgwXn40QaspD+Wq
zPol4o^aBoi-XC6FiG%|_n(QLq4RZCU?s`6sKd4cC4T@ehKUywVT8Lr;W<HMIzn2Kc
z1@M0K{1te~d%aYA5&ZiA_D1#A+3l#@v;EOsxDNGk1yA^MN%no~d#YK_$0PSs?Y7sf
z>pkTmTr%zhXJW6HCddR|X}-y~E=<ObJ_1_%kv$$_aCsk#geCjc#Xv~At8>=n2B%_!
zn$UY|AyCqr5fuOmR`R_$w?z)*UKs#7dW1j<AZEaIDijzK+YYMkxSX(NL-@3HaCqZv
zI|o~hL{kwmK7;rUKwisCOh`kqq4sZPCkBBS>A{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}`<yBxz8f(JiswOi*}8Oo31l*vy~SRe@unmnWvh+`osx6bIz3-LJ~r41
zRZL*iP`rx<OnXzO)6Ox7$XY-CBW#XnjU3r@A(+=xU``B<+mY)Q0(U6<6hlrQ3rLXS
ztF8w!vml~fy9IMURw2DBlvjC9c9>9~KZe5<C&5-i8;rzPQQdN-ILY#;3rRAQo3noC
zB4k~eYT1^EuUKH}I~#5!(-nNjod2_`pk%7o5_I3_{!|4*TmCMb^6tdO;wd#*+0IqQ
zK&}(-{a_X+9~ztsvA0!`3tECheh3gtEjddw>T+Kst^Xd++vJ!g<e~MrYvhNFmf4l@
zKwj_AMoiCOBIw0;Yfh56<oGU2-h?J&`tm}bl|(L@^Q{jMr3}%G5yuk`i0DFs*ktM#
zMQuIx%?GmV|HvD6j6{XDT5I$}&^3+94+TFrdClyMK4K84TXOS55yt(<v{|}$m0hv$
zxW6+jCRk2z&{?FcF3=TL>o@b^0->?c4QzuTv~T8tRf;o>kk8XJKgz!vF)!dD#(psh
ziB0tZXVDvVQP(~P?|s<W@GLQ^rUA+ngsj(G$N$Rv|4JC&1J4W(!lz<j?+^j-O-l*U
zR@(EV3oL!4^MI;y(r?JGcS)}W_M14(w^bhwFWa_OPPjE2){r*g`bnBRMU^7sZ^o?*
zw>MHU5dh|V*-2kjLJPcV6{QaoLD4ujqqfERm0*VK;%r&kB2Vs9tW+ZCi_|T00<@2W
z+Zg{z)Bj-&*9lk2t1t88a3O$#7l1kUeeuQu=`KA<RiIZ8d3FMl)@5g%B*bwt$JW}n
z+fdU@vc0<?mo;d#{W`x?+UuMhYM8sA7_4dKcVRM^-%ID0{Vk0;(Hu(|6Efb>>(?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<<Ek+JJ?ZB!TZ-CZ%i_PB
zgZJvxl3XtYG*HlYJUEA#vo20V&%+6ODqiYuZI0EukiPx|(Q{LUA1=`u%HMFa4*4G?
z11;+OKXUwE)AdiTdimW7rQ$DDBP+U$XW%FbhBU>lf700Fz7>(f2%kvF1%egxX??Wm
zeur53x=J#B-!)kni-<TMTw<BD-mm$^fhTK5h<$(<_t2C*%NZ<jbg&6cNLgTM+XRKd
zFS<}GQ{pQ8%at`{<vn=Z_Mv(pWJO;q&>~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)a0z2tgXG6oV<!O6_QY<a<uW>qJNY<I_2GhZL)0nTtN5IXm3ELHE?
zKU?`}fd27D(Ewp#CFE0}#Q(=K%>fl3gyovU`{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_<J*0_Vt1--9{Fm>nS)-w|+{mOfO*>J7@T5Y(+V!;tzNU;b_wZE;<6!JZPwCiI!X
zq6EF7d(Q=zc;)st<kj%@<=fe~uOU$or8zbD{QiC5(<S0BMJe0>ln`}*^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)<xi$aUq?@}gP>+8Cfe^SWSYW>*OWiu8X(sa%Oyu%5{>
zdW4Q^MdE2Lo}P~l=J&|V!V}r<qJjb>?&?lR=GmsZ?sP~6Xr#ZA-nB832G(Hn5UTUi
zUJ*8GS`n#H0qs*EN~p}=xC)lKP%oP~pc$E*7;X$NnRK_nZ<r2Uqh)wPv11~zwKkFX
zLj=Qy_V26r5!{~v*%n(1Dxm8E$<s1?S;l-P@-P9U<NY*aj>(B&vN)X)26B-rq0K|1
zlo%*^rvb=MpAt#p7uPiWUL+fEoQPi>jGl-<!GcM%z87dYNFD>@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%Zh<H$I(}
zPo0(VV<~hV==2HX;J<Y{>nhD0vsDc;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|l<dI$u+07Wk4fl9iC{C%0Ul
z)s+fL%+FmtRYQOg^bJg!s+A_e=&6wJxC$B2iDe|TpxFO5W;am9TvR~QX|iliG3IGn
z6mLQ^Lie~A2I>C=y4_Q)G_@)=si@*Hz{uyr<vTZCKEpR#6jP2SVEe7uPu_2*a$ox5
zNwnX7ho`w~dsS;9J6hH?q0d&A8;bL*@q&S4)7izR29RUuMpFGezU?h@t%~jYPpp;u
zw0VD|6VI1Xqs%35J#T(6L~ed}b_bg1**(mt7~LNUQYE2DNoy?dhEKZY=4KvcaT24A
z2>EFgn2_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}WPQ<Va@;y5Fu-B7AM(fF*^(f5x^
zH8C)*^XRNEfX!V-I93fcmMBtrd07H}Pfh~0QfPUp4y=BJy>gl?o@ZceP5_)sD=BO4
zwb$=x;{~Va7Yu%^Jd0M~L<jE5-|ReoG0H8BoPgpK>tLHOUQfao3>|c%sZ{LX{rMLS
z{!F!shb14gd<?n0lK)ojH=@jEM}M+FMBQ1hG9UKV1j)Hy_X~{WmMz_#diCF=i7$>8
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<T0AVD`Q&*?nk^KOJFHJ8R
zys^O%lwsE1_<@Y4vo78Zgsd|K_fPi<JlOPM$%nM&Vv4CFV99gyKj8%RL)JCD5MsNE
zeXKrue{bUE(Zm>*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+La<m~AZ5
zZVnQSNMDe*bP`P-%8&_kQ5ThH29-ShfK{&8g<tK#>G?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+CPZkES0qt<GsmTi2@9j*$AF>F3x2%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<vq
zx36gcbuHijmw4oHD{Ci;kEeyI+lMfc1r;EYCv-*!zsgmdj<T6QsYM1G#&$ZDsiuCz
z0lh^AMDCHbdf8yulose7*xExEt-_{BC1lN_3a#Ce_m?n3f8>*#{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<?yBJ&ovcU~nF8+7sl<LLf!4Wlg)t*$bS)F^n(CnUYQ(
zUNBV`^^%n9Q22hxS2A=4t%#}+y|ni4uW&>(tGfR{mTgF<vC}pm_AGZpoGL+0${5up
zLBSLW@WrzV{sdU?=)waxw+AR?0(i_!$Z^+XYaxhe&eszFPYhl}$&=u(si;evg-TUV
z^uOI2u#yXVfhY-eM&-L};7ja2e{X48!Nwwuqgx})SkWrP-zKyXXN>q%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#~<Z(R_1j6PQ}
z@Lb4^Vg^>;8xB@+Ku=@p9o@q`k`;=0!3-ZL4*U7<jkj5pQg)D~!o*%#IDPmQ3m+s=
z!;|S1>lYB+9%uoRI0g37uAa#v(({yPTP911GirF;%DW<FI|WY&f|n!}fDaj~Oq@h6
z)YOO9&N8Eo3jR42V&oCXKgg@CKD&t|wNwHWjD&AT7rW5=RKt^I16i7!i({A40Qx%1
z60se8n-r*pfnJ;k5oWTyv9h~~tiIfm!GB*8U=+4G*45KLnV(o^`wejSif5`WU738b
z&wdc@9QQ@z@IjI;9dKO4iYUFMlD>0HAp~>_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+<oGA)y#O_`O%E1=THclkTE*Ww^tGu1?CS-<U~M;pbwhmuTy0ND42f7k(Y>+##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?jQnz5wIz<HTyl)Pe6O?!C)ixH1aTz9^_md4xC>TQNM4+y
z)qz^{ppMlG!p$NRJb!<rty8RMKP>DvF+oBy;M&Eep&UFp+hK1H7!A1OD+<pV?oBjv
zd#@Vy6w!ZtJmNm?bGRR|?nq4u2=cU^jZo=W-X7Rw^7+}?d#+ya0!}3m#XE5;cEXF#
z4I$s6T2SS`X2P`Tn+YF_mLSBCgzRq<JOeYcec_3SAmCyeDSvD2dhOjahQ=5#gUSCk
zKIlS|G%`SM@!e-<$%2LF4<1qKnq}vGl<s-hc%IATP+?db16G;x+>C0Vj$W%!dNw+G
zw3m7U4rXvY$Pf~87yHK_Qk_3d5R$UZUgu!pG9P6QMq`JH?${r0Ep=fK{@7es&%E{s
z{=BRuLnafy2h^iy;)jFwDD~F<Rw#XOMl5{T;o#rm#PfW(S<3oR@b#vZ3SY)38d?hA
zaMA-bi5vXTzaoaFN%Mq`kI}{{HX$7hS6x2Q{d+RQbFfU~S9I`7aO9RCscu67(5}B$
zR}&uBJlzPM981y3ndZc5oUVQvH5=2p<oyd)x$Vp=Wo>MicKK;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!<iYqt^29H7^QFTA>%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(<MrT63FHXJqGk0O$~InKoXF>YSW0^7A^iq_Ii$t$3f_fKr@`UxRr}S%<Mj{0
z27@qI*W~24wH9D8-k!5x)|fx|&ZTgZV8_Boj$Vu%)VcPz**p|{%L6My61-Z-B6oZs
zYSJN3bY1p%$_xu>?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+pbLBH<s@n&V2z0m5xj^(qe5CbJekdn}zVOBT9L-a22D7La8-<rFN
zLP)7!08HtsfLSG)t{FnfS=NzD*TY+G)t1h+z40*+ey89%E}`JLh?N5UFqEW62uO~0
zj`%gAWP!}WNKu%g(3Vp*8>YKoW&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<Szj;uGLKxryrRZxjL-KS-3U
zh=((lmn_ixgCUiqwd@pt^B_V#|5%iL=pX~wF>@oMRYuJhY#BXT2_a_UQy8`9G_!Qk
zIr<pO$PWws`-Zi*5;&JVi6m|erv_7j(XztF1M*HXCUR%>1%v5n^v(*3{LkuQAd(0N
zSzNiwQ>0Y<N=d=a)bQE-q`?S*w!(8!&oHG~r|ZLSuH};9olh7(Ce&-zZkH-Q5A;`v
z*^i^tOllVPeAmiL?X#Ua?tSlKwU-B;v|f-{Nle<z$zU0K_Lmf&c~vP^i6XE1@Nl|B
zRXq)mp0=l1Ncrh*Y?(zktm8j5?K#9CXawuy#!iOSM*I`bsL;)wcyYx=Q?%d_>KBv2
zhzAhg7!|pDIl^dt0e<r3x3x5SFl76gS)R)o^DSt<M^uD=%@lKu;GGu+b7J{O_QI~u
z8RDP*i!nbdP~XuSJunx7;A>agIj$O*XAir00tLz)x!<9L3rSGuJ6)ZR@07k1!y{9b
z!7x}=dAue^^M8SPfGL?VIvTf0d5^4Dw@QP=5ee`!<alx|sjixlT$5xNk~leIwpX(B
zAwa`W#eV=1dh<*;KxOrs{~k%><nb*>&t<pBsAY$pj=h?V=C_#@umBFUoU`L&TFt{B
zxy!ZaYxJbJl$FnSJf#g(l~fL*4f<T-6ue1?S99ja&&a{K|EeCK^hMg9B*j~iK*LL#
zgBoaHUhU~{b-<DvvICnFOIJQro4wpPF-=!<1IE!3uVUEPw6VtEuJ!;5NJ*k^k|G9x
zBO)zhAfxx>ivj+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~<eyFLB8qa|leT;<|VNu+`R@#iXw^F^!P&6})WFH&MB0O+EX?X7oc
zXfYU~S+*|({Q+YVA0$r#5Uxg#hmKZ5glOi=#~G6FfB##szl+uI!zDwe1%S=4wFTqP
zSVN?A(#|8{uL+)}P&~76`v(%Q>44prPyUi<403$1t(h9<MX?3k;kzenS3Qh^@hXa$
zO(X1vbsdD_2azcBi3*+dvZlIcV~+*k?;yZ|wA{@r@#rer_yWXk$_X0(vgGuN4!lqk
zIT39c|Ag4{+pcM*Gv8(*ZkEh@c`)x@p)j3s8sR7rdmvzAubDttZ^gH#2oP>g%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|DSD<rncLwO<`+e&A6yf)8IStPbDxMy
zzz&i==Jtdkm(PG>G8}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*Pn<Z1St%4=SZic~+b)p~hY`r7K|D2qwK_Ju;YZ}s
z6K|zyrwgZvasHv!g?73!!p84Vp8S<%?BUNkYIQt_%9if_0Mx_;n%kXoEd^<`uAack
zfasSc$s=;SF^5iJ6ky^>5N5)4Dx~X_P&7DEfMIxMHPKRy#2%vODDaoswGKRmEys<!
zMe3)hT}Q9ny-|~sfNOE^y!D#8PF$fRA#o+h77)qxm{P`cslcKnPfvBeJ9BheVBrVD
z2xLJ<qy)g?B=g}mh7g7=#P)owjl40saZQ6woXQPLX0iwX5Q?2}e|xS+jm}!UDOp1W
z&)M@NB5uug@4B5_#;WI9aAAiSiA66~1WZZHk*v7s;&xHB>OIG!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<wsW(@I)heSyE#&2;}{i22X&K|5a&$Kx1cE5+yiI#NLRs;a{<Qv5Ek
zLcmt3J=fO0Cs+#M#$KQJ*KLxo0x^*jjm#rF`rj~Pi9;vXh_hPk`kSRnHvLXjVWyAh
zziN^wv_xK|bE-rgmcy_bpHU%;(-xEOg0es-Dxoqo*ZqP1`vs^^)$%XuI#Tz!6?}KZ
zm)9B5q~Q&u287>@HBFlW8DOYIH<vJ}1@(wAsf-a)S&<%oNpNpdTfgEm4B9--lc1$i
zaBY6n@q7N-&a-#Phup-PY5;>;Y$%#k)pjuJc#P122kRr8E|>ELMVlqQ52w0<z6^WE
zwoMM`Fl;a~9HaOn0+z}YJ>9QxE!)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>{F0sO<i)VP9L;EP`c;@!l;{->WM#+#fkK
zO>lfKPMCgEgk|iz!(JJfnqWAR6$#F86*_dPJ@dFK3y^SlSg1ikZU}2cFQa<t&OvP!
z)hwpV<GW)iiV}rq5LH}AJYLPz?a;n>c*sb8%Rwt0x{TT9J5Q$@24TM}7oX_y3h<34
z&<%PJAuf(lxk{c{NeB&=YSJ{!zS?(o{C!}H+^pp5xXLblk-2<W^1UK9<1gAx4Ymsf
z?o6L9+a21X_d<{j-Mu07kHq`xhM?^ra+Jo{sQdY3N?VvjL9&Y%z8$$T4~fgQuvapa
zv%?aqRgo)RtoLe7*kz;Eb+6c~^AHfRMXxk;QSs3&<+UMsk{fp>M2kvV2aCY*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<VwkTLErRkP=x55xr@3!ehoydzr#iN
zbkeRxmMX&&S4@`%%xWg(2Y@H{zC0~EfDnq2CjE*BQNZW?P{b`x`b5XWO}5$0lxFr;
z8y$yrSorI;sQEs?VYaiU)@bJ|t}#zRy0$Xa`(o_G7HoW(wC^8u>$tLx<C+p%k>lZ;
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~JVB1Le7<O=4H_IC@P_ZMXUlH3C0Un9|Bb7bxOQcWnF
z6-ISh>hq))bIt3p%3=AENxoZ*3?AqC<kzx&kM3mg;a3|7ka6K``W&jukmZh8V;-Gy
zr5Z6e955*>4ej~Nc$$Q^5hWQ_9k_|v_}h_G0Q49%i{?eHkqOed)5ow^7mSV8u6WdR
zgd;e!><FS4q{q5Sd1Q1#e+5UpqAp0FSbmmnfG+a0S>d&ido7S}Acjl+tYtX50&d*u
zjPzjw?IMnhonkXU$-DbxD4rm=nu*C|-qBPllHLd2O1epgII{}z&;9XNGpVm_b_1py
zc!HUJyF+?@Z}nr`<q{K4irLygT=npw)jcQrUPeLeN?Q2ERPDGHOFB_h*8cb{y~FND
z=Y!((-&KgQrn;S8mLF)%!1C9D8u$1%RaZ6Du}doisJ%;tcy-8~g<WJ2v{1tmeU}I5
zpvClCJ2PxN*p%%4=mQ7)X9MuRlIUltT8h_?fU_nE?`7KYM(_$-A7Q=uZ?#FDQ<$MI
z1&Io$UmkUF7^tc`0#z>Vs?;QI#l327E!Yh!jSlJ1yYDSqU1}aCNZib#5c)x5S3lrk
zJq4k32a<vTaucTq-^0H0j7~2n-0^Xr=1#2<0s?HqGZ5!nAPw3WDy#4u*+wKu^|R7b
z^-tqA9Fpl+Z5HjSD6z#3JY_N(z7G@uU%;^bd&|%d0css+7}(6FC3b#tcArq83Dm#z
zl@SaNjO3#}ud=`zpEzlyO;KJ*+wgG7&ZxeG!PM4b+`5jaLD2F;{!HSCO_MVQbW#>M
zo=o|FTV=6;b#7ocB1EGfC!^J^x<cZfn)kO6)Zk$evZ7kPTfLEWRWh2Wf#2!v_AU-#
z)ur*O{7XEKpb&b3z6jR}MsxvQN!?7`lonuz>~TJN*~+L)qnB#M7<?AH<ukmlwTbg8
z+L?oGvTROpSEW;+1V~F&SKK^$g^H(<hcseyxPIPAC1)2Z1Qa`zh+Of-Ob;atl->m>
zBuVWF_QFO`LIND={J1Yr%%GxKgNWYI;)NT*M|hNj?3wg4H!9Z6CLvVJ5a1I+9qHa*
zERPg`WsU##zLoszJpop8EPgZkoZ9;4=}4g(JNvT<eAmuDeAocn4wg`?U%N8?_<2@b
zySMlg2GJ6tv$FNF{_F2pt%gp)28H_bMkNz;t5MgZtJ8V9-$^}}VNP(S#2Ao9OHL64
zJ-AQ5g0E1@5e!i1pyXmyTT5fAF5&;I#33t=syvnVTn2;+fR!DVPC(@vLpECQntisz
zbC$yWQ8V&)OUB*337~(~DntlnM=GurGXpViyIcVlx&PD3p9kpu?703LzSka}+cDV9
z5n;$bZ+3lgUHxeNlR-zAKp)q%fYi=HnjeuD16-@iau(Ia7nU&80X)JEL~hQ&Zz%4E
z#xGmla`*)qi{<$iiCcY+(~Z5%<aishGp%+MO*a>VvxN7=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;<Xu-exw_y~M
zZ^lxWA`$(_z1lV0mqK>s!6HB6z*5yTre`<2-DsYHK<9Y;Xe3OLF;qQ`s$g`T_ig=e
ziJ{0gn_$Z>XPytJTUl3YL2Gm&<Bap5v_^Udix}50@<$@_D>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?cu<Z<
z!Yy5u7$=FuYr}9*jMHF{uoy^^f1r|~FX4VbZy^k~XRA1?#k~Wl>Ii}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-8<C|sIb*XAXG?Y6F?z<;YPxtNe~VzJWmsHwJyrkr`<oE8q>b?Op@nE3X+AI=UW
zo1D%4U0syCyQ-N1G^7luG4oD1dMdyVWJp<f-*5KDCEJ$Q8)(phY0eY{PR{76s9x$g
ze&-s>GHQ|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~<kFs4bxuvmGC5UfWTyY(enF5QcMY10jl}!W+O@T8>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@qnfDN<UD*G2I6>g|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)<!H0CmS<jz1#7gw
z86HW@hR&7wu572^)+!)tzXpXJ+sGnD1ZVXVlV?xx{x-AlZok%+v$8G5y7YCowEPF*
zg>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+_ye<mSh7_=5Mac7si1C@W@}yez)Ys0o^@Ml7zh8irL@b_eAcx{a6m4?HEF2f
zD}zcdXlsR!rY;c+DKsRC03U2>PO1mDQckY5vW5Ix4Rj`4+blAPWUP6vAeo9QYOh$&
z<wr-J`)J1;Zb)ipGnfznFIu_k00Q4DA+U0dD(h$Gwa%`Y!efkdv?u!_wsbybg_{dg
zwl%e(<QnzE@Hb5MAjNf1ueuP-hTtPz+jEu5u$cJGfHjtBz_+FDLUEj$_^8sc_*)As
z(8jZ~FkPtli3S9y>9=!mCs&zeM`wu_e|W$*xeuOB(jzkyZbmn3ey%y$rgu^%oRz8N
zbfPZg!P^Og4(Qm<_J<}>#I<PK@K<4kyl^lchH>J?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}k<ikS+R3H1#9<ilxO_;Tbw^AeV}b`SiF>S_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
zsLu20CD6glDHjnNO7<P`b4~7S`W}T4#a#Td?3p2*2juuhv=T^M)l1>kYMVpUmlQ#$
zgylC$5*n_>keq)&2^+_FnDNr_{<asqTSh<B{i0cqzB_+6b);$#jE|o#ldS=a!WxrW
zhPvh`lRp>~pb(S<<UGTGgf>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$*Uios<z7aY
z4oS8q^7@FiK=%JEACDm`r9Z`m7X3oul5zT>hdx8=gXfpp;HABnKTyeH+VW*+aUtf*
z85f$N!4I9(3N2ZASx0gq2j!%&3()VG#^W5_7Idi-Rch<G&<w)Uw&}aBUBksDGDaes
z)BB)2%COd0Eq!R%B)6B(({x<;6sWhwXy|vQg%H`p@S@^z2Ad>QJ{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!m<Q`3Q_eY2!iYkv<YE8LE8osTgF!c
zE7!2dd>xL+YF<0lU0KQ=R^|nRFmFp{o?qsNZVIaS+S0*ccj^sKK$|nlO<cHNZs82S
zS5fFY@|LA~7#;YDA2nY$>>~zU^iu%;8UL*kPw1GjY;&=T6I<3cF=aH(i8<b!nE{F<
zdZJ~ZXG8c3DZq2*T_f=;FIPNX-lZk-TGzoOOU)&O_EX%?yDN$aI*^18TLCB8EF1?g
zt7vjn)U)ul(a0K^Y$g+e9)E;*<VQ|4On+S^uHriQ{$MDvM=;LNGSkfyRV<_wn+<o#
z&?rMW#H&MbjcirA69qS&HtzB0_8id8Q24G4O9h$f`g_qihRWhB4|kOTP&$BrC^rK=
z<y4%(=^RWgsOs66h;v%d*j~2hNLB*0U4D#5pQAuR_B4l_3R02^O(6LTzp{h&RUkvd
zyvNT?2nK>^<genITF#6&ayQ+b5TPX+bWXb#bPbEwY!8(D*HvDb52!ee>UT);WU!}Y
zD-&Y2m+oM=x%ygAF}(47YKH2eH=#0&`)U@k%?>yP`fLY;-~5oF0~gs+aNdL!Lhs?J
zlwCH4<&i7Le;HfG$um<rVUb&9LDUzcObV(~SC};-W5ZAEv7H9HGzJ#Q!Cgn*VQ^cu
z0gN=rqulhMzgQ)#Di`kquFSf<{#=Suh`xYcN{N7EP3F-Fuv9Yf1-bI>QUlC=Bm(9L
z7Sw;`P?TY$020ozJH!U9H<otlK%N19nCzgZ(m$eh^#rtNSePYceA@?cz%L`o=X!Zb
z1VJnst_p>q4tAI=XZa<D#?&yCc0hZ2s7gp6m~+^Ef)=z$+^ZWAt5_m2CE#Ye{C@yL
zK)k>2k>W{ONyDSd5u+)T&T<YPufdiJTPz?TMRB*N3~!_FjZ|S8?pIRd$GK{|6o@N7
z@q*T>&3TvmMP}Q{`R8uzU@*EGu<%cPlTu`vTFlF*?8<mgTJ+niv)4K|eQZlYLJyZS
z6P6Dp7Sn)IBT^bs{RKoq40my45*icy?8<p8IAFi=h04|_mmJL06DSjBle#_x?aSJw
z_wi#*K`7foS@>XaGJXPb0z<|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(kgVpdc3rr9Kd<S&BvATZMc)@?fyz#&fd>DMD
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^%43z<x0EJh9CUpW_X@!M$RRH>7
zX^o>8Aq!~FN}LWXz5(|KPjIUvog1GEQ!$dI$$tJBG@w8}V7lTjrwxBV%bceF5s#qU
zX9!n<XJ=X99D7jv#%x6c%`wgzFLe`DjJ3$N2<}gON}ev?kvCeBxxbj}A!cPV-YP)3
zT=U`*PaW*~Otn)GX+nUecr>RNh%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<Mf1<eiBYwFOwZ3?4Y}F*kSxk3VS*QTscb(yGi>)&lar_?lg0
zfoCo#n^14vHm2qnQ|l9V1tGXfAFtc)(M%_^)SBRtwIJ;cn~|?&Zz)g7pMFircDqQv
zlAp%Cr>%j*aOd=mV`VK0706)V{K6Ly+u80<^XvKtTsvSO#}pJWy77<hQirr08@@PU
zywdTj{dTi9YAoxiiv$5N>ssZDEBjK5KR^NyH-QbY?pI?uv|sj~yj2s)6(_XCOqG;v
zs6#bQwdgg<^!1YSpvyd$-s<oiywYmJJY0m28RdMwK{A2bzvR4*(EvxHvX4ec$4AC3
zBz4?={#p@KQtvqYPADez5565rX>jK9#PG!kH^QGztszm}V5_&c5|(P*nA{->e+HWW
z4_c24nMd<e7%Ag4S1wm*7T&8Xu#X@n_@yWkO2up#*&2sJp^!QU|8F`YqeKQ;2-4@a
zG5SJ!oh|DVji}dGZ7V=^Gtn<;^5R9C3NJhNo1UW*5Joh)l?nn#J8{eK78%v35-JTP
z4a{NaezH8ilucEXr-Xp+YQ@IFzKV$#1lWN&f+I0&i5zfn5aR!f1V(e+tA$<-8MCpQ
zqM1Up=<R4To=tQS3%Ov+82acw=1tB24`dlWpk?8MB1+f&u`Nvo5I)TM!Taije_XN;
zoJ=yU{^rj4cABXpCpJ}L<r!K`$?`XTGq9Lgeun=m2}A+98cl)bt_o~^yC1_N;?K82
z1{laNujAs!_n#0r9!3BG-er{gB*a3c)6%CBp*i;i_#A$HplFfI#+uePQah+2Kf#Yg
z5yH;9LgC8hgGf}U_{%A}fw39A`h%M8biAVg)3AVmIHbC-0$wn6kg6eQswp}5Zxd-v
z8IIE*o#LKUN{u*&b_lE^0@$PBAay=MGhb3PEXHEa9EPs-ZH`MyG@Gk&uh*lE)}!ob
z#UXa=T9BRKxG7`pj~g0$*^?96zmCCaI1^5hi)fdY8mA9$u{H^AdvKL?Db=U>k%ir|
z+_noRVq7i_=m?<+WT|(MV<M+DN<dfI<(kXGNK=gwJtcaqh8KJCpjcen8e)QI)@v^x
z7{L<|2A^U#UI}+z_YDFWp_>78i(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<C~~GhcQt|txYk8lXsM?{PEmw#W3Ry<QEHh3jvbIeGN1X(TvXGbk262tsP5I`&k+Y
zzA-OVrizN4kxLNsKEUMjTR#eSxSy5Tm<2C;R&iDkHUoy~T8dWe2C5%h8GwSgtO87>
zab8;3vVs9uet*bk1$qaDTp#(<r&6>PL3~8%F0>*j5yd1n{kY(WAzTjeUiTL!2YL)b
zu_#ku+$ULXZ29A*P)rHYGV-@_>L*T7o3vTrp$&oz0u{iElC4iR0T^US;WN*g6#o&t
z@+1p&SnY5J<Bb{{X2~T~)^aTjKn_3=oX~U!eWsg=oUy<UWURd7B6~!)0T0jg*%AOu
zqt1Pv48Ygy0~66SA0a5tv~FpmY=x`9@If4}w56VH6|x1C?hwLWpR8kl6BW^!H9K3`
zNZmmw-Ujo?%O%>aCU^swtU#L4KSmsP&31srC~}aLFX8`E`-J!D8{mjXyOCYMBoqG`
z{Z&p7$06X9kus`jCnzT&eZK*@PLGp?VV&`<g2-Dw{U)fNy3iH7PWrskrpQ{+6N_$L
z1gpv_@EPR+)J_$}jYL-(j0%TYr+h1V1CT{dDU2_+`ZPlpMyRIsE=6+*clHi+ywMtx
zFXZp?BoT5jTQOA^zlW6Q>=mlhumqput5Y7u$Vx)_XG^iP8W)Ge0=|!HVtSJ$d#woH
zZ1(|dt%vJHM-`jteqcB|i=VF#2J<c5Y+;*#+bKiixC*Nyl%mJDdKc2G=?4gq`j?J}
zm5VbwU1ga68#3E3C(6oLEw|DCOV=0^6pBo4o{IsT=a9_&VoC};>-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-grFb<cKNs}H)72W`n*r)+P87+Pdfc22k%M7@Rm{jv3he;A_lRzviUDO4e&9nUE
zz2O88G7drs-K%LXP2MZ4-yRn3c6a@#$AP(xEnUqw9E#;I?LUN-=y<iF#EZO;*N(}%
zi<2X7sDKB=?Is5*_^CitP@hQf>g#$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@2a<EIq~q*TZLDTkC;?kF#&w-?N4!dua7C75p`B<P6b9lNiMBjn=*}X
ze6;uTsNYRQ;^M1TQp}|_^dVv8O0Y}}v042Pe5Ud*+;DZc;SLi5h!i1WPg_+c?+x^o
zip0hmCImdzR`uBGAf3jcasaIs#heok!6*kjLHsqMas9tEQJeFWoS!RtnChOHC$l8J
z*>lOkie;Y9!-C6MK)p?OQn>;VJY!TwMl|Z<cTZES?0RTIcyjd!mavEC$fVfCmsFv1
z@l>xhj-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?<FMk!X#VtM
zW-qr>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~Z7y<vm
z+W4_x{Ea8<^E-Fbl<=21`nsTvk+!OILX}brty=AEy26Neude=NY?KffKK&a-0x%AC
zpS9Dt<*9TC---TkYE8)o%qn=UWsw%ew8o7uWQ_a7+VuDDUR)FOhfJom9%P&DX|DJO
zOH9wL8VWZ@j`%k<6~xgfl7qh!;$N(Kr^|bo(b#}qpzne7kqR=P4H4gO6=POFVI=nF
z{LVeVRa1vPU>NeSZM`5)g%7|<91<^jW`+kvJKKy7D&C3`Eh*X>xRNp)3})U<98jFu
z&%`*^patg3`=P0Kl8H0^kHD2ZKc1x^!LuKgvdvmQZepJ=;}s>iigbN7bLF6Apx8B5
zXO}f`!2i<H^ZIug#B??lI5I2B(T}05d%X0+-lDG}KCpq-s&s!_74D-?kwoU9&v&j?
zppOz?h$ydlI9gwYFX6Vraay3!Ux1kabfCtf3&GJ&vgdj^agY3J1*HwpPJC^g+VY*+
zDf~zoqdqIU|A8k)r29_*;={4GCq|P9Ds8KKz=iJKv2Qng{lS5);_c=#Wk2V$)ISi+
z2dwX*7taZ95o?u6+m*^KJXK^=oZ}fb*g6UmA3NykwrZRgSYd1a2tg{so%2d3Im+==
zyd6wp7o7?Ha6lPYZv|HUF|CD0trkx#rm=+<djo5PJ?_QVLYZ&cppvCKJ%Gh-01`d$
zY!RZq;kjKetR1~>BD+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
zZ<Vd{y{8l^SD2_WGV=fjoQOvb3+0v~%8-0k)wph@26tm*!j}<3CDybZx}EH+9eb{*
z#|1`k6(i)-O_xfakRc1X5~j~MF>9Ns=M2Q(fgfd}bw{7&j;7MVSQe!?eaoAQFtK6^
zH^?tL+>p)}x8J(&*_IszL5fq^L=0Sm3S>r-UpWp~HJ&IIbl{%z>4=!ql7<jI+U&>5
z%rRvv*N`I@3a=^VCAR<LbK3#8dF*%12b~~!jETO7xdDqoQa3{7YOGG1d`w5M9Jy`1
zHB<vrg-1m@G<C|w@yV!m;mu{wfj&l9?^^pT_$}QfPPx5PS^MF{Vbv-7tdNF+|A1wZ
z0hV55H!8F7MX&;eYVgztvn%(0{~`5X>I23X@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-{<K%rOBGdxtgM1}?LWCRNpuW>Au!Bsab=tn^vLw_y5uCSWDUV3ijkfx6KUKN$Vc
z;0^d<Ez6w+x6%CvL{LAz?^2d*h<-o$Vn1A+I`%9IxTBnG88CGI<@br<zlvNkZ7lQj
z3nwmLW5zyJKT=s<Afj!`ksMf^1j1(-6Y(dsH)^eY!Q6vhDdEc0`w|eyV{!GGAmdXS
zz3{(|qXyppog*9YYhnXrP+I3;Jtg*Ucbj%*5I#^r>&P|0e=kxMAR9(?(8$(+C8^E{
z5220T?NTQPUHc<WelK?Nmr3No11}BE*<Z|Jt%wJp<fHD$x23g`MF5V{tSiWJILS>F
zAwnOTHzuv<9JXVA#%SP@Db2PHv|kKFxgW1h-&RQI+v?QVzMM|AJ}!`T#ENDt&#F9l
z0W36!XgjqUA@k=BEnbtL+=~HM%;klHP<J_rNJvG)PU>pqks$|^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?^@{D2zc814<VJpy{ExFb7hd!{$V;TH+YhFKZ;GiTEr|1PiZsr<=0
zEuXX9oMnvillG$Dp?8~5+MHq@3l8-<u<;&TLLealM{<w-S0w_37tS%#eDgd@RbrM`
zA)?Q0bbt2**xgme>NlH}$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+>#y<U@$-o61W2
zMUxyq#-)83(~llmTU7&lx=rTbx_L!QluQB5_jso&Iw|D4d*@=9HKgNI$-ec@68!@A
z32SA6J{Z<=dFsgsf+F>FWV*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|KuurNd8bte<?m`z#yvWK}bFU0vZ$dke8U|Xb+_gVW@|~%J
zvw(Gh>Eof4X=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#<YU
z|DGfq)2oKOP8S0W*K+7Qct#6Rfc0^h?^%8C72S&ttyJ6`rBs@b)~-(8IO;HmxQX!#
z?qRtD*Nk8qmpf;K7AQ;h*VGQUh@9RXf9*n_DaCA1qb8wYRd_TRJh)fG0WIjXLoKuS
zcZszx<oW;+On5G`lX;5do2upY#K8Wiv>n!eSSP*+05q{0&Tr-93Hc}DA}P|3ar>Cq
z95h+O4<te_q!p@<Xh~sZuKhg2i+vYX4Ez04+0XSNbU{(n(3et65(};@-t42k^<1uf
z609=&H2P?b9^vBm5GN@A970>|j^CB|SI$2G_fj=La<C1iKCscmi!2>5oO^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
z3iKt8i2v<i9?{n4*ATV;y{l*e#ciz*>u}1uXyP)spYWoa$Z<d&5eC>j3CTYLPK}<u
zvu3bFxH6Sa=cDQ$Y=cmKed^?LiaKt!W95V(S}XbBrfGM$+u(zKa@jLt3`zCql8G@{
zizYM-r&-I(K|K8Vm03K1lJ5e<A6*w?SGLFU&Q((sr$#`B7SxUV4Ugd3<8p%>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<vt}aaF*?H5mPk08$=Lv=o!{)x_^w
zIxqggC!R`|Vq1iKB=a`&Ty~a=NBFyQSMK|UHa3K}&twPbUrN!{!!FmDyJrit<#YuD
zT%p&X4u_$^0B)pR>}(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#<T%~hsja?{cETTmP~uW`Wm%RG221Ns=$$#a9d8j%1tAb7f6<*
zP59%;8cWm&tT2cF?3Z`>K-Prnug<y?YM6M%#t;J!f)mU+1l_I-m{3UJTmt{mTJ+in
z<BM8oS3kxpJ?41i((1(0S;xdgf6D;V%Qb1*?_@w6j}Oyp5BdIt(y$8$na-y&jmOuZ
z8mJdt98^S#k;<9Nwq6*Yz}6bmDyiy%sRH1rWLQ48Z~ViouK{J$2mfUoQRx%qt0`dS
zSW9vT0rO!`pSlmluR=U??tjpO3PmYGa@pLC#3CUNZ&;~8P6yqmw+K;1N7#}DcU<s4
zA5f-&eZGQ-{o!RPrO<Q4KiPP4Te|rPf`XPpp4>t+Z--G_7qR^OjWoSY*<W)~!d`9y
zZjOd80jmm`#MC<s*b-W%0MN!j&TNX`dN#_GCk26FC~8Pb7ib!Ym)+r#$1EVFD^%XH
zD~-)%3ZS*44^r*}n+&cofliC9U2gQI&0+j#Nl+KaJ&5veJ{=>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#(XqMJI6GDF<p2SNFV#*N)a^j$us9ZaHT)<=RK$
zzQVQX2%<N1)+sB`y%IOlp|14L!KQlDZGZdS00}qFRS+KTdCx>ww#(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!F1G<Tq<Xv^9HX6z#
zW_UIVp4chcDMc@U=q-v}V3BWv{1}jZuZOnduOlQa|K@3THy7(6>UIrJXy_ry!of}_
zs<_S<OdVxTSrLwil%$H{A)w)tY&H>w6UX8R=Fab!@iSpmNB$MOR~oekJ#VU>TE#cr
zHkIM(n@X`Y-#+}rMQ@Q#yK0Wmp>!y9vC7<wjI*<RR0KN@=mKEg>xislL7KZ`)li{H
z)lk82E@G^WYy>FCV#Ytg=ntkA5qK<w%ishc`A6i}cO%?I+`j$Z!k1_@06XD}@yv**
zA|TeMKzj+m3)|aQz{T6R^2NFzYZ(CWPnbOvHj>*3{CE4yW<DvaW{NnYQ{`B`=z%)D
zYpf3NPg{(90lQv%F@IlZOq7076JT*6H=Xj7YUE?}A3;w_n?qw8NV}bl)tMT}y~a#1
zb<t;m;xpEU_P_81an*6#8<Uk*<iUo3)RO{(5H7CQk&hshohoS(HU-)-NX9x>q3j~;
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+<Sj&+oca
z+^SrV!A1tQsp;wZ;rQxItTe9zIe{ym;c~;f44@YuSuf!@RRf$_;Fa$%iHv~&jlHgh
zcvfC@^Kh5J0|Z^V5Ek7UsfBCj=u4M;J$8ij(z-I!A3kIJH72Zr%1s;SpYr-A@EKj~
zm*<VT$2d&Z5+jc`6J4Vo_NTie%_G8vaJN9w4$%*h32{lT;G2%5U{jXjX^oYK{()A-
z6d~C1=bCU3p681|+amSR#n53{+Ys3*07y5I)g%w88FM5QDoA#xO?|)dsEQ<TA(d8&
z1~7%}zeF{yC}1Y!z17<uY<;gvF+as0PM|l+jJ=dU=5q9IQjIw!u`Do57|q+9CxUl|
zGoKlnX2#px+%Rky@teL&sAJYO#H*<m0hT@!i6#k0RuMFnrzLAb?3pTpstbi2d~f9-
z2Sn3(#z8b^Cm2d3#X^lMqCqNEY5YGPH?YpkkCLXe?Xt*#E^A$DmHCP*ZkpTy?pZX2
zGrp-0kt2*zFc3-iU@Ad!k*t&bE5QaR8YD`5ZicXqCRWNWx8>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<Ed+#$TG
zTt$*ad6By3dQ%XFC%y+#ZK|A_EDDVI?P<0jGFXsi4^htKo5OUE4nA3d+R4;rQfsOn
zb-iA(rPcmO^zn9|%Bur6YD$cG;^dHz&mlYhs@K4+KM+^0sk&BnIf0Jn6pTl(?$pE?
zlGn6*c>#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;W$WDk!IpYlc_#>
z)_rVhB`re%PM_KaB|6OY*P1R8#d=Dc%Ta<Sl<UGW-?zGuR6n9NhDtt-qhI_gdJ?~<
zLU5Z+%LM{&JqyN3MWx-ah$o3KRKiVZ7=>z*H7G~Dw5E)rS3Xq^B!sd_Q~BG<;09J)
zH=c+Hg<RXTDn@Ep&{-Qvll<diQ`_J-6wuca-uZn$ZVupBSlmb={Z8vv8JJt}jFnGb
zsir2SId-I?eX@bUac2t{kMvM4TE*s64!_&&!SMYoUFB0xUms+VSZ9?^=4=B}aPSP3
zF7IwM-f*LL*HORTMectZ^nBB-T{Q^`m08hKG^u-pr-h?FjUlq~K3k~<8({VDEq0Gk
zmjlEi5Q3EW&t*{N@qG37tl;S{Txnxn=Nqtr!gZS3aKtw?;=~J<;wR59QfI>Jw=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`E1n49<hbt>jmc=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?Qc<ohz9~sGyHZf^M!l|u)V69{;
zJyCol9vg|Cr;u-BJiB4^3X!FiU<4k4%JhlhWG(M~f79=L(@NV5PewqvSZ#JNWQrOH
zj*oA>8)_adc&H7XYz`9<Rd7S7c)bmMxO#T_6WV{}BgK`#iVtB7q|O=sE?#)I2WzMZ
zCcCe6p{NY|vZ0rmLLaNE$c{3Do_i91{l1DedC+5HqqTaoGc$f<D>gP(*(szDGlDHV
zO%@;y5{Apv4pT~BN{ZC>35lad1EWfJ;!HS+R;T%LTQt6eeJO!eOl6Vn(M+{wr<!?y
z^{~D=gaax&y<!aH%%vr&La~JQEhjQyYoz;1HG2cdAz3pW>@h{zP?q}7c1A*fVbq;Q
z!;*#js`inxT+Q<RgmAT9v+*2<?(&HkD$LSROY&EWyZ--3@C4JU!Tl3H{@1mNN6&ZI
zcvqqSN8bNnbyy>@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^I0cq<l$TGkTo6!-R5@q-JRxd=*5-Oaxh
zvTPA6T*T7TKprB}T-sPo+Y?^6eiz67&}qCt-;<AKn+vcJ^y7*#vc9gj{F+{Sz6t8^
z?C_KrL^&>RHF%$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^wx<kQJ4g{AT`f^I!A3ecwzJN
zCI|3~U4}#IRROg<A-EK<;q_ISk@RTMY9BNhMmzv+*8bC7Js&h3|4Rn*oKUXOvaz0m
zpuF`HSH_kT?=UF2rv>OD+_C5$IE4yERZi1CNc=ZXPFxXe0EeJN@uB&ZWtDwMDEvX7
z1i0W{tL$M$IY=*w{E0J?O@P<Qvv%h`h#NQM1nCWZ)kG0a36P2&zBjamYO)HzGcW$}
zfj#pzjUn|QVVX}=SNovrn=*c}K{{t2X$yEyIZ966@vS0>$=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(8KFGuP<x<D3lF@;(kQ74NbS7K{QG!EEcF3@q51{H?TnWVCbdkI$xE*wUS
z1MBnKIbNH$ijgj&j<3voMz$4@B6;C%{>6R=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=rvpzNgg7hj<m0HwOij}7IX<#*OY!^8x
z0fh1MO$Ir?wf$$E3BdA~gB8AO0%ttwz!HY@>k#cfTt4#F29>Ud=L0BMh&>9|Y;Df9
zt4^^&VvleSo7^|aYwGf^*wOO}lwP8M2;F<GDYfeHaWw$Fl(4IumBF6gN(83y;agbh
zNDL8H;(b`36-dgK5{V^#c4&DAh7w*At1im~4rKC}#RBoim+zfF<ncy^NUpOz6)sU3
zw4FBxsthm@rBl<%rfo21Kqlr@3s>`}^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_T<GXmIjG
z29$pz8XpDvSHH7)VNCl(s)XJF`HLbhB3l{Ypc?oTMd|_h(8wvz*j^qJNDL$`erBR*
z0CD^xK-%$8$DSlE{Be4E$}5%90lXSc%$<`=JR6ZfqytL+;zHHh9)Ao-m*4EaH+Y<9
z3hi)EqT+k~h}dOiyT2moBbsS}NMukbDXOSek{7d08s~ocR1l*H>5D5b1KKzI0GYaF
zpVX2AjpuLoKtm7e!n(Ztf`2RHf4)bHxG%IHVJQSjRs2gKd;+(+cQSShD-f<3vL6JL
zyM#o4WpQ+|4HHiFu%}qtmkAp1gbFuiTn{|j+<d*!Is6>*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<Z<2)A>(w#iA2js&JDp_o
zy167)64ZQPUy>vss8}BiqH1(xFPouy1Oq^QLJ{ymfIcNL{JfAr;{jm2e=WpxbV+`8
zl4%%!#;TIii*L<H>E!;KSjGYxttK%i1X$MUHeuJLT1*UWtrAa`(a=ad`HND|@pSR*
z7{{LB!@5Bnf<R?Op~_RgP}3z3Tuw-Hf}={j(p_0tE&Z3yv9bb{eS!O@2neZ`Vb{oH
z%eyQuGeJe5dw95@H_)x`Y0~5fL|pq}d<-fb<YZi9-39z*mnK>?fTJ&^lrNKo7DzaF
zX<9O|b;^u%fi?MTaolpkcCiu%_H)Sru*|29R~bYb%%Zit(LNwdYjkn|g}`I*O<fou
zP|?Ot30Cx+`}!1OweUGi8SrvrDmp%#xKx(p0y);!+xaX;w6P!H!6>;_RRHl!)d2Cs
z4AJ`%&r|$eG}M5Iwv@NDiEb&vLtC@(v6*v4${EtKhH2@q-T}u|n8qk3<n@ssr5<Go
zAfGyM-Ts#`EOB@WD33s=W;dfOL#KZEH~)HVZq+<o{pmvw+{GYbfUcpw*65Pl&SWYF
z-XA+XPj$vNX%DYz>df2G@l+&^s%62X1mj^JaAX~^R1<Jr@UJbQvAkFm8;<5_P=AI|
zDbB&bRfKv|St^Bb*maRni<Q5z<U9R@R6~OJnaTqV2Wx~hKI6id9E-B+uo@DNJj@vy
z;KryuIx49nbqnKC4#C#UNDU<S<z{J`1gh~ZoDXl<sO7{&tN#)vOsf|17;3QtE}ye|
zY|_meNm7ddQGd|v+aP63Lm7${dZp*WT0@h<8Z8bD_Wr_bqW<L7S_4rT3mhR?`9Jbq
zV6Z5R)EyJq+VYRNJBxqqgluFYKYX}1j797@O}_$l@m!eU4sZm}0b}I3v##2;#eD(g
z*Ju_}#6L`Ry3%6_Z#zPM0*U~I;%HVrvgIH6SpoHA!K&4yq`7iBQPcQPKW7av)tz-X
z-BK3@$fO?rLRVFgvcBt{Z1z5r&r*Wo(T$LdEyPCA6Gd`vTgP#?EEIp|J2;>hm&<6Q
z9z?<e_@0NAp5;M7qq3TBMsX##$Tc)69ydMj$gx40AE<QYAUT;8=|ozyR3RO6^SN|w
zzw_?gM5f0T6}dx%)7C9Nm2zWoS=)5l^(>35mm4H<4m~@D;ERCDqbQsPt+UB$dPT1W
z<F6qRe&R^azY*bJ+mvMElc8;Ue+6h?zyRLAXAyq!?sE=?VZp$~+%l!E`4U3k6fzv|
zkj;Q37*H%A+}5=y3OYGI(ase2!<LhyY(|>h5mO!L2^&6Jo_Ug<E4>xUETyxVmz*?F
zUm3LdPnf2Q>Ip@XaU8&lAnx>)<3~t)KNHOzF0U@qu@O#Alg7eBsGDpRKZF`<1+=89
za75$<glT`*-3}bTheX9wS!~sr2yR;<;Z=9iwPK3}Ew2}ps&k2FPIM#t(#)9zf&if?
zWZIG|bV$<T+V5e>6KF#+sNwY>Mv3z-dJ?*dErjI)2y@7EK?C@odI8jTy?ymff{O#&
zfnibFu1Z9^(ps>DL+MZ8qvX>KD#fFid|Koff*%h<{j-p$H<z_LejyN4=EX(FW*=QE
zkjSysbhu^os0k;&{cKB`s2K3?S-37BkO&FCEM0`SldG`}!FT0{2@>vK0=TH^iu6Ge
z{)`IIAJ+r$tRGEHvOtYo1!1ceJw-KuQl(Cf{_TkWf3}q;vg(nMPqfBOwRBi8cNqp9
zTm6TGMynHv8l5Lvj;$F}Vo=Z|A_u%${k%UtKAAUmJOMH=-azfaXL4fOt8Ytnws*=-
z46jjlhbyV<hMsW0dRmE!6<AAl`LJoH<O^pMNPJFXNdA{99vnnYb`hFSfa6b2h8F_d
z0d4S5F8oLAV|+m%ITj^y8&Mcmf-*$XWmmVqtO(T(2Zgj>sp;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-8Gv9wSbtwA1CsZo<J4L>q}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|<KD)YS@m9?20wkYkrQ0K=xjA4ON$)JSzNBG`7wZ1mX0BxMEjyU9;F%@9K%2lLEU
zK1z>(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<!p4E<=Z~3UFzm
zqJ?T8k3&L<B^7zB@YnI6=(=e&v>}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|Oi<m}IDcCg(NmpMcJhREA(U^kx;sYlP=*Z{^w!n9vGxcX|kF
zTwqEBun&>R62D1MP64`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`H<uL-QQ8XKs$yy;uLt)VO`hw3wF_crkjRy$x1|~sm+`0GoXT6yF
z;UEhS4SvC_9vg~0rTc3JVp28H1fL^s;}wzPvl3U-(XFDW4nH7xuQRwxet=Ot`;~#8
z#(i8ZbB$<0>Pi5gQg(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^<yb4k#vEtTrZ
z(I9?Djes7nQ@xqQ{GH!==D@56Lm`$s($85LFaoT&ftEXlZD7qS8_7)1)~SPJG0)KY
zL$2CLYnZ)s<R}{3c~G3Salic?Z3%d8J;UgW?&~%-r(@!<P>Mzdc?<Yd@Avms!kjJv
z$#{LP)-i??2s^w=oEU+Y@y3@Iq3K`iR!zlR+bx8!cM}U86uFuLDe>|Uj|w`1w4t+q
zPV{^-ngSzzv+4AdlBB)bO%|kli<<?C5Ir8X4htj=Y=;zy&x@}>nBT8J8l41j&QoHY
z72N87S=66|u)p6%XMIT_XtaIrP%E<U5oHBE|43UmNenx`AYIU`tRBk=@Swe4U%iyf
zKp>cGb=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<rTVDPVZM#c<e-7A~{7F%H`0AF?o~ZCbDX6CEDEu~Pv}hN;SWXKQ)#p<-XP
ztp~Xx51@*5)>@$I;p<=!>Eovi&5$|;hOtLFKxPX3k*>l>2Tb8#U1uubl9K<yP*8g_
zQ_0J45;fAA*H#z;Uecs_W{2{#E(5RSc&C&Hygby`19f04l+v1A(g$U?iJ?^0rRyt7
z$)j^$MlOVi>po)%v_pC@rGG`fMIjulxSoBxuGYXa0txtTIK{6$_ZL0-BcC%aB5l@;
z@-Q3DgKuV;Oxa83Cw=^n1D?}<UGVc1EOyRp<+cTwQa}w4c&dh}k>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!#Y4syBHAq5QWZ<rhuCGCjN3C3$-k!TGHhy&
zp0Cb(J3ugyD_Z>N-vAJ|InXkWO2J)|iQD}CsAk<tkHl%hl;;_};-mEh={|Lq){wmO
zz^mXC6H`=N$g>!d$up?sBt(@p{IuePEH)X);+hhYKCFQ8Jy|a@^%0)go{j|H{ldNt
zS0tgNo?^oyNtUUIu6jxJCmN`7b%WMVQw>F6=5l4ZPnDOBheo4ul3af7DW<fmgY&zN
zy^pGbd%NcM;C`a6{^5I|J!?+&*WJ=1I2pM=W(cKASa(}_ohsaA?Ckr1O?ZCElPv3x
zhSb{A{peZ4#*n{=;TESW%&I7xdXM95aV1%Io(phBDXAeHcbGDs;jt5N7a`5xvlL9h
z$;NyooyM5F8ze_kihsM7)bGfczh3>!g@&e@1!{Ba;J|719(9n9_*UZnf-#FKVjURt
z?(!d+TFWKe|HQ$eV?AzTuUB20x>|6I{64^O&@bK+{@>KO`=X?6<p!RCirHswg?KF&
z&>Dls8g3u@#^=iLRP3$>9GPS1u7|i}BS{xa;6JJCK0Z)<Axuuzn&)y<DqTwa=Jijj
zGPN0GZCKbK3b*O3T<q`mHbd3~E_R}0AD&q24@@FmMP*p7G`y4O7Jmps<KiNeVPA_J
zZ_eWh5*snX!?)#fDQCHU0+TSk?f~imivR%qdX3~B27+G=l({hVY5V&CO%e<S<)s34
zQ}c50Ob6&nwrhAh$tyA_BCi%u|18^8W%_fgzOd*LEd#4B?SA)K2SlsD-&SmcEpVlY
z>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>JlT0<wbf6tUEka_kr(*jm0SnUmraaL&IXiHQ8_+`Z$%+s`f>RdgrFhSz}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`<p3i!spq{f7=vWa_y5c}hkTj%=O8!R}+ff)HlA<XQ>n0i^BLB7zKmr!$I(hm*
z@+o0L!(^0jP5=s%l21Z*%^{~yiC*;_K=1fDNwX<;ZaD|~&OoKxIn5ckww*;54@phV
zz?Mq?Y9cE*?2TC<ZH2lSv42xp1gy4oBNqp`f`7t>t6U%Es*?Qq2s1Iqclb5`-$G|N
z;8J?aEb}AV@seu$7XXD;nZD<!W~zv6a=#zA0FjjZ?XVbXC~{0{R)(A0Dv4PRU59zK
zi4<j@Jzv(f$)&ef$t=$!wISwG!_&kWzorkkj2BVjy#fAfe)(v&hbN-xZM3Xt;PXCB
z469*r)Ue&uFlA}Rs`Oag-h{O{Wc>Ivu==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;<y%V-xDa<JpMx+2854_pfuX;aAKia}H!pcRU1(WRV?5iJ
z^D6h_Gn=8cv&B7A&d~kW<(E$k&uaaGt1-zU%ZuEfxAI9&L!2OZMI`oqT|GV#RE4B!
zOpnZ}&O0Quk>^e1(W#bE75}D<Z?5$QM)I?4EsU0`PpL^udSP_mQYC_-eEB3y6Eath
zI!qqoC(g%WilW0Sq7VnGZLf=YWO*5#_%r%F_BIp<b0WehC58QMNJIdkeSp{_ZX1Qn
zK_J?tDKsG!I;s0$H!QkjMd_rQsvzvOIWP4BP|k_qOuqk*iF7n*rPDmI((=l3z39@}
zLW?tzw@3N?b+`7mgp96-WQ`<po5jKj7OZqgXQM=6I2bMu*e|$W01+4fYgSF`<dgrc
z$x>4u+_T&|FhHj$?g!LdyOip(AcX^iP||9m%aILNoA1Bi(f(AdBBAAYQW3uz^Uykb
z43)C+RG{fxepymTxS<^l4<g-ufJ<5SJ70g!flePOMs5E30jT`?6Z}a;hwWZ``vlyN
z1lRnB4LE0&EmQZ~;^4W+D)Q8;X-3*1pd*_pP<1bwQ5sG2+kJ|TVu=Wn1Tq;)eo&%z
zyGkL0nrxgCgg&gX@7Z!}@9V(q@}gk>h({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@k<Z}G=bgDLF9jYT=T(~`e8zSJ19v^vF6F@+JLM7lQe
zt{adJGz_gXgrEVDPl;A?$|bjb`ms$gKI~X`-^~M0)_3k(pnz6YOkepaC}B9HC=zd!
z3^y0Dma2jKZ>up`*~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|I6MLV6B<z51%$KC?um=@O9@yLp1H6~%54`YeQ-&S|L3-J^&f|~Gm{n%*7+{gm
zb;^I4&`qP#MjQryEP%__u$Q`30AsXp_^)BnpgWB;Ke4(NfMJz+OgJ^Pudqt4pb^NN
zGB4dwR4YnFc{m(I(zK}>a`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&!taG<E?E^R;!YzlCqTAAxqW%$&3q>Ai?pT+Iku^HOaUeW91P*Mg?fy|l
z6dZR~g&1^W%W!6Njv=dN!&9&zrS7L528|FrkZr?We4wB{M_2r5QwqwXf&zhh3Ck2p
zSux&O1vjmm5>vOZ6GLp<n1BkJLA&k7PI2N945fcTrC&=5XaOOpsc<mtFrl`%zt^HZ
z04-Ngf;`req9Ur@gHL1*bVPCiav|M1sCMN+iHoz-9H#yz*&LG%<V3<pN$j5)4(qzx
zE%s&x@|D76XCou-NeGnnIPSkMWb>!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@<t
zm*3!aq&~F(G@1%YjyM$W$%IoR4Ft8%q(Xf35^~kZU~OOtCbzGvzNXq&H6$nCVIxD&
zEWW8qC$E*5<RtcyO8+ST&=(A)Rg&9!p3ngj*AWq7o!P`j_1P~5CXBQZJ^2z=#djEa
z{D3==JN|~;U#q@3y7fALz?~kOxuFleZ0BF`n@f4aWoI8Oh3Mx6R*SJLxx@z;OxcAN
zfVzC{7d3KP+Iz2Dx%X6v_MnLJ+R8jBpgynVK5tWPiB@08TPbR1L+VuZ8tUJq5IA>v
ztnoLOb^2nmjuOZI#fM_wb*)FfFXZJYdzr@S4Uz0plnUu=h`Gx$UEq55#}|o>iXQ_q
zQ<B<uuJS#Bx1winyGTDp<J1@8{jsT2#W7C7oEF3z>8uxIkqfa(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<Z1w5OR(7o`x&Z=zjB&5PtCyM!7SgbiJm{Owgm@WCxv1)FMfc3|=huit3))x@
zs}?X^A^Z~f{Az`h@)PN}?;y?)%<gYx5N2u7Cj0Xb>}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{G<SO8I_khq;c-U0AMY>a^s+%^%<BA
z)k==gar{0O<i0>j!JiZwJ0Z$N90RUJT7WaaX$>Ht90T>t+gC3<LfFKJbyv$q*0Qq}
zOg3-B_KS!+{p76iO=*@DP?U^Au={K8KT*h#60@4gP4#jeB1T%u8jOs7+JR;8KOF9T
z{heCWYA^4tRN)ajp_`4>ykX~{pC0K|sG`lc2^cpRBU)j$u8;?Y>0THTA_D=E7`5<J
ztL}2$M8WjonWU^7paBbjsvrqp&>46)9Z%!?{sx<$E$8|8Du#cdHzb;K6#<(ATZT0x
zH%AfZIj&_QMFvjenu8FGW(*%vK!QCs-QBY^Q?}ycMvVJ%29m_afz-qg8DsLaYNQkS
zp~|M<pV>P%pJAyHI|yg{Id1<V>!^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_<l#a?1JWZZl6m#R|KPti|6XlPGY$h<}1@4^UQ&Y{qZyc$oNmoE4O
zM4WM(&=T$^S)rD&j;ii7;xs%BhItz|TKkV%F`~&bdI!%3b~r}g5C%xG0!rs_6c-%9
z7fe$!2FHt%IrY40ye)2^QMlKhf_D6DF?E<98dVetbY0K-TG@BTWO!`YhUds0cyrm-
zLceq>I|TRtX1x0MWm2U=)GE9zC4406Yv?)n-`<=rz&s17W5xUlfs6Yj_@)mvWj9|$
zI98FwZ`P5`E6-Zs!MKD0Y5-vWDg$|*qp3xtX(N_H>MH|=B_kysLN>f^=Pw8wQ^CVt
zRN-XMZPoQ`s<K-0m}(pPTaySKyORis6kf@cofH%seb{71;Q#?@sy%dvmMDsLqUOBn
zN7ZuaKfp@xG2mFy%N2Fp&~7_^Ek97&i6}&Qq_;})p!^1QWNWYFD4L2aswM*|+ECH?
z=n@;siOKXuakv62VW3F%mc&3|#X>NT<!K_4R{${G9IlP7-YIWQh6X)Y&-8Z?h(rsm
z@ZJ<|K0#KRh%7B~IbJ97r<XU89`+74=7s~5nJEy0ZSSiWJS%U2AJw854?M^w<Vh+5
zfsV$gs-Mg!G6oE}y}0AB+9@T!@IW{a`UZfCR5-?}>@=or_abkfr_@-wg!cZ;A{92z
zI=IV8ZHw9NxyAgf+jPJ}MzXRj%_N-!fi14?YhkYmoY`ntx1Gw0V?FBKl3b_T7G7kv
zofTmJVIm7R4oIKJtNNl0Fiak5zI_{;0YX-Rz%{?xQ`?R~DIHlQJk<u#-1{=wH3dV`
z=gPn;a8@caK!+r49!gjdh~o7dA~17_RP{}O7Pa|RS<Y%rztR<;jZO+k%rIpm9dcmu
zg6wp8tX?yG0#QH&T1!Qx3vP_Lu}+PW=OPt>iNMkNqtD~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@l<OPI*$
z*wrL6ciSVxi}a*kenIw7CR*jaI%dpPYUM3gCsx{%Fu3OG@Mu8rI-iu0T!YZ(T=mn{
zuBbDXuQdGl<yQ=)SXzB^fEl>D{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#<tWu_YO_wLYurkzCY#2U3r5RtvQG7aRjbS*e(
z0q`F+2c;ni4dQoQ-3B{&W`JW6>QPZPXNX(F3gBs#2gWm%W64=e003Us`P3y(<YYO%
zopG|WY|b9^`oWAPYbc}yGzn|f42{t1iTNqqYFC48-<pTS!}2O*P1c#C7_4#+tyJLd
z^YkW%V}2WO0(`~WthqYeo0}CKDU;u$oXXM+I3$F93v`1fumWL<2nv@cIm*Rc;UIR3
zPtRW+PozRVgL1m10H>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<{<ke@Gc>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(@bHB<qx&Sd=l;|8>OB
zeor9D%ZnZgL|==hFwD}lI+|(9X2>ci^U8e=#ZsG$$c;?3uzJID&*|1dD>@<n^C+dn
zJ;-kM_miuJAcZL#fuZq%rdV^I4;4WhZ_=-e@o<-Js2vCdJD{NcdK#1s=(zyC!dJpx
zDM%V9ig(>ik(2=`o3QCMNus#sNa-q8XL%vLGfQ4q05pcEtPAD6*b`z!anxdHqKjS)
z#=m?JTS}_zaiBdcpsXw(!k><fEJTZek7vFoSp8fPMSVlw^DT=Lk?{<^B@1{Tx&C`H
z?n`O%%Wk!07cE^s8lfg{LF|G=?jSxqChfjw`gD)`$;f^qXQR;lLnxx3x(t4qKE=P_
z%B=SBKH{TkS$X&Nk;X577coo!Ab~KW0YSM*L^OVs5=qtd_rVSf5aD2`&N5R(WxPoR
z+>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-<P0%_WDY}C=kskHw)z!rH>z*_;R3pIt
z-8ZFC>hsCQw`<v$5mD2`rX+eQiVqMB|31UrWS`d^AK1A+P3qzP%s4RFVA&6+=~P_c
z@kW8wid0+bvMo@2CuKX^oW~=z5a-NeO)`XQlhqkV-G3<n2#f$IAR3$CeE)MoheVwP
zuLk6k68rG?{yLF{V;t=%g@EARPT_}V=TRZvpw;BGQ$+Mjx`58T7}s?8fMmwvI~!~J
zn1ck3&zS<7R_v=ThHjOen;vuuQDsWjL#oHpAf;p|xfdEcj9e(7qKrp-^<FTqarG3r
z78WMx)^{sDOp!1{RS@(3P<C5DWNN5QSs4g3ZKV}*(qK<lNWH>_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|-@=$<FJr%kdBi
zuaLPlXhCqz7sz3B6BW;x%pV&{j}Q;+pBSq-9W}oj3n}H0nk&_*Xj;AFc_!n5nD5$5
z{dSGfi-5U*ZB4rY^hJ%5oNUBhP;A6|`9bg_Sx(ljpHkj*8<R@&0Cw6n*yoNqk$~Sv
zLojc|UN*4om$Rlj-xB9p<xOLu(jjiO#l$j<@L_y}3TbCHDbKt?NL<!aD_0+S1)b@)
zz*59<4z;f3LPISXRrs_$52oAuUS{axV0PaCn<zhudNQ1!)f{%x|G8VV=WlBwWl_7}
zB%QVNYQWI_x!ss`GOh<4$|G~KETOm}i+WUGv05Ki$aS9%8I3T4q{onP)#JB73uuqE
zHe$5fL<5Qd5Yf(+Rc%8f{*b@_MND$g^&g<?w(-8Y>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<cC=rtLPNh=;H;!lO$!rqjLMHes+^9-b|l;G-)@wcM<TS~IRv0&g}S4{g2
zf-R%#>(*`FUdmB0F}V7X&l^anKc%oTBdEnjtSHt19GYhBL|S{;NwSv~`LNdZh@>i}
zU`7@Q#mV)4{KpODGUHxCc4@=lyG|rL0Ldif5BG>>`?!&o8V=+$R$mJPgIFQ^6bH5b
zCP+LQ!Pj<zkVVy=pyW*IJ#0gLS?wT-)TBNZ|H#S3axFYn)B2s(m^AXXyHg$@QK^`6
zxIiE3UK9>S!7-gX6~$GEY}^y9BIFN)t~!hx{G<O!S}l>|U(N93>b?X;<C5+mOfr*7
z@!bIOiV;@`r}eG_xAP<VYXOEHN$(fjwi*7cmC$@ZF#MswZ%_Or8rWT~CWvERa7UJd
z!COW<y7`TH8zw~MNP*lM^`#-;gjH}K%;;$QpR{||b3;ISCu%IeN1WpIMktO%?yLht
zOH;R4A5*FU?TZb~MZzWdNB|rXZVWdcQL3UpSz&rzivrZl>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#<Tbmk&-E2@u1i<P)SI<9eTTYcH@~XhiJ6nZWk#`j9h);DNFgr7@
z5L2KeNPBUVx<bT@&Fj&}|Cg+LHdR1OT2^LLcQS@?m7A%U4FgO;;OJ;7Kp5yWre>s8
zRW0P;ppaleY}my3PvTGk;mrmHFdjFTxEfsmQHJ_tmYBY5C6X85fd?+}O=b*ItXEA8
zwKNaKDJx32twgq2>%M-XDFhA7OQMt%jgRLX^B<FcjF=tvlP(Q2j-KGyPn~7Q-OcAf
zW#HVdOKR&=lv{7ia?d&fc4F*{FM^hUhn4RK3azW&a<{O|zpDbHLU>)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!
z<?!zU5bXI|tjipAQ)O1ls?SO4xIC_7&q>xyHO<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<C$2Pm9B6rQ`K)j4%(=BJ6{X~#*s=FH}^(QPL
zybm@Pw}&pI)4dMclG)-uJl7`kdp5qDCd9^yk}!AG#)=l|#_!gn?@UN13y~rtA(Dee
z<IWT<=r;1_@wYic;g+$!vD1L~r*-esrCv%iZ!2R!6Ux@zm8cCMa+byq!Wx~EID@k`
ztH5U7Z+Z?<BRVF7dis3ZIp7JpH*ptaxVK(w=SrT|IK8A-jx@Yy?ZUn6kn+ttnWs$&
z2lu4lxP|4ZNb&HIHBisb`3taD^Rs3mqXCk%jb|mOVju~gvwTtq@%NC?z*AD$2zq7S
z;k<wjT;=&(Km??5nV|qSM86oQf#60k6oe8)wGYN_%-guPpxfXAl5CAl?|@Ots?tZa
zOyicKXg3~knO$M3FKn-NQY?l07K3rrN@9avHjnU;u!@ReMM;aool2Q%hs&%c7Q`aE
z&}>~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
zYm5<rWxW9mE3<V%DM1eLg&LS0xasl3E`vz~w5pq~Xy>h*I4y%d@1b--fU8pD|50yS
z2Xo!K=N(~SIJO2V{4MVi185fspdz(eaUk+pc=ZR6Z$=uLeUbnihHc51$q`)*#$%zR
z)Meo{;H<m`UT0HfRg&1*2mnN?vFSXn^?i%aYT?SkkWK4oQ_GMR7n~6zYE=AuIWyK_
zV3ZLbDpY2tJm>#R^|A;+)%mt@bD~;}5oR363a1q(#SN7-5DVJVNgJI6go|z0Rz)w8
zp@0f>5z(ZfA(1pk%wg`KU`vy6+~bdS{{4Ud?b0F#9nFS70<qnJjaP&jvbr2~YYr`?
zSWR+5s!P8%(rVe$y$F9?Y;)2Vz}k}{+ErG0&>2D1X|6Q+SMP_ff#+_U%J%PIngj1|
z+ymaTck@LD0T|X`#3XxMKXa6q;yH%11g)OamLnUOn}EsFYgSPU)xS#WN8%CXRq==b
z0S<(bk=(GzhIk=+^O0ON<yC!&8QKj=^K+$M$n`nkREzh+0$#Fwu4C8rjS<LAEnM4^
zfGYb&@EbIL1&(UH%YDX;5ddKuat5JjQs7??W>Sw#b|YpfM$VOOQDC$Um<w8uy}Ewv
zV6s_MChsPU<|gkbhPxGC-zZQ*lL*^_QV|1I8c0lLx1XXZr;y?iMBjK~e;Lm!wT}4*
zzB$dQKp9G`#wxIadjOFsgnens{ylG8Mg7Y~9|fD4*!9uj{tyi*jyocaFOv1V)XiL(
zOocQ4KYeVbGPrk>Jg`84?YOEw%OLziD3t%>xDIMfB8G1HvCQ$pan(v(L}T{Tvu7Hs
zT5;<2g@6E!vPU|x=|AC&`+3}-YV4M@aRoAIlp)T!F*RNd>*J{a3Utb@8A~<Dh`e&T
zK|LDiumHE!--jouAdzwEA=L$C3ncHzc(5gXR)9>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<Q2(f3@XH`(3kk#q07zZ5#9FMu>+w*lwk0tEf(a){eiE)+AS%A=J4epmX$V~
zsFB|rkRYoA8m|W9wW{Ff;L(L&#koqcJ5kcWlsA>z;fi{$I1YeY!h@F<kCA@_Y#LDU
zq7|Y&9SLtVdNd|FV@C4gw^(Bd6yELBK#xLGX~tz0Tzza)0zzq@tGwv%w(o!F&g3)Y
zX6b`fWJ5O@mR?h{SM-dJXkvEhX+D76o_UimJap-jJm?Kp{7O&dRcD<B-o3CpQnr1(
zqu-gp1SU7e9y}5K)h<+B(_AyKOx?WV5o@fQxJmf~QESc0b@v;uysEwcAn|1P$Qpni
z@5)*Lk;h2EB%$`7F5r;>5f_K7-gI(67lwSPgy2Fg`PtrSv6ql*dbEGN`7yokt&K<v
z-TemRsQ?u%=cQ9LeFo#MiKR}9zq2OwkO#uC##{sk*pPPkxxc|0z38ssEPd>OY&@z<
zCS>@umBv9c*5vy+##n!_4=8<Y6t?c%Ei1G!(AJ2BnRS&^*Sfpgys{eem@_w>2Lc&f
z&B<=PD2*v|q9d=1ti60}NCURU=N-%9l4B(`6~|Hl5f_d&TOxpSYP?FICiTagoTY;9
z<LGSQsRR-J4*wW*Mu1W18l`x{ddLrg#bfbNQ=nk$;NJ=_wU|&QHd6O$RjS=YyI?Ru
zh*`Tdrj*z<T^0IM^SzY8yCt3uD5Y<J2#b$kA}@HOIE!YJ`ijpu1c#(_H!CzLU*#c(
zup01gI-e*3F%1EjG6}fX<{N4G4~ZGP=s@_HyN&GhgCe_tjP|6KWUen=^Drf5);o~U
z+~cFeZv3k+qI^*-%@JSx7}&`9Bj-Spao0f5xmnXqs6|>nY7^C{*89yav^0l;+ElqV
z><s@XD6r7W0PB1;j~x?W%{L28szed!rr@(Rky8j3l4O)E1(~&84aT~gt&K<k?D_)6
z=jj5!uPKXZ)5Jt&jK95PBX9p${ZZra--x<1W-ZS`WcotIISL9LT0T>%z4I)l9c*4x
z>WEf#D*avayH@dx>&f8a27!)xN6>CIGszF`GwLoU!~Tk3%v?!lnE*#;hcRnTf;1;a
zVuZrOh0DNbzid>}CHKQ01zXT$)-89ms;u*syF*GHx<PS_XpTCNvz9N~e3QlK+|;&T
z@f$+SYO$>roT5R0*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*=pX<rU!G4D5Dg+oX8Wn=i^nkZgSVX<
zyn(J#e=5RhKLr_b7U!J?<Egu^pNUe?*$rmBqh=C`$XR}`YP}?^;KKOmxS)bedASb<
z17_yNTl><C>H{))Wu)Nl1V&aN4(cJ&3Knllh(9y{iTbQ7UB>v!!V`9qruX(wn3Qav
zpz_fS^xO7XV}=}sM$NmP{yO}|S166|%1GLcPlDsFI*<T~b0Vm5)PMv<<C6IJhO{@W
z4kZ>mkH4G!b<#lnZWs1JyiQFe_|hvnD>;WVQGz2gzOJP9%Eo$XO7)%8H3{m6pNTO4
zJ<Q;mS?i~Qd%CVo<hYB-_=pqWs?R`3<EuLCCzgNwV~(OyFq0haOKhX~HKZfuIagp_
zoC2R(?-BA@>?wQp(0Tw0dKd;Czr8A}K0JwMnUeV7B5cO={Jtci+y2L`s-yE6R}cRf
zSUY#@sevf0OsTTLG7gFQTSbF`X7xZJYrGkr4@2tX6CFe1)@Ox`UK9K^)bz^5rB!D>
zxGGWr3fDS09O^O#0#g&yVR<C5yiGC)_y6kZ`{uEXFnoyi!QPagfDsp=@nPYl&`rlu
z0-qz0B;>9hL$9v}_Gu!IA*gg{2BtJQ^O?MYkvgPpg78oz5`P=x63(7E0Z)}z^5GL`
zW}tt`8KdC;zW6WL4n_d?7lGpE(Ugm4U8^92FHfgxyZ2hN>b*JuS902@B<f@gQK6!h
zav6@b_m(s5{@yZAxs>j05Q!*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
z653Ev<Bbc4EI6dYGyJzr;>z{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<WI1704ZM2bc$2&)PoYL}^c$5kn5=E9&7Pt0eFHPCfdxc2-a2EnDa}Jhez1ZZ
z?&w>(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&<v(b6B83Xv
zbv{r4qtMG^QUDPbjysu?2PgnUUWbC*W;A|y7nlAbP|i6=em3Qk$|HJA+O-`!WU8;M
zDU$dAgM_rd#ik@n*%wwgbx8Qjs*>TXJy2~-7&GCZrZjJcpT|_EWx_r>)QdhTA9V`+
z(0Q&1O{MzsmK`q#iO&T@sH{l9w0^CMYm%RI7z4dLJGulg6Q`mt5`u0zk`CT<23|LK
z<Ea3HGa8tZps{>9CB}yPv7?fI+K*6a@9Wa4vyB=RgJI{ZWbq{y+J&kK?#wfg5|9w%
zGUmooG~@Z2KAO?XKbn|<#%(r6t%F6uC-ttB>9~Ugd6ZZ<!y<V#Fdte$Pe&A1yHg1<
z;&kacVM%^6E|I#6lBTpuO$_7*%zX{&AX`V!ZahI%o^%~Rujn@&NI_Bn5Q)l~dMDn<
zRB!+Q{_s=HP6n;QdV5VwNnX-<MZ5m!etlDsKDq(<t6spe{3SIkt?By5IjBNSA6IyM
zyF1nZxAtw6+dJ=%Y-3qsqmkvU@dPw|TU=T!jN8JW_OUcx-Tb)*HpOBBW~CM2?n$`;
z+ka!0e)kvt*7V`cR^2%RxST-$7E#JmZ7tAa{@-`qgBp_WzQ6Q!ig9)A3by$(Nsl=+
z6_rIx&O0h`N7$sy_`<u)GjDtMuQ*2COVjG$)^aYcN_SzoUid@krA@b0+1nUgG>Vfp
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$<L;74D!b^2J>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<o!6T@O%h0ngIQ$6EKuhrMH`K<<OO%}_;APfYMH8Da@IQNPadk=#LAPMn
zm%$orA1V|GU}sS&sSjssrm^jH0#SD6^bu9wZGQYUl+j&~RHceeU-s@$nwH@wwd2vB
zE7bc^A3j}gJdSH!sBm|4^4>{H0f~R_d=7b<h~}2Y2f3BQ%ZfX}O50(`Zn~3j0OH)(
z#haFj1vNI^9>9DIyf>O&yB0}sl74fXJ~B8!001(=dWJ!P&ncgcnJL?rQx4R~r9#)e
zrY2sBB5y<i#&<uI`Y@BcHC+wbT_G-Cm;Cl_69y=GDn?@{y>+B)4$Mqvj~yHmSe1jk
zSr3|N0kIM43;A=lco064Ou<*WVRIec(CtooN!?~Doc>7{v{UACmfSPuA@%{ZMyt>7
zgzz<yjzPpxQk0JiBf5T<({5CnCIJ!l8d-S}{1sBEPst92SA`LhA^j#b+qb(^A`ddw
zi~%9+LLuK~kW{9&t+MPyWNe@UA>fGA001;at9m)(;&_=c!NUolBR<+rq6IH%wACJ7
zl>U|*teZ<QtVAJ|!74M(`uq>&+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>&<EY1gi5ax<P8x(
z0009-Z3=}$kTiguTt|$~DEjo91;g5ht8@Y~NCIR<zedp;|K+AY*g2ey)*^mdyJ;-8
zXs&3n0=QBMpCNILX{u6miQWPY#LBb?xtd=}82^uhK-Rl6bdG$r1>tnr1|#A{^%(l3
zUtM2bS8r+YAQiE^rM>&dvE{~8)ve=Su{;NC<K(JWrP;p0?U2u<yXn=uyZwC~ydlyn
zeae@nTyD8yc)RZZ-R*yX{r1oY=g^`CFeKL~Mmi81;SUrWj}!}d0H?ICyXeqZx5E&#
zDXzNNuXH44I3f$_7(;Xpj5iS(776#dDT<T;;L4!ZLGEvpGzl+sG5RWiP%MbijsS(Z
z19F%S$&oSTuYXiHG<tVwq#2Y3J;PI%_PQ0q;)M^MP6QKZ#3ncL8^2zxsaXoFwJ3v1
znqe#%7|j^}M^5B7H%Z+s=%__$mxh37ayfjMlIB&TL(R3!qOg4!(`|D7YpwhT@79T}
z78*|!aPhmGIy^}bLDGKbuBZ36hyEnP6^NaH2h<ZVC0M0OWH*-p003G<FKrT6X2y^J
zwlcz6a%mty8zX%F!0cPX+bAoy4`A<j=J9jn$V*GP=maS!mk-1isW0K=GI_a+tq;&7
zV(xuzPZKtwEb_J4(tq}-kKNJcxeixWXFeT=WCT&26}HdJ{qbb7h{H_-X%No+8MXUJ
zz_&#JdO(H0+dDw<<K{-6ME9}qx6GM-8DZ_-_tFy{^YypZRD9wl{|d+&Td<Ou>{j(X
z+{w&<t$_fbSMB^x&dn^5NruRGtfD{xvjaF0=FM5CbzlGimIek|P#haG1<1qo?&Wi&
zhN7b|M1yhrmP?hu8x>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<fD(+zcI%6r^8`SAm-rZ
zQIovnT)Iu5BZa6L^p8DyC6ES?Bo;UqywF%y<f?#@%Hc>_M>93Kut7wW0000O>4IdB
zrWPP<<w`f>>kk{u)C%zrGd$Qwl<mG1n|j;V)dHnayP?jKi{2-s%V`;o3NlYFYj_6#
z06m3AK*Z>GWEU9>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!7NJ1<L+N>f8+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<FYJMV!G
z6|T7lhTj|lBLWJWw3}E>(2=8m4=M)85v0)p7MNVp+^ANA>%cm`&<Z}*v)rp;DS$xu
z<ZGa#R{tNk)gY1BWcb7%FfPhyf}U9db-xj|UVER#=Q?hP`H#<UVHIUyTYO-vuwA9%
z<R4+auzvU@6SjN~aA=Jv5zR)`fBnx|dJ#mT_)DP^nA$5fT#!t9F%f*Q(tvEXy;RVR
z;2sWAO~*hRX$3BYL|Mthu;P#a1JNh`U_k&h<Iw<y$4b)~ChgCKAE{mnJ&am)!F82d
z&MR;}xhi-qFj@o{mLyr>P2v3eTj^FapI($H?^{n!$O{`&15gNIY&cQx3a$te_kzWs
zIByR3u1ymJSkui?)chGok71kwOZ4u@V^u&NbR(HhhW_wpa(j3yp0<kanx4c5=o4<9
zc!w9wRDb{rGJb%4HQ)|y8bATur)ow5WcwQ^rnk>GYGCnGzIF>kvU%8^5``KVhh`JA
z?S~zz<fzYvt16$E8nLYaCdE-Mm}~D4T?B(j!b$4Ry&)u8I~F(}^X6ud=E;|^M+~N|
zdtmI+^BmJD0zSbim=BI>!Ig#7pQ&yL@o-jx-?(=?Bw`e)aDCNBuGO5pVjG|m3_%<h
z)$KNqVz1K|qpYDfNb5eg2k~wjU;!p60Gc{UrAkl$015dwfzyz+vT<T?Q#s9P;RlE$
zq`(Xv0{OKsVfVlfk0f>-79538E653DMJE!7#*_Fwsp?_)V3>{YbdQq0_(BlfKLvZg
z?(4;R&<HQZ*+Ac_Iy<ys(dg)V?s7ggp${v@*MPfu3%R`kKqwVj*Nc2U(S|e;6;-d{
z8yacy+IbgTNnXJzk6ay0OH#;?5A>7())An?E+7bIrlYDWd<K$$mt-XxE1~9R1FV52
zi6T(7F9U?TY`zO)L@VSk&5SdL|0}G=8DtV&l(lb300KTC-<80*q<}0G$~7W6($|=E
z($gJ`d@>K@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<m_%xsZ#{_nF3cFG5N74iQ|tzI;NmzhJ@$yISRI`+jlh<
z;AbK9^hDjAbU1FA7zs{iG`TmSW1RldBH*Sv0ZozS!eFvoGV6iiR10=V@M7A|8I+RN
z1cj%--UGOP5upGac#3N92EIyw000LzyS#@2@@xHHHc*RA)+f~V;S?zl#Ltd>?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<cMh(P)@^u>#g+XmLxi69&kbXTe
zLd9Z+p+GBw!TVbj-(7eXo0QXzqGI#}EC2vd1!0hYA?5Ycd}GCLfZ~7<usQ)C<Zg|Y
z3svcwIJMK`@DHOo(n%*f?v9_P;Q7r$R3JPLgn8#qKx2MT0801*TymDMQ^5pHHpyxX
zxB&eQFVYJ*xi`(Ys@O~`&Qf;(^GY3pf{SljjVlTqN+!W@v-Aip*%6@N;NbAl0000V
zfkfMdT)Z#Ocs_l!4Z@7$0;Lah<Za{pe5f$4&3K06SRq+2rceL}cduj)h!4FZcR40?
zi463KV+N4j07cn-F;tc!2=GWH+lwF3r6+@}LK&)-N7ocZ;l(jCjxi=9&E^S<&<r}k
zz%ou}KAD>O0001eDF6pHI8Xo=@}(lBhYAmWpkbiLnfwP_@=?(ZIB8hZq(VjDr4a-G
z0R(a`7<lo4NF&a|@Gj`gVXJ&?4W~(;70ucPf5|7Ai+|jt+h+#_mikIWB5+=}F=VZ%
zxsH_vfEAD`gAO<V1<3#aBj9sjomOhfr~?4YpJ{2B$p8@XThPYp_$9KG&ql{~0A*^#
zg*KvFdyn8q*?|Ru<IJbmsj=xC%4**H;Jsdz`O!SVgZKLNPcXRULjdlBRbygPQr1h>
zmDCcQ>v$f(fB<L`LrmxbPymn>z5_|e48G(6>}Ht(8|JVu6ri1cK8b6^cV<xhTgbTB
z7_wbc_&C?6pcpaS`3vYN`~(3N{^5{cJ&|{Wqs*E1_kV|*dWVN3J7!rUKovYWyxa8;
z4H8hwivyv-|8dM%ZfcT;^&8K>`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}<L4nDI%yg`yFnL6Zt&uam8_hAkXm7h&cq2w
z1rOJNIlzSW)Op&)^OT{XX3>oZ>&eFkA&+q)NRlNb*MJcWQdWQB+BI7ID>}nA;UcIm
zA3OfFi4o%#dS?EbXI@TfZrDvqnfb!a)`dk!hrLrDp(?CGr4-OZO;^rl<D9agBe=2S
zmWF-2>mL8EYZ#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<j6n(0C1o^@~{AC5OJ@GGq<y!fw<ZG)CzI&
zd^W}n5w}TnziC-+CIA2cgZu>-Fg%GD03xa8g2@CGzUGPlT%}Xs-YU)5uPtFSZ@45$
zdiEjdl1Jcoefly#-H5qxedISAXa(LN8&G<LJL|$VXh~V`h|)A5001-y1BCzv9;Q>w
zdLE~$=I2qCMf;s5GJGZeOq&=(lJc$mOKt<Y8*FIEK!ZSl1dIST(BJZw@U6G=*8xJd
z`jCpObj3m0H)ZpGyy|d*QX$4rNDLwK=n;s_-FrJL&$9nEkRE1!$$cqA=!`Z`R09*2
zLr~Tj@BB7F13cp;{#!O0Z~z(f96AJKn~vve1|g3>!~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|<C1n1mg0s1x-bXDoHL
z=eB$pN5?Tq>Hv5XmDn&P;ek~MPyhr4t8@f15CiFx9&&@e%AFnMdV&jb4(}t&fos>Z
zHJ=a$+k7QwC(^-0g~+6%pR?saKxbAcN!ywMd2&{)oH7o2PfKoMW0PDLI1R&fekRV$
zJqZxYirNBckluPG^<ec;3IXL{aqOD$_0m?500;0x!8Ov18UP5W09_WAmhvIG$()D9
zX>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}<hNF)n~
zEa=xQil|-Iu0{LSW2gphMKKp2s_UgdX#l9E*&8e1mK>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<fiyG@hP4Ql00FnJ*brSgSA6}S(>`?ODcJ}-Rac{t1!dhKKl!!<
zNG|=Jh+WknjQ5wSvpQrS8$5~3Q^PfSeWfh4YS9%(_=@JYnuPp%>EQ8M3K^?zA|!<*
za?0KM4OU{Z<z?dJ*IA*t9}qDB)*f;X#40&zn2Vbg)9ml_c6M!k(Mxv;?gUS?N&9e|
z&l&->00000dY}YN=o>X^WoLtLfWgGBV2`}&<v`yt;{{lHv48*)()++-yn93$H}r$-
zSO#!kYV&?Wmb&XeIQBQRoeD7skwbeAvI%WmSh^caM74A3!<~-f9}ap!%NB!D0Lr1x
zo+zB?!-jxJyyX*k6FJiWT0T={dC{DaP8m&b?gIOR3TS5QJVBE2f)w)E_HAv!Rt%ua
z94;o#rRh^9AYRuBMz5IpCAgP(3jzTj=v9kOumNj82MS_cfL^NYf=1zQSC=+@Sszi^
zjzahl3Q5Vsa6OS7o*HG?9?RNbdp7U2fQI~BNyKx#@8&oE=2tBf-;M=cea_Qxx8Umo
zspP~-W~M?yPBqM@Rln&nwxw~Hj*WE$EhVh_!=IWPW)clZigrYBeji}=j!i$9*tR$a
zvd+{-n12P~!IfKN?#q+6WJd#4eG6>nxFe=x5;)}D8e|;{f#~BcHF87PEC<KarDc_K
z_Roga2)pWkbVF0>AOs#7wZwxKlm-<50`VcB9kvL*pT=z#)%oggLJeLWL3*ar1lL9l
za1fEkO#0mCqR#@WYt!WnSd;)79c~VON&emPDLp>s-%wmbn4I87*__Xrxx}8_FR}2z
zJcAm?$_{Uh58b{pF#NqhQhLTk*SN<poyU{^p^eT=`rsYciQ9V@bqOynt}!(0se${w
zHqg6s&$m>8Eqj2;qw}Wc^|C2?)y8~It*wg7XQHb;aJ6d0z6u7s%IWu|HaVQB50t3x
zM@f5c_B5hEf%zPp#nTqE&iP)}wlkipxQtou@s{u53umxkPQYWZ04hf|f(AlXPmv<#
zr!npzf<A{qKnQPJa`}>6D3Y=w(9>^lq9WGv%*zFA>0x!sIZq{IofW3;bpGi%XBz4}
z#<-nh>Os#UC^3WqzV<Q6{so-FvMg<f{+<1oV;LytfuOHeR`T>ARi~@)@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<V7@uQ0M61}JMnU0_
zl#(5DXO9KbKNtT&V3$pYB=_29KO#C`=Gg1Xhl)X66a95V7xRtO%FUObs9#}j1RHp%
zlW0L_IFdk*7##X+ab`MZExJu78pM{zu9#L(<@y_YhzTr~)DQp-)Bta#lP~~T(kpLE
zJb1ttBAc!QZ!G()nFiLxoX2qBVVO=<z}nnuGP<S|=%BQRv7Zc}jC|I||0hLqls777
zB5q73KVC4w0DUC)03J7|^F6iQD>#<dZCXr^lny7Qz^p>f+kBtckL(Ml^hJ;ChA;s<
z0)^(@NeU&B50B}uhpO75vIexI2c6DBtWfYmto<T-A3@lCx|dfW6@l2nZh@?g>#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
zFDQ0<CWWbX2YCx!5$876Ka$ow{3U__2MGK2!_yJB#G2p(5bLsEzAWn{pUQSIj~G8n
z!^kzt)?h`qp8N3(e#%qPq&gZ#=q2Vd!1kGez|q>Cu(7I&2Hi~unjTw6{@d@==Z9D7
zi%^mYL7<Z4htfP%CyW8I9j<V&;N52_)`$_SIu!Lpwn03&S&UqvfN#i%5JNJ600)w^
zScxJ?k|b6}tSx9Fdl4{DktU{BVL|>(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*h<dDVz+a#-LaiAVr?L^X~sf6!Sgu1+-q71vTIQ<q1f*A1ru}t964kdQ~&@)
zsR&&hxFqow#@7GC#OSfSd+g;44J7&1z?1*LZ+<8JJpDqvRm=c!35j=|g}u5Yf&>nG
zgzcNewqF9(v-iilKY}Cj1=pbeT^ftgT9E58LwXe^RS-)!c9>n`zMC00c`g#I1sXBQ
zO|%d;)Ur-Yvm+w&8q$0*jj1HQ`3sjoesHz-Vbvi{bc&h($~;<J&;d=7Z?IKxDw?#L
zc`c+>3_>h+eyz=kZrI|A;0oIY?}L@6`4CS!05kSio45c0Q9vj(Crv8o0H{6q1C_XK
z+>~vvc4we699C6t<aFuXc(+L71ZUVR7&gwBOZ)8z5<r-YTkXUOOuf(?n(i^wDo_L*
zJ}bb(n#v_(@b7O+{UZiG*DXnrgft~-h{y2ZAzgaDWnwo2wUXV8)n>Zlzmkt4UUk?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<<TNKklRc4X%J=Guj!9eM|09XF^B<k;Gt2
zc#z=~PS?zkHmma=o|psxL^E;L4#66p#fm_8e+BqNkszA5vH%YzvtB>Ocylo6zU`Jn
z#bGYdc>-&8fx8f4>>8X(5CExmxU`+NF;+I-X6MAJ^$4A76EMafg=@Z4(X;%9O-|j+
zdXlj?B9$DB{RWrNMIG-UbwrOu)1|18#bS3s9<>88Q<O{6$v&+1_D8<bCnmnIhW+52
z!gWph*Jq~qHd-Se6FWiZEA{{ZL?BoXjbqoB^?EsN+&P~5pH7PnpD`%Cb~1cs^UhBg
z_tLagGRRIDIw4%U87&UA(6tWUuRzaY5Uf9EpjqVrptmA8wZ3F}ge_o19PMTVyCOaY
ztlHU9042GU0C9^9kRDRsPr~IUrF5{uL6rbg;0?WefDy}OMTS2xrz`m5i@RrseC*w@
zQL^{X0xJEeYB&@ipKFfE>QHv985ZFkXR|q}u#m6t%z;MwH?{^<uG|ijdY31UH$dt_
z>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`FNmb52<r(#BBP7lJy_hfE87E
znsNDqAC7cX&t5UB^!EvtD`-2CcJ9GB(r^b$Wo;l_ySi8da(1rQiUO36LxJf6jI#Ov
z2ZMjk7t`w;2kgeDQzX~7ngQx-zX$Gjgpe@2xjFQEi>S_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`{<c%tj
zCH)FDUt|P-4&O!1lEyF|A0t85QX8dHdeLK8NwpkI2Y=6i4|n;##-{>ub&hR)p@+;+
zy^&#1PlL2$1jxA%r6#s4aT!)*-QN6bn{Tswl#O^ppxCDSQLWBYa(#f*On+G|IXYO?
z>4{|Qc<V25&LK*2;6ot2Thf%%{xUG@jiv=K<|xibCE-)QV4k$QpCzBgFUVyT5XQ`t
zUtB+60Wk9gKy?ZHUptHm0000Q;94q%1O?s{$aEw@D=DxecR+lD4+0KsU<io*KMQgP
zcVV7r?CQCwX>$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^=<vWSJG<y5DQ}_fbWm)P+vi|H%p`l
zUaCvK$;4ko(KuQu0qw%qXWyAcT_mb@0dQxLd@2*M_6rW1Qa*C-MFeV}ayL-HgLQ-|
z<j}A3tnCT25w#@%030;%Ok0cq1T3wG?gb9J?&9ls5xL4}e{wlTv2n3CQeWgd!`Sf%
z9EQ%DE_U{j5q}vMKy0P*h*EC(y*8MHe=G?5%w%8_?O$s0-iKKrrRT(EB^u&!39KeQ
zVzd*IfAoJ=uvl15%XxSmd$Je;O@rVJJ<a=SDY1Uma%=PzdUyTGl<*wctMu44gZ8$p
zh4+`A!5nA+0~&v2mDJ9>AZ_x3%mGA~IH{Z$G5dG@)-NuIF<<T7Q@*TBY3^i_p+?Rx
ziQK{siWJ<359yov{W-BCO#vw?uK1@kDcqgSnb6eJ1~^vmNhT^!p$B457t>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~N<J%vKK8&zguiRZ{h#&C5b%j;VGjb15Wsb6Bz=kL+VwE_N-jB3GqiIS4Q
zBC!R&diPQ8K`n2|)(|`dlJ*=*5Aeu@;o<vp(5?FZOo0bSAY9?i)9qvKZSvv&=ha9e
zRGiH_GU(_xeNWn|Ge%Bnv>7K9<qc`1fw;<b;+H%QammkNt8i}*qdZ};G=a^BeW0jU
zItE3XVuA9oT+(({DwuWL_iz8Ts?4FImG`=B+SzNvVo=g5_7ZV#Q#&U;cyRgQo)5bT
z4QwYux+cOJ*iJ+<;^|0pEr*mpjh-j()~T;UeC=VfN0KjoPCeGCsU4~-Y~^&kVuUp1
zVhSdEjU__Q9Ek<nkKMXUEc|Pp035n1gf;EF_TAv|pm^c9V7RZ}OwlAEoQ)y2A7V1L
zEnsbJ!cfF(lOL-X#1S@&8>9^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`iniTB<y94^7#0=(58%GZ@EjgdpQFtBF
zeyVt0Rs8gmM(fhhd6x~_`+2ESUNp{W&~7w#SUIf8Awp}mKtpOXG;kxSt>aNccnnT_
z7#?wO@N2VrNx$lpQx$69+025_1&El<3;PJx8S_6?EU3>G+CQ!bzjqxq9?E99jJ>+f
z;AGK2UI}wcmeO7<^zTCNmvCjfjtpia%MX0m<V_zI`M)3mp<zPUuetp2a^_&VJmw)h
z<~)739xb@}r)+sY1Zr;y8yUff?}~*=N0bY}FlK+FN%LhdmBUbQwW^>LW^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<BKs!B$bk^VP1NZ%2;e
z4sQ35|NfxKvVU&7*aaCoWi~qu20k6F@?%;^34Hy=`HJqFb!|Vq&@P?;$m{|57#FSD
z-3A&pi&ed57na%yuE?CCQ60nXYBpttJpX5kOah(~K1R)<70bd=wVmqof9{nQie$%K
zO1*ZFgBfsz!xSG0>_mV7@#dmZ6Vw8c<S>}$e-6*E&-J3pDa4ra48i{<A<62hg-U(7
z6i_S~W`C}xvWyoZ(&Y2w5Q;3Vc^5p9LJ2C#fYD=m^ebqQyRYDM<`%2>t>r-vDD$f)
z`wk^OQrN|ncFvbDg=<qAJqF;@(ypGk1!eg_|Mm;>L$R7;*}_;&NTa{^b76-ZblTez
zw~q`zu-1ixO`2YN<ah?=vASGZP&0Ra&OCyUgnUU4ek=-sM<&NRK*A@B#gNv9UIt?i
z=X0JF2(^eF1)tJ;oZX6Qx-x*|AD>DLqQ33{-!FDShx;2(&bIO%;fc)r_mYQ9l$%F~
zWlGOc({)J$RsgYDj8wFE8aMB40uk8@`GLUnS9(<*4ngjvS~N|wtGhX8R|Bj|!e9Z4
zP_bFiQB^d|3GTrHYt{<CKWWi=tP3m6#ZUlDM>fKM04+A5JjP=uGKddc^&7wl_yxm&
z3`(W-!;Y4UJy>6^rIs5%#EyGvy}c&<vet^}56o4UsKHf9DMPi6-W2HiL%bA<Gm$}7
z8pR(Jg#j19ec5l}HN{9I9CHCgf6pxvj*t>aQ-PM!kQyO;!4Pp(lfpi;Nx@S7s+~n|
z!Z9|>Weq$E(}TJUN00=mawQWf%x@<`JpUel)dIz<oMj3j556nlj*C(lYr7&J|Bfx}
z-^fPk)$MQg%}tnVuB*D?>EE%5eO-RrM;tDQz%nyL<*=3a#ll(qsM)!!4ipAK6;Y&`
z&Xc>z)a64og^M6RJprWq<%wVTf*DVXz{L<aGIQO7Rgl{Q6IvfV59af$-a<u!;57;E
zLc@TbPK&U~-7G0xGfD_tNVTJjx8dtjU12fo6&MPgklSFy9dyDi+v3NVF(F2_1ymd`
zBC!FfAdae0imWQfo?R}1^~n)5kLg`nf3eHR^1GOmi$DY?dgB83k1IBkNTgheUeUl2
zpm_k0FR%u4HfVQ6NR*;a4l`Q^QM84Bnbd6|GEzM7BsV!hNucAk+oSnJX%eVqj$8IM
zYHN8-DD<efgPYU+p*uN1I?Y+{4V9)IOtn*fJ#d0Xl`h$%zz+bUh~oxia)Ma#gMJ0t
zQO=)`d&pP7nm*^2jNe*l^*-FxzFp0(-DdeToK;BK7i!KHsw5teXGRlq-~B&ARKZL}
ziI3-Nypm9v=aclTaKj`%q{(Z=j&XSPudo0p4gSFCO|S+CoGkaBu_It>y0=jNZ~)-8
zDPpHWTr-^&$=rhy;*xL!59phe3QUAG)!euB5DKU_SrKr2Bz%}LNL+6f;%cPqPjI#Y
zdB*i}yj|8(21q~v5)MWcN>H<u1iyZDvBN8X0$Q2etK_T=ut-?t!V9lD8A=#p8YKw5
z<Q{+!P3|T0%X&k)G>xOuQ~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#+<skwTz1*bz^1
zf3n|NLN7v*(4-O1P59IOh6O4!10V&hCl&_H<38m|)(N};KzsXL3*YuRuimp|6d$FG
z_Ap8dk1NZ77<_Nk&=3mqCAGfkzcWpVEh;W%4%WAx>u}U&??vuXMG|kB#qbnHUMilP
z8Fio9Q^YkJq9#-(UX|ZA;mP{$5m?37mk+#k(388LXbH?zH7l87oUhDZLWUgrm5+d?
zwCR`ffvOZg=&@``wMTtRd<w!$rpZPV0{$Gf%kNt(2ZWaP_G-i*g^?EXsWOFT7imZQ
z`HNLIO7aC+!K6!vy`X>qbV<BbPzuyh{9pp=&gwTR+EUN+WVu6)m$Wv~A*<+nQ}cII
ztc0Yyxo(KtD8E2iTxD!uqpZw|OK&mTJekHRz{b~R3H)7ikK<Plm|=gOE`UL4;hlqz
zFe#H8$+`n;fMdYTav3u6er!olGvNR+CbXw3``Vj;0n`E}<0#hjzO(6Fv%$7)e36s4
z$V2aB@;tbd|5y7fJ3AWlTj*IYVpr1hkB8_5rz?_TbN8F4=9gG>?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;_#$P<!<Pm2Cg`(T#dGc5Ui(Jcc$`+XrY0FeUMtwCCW`g<Mi~T)|iO
z6NPxB3J5@6KQZ9bMnw!<BpHXfR5Zj^U35$5$5LN^s?@r1mT4T&AJ;yoRcD@;a>ENA
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|<y*fj;?&UK->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{;KN12u<zpE)(ZD@F7JInk^<AOC5XFg4!3<F
zx5CU}1rscB>FKP3;GR&x_&CCrcb4_<Mzi*mY^d=xwFm&=tI-|y^UQr1@)ls8%2>5O
zRA5_5VsYy^<`2KIsa9<^)@n@50-X};=swJyNq0@8Bjfq45V<JDcn+ue1bD8h>m*2U
zEZb9P<Jg}&qL{zPt7jB+)0qa>jeT$?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@1y<be=pMFhLd;SSHOoEK%<+-PVz9{?bq>YL+yQH%%r_K
z+EUgTF?5&uShJ>PA^><a`cG!S(zPqH#8xCnk=^f*<;4_p9!=uRavC~L2he%c)xxe>
z6o>9l8=i%~M#k^qX-uqWM^`oEbQYy&)jwcNf1jF0o7ilWpc8;rfm4DR^TN3tq2L3P
zQ8qhb>50Eak3<JGJ_dT1>*mK&;P57I0Zcc|mld!2RVtEWteE5y*cZ%YNi<n?$WwBB
zM2V9P8~KT26Fcx=*TqJ@i4nJ`>9r^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<LLzsg+S2%c!8)9Z!t?pAw3e?N6YTzQxCZ2h6nn)?Qk?`i^w-4<*@%MWh(pq
z6tBbdI=@$DT!c&32z$y7rOiQqM84tsNV5zIQ*sIa%x9fJQa`kDo1(9TlvM{t`^<em
z%yfNRaFx?Pn+zvFHU)<^+md-L)RYPj)<+g|n2;_UHWjrFTy4JG=y?|IY!E#Ir2pI0
z#0((?Wg2p0US3VX%Dz{w2Uw7Jyb9XvK8RAF8+Ai(XjrnOtP$f9sxyiJ+GSPd#0rhw
z#<QU!nZXn_gs|`r)Lw+IK)8X4JCybc#7v3(A62cw`l{SzL*kzV?D{2eNN1-G0QZQE
z1mY<Ltp4FhTt{p_7sb%(QhKprpuGKlvuIJG{kIwr#Q{9)4{fsVYztOtj=-{&^>-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<J%TQno>#cqVtlM1=y&m5D`vGiOpk>dYODkj~Q65yJ9$6m{7zLkjjvxZPhbGBGa@
z<+C7Yt}{}Tz(*s1G9S<l3*S0>4-{x!x4!N#A8lCp1~WN^t7Cvf=fqmvyS9vHPQb`2
zfp?MCT6<dxr)tZq$|-1~X8Ew<6H*tSCGUy*d6V%?U^jSa-5^Eu%0w9S!g(7f`jB5;
z=4O14nM#I~Q=N(NKo-9Qkf)6AZ~$t}gVFZIlNpy=mLafj!-G?tah~q$YdMew@;!#c
z?33E^6_+HIO|DSnD~q0T^@(S$m(YrD^gCd;A*9KCqQ9<MPD!uJHhyV1O}7>6sDWOF
z@$PsH3Y63skdCSGhcwV1Lj|?#`+p$61?2%stFCkkA)tNHuhm7COlW%<wAuz^Nwy;7
zGZIgC&~WPFtvU`CFy`nXCzk>+Z=bCy?q`|ze%l$yrJbZ<nQc_$DvHB8zlE+V{7yJU
z8?>NC(zNRcsK0j>8Jl@~6Mcsss1m?^f17dE<hMb+D63h|y~GwCk)|Bhw@C%ez=;n$
z%nSZeXAM&RS+*Of%@vhjLOX{u2&nW=7KMTsQ80YnwodxRw0x7_BzOWex?t?}drBJh
zT}uDMspuMr0YNF`Gu5Isp0!xZl+;5XrK8ZdEN3}49DzuEY9<uF#ZxctFbQh%E;rk;
ze0Jh%ic)q&SX+dvVSoWHoQKhF-j9GyZZYGqiTsxLcpI6`sCQD5>lqHtalfJ8M}lVx
z%rtl5egaIgRO~d8!nYL)JQ)`y;5y{r`ss-4iS#IL8Uzg;e1VN*%<vG&yI~X#9DFsS
zVhz{@-c{%@4}o1Six3Pd4=hoBx}{cn0dxyGaU{^i7ti{RWyqUoBVi5~>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*KUbzRppp<Iy$a4&Ca=7S2o9;**(XAk|4~gC1<@dX>L8%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|%A<r~Z6v&47@qQ^6E5L6`d$^X=FeE;Xy)T2y1*}T2<;fd16O$^
zoFU+-*IGyW`lHHyin1QQf4!h)%r4Ys$E@SU%>q1Me)R3}ubmTMI~M8P-atwu<%KF^
zRDXSSooA?@7^l@VJV5=9blZ8X=_3+f^$478$SfMW>)IgbyKy$P+dcCqzk|afp{AeR
zpSj)h7F3tKZgEQbFaQ7uSS3}}ZHs(|<cr07x@}$%Z0;_!LdOd01}HuInI13aGjw|n
zxn_r;cX&CvdQ0{=Dx3%D;D;+0N_(vTe7P!0TCEFnC%>P0t6&f?<^VCS$7P9k5GXm@
zPFJ=&)Ijq<{|z+hCta>AiAoWe<QmQ1U=FW2OJ<cE84WcMWfbx-Po9ktXF`#Zzy&Ix
zM1-Od(Ye%^1G%jAnffh$V^u;@8qu9+Z>8U17rr<~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*4h3<Z@SKXP8b){eGG%
zZUG#EgOD*Gd7eEy%%-wv8!VzFYy2H)!2kz*oKA^lrHVc%I68gRgB8Oxy?_9>0aFQz
zoTbuQS&e%F`pyfbC<XmJ8WsUL`9s=vnv?n<!k`B^yYf0Xycq09fB@^G6)0SUe~l3r
z3y-TkN#UovdhX#BFecG+lyLUs;gGiY?X)|5e0kitd|pU&5C8y1R{^jDs-v79Si_k#
z#rY0%@FwQjrvf3r&){E}X=eD!<~3WP)`fK%X#>p3`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%p<RgR3^3hhEnxM(Ia=qp~k)x;#viA;EOqRr;al;b;21XUoIega^
z?|1_>93thRB=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%@N1<hR!jt2O6+)@OYhIT{UC7(rNPue1K@Y(zG+tWZiHwzs2a_A
zGIQrH>l^jq-RWp<p!Vgxh5uc&%lsBoV@c3DbRKL705eQna+JJuBKE+1!_=70&G%_T
z%V>1GRMLT4w69@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#+<zjLc@6_rd>s@Vi`Cn<hfEN3FqB|8DqjRL>su5;~
zmpy>HstfHNk&{Jq!-q@lDOKHI)PuCziNLUvAsQ4<<ABH!xHS!CfwKNh>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<ab8TF($`=_QTP>*Udke0u9Be1PlOhrR$0sYKgKp3^os!?ZRcU>>q{YDK2Bh;K5k)
zxz~idCY@oB;FFi!Bv<n}iI&%c;j9eTjLLUUdf)&tK+eAa3n7krN}R&M<m4&)t`-Zq
zVU)335=~0Nk$FIzGbJ1Yb{+cz1$w&OBEp#7{fdGIhWBCVMN$%PE^v?1n_Ck*${JC{
z*;@Wkjl>x{Ahusm<FOF$O=_v#A}zXYCx7^VKXNzZZB=~*f6kb9BC~Y6FY`9Ln_AT0
z>u>Fyvf<*39;cfOg)wEIsmDiD5l`1iFG#ci_XIu4og56iQ%L*66n6io3x$B|{U^C_
zYtTz(i4FW1eC$NoX4BM`4JSjYBMhG|$L<huTyG@M)KaAjP)JT>Y34^D>g-@d%-u2G
zCG%k9%PTN<h*9oIX_PZgnZ9FIrPWd19*WGfw~RyBKrJgVKK_?vIx-;bcF6mxh9Aw7
zOKv-jz8qh)9*eOuVZ+d#3YUe&QyhG@@A6tJfl{!RfsA<LTsO%>mw{=sAcIRwCfw1d
zS4Qt_{4unD+s-oSJ?P;}95GR&*dlQ88Gh?Lij)ImK?<Y3657~U;n@jDi)Zk2uK%yi
zDl`^zj6{&)Jzh`pl307zi!5MI$=~hY?W@dT)4{va>t^9;N-s{*Ee7AOIJ><)Htkvl
z{?h@E*zG77W%&(G$bmTgAxZ*$fZ?}k9uOaTX`8EL{Dd;wIwY$Kox-(`aW2rT^JH<i
zL8*gQw}3mx-x4W3fRNlp;I7Ctee7790nhg27vbYn_YXqI?0nFN-JQI6I~>R4U4-+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={pm<wd^U$Wy;J$m6^zg>ett)MU`%;}Ei=SpGhz$nOQ
z_8uuaX{-PM6k~~W%h|JrJvf)&FHt~UTXmYZW?vV%h2h0@)K2VD_Ne9Hv+~y#^@Mrb
zH)kD`%Y~%2XyOhqox<ZCjOdaTGtazPHER`h*`V2ew;`4jJf}$y2g{%7>v9PyhCnmL
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<L$SctaBv~tB5l9hil}<6Nhva3
zkK@no;6KBpZqKt(=A`C$psd-dKFeH|yGqX4=XmRW60uq&7-3k-beS?RCeFB17$yGF
zL;N(hjUkt#**4C0`Bez1g$(IC0>X#=mW#5pi~7ddHLC<-<2_MfB2lKd%>I_NsV<?I
zd5I_;#d|Mw;0h%ppTc3pT^;VyS++aPCgZVuhLNl60jA@iR%Qi1h-Pg>>EpL14=+9E
zl-!ME{A&`ttJ?A0ay`w#su?%;9^D5tasAr~D<w|-tQ=n}WGJ-oq<NFi9Wok?ZCJFN
zZY$3Lr<lnvA~Cp3kcOQsLuB8Lt!XG1FPl8C(G#DcGTXq()1Az>JqKPL<i#GA2bI2>
zefza>-S7chTlO5=S8&2qzmw$@<bsVNpjI>?)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{NQW<A7VuuiI!+m=
zSlQOmoa(}Z)93yt&9}#iCG(^Uj|OARv%^l7{ADkwyFL_?MXct!IbfFBuFxlT_a2|v
zzG|Bb@k-6Gxkl#u`3)bYwE@<E8L2X>vX<_ts)5F{>e}Cf^>vHPz(TPLhY^^d$+?Le
z<<cRQ@ve0J<cKJd6fB&NVI1QZ%v=o`QT#)jA)yXd<%hzjefn0QJ=?u8_J()2&KL+P
zKTM@neMC9o5az_h4le1?K6vm(=uxps=NHpIJ@|h^kfa(KE(ZbFeep%<tVIYlf(C_j
z`8QUi2cf+z0ebu)3?t^zp`4M~K0m{N2?X=>5l6!|{h{9epAG<+K79UOXq8YQfGuIq
zRAki_QmtORkt!XGy66*>0HIBw`OfmktGyOB>%LGQr*147D&iM>WOwN?gJp;Z><b%?
z0=soj^AG2bT1wM}kZ>^+t<E}-+0R36^iZ_}XBFj<H;BQg{C^=!R_x06kYYaRH5kJJ
zDSZ}x8Fs3V7wW<qgJn7@#D=W4?Q<_ZGcOR><52fbePAHtguDDmC!CYC5DH4-JD&Ib
z5bje*Mb-VTqO5O~o7RZAAUk0sGIseO@_ak~#xpE+vdt8r#A$G9uNB!<m<t<AFY>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<B8*5|;{DpEekXI!)#L&+WY#vGgz)eA_38Kk4lHHBSDy#mbBQS+3kP0n7x~0E
z>;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=;Kx0<tLQj?%RmUXh6)nHT0)X~5qJwzN0^$#b*2gaISoWJPye!IxpJK534
zCToD;6v5ZsfM^7Uuvv+#&>h9xOqTnt)2cpUlOJ<)Y!s=<<?_+03>Q@d#W6yQ7Xp-8
z7vmrZ=@iM28kiw%+*d?hzRTUZRH?{6MQbTZ1d~U-NsCZ3PVrGKO`&xYH1Im4Q`za#
z$Y;LuLJp)PCN%J(dK;F;(5J`Thet+r<lBOM56zP{0;9K}(cT_BUi9p!1CcoB*}tlc
z<659s!4$wA9G*+TK8L99?wIHJ+FMN1Q{UUpo`sa$5{Bf9T|bBOKYOvMjJf#+p6tBd
zhAVFsX6QZ%WU7VEIut5&LStYJh4zCUz$=5^@NsjE#bo(aWfZI?4NP|Zxjt?&$?*S1
z8=Y8?9YQW>Qsf_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<A81
zsB}P!B^u#wLYL5SO7dqry;Qe8i8G^HcQB3by{AcHMb(&i3bRGbGfcVhR}hJKz%A6a
zL;np6o>|!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^ztQ<F$XM&=X`_etpOKZp5n3Rk@Nw3h6fvX<rSx>mMr_(xHIoR
zg1ygL@WDl$`Sb%$jHaW(vR_l82O<t4o_RNN9s5*pAYSV&Ep&i;onC{kd>AH>3OZMO
z?3o-7bd(OA@xE&GoMfsS`?Zj&Q0`=>tW$Q1Td)>%ApjOERZL>aS*vz<oq_;Z5#oEZ
zEnnq%UoZl8+!!?p;%OXw4zhvpddNs&O&hm^DeE%xm{9LD^4<J{ytxao!-CP&F>C}J
zvpxB7WX54lRSpng+T^$-BMT3N2g!8tU3H#9f=nHMw0OE3Z$$KDplhS*+hYSt&U+<h
zw>rj%Q`K;4OKl~)VyRkAifYzK_$Wkf|2IQ!Mm<T}ah?ruincCfuB|awtEtd3LVZIn
zAFov*pbsS0>v0@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`
zkHR<v!$X0wV2Uccou`^Z$ppd?#hoaqYo2q#?3Hy7x!nK>FP4_EO}$y>8_v7AgFiH1
z<i%d-os|3&f+dO4%ZEGC4B3|@efGxbI8!-ia(wxIZqh*{aIt4CRBhb>%f4KBlEGR=
z*;0<+uXa)0j#A%0s46UPnly0%gU4O!d(z<Y@Ib$L79MEK&nnsBE>9KB>LTKrR(SfP
z)nP`1ux*f#qLQ4Q{9)B@>|23L<Phn!N+u}YQYVd7EZ2Y6!jT6Z^+<uJ1CY&xy#|IN
z(A7NkbD+;9prW<+DnEDIssd@2q~|vw8=ld<vzg|6Xp}gAm#azbBJO^NTvR?XVXseR
zSwsHT=KMZ&#aODG<zQv3-a#6JWwI-e?EAtz-b^ELgtxsMC7K9ZL?;ggNYB`#IDM!d
z2<T{z_eX#cM+2s2*wM`2#d&xVuD(avs1S0xPga8f<t6zDb@Vz0l-(!}%2c9DWYEe<
z@9@ITw#c5|UW5|K>@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#W<KFr*1D6c}1&jn}z3ra{sWNp_izCi;5!IZlW9@nR~|?RmBUB
z-;xcxI?%HYuI8%Fs2Op;()Oe{w}hD*!;IJ^We|9{Y}NvSVrM3=haikB&DqFRBT7^|
zj9wBfLa?5S;>1os;PX)o)z^v)0ExO<ILmdM{y?D=7w7TsC2vTSNX=MH{3g5ft(BFI
z+9aoTu9FuAj4qt&wGD3}4`*{0#hR-zfMJrg+w-FXTjM9dx}a=rAQc3uea;Gx+!3-p
zvRuHjVEgc4c<)0(amLX1H9xI=<g`Aj-#ewKK%*%b^PTB|=>Y!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<OiH
zS@Y`3JR(S}VH+!P(?M+yeL8?Z%36b5YwLBV8G`fZu>?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=<fp
zG^eRL7AKg+y|M~8ok}%vO+$J)+$8DjAK9jC=Hq^2{WES3jaq^z;<JDHx#KRoozW$Y
z(rVQ037kw&?8^v-o2!+}*>;@Ru7E{wCANDH3B;CD0U*4OSY&jUm)%K4+P}DHc8y2b
zR;Cl6H*^s9hV27u=C*mYxrH3{7l?XFY!9CXx<3X0OrSOl9kR1u<cnNlS?tOf8b}nG
zmvT^Wu0>D~V<Jt&d(-GrK}=$PD|Y9Q0K{loV%AFv8`z7CLtfcr3m6z?ep@J%cCV-C
zG>=@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$<Xi`v-4Em<I|9Xbfn%AmnqOv?H$FeK?m-UWtmOmc6h3}U)$EuKGK!KdJwUKEB
zJ?0ZV=j`RwIdwde`nDV*co~DYLLKq6QEqLGY>7&#REGx#8JM5f4NU7-TO*m6Eky1K
zk4ErTpeQu=UUIi-ad+<)CJNI$Iu+JverlR+Vt*}v2SWI33hs^-MtKaY+i@d-Y`fBp
z;9a$jYwS6z<!)x3YmZ{%a6xb@sa{chnUx#S!M-HA%9Eu$a@N9p&!RVcTQ1~FhTE*^
zF)aU^F9%<h>Sa@Oox@fMoY9|iaQgZq2A611xQaCBrjzV^z|$wx{I`FPFKTkxwetw^
zJzE?LY$4IwteKt=npA#0PT9<8ZOQTs&*KsedOU)v)t{q7a>}K{(-Dhd@>0Q)nZ55o
z%LZicdRg?<Veqx{H8G>_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$<p^ZrErQ;1^|Y%ruDNw%{jQVJ2%5QHV&xJUT=jqpcAt1JZhlljgCJsgR`$s+
z3$bL>WDr>399Z>)w$}+tD^WB4ffH?#t&>Fugvol`UPmE@XHpN<pgJ^0fJwm7aJNsI
zhUDXRoNL^7wYdv<$n#_Y?v2#V^X5%t(AAPFwEKtz5ZV72#W9k>8(Amk?ec=AVQuSz
z-tEkLFks=mPY3%HYsX!)-T%}x+2(#hV4f(KsJD+q2&GUX2a30=;Lhvj_ggJGQ3c<v
z-)_nHc1yIkPq_i5#4QfhN@;k-uIG0G%ylf;saccO;uK`h8o80Wv@?%{C(qdT)mJV(
zhI)iWR?6*zm?I|J{CLH8A?K;w1#cD9QTqim!uIv%foTy4F%-C&bu%acn}G&+s2b({
zFrMj|^0ZxB317h5A8P(<zUGp{>znZhNxSW2nY<-3gNmpA4*A0b-@f;b_|<B!;FrIk
z?1W6L9&$d4*kjmxA}Z7H*D^+J@1D0prE5FcDkz;Kgo@Zbj<?p3uF&5QRt7m+E}J=+
zD5312X&lL}*2G)3Y1_TdA|b1q>`%2WMl4`(;h^|Wa-QXW|NnLYIpo1B6FnhWaT_wN
z!u7#hvQr}RF-5p_c;kOh7L(AgnDWChU24YR4{{WXS(VTbHFIsh&P<?9{3~;9swK*s
zvA}mgmLs`$*|KoL*pgtC`k1IS`$(lkRBi6r!GTTi@hpv^e+;V~md4a0fzIbUm1!5k
zKz0Q}6^)O}s$|buA1IFLN;+wF-q^zE&r8@9ql{fP8EN7;Idc6QYyCB*5VbD>s@tep
z1u@sj;PIOJoLxjXN0(=VMdl!pWwTP-XP$f<OtuIa?)eoR*-$NaMVh|o(VVD5SmGqt
zVjF3-(55xZ;eltJrC<H>!RM6Zt{OQ^oau4<abPyWZ1%byAP|F3Y?cZfFmth!kkGF7
z5jP4^+Q!wIV?AWKgejAWoZ>Pe#-f0lJ=E{q<dP58EcrvB5!UE0am}D701%OpgF@r)
zN*wu!z;;|(ukrA#tKB9*LeCxb)U%6fNp>TJM;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`TnEifCP<eyT^Kwf08!Xc*W|qG9XT
zT)mT<Vc8fY-wK~fu>9y$${aunDF69-{11)}e}!zouybj_1K2X8`l+Xg%;??e&(8bE
z_F)4mn#Pl|wc9+5oQ-6w3u@vu1jse!sQbQk5Fg#GKx|_~TR<d}b+f6SQ)3G0D;<5$
zD<ih36G<$);7<be3s2cdaVQd0bjQhcnY)~MOZj^;u__1R9gg~sS=l`BYAFQhw>yU@
zJEI`)daaZan57BQ@)^z|T|~|u>pyCz>Z@1BI&{$VQWT}XaT)saIk-$`(^E6`GJVKd
z&TCkkDu??tZ4Yp2JjAaX5qAN%X7^UYAJOYu;~egxUF}v<yBI}vIW)lxINZypXg=Du
zg+jtkLTwrs@Q`(fKl05wrJ#fWx#H%rQPa4uM0-{@#iBJQCUZHImjVV;O_ZeoistEH
zB7}L{7}k~(<(A{H_Y~;{5(5SZJc&oPY%0^tlZ|p16R;pexK0wEEUPvn$lq+RABl(t
zdRA8;=d|O4v(2RqG(s$L*n3sMXP1Vsp<_k(dAo!Zgfy2R0jqa+i_>`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`Pvgv<fMNnsIrIT#;
z+}M%0)&)P`*ToyKj${i{j4ua}w$DcORv;!<v_1Y3Mr!2_^7jg8!m3?KY1Rc|GWqdg
zflZxzde-Om=tLMs9EdHu%??^FS<vK@f-+dErHJ>jC0>B-n^fi#%f0_K+)L@T4sO5O
zQ`yC|$F`Gc2*WR9K=CSkQIOt<KO8rwH!{{lgv|!WsTVrE<TGBMp6AV^Ksq|)+Fp@V
zKsjRZpMA{W5F#=uUVN*7%-I>K7Q6*{*!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?jhw<u98*eRq@Wi{sNu)h<QupcquNJ=`<xs`H5gSK77!Lgap%<Y7
zq1gf%bal%H_Bmb{i9+Q8%goNA*PFbW)~J6MxAcB`XokeVi5DAVTHW1@^h55)I)EBh
z@=%S$g3T1uN48%%z!e2)OmlirO8=CA#xc9@V{Kz`Iczksl|7#)(%9;cAvJCJ6-&Z*
zAwu3ZQ4sLiq{D`iN*-3Ja;U-?&+$L{(*={HQzp);BgVsDYKf}jP1=9(C$5=p{trp~
zZoVYE!Uda0Oi#G!JOJE@G(jM}<!3F^k6#s{$hw(7AhT47(0mXXDAiS?nkEPum6B34
zqz|B-rb=@*{7yX%hGqBj>J21kH*X`jYzi+ps_ueW>>RO>HmSO6KRkI#(w=?2^=r2O
z<Y$(tUZq7Q9nmx;kIl7%gec-atRSMVg(QYd?REA3Cmx6~Ysn}g%RAtajRcLV({8~q
zTtV|v?djLuS4i1@OM<KbnXMriS>fw0n+Y*BK_nn5N!j#U<C52}P(*kaXxh}A5kN56
zneQ5N-*xTV2(nY)!~ght<yFc;K%pNxn(7PPkL9p(0bto<Z@qYpTe@VJo)-uP`0%Xe
zTB+49NDe83H1hJebMu`}{Y?qUTc%!=0Fxez82ho=NckiU1Bpke&F@i68GWmXU}IuY
zXrRZRghC0*=mpU&wqefR7k@w%#xTEP7?TZ>P&?BVkH)`bEGYXb{p}Qv1kkZ?Xa$%d
zJm`fPbS2@Qo6CRn6s6$clsgEy?|i1vqf#+LPwlJVTVu8TiYE1`EBXj%qKvn4+VUBs
zYeExrO{41NUSXcy(|cyL;sf0vtY@Cz?PcxHHAZuY*<D@o{APAozRa)7Mez~89Y!8I
z9jYdhIN3`%sVf08=wwNWm;jO{4oBfz{y@~Wfc8kJVC8Eqd^ZroJ|~2|dytj@_qz^h
z<@LkMQt3c$Cp(K>;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?<!FGd`sep|vO;g3f@1{H1v$lyMM4Ioskw;NwP~_h<rFy}&2XS-b
zRQ40cR%b492~BT%c2cj}g&^17umm<!4=3)Y{zJ}fMr-qB@ibbt=9@m85Eoaj3M~4;
zcTfC8i~Sep`<npb(vp((7G0VZCH}OCgu69SCYtqkKF-RN(2U}uekd;!!s-&d%CDt-
zzc8bxZ7=n?MBrp{I@@Q$cm>-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|cB<K{ZwD`2xsH??aLb$zOL;V;bB?Woat@C3YC&<C
zC}k{@AL^(SOCC2;TMD=o3M?uV+#t>16?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@hJ<Gm@N(M
z|4u<8{dq1{d#4b%IE!+AbY6nJJ}ufh88syB3B&g97zlKY&<}R8+P4n{c#5om%ZE&T
zp0;<<ZFueZ^&f9Lqh^epdJpwvb78}^wQ^d`JqrjjcI;B2gie~M8)inj#pq4is*s)%
zB@!Cl(x-tH(^>UILhft9w<Ioy*Q-vS7+TKlh=3op*zFegreR~Dtz~m<d2jyy@V4lC
zO}Rb^<ARK=uH^O+DyY(+L4U-?<;Jz0=Bi(D5aWz@uwE}+C{)HAhVu;&O5v%3GUU!r
zlkBT{BDg>Oxedi9fRb}yGls!mn>l+f{#8rDHV)?CsPeH`^sMXSE<BYuUVBekgtSzv
z?aIEguut{#k9fltlO5k?z{ZQlhK&blqB6NdZylCx&MbH8%lk$0Z`aS-`~aBr0zSrD
zoo+DpdCoO`tWn%INrdArW0wD&$K}3WPGm`T7$vx^eW6JlO93Y{CgT0pF>8j|K5KhL
zMs*dYV)Z#%F_u99obUuTfGBE$9lcb1*5jJta@{kQLBd`N-%0y~0j(*0CjtbyuCm31
z4d7Jd{&e5fYQ9aMzkCd;cH^HMMrDc6m?I$2xw27pXf|lUItupLV(K{e<BHLd4R@pp
zb_E?K-0R6xybBRP6mZj9ppBP8<XwAXgG=Skyo8mI+Wx77CDB@R{(s`~(HQQ2OG*8P
zR;Ys4+py;ka}2JW7D!OP&4TP_C)lS{EK_<6N@F2`X@iI(#Qw_AaB=@8+HCDu<%wvz
zCBCofq_ZA9`W5jg^R;ut_6S2R=!%b+^>ojRx0-uM`+rCYzR({e=A@hRZe?!E6-U~?
zAdk^(Lf<qHQhMzWU7yj1*>J>Rl<fD|{AfHaE4Q|SwBj$K<x)EA9cP|vh+g`4w((~+
zUR#@<XIl3`?l4vUVBBei%*l``Po14d`uS&fS3RS!Wxk%H@gySD;%K$451CBjh{kbT
zJ*<mz#lJI}DRvTqgH^33A=@Fme`M>>$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-<wsw8i1;c$#3Z-9-h
za0}Psk_ioFydQwzH&G5%IOhjlH49*_X>ehgaAvg5<*Hn!875|uG1*dkwfOc`*7Nvu
zva^tkLuD~{)Jb<ZRRo&_G~fJ>xoh`0!fS$f{3>#ykn}iUrT{;nLqw;hv#5uoleC0?
zPkQor$RcI-s+ih2$xt<dxxn}JdFb?g1kMH=Dai4<bZbklc>yO;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*Baf<DUNMqL`tPTIEJG>Zv;IQ&qoJiZp6B)kV(S2)V6na%
z?yXPXVCG%Xod&b6vYz{~kKiV`;&IfOEXbLrsdns+^utJlfT9M@W`T^dltgsKAYyH|
zL_<#L+WbIy(J2LIjXMW4u!054TjVQozIvEuI}Lm4oe!&EqAk$ie<h@TC(FU^jhr2&
zPvAVPms)3{m=!$itnPSjhygbd4y_by@d=C*WwX^C2#O3TCp{GUS^iw!Z9f5d&G8vu
z|2u4@PQLz?BAHNWayNe9@Rfx;`K@!lqL0gY+~Pc!m04Ibkr7^`uQFto9*Rsfj+S?s
z*lL1kEUJi=5@JH;|6wRRK!-kaM_SO6GGi2HiHorl7!k2Z(SO0-H`=L$!Tio~%PNJM
z6H?|&03&Ve(4hk(6AjGoPalPBn;dPr6_<q2ZHS7a@d}H5-y#g2(BiK^>2fn=<hGXU
zR8O?!qe3oB-Dzf8wl>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<r9gy`3E0rGCrw_h3DiG6M1JkpRj
z()$CFsRt85IQs)oklAlj$Z{?mO?6g3Z|DTv*jKP%6-*5)+e9g)>%db5oZ!0(5{$*I
z_&RxQV9PS+BV#IkPd31UDky2L1xTkp5p&6<UE@TJB!gp(?wO?K%nW(B(3{IYhfhM6
zbXrDo6()@!t#a7B?i`{g>!-VEnoj$pW5g|+b@*NMI43Lu@$A)Tw{;;%_q4@@?$&`*
z4(h$hWms;|c|IPr@qJb%&DhzY<u&%F`@SYZAp0gU*Md_ieiH(`tq__~AunJG48&7f
z2Y=BhZ|`5Mh-00sHuRq&SZ{(a+iS2TNOcv@K=n@X`F*XwN&>dh1yH6u(MNBhGxQWw
zERX|Pt!h<Xf{w^@aU(`|b2h3@)c(~2b%UU>I|iPhRz~|3k$i~apyBELXsK8HS<DdO
zsGNl!tt&VSmIno~fK3U4#GtHzo#&(gwU~FoqZss46d~DFSEm{{+zSny5IJ0beU}U$
zvb?ASE>B;6NOs1C=Q%&vMx0<MjyUon`opZ3NfB2PmJC|OyTO7AlK8Y50Ck+7cxx#Q
z`!9`2V;NZzc<-tSf|p(+BW*|%7yL+qR!M0wT8yAZt7_~5!^Vio?J#x<nK-0ki8W1^
zW-`HsOfq71&t~GjtF&C@w<2UhL;JWH5QZa+e@2K-9Zx03c2<pXc7!(1CNhhf+fiDN
zo}Qgh7Wf7mXgH8{GtY1o1&cw5W*C`LmSU|Qt9Ct6=jOH*)Dl^knE`-V_`EK^*pW8?
z&c$`?MreKBwR&D-i?s7d<#*dku7#M3b@IFDw6vzq(el`hfu2VhrcVS4`Z!R^Ceouc
z;CNuKfdU;z!cq}Z>lO<c5M$!8e+M(L{`AS9{5^r8se~6+ftBHQHK86jfCO@cTAO-j
zdihMR)PhkSf`zma>AjEu0MDyaSD48!obRy_r0y486kU|^c2eBIq1gPfYR#urNAuGR
zX`v4{VtbJ(CuQIHKkoA&Mk+<w&-D{I3lDZ*w6<Sm^ip7!d75YD(q~t^Q(7Xb*nFfg
z_0J}(Q6m67wTnZrwl5SJJ@{MnWkfNTRoG9UgZ^-EOkLw7=ue~vVMQ=HHMRHEpPpN)
z8_@D^0oUc789pTq^YFY?KV6vyv?pXseS~6#vWpuh^4f25&=zj5fZ-b{ODprU9~<eJ
zs`HZ(P!<`CBUrA=+YzWcETkl{z_vS9aQB31(<6@{N>7W`;|0$sAeVr$uzkw$8_@V5
z+88X8edcy7j04AN2qM7kXUQsYAO0VEGamv2`#X?Xr$=J@#Y&NL_!470bv*UaYeZ(-
zQ7X(r11I_14F1M#bT0q%j;5*ieBR@tAiVPr8QPxHN?tN6EiGp&0<viY!8kFRg=4Vl
z8ECZ%&whNo+qXd*teMkv%^#23+eTfPf<voESr%nSlR9^l8gYAl{9elh$u8@nP)=|*
ztjxYp*yok-mgP0l8oSg>fG)LY7?yWt>%&gg`<vTlL1SJgL^%;M4zPZq^&!~zd(HHH
z37-IC`Zs+e8j(13^97Ahb#y&}i3p3`3=-~GY$qf;Gq+Ai=j6euCf6`mr!~{5xK~|N
zIMS*gB%}c(?Rqzd29K@II8I!02hyw>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<lsbcQ^q=hiW-F
zid7A!SBlWy>!+-5s2hF1$=7OFK>~fzRnC^F7wb+XNyH_OvWIoNbu%kQ-b*!dd*3^H
zWTS>WRg;}z=h|;6*CzrD*^+gMwTXcv=9SaJ`oNNW<!aKJ8{Hc`(tk8<Wtwz<WFf5Y
z{q%x~dl+vDS;?R?<}(TS0qkRmq)zm*I&ydw<!ENOW;~C}lHVIAYXI_^gMiIWJ{e7&
z+CoPVCzNF9Br@A&huB%Hg!`Z^|96&U2+{q9^<Xt?O<8A>6)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<aF+<Wxs5oYi693t1cWkndEPZ?;Q+~$
zvaOPW@TG)y-bgU>^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!<t5;;@D<Um5snF
zv==j^aA(+`gmgQ+nQb<TfcWC(0f+j?D|a9_a@kh3^hAa2Fy1l3GXC?SzA*4B7iT1!
zf`~$CeOiN;U0K$H!jlx7Whg}10$D~5cJR_XV-pYc_G7kUERo9>tp(8*=H;<6i>5y{
zitI2o4~ffgP0+>@d1=7#_Sbk~L%mo=VwhEJv<F&Qr<`G^Cy7RLJPgR)O0=Bgtdp0k
z+h6WZ1bFtS^qkQm+dlM5n3qO}oj`WgVW{>hZf}H?e^nV9P(%226JdyplEeyPj}g5$
zR>PA!9p&_8rBex<nt-ifIENQahre}^fgdaR5ljv$DuG~%)ydOvVBJr?1-aIqQzX$1
zH^=Gn{uGLaTKE0e6cc+cmJXD=-LSbYVxwi$k<2RduMG%5mi9UsKECrghy@v07ONj@
zQtoT#qf`OJ7!=l$?`WK^)ez@E4SQl}dMO$SSN^OK{EG54iNikO@xH{#+oyBi3v30j
z+D7LnO&AGrH8o&~awqL>il0Oi=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<wV?0e
zEWZLG4Ao`&RspunYn^VPbvuwlSQFHM&AMiaV_EV$bk!d&jFFGKsq@kKZbSUCuX7es
zpT*KB8aP@ei*k3@UseSe2m}H)%6jc5>*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@<F!AKW7Q;K9lS|j|<DRo)NS=Kl!;UI$PkKrfFYg66-pDO5}XoAST
z&N`yy4k${=DRn*Qnq@Zq^E_Q}@+|Z<Kg5zvd}`3cPYy<KBSYdlxZI;HNsgd#O?{KA
z&CQ}Vbui9RNCTca1@3DD6R8a9Kks9)=s}<<CHUTBrE<6YF(9~<sP972dpP4*J;RQ6
z5M0nrqh^z+wu+I{D}FK!b{U&lI^x5(o^Cq_$`;C{bG0(HKVDqIy#4?er9Qm9G{?cu
zjpy9z!<_!-JB1pUviSB^a*f$pARF1$HLA+DQbdrW3KiCcDm3+${`DJ8fDXYQUZ1<Q
z>`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&%<b
zXkzK_bCNPQjCA~>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`7<hYCTf9VNu#KV1(I>jg4I3)<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#<H-&S9iFK`pRN<9qQpnKWyu2G96k14x^Lnn1XC?V8Sk>
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;%Ikmi<CGz7d!i?Op6n?l3DIoG45rJq1b@Dz=+`#7Hc_FtAe5mxh9BiZ){J
zQbggwmE7Y{8d8h)!VgGc535{_n%s>9#sZ&y$Snbtu(=WXwuj%G8@Cdf<ykP?*cQ^e
zk+IYYzlidP*>!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{(YL8<h0*FXLdhQ75F{7#%)a29hrNKS}RM77##KQvL}zOs-Vym-?*9(
z7(*qNGys{1rHT>JF;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#2<Lvx
z$>hLZk?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<loC@Jt<JOI@RGMVRGcxBD})t~mH!WV&$nd9-vL4n
za}X$@-;(QxyPdsB;{+=?pmflx=|#XVs&4YF;X0ZA6q7T&^Bfe$bPEN)lNw!AYHPxt
zx}ayq^z+x<PiAXN)NXwo_bgoko|Oa)y0@JeX6HT36O8UZ);dZQgd=46e+ON>&%|n{
zhZW3?IdkPNd`)(xvH>3hJAH?}$7n1viH?qTqaQ>5kZlTxS2G7adrxQr`e8Pk>5%cO
zc!bCFpa;o<D-;8q!A(bev?;-HR<wP-ysaEPo3I!<s8ER54AI4=`n_YAy))KePRcm?
z9uH>AQBP?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-WIG<g)+T6oR&t=e2%C_7UJ#6HPT@~?q_Y9l`07F2$zbvTYlt(PWG09B7
zik<n|{Id5G9*vmkJFiSuq8^Di4yJJw|JaBTg@H+X>77?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=ixi<wK6ldgH{5e?ToTUmmc*fP)l&rVO2?W=>l%v!^{0RjhD*W
z>YXFv;+0%fPXOa`1|nwh@N8<O)UAHTlWkzB@iY;*(V2<n=u3bNq%2Dlk#v=MMML>+
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<ZSWI!&3?L;Uo$9KEXwceUb1z-^Tts#>_;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@kt<LRU6E5DH<f1iW}{h?8s%x+Mz;we2epWMU`AZdD|}sBhho
zDWQ)d`@G7KZ6Hs5uC#zdqhm%N=@}&#)e%kZ7_{do`pd#Sl!m+<upym#CfUJiC{;nM
z){Zx;Jq0A|-}tqTG){oE<OR<lIpqh?C$o|0^)QkBQr=SVG3OZ<ZXaX-uzA()3LpmB
zI3b-QNqYVL7ntyNOA9-_<G}=>Ji!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(MClxF<zj0Msam<_SLb%9=u1wkas
zpjROM9<o89b7ht%V(paaX|qo>BbjRRtC!NvIi5g<B33}<#ghk<szg&f=v)4>N>p1D
zq#eM&QHN+H338m+yjlZgiO;GZVI`V8biWD4dL-oC(wt3AKiu>3C_UMiRtauhOB}L6
zBCr{9f7W}!uWXM%H)ZEQqdC{CFn<BTmTMiSeJiNbl*%~+Wd>8Iz6*n2oZ^uys_3S{
zJ7A1%jg*6DU~f>w2MmEbQ(F4r_#3e+>Q9l_avp~UNtln~Cytgy;mxn||AZP*84DBJ
zGBt;&Gn*edC-~)N;|99)C<l>Cp^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<I<D&^S1~&XWuZ5^71ZT$RrsIQ!<-l2E
z@tGNt?v!=~3i{qPS8QiTP<C5h(z*m9@8nXp;fG$|z_Bb;d*UyJd6|V+P#B;_hKmi;
zK0I=N6RV^U(DXyl=)-2t3I*T4+&y6An7IGS+hupbRs-~-Tv(x2z~Rv1B$gKmftniS
zHePiYRuk;RE*Cew(?852-7kx`S(nL>+W_}zbOL;u%Lt)tgY^`WuC@hEaEXN>0dxLM
z0Im=6PPC`2c?|M8N7P4htW<SC@iOt2xE<u)DWbMo-C;09Pu}yf?WvH?SoJTjL+H7y
zGa8Jxt?r3A0nC?AMJ<cx5|t6>&^7E`wNY6Ghtn!PqQo|(867vbC8I$Nu+^z8gXdvp
z%+8eSr%zM8AM^18%UyCP+GoHtb&<mf(~<uGeSqBQgkm%T?h}FxLjYsmp2^Uw@&o%h
zg0~h;O@n<n5SiLK$;sN3WDO~o+#?vs-lAQBU9stp5Oh0IPgs%{7C*GKl3=uF9s(Yt
zu}!s0!&fi^S_Kjv1Q6<ptArfFv809bli;kVAhaaEb}tNEi~_gf8;b`kRCPX`RadI$
z#qyweIWhR7cG*|ys7P0YQJA8UpBNGtJm@i<T!N#i?gd-o4dDF%4<lR~#(&~tj7zq|
zM(~MDgV;|<+YKcW00?;*U3a*$06{@Na}2v?^%&1TwH`(%C&G>1!!TB5AHG*?teR=F
zVRKhZ;dTZgG<SQp&hrdk@P^L?IzmJSm>X@8@_vGeab1rK6!RY2HB?W%#1Lnp)aOun
z4Ov0G=32vxzut%0$o`eN*5RVvQ`y%07q8FmIAs?xKj^&`2dqp|B&IY@02besJq@o1
zojK16^gcdd#@ND{S<Pm-rWMeUs%e%O?cW_z@4b|JF`7%fXe}j{R|15xa!S$K7tj5c
z6eEc!|E67HBswm&LI>i`$Rt_pw4HGwB?CEj9<W5Rx8sFIMN#2$k|I_zc^<U|72VaK
zDjPf3pqvT-w`F3=u11zAjVXOwJVAp?I@Nd>*N$9wU-F-7d)Gt+X7EFW#A&(JKz+5<
zj?-vRoV1%XYqKXEf`i$i(sLKOmdbPouz4xU7r>_d=BYo<<v7W|20~kZKI*mjik!-V
zmq3HM`0%mn%qhcrX2&+(I|OW><?6c-A>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=<gFtWm}gCDVWPZTKf*goEm5O}P-F26eh4FaS#uPM
z(HVhQ)~=-I4`B5Sh;3Z-G&Kg4EWm>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<GEQA-mQ0{F8V7ePP>|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-|iQgrhg<Xa^I;5SQ3WbEptkBp-@YXl=a}M5Uio^}Xsc9Eghe;lFr0
zvCd=Cl=p+kKS^Ib=v3!*`%M&*KObUKWeqe@zxP$H$F&=uwUkB!TDynohalBZR(BZF
zrJ+nDhbZ;+)abM<JwAX3IoxtwtX}6}_VtRmBrL~*^1-iBAPL83^1YVR>X6e{Spz^A
zF^$o*un7v`k<>vwy8gl<PlO`<CxhusY-+*Bw4Z)jhN-Exal%JoyF5y3dBd;517%nf
zScn0C&kO(nEQ&3O^PJx|syfp6wokJ%aPw{|v1GD}mif?3T;XR~1qfo{kY!=p<;?Hh
zT3P0)zt3p!oRMpqYj~w-eDG(6LmKmyRA3yZk2mb&e<KOWJ?L_uT?UDFgHAxox&Q2)
ziQ@?8!*+eD@z>5e-eMcs$Z=5ju>%LpV)=%M?2Yf#4)7IrfGPlNhl6@wd?}s}!ty>B
zxEH7>Jpr~FO=BwxL%g5DY@e#>42AXL5>bVm6hjn>2a<xrere`iz9w<uk=9B0t^Uii
z1@wZXzF5CBV5<#}q{9T!Be5{yvWvT!7A$`}!k5>Mo!F|uwk@n`*e@lu`!Kz1HHg3f
z02j$iE3KRWqJQvX4@p%KtO(Lr27t7C2%stZ8Pen}ztZ)KXOz6eUxy~a+B3+ktfaUH
z`jqusf(zNN<p$Ls{p~HgTW^mpKcgB4kB(>M#%w>4U~FeLBBe}rr*qLaihWFQ5zu7X
zP4eSEQSN$FF^CMq!w9a!MWTz=B0;O<sR>B?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<QwP8fbT0FGSz5|!1`w26UoiKRHjg)nC_p*T@!<^OlDL7DRfLzg?H{PSCu
zqN;xBAOxnIIOZT{ftTC8P$G4kCubF4O4I2574UIbaWCQ}a%SeC2$(27u5HoFT#1rU
z`y(j3XJ2@egfs-kg`6DYK>)&k0D;-B4v=qMh|A6*eekGwcxZcHAx2<z#SRAfo%q=$
z*q?4Cuf^|hHGnslwqM?5ATc12pgPs=hZ+OZ@b{yqCeAKLqpMi9ysvY_z7i3llM<K(
z^_B>HaRyBqK8w#&UJKK{$#-eqpc^Gk1!z$anRNvuUAcyG6USdsH?#@Y<s_j7lAjw|
zMIN?rB{2S}y;-z}w5-yg&SFzhRZXvTOU15wfJ*-Zj(6^&<?*And4G6#&m({Z;Jo{?
zxmK-y)1;M+AI$Ebu%@r35E=x}_GI9Y;x3LW`q&3#U?qTG)c#sCsJBVLGTTNsDZu^C
zEGPuv_Gr&Ewo|}qb}aGwoo6h}P{rt$LY)bbJ4?cWnk_7-O5$AMoLDzeRHi-nO^Crk
zd;zR|c;m&ns~`hh1pojEm{7~t6yA8f!T76>Q0Hhr?eRrnokOy1#Ndf-bYH^DCLq*u
zPeM5_`saAY6Cm=N)90Sj-Qct?=QrT&{Ky}{`-NmpAvZ;qd|c>9k+LF-W<f#aAnPC@
zUod1IgwD}f-{DLEYeZ#)Q5Qqlf_ywusA@8#`lo)@40g7YvMM5~$IicWZ8+zCjij2d
zUR2jF7My)J#_v(|-${2tE)pA08A1g!AJ+(zXan|hhj(qiGAz39i3(^e?V-xFp=rZT
ztf6etFFt);;yOkOKk=RqMQ8)_|G3QA;w{YM>MzKQ*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!CK<GX6>r=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-<Y#KXGqJ|7(y$wZNPe|L7%7VXz|G&
zp*VB!`Jl625?)_m4H(-K41+z!1c&+;R}xV-!pHYQ{=L$`GufuBFkhVGyp*wO+TGQ|
z((|=7^Slza-R;>;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=`<T&3bpi=0%JIHuF*oAo)OPPf+sTWqKpx`lY1Ohv%1gOm+jEKmRb8
z^F5#QwpY97j(c%8h*7z2{#74k&kA0eO)ISo6LmU(SI~#c{e_}Jn2;^PjL=db`2+@9
z&7Z!)PIv+SY5aS2{?O&`gV{Am>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*?I6A8x<iH<aSeQmA)rIaWx;9B^rvP#vk-vX)ntw16O4>o|%I8f~Hob
z!<ass&tn54jg<U#4n_j}#R?^oMCpgfm|`r_0v_@Nog2c}>2+YbA|t+|yW{A4ZXbVU
zaOKxqap@PeJ{Z(3$W}vtc|<ja7|e3JJK&}(bLdlE9$47HVPwc@+I#f=ZSe=!24xxx
zA6A3#k!FiXhG6oxab50Ayx~Ezh*N+F6E60p`(paQ3`3z^Q#^#A@plVOLTG={N}vI4
zdx>gUj5(+`(Cd8LTI-l_!%D<EkdbCZwgRnL;2suI{($<PVZ@A0UlKk-pXx#(gk#>5
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$<Hp~w{i8g+=R}CEJ#E{>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<PSEHx@N3!@$f`*
zZpiHv(Lu$`uH{>|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}<te6|>MH34$#7tdiswUhIVL(1>JrGkhkR1s|fl
z;rXW~*eWJa0MeMi^6_ccUX7{~gelbykG6J7zz2^Jrm1_c)wX$vn@q(-gP&q%pg+(c
z%!;&?;eRMA{24WZjG~Dnssiu9`augG4<LZET3s2a)Sr^sg47>kVa%f~=d_G<rmJ$~
zFLUVH5I~7(DOA%@xA89RzcF0$^?q#jzc39^=q>AyzA?>gHW^uD4h%hglrg?%J1Il<
zt0L_RGT%{Y$*CeNiE|)n-5a}CYprgYK`6&0+I&IlD@vI&=oyc^KMo2>uN1aoY|Ucz
z-SH+NKPbj(#W67P0A`2<M=hc(j}y-$ZL$xI&2!YG<YV5LTE-~9sW{gtO;Q!$bBm{w
z1N#Fg)+Qxr5`wO4&HM*U55ZyWZk%d78F>c6Z^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+*=BZhEKX<UZ;1D7=$(Z;DaE&qr_=u%D
zjN29<d&ku_06jXAGiuYknxJEw4~*gdn?M<UU)e{DR3rVKHSL^QhI>t8;xz82cp^=C
zs4pT2yfmmJsXTvo_@Y2xQDoVqpZ%)8Wiaeyvv%OxR*Yn4Q9OVIK@p^^_Ca&2pFEB(
z&o{IZ$%OaJ8Ei*&gkCY%ebObc5JI}9qT@0r7nEvFkR{X<WDX=!)!+h$#I&@v#8_{C
z5UWmAIU-*W#N?M*&74I%W_Oz)Kha|^^W1ip$GebQpx|rkg2jeEVJ+vk)bE!%zm^C*
zY>*Qi_QeJyg(kidDrdmxg5%Ef*02Yn8AR4oK>!b<p8pImS^7iL22X3yGr1&}UA&41
zFden2O(j+tW@1#io`#TBjdU<74~P{U1xqo>kY^-MCnC^Z@0+_`-wxR(Cie?zgw4p^
z8wb5&r5Q4#W!<@i5tg35w`~3@UqWjufS|qWi^BxCML4plpGy)oldFDTmFtm1x<fe~
zwnj(+zzWw8UP3w0d$UCVp*hB&fhTXtcF9w@Z069gAW!PW(MDYk3pu%l$Td7{lrI~G
z!OY3CRRh0dVDbbY(_pH}+55E*9gEI@MEWtFmzKWi6n7ijc{5P$oy`n4)XIBcCsM})
zo}^9Fd?;gEKvUX%i%m#M%lXJ5^!eY`B2k;uM_m=d>rMHQkUJ`w`5MNUJYKtQ>;TOS
zodFP3Q<zpOc|}}~lvfmuuVLOHYK>=RpT=lu2TFElwzv~8<CtP1kgFjJ0;df1rt|;j
zT#lzK{AuTqLbsf(Q3{onoYd3%AgX9SNvP4&_6hYQ)OUJ;O4$qu2MsFV>r{lA!<zCk
zAuLw7M~omW<|mD}COHKbJy~@(qRWX)0RQ)-P3lY`FqMQUnS(IL32`i`S{3jcb)xo3
zv%e)hfT87&ebI-=v9{4R*HFfsvV$O8nk^I{Wn55~M)3*KW+}IvJ-!pxxaY&9=~mm<
zVW;eQft>k>vkZCu-3yMm2PEtY=R!ZLHI+zOc-8WqGcKLfZuODBMnQ_mRcBPZ_{xQ4
zE8Y<Nx8bIXXs8yQ&CzSR#j98ey_tIpMM>kNnl1<@L!C-?ev%c`xp5lmd)94#elfIn
zPAY>%sx34q7^yjNEJ8TL$;cbs=-nH8xW<Gz@|<&VtQ9{{!i)BQyphO?mM=|;O5X}M
zWviMMEovZLXuvNsWnD=}mNe+U<*#I^c;lTnMZ#wmPcubvzbfenq>(8(JSXKgWdWl5
z(By`(DpFL+ehJF~PSz?<A`ykJ;HZLLGwp_21d0g@>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{DPpP<Pu~zGuV9
zL_iJ!FHY0waamUD8F;<6Hc5F;J~wE93Y(O?mUb>rZ-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<dnO8IZ%H9f57{=5cdv=9<R$dkUk
z8_Jc@kb39)twsivJL>`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*~<!^e?*M1dL)WFBf4N`E{oOO(n8|bMM0QztFspR^K#q;SgVPdQ(lI$gv
zm^XT^_=s<!dH%%w;(74q1{hf~WC%)e`02j;C$7R((y3}$V0_1;V2vPA#@J6k-0x3?
zSIYMD_Wfzh%@qeT+g;LFDj=<3$s%!Z?Fx@>Aw0My<&G(*Hc|0Go=NIY(Mqd~9Elpn
zc9mW(L@32`B>;HCY98h*m;8G#2Wm%+PywnRDZ}c-aIZ|lFiO*{#!?^lP`vCEHgc-O
zNOTbb?d!i0LP<D0b1vMctU$LrUF(d`NS})yM>QDyKQp<g@7a)PeZx^ItL1D-(cRw;
zbGeG+Wr2!2t8+jAYVsE|x$K_eqD|Nhu<@(rnEB=1+WFu_h!>d%)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<NA>{kU<53GPd@hip5I@Noe5C<ep>DhkC))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?xeUMSIeqS<ydGr!F8y8Z8^T@k=pOi`2Ypyr?l}`
z!hWifx-WdwVYqg@Q+i}PSkHBG)7iwuN(KEEKiBN>f=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)Ri2AC<mMGjqrhs4YeVD+<Bt#{
zRHQ(utzkKKp?7^j%_Q)))2~o@Wo<3Qr5lVrW5__rZ#BnZR5GIGS}rViT`TS$Q15Qh
z*G)lNh8j2r@Gv6A11YUA9wo<?c}ruM>3q*yeUXCr^?HKjA!R_HUpem6o2Hul8!YjP
zs6*r5JJjkIUxh|zev%#ChMl0Wyl?m4hU>L>f}u<ibrnpfvXPRIS(M6MckW=r^&JDb
zC=g@de18nc^*MwL1fO7G$NYU~P_1=X3B4>iJfL_!@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(}<?P4rB@i}H
z1&YhTQ>G$7D_fxtLi!C%zn|#sQAC>fpu{UrH^$T4r1gKUZNxhYR3KYrX2RbUDxD{_
z<KU~O6ZIsaHvG{TPAz)6)}BE{&{bZLQA)!T(Ffd7TQ*qsMF_nM-0D4mYAbxcwwn%W
z8YfdQaHP0UOQMu+!7B*e+A9BJkfOB6%?a6-=%ZOgrm@`$vm#n&{&SKE+0r{ALrkMY
zbA`1V@UltY2?qWAVr;f)O&DZ*>r=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+g2Leu<fo
z|9zlR3=tQ+x*-twpb<;m<ry?NC&JU+s@QfNufi`T0zX$g2N0!pCj1J$PoNJNI8x-6
z=)SXaCV`zBMGFl5G@|DNKc({+2g^1?Ozz5r#$MX<7TuUNl-_!S>OwG)o02yLYF_*J
zJODOVm%Gs)SO|-4mMR4l`&EJtMKk`Ae82+}RT6yKCVo5fuN7RmJ_gUbUvSmUL;r1|
zk-~X$Ha+$}AnRZnf(afz<beRe!XU-zS%Q%UjIxx7E+8%6X!g!}{00*QdYyQ_3DU!J
zmI5O=SRp^@egdBB?XuUs005JJ(r)^*-49zj_z2+w%18xniTKWcy!wY>+3*RcbtQ8u
zivid%x;hmKW)bJqJ##sK#F+}v66D^du>sV?jnN00ddct0Z3th<e&Js1KPk_AxIN68
z-!>pOc56pNb%t_p$M|;I?cbiWzB$DNhq7BA%tG<kBa#9s;&;4<z92`q>bbJKkdckF
z6VDeS8NRDlE0{9SSub?4YelLy4Nb`2>tFLKqiXo21MZ&1q+aG-psHIoTAnWHAY5Dt
zb>UZX#TTH0i2achi<D#`>pTTb5VM~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^{^j<HOW9^ypD{Bges6_|Q`+`QMz6NFJUu|hk&KpEzt
zn>c5gSEqWCOBFA1PLnc~jT;=qFo_2JRO4ui8|mSD3$@kaGTfY{q`GYE=30-<?|DLz
z<RZ|vd{Iz45y15zf>uFCk$|lQo2dmJW3bdNTVdCdDK@F6wHj|IMUjwlGRK9X<gYTp
zor7@U3EoDE%SLoVW@ZXUou{xhPw9&J#qt4oUmvVubBH-*DtZC3Nxa7teWEmpy2glg
z-vFG)0muq4shyxfE0`>3?&(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<wA7r3@>?khLgz!v
z7I_$tT=KlhX|*qGrP-<k<tn-!Nh+o9<;b2CKHPS>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^{<ZUVn1^e*sh$m*dceaoIHLtG^ShJV!8K%}n^#
zxq5guAl#jC@xObhmebybRyc2Q?ojhuGvnsn;(LE(J$v*?SIs(b(6Xf2onHQlvrV9D
z@RzDL-50KA9Kf8s&oQEnvpp0k5$CW84`CqFdUkc9bH~Aj;0%{@KIl^9!IQhKFpEVk
zd_a-v199c$*#45|mm>FDp9`)krB8e~if!%nIk`Hm+N|p9<zOy&n;FadA#wn^Dy;~2
zfcUK<WW@T_@Bllmt4cXTb<Xhy;Oha~f_?yB^zeRT*bDQ*>3~-JOf?fIO;oP%as#f#
zP$u<Gg8)m*l!4t=<@$6~eqXwy+enilOB2OqL2=D<q+5aLYY&3Ed>VSh-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&r<l
z4IAz23QVq@R{6hKyn2hdFxwDOyWiPM>gRZJw3~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`<C3}1QawpSS=tY1qnMIh_$j@iY9|{%
zSvzqbd}4IZvJ_u5oE<-npCR&zB#fE^9x?LS=Pdt4{}-9Jn0tPEbG$4VGNOZsb0q6K
zq!ditauTR3cSiUOub|+hmATWph+xuxa7q`alQ2CzPf-^=o}lA)0}h4G790rT(n#N$
z&s}~V1djkUE@5bSSpkv|3R{HsNlTs!%Ezh3;HX0JAaLzw!kz%zI;>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{T<U^kw1I-XOCu-L%gSZKi
z=HrF5ojaHFQizBsmmR@9A&YDXIdIOeQDF5-6>2|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@v<ZS+7i$+Zbuh&;nLehLkmXVbMV
z#QF6|TdFji&pXO8<&v=MHF>tk)Je=Oj=;8HRL?$v-@B_l|GgH+<R?@v@kngIfmWLL
zEVe7NvPQ7=vUHRjV#}Y#qAF9_hh+GpZYAI--2Wllo`pDbmUNspw8UBAJIY%dSft|A
zGh0Be^1J48bwFONoc7KIK1X(Mq2Dmt9B|D_YB`1J7u(XwTw+UscAi#&)90oToLGCf
zq1$m5rXecR%-Z3_k7mauN8%v;fL2Eqo#sb`AIV29O>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<k}PN4#(d-S-PHFxAp=-V-2$5eN`;i=J=~
zYmjA`wq9VJqKC$larB<is#TwEqjg!LS}`@XT}fubSPo773s4z_gWi-Jtgm3lOi*WR
z$EUD5vY%LZf!L0l@e)eITs;zH2E>!~^1_ILDpQ997xQ&zyBe%|<+OYQ1Q2i}2F`pP
z0U?UoUhwKyL{=H-ooE5_|Mm&X7HkDyHSSIrZxS_k{m{@Xw<}z|<k;<T#RN(&Xo5GE
zx1|XAEf&MY$qRO(iG^DzZX9d-4z)e^WH{q}$a|%TX2y`%scE0W^1e=J%e!gLL2~F!
z#L3ui4>IwkOrs+-sW)|{Ssnw|no&!YcGV<Cb4?xk{m2mB;>c@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`2GZmua6gg<OZaIP6AHx1J_8@uM%<UD~H##}eV@
z7DL&p4nFU&ROI(;to*NbVfW%B1BGVanl1q51~yUX?Y-ty$>S^GaHaHYW!DweX<k96
ze<>F_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
zi1<z({aeeaE>hW03&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+<Rmakb{m~cV68k
zZc{izx>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&(T5<ejQ4tdYSvF?<k$8#-mAPcD7$rNtt$=}htk$;9
zCwSKMCD?Y-V(d-`Qw~!Z)kiN2&Z{oLAPY$In@d-_jl&%s+`3o);$9r}Z#9w9o3Iql
zHax*s#n6@#Q5*jQc<AGI%B1K6YEi{79auzfXMd{7PYDbmS+Z8xj#a5j%*qjrSi3e;
zP&3e=sO2;YoSE~Bns)NUo2^d+(m>pHe2}@aJ50`RU~aHT0dGJ<(q)=FI;P)Y618%}
zE|aF5K?C?$c8=bU=F)ludH)~@Qs-|mGC7QFZ{)9JgiX@|)C?NZd=jY-cF)bJ#<hlq
z(^=f-Kr5hAES@HcA}#WtZ;mkeDiO6^KI<zKHx;qs=rKqVd%yrC4zb9#x`S^w+OfAQ
z1hEh$HKdNXcZ>^VN_FmYwNxg<Noe#o7zWTM8kn!X@=cTZ{=|72AXYyT1H8JN(w~E_
z50+jIAkMrSLG5Rsb$!sGN|hL8FRap9Yq`jS`#($sf@5Qa`~H+kBt2>ye`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$`)%C<K
zJ-1%;ng^DBQy^cv>vw<k@_D!rn~903o<eGEAOo*>;!l(0u`3*1QEr=FZ-hOqNk%3z
z{KI4dTKBc;f#Zj%sh=vgecf!vMtST}`Q?Z_pzU$RZn!5;pmy<xF)xb55Ln)+8WS;-
z;4d2%)T^;4(_x|6xN8^KFipw?4Tm91{)3~yi2B9|TanB)-Nnvg$8yIN<U{j#D4~i)
zIhLaRHwz5n%(2$axVR-@z`d58=+~aCC>t>q(-v&f5u?e27e8OLn4I<dP>2fyk{S7Y
z)t>%qYQ-$ogg7r^(>Oj?&&2kE7f<ATV(L^|%03*|SWbq`9@$cOgLKv=JnD(ESsbUB
zVT!Ycg$zvi)+O)t$={mH!5yL2%%#YL3BU-RbLW2~>nUYm!!(Y##4siTRi*)ab>-Ml
z^|G7zO-vIf;?A4@b6*_CnFB#frQlVgw>7JLbtM&aQ6qXB;1a<OAI1f32KCpMW0eJP
zqUXIadO)qJ06##$zgh--5^c4w4{!$Ph>ngFu`%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-<Mfw#TOkV%08gqH1~sVI9Z^F`?p35oV!
z<79lwV97I~a85xRzrr(A_mRO8zQB$WH{=)8rf{=jvlhO$K`Vb?HKt7n9$cOyppu#2
zQT#7-QXocXH#t(&Yq0+T1KR!<T$@R)G1a&-H9uHnZ~#3Gsj3+rjj>HAm;P1}^V*sM
zfJd)1?X785v{C(XBq<I%_mJ32Q^%0oEOAkb(-$S__Lzb{>^7{`ROr)X?LDJ*zp+$X
z%|Ue{JHId@t(UKTdgH*q@11(7TbliWsf542i)^IWBj7&_>B=4s31RmQc5wkA{<QKi
z)3Xr?NY5eapc8%i?s(j6UojIPn8yYxXg7-j?~3BV$A-$=WJ>fN7t%b`04nP?snq{~
zk!1b{vEYML>0!fPC<e~HdUgTBWL)ENKSa_3lL?nEml)qH=fkHPvbh7x!l-z@2HxzV
zdJP;sk2t_RxOdHmW{Pp3^~~Oo^<y{J2YJ=d)T}sH=L9USef<t1IhQI}jTceh0+~G|
znG_k<Jr;%%<dj#PMRoaZ0{J$*qaZ&(9JD6S8t)myKN|xyz-}p4=2IXDrZ874qzq}c
zw$F^FQpBk)jbpK|+ujXZ(-Xwoh0^UrrC@B$E1Se$Q1Y<7_-E}BlZ?ek^4^(i9R+qt
zBj<JUWNtIs!QR}Nn_;=tdgDk2RVCfs!3z6$JH1YszJFQ6^t*x@x^_bnv-)z8(SvlI
zLW5#%ITVF|TB9>uF{M+<Dt8X_(O_xqzeN`ocwg%G#Hu;NfcEwodEqH9Cq>wmSBb^!
z?tW~L{X^9b_j@Nhfc12eHl0pIWbL!ca8hJ5<}z9XM|K8p0oj!Bimy@m(d_#K0Qkyj
z<Cx3i)UdXDM|`L|R#Ydrx|^dH`EwR4*)?--7?&gCnm=WM3GtlJ1Oj=x03m=`%R4_{
z*g3$kTr;4|pdttO6{tim_9&J~GE%+6I@H{EZVbU@Z<fg@nsC}?dqv^ecEA7t2N#Vy
zxZZnY?4gNVe%(WUVyUQ0s23p_e4~=(INO}e8iraxq?S|?Yx|>(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<ma>}Y?Lfcl#Ru7tjYyf2e^Zl+hvnE|
zRoRtVd1E`rHao9$2{5WuSmO0ufARD^x$~VErL0_%<%j5ECKEBvYmjU&1$av96yrr<
zS9@&BsYHe$a{l{TKdYlWg<an%6~i+IZ)iWp|1x<o%T-&wNRhc7%Elkylee>Gg|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<NTzfEm^7f-No()Pn6gaEoYJa
zlkeYTO>^cJh+(do{G2gm8Jj#Cg7Fvg&gzdFBdJYu6lieo_{3<^GutWWJ<X)bOv@$N
z%(<(a2Q$)V43y$R(AZ<FPBBPjZ)7;m)Ote-HzYA=$0h|yv3bJ55j^X|8v2SFx^tgn
zE+Y%6&P7T>#k6IL3J7pDUqP#?q;EKaFxtu9==r@id~BKYlY1waZfdAIGSwZJxFD-0
z1HK+nKSF1<CQN^Dt^wn&Moza#(o%(mNtmYG`%8+o8JsL!d3*wRAuB0o%Tf|MQbb8N
zL2vjB)~b-pkEqP<I>^Jbr-i905@<A?it76D)Akc=Ba);MjCWM_?n<k~x?Zassm!~Y
zFL&R*bGg*wJoO%5u7{~2TA(50HePip0sK;W6y07=npRIAD+XgG-&Kj#b4yszE0Tjr
zX^i4sRlj%R|7;2Xqp>B`?DKAVwr*n`Qqt#k#wDq<WN5+hFR+UNZHOX$DQo$*T@1cq
z+RA*V(ql<ran=m(QYRu<PXGWi@DZ)oVWb@5o=MMdQ7tTQk;LYJdK^=HpL{~it{j3E
zvC$8jmm^q*)Yw`SB&1XX_Izc6NR-$M*w<vIRhYPXS2|imjh|~W@qB`qKHbtlu9}t3
zh9k5tktsDwR`l};a{zf6h9yT;>jU^vROLo@j_<uV1mge9nv}0L5}$SD?6h44y;@5y
zSBYEBNRWIkanuwiHXh3Hr2zX>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!FYCzX<h`m
z^(pZ7A9~3ehFgu`CH3pU*sjheWS~N!D$y8J5_9a&kirf)&}L%ujiaoO$mKvmEd((f
zV7n+M+N5v|r?enH=N#1^w-*)<CHcA9303v;+Y3ddtN?3U=SmQt%X{RBoj-N?8#&-P
z#;Hp*fAC@F(mzr2yn|{-wiH>o;4!UJM2%6LNm5hXtwS~!=0lafQhw;{2%`u$xX<rS
z*)4q@FUnP!k*FSzFY}Kem%^E^TG!yG_4u-jYRG_J2Xu}%mbW+p@LYNu*?D^B$Uy~U
zr%!wKSw3gitJORoxDwS6nxk!^FSIR>X_X4vE*&vjpEQIJgrk~DuooVk3l8cxUhVB-
zzbaMgF`K^rJW0q>b6Zop^7J}(M}wu4v#cw+F6v>ZTe5Nd#Td0C@DBZIXy&-NQ>PtB
zV<QGrmD`1=ME}PmW$3vRE>ZM6_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*L<pSHm%OCu!
zN)=&nhC$sr6pna@Y@l?O|MZhI6V%B-IKklSh^Qw#&;BclGy(ciG7x7Sk5PB&vZBLS
zwKUL{d(s_)Gfyz{l_g|=#b&#NZpr?65Dq+)??~xg7>r>K_q8>rS&=@$DGQh3;NR%`
z1&~8l9(`2qWMxClxSb<1!Wut?EgLUQPL>&>L6|Gu(`Ogv!&*w^e&P9DwPiR<NNg#W
zLmLW%DHZ4G&-I+W5sECG_&Kk^GtqmfxDPS{RBZHNMO+Ys2?$K5yA0-ini*ciOz=Ev
z8#dAj_-qK<+ms>isVw<W@H$vpdMM`k(rV{>U>?sw{}BSJ#UX(|Ek`#qEF7nOMW{NZ
z4W$HPV~<H$3#7w|n<a-4i^sUxAVbyJSV9YAH^{?Qt_*kBb6c2ExVBB_O5XS_U=Toc
z3b5!UW2$IGr7&)pph1u9(q=MUdWsidYA568yCm@Qj%_@-mZTC=V#f0xMm@zMc!ou5
z?vXdW^yV7^iUWZ<aEe7`TVNoWY#VOTVNe(RvC$pO%^PBXP-brj-Ro1;@@017OM`Z4
z`*JU>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<J5!tNl?d4mZa5C5%%1Cb;WZl8s-N
zAdifSzqNcW>~Rj!Y#IiI8HBSzlnyL$t3CbSDFqM}>1?+c3=mj561j9=6`ZqPT$C>G
zxg>DVFC4%8{JVSr=Q58Q{Rdroh%G%|yYq<T0z^}|^2_03YfGsCTcbtmkyPE$?6_J+
zd_T-0ZLQGF^(Q)N!KtSs%+I@>%v8xRAGaiPPOK%j`HC%!mP{}Vu|JE1Y3BxQi$8Q#
zi|0<HNUZ?R8gzA@{=5ElKHB?mig{EqCwM}`voSv7SWC_K?fKoWjS}(I6}@Qy`i_<5
z3v0MDsQQ~b%=(Jyy3qBl6wwx{ZvXOqZWOOXczd|^*q_2VQ(TWH_+sPlDys5%hC<Mv
zfpL@D&ubXT@S_p+48Ss8>?^F4@|NE>M`rw*Pt{rY@*M%JV3N(kH^_Jd0@Ii@F>weP
z<UOjdYG4r_Kn;YD5N<NP*x}R8`QySN(@P>Fk<MmZ845{3s`H|cmIcb!4)`oui9h~3
zgsUGt8NtE9<Mpo7@hZ=)Z@&hYn&)QjZ9Lp$bj?qAS)p;kVWAkQBL3WuSWeYmtrEVQ
z)9k$nWsNLf!eQMxER0<e!vk6sI#E7g*wWX|cjSVbomjlH_(DjD-fRbu5VO{O3cB+T
z#qfc*aG-xHay~GRLN&hKIuDTRP0qKw_CfWXUTD*Ezl!IlhX1y(LcB<G?R@EW#A9$y
zsJgz;H}@bxb7;?4S&>fO%Q>Xmp2oKnWlj>xNWl&G;Fu!ZZGuH2K_@#eEuHF#O9LjY
zq8M?oI>*J}U9LXYu%>+*pWiRuB<pxj<gY1jV9c$LpAKPz+;`xD;T|PpQ6Z4QlwV%~
zHQIubRu8+baZVDsGSy}y#<?lRm#p4@AofH-1au{fiP_f)I9rgxoUCH6>WWmjMNB(T
zY(qBc7jy9V>EBPl4J{-gpgAxgqy7vkdyf$m2!BHfKpNasPgq2Li)UJ7K7<I**#n|w
zNG2VAA-4xQY6c%^GKD)tu_4*GzckWee}G-VL@Im({u}mDwa+r^fBxbd_ot%%`V+RT
zqopFbCW!B`fBz*iAiL$<;)Xch>uhJ`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#SCG1mokwi<YytbI-QwgDiJo?3+wH7yGV%MI`m<2?GJk6Fw+?jE
z_upZphc03ziuE5&$ic*|<Btt>5gjTWDT3JgSpqTAKoIl4?1Y7O4_aw4a(oyM7(eU4
zpX!)fI(bcltG(ycWEi49)w!ygCI{YiSioay>;{U+bk9IeRk;><v?7W}8elI@Ez?$H
zvJ08KbG^0nw%;q><A<>je9H4G(6k?QmnXg92zAw`T@YI@TSD*k=I$?C`FbdaZPhFy
za}qsQxDhRP!%*>5^>P5ed1A&xSD4ac%YSIg?H%5nS}ZZdiAHS1A8xaoH|wvWFTZ21
zo)dQXH4?3v@?78H<v^hJc!Ku%H!JQ+YqAk!d^b*!a*px2U-q(?|I^^Cy!(8(lt~Hr
z$&QA}6Sy+;u+^GGg}n)kqJf1vF=~-~z#ZmUKcagP-P`PR#j5D&r1|DOj=i3B`XuaY
zwn#4@_%?lzi1oWhkuE?2tMCFr9kE`OcNX#2W$;XC86O>NR{HZ~JQ#CLa`rAZ<5r5_
z);s_b^+k`pDh5e<a9lnWdxj=sO4P8=3UBL9iHWcF8lpktkVN)7!azLx7V_9kPFcsk
zpFioegAgAS5Jp@0_+|)|bYO?M6Tx!sJlqtrUlgiVpD;Tsvssgsa}pw3Icf!`=`7Ec
zr_ZcKuUI$g?#DTt)nAaaHAh)RMyTvCe!WF7W%}&ty7+W3iiS(G1Hlt<LeA&!yX243
zsI$ERA4qTa&LuGC<o!oDHbYRvQ|e;L12wsr&s`IxZ1LHhU?KIW_U7IsiWY4QC?#CN
zY3sI)?D)^#z-T;=QtN>iyu(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&(IAl<Qg5x1o*ZF
zl`bBpo9fULbs6_Jc6VL5#6kW~p!6C5J^VL4v{CVOmz*`0guLjEak+xv#kBabN-OFB
zTv$<6eeOjrK{Cm{=h<2?)06+xtWV2+(P1_K6LgcgK&Niylp3v?c9-D$Y_&Fp2p(DB
z=9iA>RojIUjt%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<fTOCJ55mFabE)7(6L
z$&nC@;<b`UWz@iWTRDRJ@r=tQB6}kWT_O-P4y2ehty6+z*@h5`TC?;j*J$%ij@3d)
zEIY^fUjsh#8A6ht75&%X(eTQ#^(6nWOX#|Zpwg!1s^4J_IMK5zK}|`ZUlNHgAzdbT
zlwm2;l>(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&<fN&lW
z9u&J(Y?VPG!I)!Nn6t$|*~QCoa_zr1OJ>6~0!h@?YH@ri(?2tP`t#g>nMnw*MGvJU
z&{Q9MT0XuiPMy5SvE$<iPjqa>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<QnyI3)^8+C&7madPO3Q
zEQgC<^@=ru8{T{TH#N)lgm`QJ9N-WMbBG$w^*GD;=?X3xP$uk&-gKq_Db60Zj(}~*
z{p5sEhAmo@S1khr=S*MRMVSI@usy{9)zp3qn!5L;9a@0<xXje(2TxMHMOX|-!KOy*
zXf;rBILacg=K@*=F8$KqN@-}ev?jv1b(-}sA9dF`dd1OF{oc1;X9Q?%?D%nvX9JB+
ztqs7;b!)_lzDY#}CjSR?&ty8<nmVVqfk^6oL*P5cQiuwciFr{eVNz7lll&2zszrG(
z0DOHlg@3Mznqmur97CH4<|_N1?q6nVas)ylw$=n0k+{=OidEg>`}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{%z0WqoP7Fxp<S0&(oMkO{azMnM<)$#_=
zzH5$Us`!Fk(h&A!bTREGrzSV%%n$EKG3<*}M&`3XiOv_)fmJZ%;G?t{`<eVbCEiM@
z^#>o0H#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+zYmjqj&#x5MBOhj#$*cTyLv9N7hpf5BTyBQj-^t8i@;M&
zkjSbR<Cg(jm-o3yI>3%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<If}ZC8+7UVc?MSB%bWtGQKk{Avvk`o=Yi;J&+qQv2U`6JNuRB(RBB
z6aP*{iVDfb*0bIs?@N}oeLPR5qtn>?z2kgiX+m@^I_^Um`<A0ndKjP$Hu~t$D^Sfe
z)YUi5)x@7l1W1<z|2FlTVh2sdQqIf2S;LJ+(`?pN&1-<}y(jPkLE=5z*&2IKRa#)f
zz)=XHHRE&D9>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^<o1
zODM6sw*B2smy)zt*HR95t^~1cRW;wdd}wTB(cMhL$hn*3F0%q^9rz2-=ZB@cU`&pA
z$PV?`W;<!VHOb`!y;4Z_kq{5Rr|ZoDB8om3Qy7C7rGr;&pI+1pnZ`546qc#|YJS$3
zkItqgj~eCMsB;;Q9aCh}pSlwHx-Z5;$TBuB7|UG6w{Z=Cv5#1xi0%lRnd^nr-{kCU
z+)CWilyoPWXajD6V<(by0^QQWeNQS6U;lbbPw8tVIzG=I8CCJEQjObPGTruMuG#`6
z7ZXaYJ@?`Q5XX>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*<E6uvs2_KqF^F0
zJb@o{w1zZSVc@(xiL2zZY3w^7ipVTbAuZLzgBDVL4P^gRcLIUCcSC0!48IFf=w#=I
zhr8qynNjfN&pNfQRBMnIDfNxL!2u3lE`uHBoI|TUDIZZ&irkXEsQijAXuB;4EW1yO
zi|8+*lSsW@so1%Ntbk|A%ubi&vr@eITy~tSQBZAnfdJ%8b~HMmk_ZDcIm@CkUfH3S
zvG=)q4~mgSr?W7bicx}2l&7#6YHqGBySD6*`Xn0ObfqCZy0)6aX7jFd1`#)t^gaSL
zpI*Tlb^>!ffkV$HnDo%#Iu@Fo-d<FqmAx6zHDLi<X;8kv!4Hd_)}F)_V_8S4om9n%
zIY)2UeRk&zCsF)MH#6Fmbp`N5^yxA(@T(@UMH?dgRATbz+aI<p6|H1o5x10XeBpR|
z547Lw@MNucP-Jp4o3=?qZtrHMp#}u8X6(3jt86Dl80Hc+ovu%@Rcm5hxOT}~@+6u0
zS`%ZzlY5qIovr-NG3Vk*mcK*&0BXNb$Qy(|`DJ<hz`L=Z_&#)14BJJHM-CV)EL|Ne
zegXFGM47!E`<F8_Wm`$r#)$N)WN`JNu@%}pX}O^UG>Fa%FwkCfHRA+~3#;x{Z-?>e
z5f$8<?CK+s-Ln=HWeamoC??c6_`Nm5>T9KahTdPiY8E9xR4dn4v6jwEXWb_+&tG5a
zax%_xf|qbY8Y?@P02TI089V^H{xK80C$GE_ZEdN2HA%ktZ#u9;vm|)=jU0e|7kGmu
zJBag*TZPcP!4x<d;t<BGFtH}P`Np@~k<NSAE)2pXj3rnu8Co*Mptf%jL|3HIdTfqT
zXfZ0A#uf1mY$P)xTaw482IfH*n8xFXK&zi(i-2`ytYErmm`RY+_L^2n#3DvW@?86g
zhm_g&2(RMb2_=x`0$x5323k~6EvZ(5z`8S^PDuwhV0IP|-MPNH@?cR&AE6TaI?V2R
zVu$9Z>$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@<Af%XH=w?ZZP+U
ztVb^)-wkn`ORJ#*{_(?}+w=BUCeX%s27(bc$Be!h)mIR!`MMftbW_g@&9Gh>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?2Z<lF5L`)dVHnnjt_
z7b9^exX#%!zKTk*O#mZeK%c7D8k=F}QOZowS(q5{ghdk~;_nh${ueX|(SQNE_uT1n
z*l@mB3Yln>l8NJl6*aMJ+(8^9gZ0SKx=vQ;)i%^z_X|SQ3syHez2q?OFs0p3EJP=&
zsrxb)C=TCtp2PobQILEEq=M^Os1yP)*Ng&%!!yoXw|`NeTSU1M<xp2@+^WwXVQA&s
zxZ%(5{BBUrqDlxh1$fj(0n%Hx^`hzsel6Muy6Ud)0>G#hOg)i&8QaRRwp~<eO}WT5
zMDAa04x%*o`4BtX(+iX|O6ht~f<xH1Cy25#IN1nx?s@$?CK?(u|EneKLBn}-kF7Zx
z0J%4qV)_vjx={oYP;(?VV9|;lY4<DVhsjf7AnIRioTuk3-?`3<;?IOZy&m@fB?J?q
zSlm%HQ&g3TF%;wcIs+&_g?x);73koPTG?HNmRM?#+r1u?Vwmv%M`9co=<m0%&NLEy
zUTG3Ku;7-*62xw9;M9zJ%&-JQBA!2mjJloPE@8zodhf*(6zP3lY*MGj+u5?4oBW|t
z?C*8v{S{?bGsw{y`D*yPX}dolYua9nqW&8dD^N`ghK4M*A>Z^Wh9K}#OnrofTFDnx
zc1`Y%o3B|Z=`j-h7nr$WRGJDj)(hMv=@#=uL=`A%IuO7;`p`@S7_`}5`4~##nRqg?
z<e%W4y<30;Fudj|<XZiLJlv_Du!y{zY|Vhxca<Cr=m7TUM9Sic2k!bN&OuA3QD_)t
zDWeHPQ&d}r;Y<M8%~1^j)oc?x9t6{p+P3wcRP9s+TL}M<^<6vdl)lM_S30!GEQ~<H
zv|-V}MnX(wK(2h9F^^No+;{X~unU2{$xiZcvb+{8yd8s|+F!g<c(}-FAM5Bpsh|@9
zzt%OSSeP46KZz9EhUku*EnM3Evlm5s3APzh%8KPbbPN1)L+!T&Z8>o@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<<J;f$r-)DamX)pCx(a(-j-fa0}(F)gQ
zi<{7bm$Ms|hApr0Z+jfbcr%EZ=}1TlCxwXQ{wl9m7m+P_{*cOFMY~m4WL3d)OS^Y#
zl#AG`_cOTD)J#B*bd((uaB54BqgJ;N8|d<7wep$U-|9Wum=9ARI=+Gf(eldePD%{D
zK9@%!seq=10(jwj%{sZ%$e1aUY~MHK45K+kt-$41ROPo0`bvDDSBI>S;o?No&tGqi
z#-k!pGo;zcg))Uv<vH#i>eh73>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?ur<Ry%gvJ2D<*bk}`+Xn3V`*D?KXOUZCiS&q^jr;g46Z8<DBuAmwAS2>J5Q
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=d3aqA<wAlF;|6ZwHIaxG<6QWUr>x{eXiQ!V=L8GT7P
z)llW5e>HUqFQeL<h7FM`+5L+7WM0$jrNNriJVdz4H&1D}WmUHBZ|%@xX@q{kI5`Rh
zOiQbNKg;u-quZtZaZ5z9P=`0Pb`FqJ$f7u}u>jxe4j0+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<#zepa2pRVwzXdxan8YpaG9u<WR6$+R!P$
zt=?p~r+1N3Hw24_iWnGsr?MN)<BjpcITneIZ4HxCZ*QJV*sRs7ba$6&6x`p9Se`7N
zjGovrNYrBgc*+YlXQ!aQ#lhL1FFis;wbZ&_`>x)K!%c0QR(?&fMU2K*C<NU3!#U;B
zu}8O~#s)+UThFWal!$B9l#sUGlvo$7p8jwnF^_YVYY;J~oy&jAcnf`;%|y=?1Kj(3
zLX36{2HH~(XC+&kM6Z1w*0}e{@Q7pXJ_FPI5{u(o?v9cHe}J}Dk&LR_rpk%g3S!!j
z7eb6^&`{Df9zvZg<2^hzx48x|5#CnPUrTT=vL7xuxrjcZezbY@*(AnS&e}PK#ojd9
z5}Z9mggH|ekWg$uFtDHQ|8hFj`flbze_q6^nkVzn)wFiMD`_Aaak+IlKMyo4AM{G-
zJ(8)Uacp>A{!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<Fibhs>
z48v)p<g<R^_5{bliK<4FoL5={Hu86L3q=NL9bpDyQ>$Z&n#*x`&6bXsAMWFsgsum~
zif<5AS!$@=*6T>H(tgpZWDei6t8lDta10@>Z$VhjPYYpT6NhuXhY5ch#H9PHUeZM;
z=GnU1KJDRZQ_<eBH4bEY!W7V5(duc_rP`PiiLT!vQbJBuLFbCn(Ne1>FM_oTd|sZd
z5k9-bo7jk2=)~cw=s`-!6w<m}xv!HcoFD!o-aD^4;kaHM(JbS)Q>EudDyf&#jkTVJ
zF#sH&VvtNy<@aw`E#pKZK9KV6yz$)oW3x*7SgLqTM*|r#$Uc(X@~oDxZtk<l?)2tP
zEJH)oL+<6@gbX1xwQL$?ZRi$NmM{@<Z2qptx}G=@-mv$QnhWru$`tP8>P@I@(Hp#@
zf%PnO$#rJ7rP^pM?-;6N*)P65U5-~Poh#Ow2~=6xa={7TvjXB`c*{<?Ui@$@wZ|@f
zK6i75Hb(KTD;IlCTh~_ZqFZd6qxJ#diWRBSfsU$V1-=^ALe15iTM%!YibdOM-8c1a
zz0)-N5q<D}&_-B7<7h3&@IosOUh?afSF2Ic20;iXO_$m@(@#=P>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
zhD<Xmrb6$~U`y`Gh$?(u`EmDupjNU{W5x3B@^EPN7N1>fi1H?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=@T<kh0s)SzpeG-X)52tqRCLE>t9
zVy!s5kR~?Bel|W&zx_LSv6Pw_gJb+p7;H@s00zt%PzUPJm>-u3LFNMjU~vf~{r}NY
zk(uc;ODXz9WAP&T!Hz_Qn*~aMVTQq4*<wq?j48T2DVB~XP4dKjA$`4Nkm2?f2c4lk
zXvaO7H3A0RqaU*{cXx}HjVS^x1Nt>kL{@yaal;QFqt5+q_%Wm;S5!bF-2G%QHhLAX
zDhWaai39oRLjUBW_&&m<`62dVbXa9IqcbB!DY&VeY)APF`5Z#hCyLk8J!%@Q<Ott@
zyNQjA-q;%64I9M(n9RcuyJ(~vdqp^4S|twrcUUea={^LovUcw|btw*p*hD4u@5^5H
zjCg3|lT5TwI8M{F&}vaqx@u0J=jIFHd<+<ws0bLuHUTq_`znMyMsTk`>R(i3wy!V1
zva8IP#*8a22q{Y>JTAc85oQ6!Lw7p$ykEUH<iiJs+-~rr6AJlmc;JPh=59euN;rRf
zP!o(ad>`8$(mNS0YHIH!kX)d+l5aLLO=(BpZ@xZJTCD16>^a;|XX@6bKI5jN@Kt4f
zdqzj-1dWb{<O@bGm|3z^#3UO@&mE3$GC0Hrs<{OT5Iy%EzIB_BsDd?LDq0f?mVATD
zSGASkp+_K!yh}M4%}cmA#rVV35>@yWv>$PiwK8E5MVo-h&)E<aW+A{Mz#N}ou(gRf
z$N|g{08Ztoc!mAsOkO+s;}B?G@Fo5`>|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<Z9cPopfP;%n&y8|^^`a{z(CYNtt)u`l#c5drE8gtdk1C0SX$q|{NEOcxVf0t1t7
zY~z-IYu^stdhN|;s6EIyjf-f!G2y)n;?iQMqvg4(K85(@Bs`lbfRP3hU#H^N5Hqn_
zcCC^BrItu6AKeNsatt(|xr2+y*4?!Kf$o6(b9DJs$UW?Fv*o6%3#fncqR`spK^WHx
zH(yGUce_U%75&kiOjS}`##H|gAR<9Wp?E#qk&9I<vchrPi&C*F={!(&*j3+;jb2xA
z3{SkRAKwA<q(;lvIA^P!+$!}p*zPJ6bcjen$cytGBP#&-SKXyyn_|bc&dxL0+$i-8
zHo{ooE^J(mhW=MqI{0LPsfICq2e=IoI6%Q!?b2`*ZZ5uOnjs^Xj`|y8f|}BNZO8F$
z*TQYAjdAV-ZO#SI03M7lVx4ZOK!CRshZM-cIf+g$$MM$c1+kpAM%J~fH5ZBXuj2E_
z`TDCkyNF(jqD9@P#uO|}QZMJY{o$oh1rfyrK8wM*haR!EB|%ug--A8$d92n@E6$)V
z;xK8W+kIV(i=H^)AuG?aVL#8Uo(Q}`OUP6e3(yJZg*r4L8t<&4jA9vWa%UeV+Ne@U
z*C#%iNg|-Go&5iAdm*Z)o*HDA({lm4<lj5o^~|NX(<1{;ganfY`^j;$jHY|`Q!kh@
z;N$|SYNxYlfGUkeTwwz8Sp@nUTl}XWM(y2Xc$NC~cYu@&GO(U177ME6^j}Nh{R&@#
zS<JC+Hk*4y-C<B<e+3(Ny_ny|>$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^<FZ_FgU`msLP#2Bb5-k
zgO_Vw7`M{~;AG~cp+zMceE*pd)=g+~((n{v>$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(H<E#z!9*0t09q*T=VOa<4+`uWxE|
z2-Mn{af{5{xnl;HgO|U*5dDm=VCsSa`<08^>nRo!_af<b!!AW6JqU?Loo-OY+P=;j
z$FgeKu+*Lxt#fJd#g>9x1_8<z@lA2V{Z~s@HiWmzrI#_$=dc&|feLZ9oF#2VfX`O$
z9g`#7rP<P?9_Xsce+e7t>5U|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`JQS4b<?
zIjzUIg9l!qEzia+F@p4U#nBuYq%Er2f=H|*wPtEm?m4D+znJ|zp&Oc@sB92u{S*%R
z4zHTvz{TvuO8_=CV;J{B{aKZ_-uuer1*nFMOL-zgrh1v*2r}u#fIgL$R4dxN%76_d
z8+Tv~pX4psZBiGj+D>NBs!h{wB~~eo>eT7Tgys;(!|{!BmoY)`fkE%z4k@S8RMQos
zSw-VypKhaYx7&@fQ9OEs4SccKCpB4X+ORi|u?rUaP?X;N?w`WyL$nr$TmzGWVmaT2
z<UffCpFy9HpLj5;{XZ2;)vSNXFb2SZnLV{k_&1@vl<%Zr!5tNedhVB8)QG<Dowa92
z3n#gUF)_bxC-uFp`0q-u7F@zB9Rb6+TAwW_Md{L(&7v*LWR~TY*)t|W{KWQ`E}%$M
z`%_LPDTkawm2^1ltA6}RPE=(l-WpGgDF|C~J7GD37T~OAg21^#TCw#b*z(fbNG)=W
zgdUtbV=~d|Lhc%V?@+9t<0i=$X{&uh9BD_ROo>vKJ%@A^1A}DQ<?DGZ>AB?4*6>j`
zhapKLKm_X-NA!9MTJ{qh(7}yf80_p&Q=4_nRicysf$~?qT?mkZBIN=fUf2<iR3-JP
zvTwIZb;Y0`tVnc#(gvaY6W4u$MBVB>?#-=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-<m<3EEpk8$
z)mMLi6Jx?;-se~6CCxnHm674hM1e9WtCe<a(N#3DyQ4W@6d|l$o8E|2=QJhTYTZG*
zagv$nU3=Ama^}ZH)VKclyP5ioMFfMk3$I>5Rrgg2gX=(ug&_3LHd?lzqGjx6<o`?V
z#a$U`g-cHK>c`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!<zB-^HU1IqW^t43n!62+$^919!!lXC`0#gcaKG?Zzqp$U
z-uGpA_2UEbvN7{tdXXOp)f(5d<N}TXTxwkcAxi{LkAN_+j9=khYf&s^Zj7W#9T|C-
zv(AfMREVVYm|mmK;}Gue%KTTdIel0AheqA|+{DCuwHy<5uA+jJM8tSH=%;kdkfqbF
zld#-xHqO7!zehi0g*yz>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#<uH<$a+g|$f=Ka8);YV#ob#1D
zNTA|yfr_wAh`ZsNV@(oN!}aw@T6de!`~9?&HmOEcxH@h_mV?Qd1w;SzRX`{7W6&S;
z#6FTv+(IW&W0cK>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
z0tsk<cE6wmy*<a^g#N-5xVLw9F7+WQXIBZPycPWr=Vj}jXCu#|5gN=ZOe02XZ3ZxW
zD=gsB%+Xl${B*exn~pt_S;-x%zrls&k@?0^TLa-xWnr0yjsn&mb&@2yFCeheMFls7
zUhZd(a=~AcJ{5!Q(2(m)&Oq-IanGcpAC!?ybeK(`jWXv>V<|5DfcSnSE!6k%RF4eX
zjQwvDGO?S`4|)Z6MDXp<cFtm<)Q#8;X4?(CahNdlQe4Z|l2C-r_}e|sNi~}j;?6{y
zYepAN?o4-=>q-$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#U1Z<KpUvU!w>E3s+aG%V1_TB!g5u(yFQ;m@uf<UP*e_vk0+1?x5
z-<2&Q+ztnKjJ`f6H~^tBTnu+nA4#b65vI>RN=oDmJ3IPk6lt@6^5%*MFGwL`4~Q7j
z==4Vj@wJboTT5LsFKSn?XTufj`H8qQ{lo4wh+hWr<g_OKL)0QW3g>;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?(z<O*QIgp!1k7nH
zsmO0sY<O5-J!V_REgu;0-W%#<PK9#27W??|GN+GtAwYaU>y#u+{G8C?t?7$WHJ1+v
zy7Fpo720|NYok{iJV=nwtk;UN^vvE!o1s@p)b~AvJ{o39G#T7PR0@*=_YXM0`SJv`
zmskLBWH7MWetFL@>KX$b{4<B=sx5V1idJ*MmUdv#9a@@=?|9T1gAxV&q4yxCi5eIS
z8PHID@%Xw?$MPM9Zc`<ff-pZ6xq$VW`qdml#!3+~@luAX4Oe8^cN$lYyJyb8n1wtR
ztVbOtXtuofaIH9G=%!c~_zLam6%$2+87hb$qy)rxEL|Y|BeJq!N!?l-UixisdC{7V
zp60Vbfony1d?N9KTv{SSCn$+KR*${)_isEnDME0}^{et}<h0z_#>r5yb(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<LIclDhMy!-
zk?75%WQPFiEa9Hk#eHiTkvE$MTrBP&{p0vW+SH$T+e-FT(S@M-_TgGOfWG-0kmnOq
z59F?w5w|dc3=TyroO|L28R8M4Pt^knxNJ9_a~F6!$11w-XYKjWMkBnxjNJ%oinh{k
zoEsfvfYR?~-tUJs*u^>`!00RG?c!xzgS1?`xo$|L&lEEUC}&Y1Xza<CM=0Dzliegj
z0uz4hfd{tlD&^=J%^J!*kb!u%a2(>A;xmUU3qjC{fd;d`*A%>T?J7?i&M*(tI`qus
zsBO<hqNACpc_j7@&Ll!1$5&RQ5(<9Mf>Y`8irI5))`@UrE0)<T+B`NY;D7@z(MOul
zruswMR+N)d8c;oMchrzY+Qq^8Fpy4DqP+Cc`}ks8Q&z-x;*C(RYqCnSDl;wkOX@cD
zN~0T98{*wOOET_Zb9E;~vPsmQfjp&pN2?{$cC=|b5X;svx>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?pJ<eph5i5GOk8d;2Z#So4TmfWEE&x>Z^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?<d4V?<-a!F0e%@bUeqbEhZNleZSl7wnvz;Fp3$S!u
zOlLn?2{64g^hd;)GP<fc@vIw1<?^#%r_dz$Cg%UER4w-y%ipt)48%aLHr*26l>iU`
z03eqO#P@eqGzP$z9`ca2l2V~-UlfL-v6LM{B?912dys^xr&%V958g$L-tymjBakRQ
zXPaZGnPy>PMYOHurGlbnZowk+`<y3Aqd>zg_PiT&v%9qq>jehjcau(`&@Y<bJ&DK!
zqTH$DdD>BeG4)vq_eext^`>pM-er^J)HJxs%|$L`C$(wVh@6)!JWi-WY4^7v<7q_5
zQ%~dIWqKIV)-_7TzBOvRtVvIhhA+t_U9FJT7CchuGGC!RtDnQiiCsSkbjxYt?;!9=
zCRs$ksP<eccQ{?_Im#x5Ls1)^Z=CibCQ@&4Ub<8ezIKyqc$*>r_74ML!L0WmiUfLZ
zjnD$vK32h?b$9(qGV14meRq)q30-OmF6#LKx2qPvT!u<r$Yc6fq#^O#MwTQxRPoFT
zh&HpwUe-i{$lNk^BKfBCpY=g5+RLtcvQbMqo$e5Z^0Eb`R1y$g6_=67kTS6bCVLox
z^#j%SM*xK{*ibW9oUgNdL7=Qp7pnsL=|h9^V}!VG)wKR!F(Qe#v{pavpHuoZ>&Mnm
zE7XwJTwD{aXiOm{=H3mUCjtNX_2Azq=VG#{ul$|YrMn5ann7W?ubM;*CR6c#ao`EB
zo&i-ao}xS%50aD#R;Vp|<qDx7BPkx0{BsD*kT;tgBjKs5Ty4dKT6`Yu^A{@m$Qv`U
zB1JCYPWMJ6t|BSuNDc34z{}~v@f<w%j1#Z{RE)?)fD^up<QpS!k_(?#Il@6LP3Gz*
za|Kujo`^kQ+`Jv(L78q<#Vwh<B|PL-5h?`{muARQmHT_gg;)3zD3ox`lCUBk<35O!
zOXmd`Hp>WZRdaecRSNlI0t}qn$dOdf4$$gX42i0PcEgt@sKPQ@p&b}-O&N;;eU2zd
z*onOoP+_R>WjoeTnUPD%$61|2pgI$^y9>S<vT<v@j`mv*E`z5xiT6reZr9Ep<jX?-
zRUWaG0>EEEjy?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<;!<F|h5EF#
z(a|S;UvhJRj48BFK=T!kHbKpq!V@($7%IGQqtOzYdvd1$WIU|8%*2EI_1-Lp<|;R1
zQI9!t@<uw(7OJIOQ%p(?dQQ6cc4?pN{gX2sG=-9Gk=<ti4Zn&Fu#*4)0br-2OP8>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<vNsR}gfNrHtJDHXk<Ab}Qt(Q)U8{p#5k=z@frDiQGj$|H0&G&TTaBdY{=f>$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!G<j#lA3?6&a*4Y;}A2(HdYE496Wtdj5xcH_4n697BmW8encwYWJfPyuH3}
zy?ZPXPnPlJTEqMPa$^>BcZ4*?s;wI0<G|O`nKPjYrgN?QRk59vzaO<d$jmPdL(A+~
z<($wucZ1te3j=wjd4l|OI5m0-m$d9S@AV>DxtcLT^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-pfPjth<N}NA$UAWMg46FvGG5iSE2sL<P1D=QGX;T19$Im?4>h#Zi;J
z@{ar2yB#v>s-79D76Gkp=&}?v&r>%zr(rC!I9zXiAl&df5qZyTBo|(>FqXOd3&Z<Y
z0%qtjT$r1mfkI!5SFk}R<nttydfGp{l!Li0g=l|Co0`nBG*X|9>J%dq3Srplg%rV@
zp1YAV+cW+~u6VeRFp<Nzx?c9|1l2A~avH1mg=>lkP=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)*^0uoBUytP<gU^c55|EuoA#GBXo
zdVrhsX_-%c3`SuEFnDbc<n>T!EyoZJxe!F~2zf0dEvz0-QJkXrma^OIN~ELwdjz>I
zTsC21<CzYrF8`yAMge7B-TdaNMd43Ti%;^Ub^wGmQ{mH^G@8bAF5ey_?nP~s;Kd~`
zXzTw)lp1#j{&z6UIe>kjKCobZA!j{$m4|h>vvYy$vmM-&Zn;~ulk6|YeZVI_u027x
z*;vNW5lH?^2mz?KA6h9yb^;HVlaN|zrz<b_xh^^zG=+k#d|{;nJfjSk^*Q#W13n$T
zlEwb6B$$zH_c38wa#^*phuj>-Mvgbs)TGFsQ!-<c7yiG3OXbuljjrip7gE4F#><Ky
z2}VoEKKY`xs7r`2w~XS04qL>6N>%P;8+EsJQt7Ntz}nh7G9$W`&mK1kg<?e38VBzP
zF`-XT4esjmHP810{A^`o3zH1F-1t0@XG)jp3i9Q+?1o)w)5>=qoVC@oobT+IsY<wm
zRcbPk{mHDRQ)|+4e6b=L(L7xvuGB6j9qQ09BF8vwJ>16B(jNI>6q^QB@Bi>d4lSQ*
z%?HABUbJ`bPUG+lA-4(Pi&)dMGjh_k6ZTdQ`cVS+0j*64v=(p0GhHkAy{a4?mYDNn
z$M>P0&{rk!J3DiI<p@}bRB}mUp{&T`!pbrFWZ$#QOqxj6>bG6{|3G&Jvxl(E(39@D
z?<fZAmoL}L9guI`D|yCK9D*s&rBa(m{4>&ytv2OokR#`jbpvKsYg&@}iddj^UHOag
zO}|9jmw6_<z<)KipO>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!640b<ak
zZ-%|*qoLfp4YZZ6iON?PL?k77gxn#~d=?)2&`;A9@@cw?m`#2Tuc_RBWn9wP7R(>7
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<UGuyqRF_cgZw48t@@^_Pqa@DX`Pjx6Y(yYc!H4Qn2V?7*WEFEv~$-z%q
z4GEl$!)Hj79aN@pTR%}C!0;W0Ju3BxgZ1-qwVC;(3brG-`>%$i)1Z<r8=<`_OeX%b
z#v?kCAM>LW2@7q2+K%OvKZfKeI&{%AEAtZ{drEE@-IC)Z$^74&zTTj6$>{Hp*Q`+$
zMXX3!DQQ&hB}1tKg`mxGq<yA#^D{y6rpxu&PYpj1kX@q=-uoNSsT2aSoe;(I3oz~U
zMnoi(dwXO^R6<KC7X^H!DmiYBHG{=iz~4n<>o_9NdfRXTGzoo~Uo?or7|;MZ?tQH>
z@84)YihxvZ15YHR&TNflrR`3>ClvWr|5jWp&>yF8o-w<`!Bi3pXb$^<i7bC7HA!87
zBezXiO=B?h><s-TDm80wTa?g1a4=t?L5XYPPvq|Y<l${~lR1S^_rfC69-N!jqL28T
zAHtCdT6{4%rwRA)mIEqlJFewCAG!YEfceh`*6%G^TJX}cR6l4)yYxaRWvv!z0I5qW
zP+Zf|_UR96A4to>c0e&OxTGrL6eZOC{Lv7S4@nFYT#PMSe0&RaR;@`<<ISeCz_t1n
z<(X?Qg=`83=R#T3)z!8A<DNl7V?hp2dmvMNP9FVo4#~Yzg-3^vc-1~Yr!x#78-f!L
zUbsrmcJUp>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&<ATJaSH!p^XY#dC;3&^n(f;`
zIYuDk*d18ye#hmiZAdlS&c3OhwT&sg9`QeG<AZ0fcL=TUC*{y7aBe%qEZhJA+eOqH
zz{x$q922LVWj#>BJdJLZk$qtSkRbU@&&)O3Q?rBOu$$)TvmnJ**na9<Hz+2c<Emu^
z>PYl3i0uH;yo30x(JBzVX5<QEMla6st4Znfgdi`D8%zZm!-FTHvkM)puNwFpGq6_F
zqFauA1sYnNm!lnmD`PS^>Tv+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;o4<sNa)s3{If0te=?OfyF}qr+xX81*Gc4
zDN3M>6fhJQ&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)_S<YHz##)G#6?RF()SP>OK?*Dw?gvb>Zf*c~|xU
zE0VT-J^@mDN$@+8?M6Hb>=;@|cm@|})KQktp8GV_v*xN=o9@$^3eIMuM#Js2E=eB$
z6hLMSR3q^~L&c!5TJXtHOB$nXk<IU401L#wXUmyhBA@-?Sj-Wc`Ppx(Q1-i&b2`WH
zdflZM=5X?41WxW-^C!kwZ#6xYxKD1SB392B?#qrSU{>gh`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$8OlY<Ny%m8odi{
z??UP#Oe1|lD$~RzUeB0c?Vd^oVIvZ;!Aj}38e^qzP(&<oSApb(9e!E=2k8Z>rU%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}
zuSnTdqWNB<jN_@8J}$N)e5B_1m!vSK5U9g-v(y3zt^H1G#~{aQ_^{%#$uAuPs^y=s
z?=nCD7Yi8rumB1+YLG%j!YHm)t`#j{V_}Hzv2d$ZzVBW1T5l9#4I*lh<G@$2_uAP9
zQCfJ0XCoXs1Ve+Mg(~%rKmnb<i6d^f02TJC^ZVn1*A?1vGD!Nf((oPvBr(vGa(Cnq
z!N!=HK{l?-7JWyZ4$(mme0>rxiie?72mGEHCJV!+!b~?2oz`z)vwgMOmaeeszI<~7
z9V`;|lSTboYlrQu!*{QM=K?axQOMV355Uxn#|0j!ATw=_Ek1UvI}@<Zfq^E>l%@Zq
zH0^bTt`$>!Fex(Z(ljqeF?cnFgykfc6Dq<X9Hb;p?KIw><Fb$x>uKfaev#%m;4D#G
zQj(D@!xsSwIE4{b0abZQ8m|=yIQJO^E=_1(Pm9~<c<Jzezn$+zOXqz$Q1YnPQ_svF
z1Mp+lG`NvC_jj&6b+`cF9W>&~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-XA<L$ebjvh_2!B7$~=meT|Kn;gGmm#E1})$j#aPk#R0(ke(n
z!uFFiCAa~d05TqaEuEPL0-c11*9=dtHlMcMK+^TX<8q;N_B2BoN{1XJF-U^$`Q(ET
zvFP}^hT9=j#$j`vgYbDO)WuE}Puja`F;{ZPT54A4#MJjR^J@h$II2MXK<eTQUH5YY
z`b?s;D6!lM&4{H>Uw3fLW5fl&r(R5cP7|)%9rL3SZFx?F5cr!8y<dM>l8*I16KWBd
zQ*QeRJmv0C<gN0AHc)vzIO_$6q0EKZ+b=}EK0j#~aL5|D3(54WPFL?S#Z;(JmdfZ^
z@$py}4&vqRJv=;VCK4DuMEE=RK&FnIq0ETDg_uZ)O476aI*;Eeb1%9v2L4gO1zjEk
zbeD&*^R&#)w^_0IBC#eok3`zvaCUoC7Ip_sPUBd4HKI#fx4}h#YpaXH(3+>%yz-1q
zu^G0V;<UT!$)tflCG)=5hTaC2sw8re{z$9Or<*UArTInO^`%<(O3$4}=0}J7zN-SU
z8rYnJ+~Jz>@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_<pi<?(N5XsyWa*#7%M<^y?LyQj#0x9VyxhyZes6631PJf&NH
z{@x1_1EZxDyXE6Cxw#R`!kQnx=CrcbItTUrnJB<NB_q?O32kS4#II+t>$0GG?1rny
z*;Nc*)l8W0Pt+!b>*<(BJ?z!G<OW3ToH(8W;2}hI5k1VrW4qQZ^EA>T;Gzo6hY6bO
zBE<%ck=FK-8wL5%z87<BWi&P;_LpWnZpB4x)<<0$H6_s`IpiZ^gk<pVPem+9`RKKV
zp;|?nO?CTiY&#>XNuOLL!@q#dqv+;^UKsn5f=oS~Vp2x|?MLIV^N&@f$zcm?p}y`L
zU%rkW<SIJ|pXnINbCQl4WnZ2(K};F@Xlpw+J8v5|zPTzSIim>r2o@DuGp4DZn2|!T
z;Ece;q4%S6HrHX4q2p&h*(q4(&|2P_hFQxb=iUc{d<P|5AqC3yqP9{9qG1>Y5D5=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+<MNuES?iHrJT-sAb7<C2!C
z;d^I%Dxw&u;!EaL8{MOFEZ1#nN4Dq!t4|AbU?dylhbXi#vHOVS+0s*8sQh=lHdTrj
zy~jLAmiq9tp*}GN980IhQ1V9EmIPk7CqK-K%m35T{Y<e9T}&Y!VK<A_mp0we0I}n>
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<z{?~QNo
z?mpT_Wn81(b^A~nh2sz~l-Pe$E1us7|9kW0$6_FDiau{mnXkn-MW%bnVU-)b>^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^{s2VPvzMrYcRnr<rF2j&)kE;FfkBXC-Dn$HD_6xJGslShjG
z%C6{-$F0s-YqwWA;8u_+Rv+nI3->bAdvE7M2DWv>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><F^{E7=L9wQF-W}?OK9hWW
zOedcZe?E%tin!pPb!kSb1>mC50Fj<qLd1=X4xoQcbk8&%E`!9@%yQgCPdPXILs=_8
zKQ0Pk)JP?#h;Obtks#Z0s|M>cKHnq&ju1MbnVSR~*v6G@8Z6(=`|7`vm{Mf(pIgcv
z9K!diHWzf54@FCx{oLyu&ewndFIXu47Gc^eIr#W$pVL)j?cN4)=1ckyN~E<J?R19j
zUUCp{1T%+0`%rHM+gzb)uqzQZ8e4}+i4Zx@_!K;P@?o<Xv~;cbM8dbP46Dz+Pi9Uv
zQ4OVa4He#nnhE5Ek1|4AiOwi`&i5h(hTV1$YbeG;4G%nGn-h2YwRbgb(S!lH_J;>+
zhr!G~^n7<nbnki)JKINHYpCCKpaS;z2rSx_W5&kI=%~J12q5xCr6p7Kh?!dmm=w+$
zb2zFPx&2021LmnA2OsJdxBS8Rir%RQmT;>#jTB3a^eH(4fJStqG!i?Bt5$Yf-A&+H
zlEd%V4b5r;58{EbUDnY-MHS)tE>7{z#>yKQM{<wdBfZ@I@m~!J7&<6e(m{&QtUt1s
zx9(D{1YM!dRyjeOX$Y4qmC9BXQ3{OGANx>7_3<!39RiIq)3`E@ra=j=&q<qEyKPYB
z5rogtxpcCI^9`uMjg(JD1tQ0RqaW!pwy*RQFB4D~={<hY<2@*o(&_ODq_rWQO>9;5
z<Fn;t$ADWlcXI)rBGDg7QK5T79O$*6n!rj`TpU`@G|^Lwoi7Toy`r$3QTNTQ0Ld4$
zJb&+t9T9g&e!Ybk6i;etCPsYYP?3d^E)G4ZO|XSz000000Ym`&3h(O0!1jH6oCp9W
zTMC?kV=fTns~r&?9}L^z!ZGa^ZezUdHg$CB?__>QP9ynHWM15Dfz>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=;$Ru<b
zG;3Dl+FyJ>PoMTc6(=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<Y>%L#}*61C!6m1Tx1LJlJHHryWT)er{{6
z668p8mohtCX?IT~#vP3nJum<O?g{i10gMna2>X)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^&W<M3~Cg=i(C<rP?##i(1mw!7qwky%4Hr@GwMdPEa
z^npVeU7S22FH>Q}uPeCkRJ$Spq)JB!LVe{Bv_bqdp1uE*9VV|2btv3%=t!ejt&?2T
z8eo(KG|;}69IE=tel5ss_<+3KIYM-e8Qa^BKJT}<po_~?s^dotI8lSqksEI#>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?xIf<u&ydI<ODCwceXIC#axVAWp4;7TXpHeoRl7R*xFm(x;
zmoIe~X#!N2Dm0bfhKXx920AIHH)IL<$O^p7IHlq*HwfV>pb*WNjnD%c+9w0@*&r9_
z_O`F&KUo<?V6SfJu9`ZeAft*BMFN&PmA}NB=lGk3`RX%2<?x;)?>)Z2G=<nu_gC8v
zwf8vJO$yM3c`Iodp=RE&jVCD$Fbwl?fpoCORAhF#tzNQBO20l~_X2pR{Ur?B1Ksa9
z+?Pf3V~56&dmgCm<?7I-(!lUltq5J(2y8cB0K#}jh`3PqWdml5(N#?6>g1J9*EUw;
zU0ZEiOhL0BFk<e<eX8`1tm~KRw)zR}iE32*7F(-95^v-Eh$naA7jDbb{mP?pRA@2v
z;Q`<30RX-YJ{f|D7}EwZN*39VZnZ^9YwL$j+CclMf_=?^cPGY=Klap1Bq2H>#-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;Ubq<I!>7xpKA;vjZ9#{n|@0Y(7E52cf5SZdxy=
zBWq8O|JgTsHSw(w1e4XcX<pHSVd}UW595Z13$?sr{%tzVhNszl@}uJlSMA(5i`H_4
z)|0k<49CWk$Q*HMDfz0|ZDi4SA_9B{yo#%*`L=|s$fVh!4O@$cK_ic#ZUTOHVC+<T
z{s1>+s!hTyZtLD13}FR%*~?y!6T29CDT*{&+b}3J%Qb-KT`u`5kcjhp4D*VRPGDHn
zW{H`e6#8@C(T3ceY{gMlj!R4~B$gkxMu$O7`Fb=<is-8MSc`HM7_VA#wkJqY*qhu7
zCk;ZDbu%p8*1p72u6VD+rT}*uo2mdY9*7B8V@?NJqymNdIUX@gX!r+c-~a)M02!Dq
zC%_K4ad)qo&3^;{BSTHp7?`8waKE^5)CA&Ei3XrEMBP#~ZSyOC2C)eBC&boHPs<pY
z89%0$zMn*~F3~<V{-~s_O+C_+KA2CA_=i&Q&Esh&;iBu}BrIWZV#Z6_vG6*OwbWHB
zWf<GydnTzfnC&@hTsf5mBOWM}vHdofsTHG%NWB@Ax8C+4+Q$M-wLXSbdsFG5tQGGo
zfYUqw9gXfYJvLXl&H=E(f*FfLUNh3K8LfeFh)VyVr1dog_y}vwYwzM~4S8jItiZRB
zn*usfxq`)CsG($>i<EWdShuhD<}X3$JH?>5^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`02cS4J<w|Qf8ho)WxblD@SonC?=j|6E*
zpToH>dJC6V2XtW|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%EP8f0HMgw<q?>uoh5{v`Ro?c
zF3R<Q2BNt_r$b|mU))HVyF=96HR}yPOv4!9ce8D7NUQoEgFJ=4Ez~`)WN@;H2%Ul}
zr2HT?!CCc4;kOoY27_drCOK&gZlG~^8K}#521t>?4Te`xKB+?O3>_BRK4&W87%xDm
z(m}yERn9ja2F(2Erc1&_<XlB2^y-6*<)|SQ4@J$J&v2C%m5zjE9mZ$WC*f6-aMqQt
z0j;x<86FaaEouSY33omDG5ay*0h{(|<XU&9j<0H{HNOk>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{j<va=u(=A0tn0mc--O7yCGb7gUQ
z^X3gpl9=#O^R=^8_y-H{grOV}@r_EY9V`N?3(Whvwz9Y-N1Pz<wNxCDWmlY@tgyE7
z1RrffMYD+iAZ#rt?kyoIugriTx#Z35sSPpu4W5}Gp8nqOH%)ix!>W}Cv`2nCKN!u3
zt6dQP1B<~Si&jh@utIDR<D*nPL@yd_3BG3Ie*DU6#`n}X;NMgQbdt2|x4IRdhF*A)
zgE0!6m}*=5*M&5HsW5}{UNQb?Sm_YF2h9M%#%^tST%J@z(Tj;iRoJu(IB_Vjq2qek
zP!Vn7W_JQ~8vj>I`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<VHzk>&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&<m&R5n~$pwG5p+|dEPL^)u8KC_lLbKeJi$DY(7xM12Py%@>PeA#@F3`0k9JcGP
z_eo8z%HuojDoIAL6|yDeb`^Fp5P6(Z+VKgp07G(qe=(<o;NX$vP$bHu>YidEcoWF2
zK6fHe0LVt?Q?U6{vo><kT{!-t;u2aO5w);@%K6<AqU3Z`E)b~c$*axW`*%cgCL8HB
zr%(v)4urpM1aSPM!@ODR&hy@dC|^E+#lw9a$%{@%pYc7nBbnaWtMpr_XS69dDT{NH
z0wym7T41q+%yiQ_PQ)Mqef^`MkV7;L7><3;w(#ILM&nDrGr$Y&T$J34bK_?W=>r`A
zJYo&&iT1eDgTYl*f}hwNw!!$0>P&V^dSo<uRsPr^zoh6yH*G%G5KE`lz)WLq6kNw4
zGc4{|M(*l`5-!LzH&4J}lfwQASY-nx`EvD*MH_4RAQjfP#F6;CWV0c1!kA2GHd_@o
zKw7LJs%#o_9v8XFOq2pjk8)y{5jW3&MqIs@eOcYvQKfXL92)3^z3Gr}EX2^HL64Tb
zinM{@aG_wCU;qI?#FZeV*R&8#u;m0=W;6=RWk5A?H0?TcGnG}03U2p+cEeCGloLT&
ze&zZIylP+^x!@kvE6|?dEd+lZTK#Zw6HYOK8|WKqt`RXp&t~=p#{rCchE_%g&Z5y0
zVr?E5WTxEHs+n@jy@)%Yq>Eq7Yf_=rjeW?*i&@sM<O({tfQ>sW5&qN9F@bM;H~<(_
zB?ReFMdU3`N*mmNglNlm(_+>Xz1wQPwDBAXb|&i*esv!CERmZZcEG0BNSItX_({h~
z$S$#9dM*X)JB2+l_43$^EcalEf4gXcco^}<oDyQ-RkM^rAb>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)H<KQ!#d8E~TvQ(*?D5-VX}Q_E9f%
zSvY?_RtEw-5HEx=YS4%+o<|&J@01yyL*&2!%o^nlkA5HflKZaHG$kw>hUf)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^3fD<JMHT!g~tO!PX6&=b<meH_JEnN4nP`SmP{LA619lYg$t0rS|
zURr~y3U)&?4t3AVb(`3K>Jb_Nl7iB*pfScYOs2%YMo_qcioJSp)_>`fKw5U^j~am>
zaloyFrd1qBM>p0t#5mv)IGebE-V6uc1ht>Txeja9CY83|VRsG2_U8l{P34ViaE<n>
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*SS<zV6_&r+zmNC#sDP#Bvt6vqZc7LvOcR&r%OOSfWt)A{=k3(FaDKRsS^?R
z(cBYB5sbP3E*WQdM*9XnCEadHYs?5Dc<$QWD0H{Z!%pJqfkom$u@-e_b(YTRx0$N6
z{0?92Fu(7XX{}ju9zsMNyja^?^4^^eEd%_waG~m3PujB83e1eXFqCdn@+3}DuSEey
zKuPjf<eCwjrEp%$=SqdB9*ei$T8_{l0pfbjHiGK}^C=E&8U3`ZLP7ulZtSKS5;$=G
zuxE@9fmDQ-rI0a3f%AEMg80FgdI4R9LjQ4*<e6%ruVKj3^toQNwDhapvgN=AlvVd*
z6L^EhFD3>kU^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%d<m3x#fMGZI-&ARTC?Jw&Id*qjjR#Ml${8~k7cdy4dgIoY5IF0cW-
z*@-<}sB2e`a*C&w0)l&}02a4*!8(QqdiS@2&;q)KzyB^=C{znz(WBSY_Boq-#AqnP
zZw39AcYt%Kfqac(an2fX=fEd)%f*J~fWFaLuMbb(S8e>pW2U~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<N{U`mB9SHqV7f}xA3<y1=1e7s<QQEbjIVx^;kNJmuRa`!1Ms{byWuvZ@Q#q1<k-t
zx@c)yJ@jJPYPn9T0q7J%rqRH(^)wBM_@E_pLsl;$%T?c%V1UJpIa=6ug)Bv>+}66h
zT7KucKd8bW)s<^_OFQ`qC=@UkrBfq^hvB0D%U>kn6SXlOIzU($tRfnK7lZ<Ok<Wfo
zEZhe^Det6Y$|>mtqyPnmFkt+33q2nb@whvp#FLS^YPx1KW{Hb=3~=)0O)ZnV9Qi|;
zppj%`XWK>7NAO^}bn*}c1hAIk`G(*<2};5_R&<x%f79)^?mlG+o?VT#t;dMG6`x8)
z&lXSVH@^M>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<J&)Ry4W8wUzar4
zV#Du*I6LL!`{?%cM|DL}nN)mzU%UtUIU?oL<0dd)Z(xwu=t6o)Puoy#pkm&c-UuE^
zH4A|i*Z0X?1#uiP9bh0AIKh}VfG0dub>?eh29AgEqFUdpZTzCr=MPjvDQ|<D2}^SG
z<@xu!qqfkO?88#Me%k__8dXJg16dW9#;H;~j{>$wv${p3ifb#ZEHBV435(_)Zoc4c
z1^Fylk$OGst~xZ|FIU1Ogn20Lii-kYYqrS<0Z<C=?4U+O(g1wn>aPas7|o@myMj$-
z(#y8-ExHg1LWW*0zb*g)(1{jD<8kmkjNSCt5OaA^Z#J}+Ft6y3x<HhH-so!A1?P@j
zkI=PXMo!9Qz-tHxvvpvD&>WzIgMIT(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<W$5P}T
zVtAn^c*qI*nuHD}bim-BOPw;mhu$T0yhYW?$hVe6vwp%G0kOoSj<)wTeu=dWJJ@Fr
z?1H<FeRnflhb3|@MfEH_akc&gJ0`zUXV11~NS7@Y0>!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%e<s@l+;boKP
zl!XVU0+p&{2>c~==_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<c$Hy6EK(8XqOE`A`Y2gA`V%~WRxq~x{dglW8}b-7<*S-vMRkp}FKt~5
zJXC2Lf6ke4&s_+)Q(~AqLozciyP;x5BDJm?>)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`M<Z<)Q0UC<}bN}^bs^(xdY
z^(_HSiqg&nFBkcTY#L6g=<0v=)0^yVzj0NjB<G)pV)NC$B_j>Yk=$d=D|LcxH-_C^
z^uu`<o}6>k<deF2V?Wllv{88VcTX`=w^X#3Pj&VjxZkF~_38X|?KL$X`#i6O|Ei{6
zD4_6zRxdAK@K66s|B!>$$L)x;dXveIH{MFwS-0<+f5TzrS*2@jM+ir^Y+KGhJ1jC(
z2j=aU`;e$z@+4jLuQcLBCE*+^9M9d}vGe}cr)K9ea#Vx0mW31cyT(PskDvX<Ia*H3
z{<~q%%hP|4c=I!}oXw4!vN>igJB;>?GHC7$#*JOZFKu3|zOcL~X^U&-(X?s$lix$>
zwX?Ko>3u$4%*U@17BN1=trK=>>*e>PtK67ADcAGa>A_pEJBQk<LKmD#<}a%q2yxgm
z(%j>gf*XIo{C_}xZDru5SDf&w#jSB+d8rT1zSW?pX_Z~9bu(|tCSv%PtgLx<-qnA2
zS2uW1yVhu?S!Ts2P8xJhvEs(My%@ZEdN=0}r<Ae=PGH=U4MVkSaym=KQXGsv&NCEj
zKiWFf{?VyPYq0{oaPjtyBYU15I=`6n)TKwzkVh@3QCS@iv&gLD`sdqHD@?*>Mppf{
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(3Ifa<vXerm@N
zlWQA49$&aCJ#+9yR$MISCO!bY#4lM#Z$qoLU&k{$%g6-pdU=&iYo0Og*FBmNwEn<r
z``TTRo3`$8{n1|a`4o%G!@Dwi8RLVG=V*h=nA+oSg$H`8gRNP=ENv46U&@IPY}7w*
zvfu3+%I!lRYL0G7DKPdwmoW9;h0dd)zD7S^<?R{1XK}A+(+cC1=KiFcujHT1`(wvk
z!&iPzg;Bqz>2Buhr++HJ)rbtqH883q<)$C-wv73uvc0CxbPS#xH}m0h!u?tA{<z*j
zE=kC1%{106Y1X?DL}j`r-0E@m`GZoNf40ry<$SfekMBssNc~?=ZgKVVe_lN(c(nV0
zo8DPBc6&xpL+?+c$}`BS*9N0Cs(m-ARWBHKZ_Gc|(`_Adiw#rUB3MW794}qF&+ezn
z{4ok~FYUy)$C}F+89zt3((ak(kQe>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!qD<l2%kdeehhd+v^u*x?B9xE~&dupJ_g<
zdEn}?>c;Gh!OY|DOP4lUj9LC(K62f_dxlF<nMS<g%BUQ}Us!{){_1cOhP)4XYs;Dh
zrf;~7WYpHlN6d<&R?FWBpz8Sb;%_4c+zt6op4yC42HVsww>-Lf!<Fxx^^&3-v_ClO
ze#mouVV-D7edpevLa$F6opVkt+C6~!LGTK~=oRS+&ELm78g9Cv{k!**U3}dKjRB`r
z=3iFwc)T}6ujWeG<>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|D<kcVnLVO+vrGcC)7bd5RbbTGOJqQ0nwI0{H1}Gk-l(n=
z;o|r9-yhBW(Lf2GwKK2uFfgCgP#U7d)EpJjx*i3k+oWe0top`?eN(@P^wa~wOYWmj
zii6f84)49j{^sW{9;5AP{U`laIn?N+yN|>jd3=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_qvDk<Gl?D|aL-|u*
zm}umd>OA*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!^;ZIzr<QNZ31TjVEx50Q|U|=vxFjzn_OK&mEq!&&v`*T
za&L*IgcsvOC0a6kLPUT#Zx}CGFCu0A{wAWx`0FC74BrtcOvHeh6)8<%4aCYa+lL|@
z36D7=pNcZYamu4M`KPE<(l3?8<AO-^1y>TE{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@=dZAf3<J!RVJZk@7{FVG
zNth#xVIj<w)G-~$8xHd%*cS0a_)exzK)_cRQ>TZ;(ZFJ<;?$|doU4;jFdGxW1wI&p
z8+7BqG*CwilV1xyL^s|riNGm6A3M$hH-bsLhd2nslzxwL0kH+j;3NdWGWY}wh}nca
zK_wo+bi$R;LrV`L0eavGq=7l{4dF>lCCpLY1H<r+h$aNYJ+LDzi6R(6xeuXDjDi6{
zAqJodn4~=^M|cw!#9L^Ezrm7FBf6mp3{l>PE13_)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}_J7<mL-2MSRPNss{*7}pOdU4=0gU=IfH9*#jA5lKWs4D#!dTZX>VAs@$(
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$6<KqYS1EfA4A8$1Vm^TNN
zvL%-~U>foAVtNVaj-EUgjZ1eD(AX>vhbDCAxzpHQUMv=m;mBfmxl0@i{Y)W+N2e!(
zkc~pNkVkW5Ik9MLfzX4-;|V-y0(VDuM<<qm!}b)Ld=LOJtsH?RE-vCv0N6B&L9Ts0
zuB9q;4|hkV7u}P_bmV%_*g~!&&56fxq%oWXLN1Hx?kRM_9r$x2fZUFE#x!KfyCY7X
zKf|A?LF|=NzJpm*3SinZ@L*c-XDhA}n_2MxYBd!D6st_K5F>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`<Hphl5q9hJ+1u!19|KK@lf)mGwd%c*~36}7do<{(j
oacq)YiRCzav0M|Ed5N7^rVRRH9hhEo>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#<p!I8+(&%Y}>YN+vfA`?|<HNo%7}NOm*E|UDeZ=
zYr3bqRHP*&HU*#on&Ki#8cJMRumAvn?jOy-{dY@?iYj4){!0Qtv5g!YY{35^TRRsg
z6-g0dEo~iQsAB-gzw3X3k%_Z|u#%G8e~JIi|5wicj-QwRm+k`ne`Q^M6~=LeN)FgI
zb}4$TV>AA5t^Wsy{blNG@-Of6A2FFYIJp1-ApccV$=$`_KkV}lqdWbp)IXf?A2$DA
z`0sz%_<!Nn|ItxX5&fq#`41DDSQ!2KhcEwOI^+LKZvKB^TN~H^p8H?;uch#&cIvAC
zIQl=r2Z#YI0nPvifDOP1;0YiGC;?diANp+nqb~}u|EKK<aQbIw4zK{Y{Ie1MC;6`g
z(|=eRU<WV(F#H<=VgL((=^wHD*U$fK|AptJ|G)p}{*Nqp2LRyj0Rn*?|3@a%0|3-<
z0sydW|3^l}1puJH0RW?I4n|H!|5F^;zZlfa3;?(<0RRxR0RXhwe>S?#W~?m#lMezf
z0sug41Az||002}H0PvLn1b!3%fnS9H0N5q~&};YajUi^Ega$A*u;hTy%)-sW2_#Bn
z%aRw?Gm<WziwL2@SlZ@S8TZHnAJm9afe$&7-xh*Bp3VNiKUmrm@xbq4gW<EiWrHui
z^B&-n$yY7_as8ll2D+>4pk-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*phPGz0PicRursYL<FjycYa>B2MIi1G6{Biktp#
z!1#-|uk8eXoO7hFn$NUK0byYO6EYCxj0hMHy!q5G2ZjQNK1yz>zp}nGuhLqfZh%0=
zC}0l}@N3iG4hW1DmclAfe&9ymqn7z~bjvBubM|WklRHho_(4|JA6&_ddEtFw;YW8+
zeATrX8i*Vza@hWI7rKv8chmZqJXB*<dkXLC-g;C#@DuK|ZTAnC`e~(+KtD|DxezGH
z-6-t|U9Ez2zC3<oSo76vuFD`TU_5rlt7E}R4MGG|ag5^KFFQZQ9{p$Yz)GlFpNTd?
zhwi*--a$LxUZhy|1>a7alRb^Y3VwA=3DKDxANqqWRz#Xy+xoYw5(Yy`ZF6NL{=h6C
zqSJ9PK*(c+kWuhAaj0}-Xbmz}CS_G5v<b!XME0J#!^Wvlb&a^5N}DZw9q+)i+~Mcz
z2Z-#`lmn3*Ocu)TD3{W|2VK0_e`VdD_QPrzX~jZigHPSR#8WZETWfMv7m&F>e}C;5
zjn<_vo4GXam|=X0Sg(q8N<Dl>*%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?*<oR?F1!*qySusSp&Gj*KNDKf(IyHI8xUBRdV#>(p8eJz|h9(i0NrrEI~
z$4c_Mb5N#f<f_ZrEn;4xW+Q_bo@LXOuIsgJXvB$P!0O)%f8<@pqtFj;VXsf~tQQ^&
zk=y`k3PFf)A#ZXp8!MrJFnRf#0O*K?HoMZKh49j(veWBW5z%^A500uW#W{kc%$B44
zh7H?eN^Temmkg7fU%jq|)@9N*?LFnm)Lxz8fy#74b<QQ$j(2b5`N+~IRg1s#EtP3Y
z^V;ks*VF4X$0EmhCMOg7DSF0gdrHO_%DiCpdwBWk$u}WEFh+c)&WgZbGEyiG?5)}3
zNbe;t1ys|6ovvi}^Hj&I)4K5`6wIL3+TS&U4aV95HFC^^<K7cTxhwox>8OJqB_5<%
zPBGC>f`42iM0+uUAqJ|0Cth%V6UlWXV(L^-$4!7YH0E*985lNKqKBDKc$?MopE+RM
zI8d0wP$MShgz93ewlcHv_nij}_AIDX$I1EScBCd5VozG4@7et>^sp%47NESo&8<r<
zt-ro!%f(?eK*KgW(GX(lZS))Mkm8T&3QI=e6Wtt134p<Or#PueIjrd|p~;^NQEiD^
zxnt@z#?Hx2C!`%3dz9)>SQ*H;w*#nmhn@~~E#YMd&Nyno!Y_9ED0;IH(ymXvUEUBI
zWG#v~J_uYnobMG;I&~Wbf2AYgDUqqj`Y;t43PFuLl|@$g3{#F%B2S(<v5&^mPxIvP
zjC~TTB!caKl(_8a^#iwr$|7(;Kf;NU#YW7E-;MI~>Z8@?^i(yHts||$zy<n9isOxC
z6y*WbFMhG?q<L_%Fflkb!81Ezu+-(&euBrH>VglA&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~<n+YZKbo8999?}E}b
zsJb=&`Qw8cDxQI;tpzg?5vu)(&8p!=Q@;S)6}flbngz>pmiq;w`3FTlXQhsB!nEpx
zRI~#g77q7F1WoUfLSd%JOd!tKJPP3k8bP{KLH^x<bn!mfHq^KZ&G8t2Vv!Z3<&;<0
zpY2wQkYxP{IV;?o1kMn+>6RAG_Pbbc<|lded@YN#MttjUj>sy{kzBQjCR$VL&48(g
zrXu%d7%-{CeU#{_*^R?6x--J)EHvf`X)!$9_~DE@mcIx!Tb<dSv%O;zlRK=5w~@c)
zjdU2g81cIT<l&R=fOPv^iIpq3XO@RAwI+&*2=ZTE7o|3)IeySf4>mbGdeU0=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<<C{aWsc_N!1*K}R!aRof5F
z{XtU_<cKpOvfzyRzpa#?QTdRHqQ#Vmq_#Qjh5d8OhMG|#?6+<!oZk2`bR=$WQ6uf>
zrX?h(U+IL}dXU`I<1RXQjE%&k8}4C)hwap9$uxe=aHT&v*gi=6(zLi@+<r|CyRHXK
zlaOG(wBz3PPukH^t`S5vDmC72o}q^-G9!RsaQ-$HDxFVr_)>)WPN-??|3U5e8ur;1
z0nwK7RNc6Q+pr5t?k&n%<Xf#v>9s!lqK{;VQDHQ6QNyFl9v{uvmZJfG_h%<&em{pM
zSQ6!Zw=l~H-fn0lHv~j6`<Yyb#~GGkfw%vjU2u-?gICuLqr9>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+@a<x%X?RN>eFzK%=F1p++8W3OdX;GE9BqB?2WXdb
z%MK%oy5!0rXcHJ_gh;B<JtXp1?>-@%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)<p&1i&rR2pfS=juqta3WE3FeL
z&PKHA%&^Y2Cy>vRaOl}_C<l>qCP~u7a}oAlU9mk>0$nC-#QOB+M2bOm-$xM3r}|^C
zBh#;%ATLiA(@xA)0<FL062X1B=8#*=`XIh(OxaPYdN2H7C*;V_><1&Y`a{g%y5ND!
z?&C=ckN|)39Clz9z7#Dm`moj-HLW4npifla#)g`7J|ok?{kDSa4Ns4A<lu9MPNEPa
z^0e>gFmcdnp#gIYdM&9<?-}{9GBX$1U-yCV8SN;)g?!1azUh9ENO$-5iK{;tkjZ6i
zIBrDa8M2*`gSp*3)S|flB443|Up7SxNuq3g_{BT)mrZ=MgCT2#Cw(-=3jD*RDCeZb
zOYQKKF@TFdSEG<YPxtW{AfqUNMWhPE3zs$jpMAsgFa7zQe)uf{LkP^*`AkEba?R!P
z08zA{?PdS1KMD+^Shx5UQCy>;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)?#<tqPW81p
zH!r#AbfV*-ig674MKQ~8OK;#i=@@t$kngt`Te^Ef#h`a*$X#5dZ~02<HXYxPXQ<1%
zMG5ksf9a`w95TF}KTsg;ZHyyxeaO*tuo%HKQ780dv-2L_RyBk+jQB}!_*r<(!A+_g
z;~wU>jUcNULop2wQam^b$g|R*iIHg&XOM}#&POCuzi}F7*nYChz_)Hvy$tyl*peVk
z3%!oVs0kCFQkW?Q!ozMe=4c=3QloD^pkU1*<s>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+<T^uH}q&DsEDE63F9!T;ZfaP>O5BM~X2<lfua(MRuQ|-?U%`l}jAQab$)o3ln
z>e8YSI>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
zT34Yo<Z(*T@bYLk(bN*%>tk>4rhj=Pdw{Hdnt#^6kSl(hZ;ME%jjH}q<zX)&VsyJb
zs9km7ZngEI;QTVxEeEc0xz|`I)?L2C$Xn};?hEZVKF4zOaq_yJu}N;8Lr40o8bp%y
z+ZrK9Dc=xR)8(9s-D^N^{X&ou(Ld%*<xF)z7oE&3nB?}oUU{{Szz>V$K}o=9#?odL
zlts~in)PLw36tCRir~0;!MfGUp65%hm&Bs|qP{nM1Qk7a01t|Y@B9#T%70#G5yi3m
zT;YVsG4Emu7<nL{=>%7GX137>{ge86IQ4JBQ?!uSeKg06&SfJs<e&Fi(7DoL$!8VW
zfHEUEHA(UKiMy1nH1Tf0)oe)lUBso42*1M=jchd2lV#hSY;AO5nWkK?DRwfg5Q|P9
zS7lmsxFoVfa&VykMcsLPTzfDA-5e6h&nag<Hy~RUbpk%$<CB0d|3f4=lhy%puVTGi
zvRcaC1$OY~GwKh)o7DE_u|FcyS=hmIz0b*T-0k=-zXclU#})ELXDfsO+u-5{aeo1r
zph|RPHorU$%I*y&SS`qSOL*Sl5vRaj5Ef#iTtnB3wJkr)vg)++?vwGcmVIakyNKvf
z4nld(YqB~3;^zU$MtF!(4#ULc{_6@)$BW&e(^H645PXFYQMJ2eYSvq4%~^}Uu1tT<
z6GrN0&CC%yE7VVr_oOw~JFS+*q3AOs;<dR?|4z`nbjWHSM$T?^z3b1OiIp;_$WHUP
zzgFmKqRA$>Zw9V!>}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+Fr5<x3xH9-FRi&O6Yx482DjiG%|k(;)`RLg
za?8*^(@Qss@p+4-Uz|)(SdxA@a>T_}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<U`Tz2^~2Abw{C~raSNtvhu8FdUyoTiqSM_zaKOv!
zZ8>)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?JSwh89<BsrkDt*KSRK{>o>XlE-
z*z!4hg<)yO%DgU0lD2Gg=wrjiCAC^l4QRORgbCTxMjs1CV=G)X8^u9ZY)-=aBENxr
zz5YlmBFDFv*T6YL6waD=`c0R`UioI~*D)YRU)z_ua1u(Jc@{A8Cs`VXPUMu<woGCI
ztN?LmY58h^V|cCC*c8d>E-GRk5cv({Nb;ym=V6Fi*e8YunwkG3p7v0`<rgLoRMEz`
ziwncrC3@t-;-VLNKks*d{*Lt&(tUcr`Rsz8RhUrG=N3W1>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<znI0(G)UV5hPx-+J~({z2_A{cPb{d%P`hB
z=YunD2y=ybpSKld-!j`&58sEEs@||6UHGTaI@Yc4PN&`D1h;?7BQ@N%V)c;b;#xXz
zm|sF7NsDJD!4UH%Y61iTy$f1KppRf${h?Va0z~<QW9MMUuMZ+6j&!ENEsG%0jKof^
zjRlb{cn-o~Qk~iR)40`jl4e|IjEgob5~HT3svC_xOpatFJPKcw^UcH2hdqKFB^eZq
zW_PPkU7QPfTR!O&7jkhh*|@b&zP8vse^3EQ<S6)e6rLzz12>&ph~C1}7waF4GeY93
zw<{MB@?!q-ExFa1robQr2FeY}DG-K%CsNOcAK}KUBaMT2ugd{u(s0!D{a(pHDt@NF
zISjeOQ^I9UZ9{&<g)D)GZ~j=Fu<43X%O5!>&!*~=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=MqbLd<lmxp702FvnJ7
z6<_tFTvR&!ak;XC<KO68knMvLC`k~5b#a(*^(|iRDq!49LnKE)wx|efs;R}g)FM4x
z9PQP>qRf2Fm=_^#hZFPvF3qi!TFf`Z>w3fxaP~D-6q_NS6^Aru^JkEa6<(i$B<lR6
zI&VYCL}0Q(k9&c*^wQWv154TaR_2~g8-4zqBFdL|&Kt?byT^srqAuy6vQ*d$h*WV<
z_h3}JGanX^un#fIq4u&U>p-bQ+_CL5S=CP_hd%F7o-xA?gx7jm@(sotIHFx65^e#i
z!D+`<M2okPeY3ehQZm9l_BffzvSxOSIyopwS(>?cbSuZ`mpus~actPqOmB}3n(%$_
zBdT@*tPHhx<p8o=n!`NcZ3U_hs)q^(A2nHhAKC~Pfd_8)2W(OSJm$<*U^{F>m_N{~
z&Y-^eLseFbj|ROpD5R&2;l>HS<d=Wcz%`jIZVA#e-=JwEC1T2B6uug|{N7pL4?l8z
z7FY9rk9F6ztaPK}I0n)#ewO-MjbfR^9GXlV?|=;x-jL~)RYsy;u1o%S-azVZ8jJpA
z+G0F+-MqqBqm$Kxzf9C=_HTFnWT^4P$!cKBl}y26Pt>KPEgPl0U18rFkx|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<n4%uHG;jEX9+RgTy<Vf5KYzPwqLfvvR(`7MUX
z)W!JFibmXYWOC%3hmzAmEW2@W8z@N!Ja=kyJv&jt5QWl1e-ifGL2G@q=_z*|9S?tg
zi05C_V#GMfWiY*i^hy0ng;O<_BBASVPcb_iYIb;2JEb&O)+k`!Jl#9`8D9i0@ypQP
z-qPS)x`Cz!{HL(Bti(FVvU(hEcWny^8VFn1-{eXo!!O6`*UdrBVWnN_{O47_U=0Wy
zG2N%)s4U=;#d$$!IZi0ubNa<JF&Q5@URfbEenR8$l%EL?#jndu^;<o7nQ9><5|6$x
z?bDO^uC#g$Ub>D$+D9@jB8bq|@fJjPXm~QSS0clzd154_nLq`kqdy{}%e)Sl4~?^^
zmG<&C8NWnlq0OmrEBlTSI@{T4E^XpX<SRJ4l=ps=SghVoEG{(9!P<Dv|83w-(yZ0w
z(xSe&cXVv>m)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;R6<!(*xbHsI%syq2x9MQ!Ohue&I{y;$U?XPP
zd?|~_Eet?OEa7WHQzKM@AItfz{E;JqMS6UMtvG9$>nYG7%^A=9Eqwn_lT6!70<&A)
z|5){jRIv+-B^5sxf-LSJXR=Wz%8*dF>JhUajj3!tgP5Gyxqb8ALvw!wns%wsv0Mz2
z<?A)p1?ukB_<9Bt_ptIc`<Wbk6SBk<SINCj3Of(>L@6tzY^7LRcJ#!dJ>R9xYFjEi
zFfraC1@NO=mydyvOj9wlXTF^3IIWQ%3@ts7;`(fZ{8dzw*woE-x+AoKHa2|w>5n@U
zF508;lft_TMf!{CBpGS7vs5G<4X40<!-6LHw*E?AK|Uo59|9HDcy7-EA7+&4&@{@6
z(X*4|b|bTRrjX^rLhNl!A&#^v`Gk{3y^GrbL@0EcC;lb4(*L~XkrJXz;_pW>ZfVxc
zz8>V*wb&kkY3|IH{L5c*2?2URof)#s9sy5oMrQe)QCgP+TNsCZQzLJfINo|Ru6t80
zYDTEAy~M_)IR}GeNf&oG#_zj$Zf^_a)g^jVo5Pz9o7FpzRM+FO49(KC@<qY*;!M-8
zmbdx?v_Q?lo320_`OjCzEnblKR#n-D%Cd48Wd%}O?;oRro#NdrCbZ*fd!j~<9F-k8
zWE7aGr&HcoNa(MaQ8JtCB~2dC;N2Pz_Bv^8an6yROZXiV1=)+V3wz>356o-{S!|h4
zn%-ivwzGYKh8mKdDspG;%wuw-H0w-Kl)vc6&+jCNqhwg3=gQ#N&n`UfRZ!!-4&N49
zlHbGL62(J15`y6-p85d$(hxh;;}yer<JTM69P?^2Au|+gpj}&i!7S2CKaR5lnTmh8
zO~~LCU-#NS)Nby&IjPIl<d0dT+%mlHtJEz-s_B{CMNqSelh$CAN8jUX&No3!bNcie
zg?8bC!D7}!w~Z(R^DD3YN&3EFSoAeW<0@D2HtRS?#+H##lkHn`!0v~#XDWDL_a>R2
zWBf=av)Of8$yDEt%K<7dI5M<r%Zv+3pALq|^q4#pP?W7oL7=l<r86SEzgk}W#a09N
znQzBj(E6J)*linv?_vqF6!VGwfAuEhv{dg|+12_ldxAzAO(rC3eLJBzEz91NX@o#1
zBI@dTq|v;Q4ap%&5D2w-2Kvk{SIMBf2ed1PV`*n&ynEcW#U7j6MdoCE`K>1AiP+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?~<sRx4t?PXy(dZ3i=v`&R|wrt>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^<yCNRbWEdJ-Ia`cLngL
z9vqHmf;i*7U`2?DjHz?65;v`>r2n=~{&vji$2DW5QExw@b4M7bpc&IZsiZni2z|-F
z<n+*q>o$!;%QZcO;b_}fRj;kv?zgM0Xckiu*mf00i+y;3Y*mC`p4N*Oo#<BwQzgGI
zOC)x+Ii24V1yYdy0=fF~kO=sUA*B%DfxN2@7_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`A<?TeKi2++G_Dygo
zk~_F!udJtfI35p;VDl(+e=`#0$r|ckvz|C25n;?-JR-1@NA4|j&rfV}%zsyEF)0(X
zz9;lPpDI&NF6v-;y-eIhIQ}uc8F^Q|p|)%mx1LglNrsxVrM`PdG-ymq^~&M<02=58
zP?3NrDS3a_BRP*pmB<Z)C0pCzHp0$)nu4qEu!Ss?Wk&m*_wH}9>mW6ep^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<m)S8fj%}Q;zcKU
zU*4Fmz7B9Sy8W@6MeIs3H5kB4?ownxP=DRg;VP_iPHlTsX!WCwDm_Q<d!EbZQZP6>
zWO+m8B<X0q%9z*K5JK<=4tTkM6n+Z^Bpw0DL>Aj&&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><e$?79-g3q2(R!A?D{&sy7XI&pVkd{o*fg-MVB+R8F9*ulsv(1
za?n}<WxdJJV#(EL!Qmiy*n}OBayng_+WRE@81^Ru?z+}P`3kQpmKi-QUR!z8r5IzQ
z+E*2eH-eZ_0b9r8(T`87=^m3up8IRPDA)3l6nJZas}V6?(VES`QRff0z{b!*v)%Lw
z2U79}GUc4xH;2gCP0EO`SLH^(HYTREj(5=^?Uw%Vfo`!0KLI#Y!oFU*W2GcN=$1x?
z24brZjnAQ$ANMf1`jl6!de_pakea)=SzIs6vxW}W(7a$5P%(ED%TY}38K7B9VtGcI
z3M3sebT&)NFL@Msj!>HMSyI8^E8);DnwgzwxMhlGMDQ@r7jfG9paYxH>H#&u|BgX0
zF=4Ldp%+_Ff7cbPlr6hmQ>o^4M{Ow%Z<D{bSO(F_U*r@k2L!6MdZF7=F^2zm5@zjV
zYYxi2%W-#-!bn;cNs4yv<@k#3jp(%US79SAwy#LY4~8`UJ1O$|dxkfcuXc-9CQrD{
zFob91FG!BaH4OIhvIVVuA6j=bdq-<Qa|YXsaWi<O=(U;LYT>cmlNn;Z@!AJ<&}A=d
z@yp<4FZHi%A2I2hwMnJ!JXdD!_~8oH^a+z=WGb_1<fqOfL;MVTWj@0i7UIaK^@`wO
zd$Sf-R($Qe*LlR{Jj9nY7K4k1a>0+vc=#h>cjR>im7p@uzozlaG5jMU!1Q8$YYC|e
zzv{a>Yi<XYw@6w!hz7KNTAvzFTfE?kLi2-h^7W{Dg8RZHN`{+ko0IXNIx+m4_dFr=
zO**YYw|?mF+OI<hR*n@Cz1pZ9Gg9pF=)_wjgJ&#_Gwy45rz(xiY27CQ6p({i0-@Sa
z;$ub#0f~!-PS6GhHJ$@!<^5I7llu4{{;{Fi8mh%49GgtpE+AO?BXVCJNw3r51~Do=
z-zGhf8G9b%loksj0aH3dC>h|?H8w|tt0T!a4*T8f+-tNqiNd`p3^}*PkrXd+4HI2&
z_<<)<8Eds=SNIpdwHQk@ev<Q@o>K8ZD~IZ@+>LN1r39Ew?}qK{Fwxq9wDHMK)=};4
z%@J;~i+p{!5s$X(`FJC3&8Mt+JPy9;X(Uo2mEJ>Pp#^4Ju2<fP!F`<jPv$aBT+$sB
z_Q$C|K0GX5XgawjaeMdTek9Z*g2L{mB%JseIADcfH$eU(MBf>er)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?3I<Lv6$)r29V5_37A}*gC<rK8q4a>jwd9SRJ
zTDRg#)eui{>^_Qq?t3j5@aKqLgPvOnq__B1&28LqUCb6n%XomrAeSGIKFOsr&Q;cZ
zMMMkm<2J@FI__KOP;Dkqm7Ze`tjHdH;{ow^>q>06OZ?ZZzPHLph)c_-(;uT<Ua#kD
zE3rL8$l~1yX?5PEB;7nQ!4MXG-n<>_25kQ0dP!3LVS}QscU@91l42vW;>F?DTO4B^
zL&a)6cn7Lkj|C(?E~I8RZ+q#G4k?2{2z$s5k9)j}v<*jGUq@P7LV}oPa<rebn%tSA
ze!_tj1}}L?FJ{XM-b|#nE;OAQ%>lJN4fG?w2cF)%4vIy;$4i*i)1z&}G3F5ov<Ev2
z_s9U@W}O;MD)#M3gdcXgqrnaJv@I3O&c@?U@+#5QXmP~j#kcbD=CzKcla7VVw96U+
zMGaH4Y)n!nn~fFWX88{@5ac_zLVaV?2Br0u^9Y&BI`@}oNS4aIZv)27^7?$GKZV~2
zmHzO>*R)vaLYY?tcuDAChDRyYIR<Lk074MY*;DkVuMl(2xvm+)S{ZZECpl(<Xhm7l
zH$d=1ERhpgXP7SIhu<;<9h<OkxCj6hr03Wd?LK$wb=B89NzC6=!h9hf7-yWl;Npku
zN9yKzX4uFre11zDoSshrD(uq$B*o-4lPQRkeS&z*sP*a+vPFs5`nB$V3n(Q>Nry#v
z5PQ8Z?IEq<zUwZ*yVW24kdSFjHiJF8YloST<FVi&$~%!Zhhz50RqedG(^w4MgoU+Z
z+{hX<QbU^+7^A)VU-0zD4rU~)I=jd&soXZ0SkIAlv7<P}Cqi)p;XEhicuWtlg^&nJ
z{lP)Y-yS6fpGUjl=4=KvSkWgGeZdkZyTWqtB<8$7Nk?Y|8FB}OoORcE@O3vtpz|o3
zVa-=ngx%=8B*?8SETb(}2r_>BM)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`<W=v9j#IAc>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-Bj<AyCPoY`JT
zxX6QfgMGr+c!n@|^8o(&(Dx&<&SOJ=3q<8`sgsG^TTs7xu4|!b!0|>0izqC5#kng2
zvQWG*-nN*rAZ**)d9wUb`#>~Vp`W^A`sZYIgSTd_p3e#XSwckse`Ox(Hvfr8Pvy-2
z!4FA3XQ8nHF&si}rNtK}L5B<lU7N9XD*N3iR1N6a<5T)kfPGy#BLNV&V#6~Dht!+l
z!=~0fdUJ#yYx|(j)5Tfp`do@?zQ=czz^%OB{$c%xX&__|A=^{XgAE$dQ5c+(5awZn
zs9jO4+2(<2@)u#hd{M!&=e>jL)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`$}<tZn=s^G36qsnD$A%X7Wfg=Qli){f5@oTfX|Gry0+}RSH+mI@4Jnm|_Eo
z#p8=iJ+A6M4;z0rcA}{v|ABqKw$5e}2QRR)g_Hs1``^8)(^EfSFlUB^;4K>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
zg9U3wg<BY%&r|NVYJcJ``%0gey7?1|>g2&{@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<zgGPLw9>}~AM!2Sfk7409QQX5g?hP4|bN%U%d67l9&hogR(v-PHNt|r~sB`6mv
zmHFDsxA{;UWHd<La+L$`4ih?%Hc}f9A>S~X!*vD_hhH5NS%o<?`uK0r;4q}BEIn(8
z?AH(e%d_L96i>L_@CKycCo8G`BM02vh3IdI6TUzx+U>Q-%Tmd)sNU9PgH`~|G1|t&
zvc1C6tIpb`dm&v2GQeKBYP}o>!@=zPG2>}^uS+G|5DKS=56P52U6DMTN|ipETlNQ$
zje3`xrTX0qR<=Q{<UwRh<T3R*9_(yt;w|V=;K5dPDy#*>xAG7-ll-7RMU|^%Ns6od
z1!L_b@Ybw&A@h!Yd)`UX<G}tzDzkbC1Z`RMj*Y3UC3U}ngf8Lt!Mj>WMsjR29#Fo>
zw5fcRT+2&X-GNenCY=ppbznIsYFoo9As8hLPe@8so^ww>%UveuClR6YfRYekK77JE
zuu)l=rdVLOOlWUP5DrQ#3Qq*IlVw0Od#yEN3&w{<>{&td+5?<Z=9we5Np9`fHL7sN
zh*h~WK?B5+=q!vwm@j&Us(FT6@@`-oLn!m0HSUi$mOwGaQ<S|%b$&zL)X!_f0arzL
z&#dv!4_DwVih>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(V2TCjn<J8BVfuzuUs!ik}%+?
z?zl=tL2n~7&2N@T3%Fvxf>M}@o8zLV<)-<}l9Z~nSthPt<r{R>%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#``<h%r6zu|1A<wjem@700XOh867CZG4Vdi`=DP-xZ
zT9#0rL(^5*uTySE6!*oNg(>)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`k<H!hq88&<sRE@6E4tf^OSu%(!ItiB@s+T1Z^#B~VXJmKJF
zS~y;|aR*rXTkZAv^De-Otd$;J#uk1SPiY!;#c#L9B&+JcG@#(ypa6b>myu$BwA(g!
z4i$?FBqqqfdSosB3JBOBwOjSu1i$2d3d<%!-oV<I6ladvt?O@D#A=M-rH$0sL00l^
zFvvL(*Gjv%#bm6#Xh=I`9XlF-@K`+J?vk{Qp3y9-WT9lmL8DekDdbLL#Npfgz@Ihw
zj+-sOpywMB{VQRl!s0$;!Tp3B*?8p7v-#EL`rxWqsa|Kv1!aM^S&`P6kRNTN(Z4k+
zt8xVHM+0<Kn&UrTlnaD$@79XI=q+RYWNRG1t*+Qq5+40q`a651pDA{}EDPrR<?#P;
zLm-Qb#j5OZWjR=~MCZ@lWCt?KiQ-{-PQ-@EreAgX;LLrYg4Wd`hp0Fm#@BVIZ}t}j
z0&WD4Y$@1#tr^_tyLL0YRl}G<4j&~d<sr#29I1Gv#3)#CLSat5_t?11XYsJ1he<C=
zGSna?zmaPA1LG1JpV{7f9x&o~avf_ZNzBN1u+LZV;um|dd1eUtZpqGXX9lB!#Y)<a
zL|J@WW7Zl1N>d-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~
zAYpS8gQZ<l$%Nd3|NTh+eHUq%I+tSh2TvtUvkugy=B4u*#xf02CqXs&Vjdrxd9IJO
zNEbDUj3$*}{Tm#c#JQ4BHSctDR}!K@yiYta6VV@$j#znZTv~bR$4yK5SQj*;!Z(^E
z><e{~H)G+*5fz&8iOzffrpK}S+eG+))vsoK)u+<Vs3#v0r8|4eY!d^=qaW6MH?@6H
zE3XO+hi^t>WJ<NmXP4uy-EpI^{t!m}t_owy2JPYNm@+fWf@*PYsY|xhwPVB`366qk
zz>UYwmC|V~-NWDEFkRQF_#x?*co<ew7eYN^*4t9}Y{I2)f%!Nu;<4-l97UnhDu0go
zE+c8QO7Tna9!|j{bGp!80y*(()!|2iW1|`xnp_GGc}u~4C9O?)^mk-poA%AB4eo95
zxr~5V4~e^Xt>e^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<!hzbBLj$&{sOc5gfu52}%JvkupK{kVJjz5T!)U#suskF>>
z7IKDp3vYhA`?21WGOtH0pF>Ra{M*O)__>xpwnZ`yvfT%cS7SUjSRXZZDs++Znkj2A
zXf6Gn^zK{KfAG*JMTUSabDzH_s)%!)eXE^Tq=l?(Tg6o@wFSGLY7Y$IRlVtGK$ffP
zGd`Del79<nxJ^@rQ#dWuSuLJ|)$_{R<&XURel`y7fgYK8?HP86!M^L<-{;OrKCv3H
z&1YatUzjd})o%9R7n*L*oom7G%K|=u3G?1%^dbWM42K<48XJxlg@`iMZp6O{*Fw_)
z6Me16eEDg%B>H6zuGjR2g&{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(<O
zsXSRHgZ+-NG$F^&YYdoXDBXAVZmkbW)O{WY9rj{)iD2o#;*;Rq8Nj*DLPSC|E`a<8
zR`m><P4Psfs3vcVf_n1Tbxg@G>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<e`(HX
zJ^Y<jNWosXJz^*hu4B5EXJuR;a<|uePk)G)V(yV#q5B^2AUp$2UskqD?>|Ld{m{1b
zFfao#cX!o<c5AC|=s;TXWUY0}20>qB$8Erba<W!pMp)fraL-y2vc_i9*Mws&x}W#o
z$kYWWAzw=-m`DB;mr_fy_9Z?~S@F&-(fe~HW%p$_8&o+pfpsRw_S9z2`Bf~fWS*i~
zJJloUkPpNea9hQ+*jW~%!xc;6r_ln-aS_#`xKc&wLc_AavwaWb?7SIlo)EmyODRGa
zEjVS^A~EZkX!f$32H2lhLDf9EbC)n_WixR$_4fkE08&PH50;)gARdRIU#K)n^42uu
z?20a=ZYfw4QU0QE8(Jx6P_60rcaqu-wD*fjo4bt|ck58wIJK4W`Si@?o<V+?#nlq2
zL@x`sC0}Jd|IUmA&0oAdsi%;9nWKY0Rkc7p$q7aKIgxjZ!-FCRP-Fe5w(U;geq;}n
z$Z`2<!~b*KWZYoGUUOu_N?@(nd~*R2K~;5!*%3%2$+e)%NCK0I(CW!NGJbK40kSd>
z-;brbbpbO!Mnk4@O*Bxo(*`o!SLYh;6`xxsyp(w<F6)sD!s+S2D%<<4q-^30>o;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<A&8mI)a-}e;%vHuQCx-nW0
zA+xWf*R_Ep-8{mHet!oRly9b-;UCzw5Jgj+Gm@d9xl6sc%u!GnJ=^Utf0TZ8>}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*<w1p!g$a>X*^@^UBFvxXpzDXnKEznNp^<yz}SH!2JbSa
z2yUamhd>c;@aA~aHHI`sJ&_L#su$8p(HO#!=L4s!b29Ufoxb#TUA@#4?&Bg#Jv0Bj
z1RL=0obUfr6URSAJ<w~g8Jjyapkvpszht$N*iS1M-H9JN{+#lGEk5Om`lp0l#wI=M
zt=q>93_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()@CJ<lT%HeNTl2yz%M_Q}t`qfm>XA{v3~;%z=?R%;
zuxQb;TZnj$Ee-r6S`1n|9WG04RvaV&0aoWbOymfUOezUV)2e?b>-Wma=WkqhteyP-
zg7GFCx5najPl0x&@*n-REu&?4sIR4xU<YQuGZHHMKR(HI=~w8O_5aj^1X&kM^&S!d
zhQq(nC~8VFXeRA5H-G;^=3K4U97iE~P2x-Y#V0&#8>(BO-|p0j(O%|9VLiT>;}sMe
zu9yy;-wA3Ng46?1M$_R?B+lV<H^*@d6*H?@v$dh+Q10D=hxWlpfjdrg;WHN{3=yMu
zjhR2m>)`~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;5gfF<LZs)qB^d;6ruPaRa9)g3Wf+Rg3Z}GJ(!C_3K9wj>t(|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&<m0Xi_P!7z>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<v6dZ^Vc%+<I=am$3qYZJ
zBV`UeSZBN@ObK7d;=7f8$n6a?<mwZXCOnJ1E>)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|JLzASS<o+c5$(S;3TEXIKuO&H`|JwJYws9;acJR4$nfo2UOP$
z4rkE?jou=K&tZ=I9ya3nUh4`R1rn`nYzAyk3^l3`-JAqd$bgBHa0+JvVVwac$NTX(
zvVOkNGQ}BK$>eE^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<Rzp>(J;Z=-sEkpUnj{QAQj
zpAk3|VEdl9*qzUwy_SGS?#V!z<7LG6jytJAh;1Z5LcxQx%B;}=eppsCOR+!PzAu~{
z!1?8ZDEZ9?7zAov9fS<Ju+QX1-_t#*0k&SX#B_%HTrWXknvqU9G>R$;CVS^xLaKwf
ziR|8*i+=T$jx!oacvQ4#r#EnJEA;NY#u`d9XeeDP6Ec<r4+{on6segoQ|yGew}$?#
zTLN#Pd+cquRTorY4Ms1|#s0vGEDoK}DWM$yP-6&-N1nfV8Qno8W=BLYnZ`xvZY6uc
z4Bc*`|78wXlwTNglK6k6L1!2Ey9934;3ub1))_8Q9*#Wc#h=oB1UVI>HZJp&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#<o&4wgS4Y6vP(*L8*haLn~
z7X2<n!Ix|XU2m)T_guxNhAq&4{I0jDz;P7r6#HtEB*zwq=`p+S{43gFk|mImGVC|4
zoDxr6sM*m%?SVbqR$$?nl9sUn-_hJ~`km2$+?F9;&{6FRi-uVdy0}S>Br6<yn^1ou
z^!Ftzxuh}Fkmfrrb^0YL7i@~k&f|}6DfqXm=l`L6eCX(WF6MsLh9>W_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&<IXCO`JGH{}r7->tto9Eax
z9~%mUAgKTdi2jhHU2-fL!!zrqWM_ZjcIECgeTvRpZcTf${k82~p?X;LW@{fWF0tK6
z%@9P;seodxlv*~lVkWY+<_|)WsM*&x+T@9S6v`$J(o5^I9TR9nXlD<_qp<e=bpLS&
z#D8D%NILSCEBNJZ4lv&%gcpYEg6!6eeYk)VGzuFUg7@O4y-h9t9uf(iB+Cd9X=SRo
z5;n#wOz=!qy<(}Re-_}XvfV^odF)`|>8|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<kR=aiHQ>_Gp$xWdayu
z<^$pkTybSf3WnhSMIL%|->UMGY>ZAdBJid<P!2Z13W7fQ$~w%4h*#_6;7%_tOT*(0
zW#Jxaa0C?Ywf-bCtzk*_A)#>9q@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<ivTV$BuXS
zkpBgNv>_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{JUozp<bERI54v
zN_2>JuddT*j%GH3Fz53GF-aCg=tBI4Dzp)*vRf3!_KRK$x8A{k_HEtr$gLdrez^4j
zWDo@;mNIgXBZ8k<mT@1rk)>FW51pTf8_ED^wc&!s{vXhF5N@}V@Zfj;KHqR|=c}G_
zi_xUDetLN2(w+2h<}R~cP~$b6$o9oe%Z_VbQT<XKAZPQ#RsXU{7lE@MR=;!L1_5=J
z{S8Fct~~PG>OC7vfV0m7v<dU^ckpqm**?wQx~(Cc%g+#4GgI&*&4Dl8yZJwEv@tBN
zU1^Bbd05PLl6N1q$mW<o$*&7Wuthx3gD3Uee<Di54XLJpsCOf;f0f|zNd^nVva1yC
zy3MLL3=YTl3Nw}e9)L2kMkcJyb{E+2`KJ6h>n_-*%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-sJ8sXtk<HvO#JUgtm==0OGa+`9U3(F6Dr={rpr+X
ze3gN!$}}3gj8UvaM#Q!&(D8b8WTUJF(p+wjcY8EikBN2O2js1-^>P+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)hzoP<X#K6r4pzMy&AI!p(&qLPxob
zP7q`gqGNokJ@i4f(!nmQ|LCZ>H`fN)BHcS>MN?>y<S3V1YNOSeL{dcwnzH4>kO9J3
zU&uRjT_6(nJFFW~SZT5tM)}=$9U};e3k6x%(n){+_!(7@=;}DSbpAnPI2d{jBbI4E
zKk3|#;1J}<n3o+@^p3Na{RL)?Q{BX(<Tb&teFget3M-I|MPis-oxDC(MsF~tKfNtQ
z#_9UrXK?T#0sCjp-s1zgt&F#>Ib(zKPk>T~D`A$iT;{QTYPy|*2m7<>e1}P-k;y;@
z^^=qUA!>NMor|$$x+YwXTHe>9$vnYLeU%QvsB~l9<tJuVGt-V0ok4jyDka){g=8JT
zwBw5x#-IP|e20)L%wKHZ8A*>SefKCv+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>H5FgC<O?jOSr2(LOD2
zfPNaleX51yF22F~DM|j}ErgmAP{iN)61}U>di3V%av;|3Gc|#H^<_jA6-l{2k%q_A
z%opyR6+WthWQ)kku-7a_1>UR#-c32&T!0@(EcTmVi&gt=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(aK8ictevAN<zK<pxT2
zj(LdmQ)t*~V$@v#GrJwh5kzUxxv;LY?Sr&uk<2@HW%PB0$<;h$H4B`rQ#}BO0YIO3
zmEyp-@h8ZL%$r+{RYbs>8}8CK@a!D8$Jt~AjHu>IVxEvUYp^BY1ew2jUg1_+py8^r
zZ>X!^uJ{Sn_;;M<EU<`^$E)_|e|!w-vLF<V=@{;xoO|-$Ga>j$4la11UVPIUL)ms~
zIE$uO*=8m`<YF{f9aD|yuDGPovT^zP;eEJ2<DGlsDVbR39}Wk-3JXo9L!UQ;kIE|#
zvN|}zZ~0<X3M|a!s?0~M`dAeKhmOx<8FUe<tn%Q19io<gX9r{ZvoCTP2m2L-`Nr7j
zH5jMG1SB$Je&U3YD?-+7645=Yv=(qIZ}F(#2=J5xGfCWN!vu8qWGX3dcybGx{~hIP
z9q4TxO67H!XQMe|(pmfIX4iYMcV}E<%*@L_-WD3~DhLUdU|~!8wKpDYq<0t@GmQ^l
z6lQ1mJjfwu$(f(c36AY(-QQ}5#Yne=Ptxt{o2a-vQ4arHEP}cNB~%^t#xoKhF~y>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@MHiNKIZKwyax83Qa<!vF*Rk_yjy5-qLy9h#*E3>1z
zUHNnjfExL91=rPx&RF<V=<9;1aC)ed(xnA_=>uPg)4hAEX^LeECR#?yD028x?9Wsb
z1H<$Yu<%%%IC!RgfC(_X#f8+sq~kkfX<hWY4VpEYTKuWCFpTF)ey;ekYThHOn+;<S
zHDK>O4)kdi9E}<O0TQtwqjB{Z<G=GXsNvRy2`q%ML4?<-A;z+G<dj_3`R<(O6^&yz
zz20hG#pnkzb?b|}5IN<X{Ee~-=3%4xFi{WU$}74l5wN5W(_SnuVOV@9DBJUj_2?$g
z5%(x4!b+wx2=c<tlS+C8-NJ0Q1PFWogjz}Kwtr*fib-Amt(T}dzv_3hw1NTpohg#G
zxJkHTr?||e*+gvqbsL#wsnRi~v@J}#l2OR31s58QFl5SC__uJYC8<3gF2<gMDk^5*
z=3v3L^@MML8tc4)_goClg)TdG?LnQekop?s+m6RCf-{CApkH~(-*ZCHwqg69`4mGd
zGy=s%1aI!&^+vWHZmFsfK7qByY&~C`w&3xjT1a<#o)FeFDv*y4{@ZTj!$Lpnzv7@n
zBSPoC(z(Sw%>V!60_hB-a!p*W;C%TR`0U}p5jxOt_it9dkxf;fkswZ~&mD2nr+ui3
zyYUFYrxW0Am)!g-hyuILa|%;|A2Ltmn|h=S@m<duq@NaK{mA0^0|Ph~0IJz;s0sDC
zMIXV@GO`nn+XAja(Pk{Eyy!S>Mvc`Zt2cCZc+;EUb9P|5^Pn>H9l4y|RaPZV+EVeE
z3FM4;>OD`;iB3rfTq1>Yf9l<z?p8c{va`IYkjHLB1G?^hxGOj;fK^?Om<w_34o#tg
zUcA{li%yJ3L<H9pkCX;o<vZRd{B-M>#}(hV>FpoI_Uj{mz~^$Zk6J^=Bu6YcP}k#;
zlB2UzJtWXgqxQ8T{p`h83eV{W<wjhbI3wzxz~=QgI5Zj9WAtg$|9(n_P&@g=+OpN9
z94?z()(IOY6db#)ufF|0X|HTveCAvmD<$AkQ0*2t39>z=#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@*0g<R{PGIc~IO4ShwS89p0
z_|xKaPX&|A8|iO^Q=Fn~%n2rXO~@_xTf6%CC1ewE)TyjmloOc^q~`##AqDiEGG_gl
zBY(Nh8p<r`+F99jCQv6zi&1@GuVxh@R+Ld<fPma@nHo`du;PZ_bz)Dc6g%zxo?0@3
zk~c3w)@qL}w0klt?ErvI<CcB47m-97gI~hS0lCP6a^Z2CGD;ig@1=~~5?&ke74d4c
z`>16dS7%x@T+3MuPq7Zw5fnU{j>~>4FVwQ`WBUvqkbqXBRZQtJZO308h0JugXF^-x
zQ}lB`B0A>x#%@{WOnqlOg*p28<VAb`9(h5X!I1@$yxZbgMz8ewwg?)$^|LxUVTIHA
z#fT1E$h3ZGCa1-`#I+nzB>z+Alio~~B!;R|dsGYH;qFdL5muejebOFo`%6e?!x}!}
z9leE^wSWJ}h5ykkmb?0~P^NY=WfY-4`0fF0!_mOEXk_pIF=4ZHTw&~`re+5JSM%2!
zPlq8HrpwM$?vSi|Ylb<B-RdP@1Ey~K%gosy&y&GB^bQ|shV>c1!papNdjji{NxND5
z+*rz+DzI@ATqN#|<EgTwmS#AVirtG!%yO!;=;|zRMZrtzj!;X2hv@;LpluI~**dBT
zdQvh^Lp@X$CeIs?TBAq*^-gxVDwh0QF5aGjkA9taF5lUE=R!b_<#87@r=zECG))NE
z0yKewmgY6}Z(?4&SD4DO-@7qbL)FZmy_<%jiW^dgwya;u2igZg5WI=s9f`K*a_ED+
zg}&F4m(JyQKROGdB`!hMlMm;G6!{B?pAwn$jP3480B!yddmtUj!7~I8w#OcZc`|ES
z3&Gwg)0zSq=xwczqizJ^owEpyo(t3u3fpZu-l%#tIjltX5$*+6;Ao~LnUPi9%7c#S
zBSf>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<padj&oR|`-2yx<>)}jy84<d|W3#~hrbwl*To)1pUEq)t23mBsw
zANhu~6sZeH=CJH7PMh4Nqwy?*DZ28Iy`Wl`z6IcLaq<1mSr`46;AE?kL(GqHsSK^h
z8kcL?LcR|NC{PPXbI|>21R5uF1Y+%c#5K1-mF+R0mTP<{m1-+`yQ5Ng;`Bb%Ft#mr
zylqSPCB<xaxIf1WI|@WF!3<Y6rn|#`aA*(^4$ieWPPsQz_4Mw_FHo~odx7^25#uIw
zO95SA^rJuPELb(*#5TbkXWp+d#Q#4f2-ii&rs<~Mqas8ix!RHSCya4<zg(za)`j_q
zpHa8kfB`{&mDE{roDdDC$8(_;7_8CX9>_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<mTlTxucs!I}l(qG?gJ^x9
zv9$Nu6uPD2cf)bJQ~Nk+CO((k5}$R)AB^CBPM9a6`L|tuc{I?7#$4zYO`%Vm*1;!^
zEqb=u>#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`><U4%H9S|wZqzJdG$Rkq9-Ro9D
zH|-4f{?yO>0wt05eRxA4V75*Wdf=Ck_S&&3K`mu1@p<WgKUCsV$s9{Iz$efci&8{K
zf{~Gyv+HA2w1rUViXsw3-58aMnPpUCKy(3N;N%bEQpw_SYTTPN96zcZw*EmBGTlL@
zNUg4iuqO3R4-tLCr!%RB+VAYnnV%^sD_nGIPz0#Z!6hsh^K^zVN5l^n5U3Y}1vHdg
z53&P&Q3onG@N3_@Hp>KhWiIHuyt@G^qpSF3L^5Lp=yl5JM=mH18gS+9vwWTnDDjBW
z<AqZ^meVzZ9A11G+B|075RdT==C~cfBN+obZ2ikwJp|!e+RrEFtoS`i|4LmVDiw|%
zE5vc&HMXEeUL~krTz}(En=Hckft#(>k9+8oNQZ+M<M>GAw73ae_Cj^qB>)@l@DQ$L
zv)lqu;O3MBNd<1qo$S6;FlH<dvy>(@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|FK<CKV0@Gz$
zTgsj2Z~-eorDF(Jm%%2pyUa%BrAAJKg)x`e-?$~QkxITU9?3@su)E^!R+oh;+m>sV
ziTVn27&^lj{Z~uaW^N|M;_}IJVu|EigYDCc44?IUSF+bF_6M$nk8@k9jD<uoRnur$
z@nR4oCWTF|Yujy2#rC@FVy8rQ%ul%{l2m3<VK+Y&AfTs?-UgLi_c3q!*D5}_D`3ml
z-lDKEqkPZMP$ee$!%}g7s%_v2tr%|HIcRosPBd=#6Wm3?IG7C;9{=2(^e98&#5Z|9
zw+O+_prj~Dv3^S59*kwa)Ewlt0xM5d`eHb|It7pNzU~bAS&8s;oNlQcO`B=zYqL$D
ziNT~^>{^IC&UK(qr^(ob983}DI8|p^15Dh`R}%*3RFlzgTw$+~m+ehu^|r#qG0+<b
zL%zSRWn=Da;>q;<z0{ozoH$VZZiR{GTjw-cH8+UuUqTZOJHs;oEJoVC9Tr;M65dil
z(sCm-1S(h-Z3Gx(2Bi)}z3TUbcwN$wGiR{)b_;1n_ZqljK$E@NnSwM3o!?{?X+K8$
z_F{rK@BGWE#<Zu;7T#g@B#fR_BewotD@8%MitALIZcY`2L1v{y;DG@6Y9;z?`moSy
zaHvaKo+#{COdVq8ryq~>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-
zR<g6=kQ7%fDEX1~*HCZMDs2693!DJ0m={c=HM8<eI2+KchjhN+@^=n0tX809hBRXb
zgzATn3I)5R)RpTiNM4M}-9{@9L4Wov!AGNapw#xVnC>S<S{YY9d4<jrH_%h!QkCs~
zPd<a2kq7sG6yE?&QcFZ$BdZ&Y(^18b!||-`q_-_tOOGJEuKrI!Q;A7mS+bDNT-X@!
zyju9avP;<o*UI4+^J%u;<0bmy=CDUy2ZvX;B=*IGL@UCiIqkft+6Rv_4P=pfz$g<`
z+n~>A_fvC?olRLFi<Gf@$bKpVs$;OlME;^VgMeba)gCj~0s<sJfFK!#Ik_?WxDlSa
zs6dKK)h<IAdDi<%LEy2Pw}ID@B#uiB51$Nl7=|kLG8#wBf05pwYj~w7uRX~)7Wh19
z>t`tn#yh&&jP?>$D6@?uAfkZoP2kK`jCxAk$p9=#`z@5|t%3kV>5ltIzBkwqWSgU?
z`Q)F4rV{I!Zr7NwTVf<d(X-E8{Zf)+lVNwrG3~qYH=27=6LThU`=@bYZWB(PE<z<w
z1=ls(Njy78=j4k)D7GGQ6HXhQyd1Z-;o;t_`V#JI5iP+54>)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{<lMrN(X`Zf|6ABmekS~#lt)g1GwxYb7o;U%y>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<5G<kglUKQhM0L1T`JD5WphOLZi(
z__TU0$et#jVic=me;=e2bPXI=Vyj6Le>rBBVg$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~l<w?mT@f_0bU4QJ4bKd{t
zh|?Sep;Gt#2OB!-o`0w09xAzLL*g&f*zf=6Vs?GCyv2!LmQoRvWJq2#J%;$jb7Q2W
ziL-JFNnKL##E?fCPPE_-Hw_*yR6^Wdx0PYwZa_>9T4G_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%CAAgVah<SYaTQhHQ_iV+`psHKCM5
z3SGSo3}d5R#xtOjA-clgoA*W0b95$5s!!QW=g*k2vmRYUe_I*`fCsDHH0E?<*<M5L
zhqzrPze5mh@X@=-eWFbZ(TQ__i$o$-z|c<Qd(~JF95#&jwSRQepZ?Xz&T+@RG>xr{
zgTf`Oyz7zm6h^=<fDz-ZTOMtjVkLl^r9J~5p89vNdegzWo~1D+m&esYje4D7Bp0$8
zQP#GYu-S5vJS<B!7dV%T!UMFy>o<KpI+Gx+Ra}E7rZ5Od2FY4yE*+fv$<wNJY#!}8
z_*0jM2xkBC%bOq43m#0OM5x_7aW*wKUhP=<f$517cLAGDu(YdRmmfd_l99v4#`EZ6
z2Ioq|Q2B^F`l#hx!w}6T)o*Q>&<m_0dG%!xul3MjOYj$9&5kxt3w>nd>yTs)5l-+Y
z&2{2^Jq4Vd2^nM1{!a3p{bP=enAcn-d@l|9ftS36Z-0X&8@fcoq@LY$DJJvowgJQf
z7U!KBI(Iy2bzTK<cSQxYqwlqw8pgz%&IE)78UVAsJr0JV@W*{!bxWHrbAE`GfG3!J
ziAMu-ITzSEFB5!W;={ks>jDxS3!x~<r^y`zt+Lh_)ZSayv$BwNI#)q;{zNmp?G85o
z4*OqHppC_`o;o#D0kfc*(A(%Ds}lXB_?MHzGeell93P1mkF|9DME3LTzI}}A3~>F<
z5<Vi5RTrk_jNX;r|JV4#0<E!&URIDheZW%q7m$Lli%@e`H&cSQ3cx}pS|1;WR_~_b
zW&!^1<6KRTOm!5ZJbGVbQ~iGc%Jn$dpd@n5BrTWt8Zg2Uz=_W40~(_ip0*{30w^E}
zJ^*FOf0Dwi_ubgO9=y@hYwQsu#MYN`h!RX?vK`Ae7$$+cBW?@T29cHu1USk!J38Hc
z2rW<D8t7PJNHZ#5#kQOP*Y58>bH<E94>Q*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(3xW5wK<oUEf+oKkun5SvWc?iQ;BMj>JQDF{#kyXPVaktN5jfN7PV;CwfgqKiufVF
zepia;vZ<CgdHqa_r(dSOAp=UQIP@ze#UAqTg(`U!933Edsx4_dHR!t7qdPx`K0vca
zt0Z1`l^`%~l@9|^$AvZa!^>O`JX2-D^MKy_y6XI>1_$YhYRW&gjsb^pH<mps{{W0j
z#4X)O*`N(Q0;jK_E^;>?Z=o{i=f~dnEzZ!AIt8_2O0X;}07Rq#KmrL+NX9`YnLHe`
zOvER{4b4Z^3xpoxdPbB2Lr$l8%tQrZB`H|N!QM19`5}AR)L^3*<jW*9WE>)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<GvG^Jsil
zRv1Oa6-0X|XT-Dg{?ZO#3~=JkC|*tQ(S{q0=qhSk?(r()OtYs~?F>~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>5<iHsnX_3L{<}D^!~pEzTw#p*nv<VTd13=}vW$Lb5xtDZ~9o
zTTLLnKjA3h;nOkD0mI7iC|eIKabY*O+{VzFU|slI*Zn(dzonx$d!Ie0z7Ujae!EOf
z<EKZZY~ePy`Kj@jSXA5|{T6OBgO-2Y`Z^g{aw?PZ>N7AwBw2FeN&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><v}hdUR3Y-vCWq!&|q__uaaXoMim`;&UW3wKN6gqdR}$rjM5PcY;=cQZG@*7I#Z
zirfjtBC{~C?*Gp<E>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<n$!
z`w-q7#_92uwtJg?#`^Ek1fYG$e9nekBQWa0`O&%cy59^M-?QP)Ej?TSZm&JG=Q=dp
zuAu1Q2%R+&8dk<h7M&c9OpZ7xgEL(Yks^cSElz>+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
zRC7mpXQ<x_*^-gHkDcmMk>9rSgMxH~n4ka=c@ye2sa-TxY>)M=gg4FO5YHld(K*hs
z$cum1h^igpHmY}FQDVdbLNOjv%Pm(I2DD1mA)(B`tT1E1k5Xq^6hZoPr)fGAHKS>n
zQb<v8h<L);5KoNDx@|0=D#Nj)u^<@k2yRD$x|u{jEp60xEE!~FD13LauO?VU<?rO|
zGUc;K>aEmsn@;@lGChU^NzZ)2CNpZDB|tFTE`E!{(n83`M}Uyz_Cl&ibVCwLE5c0<
zmC-fl1NfdEi<ZN$#yJ4H3QIF)*aZAXVgRv1eX)mI9EsuWgdHAqaPIzTVOSX+ev>7g
z(slZENwG)D$ja@Uo~$az{1_&PCQZE{!9QQer^*0TqchqnGjiuRWunTblqCduS3IMB
zn)6?Uj$<Zb1z9YDxBH;i62fTz5?n+uJvQc1MhPzEO!-Jcof&U%Rc3duyqT1H&>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(<XulWZI`j`pW<hiqBwYg%oaDOFT7+fg$VdOT#$r5ZGhHkZrqU=IOBIl^cGkS7u$D
ztWExItJv1}J<F2gLXvt?(QF|AMLIQeZu#*@8Yup09Q49((j363@F{A$)6Mqxo@4GA
zAk5?tCh~qn%iZTv)o3PqEBi2CI(tgTx*9(X1AE(Lhd9j>+S#<atJl)?1tAdJ#o1gk
zY``J@33_%lLa*THK@U)BJIOg6Y_Vqkqiabw!s<aPmiC=ZJiw0$qy8?di#VyVT;$am
zp(C*Sjo@V}J~HdOzPHc2ETpV_{O~mqlj$VKJf(mcPUzR>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}S<?bp>UMa%7P4CG{}&HSyRqG!<Bo@<>fE^!01;n~U!J>VVt1<G{Dbmp`=9
zes4C12L>RCFIw{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@<zkcR4F6K9n
zT_U)7qqHO-aJ)_7!Ec${N=Nm8%p68SXFAuk&-MLEGtlfpIg|ysht}+Zo*gX%s-<y+
zd@EIgto|BrwU&nAaVwrDnlh?*Kv679Urn@(_WWy`o;kA}9<^{11#@)&3S?|a=lhxv
zZ8AU`wvRNQ#*42d4ufcwu`}34oDjQ{XDSZV8*=XYz&Mr$nE^t>Hlzbv-A5RWWw-cv
zp0CiiODv=iNxJV@bR_U)q~dZBBt!)-F#}N$J-k^OtiR-!%rHS6`2hy-<z$(0WSE=6
z2P)oOA>WaKth%%*U;x<KE1t-!Vz7MidLEzQl+LbiS+Z3hO2lpgmetT=P(5QYyna_m
z4O9PH)@UHu&^2ykN)lLVVJ$r86+zwa*2R@ulD-<V2~R60L~+H*v7VODk|uk3c_NUP
zP=7G06J#IYD*Y23Rsi*psjJoQCtYU^L0*@G5;!4-EbqUaJ$G)80f9hvYuD{d9}g=?
zg5A`i@{qx#L8|s=UneUDLE{x+)Q|AQf7>%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}n0D<Dw{
zY6^tEh2HkLnOi1C%d8vAV8Ai;y8s-{wLOc@lV1Gd!FF!{oMgKZ(Wi@nQ-<_gu*uzf
za`s`amzLmCq#oqMNCvD2M)#t$^F;1`wa7`}1d`uh(^o+JjLDYRRYabD)+<H}#`&S4
z$-wbZG;)2|A@Qt3G`CbOfaU?PITMI-mJ!SLAIZibQ)(->fW>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<N>>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(;<Cz9!#_H>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<
z6<hPE*Wm1W72|sdn%ofQN|oIX<fbhzX;|bhra!0@UKoI4yNNx^i>sVw^z1iDxkYHQ
z-lMQFwVb(az22ZlVhj};Jh#a|EF-hb`4c1LC2^g|(<A;Y)5}*l>0G;^o=`~JzYPq?
zi(Ar&eXb*0DC`)ne95$3<o$xHfpMgempQGze1XJVXioAEQc!!XXsThVci-?Eh!%k&
z+P+cIKVsS-#Ko9&pSn6Sr!QSa{gR%ELg)4bpV$CLvP46uT;D-9Iw=-4?r90F@TNlJ
zy1qOLtGlYAP;t+luU7gV(HVZ1F?fL=e%Yzb*G{jdbVIWZX1(F~VRZb>^UpHX+AQTO
zKKqwPG@$?U-p|{2)9MW0Wse|HJMr!MsQ+kcT3RaYO5glTpt{di<mVV4!8IE<#Qzsu
zSjm7y`TpY6oOr1dx@zPi6)8POJCUeoiQUX}!MI%G!;(2jQbMNEdXa;(fuZ=A+;5qO
zeBD~&;x#9WXzv8#1>6&GS@<sVrF{?ri_=-Br7s1m3+)i%!2l5yj!9876ZuTHB<O{o
z9Wv6;#fFobXiUGLBhbvxRpyX&A1+}f*O+s0naoQj6rVLQx+l|4LsHlZkou%e9%`4r
z(P}<P&&L)mKHk6dS5{;ZLKnD4IXsd&%d4dY|Gn<>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-0WNZazz<X$KSZS62=VsDziX*Oxm|`%=<EkUfX_1a!C{LV2**)?}T8dl>Igefe4^W
z$c|GC<GIY7YS2DvJ%SlbS7V-kt_hsSL<F6XG&Z24mn5N)(8h}Jj&k_2jf>LaPt!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<p
znjp(Q@CwrjxQ?v&XM2VKN&vA$Kcn1rRZ&|lFYmipXjeu5g8VS%^ViquMeDn(^nwWJ
zTJpUA6dVAL!}(2QrAGs1!b_*mcf-IGs1)Q68IC#f5RCI!D}B~wsbu)km~G_AskHiq
zJaPwLzGfwTW6Lt|0?u_HSwlMmeik(ENF5nKT+lN_%rfxMAm>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*=U7Hk7Ksf<C$2BZ7|ou}-K#%ai825QYLhYfugP+^|}@
za#iuquMIkSIm!8CN6HKN-1Kn_-;0%^jOjc=c$Lj1CWo$I!g)7ev>p!%Ym|0HnN)X`
zx))HTvTCMNXnWw-0O~{L0PCVZ@qM62V<W^6o$-RXqn8-Zl6vx06)B370tblwC@-d#
z`}F8{{@pD#O}mx+yJ?5~&z2~VJ(^L96s{VHZPoT80vvPr&zr-=I?rja;e?|0H$qwE
zqKZOU%?t|}8nM)d?T%rv140}ytGr)NU)Dcoz)P=VCzC+=UqSENLmGsVknYUBTG=iS
zTi(J~skm|0Hvcw+0}+0;L2l>972=g}vkS~di=R3={(BP3YEgLF%n^KX_E@+Jxy=fx
zFEDWHz2@8Z;~i!ho~icE-{i=r*P=7Djg5EZO<oLf40qJzRN@W~@r&&)DGK^wIE2=?
zY}CLaNzS4$x}$N!m4V&5%~s4-)wPCU^d_D#c(%r5YKbS7TGHEnZe~QHH{O9q$NZAO
zq{n3_ij_=&Hu(YJ226Mx<LP?A&LS}j71DPgIA{I`wm`ibPaW$8UE-N|63PL!WN+h|
z%Mj1-fEO^ha`<P$eB&7@!}E_Pwl^vAYc&K}NiNm!XxV>PX+PyYqFom)p&jR-z1Q?j
z{RJR~;=`<_HdVx9P-~H{iP^FY0c^?;|4|+}$tR^iC?khr8h#2Pd-kCT-B+96KKeuJ
za2f8}NMaO9(8#%2muS0rtC9<G%_?a8l&SAJ(BR#kfZQ{5)Y0~%Y8U$sz*eM#^zA#*
zId12>F&aIha&~JG`QTnU{%+fgk)#)bElRTMhlL4(kHu7In($TlyQy4R)TjYSs5$?5
zAvLcXtzZ;I9Om|VcTj0)Widh++Sg@GLDR;S0PtD3c6x;P6Zh#Jpm914Ka<PK3Y4hY
zMVgf7SjNhoLHS+SOE8%re#xbpp&QayhgZvm$R5E`EIB>uQ`f_-_Gtu<k|X(GzB0gk
zQ3m@ioWS-{z~DFg0fl{S8w5^#ffJg~%`;~Yv8B}N7y|OaKiW1c`(cYu16TtM8RAqq
z5wY*8w)a`)lW8ep&&g9>aMEI@xgdLdQeL-<lsgAll0Q@|ai;@z_HGijfB8ZZ`b_Wz
z9agR5r}<l*_4ydn1MZTAGe$1)0h_R5gmizHrNW$oB7bN#pTYP-daSGhZgkdpx#UHd
zv1ICT@U_@5v9}%xp??7;eg!_%#T!R-T)^Vp2BJoRP?FRe`r6y9r)}=)=`C`XMpsPW
z2yOi{W@+)o=l>hIVlZ4Hb`3`rjKdjZ0?-=8gFx+FjX!P4Ae4NG?f|o=dK+2WN<am|
z&$(pmFErp)WDC;FsGF>+wCaJ<jic_DzFPnA)r`;Qf~xw`OMnI(1ZZ4bZLPO&=X-Xt
zO?p}t)EJ|W2$Fy&+3feIn!nTxgjcN;#q5f{Q6)SFGt7<_e;SZykm9GUnI0?wj-I67
z*o6lw*4JQc6qaaGF9Eu_vsLtu>|hmtpuieBp|+gCIO{n)goLtEVj$L#2+2)!Wjo8u
z8Qxo?_V+xh;bZC_aXz-(*fC7R#K=0=7tSAE5P}6fodgp?Q-(_<tScdiOxRqL6B&Vp
zYU7I5>LBDD!B~FFN-Oe@fmDoNtyP;$>e)0O?@ZG%hoSLWoH1$zFp7hAfq$VpsDQfH
zPed2}7&3hevcmw;VIiCnK(%x7s*=b7of=OPz;kIl>s+yP_vuAITIH@IYKrw@qyds3
zs<H75#~gYQT)W-e!(fF!j%?m<2S|sjorkrFqQs>n*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-<iy{fAq|V0uA|L*K)rS=qvU
zxDD<QYaJlCzX;(tkA^)Q<<kTI8d0%7JVK?y-;!x*@D!s?v`f+2)|j=Q;3@lhgx(ig
zN7Q~M@K%c|X%PQh72gTi@C=HQB)6WH!jbi?y9;7~tnO=U)-&+UWotPU3C`OGE|18A
zq%pF2N>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?eZ6L<Fv7F?4vG5V3a@
zC+Z2poIa?po<)lM-SXVaqN*X?|ECN#4A5gH-zY_X(+ugYC32Oz1ahXh|BKKnov8H*
zJ5+r!0R&0)<qvWL)5PwY=T9xuf>IEpCV)14+X&Z;T8{q_$sbrT9mJFxxA+qmk)p)r
z=7`%fT}=9zFP$6y9)TUx8O5L(Uij9glF{V4KkWgKr@<vQjh_)s0wu1u!xOT0svDWT
zZJuU$mE?vj8rCvA(@Mv<9=;69r)PoEi1`~w&Ya%uOXzK(iXr*ZcTUDcAj&srkR<pe
z8`!9lzo}|BkfresOJUAIkYiOg&2rlr<IeG|63$`TSl`a}R)!^tLBR-}sJNH4qE%0M
z--#vleY-5(##7*~c&U{&;%3&P&}C}_K>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(<l0>+~%n>MwgMQ9o^7)4(61i^PHu(l&2+RI^HsGCw1nnhf0k4
z8vnyXU}pqhcdum@rRUkJvJYo@u&=dT@(E90`Zh&dlN7bX{evOAa08VG3ITunigx>l
zF2V7kpYSwL=JH2|8otW&{<gsc(b|~*KP*2YeoKwekhr#H0*J;h>171@+W&Nd?~6fx
znA4l<TA@9xt1sJoS)Rht^e+hnINbnanE?y>CCX8gCTuCmrJ$)HU0RkWcA@*Ik7nd>
z-KxpYMQ$^M`0OwB$d@JlH0npcl~<jV3B_mv%B}dB@m@8;l}}*Ix&UI>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(C<TeM0n2H!scS)atfRy_y+x@3joybl#)V6Zv2lUNw>Va^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_*>~<I)`}-grNvY@1(0;GG!FZd
zpJc+_+Y2G$qvhT{gxqI!gJIv$Xc8i{DLY}}@Mpvwd`V@ck)ySA&xNq)6NdUvji@dD
z6Lp(^)jOuH)3DXtnBNk7p}JVDP#2Ey{``=%K@)J;y%T6;VHk3K+GCphNfu?;$%pC-
zjA_Oq8wotou`58ya1;#9je_cq<5M$e=E!*y@<S(bTMAU_YE}%f>3zHmuUC0=keIhL
zMpa#URQ2_RxtvKV;*u5t*&mtD3!eFS64qR)Gdkrd*?wJ9t9Y)xNtv~u6S1y#)}@YM
z0F`cpqIx$d(*Qyo!iwb@RwJATdGt)%d|)AZPRFBq*JZ&}w*<T*$41+M4B_y|nQr2X
zlrzxBq^o<iA#{%AEkNg}xtOwnqgz8gO~(!(0|*3IV2sfmEsL)osU7b(%118@>6&f`
zAOt~pt?FmOGg^MHH3<GreO+*7MW<I_j?;Ljp`R1k$&!@97xm}GKH^A80zL=kc1rG~
zj4FER`V1$;)W?aX&2ob%pHKNWZ6uU!ZhD*eaXj*-AIQ_xy%U?#wp6U)sSDsqCs!yr
zutdH6LSO!H5$IXqm*G6iYf5`I)fr*2S~XZ+|MNLo{lwI0FwWxDz60cU)Wc)S$)lgm
zsg&X{8};8@n@yrrG_|%9lwsxj?>!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*#<HIzt=2lMDJ?#*_Q{QBF+m*BIZz`1FmF@1j84j{Cque1_jWVCzgRM*p&6Mq%iYw
zuSDQ$t=1kvLKcd1L3rWq+d3f@Gg)s61*VL*{&Gh|vS>`)ODi@v;%^`wq~=zK{5Pj)
zh2EW2EJ|wf0F(6ptV3}mPao<q44<pGBT*Aixj0iN)2DpVznvxW5<i>;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;n<xa43a2dr!o(a(YSiOu0<|8QDc`4*?SG|D3cx=8nnE
zUl@fbC#3s#IQ`0a_ThuNC|e|!9>Mp{70vk>qpEAwHj5e0)e2Byr!90Nk06F+v9^SS
zq6c3feT*JsNtiH+w_?oxf36sqSTl2B;pIk(<E7-5iySlBVK>0jXm0ZN&~D&jhU<Nx
z+;<}GhLLenDq`#k=uc^vdNFu@;s++4G>4l01VWugV8uqY+BM<up>ii34w+H&{0$o&
z{$81T9Zh_%YjV@>r=M?dtt|E5RCDsqYVH=ofK#J?S?^m6a=Y6PkO2O<`b9mY640nC
ziMi2!xzI$sa-oSgz3$wuSUU<v??WBTHq@iDLu7rZ;t5eGJ`Z@APT`rx3AkPIC2@h{
zR8O!!^i1P{zxaOUN!lT5hJt<{DK9nt_r1b}b>a!E1%8u<vmGl0jxPMf;omz_UDMq-
z*Gu93_o-<-JJ#a$#&|iapz7`0E}P@8G?#qB2^y(+C2p+xQ~~phlmVnVC!~rNwMH|T
zoC^uv`m#B|l17lgFAB5nvw$+Ea>)QuKrXWMLOqf3yu?KrFzQug8<A@KVmCWUP~(Lk
zC7m>Fk*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&4VugV<pZCub$3GI9V{nxj^fVAm{^+iQH}&0^2k8
zTHu4YOnupgTvUae^t^N*0e<}Vf}}1bTb^SHi*>0`t>Tff=(05$p4)QqE!fF^%B-<t
zglGFiCxFJ?^4;{O87$#2oD@p9LrVY#nk*sTTyVQZg3DC#737*I?+lYf=HsM4aDpG=
zt*A+jZZLBcR}BqS#QtZFJKD8!(Eo=LKiFfq-_T~-f}P|P-2RsM@laAIH$q#rTiJ<_
zE%3d5BG4#b?xcPw3p9%2RKEP?5e)h}I&qGBd|~Kqbp1XHn9Lw{xqek;2<rJF4fs^)
zX1cQ49(4b3`o&H`7*<WdUxChaHFNESDJ_uXAHN3Mt6CJy{D9}-&I3a~3=kg%?dG)9
zHO`Aki~mRA?6%S)MkgsJXmE-1><}D?mDkzN5g%!^#QUvPVi&nA*G1u^NI4<ctTb1g
z7~P4ZNDHV9S?CNQy3O-^db(q6c;$N~It`nnoJ2gCLB=Z9+L7?yfz>`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<PE1u
zI7iij)>(~c-_l|RPKOho9m~96*ER33&P4s+QY>moSz4{V0%`#q-o*roaz0vjL+btC
zxec_D>~aD!K_3xeyV{TRZ1dN^(8j60p}$O8Y-$DSCX~e4Vl2JNnOeHBv;@ET#<RwY
zt+ZoN+Ug>*loil&@;7`r<AX`8`03p>+`*+vf`hD>wYcOvDA%GJM^LH6nLdoLXScYC
zg9;!|wB6V2OmV&-Ax9R)fM>pm<V&?7{@*GO5_2bd5H2cr1kjpCYVDjoj@JnBehQZp
zBEAM3-$PRkd<lpM4XFMWDKmQ?mDJj;vCKP)v$R6-CjZkh5+ROABc-{d22PpB6tJ--
z7yS1TY<T0B``XU^9aq{(9^<mL1|tNafMFg1PlgL%c=UG#+X>k8DTUDwFrKX%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@lJp<vdu7;xj?TXgQvL8$(!e0VHicW8!tr~
zYS?7jKg>sY!<?M@$JC#$qc`;U6P5lkg#0&>45snaMTidTLlNI06%9J^hECTI{`Td3
z+~LXfBV5D!!#{UFnb_w>IB@!$A9jaR^U~-Op0pC<S9?~FwOkVyNz7v0>2H1{YO<#+
zDqGsGJStAyvMg8$$a74KP-v@0JoolgcKgF>4IVh=c^CG~i*qQG83^iQeRj4<yJ|tT
zK+Cwa{K!*D+QbXH(*~ScciqUV6btY+0L`vN*!gPG^B{Wms=!>J<l7q1xitnT?sB$Y
zmqV~TlV*L_*F*I-<g!^|xwZFURKp)SoezDD6Df;Dz=oKv#1d1h6zevRPO3T8<{^?E
zKtUB4wY9H8b!=Fo%a5gNiv(I;sl_GSkBWf{mhLbPh>E6rX>8e=6#lop=L^~PXvCYG
zST~J(h1>0*XNKFFNI=rBqRQmO=hc}ZfEmk*;+GsKo6hNdAdT;{s&NIo_S<NWk-8jQ
zk|cZGk!{wmO;1y}RYYWE@klQ#9c|_F?m%61;gjQmWx;1D%qkU2v+o8ebL7}uLhr9w
zM!mx)fB&;ejmjpQ)`d_xuU~y?V$QJyURWmyLH8f66H2H6Y4Y`e!}vsPW3QD=i>#$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}{?OK<Dw<UOi5{`Ng5
zFX4ZS3nsWj^EP~F@Y`dxIMC)cmRUopejuv%5OsH8ef|m3pjeOd&GdG$XQJfu_(2ME
zs)LzQ)R4qHWV*d%cJP5nCLTCWLfh@aRgfh4euH!>x0Z46iYW8EkhWkMk#bMZa`IYR
zlANoh_Vb6|0o2;T%OJeb+}tON8y1XoQj<?H(hCA=cFn|JVm@n~(V-QUU!ASc?ZO(S
z@i%CCsqDcdwRK+mevDBbJO-O`OP}TwCB2%0)<<8J09&QIFT$baBV|7KO12L&g*oGU
z9Mp|wepDQ<Gt~4~m$j}dHwB;)6w*2H4LP6tli!U8*CTQ34*hy$yxGU@-~T10sr>#g
zhTO7UBK)N>dvP`-PfP<pbzw5xEmXdY5J@77KY;hm<^U$?^{ZM@$af<Hpy7GM6pR-d
z?Ph{Qc4IQ*diUGOY=8uP@I8RW3}`@>qOZcdOrrmrHklb1ZLCe5caqkcsks?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?V<sv#z@8>Q}s6!{DsRR^boGFc9d=3yKM1I=|7wn^o-a=RCu2v
z@pgYvb%!P9E-~1U@M0<w>9k)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?<R`YNG!?F?e1Rq|++<nfGz!mJbPF;F+LG`vnMubaQBu>D9wGWie+`QrH@$9Pl;e
z^6M#nXt3CI@80_fxiuy6zNUNCaJzFut;>x%WqTz5;<-8S2zNeolgZ!p>i1+XCgZ69
z2#h5_P0FA);L0u;b?t@F5&+<9O8%u<iZ-zCFOw_Wf_mA#NJuhcd0n*ahxZZ74wR!%
z9CuNaZp4eOuC*wzyWAN{#k^7)YEk@ATO-22?S{EBPVp%}-wl%?^TcmMh8OUsgOdHe
ze4&NRH7wq~KVJ+4=*FzL3T}IxoSuPf%!$ufQ5pXtOk91H(1Z&KaWKo7FDTLmgU(C3
z(ml+oY^3kUlRWQ~_FZ=k5hO~7wE8*5Q?R&yt%=o+kNgQYkIt70N_}~2n70@`XiWlz
zk}z(~^+Z|OcnVy@cXDj0=v~yF+qXV3gqwDCbcz=5W*nMPc3#CY#><Khqg5k=M@}(b
zM48uYMiDKw?(`kKj}$HpsKy)Cg2S2t4e*$`xhc}A3qkk{jgo+YT@<6D%YogFP1ru$
zJ1om16BC|@Jjmr9`vIkh(lHPwjqNk4A++SIk0>g^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$Gzt9<f)P2ArL>X*uWv
z)QCF}#U>~|Vvg&CVg3GA4odoz360R>Q|^M3E#EQ`@k$L=@m)<fbY=J_mUH_L=sRo=
z3lJw88<Jx7pBgr+(ktOoP>ZY+#GGMafqf_?bw3-z2f2r3BK4<vTXKsW!C5iUluh=l
z3a!WF{JxSaUvfpJNkS*SL;i7s8U$IsH66$8uy0HPzZK$>9J!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*_5q<A)$Ha*O)jT8T)eXHz4t;K<C$H%kqXB$p`#S43`}fmIFPss;<Ww$sTkW
zjOlpAv#`Cs35q$r0*W72UZ;ar8vk_TFy$xdWQ(^x1VC<0df;JnUG9oNJQ_lGi4yaz
zt3^)A0X}+h*(xw%QG_mc4CJmE^|?B0`sPPHS9*epQ4W#B&@-2gLjFO<iS9;8P!l%T
ztV<IuWn3%;sSa7@evEopuS*$as^vI;6o)RBS9az8M_k3hryAiq-RffJM6Pf$Kxyp}
z*_$tu9x9h*J~(+V?`pE6RDeMdw8qfnY!q0=ZTU$Dvl;^tQ-+pxcT0@9NHt|2yPNe9
zD9YGvEwInpG?fEUtT=fekFDxM9ikIXAJ)1DBe&R;GpXtc`ia<^9!Pd$KHbiu@>b`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*
zADPxO4<cB!@~5x$>j8#6$p9SX3SQh>`7~jOjA34g%lYl95_R==DLB^U)(eTjZzzrm
z9l+njwHW|>>&rHha2#x=-N<tM=UkS3&Hqg_UwVGKQNd=aH@>Fwt&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<JIwc;$
zWI1G|+Q30~hBCMklg>{j7f8z>BElAA@H9W(^pX+bxqofr7c_3<OE=smNzCk(@An9O
zCbkD#2Da@<0R`h8T<%WPlOVuodgQ4t4i7|<=}=&`Fj3}~akiFpMx9?)$`3EAMN+h(
zZ6zv$zz`1Ve<13+X{#SW76H#i<{5?A!0}DJtx_JRcUj)WiMQ0hj9AT#F9?{c=C9$A
zMx|>?te<$@0EuX@&=m{WKo|W|zFbh+6w-@~0m4%ulLvx#EBC~BLk)S5sn?pf@CNLz
z<M_YisM1`nr?wre*c1}g*Ag+@R+8frw_=W5f+uIvXP}5|wE~_1jt%+4=!zAhkYnH*
z?6Yh4hCYNoD&&9CbT{4$GS~47`}ujQjZN8fGB{(bX~w$3*U&&Q;$|<`qlWZ5=}Kya
z?blq?QTTzhs&ftP3QXQ9ON!2>acs`Ux99eZjZ+<0+nnf#)w`2`%7Q`oXA#3QBE*~T
zTu<CNT?xg2a)?h{D%*i#hPKF@A3#Wz3lIS*2)uFBfCi8{kF1|14YD>jf}>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%urod<f3qmf?v9ThB9lN=a#`KFD|bIbbG6H$*3lEUbg(LyzBYnwxFxI%t9KX#
zgzRcVf5`>q5p<>4Y;P-wld2d+8PgFlvZQ89?D#A%)NatXQ_y?h1&jf9aCT-hWL4!%
z94!PqxaY*$sXO8!S2t`7iG5FU^xZNE$rDgNA1Mw*M03{eTx9qMytPQdMe5eA4s6Hl
zG$;!HbOWjvBMjWgkzNNpK0=>+lJBBmf;05KKXCp1Kg4uXE}i2vH<fF67<G>n(?{i}
z6MCy&U`|-c%BQyahQeQ}Tf@q~TE$}6X|=TseX<0&7-gXtc2J5{-<awFe=C;^_2%eZ
zFGw8KEqZfEMQO~Wy?#RWxP_?LOv}cXodb#&YHrOfI1bskZrgTZfs9(p)w8UASURSr
zb`;E}rKi6|Kq{aN#3mVe3_q}S7J5q%$|)x2BLEjLN_aM4+e}A$8>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_b2<dIjX0(?3MHBg+q<Eeq25a_XC8Yk*it&fbt1wzu6hqMA
zuc*xvNSL58Runi=I=4K?RJ0fZW#QpqG=WqpG47rNB=9R;z{yWkRE|6Xk~tOhBZ@&2
zz2;~xD-!^=4HVq?0@pusP?c!y>q(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&@_xnGC<sIu#&)7FO*O^gs*Ir
zi>g2q#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
z8ds32Ar<fnG;{AWWWgJ-A;0KrT-$472qJkq*k#_jHoO^lte?h;Adm&eP2lZ-WxNHl
zh6cV|&=e`w2v-?bIBp(qWpf5j{cRYB`yZ9Hb0i~JYq(puXjANobYvc6pdqj>4=TAO
zo^%_I-6n_Nro73>UoIS-R#h!E3J7PnNw0|skNek!t{emB6uk5D&<b<O-9h{E^+Nsi
zD0<F$r{S_mSL=<9wxx@gZuLO~eYJ^9TBHUJMZH-;2yQ>Up&P8{YG5t4U=1PN)J^X+
z5jzarib9iC1@&<RlxV8o!wxkh_?TBz&G5_^8(F`k*|2ZJGhTR1%T!p_>)NF6VN37_
zqW7AgtXXz?bl4eHuv!u@1G}>O43N`KAjbCi{OsnsDsI_xoFh>;KZY<mytA{S%EwjS
zwA0|CwEEWwWelknWg{kNB+CUJ`>2`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%WH4<AP
z+3X_`Kxl{as|e=XGLjRJ$~#>eE~i>Bb<*@7dfBlY`s|k_M|o=)jZcke&!^A7uKN9$
zuTnaQsg0?MhNYSKy`o-f?I2pQ7F7S8CSWX3!6`ZNs<YY{3Av0z(w22@+|zp2<>dzK
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;0L<ufwPzA)>k{p$quNfYyxHtzdP^MuMx<R&mJrolf%D{^q|E?QF0d}_wD3R
z#GI&!9Ven|jkjN#QhN)tRr5FJA*3bYJ=inUy>8j{>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%<hc(u58b=(hMRrF<*l4X%ByEKaV-p{@&3w3~WE7#<C<4!tlKZHCBH@()Jw&z~
zcc5<JEH4VKcUj=}oEJf7t)n7Q)C?HOu_nJRhH{WI78%!!I8_1w2cXz^Byn5fG*4&N
zx|Z8TEs-rq+nb)l@!muhlZ$6iuR7vr7Y9dbMA}VWSG-kH&_%7U-Vdx1_lQhv1<)pM
z1w|0dxY~%br#jFLg>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#J<tbWD6{Y!aXVBY6J_sAgw*JIA^IAS
z&<skU7&k>Q4h)J*KuCICY<?g4rp7ts%<sG!LVEOW_r3{V^gcB`9AQS1;`tp3ML@|C
zIDqDn{5l9ZMet=1sb$%_5Bps#BWDe))C&*g&UZj3{khF0W+3|T6s40tZ>mGj(3?Xf
z5I^sZ#(-g)TbZK%5%syt>hZe3jnb<9squMW@=D|k&YvJuw9La0s~sm-oNO50-*c<T
zwZ))pSahaC%vZ66W(MST7*7J$chEn=Yv#-tKyIIFwegj-`x2>eTtVV!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+dPrr8X<KMb~7DX&*lF#6EjwDNkdr7dLRBzEifZ?afuBkp+(lRB_
z7%U14l$j4(Jtn8=%bmryXPpM)sQ?IX^*_3-bAH4%uNY@IeTsyK_zdQDiwi|=ClD#U
zP;bttEEC?DU3?B5rbUXb$bdG_7`OO5DQ<2)>xebCnYS+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*av<LEta*Q2?QqV%Y)u9Pr5SUU)QC?$Qp+W1
z%aW|5TUYQ0z*h!(ajubA@>vJEBiLpPME{%|j}h4p)g~2{q6Iorh6g8#s2nR8t>k^z
z`+}Nh#`<WHO*-X5?d!mptEoLC#j^~WU}=EyG8ntSz1;P9<J8eSa=&f%R--38gkA*4
z>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*<LglJAmjx^uDUtN(l
ze%Heo4yMug)>kM!<XywTlNkw_W1Ar~pHJI>hFC-fgG4jgko;}s^dEV(#fL8#iOtzU
z+O(20(o406f5*(|MGCTYlD1%%+#0+<G61Cnm6G)}==?>>U9(Bs<nLZ|GvgGM)tuyn
z&BmyvTY5@E&s{K|6a&B%m7S;8zQpxbLqKf>L8$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^$cw<TG0o1Vvx?G{wqzJ72Fj7MDBPSLN*HNWUKu)SVJ)*@+z7hTF
z;(r0HCrE^tLPfGnKzXb>B?-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|RcCX<LNM5!qw
zUsOY^UFKBx{LH3@5wml7NHzh<zG<V8xBd6e&xVe-V(4w}urS*K(?otym?}1%%^GaU
zEGVqK55e|JTa^1^zQ1e(7^rM6fFKWtxa(mrf6bslr-?=yLf$J$Cj7lsDZ}dV8|dLf
z1wO_z(PR89wX^k)5zBA3ttZ`$g7HfLq89q%vv2nlR=oJvs7Bx$O|}4~pQk<umd(5Z
z-V&h*E42M0TGlldv8o1VF~Moyu%UawRAp`2c@QrjD^4G?x$@Ja3U?}o{$W0Bg`fqX
zG$cn6Gf&T}{X$uh4N0Rq(a?Tnwj%jlhOl~_>7>Nx1*D1{nJ7C73^&8P9idc3^C#ym
zMX?oUEA_8_)M+A!8`IC#qf{Xyqx%I<JbGD>`C((Zm=I!w>64&te9b=)Z8I3mG()2e
zdIx4t$+a7Nm>~_R@gFzmdW-fTC%qF2pjL95NDSThls!Q3NLKy$>)RT#phR9c>OW*0
zB9wjZ=9T`lT}JU4TZ6Bl7VUL3rko5dTwT0tsY*?wUmY<FFRmgg*4k<Ze)!f$nnkIS
zu}yG0m4#zJ-L;#9$0YPI4q!NY1^yDDaC>J7G3j)*(k+1eYdJ0y`xw<Jl(z8AoWk|x
zBaz-ov{yv4u}y9m0pkS8F{(zFjx+&Fe5vVgvcekjqe*R-gGse6VWX%MZqHq`FU4IE
zhdUzjhW<?Gh@hv3^{Wvm7(4Cxs&yGbz(k$x0*beL7Uk14e#?<?<X6sK{H4mAu@_iF
zM@h28H0~NgoIKmfOQ7l4@*>w5HlmqfF?fB3sgp3@qj&BgR2<1jBSUEV;x<owM6RoR
za$PF!nT4R~(<Tt(Ph>6#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~zr01<a;-c|VK^>0l+
z&}%BK<>Ed2Q>%6B{a6$`*I6$>wI|5kNV(x;650LHtViuSO({tO)n(Cd>OuK`8-Z2_
zmU_$KtJ9#-{Y8KRTByOmi)^3IOfXy81ScCotl#3-XGE)g!0t>-Fp3jPL<GpKOc)6r
zxXx2KE-XeFuxs3D_!>7P==pUv6ea65bQoQ@8^@T;GDUFMivR3@c8p^+c=bY|(g^<{
zP#w)*_(h2m6`U8*G;MTkm_%EcIp}?Q$;xlpnAH|xr-m|TmZ<a3KUT;+I_<*p^F}3O
zRn2*Qb86GmpnK}WVRCWh1YIJrU%Z381VjfCl0+(uFp@R`?w{?L`9~6g$d~E%K)icr
z%}b0`gQ7BaxWMUpOhCcWiqI58q#MK5YTy93z+Sy%MnkT0MnvTZFtU)w$6%JGqueOZ
zNmT4RMjcLOSeh~|xq1<jAxiL-3_}Je!P75)Ml-mTSXx76?aol0v7Z=XpP51JG(|5h
z=jyDrCCUnI0c5Mc)7u9*`&Bfdms#dHTw4S}G%*7D)+|u?mDg0jS$w^&V1~5Xh`4Km
z2%~5$>;+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)e0i<N*N_20`ZB6GW(T7Z|K4$w
zs;u*%+w7ZNrJ;uu%-uyeGDzgzOJ39?!cjFpm*GhIEx-2+c+{mCf9`q~f`9qu4NXOZ
zzh^VO_SBCs)I(7r&Wpn_>j7u?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?;(wDMj2PqEkH<T<S6)>X_Y&I8PR<sb7v^`g82e
zg~>>pm}Wn~hVjekck`^N<@<Cyyi%;rtXSz#>5cm%^(6Wt@#9kC2^9%$ZWi~sTgaId
zD0#e1?<&x01=cG&nqGdn0bXQEmFpt|<?AzM=AF#W@LN#sRG-ema4!$D6#o?|JecV#
z2!t5q!iHk=P><BA3z#@upKw<8PPtB4dh2UZfUWftqtO67E;+@iG#kQTVnH-uUYMFf
z)*tHtML@d0aog!>F@|V!_F%F1mnBEpVnh3^$=@M+XnkM7dCqpFhb{NoX(MzdYv<@$
zW*w^sQW0+wbM)O&X3Hx2<b@n9U50qfz>AH>_M*zzEbyZs>kJQT8QudtU0j<=p&??|
zL4Ff=8&2-v(mXP{JA;yb?4S#U6_s=S8L0>Ff^5)4{|dx$QeX-<CD{o8Sw7#n=QSwC
zjHQ+#s78CLKEzVVLn~slooAf}<EX#V$7xe@7)KYBCe1l1N2EOxi8~NcnCCFszN7}2
zx0PS&1KLRu-Iu-M?97J3hr1hkD!vDV0Wv4)7_ZiObO7WN;*i*4&sbs%uH`<X+3_fN
z1Ljpr$ZHh=-VNBm2N0Z-50{VZ`PlRJdTHL98?M4dh+U&RW@aS|N|RF)N(sXcDg_`R
z^|1-X`x<n6(sqlIMQyc`r<L!}sq^;CSqO8KuNqR(y<qs=)lrTlH3^YJm(%vE48lhp
z13L1}4wd$xHL}j~6YXpk&|IPdw&-mx(BP|Qm^(!O`px%q3uN`vgR_TAw@T;KxXA<X
z(rjbU9|}xeI0GyW*)bv!#y3R2g+JdST<fh@Qp8_$WI=K*mVcaB-*!bC1J4-`TeC^Y
z9>&C$km-GO(99Eee3zFuDU}ukVFyZ$G>lMUHp2Y^>h}6I+&~2f$!@fdQseq|)bn24
z+<NN1^Na<9r}!g%Dc@}&S%z3&U;ij<{R>?i;4r2PnB+`j^cCB@wo2zM)YESgy{HoA
z_1#Dn@Yn#zU=0(!e725fm`TyP!%9iUUI$-tE@`(DtOh8Cc_*(8+>eLUtdAgLEpHVj
zl7WQ$tiNnI=KiK0Qx~<I3*7=aPfxF>8HpwxW3`Eq9mCH==+nx1l~eUnvjBW`LxKSM
z6f`hjsK0a|DX$3Hm^<mF|F_?j#Llh;GFeL`x4;DH(>!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}Runx<S#Tfpf4jeRhtyc)cU05)Sa~MMx>lA|8@=!T4^VP5Z
zbib;%94~kH@`vH3<Awq|HgMXQq$s~>sPq=PUmWq6R2M^u#xS|R5Fu2>CGzJRI8jIx
zIK4F?jWCgo<i_)|sbC|n3<M<@7PWbVO%bH#)<fWuU_XV=KYcCXFBjUR=x1A-5dSOw
z*!RaVP=$c}$9S$Cz<W=@D=bbZ0>g!qsMh*=vMPM-h3_IR6c&TdX;>i_sdCt@1XN^V
zc%hbUsS3qXhqh^>)GE=qYd7vpFs1wmEa_r#f*ANM0%5H<ts*XCNR|+&RL~H)9eUp*
z!%E4x%1Py5Vv-j0_hQCIdp@$TgXJjs6+Hg5j`K~db^AntNzfvEEwK(p!x*8ul-}Eh
zMuhB+Uv?P#ao`_K@;iuKd%8tNlsR448XE_spTfg_XSzOOr7agaxJwTkX;K}6UZo_`
z_P^{;X%dANM!oe8l#*@~eeh6%X}+GLV<|S^j8b#(^sRb@r(hjQf&uL49<u(ImcfT#
zrBOP#Ex9u2x=3BC1QF_sVcIkC@=c07``#juD~K=ZPXu0M0oJEz=0xc%ZMkKC^%1n=
zfzue8Drh$^4=3@jKR?14gi&vvBu$-Hp&g~Pci2e4?K<)d3u<Q(V+<ghj-&r!1;Da}
zsGDh!a)tjPaWHQUbJFK)h(o2n1W04N@k6IUYO%u)kjP{Ol@4s{UU}C(fyR{Bk)^*h
zVMtl;Ln7iS;16bLW*!<erKfGg@kz{vxX|9WP23UN$qz!^fj+X9oV}4446L#rased<
zqF?_yBgl8zq#O1MG3&e}A`0aP>UW*)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(RlPP<ou?>nwCr98O>ZG*4DRpX|=34rRO<pSyn6L8`})eeWi`H(rorB5}k
ziG`It8buj`Co-|wW|kKNl^sHq250_`v*FJZQ%hz@tyr`)GHPsli<!*weJfBJ!kIVP
ztF3ZGJRYWLYuI@|-F}`9j*_>JcKiW0`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{FtY<ol^TA+0ZS+z5#)
zBD)fYu?6(c6jKndq!9U0wf>DUNy1v%?wrj^c1RKM;GlngC<)jHvBr}ZN4<+9>KlWU
z03swX>-*bza2(mmP$0(bO5q2@$)+)PG9_ebGPB3f6(yv7zDx9`YFfIA5wl*Knhhwk
z{F7zeNTAjBSGT45y!Z-;7`5!?nTKVfYx7|FTk3UBZa<st2epq}6|zN4I*-L#aWv1@
zc$X@JYhxies4`-_%EXfy=YbkPh%6I1iP5vLRb-f83SJV+t$04c>r@m}+qunvhEexG
zovuuF{tp%wL7}G>+gAc5Fm&Ua#$vu_7Jf_RcU@)6v88y+(3YRk<A7_k|K_~Wu<^U8
zK+ix&Fe*N#w?8L@l`QPjD|c|vA8qbHF8dl%z$E&Tv%wpG58q2xm1G^W-L)=lge)m!
z{eqSG_kHWudCzcQ9d&rXj6@>J-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@uw1be<GtLyLh5g(@%!Y88l_uruHnt@~
z5}Vc+Oy}~j$+FkX7uE8D+))4q?bUspyjZ-Hu1yn-mDSkbog!ASVR83+(Fp>yfFwj3
zqLCTFL;rR<aJxpwi5}@=ZdXL}Os{bA&Z*Eg7u8V#?o-HCjLPcESJ$i^Nl6b?Ae)$F
zTsb^!(Bh_WpB6*QzF3ED7&4_%soI$gaBmpA?^cZS*LiyJ=Ar}=<HVC#$>Wg3o7V8~
z1rUTdJz^l&{jd`q<ugw19gUZ~&PQ7fX*kJ3wyRHEl^)g%v_0;X<4`Q%@2ATBc_*ms
zWu+UY*H`Vj@k&i%<>Id{y$kP`ZgFhi*?Oc<BYtY!X<w?<LSky>TN$#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-NOr<rIC*sH<
zKlV|TUnTdK>EwlT$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@)t<ESL2u?g8pQ8Uwor`mN0H&Spkiq
zs~ouh!hB8xZ>gRPP(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<{P<d;bm~r?ne6O~D3)nSgkr1h%)9ybRDK$esEArnq6@Qh
zPr4M3E}^PkIds?EW`lRQSV@W+hN?b^4gxs%C=P#_dB<iHm4S<7;~Jbji*eoWUGRx0
zpE)rDd)94@4}H^wcEGORDchv&sFs<hAkecocb|FnU>EJpki+=^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#QbW&#4HoEhNEfge21WZ~
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~^<J+LM2+1>7ouTEz<gDM6Ge6op2YVJ@A_(;IZ;LK
zU`$jeuJ{0nQLLiM)tPC~2f-5tcQ5cBdm&rvYt=r1xSpCC;|~*Db~(6Bj5sH!|Iwm;
zr#7#BGd_E8X&rrLdw8na!P@g8PU_73iR>&JU~%mIHi1l(TTBq=U2!GlQn(ZbCqb!i
zCY5lic4hs4T8}YCr6OfqQr7rWraWO6Avu!;(1szk6dk-))JrT-4H97z2ONLk0`W7C
zO8cN}AjpXDP<j5)2qO4E#SP<)s6QI4z9%s;jtY$yN=+bHUgZ_J$pqd&BjS-qwVWu2
zu*I5{aL$wUu<JiZr~9gXHd+#wZ$Drdr|<lB0n770+2jH*@+ajKL&~Un{D1&w9UQ}B
z{FX@!#-1@fiKFgOs*9CAm20VL;Ozb%6BEcHC7P`700x$0G;ImrzBicXX#0!3_aKR7
zKqZoV+}SJbUdT!`z^#AWOXVenLF0sXjE289aWCRo90TI}U9U@TFL3kJED?=;$T9*h
z9fij?77wjI<E{Dhn3~u+L}2+2`|sB9Td{_;@t^GoeD?-S`TOjvaeJd~8sdDR^v-dU
z5hJ8ThSNLCM&*1Zfy(*WrUXC!2P!CQfN+(6-fX)0Ovum~2laJ!-_^1Q2y#wY7G#t%
zO;qYGE-#jXF6Vza>&X$>1+zieV}pLGLggZbe=`Xnf*Qj%V#7*MeeRV?Aa`QuO8_c7
z82`=uxyWAG%Ce<to(R~UXKx%cT8^HYTDEp7YSqj2WN9j9c(>N%&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?<n6>ns9LB$u
zR+kv4-j&zeM<KbbKB+3x$yN<P2@KnluU6J-&~coo+25o(Uz)=#ja-wPvsL0A&X&6S
zdp3?oP2{`5(Zw=inxZ@(4tmwYR{txZ<x85pDegDW?RN3km|m+Cka#F?ya(>4X;y(b
zC9<W)TQD&3MEc(;1ha?^hze1Ncf4KpE>Xp0R}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!<JpIY<$nul3i6>SvlSm6X57!|47
z#4(j_s}9OR%yb}iqw1AfucwFw#D|10c7gd1a&rC**F$+l<Crl=&v}bVbS9?(hT~L#
z@K8Ac`v;{zc8OagoBTwGCWArBrk*G9E`%U+?j*KaKQGZpVT7vI%pkfw?MF^b>*<Ol
z0$T%RG#?9^_qfW10gs0Q#SMSj?6KWvCIKm@BiFHvdg46*wd*-S4ClT5^?uMMGtCoZ
z)CQeu?vbY1!&gu%imwUg*>xDGVmb|Twz}GBRpk{#a2aYQKXSSJc=-<OgG6K`cSNZ(
zlhJf9n0It8dqtB|FG9evBCUE8#_|vxDZ-5znvjuGJ-O=ieiirQVB94{Mmb3zyF*4Q
z0lL~vCUxRC_Z9^CCw}<ik`jB%OI{&QTUzHoK9MCyQ3BWG*!;nm0C=FjR#%9ToRrk>
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!$fM<k5_pl%y>j|(f3-?79Ll)
z-2qOpG9S!HGu@@<(Xl0!lqL~g`x(H>V+9=%WKfjSVhv_e(v#4kJ(pi(u2k~?s~%7U
zz{Um<E(HxJp!*^%j;LN$0dPZ=q%De-LVNKvjvLXlw&fV3TDUuUk!4plJ(=PyH_?J_
zli8*(>lM|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<On=yXk=l)c+_y#)6{qml+z~<~sj`d?)tGpAhUY)&>>}0l2
zvWiEhX8!No7j1i?`jrFH%dt9bJdp=KkWD2=jmKCHZKrHFy38uoq`W3K#I+!P<?_*T
zr=7dd_=S-|<7%<ayrw|`(KsZ}GsY!}84R5&oa*oMfZoxuZ>CI`aF}x6!Ao%})*{&c
ze4X&Si}tZ`Hd)ATGlLQtnWe_7ab{+3Qt~Uz#NERusZV;A{>oyv4h5ymvtGgfp565Z
zzy*&%*%O_CUk0Gib&`ci<i$DMMAZt91<PUH#WBg7FFL>o0@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_5wxqEMVLhJ0<lTIT7@(mRtOpqmFrDYX(t8N2Y<+S|Ff(a7q$#~X{8Zx2
zW5aH~a~m`3dPd}eH9UQhEh!1*s3~$*yI6kg)8ClSo_I0WjZ{{I{u3h%@An3IeGi1D
zCbt?p(QNK)4i8lmGj6e1Qs@H-=o$Gqjx}K`17M1%*UEOYhg<PH^GMD0{)a?%nFg<?
zt_Qjejk1`L9f^|^%oUPJH#inX8Wt{}A3a4cfX9{#?>S7fT9e|c$QT&~-QJD@qu^4P
zBOc^AG8y4g)a<zzhH$ExzB?bwDGfc`TQW2uS-n%qfHqPxwNYntnR}3M6LWemt!M5z
zjUYZR+1FVmbP48@L`D*)&8~2_d2cL56{lN>cWP=Q5C+le)+1UcoSt}eK&6`d?G;Bs
z)q+IF3kvpyJkOpTccIno7nF`_ylKN5KX%9AgL;>53>dvA&ErV$q$kgRlC`s%>#Yf-
zl<ELet`Esj)9KQa6_6}~7lY8v(%BJ1B{M1Sad;?6e9gMD+I4#4^4h&2=hJ{HH&q+7
zY$AECTg;N_M~&WDxY`<F?d1&Lb*2C7R=n{KTy@0pd?FI|8}shQ6G|axUCq_I>@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!u<TS906FuJeD8la!r2@XH6V1#b>7F9jcjXZ$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!<nB&u!!T1B@6H%#Wi&-#LhPlE+enLe8AescpaO`uO{;qQFw7sK2VK{am8z29
z#p7Q%nT$@CH9`ru2L>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<#?*^<dxZen-r4(2+LD^7%SF^L`q~)P3-M7L1p;O~&tDE04)^}H
z4$Q!cS<_u32ZS>GimOf$feSUT^6fYQ{UAj@7p<7A653a4WSW~oq(rNEwj!2;e=h8&
zd;JBfwf#ozf*FB60Kw{NW{O*Nz@3FY*$fV-;z{r6bS<^)5a4hlLaFOLSy_<bxXfS%
zUOsxBJZKXg*%Te^`o~6U;S0j3G=7So=9v_6B0Gth6@lYz%Mtq;J$K7z7RRbfCm-@#
zj$D81IfQsKZ;P1<-lZ<pe(6hXU)+Q19H~{9;kGw}yj8=gq_sx`;FgON!Up=O1LVw`
z6$8dEG_GO55)QNkmqV7aCi~Kk%}c_BomV)g=F?wzuFuWhMNIdK067@Cfooe|){pDa
z2uW}|yLnd|(eLapwraPu!^xEOnMcXSm-xDckZ_O9l(MI*aN&p73b{=uOHIVd8pvx(
z$#g`j%q_zNNmx5zZFw28Vs+q{j&$fo)Y*|7V+4rX-Q#h85U!%)k#LdlQVu9i45Ei5
z$uJXe&mF|K`Qdz{(svG_?bq<QPE3>k8geTfyOTy{KYF@jMplI6>2Q9y0{vO6$k|pR
z*VSs8EZc(l5+zXxGZ=s+*b*Rrkb0*x=unz(h!(){YQYPqYvjJQ$yoRSCFv>D&Z<Xs
z@#|{POw@{PdLVPQwezIzJ9Y*fR8*rSsTODx|1oc)f0+cJDNGKzp2k&y6!_ND?XuHA
zVz!VBjk%RsMVLcVr|A2kzvm`?`He8|sqidnuHSgE4lJgSq{VTDi=4>tU3KV-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_Z<z4BKg+c)oiO3#7}
z)9J9%p`rE{oV87~hj$D{z)A<lGF}QRp^2id%j!`DHK^4Vq&LuO+J0k!ky}9{Aj!c6
zLZYpV7Ou1Zz<g<Lg^e$Z>po$ap_KUz?AJB6ELaF3zDK;GvE{un0Wo52cq}T5TZH6`
z$6Q9{!h5xU57D+PP-732#ij?SJW20|D!7f6&y4arA<z{F$?GhWy4)Q$OCUTV!MjOU
z#RNKT>kvYOl~AmS%bp8TMX}vGud-`ZxahYE&fc<G7h||)2<v}W<f)n?8ypx3-!io&
zrx`C<Vi>OH7L<=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<dpBD!sM6Rl8HO5<URhF=taEV|~Eu&f3wm>`^YZGU1PF11d`kd)h-{QonaB{S`*)
z>2rdPv4UeVDaLqYCis}IZUfgrr}F4JTJY}2p3Ri8)YIrpV1Cr8NzdC1Y&VO`rvSby
z@yBc$g7S)+4P8Bui(mc<HohIlIyR`iL62hW#TD8SMY}^dEsYy5ylm7xGm<dOoS)bz
zk=%OQd50Th?XrlWfJ*N@rQygdJY*l`du>@V&*s`{5wFQym5JRdz3iJBi~$03JpJ*i
zrnX8Dpg;xPn$|o%(Ua7YJ!F$9@Qnyf(`&OXc{c9}Df!*?;<tPf{I_s+Y4KCF^0n=E
zc9&+MfLqrHi9=g@{;Z^H?c}vxfF-k}%H-4PbNmQeaPoW@^}Z3jh%xRGRv5)Pzpw`i
zV4y4&N5v98S_57(VQY-tqlOXFSu<zVO8%G<nGum`)!?%ZDgL`_f+C|3Q<iB$-f>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
z2NNL<jRp1!akSfaB+BtsGS{n|I*_sW_M8+X_uP~cWEFM%?1jKLUm9O&+|kg*+@D(i
zc#}0M$p|DL^;h(3v_wj6_1D0Nx4D}CB{|HZ=Y6x_p)$}6+VSAq<n_4dcVed2En6{!
zr4kRbfN7kXd`3(a7az2DP2Xgqv?0<3K=JP&Sj&0$0n5=Qt-UEsF|Pq)8WFX}{F1nB
z6Lbc7K`W)uxtGgU-MaCHUvCkZt<3ML_HVJuYX+oxK8)IjQjhkHx+)lNo|6@7kdt&O
zocu{+&g57=!K0I0P;P4QQ>1%>K)WKVt;2a_L0~*8y1qr22d0$7AAeeibYIA;{~Gpb
zz_`eqwbZSR=Uc;2$;!OSY(yubIx-iy>>qn3bH92*CHt?8soQoJt*Z<zr(sJaI9Js9
z5jAsp!1*X+@b8li%8yiQrktoroAgM*%E0sQ+?EI^k*Oh7rIoyV3r4i%n#@JOwt#re
zHY?=yREo+I5$>NFu;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>exluOLySW<?`Q
z(HJCv)(Q}>2KKbiO*lkaD02x^+ub7qj_T?OquxXhcTDc*q87g|JwKe@XXn;pGz-nK
z!_vB5GdNJ<zCLJ<lE#Sai_3NB^A#PyRXUbsC_BZTd|vMO6EYo6Ne1qX_>ZBiLxPp=
zcsS!~2%E?G%uVJM44&sN_aCt(V6J9@GE#?um|#N(x4ET-lFxUp>!GO?ok`WBm=|_9
zL~Q1X%gi!tWg$C0f;MC0y37W0@6<U?*fUtz(Dz;6ogs5gkNx)q?Ek>um#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><KG&E(#EU&tDGR3$M+ZNJnE{x+l3`z%)sA_Id=pF1)J
z=M^|#f$M~Loq^@v5ar9!0$L)Yi&J>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{+<pi>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<<B$n
z-3YURciE$AN2XLg)A`AKw|8jk$aT_O+Nr5?2#x*+COvT4^IVuq8sfvp8P=X_BiEll
zVdA$cg`o*&27^DUC!8NmS1<sM>tm<gqb+RfBH`@xfSYBNZ7uLnMK+L%IH;mglnT9c
zWy%ia50PDd`^wfnX$Ir>Ta*>>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&^6ZB<?OmcQibMN?yp9A-+nw}NR
z!(B#)3lQB62J0}%3Y;{>K8Uo{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#d<Hv4u!P45BwrB
zKj8jiYyg)qj)Fhr$H0o;=f#pu;msl!%EfRU8ovR-=nYrvLikFEMaV(ckqq)IP4vxE
z$z37t-R{m_b$-}G;F>m*ZeFPmoKs4=!($l*mqH*^JsGGPD4e&HqIex>o`T`CiHdZP
zaBiT@tM3&%W6%ouOpX;VK{ex4JdS|^WB;4qG)~T?E+k=mGT)`bnS~emcxiA)zQ2dp
zWF8N<v6)(x4l;wg${whlwU>P!qDGO4k`DQ<oE?hUYzwMsIOP^N9h{S|L!g2Hd57>I
z;{W^_(;hNQx}%!Xja<<)EA+!}#jR0c(V`%_J&AJgwfjw1b#Mr!xv+aS?k^M%0Lr%_
z2fU`<wz8Maz*0>60CB3G(vHcfV$9B|?>5!SEE7_<%R<YUpsN+D?$2IDi=Z!Sk|O$M
z((xuI0K8eol?lJsCFa+hFwh%&=bakWxSI*1d3>R)3(CxoJe@%P-6qJ~P%A8UTYdG%
zOp}2+9pTQg#N+(X_UY@W%!}f^&(X4*rR;KZ0n~jleHAIatyY^}39X+Y`z=Tmqq&ly
zagm+QZ<HJC6W2kD_6y}xRsT_A(}x;7!PM{9Z(<`>fGVir`TRKyN<%R-R0fSISXyPQ
z8s~+Q9mzr`Qmc(vX{Gl+Vz(>86KZT$DwyT4DJ3zs_ILHO_(5Iz{mL<B@UUNtBj4bN
z1O&84z0kH|#d8Ajv)>Vam?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<qRT<(e_~pjE|Kn{luf>&Vu_
z+Q>51LnSCKa^w=eD*>uNp{+?goX4y!O69bc)@v5_Fw=_!#?qu^fC=<Wb#iO9doZJ~
zK1XvsZpUhfSPlfYSrJHuTM|PEXDdoB+j*vD)p0xV3q_X-m;5#}Y-II-_)BM)QS@fy
zLLy@rxNd{dlLU4dy`^FpSfO1H&8UWSD1Crq-xO(i^J2EN*i1gQJ?z94RG!u1ZUoM3
zqL>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|<VjiOm<V?8lC}5oLS{+rm#NW@Y+L|Fn<Segr>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+Uf6Sb<qVNE>cnx!U*VR;5+jaVNLZu
zy*kOWNnc<&@q6ajNm<d^qU%w=8nMvSO|5+4wx!`9^MWhn8OX6y3kS_*LAvC<tO|%O
zgnrp~?Jh8Ek=|dB!rJd;oeLwfHRVoyyVct0gL-U6BG@81`JiviN!)~+=`Bnp7+{rt
zuoE>W+h2pVv9!X%Cn-Q|ma$&A$)Iq|b!>-C7a*?=P0rl39s0Ep(CGI}`X10D{2Xse
z?=h<ak>l8;ekuaYD-(xS#l^wqn<lhT={knRd?JH4%9|fx@*&lj{Oe&RvPpa-T9^?d
zL1UhrBD6~GT)GQN_lXT5f#N{)@3KAw;FY$SFy7`iV3FtuQ?j9$Ft+0xfYlJ{TXofu
zn|ovEnUcWE9h2wXdV`;OZPeRNJk;dRknd%)(hfFRWQQ|RxtYK0MlI#Fov{F4rk=$(
z4%t|}VO{2B$wgyQ7^-?(e?6_j>w7pZw9MmvVWk5P6<Ox7qIngr4u@oIrKAoKvDcMi
zfZ3LU&6}!Me?7815|49xbUPoO@*fr}32^9otIe~?``J}jlB2j;P6r488epl=)NQBL
z3MN$|oaDQ8uGdrLoJ@&-fx%$*CjwSy!;>%?F(}@bx>0{W3I){uDYr{jZSh7wyK3a{
zV+_3LDMQ(h#eT-&Wj{0uO!~Vt%gBdNUeE|4=@ipRx6if)iM2z5bH_tu6=rek9zb<X
z-fBQLFknga=ns=y_w!2%Z3Vp%wi=snWD4@SKNzfvAq`D)&2s|j`8tEsISQNIu#Yux
zNQVlVS0O3;<Cp^3;lj!*IYNxMy$KoVMoKW0K5|;jQ+3R)IMC#GfjWQ98MAMTSw3p;
zJyOjY-0eb9$bY24hc=kxE4)q-l8Lh`qqc`0I`P2&NO|@^AV?T)y$gS1ev)5@4K*LE
zu<X14N*2{lWIMVpdGf8EO%{xHWp@@CkKK{95S$i@<WxOCp<AqN0hPNZ)4m#0dbNSo
z)8EQ-Lf(0&BabH(DnjjsDfPm>SHFvffGQQ*_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<ITVC8?LylweMy`Ki
zeIuOzZar&Q{vwCTo7Vlcbu^E7a?%Yj)h#9@ul=wl{w-ke+r4B;n_}t~ai7V7Mu|p$
z%ol<{wdj;i+Dv$wI`l<@Q8AuS*)OM!e_}%1K|)morgOZ}igjJxzp&#IfwYwVCPAZn
zVKQuLUhorQ;3q<lff#Y(J7)_KA5NNo{?PD*<(L3NpiOWG>;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*x<V
z!*BbOzCmp6!!pY1Azsaj8mQkD^CIbk0BL3ikbdv-V?;41^ykShgCM;TF$mZS5yV|*
z%=`!^WqSqeYON~%sN;4Z4Ude1i<W^?J>7=()=fY0Lw4j;ArWw<WEUt;Etr4mlhu#m
zZwM?4zJ@v0xNv)tF?<mI#XCSt0Vj}OfkF3tQiJWXI~ZPit(5BxdQr*{)84TL10Gu6
zdXNjnm0;cksn3|H`xv<+x)2Ji_LHez@HB%@?oX&s^jx{)1NTeoWRdsjOIMeYP*Gch
zLSE1bUEE*ZQp`rvmY)wqGzz2;X4NBgn<WvtKRTJ!co#URBJ8){nf{lB?~2mJ%rB52
zp%8V3wM=Uam}ov0du)8D2WLs9?yp8`<&9+Qh$+*)vjXfR-lHzEGI@cP<1p2D^b64<
zP=b&_xVAUpIsR4H@9Ne7qjoRE?0uG`<{|q!v2?Y9a_TWqFL|yai_h#8;8W5QzL_|U
zXTz;EQY%e3dAiYi?zlKkbjiM=BTowB^iSN&1h$IwPeK9>i)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><NYrCi>!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`M<M}+fX+bNgH%nrc(H5{Lth*`l6fd9>ouhf=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#ov<q<j<hzU>a)NOW?9J{Vz5$z9mY#~3>@f?pEnQmcO8I!~
ze~wp>qc2@2M?_-l4qbWYbG^QINu8P3sNSm{+5@5#&%ruAOS<BfL6l3~vqN@Qa68(>
ziS0G!4*$b~xGSIY==xJ1rOCw4Nf~p6S2e_^zb_`KPXNT*8rxQN?b35!5CW?+xHzeD
z<i=c|Jok*CBM36k%1p&(+AglW5*s-~oc_wTx5+3fFV@z}Bt=E5O@#x&{18ZUz09**
zL`%9Wt@*SB@czj5AQ_SXCp8SdBwQ48`B6a{o?A$xh3THcZvC?hZ{W6pL(Pq;4g!`f
zbE)L`d)TWY_t0t+^12RRQ?1#N!7UCa-F{rb{R(-4*Ubd<dln?b?dJ!Bo?<qbm&(S?
zM0v6J1d`PE38f<qsv;mnl=q%Q27?=_GrWIP;PC<2HGcGogG4*!Z@70zKW7VsJC1SX
zCA~+iAH;ApZG27dpZBCWFF)Qd@Z*4#$e<o^7Wt{*EiH5yQj0;&aKD|}i<5Q3`<2~3
zw}`g-$UFmazyld|AAmK^BpgRD=9PiO19zdFv5SOE^EE0$(*>i8D`~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%?<LHTzGO;NyIJV~pZi?<6s`VR=E`Ys>5
zR0henc?TV3#l!!XNAuwPBrudQ&kTCt1T7@O+e4NLkCDT>OZ$Xhe!|5gmQb`maE`c<
zlpF6**U7>&X_Lt6IwC1K&eQam82!A$1$>m~<J}`LO-aI%u1rW2L_=e(2ZO$=kh!J#
z5yWOFZ8G?iPIs_}0dFWuO1O_WUhLza8!KAEIf?eE?_wj*^{ua1BRRQ%7@Czt!O9W$
z{q%-FxXrKeI?>&x9z|n&sw8qp4Smv<CccKEw|4`0EtWtm9ml$zp3ctjDH*CW4<Hvm
z$-yfc`VJO@GZx{CmM(HNK&>A?&y}e?AV%*=UidB6Xu!e_3UwKCc<m}Z_-+T|BZgAV
zWa}MZQj|XnSpHh=qcJy)jaS~@1BkQMfC|@$Ri%7IHdy1!Vw!brMORj+I*+IDeFqgD
zxuC=vH^%YC^OsAyi#`!2XuLp8<a&$-+!{B9?FDz%Odja1n?G_?F>~)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=A<P&L<jh=<`1R!$s4e?;VUDQRD3uj1IsaSeE
z$yzMzl~bYq-J)hKNHa&b>KYc;E-AFxY)@#eYzUuU8Jm2nEOS(>!bI`NWWJ5Um$iAT
z6BmIcm&SHJriS9<QnG-MzU}%G<)?xSuRaEg-p@4fe2Yh!>XtqXG@sZIaCOgG&23@G
zajG`VVV(`3ZZTkXVPF!jThvA=4K`<rDPSCqh8O&xe?L~*ZE_v{H^pc+>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~|?g0<i&K&RS7TOrNI1uA05gq@1HNEl)q`_%|^i}dqo8D`@
z09HM7=FS2~xnrs|+IJk0>Z8#~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`<!
zlT|v3ii}&Zt%_=999DwpF11f!r1g;TF1h3W6KVe*+6UzA$hzS|KJFmnn5Q}{u8j8@
zi)9NX@Q@r;TEVORscBi}_4b&g5hOdPV=lA0JG_m<RXd?8bq>)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+8<UC6J?kiBaT*A2Z@Hw~hfQ^~UBEa?
z$zNk)<haC&FS!yi{O8=iA2=t6kz*Gb{<cx9a1fSAm<Bw;t)o@^_tOjSp~g{H*nM9%
zzXptDK}Xi~))YBn`Siz0hoH_%bC~FC9Rnm7svv^j<dxJQ+Q#ulUv=_kr*_LN?R}ha
zPz^8K|IzNwm<lnYMPth(=5X03*4B&*PZD<ZUusj4cR>5%$-pxt>v9raN@EkQ2UK?H
zLyu1U=qz>wdhF<J;bl8PaVOXn>9$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<KXj<A3V;|!7wrOgvqc*cp3jG(R^>%4QMMS%^fbfdh9?ZUFT_L`5%+<o6u
zM!qydKaYK+M2?g(1Hm`ksFD0+U_bG83)G^K%5)wL<RbJQZga@=UI<rfhYe@e=wh2>
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+<B8}k2#@1T&R(Z_!UoeetmH4fn$NTuvgQU~bI
z-U%L!RZJUU?BizIs#tl`2GAz=VP@I2baJ}bd0}TH4Ay5?*I_gXpi{JR$|s)HlK|Xr
z$;($G`aGg}EY@5I7NR#xT{5`956H}zT0Bfpk@mCRViZ+=WI3iY9}%_Its6sf6;(q0
z7H{loS0F+uVqp0)qKKUCZm;wLU}l#Dn~)m<W4R8Z9W@@|^ePR22G>{{)JJfbb#t(5
zr*5|;13x!ym1tWIrJB?d(6T>wRxTZzCGZ*{zeuU?Tx{w^7kiT8pD6e8>t{I#^~7=!
z=)22=Uu=|yVgYs<c$=t$18aiHsX61pLDCP1aUOPp@;~3-MN0P}z4^L-zRP)sMXO?`
z@fl%|_*hg?NC2FbF0@*UhIQdb2nMXi-<d`@aA%=yh`K`}?vfN2y!{H|;QjG7g9OW=
z`px>*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<g}N0P3gemN?qgKFyS&HPC@TR^0$ZUT9KMkgtHA+7gyieHVRH-5|c6((8V3ab?Q#*
zzD`=?Rwur+f$IWZo82OyQZbOIrw-{V%<`Q@`-6VX!iPOUVCKCTa#S=Mf;|l-&m%%b
zq^~jLog_%2SM_-*-$!@AJQdv!VoZ^@0?LXf6|TrG7eL`&<E5;@tM`gdNEW;82GWzc
za3)$^v7Am7f><DS22PG%WJ(ppmP4n*|G%ZH_y>)|bcns0K-kQB)mt4Jj8kImr-a@`
zhJ8~`e;?`?i8D6;QfTJ)!Mp5Qlh<e;rJc3II`LA3t|oVcFA)TP$OZxasCjx<BNX4a
z#$CB{xJ7oZH;GP#<)RAD3;+%PVdDeCf5Q>g+-$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#8V5rv<GHMdv=tA>togu^>z^J5wrrHX3$k(mXjwr55d{~3`M=j
zt^hKiNO-d2Cc*W8MB~zvr(VpSmA<i}HGvnK!^sRsssHK92dNKUDGN$J$;}_Vw}TJG
zQlqJrXVc{4Y%zZ7*BI&<ADs%FZ-+cW@kW)Cq)o5^Tix7A@vNJ11whqu(8twv`-wwN
zN?8?>Qw2nh(tTN#w1_|rkxL;^Lu3v@fC=Qv2`5W#g3vWALzZbX3hJ^(y;$i+E-eSN
z@TQ`g{~pmGnfu9ruMehuwWJINJ<uf=pC7D-sNlrIT?nV>p^hD&xCL0fm>1B=H>$OA
ztgv1)pI%U_Q0e{Z?!!v`(jxJ$asb4=14VR#;+<WUU8G_P?kc=VR8?t-m^LO3_Up7n
zRn0SN><)w)MTF$aX0-HB_(c<SH0M_2L{79nX>chC@A%f^h*Jd6;=<)bFs~RDV_h87
z<-8_Q<wM5^EnVl-0rEcTQTs;UUHM{tDeLh%Y?cDBijd8o0b83Tj^p4E7twTdj-!Z8
zK3)B<b)Fc*4kuwMGy=)*-x31poPU^7pIGXTudlXId}W3l-xErba!h<cQRX_o7s@Z?
z_A<0oL~NQeI%Hc}id&Y!nXk^BKei-aFjRQDbVwpF_&U&4#*0g(b?VTb-uBqE;-l+D
zz7?^xg%zMn=@F(iHeuVvlx?opsJfte>}>DV%HVmY<j$5uUMj+Fc`*kBV#rPihUZv^
zHkBR)&=g&M^9Y+@c%E7uTg`#aBR$JOLU=7(@{1eV&z9Y+4r**A!Dr`9EU35uA;P)#
zvOSsf>+|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&<Um-EB9w<{|C
zYq<|G*RC%S>`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>3<EdR>MPB@;f)+1;U%7=-{8UatpXmUsTN-swVay6?
zyO&F5Zv;X)=)A><YD9Cc4c*#ZQ!<t8rlYv@-8*lMShSrakDks1<$LE&zYXYTwfobf
zV;_H-Jx~KXo>!=gJn9z8k7HeucpJr!Iq<Z7mhrb!nEJQ3*Ql3*IwrY}cKYWt(VRwe
zZe%$onO&{{=a=>>=!~!?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+R<Y
z=u6u5>x9UEKGlGY!@_|?AkXvW_8$`X)rHm~$%q+xkP01=gaIn?y2AhFOI;SiG4z?c
zLvi*^P<ft~SqPkJgy&yS{UZVnlQG$%%9spi1^`#GD88RC$>*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<NuDXEbG
zTR^Y-I6@0L=#uoBzi{Ofq(JWa+NzRndor+O?kY>}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?quDj<yoysDH0*(501KkL2!jTUwD(&Pap
zL-c~K_J+Le%3`Kk`UBkT?sf*$jYvWBK@&Nv1@cO$drGhMg+`oP7uuHBpgGp>iowRY
zf_@c?a?_|fsKo~jW^eY~Uh>mqJzAjYRnrbiLAHyOh<f!a$V#?V=xhMb2&Kh09ZP4m
zs}3b@L&fUX50R}$io(2o)*~qiXjHGlk#B$4?7?<cjEbFhyt-=1JM@r&$mWZjuYLgL
ze6HUhp9g9sMnf0DcMHA@2)-U9r<e~%NRS<0zsyiS;;_1zCsU4nu2#NdMf>tC2+E`W
zB{k==WF9fkxekK(@Ztn#h|Nm=bxjebMtka5+E3<=G6&GLspAyaWtDCl$gLM&DGC<y
z0(wEl_w8Iyd1WkLWKrSd<a&rs1jl)xnFe(gt2QG0#z5=ZD3Hylf+vW^`#GEq{(;wF
z<GDDlj93lJ=HY9Yrlq=~;sK1O)=^tiJ4WR82fLw0Sgr}GMTyU;s`$>DXrQN~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_8<L(zA
zFWq=l!CL9?V2k@|%V(a*LwlVj;G@uL-WQU73D|zd`6;8`dX0a-Y8DLoLsKPX$G_D{
znKp;#72o=Vl>cP#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&k<pMVYY6+L)WN(&u1*MI&%#Uqsv;ydy^v9Gfh9@LMPC7w>8QY`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$gUAFR<NFuy80O>P5Sam>&Q=a17Uy3#
z|I60yVl~<e;<=&TQfzd`UIEjzi^>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>DzwN5yidE<i^tjV^G5tF^JR$#l|qGJyls%
zpCJ>e*t&jOwn2Br5Mn7YFd7ApSL}CSkTwunbh(Z7n2=vzS;vECnmSv<kY9gTR(RZi
zI#OaVI@c0KO>wt(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)<?YGB47K`WqmlEk=J4*@ATj#_{b0p{hm@Kdn5XUG=3~uzP|$31c$`(
zX~`@7`TW}<sMfbe)F=&))X(Y(Nmr4^`kUBo44bsRJHuwloO%8B-MT`-Z7^}Uj)p9A
zZ_OvoZXQ^v8drK+@xst;05gTYlY$=bt=+^$>q~f9N<m)B8%95tmnw3gRsn?}4%BbJ
zC>G>9sACFqM)duvj{cfMGOsgRL<e_bG7h0Q3QbFijMZ_k7BN^K?*=~>c-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$o<T%q3K)Noy~S*>Xg7fjHN?}YdCmAFZN=V-aV5<Sf3sA@%a
zUpi3+MSc`F+zly#)nE!}{fJRArN*+J6d`evs}#AOu52ZL)v6A5hFp1;9AOf0Bi$s`
z0@=M8p`1BZI4SP&z{$kOQXlLnNv@Wkjpl$M^nqf2vS7`PGkK4x*{Hc1bu6mzT<qvd
z-#)?S1?!~9@D4Lr#ovia*=%v)K32BqtWUR>flJBvwi{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<oM$qSjg(|VgG;Rf#As(BnwGu_e(VE(!4D$tr&zWThw?vHqMtOIUo|*
zi=9y0tK;>;6Vyl94kkd23Dx}Ck0;{&4ZSIR4YoPFkO?t?&L2ViP9<D5rLaPk&HCYn
zC}Jm;{n3xGN{2TJYmRh#?*E=&ft)x7)~dpdcja+cv)mV_=aZZzw`o90PR;6nR^z;Z
z8NjWBfK2IJ4}z?#2;B$*IZ8=c1_jyEQxMFPI8$HEL~CsYKBVt8uf#-6j*LrHlC8DN
zvakHhUa-*N=3HG(%=(TEdN=X~?cgt(7E-^8R}@=mJN#M^qSn#)5MsVA1s&^JfRVFN
z*p@C?VEe-Dc#=BiN8{N@CHaX`#8Gd1M1kjSL5hTmy7AP$ZC@@Ji6N9wYC143Fq5Le
zHw&%;_QU0qS)OW!RzY{$HZ`b58Q8(1OswBJ2gHRXBE$T_qBd6E(6lpI8^-haQZO@Y
z8vkTPq$v3=^Z*OFgqH<HG4V-Et|b+|7-D~E;81SP1RZ<qJyLH3XiFn@J7REM{5@kH
z;i$wp%=r<?KfCV*UOCM2vICn9zQ4RPmJ$!x@e3Dgb+=V&xHR{|D*rMIT<wp9fQ<kb
zgXa@YrQ_CxbUEF^K!!SE(@Dw?Cgpr9rSNZCLWE^om8%pSex7)I><?|{ecc5|HzQ$e
znobAEIA=|~>eV^?Te?sW&?HwA?gVWcQjuA)9Q;SoDL=<(@(MP@AZ7xhaFO3#DM_%_
zzq&NjAqFF-q^FA(MRT>9W#^qOmRCImmTCu5F|*ee`N{^jQl<(UuC050G;h$TX0tf8
zhdqSe25V<WL8w43(Cjscw?B7rbcppak7=6zOS9550=&L#&&w^hcC-9kNU+R@p?AwF
zT8u1OofJy5<GdKe_!>X5)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&)atatm<VyDs-{jz2)f2-@|!N#Su!&z-4r}|Brza9jKeL
zAc>VOqucH7|GVTEb5n{uEfstykH4=VxL;J6hpRB8i<DXTor)Np9oqYbJUJ}qjkZH@
zz&f`wqri%6;+t&s6`svBI6+p|NbMRXyL+6D4$H-4UfItCPF<+sUosSx`!dY-qR+TQ
zHIhTeW0b4)bbL3c>UVRyVJONQt+tyaOC?rr*a=M8&-o<jG}h}@VQKIp{9sSC;ak^x
zImnD}W&IH{mi{|!VFG=_KRu5C<!T4zra~~e{5}c{%k4Mmo(Ag-ei#Vu8GdeCJgc;u
z4pu#b{NpKiPk3@Rx2g>pMLX$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!+$z<dPH
zTP?LoU`8b8<w83^fjjT8$`o18?vU3`yHF9okaNr~g+=;|7Lg-0?DTZx(v?SNmk-%w
zw9mOnpNb*F%1C8W?0o7h>Pgu43gX>V6q&~P!_c@|^*90wgW&)PlCH-<D~+X{nzY&5
zo?RK)&o{a&@P4NRp|$FSVDPz%jz|0il%)<0{s%{T1qT|Lh^XXA1}J#t23ECr3)32V
z#YXM{z)Asp#Xy7$P}$uPmbjzGje#&S!nwW*+aZZ=fh5CL^&{(IHR3zL6Y^jjS5~1W
zOMXe+i5SCYGCVxDTL%fNk6wI>k@uR8o_$S<q*3VX*Aya!jG?Wq1Mea<q@{tT;f7e5
zYmJ&evzd2mKY)Oxjv%ovh=9`a{j#tEM5+4rC4Y^itVx`n)h*srDWRy`hzCl3qp>u4
zk*H-?s0T<rbSPhUAlrR$N3`q*?cRAGup#N<GQsn_Y@laH+#KL(o94Y0&+hPRVX(iW
zA!F3bon81aMhwll?|uF-ugT7CO30L28N>1~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$<Xxj$qTbP=)M9wV!)@PFLQ{OH+
z`zqbm09cxXl(B2QrBz^}HTC-q3F0gR7*i7>`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=i<xjF{MA^EC82@umVJ<y#(YBg(jfC)Ra802&s2Fj
z_I_*R$|&cIbknfQ561d0$fMK>g<Sw&QU?`|UG(YXhzyBZb5og>7?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}8zz1Xk<X}fHk)xk1@hvVUdV=TN(!Wso~L&(b3FE{!-7HVmoiSE
zOEQuT=dv>m`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|7vCz<RopbR4sA5r<I&vbr
zLH4W2P}#TQjQ=avie3}Hk0W$t%Z#|XEP3nX*I5<Si_?5-#KCR-l&XZ(7zV}0jZ@uK
zif2Mwa-n6inthchIX?e;@%K_iz8(ZhuuxwNG39Z|KXMgiT9w)$NKM>Zin)`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?
zS<Ut`c3uhjDcCiHtt%<0a>ni$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^Pa<qcS>w2`IR=``nf84-vK8i}A#n0IEaih_4&ws{IUj<)a(eloOT
z^1p{=N=<X!jBB_LN8GMNGAFA1@YtNv=@H4gTS4R{9t=}nRDb$|_;@18k{r{4azRO`
zpjts?x|n_{JP^$+JkTrBbF{v~*%p}ZnKpLqN6!$#M#7IMqFL2tjOd^b4Al!?x9H55
zT%Jz6ZWLZ>=t%oU-%QoIZ>Dn+?gw}N)9vj|bm~<ytj*cMEO1|h!sTw|b-=aGMc_g?
zcg<QH1CTzHX{;@lu?+WVEf?1j$_d2{np+0QXfi_h;z{svk4hIAEw>WrsX3-ZAI*af
z7?Pp6@m@KWtUOEFElN`F`IdaX#j(|)4ztAgW0HhB=KoBBN(}a$QJIi*;elfYQxhq$
z>)kgi>Av&0yynpo8;XwZK_C5BVqei;0mR8qQ<E{p%-ZB;p)W+t8Y#CZ4qT#&IEw2p
z68JShKPj&d4XQd4cYZid1ytWqG(Pj6)Kyya5&qs%$;IAGL$)x7jw_;S@K*lPVw|-+
zT4HzYX~h-DFoXD~gnDvr$M{ZaYhKk_b6T(6FXpy0PadgDZ^cmwy0my^jp!@73nb2r
z2XDn7c?y;+phb^1WtBTR$=U@aCtkqHtG%AI5<yU5v42YXHD!buQW53g_5dol^1mWJ
z9~yK%L}B(-jZpiZgqG|Zl4ad**XH~X&?^z(y-k^a%7Kq<mAu?HNHlHE-aENN?xR9<
z^F~OaWcmt>#Y2~F;v}F9-Sb?q`SCIRdi4=7)#=|m8g_XVaC-UD_|*N7dU(V&{hvNM
zh9iulu=Z_t1k<tqrrpka#?n{=)!A>#uu?t55!@g@4;>GK&;Vy9Qq32|`=eh+FoZD<
zMhjZqUqnVXemMg}Hti62m5z6H^$K{wZrwcnRmsLokFp7||9Ql0c(TsK7ACQx;1<7o
z8H!Fd^TJmgxm~5*<rbf16F&p&0Kjug*WesD5C3lp`BYmuM>)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+u<Ps+!_Lf
zqD)+9to--bkN>fLequTTHs<$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_X<bK9tgxZ4nyPbM+7?#p9oY*5FQuIKH%$|@`k4Zi><z6
zZM_FZ*2IFoy)dwtS8&h*>q1i7u&%`dEm}mL5%Z``Wh?5;AnPGUzE}V}ER&5o=_N^)
zLOrTOiCE3Yf~{ty;EI$z9g7Nz_Tx#EPeTibxFHfbStTluZ|9ITGzC<NQMpvBj!YKc
zKw`*zE#OMx^ya9?%kH%>TY6p0_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-<XBF@a`)qiLjrvTqgr92R3
z6ZtMsRV@48-+GL+;-tL!sv)~g)q}pc&X=%63ZidI`d7evjVicmlnZQ6tXv`~2%Wxl
z_#T-HqvJzC5%=HvptTSj=9&{U(7Zx!7;?u|i+AFnK^6_6P*U-wRiYjRkff2Ml6`i?
zmVx-2bER4n9kHqu>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?9<ZazQ$XcNyMaV;}&Ql|TEEX)%WG
zci%!S5sw+VPY26tPGxsEn3KawT<hF_(ej@1nl-V07SnttbD3%AysuuWM#<N1$Hyu)
zTP|n9Zkb~2Cvd;pSA#Lac9W)+{O)QRt+ygCKI9GVbXGzdd%ZZBB7mxcHEf%Xy!tG?
zSQiqNTgbU$!v-@}v|rD4aqyom!y;SB5;HGxOAdGaTx&Jaf7T8`u`D4@(RJB?am#GW
z;~v4&VXHsO?834+;6`?R)E8NOkQDy}(7c0WB6xSA%9vB1K=6*Kl(Qwp;s#wa#7&!#
zOLJLA^m?zDB^SZ6%;2DSa-UJ#%kzBmDt4jJHS140MZPWax6nU~IzkpqaJ$>Y$-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&q2q<pu0Qn1N47%t+@726b@$GRx_>EK`CbWqL{Cp<*%u?2
zJPAZ5_*oSDgp{$Uv75XcyEGqeX}n#sQilk)pG^_4lredr9|E7Ei??L65!|44wJatR
z;NHJgb?9|e!oQsUF$(v|P53j)3Vm23G<=M8{%uF7<KK;cuVzbAEk92~PaPE@YfQs~
zS?^gvby4(F4j+2eOZX1(;g~Bidt7^+IrYx1w5KI2?c>Ctsv819YZ?;=XqTd!;56vP
zYe_O#_TWkM<C?OS_<SVN421Pkfwwjm+53F1rzdJQV0)h~F+g{PJI^bT;H42kg>s%1
z*!dV)>~}}|6#J0p<nq4lvBhj?a!siI;;CmiKO@!*v4(~xu^R~WY##(;3~nWPy|b9T
zG{K_u9L#Iv+GJ=?FLckeaffgqid`PZ49G^-K8}*vnTp^u3q1259~9-_>FA5cua2sd
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%Us13TsH<twgU{cq?}+y3~)=8>f#?pM&7Sq;r$*B#+G6Hi8s22
zJbUu8*B)?mFcmE(C)H~F;94j~tyC3#zbpjzOPOh#>aLD6DAr+in=FiU*_EfeSgJr~
z9(YQAk!WGyT_!g9<<qH*2##x!U;bY{72BF89Cl^`cI4l~NcL~uj9r*n=}-DLqH&7y
zAx92BmFR4Sbph?ZQ8-p&#dSO({rZQ`bSijLNL&5q;s8E<N;*wh6u#5$Kq;<qJozR_
zw=7S7-Z$dzY$msNkcIuTPo7g7NI~BCl^vvc^)C6KARjsZMF-(m0L+@WktRm!{k~;z
zL)>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-`GZTKmstz<qQ6Qy^}TAavbD;&@t2N7-AwY#e;_8Ad7v(96v^3_^{c&eVKf
z1(M-;!1$bR6`bkK@wL)LE68z~EYTlPWj$X=1gIrQOUnHT=b$MzmInLxyOP{rWvsEk
zlf<a`dOt!&WxX49;46N2pOhsdXU+UcFdh@f#{a8IS5`WPKg273B2`E4cx7`$n@Xv9
zGF2nN%6v!UNQZ%JsM{NzDB`Ozej5pKS&Y8~?6z4G-L|7B2lxVb6P*Gnm*Ye-mwYi6
zF^~EX3_t{3`{6t^Jf}XDof&y9?+lIquhwX|MI_yIw{g(q@A=;tTxb8VVMed|EgF2X
zx~*hG0XH2-;u^&{Ns;sf?zrkee8<YB-M(=*LXV@nt=taxZyyT8R=(^Gwy4ouMB74`
zY|qhVPIGxJ@HVCS9g%NuPKi5Ba16*lTKw&1-g>h~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_<dhQ&Wo%kiZoSPaW4Y}GqEc_Z;fv%p;
zw(m2qvAOEnc%et>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`K<aCZ=C>x`c6B3;=O2KV`cER`db}T@YqG8!8IjBTJPI
zWgNAuv-r2rR+a4;5H8*SWv1n9o}wcC!3H2E_f|Rl;ho{D5u>S1Hd;26IH>q@Nd`xF
ze7m<ON!tGzKvE9)Dy~Ful(Nd}+_4ka*MrsT$MI}ijUV&;s};aIqwZsuf&)^9;oEmL
zx!2{TVabtNv)Vr?cX)PQN#(s+usTN^n(f&?!e&%PH@8O9E&GOKHD{<h&il*UC<N$;
z1pzB?tf!l$6qJ;vN7%bj*#XF+Q5P`~xBdM%_?p20)UBbN3jl_hBN*Irm^_>=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|ZcqzRZt<DnLh<hZ
z_INiyKHfI6e;nS^dRe@FN`xMFX7p-|AQ*9y77)l}@9_X6h2n=8ef&|dYU*HIk#AID
zMHJ12Kgn)t86E3g4EK!Iyqq>CGEF}63a=KCcpb3dpVLV((Mf=)p0<2KU!64`*evJ2
zbOuC!o7zKFVS&j62!;+@wY^`Mz&wrAS4iM9p-rVcq+^l|1zlw|D}DAX8dkqf_-?`}
z5RPByBdp@(l4|P{9gW7v1P62<l5r*~sm%;_{{8Yg&KmF|{GnE-1X&ZG*_0STTwuQ%
z2~CRQb3!fRo{~}oK>~U0!ImlDq{O{DmMlGC<-4(+nNN$A%lj%{x`c#{E-YV%^+;f7
zv_1hhz+#D6*kp36eKcY3^n?shfHKLlQJHNO_eus#kbmQRfhV3Rq>Ps<dN;R@By-^v
zZYi}=DHKe=;F+ENhC*k)pbnQK99CQo&jJo7#Rv>fMqf5fQV0rRdZEH>!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?<ivo<9bcDVoEBbvv&Dm(>Cx
zFmzOP(Ax<5=!=~JlXVta{(CT-2e@JqU&};PYHybjxLd<@d;e#EOzmzdhoW>6oG}rJ
z{JYeTZ`6fu!acKyqec4sQ75oDrB_$-istbN?nK<S-5fDBRDd2HSE9W>xeF-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<clUj5Qqel(7R~c#JctLy4iH*oyL!oIdmKU
z9i33ze_O}osojwkZqmWij+=H$#he@x5~>`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=6yW<z$9?Bb3^<j#y@bU%6;qZjUbo_NICt76a$Gvy
z<)~~EbFdP{nqyoP$3knz7NfdiMIdG?ZK#z+5EtysmiTvCgzEg&byQJjoQi4$tuU6G
z@<u)Q@PNFzQXp0=%>6HQ`#TdqY?;co`x4brdsVMC!P53_u_C)7b0la>q#P-4z!*)=
z<rCocN$d*xh?k$O-?a)2(z+si6e+`&4V1~WP*n5&Gr+tCy(2Ckz@T7LLRigRj(Psx
z*MOl6<9_^_G=Y`5cs+(g3wWA>Q+GCW=pp2^OAf$pwXgP8xP$c?=Fq6VO(}={n(j4x
z(d13301927`a-kLgGvdxho6Kt5RFh3U&^Y_Iuh+bDN;fj)T<aq6SrieAoECudKME@
z_B69xAAkPfg@>|P7F6=MBVy`BW>)85v+N8jhvC)mkl5e=?f<l^U|nbI&eR_ItX#(i
zDUlJtHytEZGZ<Do^%1K@=63=euBqxT5v!s6S_gpEb7D*-x>;_h`zWB>PDsLnK1wyp
z&fs+NbdMvHb6f9Sdeicj=)gZPlQWK#Y%e#aP(QT<`{?D~P$pI%5-VXH<Oj;~-Fz1f
z?M6I>au1`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#<MDs#^zxXG
zC(NGmVKl|RA<R*%&1A{Mv$hZ0PZLC+KkGn-xaKI&GE*UOwLn7++A1IxETz#M%#Hfq
zJEaw0Z@o_9BYeYE^k!F;$xd8!K6(j5>fpPFaV(NAJ=0=~C3ZI1`;8#+(183XY;^q9
zyW6qESKsUwfgB6qqZ_8rz<!O0^q*?)^;a#?2%Vc~@jO%iX#D|xPloMxtiQViRwM18
zGiTx85f(+&x2V}L{GcaDn9w{be8S;C5Vr_m)ct~E4Ln2Ik7$w?f;(i+-#7u~6&}L|
zA6%0K%d%|Nu~ay^#-CGM@4Y?}eEb`KimZ&&&JYcskpw5zYjpMC+;t!VrM%@*I!N=(
zm=Y268<q$rzY+2DOOLsyGSpmKa-JjM1P@&lnUAhjW4E@5<m4{{e>~XZ_K(LrupnZc
z$?&m=%ZFR|>JsKU!R-I!CLFaJpL?#+iyiB~Z4xF}5EoSAhioyZ$EH|+^+>gcvW=>t
zxL$1bZp^;f*uhDlAJq;8);-7fn*HK+PK#<zGzNa*-~)kV!Yd^u9O}ZU6EC;j=yvQ~
zlkZvlWFR`BTQ`x2Vi^G?6{l@~I&Q>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!<G;$^Ii<LIa7rl1AMOT$!J(qz`vOj&hhX<f=mX3AgGA3?(s|9r
zIiB_WPEUV@8cST*4F;_o4Z<P_dPSa)e~Kh4BG2twW0W(;8#BmLdKcYeEVV%56+wzz
z*>sza{mvmZ^|qh!n=QoNSe%KqrcS(q7})*98EZy`%0mXj%WQ8Op#8BRPpB2?_v?^-
zLIG%(U%$TK`+5k`N~bM%nd1~}MFqJ{C9W#+fw0l1HUl6Qtq<s@RP&9M>=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!<qs#R<aye5B+poG|Bbq2>;Qm3f4{U35vU)^V_-(N
zdp+%X{%%;dsSHq5xTM2cuNWgYkJ_R+(0_@}M9%d6>9A?_^TE<FpRl!;(o=<N{<}O9
z=pr9=(OMXtJF$VOit5q=&R-8clf366kS1OS?za6qnh5;!<Y;{}FLo+lh@R1nn&`c0
z77>zi7{*@+=85y=a=I+87jsp0pZ2?th>_%+0<!m2uWB`XL6dEBxAl+cWyu3$wcO?&
zIBs6Dt@W&{r?`Xqge15OFfe@-A{2Z?4d6_&w+g3R-xPd<zW(1u$I>eaezql0w%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<eyac1DVvy2EV%LG}_NCQy7J`8%BvA8GsJ(l7`}ouILQ_#;`WS@71N5z2WQk9D4i>
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{+)
zf1e<TR?LIhKOvY!C*pI9h?zbygWu;V$_otqgk!S^ae;EPyY4YaR$4_U8u=l3DQU#o
z(*_Gx@@%Et;vy3I@}%QmN5++P?ETr?DE^&i%vwwLg)b0eupyjtn-X=I9d=KeijUVt
zkuPgr|I{l9sRbkQcUA}UZH6H@U>M2iQPC}yI3JUa>km9PK4G*lF|gnz#`HhMzhir6
zz8-xyeYGPOrfyNaOU4T3J0_hzmPcQvzQihtmL^tgo#QU~35rr$wF-<bMCqXyD}yV^
z&6#7Jr0osBwovKJ?W`0tR+sEXH9v|~Aqj*=us96BPSe#Z`hOsB<Xr)s?v&k<SSg);
z%KQ~GaqkQ>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<WynQJB;o?^W#RN+oyQ|4ipQ`^+j3M1#YS^N{hk
z;YMi0;btktloX)=FBKDpXrq0<sfJ{HJ#wn|IQlOaj$cQ{Q#MnP<B1Q#Z+-K|<s$7-
z1yia&1#;fnP%V)}#&?n=D^Xf^Ov;mNC*AIfgM^(|xuSO<WA$$kPF`wLz(rzN!W2db
zt<PZ{;|C7GkN8KPBqSMG-yIoappgJ)x%o%sejq%;yt6h|17&9iw$zNW4aUSl=HttE
zUfEAjo<vt3gykPe7FSj9fL1E)Jwx;+U>^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;<IAC15-~R(WwwmfRw6d@{xuL>7c)?I242Tu5vmF<
z<C85~n%?;$;mFWRjoql0;AaS=^C5`(;4sQ*^tG93#iJ>y2;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<m3|f<3)e7gC-^iKUf<N!w4#T?vjNZpic#bL3Wf
zq6GO4mIsP)c8I`6**|A8tPayzygN4eu?@NQpkb;!-iYTvIpz$eQREt!UUNJfZN0WS
zHd47m?cQF>$-u<E@9)sA6+w{PszKGt;lN!_^4K7o2<mc@WxCfLhg0TXl!Fnm%N`mT
zNo)UC0Di>Q1-<tE;x<a1OE5@p@<=`;9`;S#q~#<XR+lU39(0d=I)1jmFX8fyQlz0a
zeOCRW++gN6??T}S7KZA+0}7$kiz|g-VrT1i5%3Xz&P&)Inh8MIt{9uqh%}p82|z08
zb>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)Dvr<dI
zoIB{NixmQjArSZV*4)GjNyFti6O+0AP?dGkZ@MMkFU62<mj2WWbxCO`OsP(9E3jqz
zb_68@MmA+KC!0nXV$>p8wXmn!{|X2zbUrD}Anv0uruc>y4B|r`7gd$wR{7$Fphs=(
zX9z;hz=(j0t8kl9IgHeM4u<Zkm<q~3YK=5(?R6i?^K@zDDkK~X`il4~lfe5fc@#Cn
zRohESMn`7qfI5CgDcMn4*q@&K0jr-(Tr)^1a#`o)YLbzr3T{S?N-Q71)92RQ&uzj@
zar~eXhgyC#vAO&Y;wd$~a;}obNxO=i;`1qE-cFbQyz*0vk}MD7h2c45Oww?F{dU0>
z3ubS~6?Kbu7$qnW)Rv88Eiel0t79BH>i*aY)u{(c&4u?9|1)BT?GV7}b$yG<ke=Iv
zcYO8r=~*l@=^F)w`KC9`>%AMA&0;iT`-TcD&l(!%f<#Mi?JBXyNL(StyN|xH>T*ay
z)#|TmYyla42ienk8#7QW+nW$Y<<y_2vNIf>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?<nN;_y!PfI-;5P6NoHhxmhkbq3hYFqTxXT^6zfNL%Of(#q4fOf^19%b+e
z#(ivRKsTLH1+NB<C0_t4Th4=V)PMv<<8rY-HMbw0az<nG<pE=u87@So^kOfx0J_)~
zdDJO=KkAxGYdB_bKIg%@r=Kj8Td=T^VhF`4Z{D5e06~+riv3(S7oyiB|Npv>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@>uhlJZJC<j}TK+B?CLrReRrGeb#9v51G=7z6_{wm7OJ=>PF=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?<?Z#A2Y_pN^3pFr9<-LJey$%_UrKB8?-rzZU
zAdj86I2~>}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+<!
zU2c}EOYR3|K7UpDqFC&@k(@EarchP-0k6~65lch$^L*EqAYLWIt}cHjmaC#RnA%uL
zZ>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=<FxZ0E#*!-z_-
zggE>0#tWhBqJabQ3WM&_7!OU*S>Jfy-Q~2?n48%D%9PP(szwh&td@m}x_##+j?^<y
zt}>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_<mKE4M=);g1nV&>&ghwn2uT&lFLJfcA21tD;?qpQ?$f~D4LKbI3SOD>e
zH4AOzQx)^O2O>+%N|5UyY)P{Ei5iFB_DMVM68=mxXtSdJAU?0M_1{#9EM@)-dALos
zrCH(3=S%T@Ak!Z<cK8$LpQ6oTdI6f&np2Dz2fCaV$C=Hm4k-=n&@SAhwEHlfql5|@
z`5-QIdU|NeHPw*L9recVeMw<_Zr*mX5Rc`+VgrwNwkQSaA-kl{8nn}B>SQ3qPOLbV
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^6<a9Hlz32SCN~)EQ(HTcOb@y!}ajoJ9IIT&A
zqxjDzpuE-+<aK@!@Ya6pvm`Tmzn;0^r?}>UwaGtwkk?6=vq)=vDim&B;U6KBbmgbj
ziwS&ShTuq)qf*YC(UtLRWIGJ|0<r37x_}OEaL?_syWgwY&IC1G8rqXP96qBKq*_O)
zVuiW;6(gH)p~-Q}ghZGza+a`qoggG-$0cohm?qAaP0-zUC`uJBCqXhcRaSY>X+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(<D%d=^r~F_5%X)7fr~z0_c-xPYAekH3
zCP8Q9hW)lL#VfLFu1F$l1Y&5`O*oGp!=hawuEvtKsE|pDY#<}w5zd->=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><PHGD7t|&3)lUX*
zdI@oW@n9}9+5J6j-C*SjMSD|OLgXkPI_5af0gZEMTx>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_sdWfN<tN>qZ2ywb&Ii5TG0Ierb#$+7HL~nEH>>4d9LqK(>LD9;l`p)
zuE)CQdLFW>EaPgO05_3b%5j$<L_+$}QC_P55M`w6w@eLo&mws&5feNsW`gD0Jtt=`
zTu;$Xl=$Md(+PbYrbu8R9?)fKj&!hz<M}2{BIlf$?vr-l-7W|&`^lAmce?K+r}@ec
z_hGMo^g`ei9iV5`MJXk*MHpIxm3XnQR1y@r<~YY`CqQMi1p6HRS<yNk7ZY=8^7%h8
zGnBcjeH6Uf+8#iTc7f3tg;;667Q}=gY`6-=TLN*MQ_MC}wwotU>*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<vh`e#tN&+JBCHHy@N5(=H
z@~M*!p@GWoEhv!tG2ZmUWgiN@!4dy;d@-`<qdaz0_Y@H817D5OknHj{*DT_bVuXi*
z)VkhQ|1@zryg)1`;j_%>(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@<cKFj*yM`28IW9&Dgh8vX~tU{42t_W
zw>)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<L3l|Z8QCBoYe1R*!i}R@Jt4VZOEt96i%8aAy<Zky_$q9${%v=Vwnn2sV4=^|KXCU
zKy@;f(?{}7R8;#$Y1<Lqe316wD)~0`WqsYH!ZEfx(w()465ZdhW^2r}7ZgK9B3Iyd
zh9WE+%P0MU8@J(mcVY8`*ht8D%@g$_<|8hcXap^X|L&sf<Upjp)^u(Azl^W0W}8R_
ztK~vAOk~d2|EG$TW@@Q|nn{MnBuPViPGlN?cvA|ymP7bL)b0Qnic`=Z1{m9Fj6H7>
z@9l{+@D*|<M?A3QtsND%8}f>*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)MbwvX8eMzZBPd<saB@o01X31lSG>EI
zB7A_1cLIVSd~q<+qKg?=$n~TM$0CUY=Wu@%__2`MHUheP^T&@+1aX#(HH3#A3Q<mL
z`VQ2Erzg{sG!jN2r!&}3^6=y$uYUFDexi2A813wV=NXa>z~h+MaD^w4>Pnawq3)a+
z(MdnlnEFe|xjDrLlgl1!>`py@f!M&o4UOH4YV4k&06==G$ZD?kb5MR**j8Ou0FGxN
zIN{p`_!?mNl?mI-E*@S*<u9KzJ-XS%c57e&WB6&Cv}ek&1ezzRU9!B?Q=gYlw4o7X
zRo44qbH1|hF0IW~Xwk7&+khHwCT7haxo@B-^0e7AS0)8sJy9PPhu8tG*E+p$+7mB}
zEOTsl^S%P>FUjG)<XnrKjv_62aSP4jGRh^9$_e+pb8L-dmn$Kd$+^-v@91?z5t_I6
zU!wWFM$kE=!>r|?P{)mI4Wta~U;z5uI>4>a<da8RR&R=4Zld@VbS(g^25(t=XID5w
z6fxUa3#Z8$s*Pc0dDUv_i`t%5Q`l=mVg1&n;C3kb3sPbrpN$CMFVzjKTZh{ByiC;*
z<7SOQc!=}o9c*O6&Bz{sr3H+y*ghSykMO6~Hry$&*44#ve(H>q>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<pf#(6~5MwB6@(fR}~NE1w)&vfzyBmtZ3q
zjpAo6i9-ZejQwoF*M{9G)zH!MvT=2dVrhd^j#MG#Uq^kbh=FRiX+4SpsV;~Lby$f8
zOPU1oqB6@yZ1N0E4pMjks{tM8^A*-J<P8tI1STq*PC)y4sT7ZbVbSbhn8~^{Hep~7
z|23uHEJp7LC14;0n_Z>_I2pO&d2_AwYd|#J=cEs?Zyy5l5`dm)CJZEQG1Pb%Z>||+
z-&=ZQ_l|KikJ1Z<FSHvE;%e+;w3%#45r};N)w_)Oa`R(DEQ_h}7V<oBsf_p=g&Hz@
zv<z)BA7F{qijlsfXlUjzgn%6P2U?M_H8cdSTRL4>EOc0N(4wrFQv(=74+WzSc|tjg
z7oZo<UZ^_halTI4i;Mf2*Wg{kHKf-N>`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`KDNtdi<N-Qw!7B?w3XuZTs-!e4Omfby
z7#s?PZWZ58FGxA$yIJw@fFqS2%`i#P*pt69pze?tlT#~zwyc^Pu(*;)xvLHgZF93a
zCNST#SNja8bunebyu>7yPnzh+<3tN_spmOAF%48V?cI92rRfigXC(yObs{NFUNI+5
zo$vt>AIq5^KxPb?dF#D}c7}AZqhz7HXRhGu5o5L}(qhQDj}J_<D98MLmzPxYCGBci
zRTu~@(-jvtj1GlqZykf#f%DOeSwz(T^P4Jj>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$D<VL!91uT|Bl5jn;Y8U__$`7*hm63z=T(`_yB%?C-G^
z+(JIOf>sOfF#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<M7JAdMjaQp*^-ZB>
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-><M1t4#+1kTFV_JNsyb)gxeC1Qv}Mo~7#5ukfoNV@{7FIQLG6
z#`g4{`0x^w#~zJJ9t@PE>PsegYsx{|t6yk#vZaLI50LGRgULt<34ott#BsA;@nTqO
zBX07egd;6Vd4!aRlO8A)9q7c+2lI1C-<gt+70#FqKad8#nr-h%g5`nN{4MKv3@9Dx
zj3hO$2-EVtS-6*<9*NwU#AXPm&2>#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_?AD8W8<Ayog2Zv7
zo$}qvv$MmSwJ^DWglCwMxllWKGMVD8n9NzmnB}3)VEc8GBg_-@RRo-o@njSJ{~62y
zA29ASDt!@usY@`(lOjrUKW$ShERTd52I-MYSckG|qY$-3>9Ooq@dG-yw-@Fpxt|%o
zG_PYaNn+L|2h)5n<0*vSzBSq}-J1jMRS8OmK-tj&1(e?_S!Ax;_5TEri<K;D@~GV#
z%RheoPxmbPyd`KS0JUh63PLp6e|eIC-^b5a%3gDdcWS&Fd;+nmtn;AUbs^~0pADO|
zFcWdqfCMef0wE`w{GoZ|D_iLv;pnxIH$+i0V4dwdo5bavrB6QU2CjR9#a*TzAKR+Z
z;sx?ArbjF7!wJQ0U4fTo9@Pbi);by;Oy#M0)4e+TY3r_zZ27}Gu514E*j`qlwuWdE
z#NpJQ{hwa}DaS;xP)Ej3{}&fT&cKx&&4jn~s!{QX$2APiAQ+5o=LCv@6Lq#J$xmH3
zH})1SvQX^mp7PgJ<E}G?KQ2Pf95X9a7(_HEBsSORzmNE1=c2l$4hClmM;O+x)2Of-
zXfg2tEG8%0AgVriUf*`(`Lfd(O2rg)`p)++$Z#GIbfD(A9)0NfPwffV1h93<&}h$n
z^Dj_;JSYbYy=Yrf@12X2P4B!T<Kep-9^=M78>2N|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<Xk^()Ypo|fobd45p$pB|geq9s0P4`4Ai=zVKu
zB(szvo3XFZ-O9k3BRYeaBp?-(7H;4BCcZ#Cg#mkIfC+C*bKdSNK#M(5|MX3d&>@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<gWO=VPX
zZv#tMW>^(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?96g<j6{BgCpqYu!w}#ZwUTIcu*DV#L>y&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`vUs<YY{
z3ApNfpZ-W2mU+-_HY53FQ9jbsWl>P<Yt|LxZ!8UmH>iU}&KqdH7i?d+%!8`D`f0z3
zGeSz-ZPWx=-XZQiL9^V1J)mWZ-EPjfbnlsXYvi%fmYnIKHf7viY}!(zRd#PJNHc<D
z=qlq4Dq;p_8s(yGN{fd8qv};5B1S_|G+ouOf4wH4DJ+W@M1+tPwX3M9g7JoDVoew^
zt(-))W8N@lh}66jss0i)8X_4^p)3nB@Y)`!R3Aqm5`;ChoC*#=XKiL+Q6&C9fn^Hp
z<M?ZxS_hZHC+q@!_BtUsk9?&DBg%t>`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<W2!c&K%z3
z0@)H1)5qB(pr$u%#@K!(M62ydcD-^w!&qONy$o3c#tj4D%jBgw=P)4)YzGxrzdH^v
zn0#R(Rx+AlAwU2BSchJ6{+|&sj^<A*1xkMumMO=))RB1SwYN*>?<wzxTRh-(;?39C
zSVP5P7O-66L&hC<$SDGVI|*j7l4K|k8D2s=a=xu{i51_xMTG%}3_hwiktve4yNpXg
z=tJ3iAo4f-t1bb5HC3<U1`JGkwdOYvD0k?SA6u-snDp9WS}OgN2qid_cS&;CNv6m`
zZ*H=~KIX7f*`>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_lurZC6nGYiPE<Ut{wULZ3XkGuTmhew;%kVCw_y^L%mVOSYZP11KfT3A~<Z}
zSVnTO?nl2l&B-~p$%Iq);?+2g#1dB|k!Az3j;&lu60~WSo#nK=3Pt}yTORwZ2<|^Z
zE83vgbsd~P93kY}vCSZx6KB(cIUGWTI3-Bf0-|ngw(3!8cA~*A_V3hdT016*krWYd
z<%w!Nk0*4b!&%6ya5j!vBWh627*nv6<9g^ryKlfzA~O+t6^bJd8tL#OLIGlt_*@^D
zj5hF`agM8q&PnmN%SkN7r325TXwR?sfd}mcR+XI8eor=ul*gsOK<=A-&rn*$6TH&^
znJ>6+PtpUL=Gc6a?_xzjYM>x?3Ig7GR~4xO)o6>J{33;64+6@(vLzq|lf5M@<X)o&
zD!1dX<8p7MT^}ex6c>m`#q9o@Y?Q1{={=u}jRh_an@LoRFnYi3gNU&@{m~P5mVTgI
z6UUR&c%1Hg4y5FN<Cd?RE^TNN$J7r&8)k|vBJqQ4yaKDwQLss7AX|FETWO5#Ffom-
zD0KlwiM$#ly>(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^aq<DOaGZA|oI
z1*BF$$0nhAKg1(f$w9KmkvOhB*-MU?grXUIjftsSd@>9*zcz=(-YmgKHQ2y9KowMr
z2@4jD1d)b&3d84DW?t@El=LA9rY6DLklwTmX0~OKfI`PBu0ERw$M}h8sajoBdirN9
znypUp9(tnL7h66}6pDC!;iV&1P6Hgs5Sp<l%#P)LHLtiRaGPCZu~uW#;Num`M>GG2
z^|gOHkwRmi2hA6U-4i!5c*hYCcgt2e+sukAj-y#Y!HQHOzL;+uTudNu1a5K=vibjI
zMZr}9(_L<QrA%)w)T0rofaD*9%rkfKwF#;lI^b-m4&{aO{~OQqmp>;)O*0QL%!M9P
z!E?I^Sv=}#DlIvbZ`07?c-j(iO7?pj1Ix^!&tGrc=Uz5_VRO+>riL~!DW?se8E;>J
zvmYcOSBpix_FoRl{<UdEyi!npW3k<G#zPlxM97dGtLSdxDO6of8^iUsD?uc-((A8`
z1fh+PXVZ41Nat}U&LPelK14v3t!)e{3QwQC<V}paMui5RchR<H5j1Y<C=ZCHI`f@r
zj-uW@sex}aV0<=dT>mvUFs_G}?rp*fCZkB{E(Gh2l7x%0hE)vcf6RYPVhgZ`hRUkX
zIt|BC04iI~fXrDDA%_ie)XLPow|I6Bq_-uWSBoD!{)f<W9lFwuLFm5!nYY<A<@pP5
z|AJj9C1_j;UUPZ_o!Fj54qwZA-Sn?r|8DNXYw}Hd{6XcA+Cf?oy?mKUD6Gk}V+-Po
zT`v^OR2BPFT89P1qKgH99{gkpc~IG8=3aZIN@znB-`4N>DqsmkP;GLfgp!v1A$WZ8
zBvMHK1TxBY_1}m)BAM_Z^!y*j`t`<hb45Tm<TfLh=c|lug5zymN0{7x8Jx)DZ}#$E
zB^Lj$9an~Yvnb~SUr1_e#Oi_2zHqC`$8W=A*~rjE3g(a}VMN-KouAYIGN6CXg6;1R
zi}p81-EmdKu1*L#$dWRxn|%8*mygL>D_gW{1!fIYuTs?Ck(MtkH6j~<sI)%P!kCKW
zzw_2^X2uSv3>nx@IaKydHUp(f=}=0Z<!@Rr-@(1Il}o|jZtsGpb<n{NbfdoA2LHry
z0~tA9luntkcLQghhe}koiv?k;jymygDBIX|#=UC_miG%}Q#*Kn9Kh#(RQQkNTpnB&
zXwH6&XpWCy99JI*W5xAl^x98WlC>0nQZ1W9P0+LCFm{jBr@FvgH0~&HWFJtHMhvuq
za(RK2Cd<OPL>)+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
zlMF<DD<5u}vdWYQ+y~Gnm=CC<aisv;)S9*YunrPj)v3h&43>mIgt>Us?)QT>2w(=o
z<YEr@jEJ2SSJ%9O{KQ<AJ2MlOMW@0-SS{`rYo^Dr2Jn>XC=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<Qt0S9<f
z_pH@PJV;-l%4NA3nuDQa^pk(qw!yfpI-U9{6Bn2OLr`JUO}@>)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%jNHV<s3soe(~;v^T<>d|Pksokz+U#F
zQX9-)cVz*=j`EEmC8#3feEqra3ZL8)2tz&qS%_EUQ3oAULpU|f+wa<zj=ruZ`~(!Q
zzR~mQ_}qp^`YysDadcZ2ymhcBtDfBg!f2^y&MMx6Z-50{!v@~?g;kz?HQv&y(m!nK
zDCjqvo0#Mm8nFhL>eb|gn{2y8_APv}bd2wPy{Mgj8iI0=AT(<Hfq9JJkihjzWJ6>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$<vKStvlaxt5jl}M4ohP&UycaSi#=__z<Kq8r<7$TindkD
ztI&&<NR&e>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*<eB
zTx>`3s<e^x+mkWYj5IL9Jg7Tx?j56u`w5V~F;bgG@7$!@H-koqMpsaR&=vo=e)DlK
zSVx4D)>ZVs04Lcd9&zr5LaxbA!}}PI4!xXcWXLe`A#k;2^g6k<se8yFD3spd!HfRq
zG;d2(T!c`^2;B8(X7|;5J_8l2%vK%ib$vj6+S`a%0a<LQ7M#7q<WoPOj<uwA(>+VO
z=loMeCIRo}o@YqXN6%<r#wTCkY~Qq~`EuM$J$Z(VlS@DGhvYKj`V^zO<IP|<?9?)K
zdypYu$ZaGpF-A;_0Q1n5zMeEoBTx?O74PU}76*sz7B0Zm5hysHDw75ORZLm#c>^y^
z_!gl2wCKfbjjy|+<8r)-k`zVw(eKe^Xl0oXXCqgO1X<v8IFljRjDfz61JwXzI#C=A
zBx7}koQt9z5F&fEGXl^b#n+%g6!wAL{Valyn_~Ya`dB?c_v%n--zx}d?ocEF@rL~^
z21VDJyk0xGhZG?Dgwj)(+`PDUI?+->6Q;LbjPPcGz0>~}H6Qv<WPisRdVpK<P@Exx
z*k$DV8A}qP;dD=uXL5D0q`L#G*Mk3n3zC?M9jgi7nvtxI#^GZx<>Y{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{<rYqMA+Ko^wHUf4r!QWvRMGT4d5*cS1SY#94pYIg>ymNLz85We|1S>$dW$
zdq4#wzgrrN8+`|MU!zt&nN)c34(-b+x9EL9(6uK!DNeQif<i^OaFfzNly7HF-<?3@
zf_}S%B<6q}IaQ~g{r15G#t{PUcWH$eM?6|$TcXFro~`yYQmX1@6)~2Cas_x=eIVX6
zVDe^HT6Z1;s)<#1gGr}nYDAYfZ0~JU!7o)`=$b{$yaFlFFOCxSHF0<FP61*K+rR&j
z*(*_52QXJgE#S7cJ62qu#0xYvpQVG$j3s5Kd{I5nd7l|n-)eTjpu~boufOTLqu2Yg
zpY)a|lEJ}`-MG9<H~f#WRt8-fb~$(tQeh?VnW*q<2w_g++nMogaOSc3ZmQ55s;l;N
z2?rBHq%sNXZ~iAko@g%G64tB4Q}XQpheU=%)dRIOp)H6eIFdH%gR7@gexz=+mBlh|
zFI9m)=*e2Q_g$8ILT)1Y&j&FA0dc{+z;xrHbnScE!>NQFk(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<PZqT0|RMNscB
z*IWKx0<Y<{bvLp8Ix@rxYM9VX{KFXrRaxAx!)i;1l<&Qp9odM`0)=v^OEmm!+)Kfk
zprAhKajUb%tr^Hy_A^-R%pjmqK0r$kN=3w3rh)vE*_C$|3g<Sqe1}@=hrs49Bg6S@
z+g@sE=bl{S@M$ulZaS&isa}TNVO6A$Iu9{ubwt)uXjlH+3XdeH0yMpErA?dt>(=#M
zN59auPAi&bQd@{fam!e4tu9}yvvYpO7j4e$Bg5@v_E#${&+E1te09IK0%Cg67<ry+
z=rQbdG4;Ny*K4yFu-C)_6kgdomddAD$FpEbB|2{QYV#OfVQ%cy)tVa6_@f6)#UdRL
z3wJoE;RR(v*d7dHWFt4C9SkSy`B6e;x30b?5ttGE>t&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|Lb79NTLNN33QtROMGQ<kcBF
z%?ub~sOigKdW870_o>r9KZ7N|MsP`cx(oGHBoutS5b4oLHK-|peB{D7TrP0`YXWlr
zU8pxY<X7MKB<ACNBO8^<oh&@{7Wf7y4Xz8FO$tvENwf7q;SVx29c+M|8DZmYV{`T4
zNoxX#ttp?LFm~YshUrInpOaL?0)0R=rAL?&A{R5hM$Z20yjziwp$%sY>7s1YuE*f=
z5VHv%d`qA4AUi8NG_u4%bu?P#$+bak56&Oc!^gH+eskImLAK^GnbQAkWzU&O#A9eb
zc%6nN>ipaRG3f8r^H>?lf|(OCacT0EgIamhTb)gcP3RR;N<wp2X&X%PmU>Vc(HL$X
z2}aK17jeB<yzPmVu{_u*ts_si3s-6XA_;+D5Wz0_%0vy<_xU)#w11iK0fCLPcYZ<^
zZ%rZ@e|Ob@&8zKlfcaY!k;(8Fk3EI0x}AqE4gH;C03HdX&M0%V=+KRrAxQ=eOslZ=
zxVbxZ0r%vRF!Yz>dxw^#hYlMPa_sRmb<^Os&#a!h1VG~<8>+7?%$|}XlXwM&qr%0h
zMSM<Sd;DC3e!N|DZ+<f{w6SP4u;jO}JJ`jG|49;#vL2;26Y}s3?@JS<$d7>;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@<aZWo~Zvdv+bK{&3<NA8zn8?)f97**6sx|MW(T0
z*r1zOOcRTr6!z4pMj!yIcaDe3Q!(w-A}s=7TmpIRtTxWunG=?X(9diw^?N;nLR|`!
za_&@;wStwSb;)2rpqjTryX^o|K&-z5*i~}t+eo9UsjgGOV6Pjis*97s1Xw4|9cX3;
z>mmcWHjfyj7p=|{2h)F?8d0~hm#0O&xO6ePTh;=0-KA5#b+3P!-gYOY;gSJWOdH$y
z#FKBNK-bZ;J&YiFh<ptmoh)WM3m&R!y&biFkE*40PUbYs5YB6Z$Z$yGv_UM?OQKur
zR^7!P!Y8k#t=%>_j#4?Nd_<V&9qkU$y8=4T`UhEKY93f`e!c*i`-8w|b~#4si8w$;
znui%Wp!*3jUG;{JALSJxX)LH!dIcK~d!4E5M$xF~xWLO21Q2&I?nix0$4&sLdMl3B
z*mxb<kVMIK)<F|EGS<er14$(N?o~QT$*T8YN?Uk#Ubvf4=h^Yuhy62NfPr<C6r)kw
z@M$RH#fS?jT;7YxH`Nsk;MWHvIIR|ps52vWx)lPK?VnNPFN0UMEieuY@@&Co@F7mm
z1Zb<Yr)y~`S<%*e^ry0K<3zz2stFIFcsc``GaRuJoyyV!P<v?`D|M}c*%j&mE^2}O
zryp2_!;<(2m%4`s23-CN(8PU(xZg(0ZTu(+><f6GDof|AT?XUNnTOQW*6rGKM?vmD
zyj<x7j8p?KCFO*}Sk?mc6`C2uhb$?D$pFhN4-9+q@V(Yt9_ne+=(W)<=11PVM_?uN
zcLubg&4_d<3PDot9`M>@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*?#<xj@-+thv@Ne0|<&rH{RWt`roAOSKC-OmT{g?kKP
z62%g`-r?@6IfRzq49CS@4ZYSo_8MxXz>;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;%<S{C&kt$4AT2Ab
z11TZ6r|<Ko8(dN_b(LC^1v@%gd&M&7^ABSZ3=y-QVq;S{?^2UtufXeWej7q265lUz
zi9j!enxYihg}AqexebM|XKd{JM*)P;y9&A3Qq#=Qp17-jH`BHC>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&HdQWa2<J1r-R;i@s<6v);`#LW_bMX5&kD8(vh(J(pt}mLQ|cOq{84N~?~^NhBtV
zP3AJLOC_i2nu?m%x}wt#Nq`Y+H`8Vq&gcXRI==ERx7uT*w4pnUV59?%-pK`5omd)%
zjqXD5uh0cuV*;W@dZ9+e8X>pSl?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?<JRFGBSFiG&npK^&@!bGK`p#JBS
z0VZ;*-}yM16Y<XF&w0g|MG;*wQ!DCB4R_Fq@YzIzu#LthQ5QKjTTBV<4wUdd=RHg!
zGoB#1K==;W7k1iTqi<P?^LC7W_sh(w3s6Y}O9i>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
zENn<GMeQYaXSTP*l<{q7<xhyX<E%ABTd+D{Vgm(VqsnK5$j~vR&nZmr+B|N{`{7O|
z>fFn!O1J(tsby$o@f}^S<c`Mmsy!D9+>0`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>zW3CaA<GLFNBQ&p&yX~X-r+7C^?j&}=tUN~%O`d0@v0WQxs?T38y>xrv
zmD1<KXQ8%qE~+^k0uou$X78|i1o8y5zYLv}s}cQP2-$?oH$L<u+E%&NE1pgtb-P-9
zg!pF9;p-j%mlt9~p!C$Nk#g=yP{-^60vd9Uf_k0SKLVr>4^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(_<vmb!*-00e3?yW-;YPc)?VZYjX{BMFsPT5kNOe?Dfx~`$
zDtEd53==?Q(Aj`qV4aAc1LLk}suuMGKgT(IM22bkv~D;&jYuQ)S5FEzMV8m|$cZ?a
z5YPa2;Gf+B$X%0+F46~D=~R-jSM7|i-DBN>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_<Fn}5omB8|0E`l*qB^8F1dj-VqWF`UgBKF%aGg>(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<Dk?8
z5+m;5BwtY{4XTsz!Rgn(o9%%FfO+Lx%OSEoHpP7Li#*WqCD!XkWI|+AZ@6gwxx@^!
z;&EQr0^L40-hL#(M6I|P<r};sq(ifscT;^HoS!(}As`-UakC96`P`7z_A!e9-uE3s
z&EIvNy{1$-<1Vg9RFo51H#JV`jRkaC5L<StpOmTaKg5xb&NI?`cga(!4iSscKe}F~
zb8kOa#%kJ~emm?e@uontrbRm$+Ij!rwp=PhwgImb$j`v-3y<0e1N<18qgK-jPepT9
zHxqZ`U}K?82-_lHPWpP5xtuuj;`h<uRdvn1%Ya6!6+r)%3&S6&4c=EiFL6of30LKV
z8#z=rr|W}SP;wcJ;xXcfuM@4BXpaJv55wMA9LZHl)sKcn&h?X^R{AO)SK*~`G)G+X
z{$k-bI69e6gvpiX#aiu+*cxXKS+YLO<e<fv`c5SvZSgCl%`?Px%WetKD{Mx_{}{f0
zo>(M#PJ&sZwAp^uT6{QApeFjOwD5B`UpgsTeez&t<FkBwv(Bi`(rRMPe{R759>;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<LAka3QJ=S*Vb&r;uyLp|We=Gi`YufpeXwv`!3PJ$W;?$Q
zrc&Mv`=}W*EfH{3`Kf$ADXv&8pAW!u1`O@a!O6w}Y6Ey&DwR5dZ=JmOw5gILyfBIp
zI!T)KCS|_m%T;-I@Jw-3t0-Tv-7b3B^5Wp&(@IPCy=Z^0>;``K|4P11)u3JjXljEf
z@@jexuHC+EWoma6M-#)Tcp9k>)dwZ^2`9zBIk2!Gl+f*1mFsi4bJ|37nzp&J$R`X!
zoQ878dVxOOYhP^&r4$qSr=;fXvf<S<9u`#>`!5WhO{RpiwD=QvtqrFIyjXYhL4`Rk
z++kIloYTpP$hl%jUUO9@kL(ca+V@Zm-e*ev_M2=MpdX_zB4P%o7vsN{Q#$sP8|9LX
zMZ<%zr<wXtVfvj_O$?t36O;|;4L%9?nF6{Su$x{|s&X;^&!Jl01wzL|E@3ECd|3!y
z*sv!=04v&iy>j%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
z8v2wR<Lg8Xb~j9you?S>odyF)!;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<zfyZ)QYDSaQ?=@yT|L0%iEG_WV%+nfWj9+3L7*pMlABPo;$Q*#b7U<jm(#0J
zB|C0BU{^knx4HJ><(HVXGjbmPKZjTV^tzN~8{V4*xD3aMtw+jiSJ~<Ud5we77%XK=
z^~cN$U8YTkkK>A@ZdY5V|9iOr-%azY2k&aDT76XoKvaUSPOJu#K2eOHb3EEO<Ol1h
zkZ<#Ilsq{9HP?hLIqUln*LiG|&P${nkbpT0a076s?-50lCYl+qt|wx)X_S&4I{T<M
z%BwE~Utt|HCMEvoQWZ7(DPRw3sDh-=DV8|pR4Kax9#NR}^B+OD>M&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_b29<L1<<$~4~Ou=H<p;D
zS+>FvX(A+;h)=9|E27Xwxj$d};)H#%4~##;L3c?<q`S>$Iv@|&IDJ1ivcI`W<}Qa?
zeeaE@Z-#Q*W?OiSkm7s*SyM@d*4fgl?99n+8jLcnsw<=qu6{Hh<~#zDhJEsum_-8D
z)HC44r~3R8%9RUYBzY)7@=f<V4x4m{F{cuiVKF$AWei;<?77M&Jd#LH>XMEe7Bs&y
z+*hDOa^q)kBIuKN8Q`0l<6X6aYo=>rmpY1W+qfA86W5NdkS`Enc8atp0IrxOBvp-z
z6rSOrxMZA~fZDDbdGUk;bUwVb?@J`rQMpW@GAcFkEtTIYK|NZV!d<nrkcE|jGf%v?
zrD?Yx2Byd3HcMl|LOUwNQg-Rb62-W#{x_5db^|3$ugEX3GScWD^9(&JVWhto+VXsn
zlqNbhnr)Gf)-K^}Ou{mH1*t4)4Vw&3w?%05o8R!SbEV_hn-G2)dHnztNfZ1Xd9g^y
zBp5nxbg{YZ1U{oToVry7-5+cX`m2)22Nyz?xxfGb{{8L9fk7K@)p<OHF?Yu?izC7<
z7d)*P@w)4?@OD&%qxtDrG3<Yc%Uhk>c6zMoW*$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~<wxW}{%bMfCKk_PUqp&I*=6~rvrh@wEq*?c
z$(s0qkWG9Af_F@=!-}4OhKI2bTe7-;Cns%*ASQeoE8I&=QKs_z2Sd|&o$<Zxm?gvT
zz$G}4T7S4296R^J$M%+ZYLup%Za?8$0s9S>95(m5-j?++o3D9YiOA%D;RhgAR!2^Y
zEn`f%s5k%YQ8SFLI>Aw9#}@drOFjue<3G+?H#6<!^<uzj>G=)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}J8R<I+F{5H@lX67&-{g>e7!8Es761Se|^G2|-L3;<bco)_isUE8OMtI8CbUYu*H
z8#z?lsU?R08jD5}q9l6Aj)&rg7|8{lZRc`nYjb%e9{4xWCi|u~J8ApcF)fMw;{P`#
zLvD&!Ua-q-p*Ii4*)|vPGp<)PRx+B7IH%?=;1~K?l>Y<P-AST9co~~Nw1mhpz>?ZX
zWf0|S8>!c=I$k0_bp9tk88sHkzKTRj>}1d~mYI{JGMn?Pm>y|9?7GhEBm`jb%g8SL
zjbp!x77pwuD4Q1*3?M!#M_-s%OGVA3Bi>W<iX?oe{3(!F&Q1&P#WFk7k&Z_a^22j`
zL3+Q&XL*OHVrbf5?gb6Tbm@k3WEac9lcb4jXfZ+P&P!)-P(RvuvApFR8OTTP#GkL7
zi0_iGeeiMLJ0et+1%P6XbdUwOP<`{@x=MEfpKbC}d+WAOxnZ1$j3fs89RPRoJ_M@C
zTv=7C{()+Ap&|D$q_Oi)FTbk4+{O>+SAf5X;fx$SQQBPu<N0#M(>NP;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<v(i3z1UsEmJ9kuwGwQX
zt8CqazIwppWT^066x{==Nr`xTb53>^Nq}lVgjLe!N4<~HDcZR2@ZN1$l0ABB9?SM^
ztIu+HJXw<+sFDbkaAsaMN*&S?3)%2?BUm%@R<AESV=-4~wVw3p>N-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~<mk=r!Ju1~8=UW11x)}RqP&l8bVhFA4rHNW
ziKy0cqXp}d&Jv-J^i&nWqnSZHR3<l)>+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<0zB<dNthj@1db
zKGYhg({}Dr?(Hx>X%N8-Ir%8Xl&PGTDqgUoZUl$YnPoy63^QaaSfMU)4D3`1FsqGU
zbe;*98aiKJNS%fn0>NL;<A;U;+^{Vr;Zoc4Lx>;n!ayGV+C7p43}|yr!uA<egiC&v
z4fo&Dr@Y@W@t>#rApfiXa#%wuRk4L=HkpHIr&Pk(Oru5OCw3Si2*Ce%&~V>Q)3>WQ
z!6X8w-2wy3K1)@mp6B3DrHc1+K0IZ!$`|O4wk$Z-rgS6I`n;89@mY&5{MH>P`;(<V
zp~X}q6Sxy}{p&PJjD(gDL4yBs)`#+f!Mv19AqvX2%Y?1)-NQw}T=td66JuB=@|QV+
z1+}>MjN3naD4^K_lBfIsO9$M;9d*7L&`3wnsD*M@#@>@^7CnxHcL@2)$qdY|!=`Zf
zJ{P<uBNO)dZ?HV*T@9b76YTNAmkSUoiOkBh0oo17sExACJ}@u%jtCX)vL7*A_r#Di
zrZBw`t)Vph#G8@ww00lgIaUB7>g(87WZ1^0bN~=R+?P7$E(8H<$cmAA^U{i&OHPmc
zz{drx(p9m5qE@FLp#-s2HT2*+;e7g2Qag<c7C;qWnC3(#)A+zrmxx>JF9W>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#<<gQ82j(T9(H`<<6c9dYxI3^0ULD|1n
zgf27&1Xd1tjbLJq>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&<v^!9VK36|P?eIf^XFkZM4$@(3c74zKRVi0+~KawZ#VZ*xv&bX43
zgf8YTv0jyYj}^2ks_iX3KyULo2x|{2fp@#EV?p5S)ZhibNowCyu_?@NRh|A7gzk@a
zP=E%=wlucdviJS|32*$JXKPKE*oF=`7y6|hM#YAx^E1J&!bf^VWXei>*sKumU}1a5
zRl07O>ddh_(vF#?STNlEM>FjsP11R8kT*QXA9g6q*<aPZft|I^a?cjK4{wiE*{Nr3
zB4+a9RLLwrpx0+Vm!@*?JARZcTImUjoQ=E)&Gwt7KbRcysCRV*6A7taNl28YSfpwz
z40$yLENa^8l;|yrWp9cqG-Fpt>j%HkX=z7b@PR3uMlDY#0OD0?sx_6m%)9<LyQE~>
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>><r!HB&YNyESJq*$FjSr>C2A>CN!Uv&`pV;qp6^IJipC)
z8;1|#AJ5RoN*Ch+NCNwmBnnfd@YJHSx;7g6?9@syATupIxzS?SjqG&j<r|k&5yTfT
z<@&zmHLrmRkxz+ZFybRRQj<$Y%&7SE()TAq6kO4Es<1D^-iHDlvL!2bs)>YT_QkE=
zH(_x@IL*FfJS)I`ZZR1Swku%@hMu+G1^<yp2w%hFI=N3OV+q3c#rd;aYZJyXh<FhE
z#Q?ocg;X@zLv&!dYsp7X`&K)CfAN%7UJj_0@dC*&_sG#)4Zy@{N$7!xIjj|bHXFJ2
zm_p1CD2yS<i^8-31RVs6j57wdA}9@5xy^CSu?6c^WSt$!$=GZe+;Q{)kx`?VM)121
zik)4K-zWS;QzR$!)!p+j7TZz)=WOd!2iRe$f|2uzZwjpFkH+qd2|~$$5gW|a;N=<w
zo+~Y-?5b`gtC|0>H?{p1>RlShr;z2X8xgl<Xje8fJ$w2Vrl(OnB=<?2)J_wOi`eO!
z?W+1aH{^2(_pW?Ig`(0m0`#`X{kSjx<cu4@{@rhYd`V~O{;QsSArZ`F+01e;Y{0<V
zD9hUyTD7ixFQkz%z^EUQnBNo2bF@O~lFZ3|9>B#ij>%!;gO2W4uz$dl%!duJ6jd-)
z?QOrUW9#6;vdTcK_6tXADhe$)EFs4QB<Cw~>q^2~jj0<1CNn`;?HE(Zd+2<AwJ5bQ
zGo}-f(Gi>RvZ@0aT+v<8KPimIjAsM?_d0<5V1@9gR_D0*HXG+V6uN|qsXiw2{UEP!
zmbOIlcl8KC9c}=}0x<w%G4@`|Ic6nrf`MwacN2{n2SMl}Z(rxR-hQtN48cu}tnvsR
zkS2{Tcmdr}RTEEUFP2Oy^m~z0hQweduZMrC$T!F1k)7*aZMI&FDL1V9nw1!^t48vn
zvh-Fd>DnSqc5B9rLrR31)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_Znncdm<Rxw_Mzz
zCNeD+EpEl9DYWk)5YFw#9`Zz1Z4A{8!xA3I?KBTkB_|@`lU?$gpbhyEzK^N!2{Jb+
zfYS+hFaF})mF@a8R}%}CAkGS5El?U*PkRkQ!?mfLOH7j4IUp%7b4Fm%i^@EUHhz)#
zG!N!K%)ww1EUOj=JS?*e^)0?V-^*8~T7(!5AkrmV`{3dIu>r-*Z1;n=8}*{=EK^P(
z))n~wp|UEl`aCRqi_~spB!to5`<Ct1WoblrqX~gRu~S8*A76w2lD$8VW{dzQ_FdHN
zAil1o9ih(@((!k5N#M7`G=qJmd9Vy1zZPvs;RzUm=uBL0#3?f~ZT$Jv5#p@vyz~u`
zReAD3Ceir2<X#eb<~qufL*;0<Yr-KG$zhRzmF-B!TfvU<`HHe`8-B!a7ITUyAL$Mx
zUiH4`o(e_0*5Bd@k{aECO!eN`)D9zvApPi{G~-0uF(xmtlDMDeqqJ$_tRD(yl^@BD
zW{_XeXLMBjx)`0s#XA6(XHwCpw#m*JRADqiOs&vCUL&VgdYeRr;UoMbGVh6!S1OMT
zEjW-;w9<w|=uXvx(`la%{GW;jpw+u{h8ig{&Lr%><GrU1`CCDq3?9k^sf|$>6$0Q&
zw_N}Sf_KWkS(a}ZyFOj>)8}2B3JsYGwMAJO6H9oU5vsUIcXeQ~1sk6S@KO5&WiqV)
z_y<x(K90GtsdH_T0(<RD33xKEfNKSh8<!wNx1+#9H&7Ew#z#V~CoNfhV~i7fAW;Wq
zx1-EqMlGjbqv?DsJc6UA7mOjPgrq5I_1suwZoJsGOSXQMdwwdJgLe-=ZODwJ4$+Al
zO1~(3tw)!j3%%X>ff&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+(+`*<URBCVn8pNUyfRKlZj5QzK{3j=f2_*$t2bwZyXJjT3
z82FbnNU|0nQ<|<Lhu_-Ua@q%-iTIqbu}_@Wh4H@sO##ARkZp9K!LNPTw&#-aUQ)L^
z^D0GesY!;6vw-%%#X7bK9Y+T1*2~|pqe6n)ML|!xf)G=z(rc^bW(R~SKib90?BOfx
zh^_gVz%-PV&uT(%KaA)40Vg-9)y=+XjDUdAL{2>!qM+KF6E|?6T%Ma-DDwovcrnU9
z!+B%>B}8!ubuygHg{T}>V~zGQr9)QoQ_O=3_Gt`dM&gXh+y<qaXH(ehu~ThVjcWRQ
zk=DdC2G9h#J41AlDq+&G<U_#bxtfEC_U~wtB$#rxIoILXoF(EY0K7!Da~bkOslF9}
z%9wM#?a)9<I4!SM7isv7QYu#{ECl(7yuTu|y9(w>8k)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>b<zaH#2{wOlHuT@UFcF?|;k#gn<V)VJ2@7?xTrLVI2XufZ
zwJU7YK*B#LZRWiV61+sv*A}!yXSGnGP#9JXXhH43O|)NYQ+R7m9=9PBpxS@lhu>hi
zQX%jG5P(v@X@+Nnrhj4DP^qFoj!%r}9?o62X_O3HMot7(C1`eVD$l&*uB|re+b~iF
z>T#QyFy`1k+J`+`mR<a&YZ`~A!{mYqVofd0{jFY)_Y|VR$NvHLjM}6<Ho(mthnycl
zY0h&C29Q2K!G?Q<<oi@1^`<m$;7L++s1t*3VwZo$p4q}Bx_MbAGTw<5UkynMS>Viv
z9Bj$Puw9yTO$2$dp~q4X2$ohk9wP7v7A#N9BHJm1bwY?2WzN3Ljv#8mkOP8bjFTV9
zic9X05*CAJrRzeN<???pJ&sBgYyQ22S{6}=0JtNB><e%p&{0wd{#1uNv!R(M;6Q?q
z3sNUFsO=9OUAaw{2IvS5mtdF$QDzN*#!^O&6gUN$Ui{C3(2~SD!jJj}#-xmc9}ne~
zIfEuytc0aaie+hDNrbK>8=#RK%tr}F>yzg`J$33=X{>Kib-^-mn!D03*4b~Ra=N4@
zUKyQ=!G&h<lp*q)J`TM+)s{BS0E7lWiupJT88DfDIl+mIeT{pdE5mZFzE#ASd*u<w
zoeS6ds)8xc!&#jOYy*;LiX-H;6WA0F<J$O7%z?wYAj#CS--)bj(j6d~ckoRQikW{J
z#g@$#X<{Ze(~4%_jCm!C@(x}s<CbO@Z3Nnm-;bv}MVFiVK_O)P*~AT9Sj<}-EB5+%
zu$XaPcmTs700KV6000000_wXP!LAx3zw4OAB<L`7%aOUibO%(4x}eN>!o2O;9W4qX
ztOojt#0HL!%zz*nb)t#7(3x$m<f!*T=#ZKM%`Tvvog#N&s43h1fqs|xIFsb0N&ppw
z>W~|6=f7EXyaw@^JQZk@P&PqGA27FV>s&})-=i;$Im|4_S`UN3MJ%GJFqFZ(rCYd9
zuM!#Z2D#{81*48e`_W%qLNQW<ClJTHI>Rn+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%P<i_Ni0AV
zm0{I!6E=F~Qpu3=DLslv+(x<m0-+YmuvqGEi~|6Mqxe2A$(6O-Gq<Xz$Y5cQnO1IH
z9t9FA!HQrlToj(HosABq|G$EqYyo<l-{Ya{r61Km(t<a%cE2yv%|z_zTAp<KZ*u+9
zk(A%~lMD^(FkIFJdxR(cyIpZa<S6^|cX_hwu<U-(bEc2cr!8zI>cOaYZ{b{Aw7~xG
zf3Lx*=o9~S9|>lh?NMw7i-*fL0J+U1y*X_3vW7Uu;Fjo=QK+h4PBX_w$aZEZn2eML
z^wwdp5a29@(L@*kxDNcP_Nn6L8=95<FGpL)E5h$WH>^v?l<MAmHn1ia;ZVUf^yVO}
zwf$95%I4Tgb}$vUK)Phz94M`ncn^>85){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
z<Y>p48L8)-8e+G{210k;gKwmzutmH}Z5jgZnd<v?rjEbvfys6&Dp&&UG(}t*46m1W
zN`6E9m<)^<XrqQC$FR{jk7tr0+U-!bjX3Fpb7solwp@`Na&?%FC5*<@3U*%1D@eYL
z-QSaMSt_=!`?|C&Fcu@Aaf1n{co%PomLnH*z`o27j&+s2##4iDtg&IB3}<GAy365`
z(|$jrYGi&?M{dQs4~#+7STnXjE@zRI*e_Xb0p1$d$XZHz+$8>b(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
zPSbRhp4ufme<N4=s6O6HTU}><OJ>3ykm^8~)@*D;nULEO6+%Q(BBS0R9yWY`7S<lo
zr?|E0kN;BCwk2xwZ0zFj!fJ9lpYx-+&h$4-S0+45`Zg3S^s%vc(LwGq1?N{e|J)wh
zNF{A#8fpHI6+y)phiqK{K{8Z-H3r6-E1v-`{(>YhlbiNT$_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)<Ms6N|CGJ2z_in)i(l%z!ENR-aozV!4ea34b8NrZ&gYT(Ade>HuEs8vL0`)`MQf
z($B6q-k2$&NDJK3*DxHU!hG*2joEjtdt(X<mp-8K8N4p^v4dWeDnJ0Dj#6Zi|MYJD
z#~r2(jfd?-!uqWK5mRvDVHWLJM4q;FCl_hCq+fixC=>kKsC4t4C{b#S-*=Vk+QP<X
zrU|b+Z(|0<MRObLcYe{aaPYm$qQ>{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?
zEm<D<Zx0l~^?884Gf1rK>zb(B=zlu~Gsn=&Moh7nKlzH7paqqSq|LusqiqWf>wKxO
zoCHh9WF=}tZe2FR!Lvm=EeV)H`QI0|1EvGq5a^4iY*$9RVE(V;y2WNSmf6-|e*S5n
z<qwmhJ=lASRWD5vsPQ~~Q>@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~_vEq<l3~A+M
zYPN8yj4=)>a*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^^j6fxsV<Af5r!fXH==WOVoH(dwk_*@Kzu&#6d}i!0l-6A(qDCz*Y>jE-8lgIr0(Q
z+Z1nHF#)omWI`ZSKJ;kv#IQuFuZ4h062lZF`Bt8g;_Sk>a=tgxGisP)5b@q1l$A3c
z68<#!<dmbzcyTgIe6U=2RVe)Y#BLY1@%ri4VhTxZUgqV(e<XX{$#=6`XfXGI#%aJ3
z(=GBqjkxJvM>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*?2wg<Uk
zUqkwEofCyW!)|u&0P_6+-C<O`kZtxFr3y-q(v&vsUrl1l?6S;S4a0}@<;!<Xn-!BF
zHMy5y&2B_1x?!I)b&5^>0KFHe9iwDce;S0>N+0x*m~7!0xd0;fOX#HhTxK6;gGw>w
zYe8ZHJ9(%vl>DPn_!V3%#7)~VBHepGGwyBm-d|1VqVfPecD_Xf1_TR$2kEozsRh^M
zHqZnf1rki_<V%|2x6ts}uZFIW9*j&Wu|G_lm^g%gsB)mHmh?v`0CrjH)$c_cxNmk?
zs1i-z21?%~HHe(?sqg4SAo0fqi0gexB24dN>5n;e+yW^I37H`Ih*iu7m3mPvGXVgo
zjLOc*EJb|O;q*-s<pJX~RvGS%MtN5*%m=SF#7D(zD9WUA%RERn=-pS$(<>f$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{;6V<P(~4
zLRJr-fh*ZSf!{uE2HS$oFCP2(6VbGae%osF6Kw$rQ-d#C#y{kV<_@x~$c!~<K438?
zkC7?{Er*}=+JGn84Z|qXXd<W(bITZrDw{>sHkZ-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=?ZG9F<MYjm4D1778Z6UB+SR(+PE
z&Hgxp8GC+R-=zg0=x4im5q3Ry4-NxnQs4dpAY2MB1@VV(-2ZP#zgc&|;z9XJlR^Pc
zqqJu&GXMYp003>t$*KTJ;uCYK6(raOADmzfyRK)<G;X-L8tJYA6CxHsz#+h}bZZEh
z4gvy^tIJ*~N*24(43~pQn`Xjv-(D=}!8t2eri95M;09U3wM{&VT$G!QKw!7`PQ~E)
zf}xY6A`O>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%nr<DQ{>5;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_3MLfGcL<PlqOV_uBnmk%v`~nLNkB}-hq_V!
zqZ9^4qyU^{)Mw0Z9PUy2$zJn?0)fTauXpwJ)E8)wzxWeq9B@6|tBd|Msnbxp3Bt#v
z9huvNo;5_3sV@pxiZ$6WR$X<nDZhz+p9mR1A1gU1qe&iiDapp^ZPxaK!c84FosoJL
zD}GY?!n!Hm>Kef_=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><qdC<9RD-&`Y#
z{x>+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|l<qhCidpZzddaA_OUV8B=fA&~UG|A_qo0|#g?$0U1XdgQT<5)#b%DRk~{(A{qa
zTE!D%-U<WU;4D-A+&_YPbBhPt8E&7o5d24x)1ME^a6mkbP~dt-PF`LnzK2=V>L4R)
zNG&+kSLy&$K&-#&WC<{JFqg@%`fHQI4e<R_BuWcMdpd6Saq|zqS;gcYC9WV+P=w7G
zE-axPd!ey06GiwWjO{>0XMC_w3_I06pd#LwNs`Dwcc|W`D<nk<m8CL74u@COg9*$8
zA@a0y!D6<ICUgx|5<bR(3sdlcfYBt%hfm82-A?PQ{5Rt%r`UvBQ0(^HX;~S$0!Mhg
z$4v%=999m_scJWjDFI4TeZuM9)NH!j^w>Ub(=V+(l-KoKmI#N;2>iU^U5O{<<1n;U
zGieG<L3ENdS%Dbnk@04=t+c*VL*^FU&eBm;h&$DEU>=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><EH*
z^&6~`4x9+lV{OD$EbKlOZv1TFEab9IKR^z2m$Bbo`V+^|o}Vm0L9rJJ^V@COwn{dw
zD);+VP8)Z=(ZP-d!kA}I3o*89g7y&*A<>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`<h6LzHQpT4Zk_k^#q8U51*0>{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?&&r<PE8s6~i0gy>j%`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@f2ZdkPnv<j@-OzL51Wu!*k1`g5{VyI|Sxr4D+r+xTkZz{}Q1Ikh
z@x~!my>YSnIiR~2I+&L2iGwQR!8E>J@0(g)(kCBiTAXCFM-#USqf$BcL;z)D-ru#i
z<XHdGnKHk6uta=lt>}ds!dZG|uy>^39;gYQDO^8h99uV14!~>;^YVoa<CmiIs_TPZ
z+>4L8qUkA>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&H4<kLjkC$OT5zDWXXGw|^3Te*UAsQR;11=GD$N&HU1s(~2W48h+
zdh&w`>ew8+(x+_-P*hw@@g0lZER(u2Hkwu3G~9tI#ae?n1cwte1GXcl=bI{XSqUhj
zPoXG=I25MK@TzN5B|@G%G|1Cu)cmwT17%=Wac|y>Un%^(mH<HrXN~Un=CnRICEZJz
z6ruUg_VFlnR!&0BQfx!aM--UrkA<k9zsxThzIBeG>6OZ>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#3xVvot<s2pBRuduyBtxO%M5b<p!{}YLe&J)IiQubizff$-`
zX2wEkFJ0W(ytRPB0F-|iCAH^ZhQdb9%dMI4K+q?Bt~skD>c=CEbk3uBI1<m?2Eu2h
z{`9u4K>Q6RpNNJ;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<EgQJG1|+PUapL}7LfGTR`DC8TpgiU}#?nq%m2=>>
zw4>op6VRUfhV3FGvcJ|j2v813#tRlkA5E>Vu)(uF0&3*;)-~kuVF%q4dvd*_0w|8Y
zU^gak0o4nR8UnWanr<z)&SwH>co<`kB>9VF!k9zgYsiUnlr|%jY@nQz7x&=hG*Ji}
zcxPl*VH>toR7hwT_XAz_8GVHd7R4j6LBbI_vd(=zaVAY1MRnykR+<3$8GSO<G$}mc
znrD_$aj<}UEJ<TXa~#pqMv^10fGX#{BX7Nxho}aJ5@xvuzz+&+0HTM_2Vr%fv@Zn6
zY)&002Cox9+c;e9qa=S7)+cWyS2NVweL}!EyW`|~JQ?xc>HP1NkBalF{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(2Q<H)%!ObP;bRRBMZ=
z(EBrF(oJ&ru?fyn$PdC)&I0Jy+XHqFd@~T)4M3UK3<dYw0Kh;xLlOW00Edx7dLCQ}
zGd?o9;&Wn(w%~3AUFKeCzjPoPgB1yPRm2}Zo|bVG5%g&ErOt{lyNG`SnSdZAMo*xP
z%VV!xt!(-e>iz`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!<na4uACV#73w4;@0D&8WIPQ0LuN<r#<lA|Ya
zjL!pj0RK10N(&^{rM3@@`G6UGH5_3jRE_z3I;!72KA#Itgu<mj0VmQufMc7yjFr=`
z6akIbFN0_XGr8^U_JGhM5rZH`bco=Ar|5_OXi{WX(OY$DwawERoE-dk_LBaS-o-w;
zcTYVLn|l44nX6t6FamsTQah$+k@<wy`E@4z3-=H<b<?2}LdrGShDe_CtZ&WndW28)
zY`Nv5gOihdfFU=S6G$a~DUUtiSl<p8db^WKh;|mpXyzC7j--8`<X@U2USB<FSbH35
zJODukEY%clV?clPVOz5?8On*@s0uQwpXfoA8D%h>?(@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-<KY$4^k2)c>CK>Uk=BWtFPL>k1DzpQD;XAue7I;WBlR56N|9P5
z*6KVY;RaAvyxWSeNA!55gk#bBKgBo{Ai%g4W$j$;p8JU-I+5c16tD3hZisc@<k_eF
z7KUn9heB$?Qv!{i(e|S>W=7V4!OU1<kdn71l+K;T__-=y-QvDxMqkGH@#Zel1UzM{
z^cUlt|Bie6%MC%Wc=q8Ae`R!RF53?-PMu)wXV=@Q)BdS(zc*`=rm?e-4)XK`&zVu-
zQRI+Q2?}DvV~Q>6BC%(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`<j1NJ7k@mKk
zD+b|UKppV&%fta4;<)qIsjBLpsT7up5}}s1qp}o5aD;}7Tb7erIx%N=Mb|bdoY<z>
z=-3)GUCR6qL-<p=%PmE;>>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~ie1RauF67WRc<H)N*C1@BvCKae-88{>b8)+NtsnMCF(
za|Bdze?qD)0dHwtnuh6%{9(yRsSLwi<bK_DfenbbE~9)S)d8ji;0w!5_eIG1j-+1v
z?Y=A(1`zW6M|Eg|t6{NiYhyyoU;sLV5o?a<HzfCRfb|;Oeq~5qF^o9ym5(Ya=&WEK
zc*j3NBLCIB0dKeL?;!#ZU%rTtaFNd1eHK*K0x5(afDx(wj1OI-rvw|Tv#<IYWBYln
zbm>=Tv98EG<jcL6PgtQ;hQDjD><uKRL0}3OF8Q1llGW?Xzy7Ue=aisAVa>2UEU2wN
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*B<LBUM5oGBK_7QJi!IXTY!P8X63J9y2-{6?^7reQ>4Js1G8
zaviXn)Mw@mJB=_09bs`l?DNJw>I;@SLvnEk675K*suCNmTahLD+3;?sC{B*`5~m<v
zT^qCrTJH^?XE9J-nPuK|{90cxd<$iXQ_Ny<iQ#C=mJB>LYx{F(3a(<-VId5vCGN<Y
z#yI-cz6iX-o3XGTrC?<vS{Vm*H5Qw(5p>RT@$3T{`W<J%KND`&G)hf~Qj_YVizyi%
z1qQhj4}JXaK@<w8u|mt{8{<F@s`s)m0*!YK79#=vjq+Y3^4fuz)-EeDlfi<kMJk$Q
zWc>((Zv3BC#S!CDC;Eb$W|0F%H;efGL7j!S@BAF*+!dM&=@c~{e&Wn`Vo{YkP?R&}
z-#`C#6c<Y97MUV_R1A)AvP4-vKXi%w{Qw28XtH0E|F|BMrsZ;eey6<IyufEfoXc-t
zlMEhlpRS~|bwfUtp=W5=W3?2010Hi}y4r;qZO+prl22^_`6tSF)dRrrRRd!urmO%a
zi9EeT@GQBikPUSzj#K3JWMP1kp&*$S4|UONF0$O$`e@K(r$uB_XM{tf=08fpT)3t+
z3~Gz=Q3m#J?=em4p12<5JUcep(Aj%WL#%I@ziL!=d_LV_JAM(n!~Gg=?O0)EBir&}
z^6rZK))#ay%kiD*L02FVlciXNxGZz_60FP{5_LRs`SPlbpSTK+Z|z6Bl_k^WfH63Q
zs{sTCoho)6t55-CDDac4&+9Y$GY^bBsrW^9?FTq51ELBb{d=Ss>1~M|%MV8-!q}6P
z?s#F?In_9{k$noy<t}f?C6BnB@K2D806g_nKFJLTtU~Wn6rLE73NXCd&f<ekb%05J
zcO_$2_Dp64AL(7L&=gx~kfb}{EqYqHsHq9n-v<w<;t-J)$7vQou121~>*}8yyU!e@
z^zT)jS>7Xn1m4nerJAu!%PanAr236l9A{twb8<nsE3-xuODS#yTr-=DX0BphoUcrY
z)QAdro}l4!R?^EGO`-A5K2Zy0+At0*0ZhkZIc6Hv_bUtX!7&?&^awc8Oqm<hu?A$L
ztiL7ziv+V|Ndp#lpvuE>b+0=rPDwA0+1SfE@0DqwEW{V|0@7p$Lw%d)K<HM^7AW3c
z3QlNUa{``X=2HT(ZJK{5WSZW~tiXSG7@^Za^JJ6cbVxUaw5xXC4f2K?U@!BzPM*L!
z$-I~eGST0Upi4Wt+xe2;b-1KP@5njJ&hSIe*nxl{I5|@?89iBvQJA#iSCafkOSe8@
zW%zt$rH*x`th=L8j*S2i)pIYAq8~eD$=YCUTVHekNENt;RU*zLA!iJ@UL4i?0-$`F
zZedncQPdCe8&*9+21y>7PBLchgAe|`p!H{!2ihRJ2co_xD}`c6j~#S_*ob}PYjgyl
z{QrO<mu>3iEAm+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<whq^{>&1x1(-{-s=8vBrIb@Mc=dsu;l(=!N0&7GnU@8
z&Exr!K1yCY0N%i;@vP<lYY`a%tp28JbqSHt*a*15gcVx!aGx4NZjZzG-hZ9YA>h5v
z@Vh^>G)H=pe4rmslb>-NH0?v@f!DiJuU6K$Gn2P+kOEXT1`q%Mmf@K1zo?E53neK&
zy?}`dm>}<s+U{++ehVuI%F=~CHP0>(-g`SI2|#}RH4^aEaNcpSL-vihlC79`fB4Vt
zrUN$ZUfRO<gqS1WP4M03I!ryJ>atk@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@D<O)T_b_vqpTLWL1D6w<rnAnh9ffzzQ@
zQE3-gl+=ITtsZ4Ke5D{)ybW9YslNGql^ng_?ofQ+R6*#Qa*9A(UZ-p4SM%<TfNu@Z
z4)M(PBVulb%#3#75i6+r8Z({HBKoXgm&o9Umr^ybJ$E&X8%4?4I-KwDMD-s}Rf4Tw
z-(^#YKQ)AlEPJ?v!i1Cz#;LgG#)xqjqICI4PN@cacB<f@#X;HN!pxx&sNH*#s9=G?
z1DeJh)>rD!TWLrZ2adLHQ*z;nphVpQRFaOU)uk*vs{nK2-u%xqt}DY)WksxI{mRah
z;o<cdI4a+(IXpmQ4~kK0@7UHtl@SNEqEeyqaVcgUnty@ou(gPeS_xmtd@<@AMLSMz
z*;V#IEA9|-{eY57Q|Mi)Izq5{u3crb1b-f!a$X<3<Wu)cT>(oW@b;aP)-V<z+r6B1
zM3!?W_ceEzDp}wXlQ*q^m}b>A9N%I!#8~w-rzoX;!G(LMz)OsQV~<HvgPfW|!L(lR
z-UK;#`S^FX_Tv*F(=z$8q4|c7AGNA22XYV320g4Zg~?A1HD}qGmSIz+kgb`gUX}L0
zv<l~DXLbp4qeOGS?#&cc{*ae0USP<fF0)`5#t69d3{~A?)|1;Q_l9@c-}A33jZ_=V
zLo&{G{k*&uLm)XrQ8IaD&>lRpl^7&*#)V&<3<%7%=uM2uS;=@48`~=~*FZqriRy7-
zz^`#b1Ro}5!M%|;;DY$x2APvGQ$jA6G-mhm<w>tqW;;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^xhZ<d)0|k7T@b9kJw0(h3oHkj2fj!G%w!i&xBt&Xyv+c>I_!N+
z_b}g;@5C!tG#0FSoWJD6*$~~{?uX<$g#ljcrT5&h(mrv;ENjHEW4J<g%QN$jl5HEA
zefbi72rq{kV_AT?#8K3(s~%Uq8=mJTa+<uE{QykBL<;+RDBL7y6LPjrfcob;TIyk2
zskP>olzx-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<|<MerS$nN=i@hGS6S#Y(9k
zNfdE}t;1{&pS(>?8u-R%Tcn`S6j`s8HZ!_U+fHN?OuPVYwEln^uwe0#Fr>Egtp<-7
zsoN@^EO{{J11w$|^?fb59n@fMs<Hpbstw{V0;Oj$S>+u0!V?~3?LuTC7+@k*v&TrH
zbchnnlQvGx0_{LX)*8miqYFENmGi(UEe8zO&j{t?Qhigve+P8Dv6RnY=-OMlRfolW
z(Pr3m<xIyigCC|mNXL~MsdoYVPM#B`k-!C}!OJe7feTT94uRqZ!mP2#hk^)`-TFK;
z-2gWfTP`iq9`i1yh&t4=&VRR381f^(LzY=rEV?7y6oNJ!?==Ql96pdab|*p-*kD0-
zeY;2UXOe=QFbgYBiia7>zRZ*42DTM<jqG|KV4!uH312o<{rUjX=*^lS;uMK>*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<Te|F(7#jqUHjD5M2<+Idzik#(u7vmzabiK*>@@ZjC&tf+ZQGMMCf?V
zRQQc^yvERS#$<R>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%H<O|n6aTQpPzLWy96FqU6QC;rR1qY
zM_R4RMI4T`yQYXlfpg<0bs7lz%S8VCiFY4JvU95kp|P)|GVbRWOiRnAH+7;US}C9x
z^w0l@SM2%02A}!h=#K;eBo-gvZ-Y@E%0H_p{lm{FM{m7Xv890(<~voz`8i*_vjz})
zE`SeZynHR8FjF!(Jfq#WCX^oWFkZhxx`_)uax}7b>i57bG9<bt7NB7$G9+i;eM&MO
z(vJ&GA2-rHfFqUjz{=0^QDGA9IY_iS!%Qfs!1Wz>n;9C06@vW@wPUC!^>yH8t<XiT
zDo2t#wh5Mk_Qo4~?qR%OqIhY;gu{QOY`{Ln>jtX807o3`t^$R-?E#)}_N^0S%<NB_
zAG;g`!X7QN+zT;$&8dsv-;`)Y4?Sz%J|BT6(b1Bmay(CI=c;M0GNTd%9S-#l@eb{p
z+{8b$!+lQ7L*Ss~Rz%fm_O;;K9Ex@NGO6pl=dD@#QjoF=kJ)Nta?w%ijV7<$P-XuQ
z@FOjRdKfBiYs)5}gE3<yA8ozxJ#at(JxzR)cqS_CIGbg$OvmELmfiZ2>=)tA3Z}1#
zOZ;Y%RI`!3`}fwRGSI%Mu?W=JUX#gEV@FMi$ajtkO4QzPDkF^I1g4^j7k$^&NFy?b
zX>vO~Uz_~C-y<OH1N!ff3W=Ct1JJr-j}Z^#qjB?fR@h{~<4f?>FZv<4c>aRwdz2Yz
zRKjcjg_U|d8&l@vQ<b`-2-MnRs$ymutdVrkm{S%L#8f|8&}aJ0h(XAO=4KFIts_dD
z%gg!4)jVHDabbV`U{reh5fsbe09r=wAqfta8l?47!_^K#r4PSWXk}e1&?`RmQWyXO
zu~4!UC7n?b=}nrayV)cn62(u!mOr2=-K7#$pWDe>)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~<Qzg^u^OsT3
zmt=zUV`wvXAw^v;`x{ixI1p%1?E}|bv)qG9_Cj~o`o@9;-3U*^DvP09)A=5#m+$c`
zP6G6Jf8N|&Hh85J-67vUL-*LFH@x<eGwb?+;q9U`@PLF~b`hc;V;}$*85@z+*&Vb3
zo`=FKJdAAmz=VDDw>-yzHDdS6ktAe$h&qIwy&7%G(_#|8B2xkYotAX(P;JDW<sUe(
zG`EyL8HZ9I!R+w?LUAB2$0GH&=!NyG?n<~3E6EyGce9;MmBP3RyEXWiyp&|dAQVgx
zsU@^dDQLrvTRzp_vR<%|Y|i}Ag1Q;S07g1Ii=5e=qy6-NBhSwCZMAMOT8<BYHq?#=
z=Pc@H_@MR-;Vr=d|8O7SpdAET19@`!<?D7D17#OknXPM`e>(k<Khubx#cutB%t=OA
zqL%!V{oj`Ai~eV-*rQ+oa{CuMh`k7Ras^VV%Y74s&saf#TFabO*rkN~+HyCF*sH6w
zXQ{U$Y!SwzxX!4&$gA3m8s)cCJnhj~2TPJi)fMAGbWrB)+#u?|*y$D+`k&>1z>(_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=x<so=QmsTa<(s9{&#}ElD<P3Fk
z8<HoY`WwuD>0~Tn?PyyPr&GnPLdydFr!GScT~D@E2*;1{P5VT?;5gve+Ej*wBq#<R
zR>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<Dw(df?cdf9HffMltaVRx_CjNyOi{2R|N8+6ZCbGniTk+5xzHp0?B+8n;FCPy;
zQKqH{0m|rL&6H$v^ey{teHlbVfCX^Jq!p;9EXfCJmB+9m2Wp<d?5{W8LF+LbphjeM
z9UXQUUo<Bb(Pmv=&iQToH0?<6<9Kr4TtNU)-B*1bmlRr-h6Q9>^!)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(<OtNPUpEuOf=hGb%wx$H}tV*|%Z2?F$Wjxq*t9Flx
zJdlk(=9x18ytsw*P8!>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|g<yUx
z?bPY~bhlxqORdU#1yiKK?ju7OtzXn@!}*;v6a@8m_L0jW(UB9CVgYLT+J5N8aMlvu
zZN}0;OB)U#QClTgU&?_=`zddTi%r7_(PG>R3|3YhE(<jU*4wG@$fyRmTo_<e3HbxF
zO$W7b65dyT-co|AzkLwuNLQi^J&V-Uq_BtEGMnvjLOaFTo+5vU@=pxY#Kv0>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|kp<jjFGB16pxKC3vuPgHXd69#ITTUX$rV*sltizp-OF{wS9G~M7f7Y)3y
z3tGaVjpssB)2lH_T6E6?Q`g|@)_BeK7`oxpMGiGV!-mNI%Gm>a5!E0`z*~P*wTW#V
z!6<#CkHi>n?5-@ZaqvnnQ|>;}jdlA!^5|raULln&L)@kq#`efFM~I3^his5ET{717
z683ZM9gDp$IZToe)SM5WDYrXS<uDupmBa#?#U{hRsQ=;V$oFEw(nTZQJJi9Hf|-2o
zGObzXxn$T67-NXOVKvFE3ONPF)@ofQDKmnm5#57#`xAs$rdTM4N#=!aWF#NAoO@dA
zUHGxarH&K|=r-p?>z3kA5YnvLP9)Q4N)bZ3uUva%v|nSK+}efHTOs#uiuLG5kB6-W
zLza6q!l#vP`OmPk8BssGHvn<hznc?1=6rpEX7A*z*SS$YuZ&g~qIdSGIKMMJ3ONBh
z(PdnK4BpNbfa4ouUOK23LUJGrbj3>tz;~RXM#s*hUGGyk*7e`Vr2|&<URmscNMu(~
zLFi5p8-I@QaO;~U^o(?DffJ>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<C%KR*hGr3
z8?1o@Fv48QcPRqqHMlMO3?SsGCxYKLGZd`^k#;wQUS8=N2{Z9)aV{rfZsfoKRnt}b
zqIy7fe8rn@ARA^bpX~34%@zy@yxdPrsYE}>)@PPU-bZ`E9<H+h!5a5uJm<zD9MEMI
zT(J^?E<mnXjd;F*R@2Ntj8G8M%(R-?AEyjHe>8Z(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_%0jFrn5<d709tV;Q1&LE52l{5%zg3T-Lz101U%H;?*xqkQTw
zt;)H#i4_d#kWxeEx-y5LmuG;EGlqCS(u+eVht}8Dd{3h36xId$2i6F^f8bc>Mlgj|
z;-RY)x23EFCHhTY;@*FOk)yxWmdN@YBNmzseaFSp8c?<?gtU0O6f-wlB2OSw`}j-M
zkhW>B$NRRakuSCx!%W9?3lK`)sJGZq@Gt<E=<u@Bz&7Xt5WPka_$xcvEM`8I1GWGI
zr0HqDy8n7c|MI$SP5kY35tYI`q~)ph06K5B;v)GKb!q@o8b2jff&4qo-Ep$0aM*qm
zi{F23{>O4qxeS=#?B_fjvPr<UL>Go~zCUd348&VFfRfgnpBDqxtYUbN29DDul8tva
zG#inUSvNpU2vH|oLTb&?KapfUu@ev`*RCg#+FURNo?yM(NA*#mU{Euo(jYg;OQolT
z1XO+1eIk*iTZ>Y5HPVAP;OYS|Kd`tf*YhNRBr2#&o9e6O_t!J`ubo{&_12dZam5PP
z1iu7eb-lizSxy3p9tmK=TzdDDxcaY$x%!5pC`PmwZ!>-4jUVOX(4y!Xd^Db~3O_4+
z%b%N)gQc91gS4m=l7vd;jN*~acU-d{rSIlln8u$2zvvVd5RelcbY`|_{6rlZS?H=c
z+h}OorCA$PvOaPpdLd^rvgE)6xeLEKhM@*SnCZk3hG?wN1RCR;-*oi#EwU9<MZ4BO
z9EmJUorEwaQ%3jAy4RCl<)ZF`;9}Rn)~FnsRZuoSr)$$D{5vxYUN=@sOb!2PwP^qS
z=rBS#VhhLx`#P_3sfdLaIv`<*Q(*1&Pr_57ZxQqveE=G#*bA82M$D{|qyPrNPVn1v
z(h{B4-G|bT@dxBOoA;hr{Bwn75D8+lbqYg=G~hxIzfT)(;k2A5y~By8tG;?z&Ax8w
zi5;2(W%g0I#d`m4KN?&4=;kUHlhP=vG%RXFmQ9cmO9ekNNd`J1m8=J7I%KGgw^aB^
za{^h!MYAFC^$2cR7b;nY*$S^_=txHcJxuf$w6r%dK57sZCR$ZX-sk~=&e``=*C|<F
zmt<p}(K;ie0?{!m`pvsQt%xK$P6+rTso|-(q(D|1Xikzw7F6i{y1ZJuJY}UNi$LbY
zYXD7HttOK+)^S~lyq2(a#6!1OK*qtFavXu_%|(R~F()(C3Kf92LUjMwOws`n8K=_L
zO&+Rf+hncIV9W^#UO%j5Grc%P_pmfy%d+uVutYVM7cA2K`!xBK8mf%BQI&3LtRSzi
z3AVKyO4~@dVm_7KRqz2Ss!?H+l>lSIc->Zu8FvATHPtt?8;Q@Ov!<BeISZJ;?SwYY
zA2rn5Z*LIpShNxyp{1Tanjqzp&ElEW8#Cw+Irl_|dt?fYKhr{*a)$y)31+wa5swfM
z!5PWgHwd30ysR`pH1$+~i^yJ%&WPG~Ltv;{^*h}A%zlvtr8R99D|2jfFjynbK3=BU
zm5gRL4b97l{1tFe>2JqB&NBp%;r{;_dJX`0`dTJjawDE^*>PRgPT5Zr&I>^DjK4T(
z|GqHLJS`{E<-hQ<TlBe?Uk8v}e56moZ*l^Ni4O4+WBQREq2=onL{D5pxu`mE?Mf62
zVokU5p6@zyR9Yv)7*9&i8e%*02xujPBwQE?GHszK4lme9VpnVDf5%h7!o5ku=Cp^n
zl3mMv<1&N4x%j?c!Fl?{Cgx`4Qjdp*73&do*`YIgcJyk!LAWqN^8rrRI9B@4<Af&n
z<qWA;%90P2^8mZU@@TW?s!f_-Y)jQwM9x-M*EBYJ&>7~d_rTryopRA7qkNrH8l|eJ
zJDr$aI%e-u0nP?MTj<`s<uFIltt&IXb~S^$X)K3wg%C{bJ9>>*g8D37&W9Wr2IN9t
zAG@Kr=RY9YQEwNmoQs;->x(TrgX5=@i2bu_pG6Cur|&P2lPsGBl4ar}sS#*k*VB!!
zLJ7+_Wvrh=gcJjUT|ArbuYT$^!9xp+R`5L;kLyzjk)bZ|U-!iyVHfD&;^ZQ6-%k_U
zge1P+iT;c5)Kx+`Q?QOp<C^TnZq5Egn!`YXfQl?=O8PL#msWPHPe_-dfu^nAsbb>)
zR3FAIl4V$>ug3?(st}USD`m7w@uL#0YRT{M#v!i<n$m=qZ5k5Txk#}sKMmk)&69NY
zKIjc~hlx>yXjfS!SAp=q8J}z%wlYX`0HF@{+>_><rF(S3G3wn$A6Ysh30HzBV|&^(
z&sXTg?2@gtKEuvtOm)ppH9(O)?tjy`@L=iMgO(n)qv-b9*qxIvQ3S(<3(+vTn5~$6
zbFTV?MQCmlco6d0Es~Y|ua`DrR|GWHzB$sSYrMcExi#$;zUE9F#ILs=Wx0qHXEuU^
ze_2fpCm)O*EJH^QjS&lIW5|mD$n)7X?dLTxBRCT%yf&z+BeK_rR4UwHXOOquT-Tl8
ziZUy3B^rh0rU8hi$?i~o8RbiHv^<+cts1r!=LDq}Tju*=Y<!=x%esvB6fsq|EU7p^
zxxhjc=x_hi_&WRyEv~J%XP~jhAL3vvlZ-aX*D`!F<J8zd{-MP0ax{ug`q=ff_t<3M
z(=JUu7>Ck=mF}l7i7OB~XsJa>e4%#wXGyCCZ>vp}h&~!`d2xto=q#xauxIiR=Vaql
z<V^|S<^$Xbv{Ju0I1@MfJl(!Ht;x;y7|<l>*4Ql=ckNWZ8zGHGJ-t^)c1)YdGn)-9
z_(?o0=*9Y2JR?eV$tokj;W=Bzp78_iv^O}7iUoocsKfgTt%AlDFy?+92Z!;`G0O*0
zfH%duhx+_j&R-hQ7J@g~0ZjMgVqrgtiep1kfb?H{3oE+)JT@{Ja%!GtO<_7s_gH#u
zgJIcs%2lpP4)vH|m3%Pc-)?HIs{WI_mqf7;VS8?V?5Vw@c!@RuZ}4&rmE$mQoKBDH
zA7(%uVc+!&&ez24b5uY!7QdCDOQ0Jk#|wdy8+YE=>h={=`+6a6n%&Xa=&LS1t^~@H
zTa&F|1*AbsUyI=qxR19$7||SfCnq9vmo~LQpwMV+J^?HUWmoAZG~t-MT=yN)mUkex
zD&(v~65p}3=S4!@5V^YKC;2n2UYaiRc>sYt_OGl@qq0r!0O#Wy_yZv>^+QZX9C_gq
zGakn<s)IF);hF&?1sjlHAp`zm_SB|`@hyMl*eF-*<-yuD7f~5^SQEdTFO~0cX*22#
z@FrSNZ*w-X(!j@=H5%v9)H1(&I3G4A%g%xE0TRXFPjB+YBlT+2<keB||I+BZ_+7GG
zc<M~@H5MKz2xfI5g*s_3lU?=Rparb^(C^M2CV_Ue`?E7sHt;v7FP(l52rD^I2P-Qt
zJ=^u;rJ7drnWF}0!}QZiHw=QJ=g>pMrSWuyM5GN}S@{-7dE)YzrSRo%r+uq-*Pe00
zjURZ_+v!m=9(@fDPXAI`<G0i-HrOvN8(F<yb}fGwGYdq5zX(*jKNJi?2OJ9Q1Ej-v
zG;TPX$PX5$16rDxU?r}w(tB_b&n#|1b7!;^B;AXzG=2TwhUSnp2Yt|ntBqi%T)K~~
z1NHDV?=$z9DfaT7<i4MO{E3RPqS}#4fim9c_E6FpLB99n{3#hp{0N#=CqSKvKbGTJ
z2=+`bvnGEDx&mW5$aRnJKK>rgA$~VRtkm;cgl>9K5K)H`Zuf+n5O0;fQFQXHHz^>b
z5EJ8BzNd4mBasZl3ZP`DY~~xgpx3ASNviT@3baC|Od6jg=B!z`Uy|tW-YW+O8;WF*
zB6N-`o(tb<qU@2jNP)YxwvAl$RI%OoweC;D-rBvW8f|QHa)cIs^+SYb47r3djRF7p
zDhKx!M!aE7RrOXt`A$NyR=X4{FKB^`dv-6<@y>G5PTUfWA#t@PfLBs=tLHqE><^5w
zi{EI!26ROCsljvrOrjNpcP=2ck)~$L)V(y5doZy5<@D=2O?JT^R}zUmN);wtdDj*n
zCgm`Mhoc1SgJI*11um0o#l)Rk+}141zoQ!IOcvni1Lti{*Vmc9orArymUe(|W+V>7
z_b_GlqC9+xWC&VQ3y6W)DQ{e=9khv82POORn<!bK-J8i%%Riq*WDD8YxC8~_%cc;E
z3dbdR<(r^Q*!g=|;w)RjCYOfE5aIR6RNKf>#W}|p+Fn7jow)ygM3zT|6$}QYRyk9M
zMa<5_MF63Lq~Jqv!8dIfeGu3ecoDDog<UYTSBbkkg&}Fim4krQ6eix%P=Y++It7CJ
zyIOOb2}hA6veCpI_owy?Ua}m|i#USU%qVO9;ErR7+_>mNUOoa#FKhBMfxH+|9W8|k
z7fkIj4XlHBWHr&l!ye49qmauLm`QVebss}{>3f`U`fRBQ?!5+x_ZNe2s0`;W{2B<^
znUkN#)7L&IRMSQs&SF$>R}}9WEW3WV)Ch$QVU~xp^i0v)U;!GltE<(d1OUDy^07Ly
z!_+24eX?%yPR>bu;O&6+;;??~TF?Z|IdsA+axbj%%xj5ziOV1XEkaU$NrqSxcrm3;
z>14=TF2QPRD9QJHcSEv%|L?eOyjR^L$ggX9Ox*#R-}x8acNy!zeS%&>G>U!yARc+n
zysIYJ^G%^}qB2)A9R;HGC*&S>9BK`(Z;G;?1To$@DC{|5(1oWBw(D&=DlL@;!`zRc
zEl)=^gr)Eo{pD^K@m-lBVR(G5d;Nx}<p(>BBF_L0Lv6z>8ou3sF6$X~pxrrE81)rV
zgFc*gc6o?DO$pV5OJ3`SIdXM%A)w7bHx5=W8pAiVrF(92tdYl}agrM$SlfJA6-)gH
z?Tev9U>$-MIdwGv{ZQ3PrQ>~PAyQ8fRIXXg5UT1Zi)fSw9otoQyEDZ;ey`SM9nKcX
z7KMvJ!Y!l4;fq_%9~)Hp2>zS`#Mj!~OGPfUB<vRWi$(;v|50;^oB6sFd*+}?C8Y~u
z7Tarm2s^zK4owz8SMgU}AJuAI(QgppI?qae3b^s8&#dNqip$$?S>6LMRjRm>p<#lu
z#uD|2jV;k<8G1mZcDjGHPIWX1(<MqO0ABS@qg0dMT$F8Tu`fpuJR{dK9PYY{CR9g?
zINr0V=8VJVRF7lO_#P`LN8A|)>`~`kh5=uxE=c;6Vfw9q2ikj4BhM4kclM8sVCraE
zao_F9H=S9i@iM>x`zu}dLjm;QBzZW?kcF|CnqzBnrwVUr>J(b;$6DQY3T(e?M1PSJ
z;pwG0DpEf+%NdcF`!@sk89;jk)6Bme2oM;8J&Z|Ow1+Qp<$s<w-hKZAGlTpKtGJYF
zYCbdsKn9(6h*V?FNnGSs!Apl|jJhDK#CgWhT=5N1!G%VbnQ~?wg_xCm;^NDpN-DN=
zvGIcVV3}x)1`)S9D5)*-+VnI^mg;fe5e|1Hsw!c}f;y+-L3lzi!>n+yOKFruC3o(i
zdEm(DV>@WHy;J*p-VH~FvbrGwAt8i8ZCT(k7n+%YdL<-nG6%ET5IHDAbXEW}K+L~m
zrqg*4ZfNrlar8Gf@{AZ%Lw*_5id$qX_4n~!%jJ2=M|HUme>Xj4qu98zM>K;XtcGrv
z7I0w5q8HF#PuGw9_W;@eXKY<ZS^RiXDlyTqTX7EnHq2OY^4pXOdik|&Bn+C>xM=a`
zSYyXb8C&Rrs|>P8CDU`Cs?aeOLTAIr30_stXd=FVl4wTm7!9HZGqS2U%LX%IaboAN
z*Hz;F>@WxV@%XXxoV5%l{rzRYd4ehTM`;BhA;)hO3HKdm^Yx0}z^OetAs3ls0w81&
z3}b{jqzfGm$Gw_J`C8hK@@+{YT!AEb@{59-?PM*I%5W8h81@$gExBS124#{zq7l8Q
zYmdtL58-K<no22Io5jy)lrngd=>kIGbgL^Zh?E3!Ob!ryEv}WI$)qPGvwYHywj>9$
zyx6VWEG!GOBDrdC<$hU*5o%ml6UBqa`O=LXU9N^eYgX%RRr`(1T*P!W4#ZF<Cdq&R
zi&{E|M)uA<s}yqBlOCWZB+3mgQE(EDz5P{nP;?CHUj~X5m;{huT@>}99}i9Kg|e&^
zyQ38NZU|LC&Rq=xgl&;0E<_NXUvy*NDDdA3PB}Mx_QOK{&=sO^0JG+2Pz`sd&WZNf
z6)`61L&%s@^*sn%IF*ncU<UjxyIj-fsx`zZkOk*`DN~&6sk(cZbD$C_$4!N%SBF&l
zPWDRW8m};4r{Op2l-=*BZE~4T67oQQCw@e5wW$*gykr4~3GUh|VPx7A0DD$h5KYve
zF+(<@5>TjWQZX3>V5%J+D{di9bgAZ2l8IRZoq2WOy_vneUwEn$hW!TxAId(llIrqW
z8KHD8PU=<>f%D*78U})&E$;JK*f%}nRmupt?H$67f3Ba9eznhH>_DY+v2V(<WN`s~
zv&&~ahFm^<pMC(7FDR{rNVUBc1kg^4aH*oiP;M9a1dt+n%!K~afF$LR`HeYwuDeu-
zB!NGI2W0L6_k9bHX#cLnaED3R=2WEskLEL<#=hMy=Jr|X&s{24(111C<AE!=Frqj6
z59Ll#3O>g{t_)qMSie&<wD38@?-WEjiq&Vm8}9z_ry1`7j4IsnJz2gQn+UD=7p?aT
zHn>|j{{p}{O!Dl7O6Eh%deA*sf;fstBZ*MP_9Rn<ho0*msv5_Z?U@BpnvUhmW!5a~
z0>bR;zFJEodq*H(*1vMAkZe@Ud-oH{eUPALbO({F3*_}!_b5P*p0jF%=meb`?eTB-
z2ELq*0wUi6is}fsxl;9a-$(xSHl$a+4B9xd!x>L|G$zy+PyziEMWJ#CUNOsTp_cor
zziDs=%xzOy7+uQ;Xdaq~*wEJ=hXwH3nd%m#Yon{~MvF}cPg&>MjKew%xZ`Xp$gy(a
z(n>$z>igNJ=A;T=3+-324BWX{qvekLr8&hzJ?C_ZZ~L&c08C>^H4}BIumzbee`trl
zDO8o=5aK6oJ{DK`7xg<%N0LZ4SOMP{oi(E{niK46mu;)i`9=O6d2az5ru}^8?E8iF
z@-2hdZVo>O{;2>^H};cZuXDzcyl;i0BXYx9Kf|`C{%OZKcx@<`Dx1=hybRYEs3);9
zYa&%sLuuj>he<@IyAL}rsV$Yt@{sg&a(@W|t1*b7IzlI9m|T>dyU^kt5luxtC(jS2
zyQ!H_yzcctJXkOLe%QvJ2i}{sbuk@KjhrX3-{1!{mlci1`e0ns+*qrJ`CWN*ME1vx
zE&8;?SpbIeG`tu|9rB3lw00z~4ARkqp_Ak-8VHs1@&>K4LJJ1<kXDImdcP0rG`upV
za&mC~T7w6z01^+=tAZ=~jrD+%tcTT+h5?v*0D9IU>=nL^v&ZpY9!n4fqz8|fef`aJ
zzW=9XvVZNht_-nZ+HrQQ7mdexNY0s`aoAA0*HO~}K<y}fxt-8`dhl997L_S7)ljEU
zx@M2qj@a|RX^=6p0&?xc?0u_jNWtH5OJ<kt>spx!e=5KMnQli}NSTN3YSS%p7O4<6
z&uh)QT;XCZIrrefq};Sc|LHU4lW0#fRp-6<L>chh1BlZ{T7w3u7F~>hLYEPx)45DV
znY+rQA-Ku*FtL=_<HefDLWD3p&<WXcO>kxmvh9pPq=67qn?IYNv42{_Se%0ayV298
z+-kt*`vnd|IjTYbNdR+dIrQ<Ru4(Dc1#q>+DDKinzGt#3=e#EDGVD5FTq+vX3v~vT
z-Ytd;+Z5Cn2pgSGF0y{(5#ax!J#{oG8(^+{pWmJ;0CQx>x7PKShE0K#!=*3_rg^TM
zCOBnp?PL<(J8HTJKUMwJ@dZ$#Jv;JXW)F-g^N=!9+>zR&5l3#annk?`<uZbUgS2a)
zxr&|#>UIhQK9{|a;G|`~*fKbxPh%bRg*u?`N_`VueTQ@2J{=1-gMUZnZ#ZCx(x+|J
zv#}Y0#f6BmAnuxoLAhi^${DZ5wWGN7Ep^TsddVJP(OilG>I#dD{o=d{{Zy<4<I9B}
z^P5FTI+gs5a4&0~HbrF}!sx2fA_(glWsG=gwVq!$_D1Vu33L+}Fl#suFtvytFsUYb
z_K<Cu5}BI2B*-8Fc03`CfhUzC>L4aE{Pf!N*L}?t;wC-!Dk(U=;<%jKKTCQWPR&Wy
z_U;N&1rUGC6%%q^ZFXuce@}{A6_{9iU%jn9gT`GH=+Nt$DO2K++5|q31M_qIw{0jF
zkNbR>=?9_}+}JrNEeIt2hskuZ550%NL6A)CPlpo(2NQ$=1jd4p)Hwe#m<S&S`Xhq1
zdZCvJ4P+&KZ<no6%xy7zG2$9LLXu`?ouG0%0V;Im4*k2LC74|I&#|EUIE0KXokb4H
zCfaF_+K+w0B6z-`Cm2jXtGat_1k2u)uVR8^$Uz*O(28%U>vm{!6{6gZ7l$Bk<wgLV
z$}wHWT=LM@l`~L*{|)lsfn!-6{7ogFW5kH~>JxY6&iAWDcxWAz<SIf@$Vq;uZbYVO
zJuA8GNsXGU-Q~hU*3@>uOh}|DGbDMRmx0B2HBQuELi?+H(SqjCUP1=4Zu5ibbsl@M
z^-Y#JawUw!pqrKMcfGsVRwtAIecOA^?0ipx%ntRLw=<3CKvzu}k^^#|+)`feY5^L?
zhG3Oj?Zvo3C8Gj`##1~P_BbT=`$=8l-q^-thRzQ0&=!lY1fac@j{&B*Opv2PILf!j
zOW8JN!HRU`A3QvVbb+Yjt0fpd+WL*y3Z>`ae8Qkk$lTywH+frRlKp1suWSK{=3f=@
zN4y@o`U9JCTL32qoW%!zgW{r$mQ(6HqO*vSiJ5V>mfZu-TQ|#c3$fIQvwq7$ptROG
z!W%b;jk$fB^(<4)7Gb8;EbbZqfMwf<9J%aTUN?a-z>-uEbS5oQ`^QlRS5}_rsp0gf
zjGd=Zl0Ns~q5obM+9b}GTCBKI%7t4=4h00=E%sJ!f?lQTn`z&qCG56pJd~%&Y3mKy
zfEFCP@t@%Gxkar!OQIpj<x5mV!>=KFMparJ0&y~tGZBYF09XxCobQoJXxEVb8B2R9
zgxU}iF&{CbMm_b9m8h3Qt-dTn_=c8D^)sg-+nJ<n=z3GE`r*LrU*QZoE<)@<pS2Vk
zhE;A9>_bk5JaW)QYmdzrFJEkfyt7Of{Nx64ys~T?SDkN~=;b5St0HxHC!mYCcjqr(
z<{>vtT2({q{6fuBijJLCJgNdDGs$S=%@`F)RMz6u=@-yhn$gmI01+rry@*mRd2oW}
z#~g^9WVMVAC|{sssu<m&dJBp6d|ErUkfGEPTet+VzngS>irdpwzfS_*UKQaqQW^6h
zLP)k~yhBS75x57LxRg=Dfk&ueB_J^8Q@{I!=RrZl^k7!v*(ckLV>UoRgg!gmtB}6R
zAUP=3T-q>fFd9OR;w@Y3^Y_E&kXZ^Cmg%sT6PyAJyAaX_W^-E<UjZ`GM3a#S+X5Rc
z*er)6m>G`CdX|wsil+Jnv7Me{k>9-n<5qVMC`ZNp)rs1w^fVdKKf}4_<TOjuJrGyP
zRP0)oc535X@)r1XPw{3Wv6~U3QiN*v(y?8!ZDG#Hp}1TyB9%6+^|dQ3X#<nS%T05v
z$tAb{qo&SC(CMa=x7*p1bKpA7OyefBKj8P*<r;xn9@KjJWwRD^UBM(l%_d6TljooV
z(-^Zqo`{;i0(2yBpB011B}j6;<JC{QzRba4B?8!I^UsuQb<2HsXPRD8gd}l0VeI+k
zBWA(7!6_^=1IBE1HwIHHrW>d=B|p7R<xh&LU&be3AINKcsz|l}W0QvSB#9L|2>Fsq
znMqwOTd&6+M44?K4XUzmZh^lMRnzIANeQ^A)v38NY1zX}MF#959l)UCib|GVgY75~
zt|YtHIT*f@Xj>_|KsXWuHVz{%U;>7ak)EjE&qD{@+%QjSUMvoIS3dWCCeByMX%e;4
z<BtW0h)n1u->H)w*rZ$;TbnQD!C>mzMXI;W+lB`F<ybuq;}Vz@{ANWZrI*2pbysNv
zYNUsniJ9sH-t7Nu`KhBt!FPL|LZR@31Mih8l$v3m%)1&2c|+~y_@r5W`c)lD5p#-F
zY+O)-3$IHdUh+6|JpgdHr0VW+`Uw<o==D0bU*&k3rOVWiewgvkAWPItCaDTiDrv2k
z>~O#3JgYl^t;ySiZXFGVsTD%RQJ$^zch!f};)5Y9{pCY872?oLBjUJmIV;iXm$!1o
z;kLLKeWKF*?=Wq>+vOl8`cTvJ0L5U#;cC6CHj~)<&R^`7WvXR%%e%aD-L_uzVvMv8
z8vc%32=V4tM3NG5(2DhGQ)(}yVDH|nn4)N418cF!L(#absfk!c&4KmBd^0HQI8}+c
zN*1HE7n15X<+L!ovvY91T-R3#;XjdwK?PlMV0o=IGzz|yp%aS37hYlB)hK0i>`&w%
zvIn`^!S(j0gJuY;%Dy1bDuMY{IBxl}ggxztq1__DL8f4~uPAE@l^f|4jX8jFIQhwW
zcowlfP-bpc`_w-`uRt^28dD-61}PqWLB~)p)^hGM5GK7Jh`;a)eQI`pj$5_A$56S;
zPUP-hDDymfQot{wsCCj05`X+O=G1=Bd{8=8{IlAqFY^9)!XEOha0=HQx$#3l53mH4
zCwMzsTpW8&5NaLcm@;SVfcOaMXUNK9*bA7+e79#JZ^*gopL-DS=Xz-6x?WbS1t3g#
z-VHobMmBQ&4ZXp_@@J%pZw4X!Bu=#8F_1iTtn`ak597@BC1@F4ozqK06gSbvVzdQv
z<(fFc$}&>ma`t<-FX*-wE`orDx^g;?e(@cQYT3X3QeS}=Ar>q&wfJO4qol?w;O*ew
zO(5ezpm_waK6h#~TVa^Sxzj@O-e3t2U^^Xy0v5T<U|augEgq7e1AD05%@g-+ttPa!
zhn}l+t77hx?!EUbO7WyIgEZP$u7^R5nKDewp^+pX=9ErfZ9V&|sAsd^p*D!5Zs?Z8
zEryl>G-eL5%h-ts_!B#Yj>Y5Br?J8DlPTbB>>=_oxF!r;#!8L@dYJ*kw`@W8G(;O=
zV5qjvVG@G;qC*0{<;*vkg4!8)tFA{H7S~ZAR~huc*dUe0#h=Dn;4ZaIKmaC(N<Mw}
zv}fhY`AxW~sjqqyWv!+OR@rIqHgJG{!FL@i%uoQ>no+Rp|B@HjfJ<@;FCn@dpSsjX
zKt~W##1a|DxkUB}rE_nIOK{<t{;64V3*MKIv=F!lcyFD=4sszU-?+xQm7$!be0eb%
zxY$qfZxqgt-W_xN8BLvAUxMhDB}fjg9L8yfCWoArBcztnp@ilGkD=+x=C1CfIia*F
z+3G32SexMF(T^sqlW8V1k#p<gtZ~a968&VIGw$zUFJ;?9Y>tsQx%5M%eH5p5j>K!v
z2;jP+ypdY&aj>g#9}ggQ(s2euDFh#!ARfE^48huL73)k?m?}z)Jd%U=8o&xhjea@7
zHgN_ra0wXfV(R$^Qgb4k?GiPqicw|(IMbD}6F==?M-V{Na$H+i=ff6+k<1}I>i*O+
z<d_g`MC}2!Rx0jQBCpFD(*+-h*W%mybXqO&?^94jnzpIbQ&G&akjE4SVxRhW?L`-r
z`FU+`>{osRwky3AIPy!Wf-lbJ7peV0B3zeF!x(a~7Lx^(uqjJ%I=vD=<hW7l0p)!4
zt`h`$_pY+MB}Jq-gD30!l`x9U61Am(d+oRc6kDKbSBe3TV3hp>KlVvX_wX1|(2>3e
zqeauOo<dtRI4o#()ssg)<~s0$!z$@B!Y-?Ee{d~HKCh_WMMlX{G@gj*(zRjNxaj4B
zracJj6)QmS`vDT9?X=EGsCRHrdif>>2ehb1hJlO|3TKhy#gMEgCE7$9wa@Z~;B>To
zbLUnb>K*uBYkpdDXp|muz3J|Py%pJ|k9ccUB3RH8<La{L-$RNP<dBS&2aNEHlU4{X
z4yXu|QY?{7Y61(NyGM`_y#fgJUQd8_iop-u4lREX(iY8K0LPmVFE+rU!zmpbca?xX
z(jNV<+Dzg!t=T*84ZSY^LE*F5(1UbY+%YQ%-!g3$3{gq@TB|;k&8^|FempFe^Pe|J
zmr<=;O_gS<=#w-s-+(MECZ?-p6H@%1GGbqk^XotCsNUhZ%JV9W3>BQo#Uwgqy>p$-
za2hX=Wk4uw>AobN2}@T`7-KXV^QgTNL;7#gKp4D=`&{4^GAWvUf}K(H9!~9SXd{}x
z5lnJPxHW6`24Y0FG(Z_KIh`OOm;}LY*w>;Xqj`l<cc`h(sIO-1w(F|V*H!F#F9Yh%
z12*oQtO+=><Kdb=$E;&B^>L}kbz*qVV7LAdj{RW(+yAQe`4-yeJY`ECd!D$4MW;IM
zRK+u`8>3YasTT!CX+3u-y29G%o6`FK6RskDIEJ5=Pc>;!!x30rlcN=<3x^IFt!%cH
zo1EUS>8&Pq%?-CbM4Pd|PwLcD<kXZK3r#R_+f!e>4mC;St2tD09Qe3L+&MGW<sq{W
zXxh>m>D2f>YXDc%b`EV|Lz$1Ml{lnyt2mdY4LyIZ=2VzF3z{<F<n<;Aj8GOnBFtqx
zd#&Ftg9hz|5o1vwcB`w<!N_}6jpclOAgI+V)g(U4f>%?tkm_=`SkAF4xHkECfvFqi
z$?&uG4^b1z!P^2Nda>16$VDSK==4yRE~F?M^CL8^C^#yt5Rbe=Tn-{px>bM+FWP)A
zgq=c1fSNpTz{(61@Dm5mn+_yq$a{3y2*lFsLHc-<j-qaxi?f)53`bcVAp3#15}m65
zC%0sL%lOYOG<^1h$FeQa%s~rI`#`Q`L^f;H6P${?PSDzIv^xbl<&kRv{rSIw;|Nzm
zZAk{2NS<^Tq7zv3L4Wo{{G^lE$U){wTAzj8M?)^3KN?cV0Tbr;#H<;xO_F<JmI6}8
z`%4q3n<Ki@<7SV?fqG?-bIoInVd@m>L1pyM7lN<oqJb}=8OUi8_=)1E#4jry%`9!8
zV+T>*zx8d)Bm2OaBZTo%D3Xa^oIg4)KLH`iG<H>)7TDyF{X=KVf_JrLf-q`ATpT@I
z<@(JRwsL{r=8Q<_^D5sC`=fPueW@fNWj`66BXiZs-`m2R$vb}e&MHh&qDpl7N9kec
z{K>^vR2YB;-uUgvJX|V4|C7(`u3TL4zbQE%R74h^@l+&*GO`0FZ8D9i)%!yhGACDS
zW}2rq<fflni|Pb}kl(0z3<v{YXIksYSt^5r`OeSM<EP^jDX<d-S111|^8^A@m^Ogi
zp@inh>l-vF+v&%(LA69Sc4#f6n3tRrtOZeF{U}b}s0I>SD$uecePwdXUWCsgw8IJp
zQ-~6Dp|XzuDcz%PlZn0+P)pO_1w9WF-g+b=F~c(*n@*90oy2j3Li80EKF0tADY8_6
z5ibnXgl^(J{va{QWSRr7>p?G9${acHD&ufDlchqZosN4Xy0YtWgW5F5h9Y*(kOuiA
zyQVqv*+Z(dM}v{VVt_wvfG!#&Kh#_0{Yn@*^e-eXb-V@0AaLfBR3vQ?JpxxOmB6o|
zv_11(dhdK|+o2}B$?<q;>4?+pM`)BJ?G&Jr@4*D)&QXB6LpG`7Khv}O^W+-`SbjN?
zb(HV4k6^5X-j~hd8Sl@hGvU6H`D(m1eY_XPg)9%I*r@R3p()lWlf!C5i_k{Gzt0&j
z<8XghU5Rakn}DV8jT7|P+B{8yK-7-H3JmVteR?eoIfYgDU1-a&(7aLcS3|!Ii+Vbh
z<U&o>$C2*I4FTt^jkq<82v>ds{k<wWp>I<#e7bc{RGg0grNKvho^@`zL>OW{p<(~Y
z9r*oUPQMre0r9sGq8;<5cn}Z)s|MLqqzk<2rEpKL2P4YN3a|ZN1O#6Hf(J4cwS-5&
zF4f}Otz=BDe%|MbfQ?W3sI=iZ9L|#nQnrF;-MjPDId?<^4pGNGODnN&1Hf9jxC4M8
z4wNZ6m=i)&hAh=_0F{gJyk%XbOA{(JjaJMJa#wziO<pD?E?!8S0HAVaDnqomj=6qX
zmO^BArXNjLqQ7t2{Y!^gmRbkgBMEn*YXc*ak$^q({HHKQmU?r#mNP8Dv_=Cxp*7HH
zX?rTt{x%Tul|yVBTz0DVyhRHB6f0XVZ)eQd8j9W3cA4`|<H2ZxfbPzn%ay-_2Gfqe
zSt*2p0uwq>17%z_(8Y@Q(Vaz<I4*J^w%1Llbrciw87&amE>#KCIYKDs1UFr1<kzR|
zEceIkICm=T8WY~Hu_K4&!G?|oovS4hxpF!C>(n(7^ia4Gvi=lIPV_a~S}sZI7dN6Y
zgg88fW^b(7s)|WNXE5SxKplH~0UR@1^hd9weQq?#{bEs<qO)uee%nGj1${6cKYRD7
zQWEJ-oKrMOb-{I$y=Ct|*zc5f)UVzu=cgCTK#;h;I}Q>h!`fg9v7Fc+$Xbyoosp{c
zd+tr}m?I{)rSV3T-YIVXxG;s<LtD}#Jyj68SOM)i+i(9zczXigB^QtwgBt5_BL_!C
z9sop5hL5wWc~BpvhU?&{l$WjR3^qQfH(5<(U>QTg+i?FfXL*9=U9j1Pz_=xk)C7S8
z9zfAvLbm%}AWYW1uU1y_anm+LFuq&J@?}YZu2S)GrQh?3`14F*s30COclgBjBo+pI
zhHkS;6t39_wJ3%tXX$2@7-G_$Utvvs0`HMAfvfUdAUv*BC;RLDH3Ed@PIv^e^fv3%
zuip2D#Z^w}pyO*;%(Kqw>&(^Yux5cu(HH)OWQES?3<BLD^_h%jc4R*;u;xjQ&p$Nn
zJD_M_|4Su@1>0i^14&IoPHFcDCFXD%dPVJ4KxWOPicq?uR*Nlj3L4WXFLWQX43m*o
zjKRRB7-ax#=6)+IdaV#<Vj=V+Zc?Hh)u4nZpmj#v1Vf56Ic{ScN`71%Sfe>L>4m43
zShRr%ci4pk$UAx*P`517|MsTSp*OQR$;ObGZ)8N47A5^3PY*)i{*SA>!{|9@Oe=4u
z-o)7uIJlgqe-aasscDhjg}xsZ2S+cfoOXZpFB}Nh@@S*E)9FUv(3|pNUktx%RS9_#
z+O+QBbIVe95)6gVl7myzVWs^g1Jr`XMH9-8u>W*3_#*FJ0#bt&qFXjViP=rti6Ni5
zE&^X?>&Nwi;d~Y8W%pfa2sKYV8nBLqLX3P<oR36H)^~&N=M(i0@XZcPMc^2h$kfXx
zH@=$$0oj4xIbgrldWeT$Z|lH~T4k|9QtL5x+_P}LC4|70oTvc_IcW)gv>cOQmr!l{
zq&81&GquN)JD>_PC;<NRVAU>z+xAerXa-Yn-zmetz5+j(nuCE<{+$qZF`Bt%$^5fl
zxOmNwcJK?CP2TNet1+lTvj83~)W=+Dg_4;%^52+O!-ZGy2D;y(RAm|xE8P}rQo$m8
z)`js_c7@oI%7(_}(<`dJ97+1#2I-F%gxv;q;HhWARb;7<%t9FesEhg)qmFSsk2mea
z&Yerd5?9xq<b=Ul0%h(THsM}&ZAtJls7OPKf27B09AQK8{H!z@Q6)@a>k<?p--e{I
z8;i*P&x@B;`JLZvLWzr>kd^2wH!T<XBkk1PE8mi035UVPjj}eQ^$<wr#CNG}&sVIi
z+Ta3~;oFfH`bKt4J+_CR6_{m*_78b%8YJ`ICvg1w(VsP_KYk=#R_&mu{sk8RhwNqp
zci5rz>7VK9007u3ZExY;SRzMJ6_2q>42OMv0}KwaD-$X*M(!$Q(G#{Dq{wW~Ocbty
zv)ppPJDIU>A6io!&%c(37DhTc>=c{G4Iw@<=(pHx@3a;6Hr1~K8dcYgziX;vpG*uG
zY-@W1cCKWgb2H-;1`VxyF*y3OeTVJ~I9`?foiPmf%?>2t^3;rb^W}szY&cKsD>0RA
zl81c-mp*_x>@;QoMkIkC-RR|1(INch7yun5U(|^u&>|Ali?QgZ=OnL&2tXvVq|Ls-
z1eCrVAPBAoT{NKwZRzGV`}5!%l3V6JOn3sHpaV2hgF-1VfDR?v0G?wBS8|WSl+$bB
z=9fM(x*$N?$S|J{UGTQ^S{5l($$&3KnG9sl;X5YL(^udrqTs}8*JlDt*d$;xz2Gtm
zZ@`JH8g79V5)hTS`3*q|dKZR2Qe`JzzkzZ^Stf3vztLXjcH7L1A8Z0d-744)JZ7dU
z+k)U!&o~*U)mJq-RxM>vZ2Lkru#bnvPKirFIKcNATl7xu`jtII@=pTyXPq3a<xxR<
z5q@&H@p*xK9>j>XYqE5bDWH$7G_aj<>uWWNR<P=S!PpiGII-Ut{<^qOnVmse3Sg^U
z=aS(2aS(@S%4lJ&`{Wug!b?JU)t@1-7r`hDNWRuAY~@ddpajrSpLcbL_r=sZ1-qO{
zg^P%mHHB~g@>Q?1)lKpRx2M};uf&ouYbf@pr>{#AC+*qAjDR|rj?Mb8(T~_b;)@L#
zX+K1X8LYQNUQgy5lCUy7NF@QgX#O=hmz$Et43OAyDI;7FS-qvidF06ODY2#yH(a@3
z3rhhoNJm%UGTG``R_RAkjO74R=hqIvn8nzzbh4RG+FozzOVx-p*F=+K@~%=B8<Kg}
z+ml=f*F^7&Km_x_4;z3hUK;MvyViFg+5XDD8lMf;tFC+5jFuQ`P)3{#?yM60RoFmP
zRk@wtNATnV_{iOIl;k=QY;5q55pJSDtc#QZK<kOqS%I9uoZnGgFT+PZY~yTYv8}$9
z1|pG_UHrUc5gk6mwu%0MLRsFTbrQKgYI&fE<dR(OOUdRf&<Ddj@A4L9H%i*Y8LjLG
zyu%5tT8*=vHOFba0uWMlXX)3^ga-!fOZP|te$)&7&*5<EOT8lBf{t9KbQh0y?%t`D
zB=?UZAhgW|#r7&_4szoo%-s(njZZKQ2H|!|WcL)tB~q~>Ql5XnwM!7WGjOD4nu{~K
zt+u^#5dz?YRgIhL*6a-^9)7$J>kMuO%~wWr!v#DPU6k)&_qN*pBhda*8m-JIPiIYo
zqG&png)|lllr&zD=3^S4-E2-c<bf}jdw*X*8Jj%3HBg2?VeV>bIlqUv4;ux>OJd8J
ziw&S3EDsO)-q{20a-c1O^bKCIgA6RN#eIp{e9u&*5XHGm)Do(n>Q~N``{S83DhZ*s
z`PG@_SD*28WBVfdz8zA~Spj-I(=Kdk(aX+y?LrM3j%|ZoB_vr+EQ;97?ji?)s|c{u
z5vhd_IyJQA_XbW@al*CY;;A;oX1Lh!-#fG++_RzY3M0sxA~$Glr$|OeOIzlUL0hzZ
zFnmOFxEi^76+KW2+!i4|>;i_U&q%Fy%9P|<ctOr+dJj0g`$0h<xEg5#qpf=&ubTH2
zh_jO>!{Y7eE!w{W+AC8@=Z;wgbXsL>@G{smT`6r*gmC!X!T!2ogI_J>i_`N>AT?XK
zx(*$CcnXr6TnWyfqtTt8M}buyvhC3m-_m8zrig+r=a=FPB)8-xA*pHg4X@preHXJv
zW`1s0m6F|TIdc#6=V~%HAPU0AaX)=`WBrePBiC&7DHLhX!Fr4j9N%nS|Lbh)3fo^P
z%-kGD(?l~myy^}!iHPU}NMUIN?a}E(Ooo9_r&bo6TNUiN7SM~?4Nn#9RuxQh<~cn#
zF220LmXq+TdIRx*0A=605(dAMfH>3*L;yJ-9R=9Ifkk6e(!cC3;Rsks91jvg-u#z|
zaapZA|3Jy=D5IzVKgK>3pa|OdmW!brZ`UWmC|=OsaDfLcrreygu8=TF<6Y_`&(ik1
z(q+s#=5G}j?U=Nm<v~gxWKW<8)s+f6rm2)QJpMdfMv_4A98Owfubo7x>XAj2-M%AV
zfaS{#W+R^dYc~Eh6~?0CC~LyaQjkh#pLvoptU1+`9LVZhG$l%5w^+6qza+>-sM^4^
z;i}pJWEz+7ZNF(jhWSJ0de%B>5tE9mlu5<OnzO{787obBu{L0)H+Gpq$+gk;*4UyH
zBi6%RMssE_B->98DTj^-SJj)NW@TAVS_PI{MI|xI@$R@q!8#Y($u5W@b~V=rp?BIc
zg-(*<c1>db1Yn{4K;$A+z<~mV#X}*73ry_EEG1gVzFu!zK%g~I^R{J7a2V2w@p&1c
zj*3EzS@6Y$RWWRg!i}lVAdd<--=cm}FwSzNj&39hK<Up6jI|AYDm$_b^`owb;#ANv
zoTz|Grnizja+j5L3h53d&3sBpN-mE1x!5wjb--&bpHD%*&epP4^O-j?8s(tudJyat
zH5k+6?<Aj)XOFvg2QN_r&ciZgavEczvtJw)25-xCxsSa@lN1a<;T&)c<<1_imW91~
zGzNiS|CUS8PHYgq;DGaBZ<nd}${uJAgpYJIdhT_Z0p>p9AG`qo<&`ryLxIp^3`zz0
z*ULQLEAiJebDs*A6@)o(J;-OIUL|P{#ujm|?LAt%*yR%~g8?*-_}Y$zfTXw|31r3o
zX%ejC7?>JIuSJQT9%~Jyy1>fe=I1hp#1L!jzC9`9p7oep0Qa)2YU)OQM22MuT-~T)
z8$TpB9{F`T=QK>Yo~3ln(|dgDa#tlxNgCxkp<exLTqdy6d}7Jog9T;lO%2&N;PrVw
z<O7qiw4GozFA4IcC_kk^0!mniu!taQn2?)*&79YaBD2OnSK00L>x2oM^7uCtE3eB!
zYjDIucjxdu5DhxM$ov-xrwe=1|0`|0wD82+l$W+#z_CKhSjMi-cfNCSKCj&al_6$b
zdQ_S8TWLLP4cWlYvN)Dqs%27ZS$g>2(&C<(1maQ;F{$U?9lO*^ROhjf&yI6Mz(cXy
z5uxksY7@L1Bl-CauO_Q8A%I-wo^|hrh6^DZhcCz}Sba0%#p@TB8vM*e=En*Q!+`Ns
z#swrDN4xD$lXMpNO_D}X<ic@$Nj)%|L_>4iMz3as3J3-T-?FAN<EXz(Fqh%^Rp=``
z@fmd7dPU~%%tjaZx*j&gEH7|+9qUd2sncurU%>4OIF~_xR`NO`Nd|XxW*;XT@*e12
z(g%1weLH#lBYolo??Lp_nOepLN4y_q%a`_HySaQ6I}XF0$xlQ5jbDuvmgrf(U3Rf-
zY|&s2Or--X?v<5WW#qg#-jR4)epgLuM9##gL1v;gw0$*9XX%jFBBAg&oY&@&9nQSs
zA1(^qkUTgX`bc~s9FCSa%kt)a8(8ka)Q8Uw>b$)jxPqZLzrcLb%2NV-y|S<wHN^Gi
zpkOmnV0Oc2XaI+kKO9h4GCJt^#?>aaMo0`3_Wl*{TN4LJCO%g3Kv*ZS0?W1VQ?LgD
zyQEu@Iq5HF>Lw<XD6k{ewCuTK3S}425as{pW9H|t)__cYnnX6C72gFlNZ#RW+#Pxs
za~{JosxRNH1V{mrw>|(E9F85CL_MH^SSR^NVKQe{>=`puU~>$_3)VeQ5A?Rt9g!}O
z_|qC|g|%=2K~thJ9g#3w3kl~3mnO_jBfvq0wy>MbjRwudD?!NegM$>yVNp&UT#&+X
z#%QMcWQmX;g)VEQbaWz6fN9fRjoEa0H>W!ns`f?4RyUj|NsmxHwNd7oxB>C|E{3@l
zFq|eY$cdL0AIw1pYhyEJ6QTP}>>ss}P${H`2!}lj%q}Iy9uA#qA>FR`gft=spKF5i
zb;r1Dmq#(T3^5i+43wNq*dM-bpi#1&U~ZgTj!HfC6=|zMC@a46E9dzAH=&_em7T4G
z$6T=P3;M7|s>~{p-vmp|#Tm~griWT6lK~^oPTw2$(FPC@y~SLh(x6%pia-^ULn|g6
z)PA>lVA-iIlsf2b3`qUkKxOm`?4Jf%6#JRW-g>{cZhleTLUK|afZKIdkEx1D|2jdX
zT%oNN>Mr*rpme#HZ&HTx>_vhsh%J<mht0(S&6h9>|LZXyz>Vxs@o^qsXdejnAIupr
za+DbgLqZ|810Z%PIGEbmg~HU}k;s!8w1iJxzM3<Td0VR}ZuY^AIz0}7{nP(NvIzkv
z-TwOcJstKIPGQ;+=dvi51DncGF_Wq5qx+D(+$%KkU0I0A2%T<8NLQbYggIrQcxnQK
zO_%vG@}J+hVz)MGgJj|%nPd4UwgFzQdENkB5k<0{cAPXsa`-dY*u3I}HD*i+%u6zJ
z9fvSyL0_mh_WDf!d9w8H^{Ez{W+gBghYVgyl(Euj;Q7GSI}3OUSAf20Jvu&d-)t8Y
z6BU);1Ar3<N=wS53Q;gzx5g3Kbr#FkHCCr$hP59ft(Zb=r(IbdW?F_@<n&Tw6Yaf<
z7I>?#+m7GYaNp+M(Dd74dC|VUIk34{5A!vfi>MI!vn(x#4h2;4apx<ZkrP3_IjvwE
zz-vM(N}#SA;xiELz^~2SS~dI{N)aN=jZN^zpUIZKSg3z#*pQ^;g@C@2GRcs-o-60^
z8Xr4!%g}qHutUM;E7LSyWX`R5aZHuPnlMN>-gUS5+pFZuQAC4tW&bk8O~e!oBuRY(
z|9ARufAY*eWO^pYflJ(guO`P)M;<M*L7PmwNinBs{j640lcZ}I)x*H<NMSm_&k+C~
zoXJ!6T;d!o)_{*p_0W5<kIv3)q_OH!=!K#eTZ&-!>swe;fijT#wUT54seT+fMWS1t
zVeso}+Qj?%IjQ?)OdLi@J{;VXhr}iUaWzWarw|hhRfNuoAOr$Ck#DS=@EH^zr_4k}
zfRVF(^+eYd_OSCJE&%)0o7*~A+1HAGcpexv)7N;;;cgRD?2#xgJtF|G4#cQFkUrgE
z5ck>3)A@*aG_yHw*N&og=W>?siAXJVj-gKxm<;}2W{+g_5wF({A9u{?cx>|TMUsPh
zH4;z*mHWrPU}e4aMQOpOZuzNTEhe5O*`bdz*c63MEBRF%v2VTnT}c%Yp@!nG;@`<z
zi$8U-4!<a;ktXL8Evv<_6u7);Kp4xVOGE6UF~^eX#r3%zG{psIyh~R(T~s8VGIoGC
z!e(PczQ8Om3#~=VsZCl4Cj@g8@D?N2y^Ze9eOl~ODS6F82CY;$aj#KK<lkw2eXTs2
zgA#IbNgc_rK!B)X3!_-dt2Gm3=r4K`rx{9>YZ|Y)_1VKSGna>u{fSl!^T+~SIyU)b
z06)j$76}As5&GZ>2<X%+gs-ktpTHhW|Bk2(@R245bK{QQbIv&9faA}g{`V=AI_dG%
zQ1{7L0_NZRfFKl<IDoanFaRX+y)9oocw&8wZ66i;u_=<u%!OWwJo_Q^rci(T5_lcs
z^JZLn!8Fx}>i)_{;_P}YU|DhOnudr)B0u2<s#f#3FhOm}k%RB0VWV<wt#*dAFtt&p
zyWi4SF`yeYdZ25P|JWBoLr+O1undMj)glf;<vAb3MOpO8y73Ff$2)ZW6)B%#xq{mP
z5Q$QD2@v9Fz|_8Nxe$v@cVADrvl2kQ-!4FviwKxtDl)#?rBDp83jRcY%-iLl01#!I
z(EF#o6a_=qrv^0LLS;9f2g9K9yVi|VHl4o3(sEW2yu@9Mx*DH+QRBj^QzK-FUvToj
zd=6;w71re}_4N!15qH0uyGV~f_E#cc%pjn@t>6u8lsk1>@Zf2s`2#}YwLkAAvL!#e
z$v0t<C;#S7N@M7uR<()fOK%xu%!#>q=?o_JK@pIeB7g-<<=Q1$_CVM`z2@e5Jk*2L
z-2nuUyVHv=p<zsHfWN*R)2B1oF?Ck;aWUcRl}@cx)WW2ruhNCPpwa#A>^rsiH7B*;
zKOm!2l1dz7)UaXt;|fp}35j?d;D3{1k|!=6Sv+UTFR$U^u*cK+5tNS7+=^S7?WYn;
zb0ek~PdY|1Mc>>(PEN;XY8SSC*k`=?n4Kmc#!^n*QFganzP<e@#4r%Ogjq8et<DK_
z-9B?dq56PI@`~=!IN7EnXORW6{mICO*%A9NF8~96f;R<0g5oD}quzv{f{s=qxqZ)$
z=p}>qt+Yo>88%e(!X_~{S=JK*4h*z{3t1*xCjZj8qoha~#wk-+i?XyU^-<$B<zR4z
zR2OgsLiO}$t=$JxYdnC6jD8o4Vpqu$VJ5@&0s-Hu?Skc#_FTDJO15GaI}*@sSPN(6
zmJHjXY~37F!oYiN;>BVS>_l3CNI$%>>j;N%+M{T>IJ~Ux5c7Wq1u%aCD`Gs4No&;k
zX8Pbu#?EPA+_WFxNTI=6oejBazKZo+no{qd>~t{z1gEKOJb04o=hfV3tH&!+ZUK^Q
zw^ZgSki5VyTp7Fwk*a0#BNjr0O-CvDHw|EYy=Ly3<Ipwi=2yp-$v>HM%nfb!R*Dyr
zgxkngVNVvv*WLo9D(He`3aqb&&47_lA<6cpy?iAm_}yAm(9V%}Hy&o>D1;z|SU`(}
zjGs%An>rzez-uMt-l9xnlJ@`R-^z0jVAX{=OwGXFg}9B>zhG=5m!DN09o-FcVAK3U
zTQ4a!u3C~(ALRh;7imKz5hHkqNWj`}&%SF-OYLXD&xS_OC6_PnzA=9y@nQDdGeI&m
zHM!_K5LRHF77(gm;@Nf>uDE=cdJe)vQM0Yu7Cs2kf`GZe<_H0>z~#H*4mR5N2OSw9
z--bzzYx{l?{CY_eY0cLDl@D0arvyRmLb~{1wblZ|lLpvaA(d;l=o9~7UZbs437Yz$
zh;R}e1qFssILLEJV9JV(rkaB_+q?K94FoM?CLBFD22-0ai*t$Y!1}(?1qb$n8%$yk
zm2@6PtXOJ<OKVJxxlFJ%%F`|#OC*KRjs|q2<<S3rVj*Z=c&>D9;o1ww8kb270jc>m
zjI~uXfj!V^564Z{qd$9dijEr22`5Moy1{Eg?IK03Ib0tS6HHSQ+z~8ABX+na*j*lI
z*l}rMQi|_4^PstvC@Wr$xtt3;$;z_4*IHeUt$}y6(OPn2CAnGYv5l#$H}bvOaa6o2
zpC+6Xl;{UPiP1S>e@vr9j$MW@0AxS_0)~8yV=bq!(pP%D9hAM5b|K{h(G2@l@gB<P
z^BJkZXP1iy=uRL5R@A^Ef%3o;T<|+o;+R3|zXkZne^TRwkZZ(#SoNUVy&2ir3R3au
zlnc}9`VUYbJLBIidR3!AC=V~(PD_PZn-MgB7|lW53kXk<F>*KN{y-oq)iD5n8Q3UN
zV*pYB>Lnusvmqwt)|&76ey~VaEh_%Y^!X9vyblxSi{?QF9Me$XZm~0J5QR^Xj}=}t
z@qCw<173H$Bp~tq>wWXafpo$g>p+RM>xi$EaCZ1E6w+a<NR3=iN6EqqWZ`Mr{;q+(
zDJBQKyFtl$S#8_FT#PCVN-`0|Ss+A>+cN<4%C(qCtlRsm?*}UU7cAm~z7jxOI`Nuc
z&sYd9(D0@B?n)wONcxRb)JeH_M=}R9XXYecO!N6F#cI3cCt&ZQqMWj)p~##~#2OS8
zBwkFNFAoiN_vX8tbKBs{q#(P!9IpD2C#F)A55r>P-nsuRX;W3Rw+4eTAS(ID@TIrY
zfDXgWgQi%3t(3>S1VF7*Dm;HT>|WN8R8#m2PowcCd3laubFZM$$u)so!S|))d6cL+
z(&)K<qx;~ZCU6XLy^Gz;C^~H<d+`vE%dexet|2uZoAk2NIHv``+l(PzGJ6+N0f@x?
zjG5dz#u2}()_163BHEx49XPWdQP232vTtjB4D;L7!S(b&jYpFR(Cu=r!r1p-p$5(B
z$^z#ZgRA1)qH9Gylr9z#%5X-nTW|DNmmlS<x0U+U(e~sc3UaO8)5_AnJGhU+6jeU|
zv!wJGVT{#PjIJQ!%-Wn=Pg;3XjN{dK5ZZ|#+!u`uLOD`ISomR>v$^@W`;768%vD1R
z(+HD<Xi`foqpqKnh@A|vJYu)wPDhgHm}rV1mv@GbK%48#(eB)TRi4^b>jE``5Wl%d
z9C-yeS<aHYn1ua{o^%FnhV^jxr76O0%?P_R&3utw#gza?Ln74aKpe$jO{5+QNS}$h
z!$1y(0h4y3l)VvJUbbR;aC&>v%^Kqr2d*#sK-$3`<UvoS=-x0o94mUeDIN<`b55Cg
zAkPKVj!wL_aM2#+@d20zkEqj&+LZnK5|T{O43!S|uvXA{g}+#_-z>e_PYsC%RaOuG
zRG`_1)YVwa`8Oj0O{JF~l6t06*Fp|txDAVeQ}%^0qnSN+4Z%gywdwo{xs@`)PpA=n
zNJpRg<!UWN3=kC>id}CQCjnreqs!p5e)gg5?fO=LfLdR|^S23whKEtryd5e{JSrBC
z9)DW4WHV%<8zDlZr#Yg!&z`GjA0@W7F+AB2%M9$nZPw6bJSb=?<4HlwLK~)mv6E_R
z174ODmJL0;leK;#hc!#MM3af~BJcls9%?EWb*!4o5-Z%<CO0G;+-BVGd(9Z;P<t4t
zaMmAnT&h9TG?;$=@%<3-qOz+10ly!eMAzOSIm1$a;!W#CBjRzrXgf&sc-{PmC>ZUv
zGzQ9u{rxfKp@;duog|0#W{7*&*8Di^cyk{}2h*>Z(6mW>OR&t}oG+NLnp24Ib5WDf
zZBKpoNudTpril&+I31T-@>%G7hq^=%R$q&$d&+O8!mC>REW(vh`SS)K@qxbd5(!?$
zW*JW?goQYZ=HB)R*p<Ek34s0QfIsW|O|r+Y2WJLD3(B1iiObd2=?H}!`u&7L)YV*K
zA!J&gaI{s2Q~n^vgUf7j;!SH*7c6a=y?{n_1&9;~FFO*Z2--&lK`=`n+D((O+qPqT
z@c^W-9K3R_y`<T9&#pwIRT{Ev=@>X;-G?%UABWirQkvn7q+k{MypqeYGs%R5YS8oL
zeUQK7G)<ut(IK&Tlk(JM(wl-r8&KK`{8Um5u@-^iL~(=7cKcAR25A!Ii9~__ro1U`
zY%K(vL?>8R^;LmMX(&|PVmq1_;>I~4$+bK#XkS-&CZ^{)L4Y+QowuFpH7CoIlNTh2
z8{~f)t8R#;jy5m|jU<n)i0{K%ro(wQ@WLtT4h6293Hjof80UVB00)eZ8|%Fd%Bgf_
z<<>@G6zu~QKW+;Qs|p~;61t9~tswl+6Te9m@xSx0Wz}VFD?NHELxJU@mtTdH?j0cl
zzG)g^e1V+`c{OwkEhOz9XMp&SxHgNcbV#rI&bBZ;bxigdTbFT~u`yC0ZC+I4;7<Oa
zgX*wrcQntHB|6}U6|1=&%()Q$(A0h-fny=I^`N6j&^`{3Au)^_(W9jr%L0M5{E8P6
zNN{x~lc3F_+K00Hp5R4c*k;x|Gm6M|59F|EP`zPwc<rYWoGAy?>vn!5yGB9weGd|_
zGTBc3Q`#m=^IyDT_)p}eeq;qsX^h2p1SBFGwum@b9O&#VNRCt=3vtG6c<r0pv1Dkh
zM2wKXwDc54!Qr`_ox1(KZ3NB9d`tu|*!<EOS!)vbUEE~Vyg16}GuR5QOllw)69AY4
zkwyC_)#BAHNr;5xeTe`$MYu6<OKX$s!!*}q7EEef<bF{(DQ(Tw*Fy~c2j^7;NGe`q
z(Cl}_VJJmFB$%@uA^VM-=N9QKO03HODVGVtXpr~#wu6#8PvEojjH2&_!R1uqBk}Aa
zCW8}2Br))P*$Q9?vWwuQ<3O#5KXMydOeM?~Xdv^4Y}6BF?g7G2NY@1w<+x_hCV%I-
zEV4oHnIyF~X6J8kFM^ZI#J@#^%d+~dib21oO}|g-U3=oJqM$DW!Kbv=7&h!Lv)5Po
z>@7J!GxVgLGu}H0gD^1*tV>Z@|H=*YAKN5?n=99Q;b%NE<=lawj{CbNmbpC^VqH!v
z>k!tiT&5)n)mpRdvahApq0XcAhuAB$Z9{_N*f2?T5En?tK=tG{bEwV_KsWq!K!@FP
z%u9Bt$|t@#hJ7QT7HD^)F}wwo`V2${bU<NQi-qNAjWX%4Ac<>FD^b8_@nSA2AHUO6
z1Wg)jm6L(*_%$V8+VVDS%c<FT^Z9tGMk??Uv80Vj&UyY1yZgOs9baVCN9M0yS<1Ix
z!igd9DoD{%13z5qX^>(Bbgu*oG6>mOrj3_Q2yv&!5#YzWH1hGU_H}6u-l)JQF>hC;
zvKMU1^RpPxC_B-zIVrcye`L{#jX_?Q{mgK{2+7<)fD$&uqh*R8P8n`%5zHk<%(2WX
zo7vP<4~BqZx^Z|zbc>RRNwC*79WlP=SE?4}sW!n;GzMH+03!a}>(&KxPNmXj+7Sv$
z2(LLoXa5K^dEkMJ%`3RE9Qdkk06jfhDK=-4?`;>LQl1{QJGCplslHIuu6%gK8*=az
z0s!j7ed22-Mqu<%m+p_4Say|N7#PP0T5!q(|3Dm)xy$s>Al4jSU+6Z4agRo2R{1#%
z3Zeqswqg*9@t!Y*lZU>&W<=TopgDL*WDi7|Q3itF=3ZVaX?Co_Q?cfjEfdyZv1GvP
zSZeDs;h31k)KQ|<77*W<p({K>#x0F_k$Rsl=O9dQ?0Lu9av$cy<iLzrxxQ*b{RlV!
z#%+iiVZ0cq@0g~|_}|o(kLx}&!?UoW2{?Exx*WEJiA&eq^%PR#!M2|ZyL{^Uds9y8
ze_9FFWY+lF)bLCARNiDk0d)TR?~&lq;CEvOgGD%2S~Es(e!{4k@bt9@1<l!9bnW5Q
zXT*$wKBbf2wRoI>289yyMfm0uhk*Ifcs`v1Y2+ej7CDx8b^OTYkJKxnD&f`jlP;+&
z<EziW7G5~81bo2bLGBDJHkw&XYX3_`zpsOw?m_f7=ml`bPH`xhEDHh{6{SE5B-?24
zia?akcXhf9%Gi4}^V7dJ1RKsPrSZ+T*YXQ*8Ba52db0d|rBOZN<4Rdy(fx4<_bdlU
zpMa2&lfB%8*sT*1xa13OXfhPdJF75#{~`!#H<0XYRt4y|K)K^Dt~Q+iY2&A(NC6_u
zAOS5nHvcb_tVB9#LwbG=^d{SXn1u4;)<+7)c3U`!-@<YksJ<)N2F1Hh89UFN63Z5e
z$YWEM!im>#?sn&h5nMIp?H<dq$62S&tC~`nZC!c2Ox~B>4wCi$<hH|~#pMCG4|o(}
zDY6Qam=mwBV}bgFXk1dbK--ndm@crik_EE9z^U^%%BAWz>}#DDi1a#WV@tTU0|aRR
z9DRqrHE7Sg`Tlu8d8(qLf!V;j2hyZI(`}&bTkG4*Z%p~H0$ZR^yRG+DJ$rh4hBD~y
z<`QR+(?chfl@Z2{KO0@3%+W#zESGG4`Vt9C_i0lID^N!Z0pIR|go>FwoUs?~AwwNI
zNg^dtn*l3ywtKJ8-;i}Vs>Yn9PrLHw-alWIan@0G*v&#7YOk{gDelBVFv0l~PnjJ9
zz;!o02_rz~Y{o2!1{;KYOwZa-=yHXJVdFkbH474xb#`}uAL5DB)*`w}|9^UCEZezN
zqAEjH!_@}0kapa9UqbeY)-$+KIy6`+ruXT$ozoFmf7D|2t1rSgm~hS%oa?FTg_L*6
zs=5F+K*_%!bHz3<2V;U*obDX1a<+J;BM|1`i6qk6o?#$&BGLmvLB?B{`+}~_q!a#Y
z5@z?gr7`S|qtx_BMwJe2;L>j}5*FU{RNM@iMX*v3ksxJ_RYC27FkQ>9&kd8vviIaZ
z_+6<B3l*5^L%0T`QtC7b54G~W$e^T5!R;+;fW#RW&1cs3h&!8RAIlDo(3E}HoakC-
z&(JJtM0~Zijg8X`htdU9z4!JL63FWe;Sqvl0KCaHpCNV>Esk~K6JprB3e4v-A6j<#
z$9v(P@A?Q)$}|Kb+Dk>y_(*+hmAw|9mU~<cWZimaV?yR6is>^$|D;ZNk=QlC6LG!I
z9*_u&kDS3HKcq6eI6joJzLMj>e8a+<e^a?zOaXvex-twtxQ(O2_U0Bx^R2IYRa@BN
zMqp_!x^>tn(MD1U*$_i``@ctO+)BUtD291|B>;&>&K8k;@!=TyU#H6bXAibfr`m@8
zQ5O>8Vy9KOczp{+Nw@ZU2lJI1t<Sr3x6B1EIEOu4)W_?M&hHna58zeH@TC{J=A7)j
zMvzH7)_ZN~u{&7Y2Ygy!me)<Jqqo4`P-YT{=Vq-7{MvZAT5t}irTAV3n+NY!Ted_7
zIwS$~X1Qyf412PyFmL;mE$f~9>2wWp{z52TdRP;h(kg|&2d@@Bl%-iO!2y*!r&2es
z87c~Yz7GjY$X&QT`|94@tmw(51F(Z;B;HN4jO(r>F1F3??*-ciaC5fMnC|CBw&)w3
zR_v@mu9xgeNgA&7V%C5)Ij;`lk#=W(L{vQ%0*$p5gVzB%0o=Fy-TRXd-q^Iq^LmYr
zlK@3(cj4lj-y`NxH+PKb^tFBP+w%k)MK?JNy%a7^xY<Omi=)F{<$~_^ud1K^zjc6#
zoq{lb1&~Vr(0&tj@$%QTCv~W^<8vH?@}-J6kih4?0el3JKmc@r6-Y2+??)ef^p>?}
z^ITu3bh9Rm^vUa#1coZ^c$X6i^>_7~t+Fa+Y}Y1oc(F*L_O8(DxW`ueC&aR_tGaGd
z&~YkrU?@-bx56-;_U?ts8Kxsh-C8_zYoU~z`x(Ph{c`!jFVbwvo7445mH;7FSqQM8
zCf&e4uj*0^vnRv@^KhU0Y*7rQ8fKGaXi)@N+35035lAKhm5i|;WvV62;g5tEa=gy>
z-k=~r6Q#w*16o6uYU+7p-CWgodZz|c<BxEQ*&lRG!o@vBHsoor5Z5&U;WiVDnlYf7
zH_s4?+*#+2qJJx8nq4?E@}I+CG_%QgysSfGmqZqna#{vj>fP&Ll!7@$asbM%dlX_o
z;mkQ$4aJT`WRR8tR*IFSkXjc(0=?CV&)|FINS)!%qtnJTL`&#@rb8oE&ZsBbiR$=+
z;b&o;z$jg5m_)<V&XeXZSk2!is5O9Vi*@^g3Ut|>tMR`$7#?xtPOz$2B(lg^a6n#3
z$Grv*m9}2-v5LhAsy+1fzH<p*hWtO6P-wViHvRAbC21R0Z7U>yxNZ$S!EnH}bDv=j
zU%i+ad4663dp)qTM@ls6=5EjV1X5<}8(MKnQ4@_zI~TK|0dhHvMb{ulQ2k8?W`(8!
z)y`SR-QO4ZQ_@0GFvBy!1WX0G?0SwbDAb&O2t;%94;~dzc7vQsu2q4UNlXYiYwxBd
zv$Si35KkrS<EqCtK!>;ynGZ>zs-5MoW`&erG^)MRYZS#O_dmj(*{C_XoYFlLbJ(g=
z+f2PA62D$_O&&-mH9lda@-tY+-v`LjHBXwd7BQ)zlTXbzlsYeLirT9<hsCrIa5h=$
zx-;@uI-Xk=w>JNjWnO{k65y{~OWqP?*M%6YlVwlZmSg>mk2h_0k!277wz&;R)Ob@N
zUq@>8*^oc?s`v?n?O8>**}>M-9I}P<j8nzrOpFiu0%c13*=ERM*bvFx^&X!aFm*uM
z4Rudy)GTu~+0p{Fg$}B|0oB)Jo!~Y^)!zF4JB(;&GMJbXWjVQK$lcFpBL-WmDr9NX
zU2tTM?kwEU;C!l(vJrb8uT8}b4HD7mE&NYdb@ZlbX2;gjTu^n>!<?rA+vr1`PSCSD
z$=J%<irYT0#q*IV3{dU9jOj;|U$C~!U3OBfX*EV*{op&zY?c@W+?r{;sJ5@L$Ty3|
zw<ScOlyqnKQD=nHqrqC*LXH5L#5~*I0l(4;Jqm5CAqe5#{z3-f=xWt)d?oGt?*X3N
z-X#RWl((VEe{B)*^e%EV#cpPgD5%lFxd9+xz}idq&#$)^B(ir=Fo}%`7y%98&T%aW
z3d{BNi2$yiVK~#V2J(<8^9m8Vq?mYd-`OpFX7VudPUVjZ1>sO_pewD%v0W2^{}9@u
z3GWp9u^;Y&vGr^=671D+-F5O#L@2zw{MI^GLHo3tUsAxvQ00J4dgZA-_1O`*<dQ`W
z@ifYw;WJwh)_`(-(o}MF;J}CB8hO!(mTn%V>Od`3Kva$v;8&6T9{pg}(2LXF_GRK+
zH3|wRi&1s$trLcJ@hF|9b5ZX)eV*2TLj=o!f>g={@##|f-1}b6jNTtfoQ9ku)(VH^
zNqsg;lGu=eSyV=Tn_wK$tTou7pH`4Q#M=TH!$aBglMKafE8iQAin;kYKCqfU$n-<u
zK7ccdGJ&DAZdKGHoHVcQ7smtCn@eR{633A%0yw#4Ylv+~Ewar;I1RoFy39iWIdoBG
zwo$4NF|jhdC*ugRxiJ_dvipPumoZb>H*_a%h@5TRu|HKIzLo9Lnw5BVMNM1UkVwD)
z0(Icb=>P@bUdJ{{-lDpg8HKEDJ+8+zqtMnR3kQRf>lVgj;0spm2DVWC@l*~5nA5gk
z#jmolJ$cro{_=z$i%9D&6E!B7<B&5)ra$_Y@J)skRD)Gggc4orXw&y)x?@%bh?8fb
z*biU4){V1FD5io+;oUC`KEuIb@L~s`vUxiXfKbRS=QP-6)~`FBmr)^kacv;+%~O93
zuv0I@!Dq#j6WrtGk;XM>gmd|rl2n~V1d__K*l4)f#pA4nudFyRyf9yu7!%UFX@s^j
zS-%hbofy{hBN;6M;C;fq_f{U6l!ky3aFHakGACTRo%3y2{|(Vz5b(uSqHJkh+_*d8
zoc9W?SexyX>TnDN3vWDbd{4!GTo8Dffx8u3MNW@@vNwG0IS26v)H}nXA1BGVuks9{
ze2ftkkHbBzf5{1q=PzxiUXo?W+Fk`}pYC&CcHS4tVRhCe2t%$;rNl<MZGAzw>|?Li
z^yO_)vxhbkI<{9mndB`+(;~+-Ge@aw|AFmCXKO-A)({N?s321-@J0YWVzu=XEZqj4
zND(tk+CTLjdAWV|zo!IB6)Geyk!=EhENw5@bSc{kD<6h63RUeRAW}P;JQ}^qAb}3k
z5;@vIoILs?>CGlqDZm$N2!pTSPy?Lko@2%7U=I`sNIplT$xzPpI(UOcC|KQMVbG^f
zr8{PZfSyD-edA2$Jczmkj-vL+$C2RFXUGsh8kvcHC+G}aaQ-R86KVaxbbp2W<Db0M
zlXfnM2H@C54ohj@o0Yk40dv>h-|;8d<yI5lY=L;hbmF@0oUP<&hwZ9Y><doA-u4?L
zFs@$JzrWQORf(&@qO(-4LUBPKYTId@Gz%&<24#kZ4Ho2ud(_R{!N!1@j{Xl%iHr<F
zZ22V85fbliZiQ97i)*0>?I=^S7194o)+WBsjR(WGM$R|l(tE=+g`T3?wV>IIj8B&W
zk!yoDrmv&&1$zQ^lj?<ix-%p-ZW_`~zc0NV=5;5nL3L{wI+`3{;TBL}MDb(k3%y!E
zUt<c!$3Y;yOazp_3gq|o-b^;>gY?=)Mzqlo8_(Ei2y1=AIEdk_cXzNBV!DVoBH)YQ
zCFO6Xc7M!h(4zLfU;QE323~1m9)SBeD6$-xYo|z}>jo~Do9IFkltCNjQ=p$0)tCmR
z@k95TA9BlqpzB+mSzH$9P8dm8%Z$ubI)$DwRfbxw5z1bnD$q(=GgUPN7UJmSX=U-E
zt$N|>n;L&XCLjgI)I%HODtCJ10tCj((Q9avC;Zg{L9iT31ez>glf_rNsX9N=(ygRv
zEF%9|!V<d$Fn7aq&SWyl25B{KxR@kkIT97HzOHd?X6qWyjw;gTJ~+P}a&U82Bg}ds
z>OdgK!kXpEGEP}R1oD+tyc$Jlmf;*pGq>)8Va<tUk+9%`O<-;Y=>AeYx%P{6hI^RJ
z-h*1zV*}`0bijh!6*A`HQWWaE0%~Jq{=DeR$<&wWU3D@#L-epgb^4CH=qEy?Bul34
z#Y{BMqu<Xqv&<vJ&}zP*i2`dQ?Wv3m3Z6hX=KxQK$7F|gF$eemep%}}1qIU7-u2<g
z7A*<07lAgKl^2NWVYGk4U*_-LQ7kPSigDw03(0JeQL)#mLj3m8x^6F$52POhfY!??
z{SLDbFY;&(7pb*Ng^Y0=A`I#S%2eTYFz7ZPudoC!kQ%GSLuQ!M11ULQ*9Ws(;9d0$
zoB+}Wi>`Z$KjDiS?*~_w-7RuG`L3KRDh)<IcbdHR!TI3Rtt`6LnDi;I%RR(C%-agD
zrPh*wecc56IL7z~SS0cA5e-1f5ZiufGHl$J&faSEdiD$rHp580+bZ0bhJEIfRvDG}
z+s+IWwYU3JeVBUB<HWKiE-15c9dg8+6P%G3jQQdv=Gi#_BkYN#bbR)6sZEGN*}Ny*
zACxD_d*4%Uu*0mmcjBY|Q}T1spQ)H#@p11EH;%KLoxm&+ov6n$HgB8=oNF=tcCDwJ
zv(=wDmIj7^!*(k>00G9J``)ahBUe8VmyC0B&jKO-Ie?a_Sefy76J*QyarHQ}_7vo2
z$#a{>B@Usv@hCZwtmqDiHgzjxVlwRYE_1Gr^YV;%3~;aeY9${VZwO8vXH*Tj!n1VY
z$sZ>8k-{~Z{Kn}tnjQuxVbsN1Ch{-l#Z)gn_x+OUBj#z3GV1y&WF9(KLkYJZzwg?*
zZ!B#(u+0`TG0CWeAT>W~f99RPyZX+?SEzBh0=Yt?po}d{Qeu?71l)+i2K!~O!Wb4E
zsEI}Tm@&5#Q#Pq#PDq~#t+yl%<k$qYX@7UWeroLchPRECXjn=N;DX@CX&S!5d;K>m
zmp`P85(L<Rv0u+XNRBr`VFMJg;$^u9+09hdn<@*us?lYHYa#u1$`vSZ_~2aNue5*&
zoZ!F#&(S9en0nnPQMy0J!<stLU5wrX9MW;MzmkI*p#gqDKfMKvN}VT@tx}z=mrDu+
zq8!V0l-o&aAcPA25@80+=Y?Bwl&j*K3s}5_xw*IT8ep~+(Ul91<)6X_1ecMY(t}x>
zB(IWs{dRa5T8eYyA4xVDT{S7CQ;$HuyHr;Jl`1%F8i4~h57LJtAv~;+1WJgEem?O-
z-@IvBzofXkU+vIWF2b->H!YxI-ijrb@Bu##|4Gl73s_kUhmT6JEVQe+r}DMAK$Oin
zdCna7L<L#(@LiA(^HFa)+NPtKaA&=cG6R`vi$`FEeno%;&7nJ(hQ*V}zw@^>CHO(6
znl(<DwKs`o5JoURA@q(*H|hm-;zSr!R$EodK&ctP4XtJQ@vJ3H$q<6xXQ4j8726=H
z^jQv|BFOcbhA#UUuCB-Tz}Ucs?Ns71PrfHBwz1GHy#MsT2Jxb#hFwyw(PnJ$d;bk+
z+Ab2@WVH<)_s+wFl4~9*#`jQ`2@`*txuSuEa<D^j=CT|Owk^1bUF}i2ESruw_>eQu
zFAe4M!X?!q6>a$<q0GKcvGhj~WC?;dY52PX!B^VtvUAHwP5RD%hmG&dj@7~V&YrQB
zUfA-Zn0ds27Bb2Pr}?#4AFj<HaQ;{BdE;~*T@f7q&mT&rxb}ti9(Jq8mG-rfEmZ61
zq4}H2W}S`al(kU7w3B(rp!G-j9zgFuk1{VhmJYkZWhmr?IB!p=<p1!c<zoK9u&~Vy
zzx4OGFqId~UUE&zy<I39qeWWfo|MQ_*agcGl4%?6z5gTI$*3Fp*&<_;?67Jf?oC2U
z^N{;mK=8?z=UFUfK<UiiGuB6}#!ORxiyLQlL{ZYXjFcq)zcHG!PO=8BK*kSUkzr!-
zvms0gEFpqt&mALx)+6EVtPhCjdD8@$?a>4YMrnf|HcSu>HXsUSkv{cpMBmWsf6mfr
z|C&lG6)oc0Df+<lLK2zA{AfXso|GR`2!xca{u1#nN1bc{k;uM7jPG#DjtUi8hQ?bc
z9BpB};P~;ect(g>vBr`SPg;Dw+ZjywT5P)wzzVHgEpQ&eitDN*rZ&Hc8>zUs#c9Sw
z%L$b2XViqFF}^tLwSC6stW5TegO%Dj5iC8~;zn$h$E@K_wNq4-FwPZknzAkHG3h!@
z<w~wi8JU8RyC(*x65tG@?v%3$yB47zccXs#XXpLSt}2Gcu=d{&M~7Ks@&3NO$bM}d
zO3Nj_jyfdc7&+Cg%L)cF(P@T$tJK}9q0g_?y<YeL01RACsQ$rk-HJHq5Soc}>y6p_
z594cLSEyDFn!mVjZM|YyKhQMax0BTtg7iG(CfpJ0i9Cq*dQaPo0001=Bf#os+XeiQ
zu#{Q4RRoKRq!;>>l!D2kD@s|aSJ0(kzq!&(&)MSUf#zM*WXY@fNje?-3Z!ljH}(t?
zcxh&$)iPza2VEL3Wp8-Yk#kEf#%H^jI`sZDS&9+i`y!etc^IZKYAI`X*ZvQ+&;#gC
zcX4dcclBGskV|wmTnxBPCDywQF7n`=Go7=PnFUB`<PDft9;<Fcdp-CU<z-9Jy@T})
zyhv|(Q#~Z5Wh|-5i+7$%{^AJ|(!`Nw+ooM#D{u266k(_c@&d>o1n8|RT^U(IA7-=G
zrm&J!@-8(=L(QcRqs)>6<bReXf0@`%x!UdMy!P+XP$Cc03eD+Q%lp^jkO0&{H!{GF
zRq#tMH*QC*+XWrfsBIAE<e+SeEokT*(w#Tx^+~XYq>hp|3}JKyj}OO$&3js&G19}@
zGXSuJX>k-wLaHR#^_$Vmg&cDd)SBFT<=lk!vtq&}i0O;fX-%XweC{z7oVp4XCi=|h
zcH9Ny?~$f}NS})&4YZTr8Z-vTsv0qh<)2%t-ejlq6V8z84?Zo4r!+tSwZEbs(^JbB
zSG!B`J01r080~-r!7nm*^FnpuUEI&wDHY;_??nFTe)4WCaecs%WS*I{a!8wSs0OOR
z4(Gp_Kf#yLOUyEvx%1h?0jhhem5uwv#FY^QIN%#qa8%GAp%(INcq>G*1dlS&dB)lB
z>T)k{*)#x2KSBl&9E#svDxDZGNc!ORo0m;7S4L2<OnN<7!<=SA`He+Sg;xq;YPG~5
zAyBF12M1~RDo^xx3s4PkUgWfCE*nB7v+2p4CRe<iMkf84NA=nN*}Gr`g*@W;{nYVO
z-Cwzcg<~(F?3{<JymbQXH_$Sd&DS=jAgqWe6Fye0nzNoL+&jNq1lyxYqRDZ5Akh#Q
z@kKT<RB2C{t%ukSp7_$oK)i)iR>vL&ggWg^n28s-WNQStAS$Y?UcLw3&0qu2X?0Ew
z0E&6iRk&YYD4Sy>^)ImCDm+m?>F-B^chlP_A<@fELfll+GJnU5?e+wW$p#LLUh~t-
znzn<q&kel=1gDSe-{=e|ud<e($PiaYv4&@U>Sh-ZhF7{=9`&G?7XGS_&;I?eJS5Vj
z@UK5F3{|;7Puea6qX^|FK#y_+v%7hF)>>O@dhyQ`<#P;i&`$+5JNqZ+`qZK}tjBQ`
z0#Npop&AqKGBC0Fvydlh*6O<(HcM_QNLg(*`zfL%yFmqyaAabfZGk0PPeqiZs#3vg
zkrIe_byu>iza`d%b2~%MtV)bWGG-Y~+o|dRjR#efkOCyEhx6y_822JKOO1)KnbaJ4
zu(eGC`Wj$Dv%5Z<If8Mp`o%@>cSEJvj+e)nE};zR5a<}v00C&%@wF6yA(vPc;Wc@y
z+1`q=I`#kst8(6X5kINj@nDg5R(4lYEcRj1#stPy3}#U)1JLF4f1E6hFwgo;@c~;z
z4QlLh8VqCC8p4z~ju-T<PjnooL^g|&(#2d9_*`+|ZsFoM!0$Zr30E2o??Y3&={~GM
z3PD^A!f){$LcNmjVM?5;D`&CSpk>y5EvXZ-{9#yHS@a*Q7+3RCn&bEWzKaFDO*C$Q
z34wI8orci@=K}zMpfZglArvE^#6P9Ex#l`To}md+!k(?kcx$GJ@$9TVaD#B3O4P<%
z18&jmi0c#}`M9oAo;u0*3N4b=b|#0Do_&;b^)jF)9-+Wm)ojK{5N@Fqrqr%J*|IbV
zSzOV<&;A{(dE?*-Vd)Jg`OCukejQ&K;G=LT26)MqRf}b2X6Yf~<Cq@~XHnt1Ng{RY
z^{vro>jJ(gMU-y6i*6YkVM;zH9%lJ-x`Q=~_$obb@bE8OP}Y=-O}N2k4Py&<kso`2
zmwd*JbN5|SN{RQt{7hfn(JZ@bYyFbeSm_Car_HATP~5(|A0YKQN8HIsfi8ddnqj0d
zg2Fk(4yPV;cDGx~si~t>To8=wA&Z0w;Ij6?!a?wFimj^NGH2b9K=H{y=d0q1iBE#S
z1XhC?aCj8>?%+$~&QpD3`Lr2iFaJP1uF*1zSipz+Sl+{+$Ii^*_Gw~Pd(<rbKVOVc
z1+F_PSFs@u+g{Xm<%hhEE#q5@g-bv~oG>QkSm}=d5prMrZ)Y@;q7l3CYzmr+q>!c@
z;<FKsnJh`x{LG+%&-*X<gv)GGY@XfD@s_Fd!b?{Q{n@^0?*evM7&2!oi~pX|olyS?
zm}TRLL+R`i61~Goxj>wA+laXm4xq|te+gbq;`8pMRfNd>jW}Iyl$05)S}+~9YLvLn
z1-#0iENS*tk&9Uu=CXuCnA%^V6uT|5t0r6Hb)Ch`4GyY8*s}PHqKLBpt5TgO;sr3x
zEe{KIsdFTLC6ncgpz87}tK6ZFkvOn^j*QRWm|HK?Qd4GXm&<-)R$99>7vB~0n?SBi
z$=|p{HM<@c!r(d2lkX2TKTX?=bdvq|<k6uWNt=<%64mq)P-y-4j$qqv>fZL`R%tMI
zBYzp70Kl0Sb13|c+nxUOnknuK*AjZbR+Y(Oy!`2w)zR%ZCib3LdE>F;5Yl*EQ-_Ot
zumKp{Q`y}7G>!d&F4H}>mrFRX)3<%_#+i7EPZj1LW3s~O+5VAbY2ejkyGh`d<}?$N
z?;k`FiB+Zjy0snWpF-1<N9@@HPtY#D8M|Qh)qoXI-8T?jWpj(vnA~63VQx6|YrSS2
zy`Xj$<&N3BMh50xP2NvSGB~zbcMxeKcl9Xpa6P_2?<C)BWM^3Zxi6iB6QoxcnmU9d
z+)*f9>Pm@yT#r!{jrO0w5Z=w`uW1)b@k2D___cs9^rolwLt`{|X2)0yy%TA6Peqv@
zwgu{XU*Q;adHCUXh+j3v+OSW4^m*=hH4-sFSdvVfq_^H{5Xvwj$c!LQcC9lhw)M0a
zG-?Po8+%KBoIccLiaqV`@<(gt*O)v|x4>6E9^>@W&aMPJ%Lmn$uxg?6Vc#CB)~W;_
zj{R?$+z-A(UoUD#6jrnt?ut}U^)+5%-ASy^y<mQWc2p%<DA*9tdL2vst>HR$9t_Ch
zHkvsSOKfmW@UCM$5TE0j|L4Y(w-s4IZgw2ovcvKM`9+01rHF{)*6tv!bW;yyl8I@%
z#`6I#wBz%UmBnp$nsq=aAes0jCZPz)9u%>)*PS(wA}d!P(2UV)uVopq0E)^66m9e<
zlcLe3hl;Wa@^Ah6>2Jtxv6|F+1@%b_kzP<GE6+7OV|}&-Ce%veMA!jGi|^hf2mk<I
zD<Kx7rDy#3fqw<W#wbm!eIn6{1eRmX3Zhf<j?<F(*y-G-q{}LUmPJlsf}|w}@B}`Y
zTj(n?FeSVtk^*9`Rdn(4;F0B5x&g|P5D8tQ0%6>_2IDD~34p9}Hjyn>AJ``uwK6Kj
z2!%V%o{-MUKOGfDU>PPUB-lq+OYSpSyGa`OCmws~Hej=@ONg>J9=YdUSI`2rL8h{W
zJECP(yo8EITg3$o{;#j7$Di}tnEAj_flh!h#ct!>u#LBg(R$gZB7%C_50|&QJ0ZSz
zZs?|(DQCeIE6?QbAhnW@KKQ&`T|t^IogMjn4zIa0?Q!9DlBE>#{{Ox;q1;DZ2eVg#
zcd^-BN4fOulIcZdnvmULoZ}>1JZe#1>4?<(Z;d~2eD)nxb)eajU@rRPt_AnSIsuUn
z0E6p{ddFdxB2AV2gi6<PfjM;+zAr)e6F9w^Hvz1MgX)MtHr+H5Pl>XGz36fjM!3kH
zfPGqNO9^_BMQgh@j-<*|xJj+~zH{8Nn2Gk^GZJJ_Mm2ohZfos5k>zN4lHjB4_I|z@
zHuS5zhqVrmq0|-GkbzVNyGw=#01hZT^C^e8UuY5j-t*Y{m*|$MB6{A~AG4GX9)Ln<
zz*u^)1kg*p$7fNq3}&HA*bD|^v*B0J;EP!nWW!!i009-6yDq%67ip{_68<=uRAMnJ
zvTys+K@%{;4XG<_zJj2lHyst1|A7Y2#L3ipHewvLcg_>i`EW<3NS|SNj*PUG{eXt<
zY6fb<$|*08^or<>vqRNYmeI@{9WX^5`P%$q^3EY>J3ya7*UE7Cy|M9}sC+J4Xg4TT
z((kH$Yek?wKpJhjxo+g_N(?B^82~*Vo$srsVMILqJgFUTI)qcYe7QN!K_uLi6{&u@
z&I~LoFg1)lA64M|M;eI~p`*{EOB1eYD+G;+>H91mtWKXJTzQgFfG=39s4E>bAecLf
zb0Uh9jRIn{HaZVgqeFhU+h7(ck{Z32Q##cmdiY@*DKR3W7DqNFpU#2UK3)a-H4P*?
z2vGdNk9kYBaMYu4%z}oI#k0GVFwC!ob^hRV#xnAY9Y#x7f;~*dCchr|%Dq+$nI&jR
zUiJ?%oCysZ`?p)V!g+TQsZwb%R#}BR<5bUB(G*0Ba`F?;m9c<xBk&sQ>NcUqf(wX!
zsf)w+<re?O71BTrB!UzQA*!OzM>Y&csk?Bms*4R)rXH#DEDX$qwg^G&r=Z3As^h-J
zUAV%=jo(zWA?sw?_LFchwgxQoo1d&`Ux-MeMP%ZyCuA#j)ZVS@M&jasVPs5OC9vZY
zgrrHJ6Xh!<6&aOTL<X}jzfr)T#en1y_!?-I8y$;pN+c=X&!t?INa85RMkpvG*C3%A
z+nxDo9FLo8O{5$Ak){IA5+GQIXb{aK7f6sDBMoIUurpwAG~5mUd+D;C0{k{4I`8Yt
z&BBf>{kUBGz!*Ye9fN))`QEX%SsBI$T@F@_D$}R4@!_xQ%5Uhl6q?mPUj2<YK6yrn
z8}S=I)L1OxWVR3^9)zpw=t-+A1@ie!MztaxREU+%KEuOP&f>St?k@9(2x;;Q@33<x
z!{WEB95m9;Yv<G9M1x6X?WX~u)|qH}e`P<dr^89>5EftCo@z!IZQFJ49zm#_zMvvs
z4|%4L@*)}8cf{J8pNA3tm#ARg0BAp!^=&dLWjLfJbNFdodakR#QuU?$Eg)r5YQ1t|
zsxw=S*Ue+M)f*-n9WImkZ29W2Iw^hsB4Fhf48iU6eBquHvn}^gC}%C7E=|8vOGK+I
ztf%k)UJep}%-Byt`sBY2uh}gL(8AioVbw_;!J}0|{KULPjiGc$GlZTtxzmtbA*h{6
z@MxE&OFUY=YU{Ft(%Gd&;v~f}Yua|YhP)c(LL{9cjm9M;1Ne#ccfyksf^5u@m+h?;
zB(3D;S&WPp{t})~gF%1>mdXM;^HjB{tauA(UzN3`H8?WI{A@`f1)KV?cwRslJ*A-!
zm0(W?FM=)6+YR?6V4mC?4wp?q_(O(7KGr}XUELZXb3Y&9gLSw7XLxLn&=V`=7<#JA
zh;h-)uKl7e%Or-v%}rMTT*WapXV*P>J81s%zvbADwegO!=!gvryrrU$Dgy6sPP3U>
zG70<_f^4bomkH-6sEIkrC8i}>O@E7rnZOF5B^J}2rzYgS#%hwmW(WnQ1<7ZBg*wHd
zsIr7B>gn{9N^I7Em;S|_(ZjVd@bXw4K#2&DTdPA!*bAU_InqD^z{WPIBd<l|)P#?p
z_4uK*<K6m@b%WffO2k}Cg(_1mis9LV0UD1r*rV0$iSs|APF}5I!|NCa25!`bo{<=i
zy##kIJ#_oksZS`1pQ{)Rz(z*{Akvjp!~kcw86K#k1zTS1YgTQP*neOe8pnSTRq8~^
zynXrjPz(fRVOueo9oY}5*CiU_<x#gO=+fa@fxQM07@Q8voT`BnP(5^L&IPS%Fzc$q
zf^wMWeDp<4!u6AQRh2}tK`u7a$&kFkpu_grPk;ox4zqTFe;clB!4LeJEovNzWAva?
z0T*QI{<T{McV0k73HcR@1X~Jqpt?a1z%Ju*xzO7f)BxBpoxK4eEPZ8SRFvoeh*w_B
zo@uGeo@p=|PP<a!leG9uFfK9`ZCO8$7n7BOEJ?|QG}yT%;Bf&-d4Lh%9f+F{1`<Oc
z`mvqz@U_mpZ6jG2Y+D2rSq}`Oks~fmo0*c<D<gD047>#<lvOz=Y+ez*_)#A+iL~}?
z{TE2R5baBS&XqFH`*>N!y9AiN$y6*4Tqo86oR@rX$kr4eq@`4edjVq+P`oI+4H;kn
z`9aj-nS;m7TG9|ls$Z^rD<}6HErL|3NPN?@w3Q8Ab<NsQ<3yEyL<!y-k+%73z0p=3
zft5oBK^Oqm_;Cub{(udPeS<E{JKKA9=eg7LtI2PT?V*?=1i9^cnT4F~z{Pa*AI^}c
zwgw^GoMx$nq+i)O+q9_>oDwAD1}6AZ<_hH_+}$@UiNR8pq>j$O+w%+Fokj`S5s+02
zAj6w!h2lX`$ZC4Anu7}l<sO?~Ujd#a!a!o_1Q0lJh~i7i8a<k6_Fq02UWO*MZN1PJ
zu58+eCsIsNEL7mW>792v!;-vtJFD)y4mE-RqKX$2U-53HT1Y0~9(GVc(&FxgCQ8tR
z+;u=8!gd~uN`!MBrR*{X9LGWOo#fAr<^VZ!BNOX7XSDgw**G#~j|^x0d-`5!-G$Tn
z)>^5jP0ze#dkI)=XYnzgS9^)B6Dl5aVqrP!%Zr@b;Uq+tJw1ilp9IR#YHT)h1m8(D
zSC})bKPaB@qO`=lB(?cz6#)f^9@+VUZul}WlbcHfQXcx+trSMc+0Tlah>W&1)*45j
z_t0#~Z~l4dhM<#uFWWgYNB3?#>wpTJcwWWy9th-h90FM&mZi1tjDq=T^E72kIG_CT
z=+8DCb84DpZbvi+i_X!`&4TL}N;<mjzw!=%&^!pSYo==+ucW%leCufymEL$wh267W
zJ4#SQj@3&z-lR~KG8pBL5-bDcAChCkqH(DN9fyC?Sihd3X^W*(u_;!ItQP`uCAthn
zbZL!Oy`i|WD1#;TBPnl}(b`eEPWqxeTvn#`0?-af;ZZ}XmjG__au$E4igw@q3z@!s
z<vdO7Wxe3^ob-Y=rf*p&k;gOt6Q{-3F%{ZQ!k4IYmzkPSrI`Im2?y&{z>8lZp_Vt9
zc-~7Wn~awB0Dku+DcgiVw>;cQ!K+K@jnY7d4#c)XEBOMo^adYA+q}{~3D4qOn*nDT
zlpVeZF+a(csCP|97I@5qmO7{p38Ul0)-jirZ=YhU>}o)M6*rsih&50~6_zD89A9g|
z{ZBGA;Pkq5CLKq4&;L3~@E^58TT1}cUs^qS5q+k?(_r9aT0quv+y(lqRIp)N1(xdm
zMnDI~vgPQTJ`tfbH|OO9%@SE+#6oNU1TB2fWSM{uIRf?;wRq96h$2xLHBaKPuP&ob
z>lnvMs2qND{`vUsZw=GCS1%eybu1&$Pq1BM>L$FTy3GkbfEjLeUh#bFf=NgqoAN=F
zR9Bj2g2(x`<CO*R2Aj^?mWgHgtx{}j>~Kh?Xs)MME2=;+7zevUXY^ihJeQk<xiLiu
zXcq<Y@>6OKNE%Kb23xfprAHt(f(l3`UByH7dp{5ezz_+1;uXHH)^e2bF-B8IL?l?N
zFewhb>9H3G62_@R|7wc!?-n(Rguvo<Ml-}Hi|mb0w(CjLW6R;Jg&%JVAg|)0bOncl
z^LmRB&HHN5(I_Qmk!}&5$KgpH;u?w7;|1#ArHX_BH4z4Xv?L$JxL;^GgVst3GH`>Q
zP081y693l^yPA8|y>)GJ2=a<pKO)uRBdc)EfM7Am$A}v+bC-Pf^(DA4rel!VXli&*
zl%Zy4xgSwaycbY$mP_z#LLN3dc_I%k_<kQh`O<}H5EubcXlTR{{_Qs!2j7H=C>Exr
zU-|Tk>Dj@OtMCy0UvJA?VmKoF7bC1o8_oIHn3DJ9U^J;bLYQXz0l?ij-Wi`WJRCf8
zIr%7zjsDJ3$6|@oVc?k*G34)=b=QJiC_v?PdT5R?g`M&-D-TWKEnJ^_FWD*>Mo2Gk
ziI=_RT^rU>2@a~zcBN<WMF>Y}&KaHS1E4!D@s`##8d4xJc49^BC0bK~gaByEbN}>O
zzQ0tO(9Fny&kBo5ikj<CVg4pg{4b=&A#sG;zBjO`k0l||uwD7T8RkdsNNbfLezkfW
zgJRqzVSYy18!jh-_P&c4DHk>*@<T^U6Xj1%_Kig0YLTL?C(XZe{3sX!d)Ba!D3VBa
zP*RPb`;kJ*beE{y#D>-pH+$xAZCZ5W%eVw+(I{RpT#5X}eNtcURzFUdd$t9o5gIgI
zUVs{b#q8pi&V%f-ru(@!*`pLhnt2KfYYrZ2i`L5IxK9kH$MMDF5w-JqOebz!<%Pw3
zs!n#1$UkBu-J6jQ`NJj~MZk-$p5ECO@pIX<6d9)BA9jqMiMn4tn)u}mL>;#uFhT!q
ziCSwZ$pnCR;<XRnmu~cudTV!j=+I=Vcq#k(1dhh8h`x1mg}ca|GT&5C*BRtURfu~m
zmC>l*QzH+tl3Zt$ZNit`IouMQuYL-|^5^#RKS?;v;({in7z+a9Ny+6mK1=uv`sD|d
zs;pU(PsdLh0c5fAFF?E+U6etuqWlq2Gvbyl5R-$nK?n4rA7~DSwgM!`)2VCq^I$hD
zdSB2bsv{);Y9f4d63WmW$5zrv3Af!?y@Df*#Ch5Ekz4&Bo|Kui`$(~#mk5woY0+gg
zG2tO38}Y$JtCLJZ8(}?lPznTTd{C5@WX-J+EbX~Ts7gl&wV<w3r+iL#wAehGyM`E$
zaT(27zAB;@>I{3E_TQ@^k%_EX*y&7sf8dz1M*~Qr^>A!KJd_21I};`Ou-OZ?6jO-i
z@VkhLWjnuL5viib;76Pf(n)stjXx5#{TOUjWO<bw9per<tA~nX(TqHtPV3t;NAg9E
zBLg>}(b`0n^#&dK25mxPvj4z+k`CDvz?AMQ9OHb$ON5v)*HNJTj71_^q`*iA!jQV{
zfBs6ZaNz`F72b1+s47%^eB}*1xi!Oc#8kRx+k)0KXOr!i5L0TgP)GSZ1t@H-p;i9~
z%HRm{%s$^>LO|u2Scmnr|2NDWa*J8sQWY*FFzsjdq6D>mA!1;8kqk!rMdbhyiAyN?
zHIvZuOVkq}05~#&CS8V<AhE)+!@p^K2^yP^wXKMrQP0p$UVg~fo@k&#2$UODi-a}q
z8isbue^NC+kJT2k(uap`W9`lIe>pWKMALEcEgS>3hv#CPR*h<iYIYN<{rYLpzY}D(
zEtVkn`WGrLBXvBu-JWaGezBv%vQ8ySk(mju{WlT%ni^(EUF}9NdYBVRI^BsoL=P}L
zzI9Q+GyKY`Y5Od5pD>=n3mOpGA`d7rnDNSOJ*JR9Un&6mONp<SH`usHH;l_O$W&7Y
z5x_B)Yx|)Tk%%G;wuBo9ww&-QQWo$3`|~%1@rL+!!;9wQ{4_Z-?%V${OIxXrwHG@@
zymoO4qwx?a8nyl@2Hqt$<l+3$bxZ8<cRxrI&(@gJ?l9kQSxvn~Z@b@Yb<CuD@_Ug;
zEsILEwlzkjRe;aJJzOIIKj3c*(}5h+i3@ep(cQ&1mYRg2g(qj7g@g?!3J|!Y)1YOM
z6ZW!p@>8?V&~>)~IjA|ZnR}eq<&r}C_VYJBEv=syFZ-lTo~G=S;y?IS-okiA=91mB
zvClQQSvO9)D2p)nAkz^kmgZ~Ru*~fe(Gh;Uj3Fsi(w#IV-Hmm}_I3|C)jkts@R;eV
zPCI&PR0=yd-F=NNRXN$+xkm+nOvEmzw}1e=?&D(vd4XYo2qs3XUg!gao3q7v_L|nu
z8tQ#s8~L_b8_5SG4HFJ(%NS=z!<k_k^UE=JU&_cF4`#u+e3vGGTm_wbX{c@6!8RF4
zN5J}R@c66)mAT7W4Fox_Ki2m>^_qDH(^&*)W9j(dOsLgnhPFKG&_z1Y)9MR{mavS3
z<ym6N+3gp%tM4qbm}`Grps`koUS`khj70q5v{fI)s-ihnZMB>3(K_ON;n2Vwp}G;a
zBHLL*&8>?yxwUD)#D7+ta*~R^Fa;|={JjrR(W<H)#Jua??fW|#Ot#B~8J)>}Xbk{S
z$^wzAydLK8dBRcWsmAeefL#G1t+?O7%t@$M#Z_`wsn6$TPLT`KnhQ#Y3;EsG;ll;`
zVLy(B@%~hifMd)INmi*0fc+P3FbVr2?#e+dgZ*HvsVueDaC@wv;F*;AGQ4afy~;7p
z!bLgb7r61Cev^w}48Eg}{UF<7zh#eF;niIr9hM}Q2f3uw%MdpUr+XvCDEoU6(CQ`g
z4CjA=Y;7NV6#-MsN%(xze2qNznzR~rn58WOt2C>unWWVgj|z;`X>FZSeF2fLe#j_$
znC`i2B_+mHs(pnsQszCe>OaXBQ3F&sm0-2ncjKtV_c*3`-NV=x_G}VkvV_u_qn0DL
z%oCEgKY=k$DPF}<EcA)X?;W_~YR3`bgBoCp38Son*35^v(rEMj$`|d8B7MgC^b!5s
z81@KVr&glz@hn5j2eA1DN$ut|-dGwMVqRX)waAVHr&PA%<QS~3iq#J|r<xvD`P0CZ
z-{uA<YpA1vzGKfXl9|J`Kc5}80bO&YZIB|OD@z*F4iY1V!&%^=%^q!+3rk6Cb%?hJ
zwvfdRDvkkX8zA|hxkbrX%2An)Hnc~MK~d+1J1;Q8Uqji7)0U(_P24*RkJGQy%|iq0
z)7l0o;l}PtlLdv=e&#=u99Z|xMS97sqN>Y{oc0J4a7Jb~!iUZnUm5{gx6e#>afvYb
zL;Q5Dy>l1)Og~N?QpL(!o}Tp-8?E6|V*EDSKAC~aK0CESW*Y(He@w3HZ3tKkX>4Ga
z)x}w`=87d`^Z<ITWLWkHn-;oSn<CK32bkH=8JU=nvxM{R(o`ir?+-?A*1sP@aU@%I
zw!?B2R1!{nOdDRwG@(9ko8LM43<AxxWWnr4-d;(<v4$ZCW;dK#m<%p5$4`Oci{JnO
zdJU9amh`-<Vmo3%cn9&b0rwGn2q#ZR%m>uEcddxa$NGkrgYHcLuZe4_u_$6)WdZtQ
zRq}~aF*bHnF#1`=g$!z0b>F%_Er*5n=0ok3iDwpyPI&gY$2Lkdtr%Av)I37ZWc~<^
zr8EpA#0aoyvL7`0YncV-IN*R?vXevGPB|79Jwb}>{PP927pUEuL|dK($)-l544LCd
zd5QNS@P*-+sX6@`&6AHm9#|P;@_SQ_9r`XlnlNYssj@&xDuu@ae|e&PcGeSG+I901
zyJ;zr6p-Co_pvJvZ?&7?LHjnWgB)$`?|v8&m3Ek<A%x`I2qdXLXO*AAK;^2;-ttt1
z+a9Z<p4aFO&BF!67K}bn5;j#I3vT6zA@bXes6d1&D+Wh|xiJ0%V4xP!Lo%yJ)IS5h
zPfq#f-I|!oeM65Mw?fu&!1!jQ11#i5r>v2MNk@0~K{VIv^5{edKK-M!g_8kx{;fb7
z>!xu5afNqkelA9%e-pF~@&fCso2KoIO(Su@lAJ;IN{4evuLVn;mz{m7<;RW8yJ@7j
z)YC;uT%cF}N$t`NUFp+1dh{Ttf&!S6RGIxPc3tP4^sMcd@Pg=TiYM=)Q*hHUFssJn
z;v4$}5dSH#iellTdygYaNap{sBlMhPA!+SH5SXd+xrbhkzhfXH674|<5;;USmWVu(
z5v)DhWAN!fja1o_rF$WWQ`-sP6s6#+CM}Fy=l{M}pi5MNKt5$2*p_k_qfk6SkYeHp
zPoOJI^}La2bb5)FD(B@-Ki+w6Ds`&D_)uEw^8gBdv96Yq%oBJ}gL~-LmF=h)Wh~hj
zLzmjU7|ZJ&r^NT)uqMxgLybZ{BPc3QV6+2#Q87(U)nV%<r3X33ykJ-@Tbtjb>>;T=
zf)&!;ZpMftlz=PB#!zF`Cv%`;Dl$xiTs~n4X6J@+VROXb3@RbmAQNa{vOwgWC-P`H
z#-t_E$+}k-JwU>pWFSHf)k;BfCj8JJn#U`+(L9owYju~)u))t}J`(&sk(&rk)L=r7
zWOAK!pK=NrW~xyZuj;p!b^v^c8g7B2ksf-{TmEwHt2@7m5Bdc<=nBBoeB`4XZ7mcP
z2Tk$wsRl)`E~YM#_9FenL1oiuQC=v|4pxSlDXXz!3FJ{kbN=s?MCoE8_#~kR{jUbr
zs(mq-iWr_N=oDE+VFn7_ZWnlZKRdWJtPH<&=T7fASVyj<F)gJ$qUI*F>qb_-!)9S)
ztL(W<z0P6ccS!g$DTnWRRi(pf&w9!8O~n^w&PlsfV+bE=HrIv_^Ve_jIj|2vHm0RY
zQS{5}oW^+8n3V8O<1Q;X;yT+oDfSf<%rcx;QCeX53t2AQty`{x3ATL50f<c*EE#cE
ziblmSp`$8!mfOwa$WmE(ay`^Ciu|IMs{oyJVEbgEw3KMCz&}4!{q8;nvuu(nc8|1D
zRTmMs?Evc3ix^|7LuFp(iE%=qwC(>Vpk^8j*R!CJ9wzV#Jg3d(?W6uYBU422iU3-^
zWw&D8;vPOn|Ijr~^@yl4ol;9<1V~z|`Zo7`_1qZ5&)r@z4JEt8eEDf&XP0vggzpH!
zgV2&ExxZ+=p!Toaz`8dg#9xRZhp3?o)@tjMTpj(H&~_gy)fQP%7a4A%N}Z4N;Z^LV
z?1gH-V)_=6q2^(&?Cvr_y3r7V&9CskU6J;Sk()=>zBLm>1+_{IcEo4|bHCOZ(IWUO
zJ#^SebkoOaXmWM75Bx+!Y3?GSdut5WK{envhYG8|4$`+E-w}*2jm`%G4J=zrH|pg6
zgP*=lV6Ab-yD6@|*+C}r%7J?Mi%aw&klNA9s3q5V&;3XBC=6z&rLh=_61G;s<c`cj
zgVnqqGH=a68ABhOQ8+YyB1H2dBRqlXd!m!!O}dgB_bf3afaND^b{^aMa{~bNWt(K;
zNym~*IV?K*^j8loctvz<h62C9v!F+eG0Am7xNi)Y0NLZ%aLSNW9g<F$mw)ur(z$W-
zCY(Mqetn<M15n_7FgSch?z4@3k2$3`Tglg8(075j%sac!valCKw3C{M>Kj`MX1~qD
zms~RmI!uy=k^ZOsJDo_1-x7{~VFR%G<#~Y=R#};qxl?8Z>J$PkgWxInwi}eZn{cQ%
z0jInS@i?u;Q1r!Tnjrp1#a*4f*8`5MRPG(cEeKQ-z{@Y^o>v_y4ip7vl*#&0sCD+m
z$IO!iRKf&kb=>yirX2N^b}=v2wdP9rq1y(i)1Y+)8jB!J)=oVGQ1VrgfE<d47t^@d
zQ1o{Iw%SrCc%7bMgyKw^zX4>CI<>>_jUR<<_<{JP*xJxTS{(%x@$AV&4r}j0VQw3V
z8dml!gP=q1Y`gOY#+n10Rp|U&{3!@M_5%O@DnYN2K*GNFOSCG2%3ih#23?)dRDsDU
zfja7pj-H=tw1EKYL@&>`a3b&?0tS71COhW6PyMXkjRDH1_BV^lilledart&+x`XMk
zpkl>}`Jf)6;Vr9g(JTU248J?3k1XXX(ozLp<9b}fWGjS}tORcxUgKY<cTv5K7`5Cp
zW`!<Nk$8wf3Bfv6u|IHx!8<(3ZHNX0^}~7(Dd@@*)+c=`MV3Q2g+C6XOs`nUpmo&$
z;4qQdfL;@$xLv;G26E1BGLG$2xmQZ{pxtx|<)%>d9Pe`~=L==s+Q`6AVf}(Et&Nhg
zrPuSJzg46m=4)(kyxW(Bh{{n5mm)~dkVtQLKd9-~Z<!=ZpfqTJ4ySf-sjT>37O-h$
zMjlaRX^>{7zKX=MQ?E|pXjHxRuU|>DQglmRXH1Gtx=s&c7A`!lmKISZ;<zUVbv=>>
zD4p>)dv_P*i2*AtUN}F!Bv84PdYA0dC0)W<gHz1_+7O~oi~WsJPS6oKJZ$q%$*(Ep
zaM6QDm&skjS*v{giu~@ckKhC-bSJ}YIee25_%M)|xD&`by}4Q9O8V$i_D&<LHDW7z
zN?n~$W(aQg(7#?wPr-B@bF|uv^&>0Uq%tWT`7;dC<0ZQejE{+%(?9~L5tJ=LYk~|!
zj39clg4s^k(E;GaQa%vyjvQ%((CxL%oFV4p{Q@GeO274uIK5t_uS0BfL6!8TBknHs
zNf33NaCYR4)ZgI1ACU!k0sm`@@0{@@Siml_;|%D1g;&O^Xy<cuS!!EuQbl35vb_wi
z*(F^WY|;<|m#4iZAzy%}<aTf$rt&l@+9vj^UOeC+%E2QGn;gd{Po$US3$wrQ%7J8`
z>fr0G2f}?PR*_Oho!3y&ArrIk`TDCh9`ol9iIf)n)(9SVU!&Z-{`K+}#Ac+kFcq4w
z=%VoP!YR-2x+3lzTXTn$KU2de6zj-3CSa89pw8S!s<X%ZJDx4@*fdJ$kC^Mafp$xo
zgG*w%@@Z@hFL`Fc+AW!?stYvR=IF7GgvE|m9lu}|5vgCwcZ}Mxuiv=4<>64El9MGX
zV+E}+)ct~ePa~U_LthaH^lp50c{Dwc!zDgUVI_D>;*IjQ#X;BI4IW6e_u}(UzcH<A
z-_MRYTJ!L{(rEFFrQ?RP-Aq6Yeyv#QYT!fiy%W@AKH@(yeO&q3{%f?idD7Rfuy?SN
zR!$~zHd%oc1gn1eIdw`KL5YB<rQo+nYU>+o83q$svSFi2VrM<63z3K!*kJp+x9d!e
zrLKwO4lT7H8(T!AqmIg5Vgaf?jy;Xx_2q95>3PV?r#-~9cXi{(_eZ4f8n+vS$Znha
zADX%De{2f>LrVIzH)xqBZ?U(ygf=VrkAU(XN?b-_PpgDy2t*X(nfS*tSt8sig{4G<
zQ)2x>5Gz$0ci$%L^>Kk_+}#iw@!WglsI`)cIv_pt9~Mw**x_6NWvm%xjWC-kNN*%P
z!Q?Y<J+GD5Zm}6dLx?U?+I53(>VS$_Y8`irj_2-BO_an5OYA;Z@alvy(yLHW>KL-=
zgVcTY(mf+q%zoB#Ztg)tnW#H!mzSh9-@D3r$^cV=AP6h1``s;TV<SX&+fkJAL7Ebm
zNcHbT_sBE7$CtOgjkZhnv|FKkLD<`W*?J3@?Lb>JmJ+qZ9Ug*P8pwIRL}b!q9UY>0
ziRq6G8i-(UT`xdG5srOvX7Hh2IPfX)Rkr!j#s==<AXn{xK=y|(#z|Tv$Jn>%E^9aU
z$ygBoo^;Sgkuxb{2EG#vSqO9L486qedM%tG)jC~tRtl>^#?jEsE#OwyR)K9lyojtL
z&qcp<r7-e`a1dzJqV&OOs1uTLezSGWXjRC^@!2}h5a0th0bK@t4x;serOp(I|L3rf
zToBE)l>u>*H|tQs+lg4XXn`Q%4ciDLR~&kfc4W#|;nrA9>ME)@EzxgeTP}5qVX$T7
zmV;2_o*bUBKa;Ar@fXT1H;DW|AYU|<o6c`?>L|oKiN(+1d53GX&*1==9x>bErtLHm
z3(AVu?&^&^E<$)jAOKN7uD^HN+*-gxLQRc(9-$#^X_pNR>YA@ZInW_2!k{lA%JZ1w
zCK*;Ipd@Dz`%7F)Cg|}O)hZ?>+^l;Kr2t8R#q^Xa;Ht-iOJ|Iw&@<RfnzRV5x>b2k
z8zqb@sU5{mGdZXbiv#V%Ou!F!wQKtD5VzCrA4W1S(K5Mdb+WT3i9MF}JtkJ-cNJ#W
zn$+?qi9#ntXZQ^ee!v!C7aXVu+2`EA%R3~F(m<5lH4dhdVThdyTB+T_N@X|0`AzlP
z>xLFbRSlhUi|7xCOY&cd_B(E9<4L`SDZ(puABv|5DOZexHJFOa@g(XbkiE=I>s#~)
z*x5Vy@7-_J!<AY0m34)R*Q(=($O|Tw;fcH4y!m?(BKH`Sy63X65@LmO>)Y?cOb`!$
ziW$_()+b-?^+lQ9DtLGi_ueSo6lZGL@45_zF9w5=G{a|FZ*^wStf_EXIaKt|9pV_8
z)9oH<Bw<QKpl(4kV26d767B_F?msUJ{SwCz{7Z{i4bGTi8Bpz6cB?=^{A2y4Lcmrx
ze(og$6lbOXUEVuzv^9wGqViY6L>e|ym`-cAF&T|*rF``S6Aq75JgszqHRsTD!}Y*U
zUV}V3LF#Mq-ksc|0@VJ|SF#;WQ(Dx!bH?7h_{d<!&XsuS`3M%19~TpHbEoUTeY8@Z
z^79{y$WQ2FJp@K;<-skJddbuaFx*U-+ADd)odiCW>6cOEf0{0^*)Kmu0ur2|cg>-O
zzji$#4So|Mg^#^zw}u;&i(z3@$ZE&^<b~p=3h%8qkAkG(9+f_L`m9`ZWj3)cR9qd>
zhPMK>Me}Ok8YGhux|nv<GERZ!lVts-ulYtqKE7qvRkDno@gPdaOIGuG7n9IQ%BpD*
z@Tr>c&~X~*>M0eX%B_LhL1?A8akOdnWBdy$j(F=C+G_|VPXfks;vG|oQIRC1dcP4b
ziH$0Exf|wXHT&F0Y#LL}+Q~Ickmj)O>BVDq)G;@SyR6k!Q~&@cZx$Bw>GnaiAvB(k
z=pZ&cmDp8x&Q;8l+TOXCAZA28X3oZo`Bpf7(K{kdVl`8k*&c~FO9(U+sQNJmLE!kF
zXtGM_CQQiV!;1+M;_(do-8fEwo&C`L3+MDOA0qXETAMX^LHd58PfGc4HoakfwtH6g
z2N)xEEqsFR^@bd$h2L+hFW_V&Ltg2O0`e$P2gMByxQ)a5P8DFM8zXb6Q*}fqQ8hjv
zi>8g@PkYq+dLeVOWXmD<Vh2wunAHt0%?>38`0e8&>3L_*#SU@petoXq^Woi@#12!G
zVw;_II1jQw92);-PAkvtc9B}s1rOC`dx3EY?vkOQ3=Mf@3j!?~BXj%!6I#HW?G{O*
z7l1Cji`rA^3cvjono*WrG(FQTQIArKnNa`riKbPZ)75hJykrA);(H(KljJ#7UzbmR
zvCbmv<ROmrB?N;piY;C}H>M}R8fM7?XnLsq?a~q(am(qHf1%|*XA(XVf-?VU4;^3L
z&N1qOpG@d4!o4@^UMZo_j~`LJlPtp&!l^@*EgQ_6Bo@1e%kQ7zZcrHZvkVu^**~o{
z)s0}n1)A6C-C37zf`?S<y~;*(MFA1=g6O|eT9qZeRw--dmeuUa>9^@5wQo)&x|o%d
zT+dRvH%E@?9d%>)xM*%JC?YZSY}UOXV;m)ER-+j|un<lXtZ$KZjZL@ix27InuU=#{
zT+jOnjrzDxfpmv(m6r)L9c2J)*4#a*-G>}Cgtg#a1A~HK;~t9K!-gS900A@Yb;5PR
zRh%N~lH}!l;ISa`CFQ#mg$KX}4^$o{aL0d=yKT<okV<BNEGW=QTW+qp%R7Lx8p4Qz
zDXY_pfgg^3amz7AvPq?mIRbTBcmCCEax7Df+~*FCwmw|7`am9At_MOOEm<mB-%eQ8
zvab2EUDUYv4$xwjh9^P~0V`nw^`l`oo}MHc_9sV8ZnI+s`QKzwVVU2juF8+nZUn}r
zBrjWlrip$in@;$UPYL{P9<eSEsbLeJ%;P|3n)GnbP2g5V&rVmGTwiLE^LOR!!|9@e
za2TJwY|Vg0lGssPxVG4GC6pzBGIf8P_%A|fEgUxEFI_{D-|tUb(VqF3VRx<yHJWh6
z68F8k!D?h3OV~kf7-7y7HGr%)*X(V1&<tPryNm$4J2Q__gjlLSv+Bbrb-4Z)CE}Ei
zM-KJvc6^4igCMUXfK_$F^xE-!+_1VI(x5!Kaw*or*hC^m<*KU*sB^5BSlF2e#iKVN
z6VD?e=6K4fEk;KG000Pt{yJ5`F*{e3Fc+?CQP5s@Qg1Lnw%(EHA(w}~ne>z@Q)Df#
z7)#X)Fcj&WgPdAbuvY3~n*qa4J8tuKL+5z2X%W2Y9D1OJFoP_P<(>Ft*f*AH#&BuJ
z@&L{`ENXbZ4^N>jB?tt?Y=`6TIo1MSym@rM9>ik~fZlz!?W8DXePnC@(1p60)07p~
z43U(9xXR|MSw<3Al+BacTTC8VYeIPP{!kK}l431aK-Y1TP?M~Wo(DrEPY;(jo<--6
zzM)6O{nH#wONb(Pr6^%B^u_VyxK|;)YDLs_?iJLGli1I{ahs65&qlC$vs3eBj=Mf2
zG)jpC$8vYMvk~xiv+3%4=BAy^+=KGl>7h1M4;S*z=Ycb(=%2+3C7xcWkso{H%JtD@
z8iZ`KMR@j5rmx*vZ1UX`&WUL}szjke!#&pz@KGojLK^}k?fnZtL9cb}G01|~32Jf|
z>`hmrJ=PJXyRDhygjPPEJ-q{ZPrY&Fldp<3TX%@*X>3Rga<vt2CB>Rif9y&{6Bj<a
z!;YL)q=`^}J9ws=G-)0G=oF`PdbDMFOZ*?5T+qaV*t8m;lvbC~<?dWY{zFTX?gQm?
z%2@CGr0HaQy%TOrFw%Bw1>-9=!*RA|t9y0^J7nyrn1nB_A^`tW3Od#Qu@gjfacZsv
zX^!DuQ}0)%V;y8{R>aP677^p74&W=nSP>)sq;%HlFwJw0LjzQnb}kPVz>O3Y=Rnhc
zVt!x?bg5!_GV!SRY5GGwTYrbVfTo_aK1L>ekJE)Tl}?xX1+gsz$+-scn_;ssecXDI
zZKOcmpGVm1HJ~ac0gG#7klUXxM&!^9e~kn6qfvk(Cg890^!vxwBj??4Osv?|5;nSa
zHPt<l{vZ(De?}Cr@w$v7S{iE?%L{=g9%)3zaCQ?n_YWH=dO9InKd}73om3(kHwm?j
zb<KLSDvW%N?fC6^F?wXDRox_Kf7QMnd-TN`PJ^f7^WZBco~9%@wXkjB!Q<Xes|}>&
zu4XQMGR3Eq(<rFc!rj%-`bJj2fXONp7!x-Iv~=dVsJY}YOSt(+YzkA8%tPALLky#P
z6ZsuwT)M>}d<*iSQrU5QKq)D#*m5MJYTd$$l6hAnzs8Q}UekKQ4!|`hH)7CphfP9#
zg7VY=;Y)@s$F~q+h)hF!GeiSo6*PfUv=i4FW6vl;X&3+iDoPFIjDSN33;OhD?~M<Y
zFA{Df$s(2UT1pRv<6%uYF3)0n(`*wkmh8LZ5$xat^0bOGD35AlTaubbAx>o&VZ#8m
zLKs@7#P{Y;rnrcJWDg|(&I$(I8J^RNVu;!z;x2(09Xtt))5l&N!-Qh#(~ggpTroJ0
zG#KYGmIft?ka}cy{3K<{1|~va@GtT}cB7eYSBN;X?2*?n>pA1Q)1xO=R77ewMPH9;
zRyw2sFYI<tVTQ;jnz>N4FWScjP8fL^2<Z@>A(H5zQZ%F7)jCjuP#?*U<R%U^HxaC9
z1q4qnSS03Ae06#Po!}b3`}q&Od65T5;3c?GT?i=^sr2j@IXfM(AT)dz3({b+FHE*}
zRD_ya6IF?SLXNfTWC&k8H`jGo=oI%FOI8JTxY8~654k4e*BT1sY^*{!BBNw($)4>k
zhqM#(&jUS9Xc~Le8O&KktKl-~2gGte5A<Gw>VXqaMJHQnf-n(@@FGEm)GGj}_}~ZE
z+hAswnk!By1LsvrXATn7q;YDMWibV)8RYJ=sIGdt$0}StyOxwHw~%vgJYx4)IZfXt
z*a(mW=uH;1HQz$`J<uBWfNTE;h<n@41*Ahw4_&IsZ#8zw5wK)f$>UIaGMgSq-Zaik
zA7qnfYC-ELU_<je#&emwJ|3q;QWy#AG$dK3xnK-aJ&PKhB`5u*1r(!lbizFxM9Npe
z8E)8hZ&*l_NOtJs@2K7{@?FWp$>Wz?xlP$*TOAXRHzeOR?EQ0jP0?hO(2lcD)!C^>
zG2){&!v0+Z)thYy88;)6B;FKujc;hUuE_4d8&N$JFcI7d!XP+1g>$m{vpN@@n~2ql
z=jA3M```4-HrURptCV3klEh1PArYGKaSJ8BuuI*2L7LJL879Q9lX{9EEAKH{zj9fV
zSEkVj1E204dWSOt2CR1?LcMSAJ!bcsrowx{c*N{e?l2Pf+f09nBZDYQKyXl&hn-wb
z5_F2t0^YoW{3zyv=PlnBNSSh)6%~R~HVYz&O}JT`UJoV~Oap^E>iE-dyL&UCG<0eC
zTg=@zCs&h0+H%$FB(J4Zchp5B4xN2I*8>yZ-gCw!?f{Fg2T_1zzoT)Ewh!{Yh9TCi
z%pvgd*YX@E$7rG{HqbtO%IzHN0hjZoLU<d-0EEz=4NS<c1wFVfcx@*M9f12!+Y^*j
zMu9t1dKae3bGz-YW+|ye%Rq?~#^2WHrTf2}{b#p2n6U9(;$GzNGBO7QN@GYrfCZi1
zqRuOF>~aM@d}Dj1Hc||L*YJc8gBh>kX9Q{cwcp0Zb0TlD9}uaOo^FD0Yn?mquj+9O
zm#uHJc~^|<g&7(?5QQt_3={`5Jqx$ETV7xkL)di099|)xf;=91wikM05A^@5V+92N
zg?sZ)NcXx8HyU?_E?LUz0QLtuh^^H=(lIEqYkU(`!=hz6cjd-1G0u<$+tBOG1}$L#
zn22nUi^JW%2hl;x(<>4xb<s+=i(ci;4+_=uU1b@@ox3ADiAX@&4Z&h`S9RJ{^%<XW
zhqQUu!Y%I~p|;=;CKfFBN7(R7(kWQhS4pg1O7P;J8DvBG>=@IxVdd8*n@aFtfmhtC
z9YaAxMz|LyEKHCjhiT*G1NpcjHe%iXTVVG$g{l{TVoIiq<-Q>%6ca{C$43_E`Qnbq
za^J+Yl}9>7fJ`-x5mZn4!VYsdh`R_2g>(DWDnY5MnbIiDXiEhW>|>1-Yg}z|1}kRU
z&5_j7@`TDl-FoXECjOrA?4*r3I$u!Ph;|4Tezd5)m%q>yWcmju0wvJ{?ax2cFv4D$
z3AG?Jw!RN`Jw6b}64|-7<wIGqHEWO53+f#TPzN^qLMn?_rBF%#5%1TJzr%{|inny@
zcesIwv`d#*5mAYpAW6=IparcJLZoacs-T$$>lwro)6eba@XZM=^VYWJh0F2YQ3qWE
z_2szwGKj*;*yeLOYJE*lV4x%-62b1+2ip~6hYw-`4Tl}l8<q_KF_$dXDTthV)zhKK
zVpY$zPINgzOTU08Na;sn5jpQ3+QdTrd*3)*78?()_Bt!x&$&vM#Qso)Y@XOO15^ct
z(JRlBtxfs+)=Bohv~%VZV_5TlkOq7e+SfYvd>rCTW#}e>?1AY!<Gw7M$!Ki6c;6G6
zHltu{@b4L&tgHpsOWTaG_pig$=mg&mRTx-z7bDcvXs#IWm2=tofZvRO(ASCH;oX6J
zT*N4`dj#QeS1;fxd?giVY;ufD|55mI|Gk0+B7TLPey2a1oKYAw>SpBe8lyx=X=L4y
zj#-lG)ik|zEyOPtsxwlFc{^~A5_N57%P{*aae5bWW!S&i0~oi?C!X@gMZ7tMCX5BW
z;yQtO2x4CLThqq+flg=2hyYA7D(1EVL<^nm6S&fr3&b}}|NRZsLdEoDTpeKZscR6x
zI)Kykc%i-$H8!J>#n-+3Nzu12^LVS$3c%s$Wu^|wxCM4db8I)<D0Tf8-EkmlVd)$<
z$RnseYa$sSW~`Y?Z|C6I6tRb!FnPKDQ2(WpAZF_0gstZqH_kRn=fzOq7xxo9{+%OG
zbPmJfH*yXj1N@8A8gwqK$ToVA`At>;O~9>=Iq!iVp=SIeHeUD{Kfu^6***zn$Q@@O
zpB@u2F<<T>W!az2olsdrcd=V~KOWuAJHc2vP;(=({9zC)t`XBOdA@O`-fh@0jBTbw
zV3RLtwysN(I*lD7<<^(G^$oHHSX&tE6?qZK^t9YMMr|Yf?E(`5kBtYC3v<};&&`W4
z{yd^QmJu{2z$nk!POmJ=Q7vQ%DLq1}hQJWUP0Ve9W2J?~AXOu>1ZcV{y*O>fvy0fx
zLVJ)bt|bM`V<7;0ciEc{(s07e2@!y$KF+XDcny{C+ET6HZQ~f9nUSX1f`^DKY^Ptv
zKe4NxNXCdh*3_pJ!1VF042U?}=mc~4bG^X|<xThY_qQfnm{^uXL{EDdc#LqYltP5x
zlIIKyTH>Vi4mB?$+lds#9L(t}b4M}d%6(-S4k1)ETEGhuE-df&=S+6V+KnV4kJByj
z@<(^)2cx&p(6y-7AtZP|UfXG#zRxl>wkgbUPw<LF+dqC6&gJDIs^IXUn89g->O37L
zUf0z5fyEWoC0ZNNH#~CASma_HcATSHD7qO!X7n&cZ1{JGV@qTbyoS}CQN(*zsp-@6
zA0Ip+v~uc05sJU?bdgZ?wn<{6nuS5RND^efb3gJLFP{r5-e6|nc`xkOm!}3w()c%Z
zrJCKz9Un_;lZDIoO!B3_2;%Gjt`x8-WbB&s8YN}s+^Lw!nX>*;=7)5wL`X1s<dM2g
z{?V7AZdOHu7$+-}Z&Jd4lN4(!3z9?eTGxgoDaL{lQ8`#eDWu9mX*WF0Snz(A2{hB2
zgn1rwyo*+j=P=i1jfM=o#q$tLd&|cHYOim;{jafUH!&^OG-m5WYo)|3kdV<LUy}sO
z9?_fDkj=@MaFYKQ%S(IBMoD@}sixb9Xcsk0gCly(l^DhigiUx9Jz$GPAAFb@cLObe
z-ydAYN8c-%DMj`Fi4JVWq(6~?YZXDlvaeG@P=#{r`joS3(U-4Rt%n^X%}>*!qW}wL
zOY7WV?%<~5cX^Y9lp{ngfzmB!ckH?=0}c1G8VmzSD*@(ME#mZ-;P;7nNn)<>N~iL3
ziIR@HIw7a5Iq@ohPu*kYve}?q;sWF~Vf-IZ_%!I8o=B|ke|6bN9alURao~X%R~%3P
z0NhdH1U6#B4;19I0(7N0(?t_s_2ZKcBku`c*UFYy)le*bt0sisesT3R+K)wOG#{^Q
znt9M+L-`N^@f5&2>vFtogNFc4rFI52?D9F5jvs;?giCQZyJ|C=|7VZ-PtCBf0IUeE
zq(Cp3<yXSCrqZz0lMd@nsK;&nYvMm~Fh2_{m*h)6o`i^z-ajN~+=z~#fV`zZTvvuN
zsuN}eUs0Ra+E8~3sm-UHi+sHUZVjfdG_aAk5Q|Q3H)(*5P+#BioS$9{#jO*)C`i0l
z1WtZ9LF;a8D7aw{IDBoHmkMgwYVo&c13uc7PLToGCIHSctbm(?T#&f~90{2dKy}A9
zAnbUKVjz&Bl%mylRl%|k79JQR=am_xZdmL5^MNYSiL~;1H5HpKD*hh!$AFc0M<&w8
z$*$5flG0(-<WG(l@9y3<Wb7(e2Kc(D&$07Ni*b(FDwhQ`>64EK&{0geo710&5K=<f
zMV+EeGvBZfXEhL=3g?%Jb^_b-9P6o*DQsE2FD`=c^P3{{#bA6uB8-2Q#T>yt{)2=2
zb*p#%T(T`~l;rT=WzP)tJRH<u+$~VJ9^FpX({LIU(+J-8#@lh0^ea(3X7N>~n*=!C
za4|W+wwtUTypZF!U4<TeF6K!U9`ZYe_ia3IqSjL9-*5Af!UvdD;b>S=2$SCJzriC!
zDg($y8`w~eFWIyZl&Hy`=g0EGwl~XV=b}e$Ar)S2{E-?dxokSK_oivWEqFL|na$AZ
z2i)Uh3Jax1aoLxw<2n+%nC>=5ZD-r@KulA1PY~)2J4Lw>jq^f>{xb23rcO@{89M^d
zbbd=TK{3F6PacYEXZlsNq~>~{Fi*=HP%M?rfH2#8#_gF+Ib_m-eo`E!!t*vwPVWzb
z(q=4xM*A2hhZQo<Ytgn1RHitjQQt*+l7{hlmzV=-BEnmHEi>)FyEAz~$s@U18|I!V
zFsaSR3n;&>`T)|BIN_y}y7Ljt7f{hy^UbL;yA?V=6}x*Ifz|LynO_w%oCz0+g|`eS
z^pr*PWGvf*SF^sKd3fQx6t5F{J6WX>vwYA2tLSzvXjUYj#<LgGl8{SrK-GZwnnu_?
zrU{<mo&<N;O9VrF!R-x#mXZ(G5+_5N#zXG=o$RkHmiW(t_}mM$M1UW$ZiRis#mVjp
z0^e^$V9SbRR>7V8n;+BR-9ve;#}rw-aT{LczLh)hngiS|fYCxRl;lLBgxByu(9Vw%
z+~oF9G8me4PZFoYQloRO6lcWwRKrIFaf{VOPc_(`v$(@YoV0k|JM5Zqp#_!zQXu?0
zg*SBjdy(aT1xX|=us5S;(t)GcxEn?S43dC*w`tS(CHB`FAb-Ieo81KAYDusH%78^m
zpRwN4DUV_ndRH++HB2ww+6XvLGZkxx5bnzh8Cl7>1;7MXusN!Y3SC5`uzl3+;CHjg
zm88{Umbi0V|4f?Xh}4B(I)}h4X3wHS<l0}8x5P-L7JY?c7S8G8Th=~y%_0`tu8Lev
z)78d(mS$M#ls~9l$g%|J2gf;c!3Hp}!#iL<aVXihagZLb$}|K_F7?C%Mch^KP0!q@
zep5%$^8;(#C;GJ4Ct<Ad{s<un{rT(Tg=m=IoaTxWTXWV({A?XQHtpErds;<<M9N*r
zn&mIRWKt^2Z)aa0)j0l{Sa`z>+9|2K9FiKTWb)>=YfDPTU_@WoaKDbr!E&4&`Mv<!
zH3sca>O%tC?@*&Y{%K0|7eAlg8>5bU23H>y9;nq&`uU}>8~<WI;)9_au;Upi{24MD
z7k-s?RtO_28kHM!I&z{|an*$dt2=b1N*i|0*Tr82>4jXIr6~vm=N3pva>mV-*!t*m
zE$>asdSX04ypXeLUgHe>HM%ecX21_bA82X#J{b9@@G+?WGts}c(R-~$D!EZXp&%?F
zx4fE|&s^S?Hv?rB6|~hduUv&k77W+VuB-68hS~QIs~!k~_zI_U#-WWNhlyI#>v4cC
z4C6aekl0%xAL^@N?a`o+g;R-<*D(L+5kiLskp^WL4dd!!b%e@5Q?ZJF!;OIr6WbIK
zleQ+Jq&D{)N&Dp^iDSM8|2viDx^bb+Qvj<!&3ZH8B-!|+;+4fhZTS%L&T*o5_?lvk
zQl?R%x3dBhX6M`m6x7cDC08&|F3wZTsS~nRVw_JeSX6q>Fi0W9$pDgLDPn_<Lm93@
zrkCo|QF>D@c1_k--6VE@wDJ>g%Gl}W`iP`5#`Ge-9-{(`+WO8F8jW5<j~zj5n_VY7
zlt6y|I`;Gqv~RGkD6%uSq9Xg%d5B+=&qa<hvUkeF*J(gatvk5|c_OL+003LlPam&?
zVa<XdTUfZrm~56Velln6I0qOI`ACVCK*L~{SF)sC$wJLIVh(20Ge*!TPAfURbyo%V
zQ}6V4umRR$SbA3o^NI3NOt^(65&iR6D4mrl%uDA0<IrIdvf>;}idc0tp3_8UOuF3{
zqZZsrjeADu7QG;%6CfVHE7R4e)>0tB3+v0<+9mpYdUbU@)9wHpwuD7EdCn}#iiOG9
z`7S`34m?*#*tg^G8Q`3Q-wstu<!Kf{JvJ0UKb!(PLYFIQRG5NaPt?pf#&(-2&z1H1
zXNvd#O{rXAbmscYtkPtWwk;tF^dm0z)HO`c4bA_RMS%(z-!le+7L<MEHHp4h>L!;`
zYm4H(h&y97rmyMW;DUd#C2H&78-waoE2q@Jvt_}LwsiWV)vfjY+8uKSlK|nNa0t~+
z$5q)%YSKd1`?uke*71PCQd_=w-N7~!)ra!^BHI*JfX5S656$m-@hRYU1>&5~2^vw!
z$-HW~BoPLgsxtzve{$!mh{MMm4tT+1)btjQK)+z;@j;{u?3OXg<{bT|R_jR;!zorK
z44Hw3{Q`h=kYja^JLgf)8CH<l=%!aZ9>jyKU@FGitj;>nHyCQN{=}757Ou3zwBc~A
z`egkp$<S>23iC{I%Ozep7$pxE<xL05V_ffHE-2ttxk*!w#lCMcnbpse(?0bYR?-Y$
z;FZu^9VcYQZTgdbPB!!sxFoF1hIZ#z0>t}|R-&;ei-l@gmYI-ix76I+&MUT2K%3U$
z)V3s1#_pc0<5z&tdmR&bIq`t)aIL3q-KpMG6s;!;LzvooW0Kwx$;KYSlZ>rT;qD25
zi_E52?`1KP9$O|`!Q(n0eQgdqE^+Ksc6Hy%t)BQ)*#m@RdTGO%DxGS@wyr#E7Ga@s
zv){!fEk|XnOy<sc6-K3HCypGX1C5fB1IUhm3m5>w!DyMLUr72|*kfI6Zw-i#@424o
z(R|Pn2{;Z4EaS8QwG-LvZO#bO0kG$Y5@-qtS~c#BG}B=vVim%+CO6!)vkDi?nUUf2
z09=wgLh7{rhd-;)k7RezjM*?t9hK<B%}ic>B<~vsd6o&vhI$VSq(_V8*3LP2uD6o5
zjV(UWeN^$Md<YEE87F0NK}mgUW$oSvjq%Kt@L203n@1y2^!s-hRQWIV1JOIJ6q*k0
zJSE0nwZS7Jt}>b*l41Cyjd=yFVZV*5I%8fkZyco-9FH~1Vr*{8c>mc4Y;~i*Qj$ag
z9zoct7^gQs(4;h~LqkVn1WmNKg%Gd6j0Vj5;-EKDT<Y@yM<MdOgu{cky`Z#~+f@Kk
z=HEAIg(Di5;b{=a6Mos)l95;P)cP8k-JSz^W!UI&0#Z^FlIw;K%e)^TmU5xH9l6=I
zCJZ7U@pvaowBad@WW@YH29f;H_5PGLQc>>!YWVN#0e04T<^Y@p<ffT?u(;5x%~M$V
zl<hD`ICwxv{GX6K%t!1r2CA#Ei_i|N(XwO{PQ5tfdeL6!?-!mqk=GHV@_NLui3~Xz
zb3rN4Xk*fyw?+)9UrZ@EIzt4|3N14dSJ^TAko5}JKIjlgqCZb4=-N{sdMm}NzdSu;
zd#DtnI!Iv%UWi*BCZnH$c<bXB*HBs55e}VH{qBN!(ICS5ETxMQ1V!KN3<zNWCbm-c
z!hxtV3vLS-ia=g5ScWXbNP{fjz?6Lh+WdEVd7BJ!kWo)tMnCl%;S~d;X%F^I82CX^
zEL}R&;dvBcHLBoA;R_a54twX+{-ZbsiR-Ia3z*3^Q2|wnI679z=C^Tqr#WY-sFl3v
z=x=mHE_`DrHna4m3)2)<Mt^-2HF8w4$~SZoK^tzRIfriWl@FA?>n0DoG=rxM!*(Fq
zQb`ffOOAozP>^9dcn8m2!CRlx(~kWwB$2F%kHNTSt*Bh(7=1@WUTw|uU9)JLC}^Bz
zJ>w8a2-V0DJcK*C5vhK=5)XhPKIKFvMn<<5;MU2Cum1^i&#W09T6T?pQ}}ugpM0mM
zt6I@k5k2U<(fP}K{6uinp>+xWy#u)0Kst2>`irq^ex9scpaFDX00LLA%x|xZxzi=?
z@X3S+#CpQsJez`9RzCT4mf9uIMc|-xnOjp?Hz)0Y6Fn#TG068nWB%c>Po}K)JHHU>
zG^0e5v@WPH1X3F=|EE=I<ly8&DriN*PV;#Rs`))<Xd#CU4DKt|e)plXK2M}+RtTwu
z+1RzMYaliW*xX6LwTy%JmL#lpf$!L|uc7Dnc~-Xo;WUIydIRuvMV;zwOuFyHsGfeo
zfs!0ja4_2WiK!{xfKHA%kk!Yylou($S{?!aYW04`9w2x30(M~<(R$bzH0K=%kw*@P
zs-C7?T|pc|VB(aH<$6%oHxz?gR~#UCupp5NG=#wdt3iXHPpUX;Mj(&c{i&m1EU+5Q
zT6)x$>UAeEdD!`YC`H1QYvMOTh>g&9SVW@VT?JO#Z8C5+nvs@q8|}gS2vbv?0Z$Je
zkBkF8{rE^AX+dLRJTHgyK=A}(X;2UvV-sqs$K=u`0lpaJ$p#Rw(ErVV4BL~kkHqr2
zI<>^0)_?RtkP{}8?Fix#0S_NY`DS&|Kf-X>bpO9CAGgV!3BOu$`ZavjM7JVEIt|>^
zPXF*z6jm?1QK2l*5G^+`=5PjRXXkBKGyk&T-AC8?b&VqcA)8_1st=KaogEotF|l=t
zWZ7E>&Os2CXUt6<$7BJ){7z<xOMbfl3?8@qpi6k@ilXm*s7XQP%}2se@0h`wQni1d
zOm}mH>kh+tncdUVIms1TzT8)QB4>bN4*cl+f7I$^8q=yhytCx0U>^ZsMLVU8R?BjG
zEGoAA0Lcty4hP|r5FHyl2eGX}q2{TC0%S-E+@a)=qm74P?_PWm*cwDk1+1~MhydjS
zgMpq9;Lc1|ffJ6wJ+-^4(XtOeWPRXZQ=LII9~IL3pN=>BpbW^LbJmKqEKmXh+CUms
ztH4ia0000h4>fv)U}s{CuE;I3|GmvDUL?SU44`&RsFPb(FwdBG6`7V(dQ&YiALkAx
zni@YrJ_s7*7+x5M9Dm9ZYIKLmj__{b+sgv7tB41*>2|`9bYh?MGKp%~+hKiS<HBdj
z;C|J$-c|%+FA4lNAyJ(dGgG;S_w3YDRlYW1oM%;y3~ZqOrvSdYjup8+FNZGzi%u*^
zd#lI~*>sXT@&3<`7orT9w-UwzpeUrKLUSqEipA{RU!b_o6Vl`3pVQy46=1XvfawY8
zi(kSWy8Op+#={Mhh5M2lFZM&zh{lr615|-Ocwn~!<ryHs_sY5!^!onlBd(e*zSP+=
zy_S*5XX?RsQpA<pY4TJhBbj2Px_V19@OLfT7oehDa0b%L>O{G9)v{mCUruqBj_4WO
zto}==%oW|O!<0>|-fxMiFh;R<pP-+uW8sq^9Jr<gg5)pAw2?ro42Cfyx^jLt4{B8_
zCQV`;FA1Q$J32OQ4?#VC6C~jX?GxNnnuC6dywJ?Rq>3{8SZUpc)|*M;#l|8pklLaU
zGem6ocS2-y5hAl>da|ZeGMM6U`S@t_^&2@gf#t^p2INF$zU@huUP136IWk-VsISHw
zbTkFRguZ5j+7AuxwVDObh`BH(Q#V5WsgLtJ;?@&vQ7lJd<5a;%dCMcHBh+VG1R;S>
zAwgTQfQM&y&;On<Q6lOAMDW1{)R+ZN{J=c}N#^`2j={1GCH|(al>wD@k2i#MfGe}S
zz~e2WI26ZCk5=6o{A?<~T2R4~UJ@47-qBDOnleB@7w{_iB)~ZO7V7#++aU={6n4=3
zPy7wraWgk>=`1s$0e9IMRBmoY6>9&5e>td>Yml2%J!U9r0TywFF_)u(2kDB-n&KdA
zdC5+zJot;rq2`qMs?U|S>x7lEBrN!F4V7)Mz-{q~kJlk&w2%~QkE~2Vcp+&>7Y5dn
zD4b`D14DP4bh>!9k1t(K48r(?F!}S8aO?<*R4?#_w-2~9S#A*prG)iyd9q?+{_xF6
zqdG<tF*Nl)0(UB6@m6g-H$A6jX-vcMS)4QbmDc>b_F`dIamRD@taan30Va1yT81*q
zM(KJNqsS~y;r*UrI$3?=z<@;5YgYxPuRxPGcCk{l^|b3j=ygPuv%xGw$D=;jgCe^5
zbl5IarMPUI&FrfYdO<L1x`BzLI6(dBq;r)Sk!^E-GUcQllbO#{EbgJfT2*A~4p)>D
zeZ3MG<*KlfU%<X8N<$PzK>iJD2R8{*E;6sayq@6LFgpZYM*OI8$4|ZX&pkm>_<?Jo
zvfbhxX~QOMwx0Q~sSpCi+VR4HVNFrCF1gJ#w>!0p)eWi%B&jMH8ffSdXTUo@53?v{
z3_PU_VIEAn9{WncGisl8E;7*ByhwjYy~AiW-Ke@zl4FVJ>D4K=U|9l6C15{L<C?@`
zfI8rl=Ai;rylCD~(wmm;zWazGi(xQjeNGwp@Shv9z2NTt9?0!E^_9OUJC*6l`Wx3b
z8%99#vW}DM1vYqZ2+E!?nv7|ut!d<Og$gf<#=beLOPtiFv&dEg7*;8T_yS(|dNT|j
zi1%!d^cUhsR2R*spK?DDSsHjYVEt-<P(wQ-zQGgR7Y~U6qE#)-Nj3mTV$-WTbC)6y
z!*94+f`r=g<g0&LPa$zd<~=u<G?#eu(L5!BQr_S@7l=7*a2n-o&x3a}(DUF#$x6>E
zj;)F3yBW{Ac1*ALMMsz&e%4mkSoWcjH-07j@<`DKyShT!L6-i92jqeS<iCAy8L_Fr
zPS^7je_ue2bNC(y=#i~L;10lnU5{5nxx@Sr8A)|kZ|*E*CimQ2{hDNh?U?~HC6W_F
z<>_!>)aWbM7C(6AD(H_e7lvUkFTu~64;$ldQ^yG&%7@8?ceLbK7R-HtNiHs(Q-rmm
zO8Qv>k(0Qf^7ALW^Bl!i35O_K=asM2k46s;jMb~a>xH20s*pC3*M#@3&emB4di_Y6
z@QH17oADQ6Dtb{FEIM-w1A&&v@~cmcX~;jR@L^(5S00G8ZiL6(1_|kgSwB0j6HQU)
z{^wZ-PzN<e=l}uZNV-lN;+hdAc?`l!L>3V`GyP%$p5IpG#gEKrUnP({4O{E;7*(^@
z#Qiu{=%?0&`%ZZy4C;i{sI%~CaAB^IApCO6gs2Epb=crQ#JK{DFLq~8F<qaVny-CJ
z>8YxH=`25!gTZ&MnlpPqjo{E^ei|UE$n++kjW1>w^WM{V_1q}_?6G{7wk3EiKv<(V
zcKk*(M2Fb;@*!SAhLr(4WI;DyV-P-`V$~NKOiy&{kyVFU34WWIU6)hgzS=&SF?s#X
z&LO3E2P+s6mg4pTU)g|Pr;S?TZG6}|1Onz50M-qTme>Cfo=qhW2PQ8{{sQSNXXU63
zJL1JgiX_K2dB)IcbG#s7UR;ci&<G=oTvx=-{S7~L_v%|8_<|{;bb;VJdV&PTK{^G_
z5Y7pUFgG$M7$&AuHF4X8HKsb+Du)v5d0uQ){D{ZHSQ6DS?yr^W6KMI3$G$Zrb~}&Q
zYw$f}zp-6W3NeWLLB<Qa8Z;nWMC#9&QIaB)DA3^Z2qHrWCQBvN5DB%70FoLNaX160
z)#=XP!W*J4pO=XU@n7jsOz8ZuVVre~#B(-i26xc``_+0r-E+oqo`f}qPIE--cLkB&
z-|s(OWAugG{#C(a;nliq(1?Eg4#_p9W2xUhepT2V72Vc?5_jryp^`x?TMAS^*7l3$
z3tXi~T@s9ngsMdXWU{cG*?!xp6MgxCCQ~3q4O6vAWe4CdoYV3bX1w#Zasbzwy0BW5
z`ZT;>{RN1A$XQ%Jw<s8EWv$&Yd}T)sk$Ke}kB)pL4J%=WnJzRsNzJxg$zAPh2~Y}X
zCJUvy6}3^KLu|OG^eNsxJD{3bJ;jWS={6<ag5Aa;0*N$ZUZs`AZ<UjeFr}QI_Kr9m
z>6T@We_(PT{MxX|=xhykU8L^Kc1>DTPb4e5B<hGdA&E#eWST>`9ViAVc7pduY9(0d
zYdqG?YnKRgO;-1PT-Y^-MbZ<#rQKpR?LI;8C@;%+BNt&GByWOp&WQ!wsH&w$9Xoa*
zU+>-(i;FlgXfGEfdD;ZkA6$#paUZDD>gE|H8sox^+4@Cc7guNmnulk7PsWMd;*P0Y
z*Za+%!h&h%r&|2RXR&zxn#uO`o<G)l87=pmjY*fU67Jcigz{@rR`;Y#qDHlvjtn8c
z!8_YhUBMlB8yP6hNWP*2soaz5;k>f~SvKGt0tj9`-w6SLV(x3<)d1G=ui;@R4zV&0
zZ&GO>0mGg@Yc1=nLmOAL!Q)Ztp}P#e8Kba*N1DU13Ii#|YQmRm2K++_L<&(`cbRD4
zq``|ZQN)MV^^xzibzVLJ9AlQD&+pC^7<dz-*j7tDgv*%cy1|3f{?1d)?;N7fmq5J+
zg(~ffYX(d>b<~pxoRwt-9HZ)3ojpWkQsfKYr%?<|%aE{@k>78g0~4k*Cu9>CKwDH1
z>cZNOqNhG8PKt;JP!ex0Hp8AcUbvP#`@HO!+u8z!WBxz=NXfDZ^e~pl39)BFsZJt?
zGA*)*Cn#$WQ-3{9203kNq4BsDk4D7YH1QDcJz!LlFBNB}U8cgml+_*ctX5>2zZJ?6
zju5OMIREW%ol~O)8>V04!nZ(nw&imuftx}05sU`Zs}0jN#))7H1A>p5aSv#4OX$k=
zQW3!X<<QTI@@zfRQ|ua@hn|y!HXtD%=|yA&o6i7hEMq*-aoOeppy1F!@;*1n|Gdej
z%R#|jwB=<03EuhMtELwY>@HKVkN}15fqtLNKpQ+Ru|EH7ND(Hh_{EEtHZMp2-AG_-
z?E$HkBW7&-arQx)mVz;K1w2JXzjJfdcwan3z2L3i8=<}O0okIQD0*PuB)}#@e_+q^
zg35s@G%4Y528$>OFnovwZnd01jWo6kJ+$MNLHZ`FR;Gg~r{8{~A4VQfQU(H2<Ar}c
zC2GaP&W=!DX(KA&2%fx}akMCqW})&%I7A}(K741&qaMBN-fDMSZ+63Islher5@8hQ
zya3ivvDVvOv3ONmwO5yJM|st8%+o^9!9sfs*R{JpH)bzan@2c8GByKRnn?Nzxey;~
ztS}<0{Z^l-VPKn5<JLyDc|VR*3>OdCk8fMP#^BaxXnk@;{zn16s_&GLVHp^1Zmv8v
z@QY8iw#b+CMOa`z1`t-e{fE1*7Jw2$qzLR?$(N#3#6RJDr~ybTITqzew!p^eUxbNc
z=m~(q)V&QGT-}72VBYA~VN^)G>;n@d0*1(dryZQp*6wkuL+F-NI{gSf_kn9EraQMd
zi!UV69Xb&t8C#V>ecE9N+ATgycjAZRkuABqFG9Es?(R}GMBnbe`U6*e=~97rOm>pI
zEmFQd49orPe&2^i^S?#yGW_5PgX34AFq`_je*@6WPtBDu1`BZtAifp*!uQQMFZg1X
z>V`sSr6~%=B+T+6{ejp(IFarr@Lu>-)54HyTqP>AC+VM>PA`Kn0uneMmQpC9g+y9`
zRC!GJ7@=E;!dR5mN9{<M@ORLOy~hk%y6+6tFOV5m{pOW(M28?6AA?HsFa!xXd9aSZ
zz&2)+QotxRuYhX`Tbg>&!Sy16dR!?dI;{`z)2?hj3vprr=3#f>oq3YV2YhiiTXC7V
zA1=Tk!)%5e55~qAWfrX)5>U3(U0q6dDGT&lP6aw{Q*V7!+SZ$?O$8XPqoy1iuLC4R
zLi~7e?kNGSsG%t<#nA-koq6Pby?AblI2G6u6rE`5jo3nGOeXTP97+_Gqq^&naf0V<
zYNwF8F06Fsf);>kIkG?H4uUs-_KbPu@&>`(ryuI#XaE2dAEXRT!IkVZrhANDw3C%j
z4&zoYsFKK!55r4Xk@0E*u>XFlUY~9v5m#baPum)k6*FH?Ex<`;?7J4IUX{qB<x^SN
zEYj#s3_;hniaWLW<Njwp--SMaANn&`#0O;wKJtZLR!y%p!a40#y5PNx?o%0tLisyi
zb}_6KEt`}5tW)X^A`(=m2fdOzfC|s|8FDRA@uohMJhLHm7Y`l*kv~IEt{J_ziF@#j
zCQBpT4-~&ZuF<2CTq>VCZ!H{`gZL~NRO5z{p3$9ezeBNnRP7&bC*v@ZNxy4nM8HF~
zn(|;x4Dw~C5Wi*@p1p}GBeZA?uI#-++^yPSUhv$Ihyl`8Fi1^MP#j(IhW0niQM%0O
z9&Kt8Nfj__PpAY?249<8j_9V?8oVUH?0@U>-(yl)?LFre4fa*Z5P&^tH=G;|gYFu>
z46VW=<nJEz?6Sg{jAn6YMlG#|0vuD(OOtc218@K%8Vj`lLmQpKYX2Q}K|;u4bPmTO
zWB+1A!FWQ$HSnH`A#a!c#Fu6%0$b43@q&+LiuR}qX~Tn9_k%?9EGz!J@%Ho~v}7B4
zuA>y}yXfxJjqC0A#@)_ZE&As(8uddFb;Un}G<Z1*xOq(Xzb}M{=10Ic8>73_wg(h`
z-dn?OttaSPPSw#5jsq*V`WX#3-nTpZsLtWGQ0K5ikvAPfVs_Klb~DR!y3uTVZvAKL
z_^B%kf=CW|U<ceJaDTI?Q@;4J2G`z%%IeV)I_!#%$;)A2QtjR&)*M_Zk6$;P(fx#{
z>Q%emo#3HLU3IlG-QGEdl78n(@8WyL;7zRBzSC9sF*4DxFa|YUD#VIxurG-_Ith<^
zs;F+C&ZACHH}^p(fIh(egA+N9WQD6uMnQD6@qpxTaYQov{t%jn0EIbyVP<H7yLX7T
z#+h3V;#wCuZlcZ(vu-;PXa-Rx4uI4)Wc=G=&Z*lyo*JAm%v@!mpPRNoUZ$m4=@D3m
zYRd||-oD4Q;8DN&n3S*+cV0P1CTgon6+_OYba+>s%3nKOv)3k&z@Gp18bR9F0bR)-
z_^RK_@refrIIO?8OirxJKR>z3`D+Is)qSIV*>>;#5%U<6>vov`h=vh4D~ov<J7!oQ
zD^aw=f$ygPRo7>6mKdxBMmJ;-EhN+sRsF4O##;Cl;pDWj9DF?tKBfDF%+!wG8PPN*
z<zlF39kX_dF7wTM;YrVcdn^i!c3ntNm;~aUMy43n$b%qBm84yc7<aWo-Hs6Xh^}9T
zAWEw3C8k2A;BWvk%Ho%!LD`diY*-~3>cY#vN|DxBrfG3<up=l3Zv}zDNoKQmcc+xa
zVP3-WNnmnGof#Qn<xTo?YHmhsqR0W{eyiU(D*OUG>{}SPiX?|I&*S9O3NH60>oYZj
znbAz48lki_S)?j`W(Arq^#GQ$Jq1tf>(DQyFGc?PxJ^FK`q~aJ4)F9l2`6pBw9ksm
z&gpU48TQn@T@7X)#Dw}9@n`ak5Yx1-c<OJA+Rc4lba~Wb(FBp>n|qAto`95WsYpNz
zbq4X;zEw8I5s=FYj?!Ud8oUJY@x+;t@?`3rO;iTKiFR&Uu1y}B9icloIyZqW5fMqy
zg)9%50adMX{$FB)3?1tZIe@b9FT*Z<9|A^>D<EQCd$0_k4+BA``s`7Y;FDU`F!pS3
zjkU|j7ZsfYMM84@=t2h|&G^EH8rgL0K6xCTVDR8*QxWw{C|#th3=gaUC?Ar-V(H1F
z78e%dOge96uBWZS5WfTuKF7+1Zp9LWW5BoCq2fpIaDlRez8|>$2lbQL1}k?SI&E$T
zw!3zVXH4+|{b{{v?FPX1_HH5}<$Ye)zD|iFE~i4Hb&&cL&UqKRh_1MMS5i5k2?mTl
ze~?Mx(DiwUT?n)ERX5;a$gq3HtTedI{s`LAxxy`$N#)Hm?0Q*sDiFy^1rmy0yLh;;
zL!gaE?(H~<<&d(7`w*Q=$wA4zu&MmYRGMcrA$KJ%9(~WeMu}MV(FLhZGY7C=xYWk?
zd$QE703M#WHt>RyBNfD;gr*_iaq>`pfj|-XsTNf`fug{p@AVT`n`O8|kq=;XZZ3A<
zkdIY1uE)Ig{d>*Z>Zzl;;Q{6cCk*<c>(wOLbjVmuC4BwHKO1(fyU3?Si*)<`S?6kv
z+Vjg_{_8iC5W~h|<!ilu17lUuqSLeyP#oyxpwa^)$9f8pML~xpDR;N5qheM*k0xDe
zrSz40r4@a>jxk<2RV0nBN$6;wd|b!WGyaeyunj2#w5|8kY1P1U7ikP}_^BWWZ>{Oh
z!!6Vq{vPj^GJM9KM8Tx=v8d_{2mlxf#VZT=_K9Z@%_m=oeknJ8CQwX?KdwBqd5BMm
za~}~EDvAm<H;O^6E)S@-8Nbi4A5u!^e6;ve;ei}$OPSTV@X@+}z>SZ22-`}kzcLAH
z{I0h*Cn0yi<ycn=8|E!crC-QFQ^UznHHs|(uGJMv1R#0kH>o%aM2_4{JZq}xc|B-N
znZTyoD?wMHC%*gyHKx!;wX65uE<#W3I2oXN9|44yxNHd-te(b7`kt&sE*8<y>cT%Y
zt>z>;J*PRI@Ab5-_p(9d+&(}?2x_|b2dREg0`e%IOIX^g+=v9<s4BwMl(Q}<B(9KJ
zO>TbtEYT^@UjsbX{jG=zN0HNdSA`#QQc=SjbjF$2$09t?@dv*#PL&e1)XMJuz)sS0
z4Abac5~q9u@M#QxGVKCahNZU6zY2gyFME`KX3z?>Ex*NHdP8%cR4wI%qi5qW%AD6$
z5rNtEckt9kE5ZKf#QQK94m$$gs7W8#m;yOh><~4C-U=c~l21O=agjk-Wr1~DzcAZW
zEgzjQ5i)l?>J^wna9jr3XNJ9Sh4%~H*pQHm!i<*0uQo8unq#<{?!P`~+xc^wi+yZ$
zHBmw0I&ZB^$JW&mfDRQPCG~{!PqaF`gq^l67d-pqv|uHQ#kIwQln4h+D7UtgRO_y4
zSd0iB3xk4*i`!Ath2t(M8C(c$Nk?RqvSizYPvwybuPlc)6Y*H9ShZazi)v3v1qv&&
zJptCH4RNqUDrxnE*C-!$8FQVW<+<`>vkr*B$4~>PHiP+<A|j2Lxgvj4mI&wirCbdX
zV@bfc@8;l4*8>P@p#lec4Y1%K6JJh5zDvSumc|}?Wl*=!0+n&3Rx&_k&F&1CVX?VE
z_W-UJK6vcUM6TA&GUW*y3)W_~;dO!T<lgxf=EL1~NX^XHXlt<pW{0hC!mnF6YwGhC
zev7N!Hz8985$Vj4Wa8MTUnEhFQ9*%Wvnf&>NQ?GX$~(P@VfTNkSH>D<O;<T}mHRDW
z5C;9B`D{#C<XvFhg;$`sh{-XqV3J~NrQ1IGYB;B9a8k`;Ii19)xDZ4=I(~0aK;vJF
z%i0R6QW{cPK8(qsBqeU+LvUYIZDr5u=zSBgITz)Nm8+4j400q!su8^lKl((S!F{CB
zKhgzEUQja;=}B8b81~{f8ry<{wlWG|S_f>_XJ<X66_t7l!rkKL$}NYA)C)DKi*GT}
z8F@s5CvQ%vH<mM6=T2s|$-N?`GDgo|X*g$CAn_{H1vH_+YWnz9Bf)}vCfT6Sd77^m
z0dYe_eo!w-H^Obi(SMq@2<IT5Ls;L3>)pO`{;>jOEra<4mYk5eXry@acTOmB5n&7|
zJ^wDP@J2&%++QLyK(5KsS6f|^KL6IUV4ET*c<j;%eVShcM!}&)U2j^wsz|uq>l4=w
zKQ#=^^$JSLsAe0aa&1r%Oqqxs!2KNZkI$4OEwsO+qYc*Caxp<!vO*605>NNd&98>^
z(QFfVT%!30R~BO6t(fRvqn~(MJK}Jc@OnjAYhA9vb*kOr<JJ6<{}+yDk~P_eWhrHV
z)MbKW7s=#NcQp*l`;`wKP%qZRx?<+4u1N(Tff@t2vI1b!1ko;)#Q5}WuT`)B)khjQ
z86<xhV~TqQAG!&VQ_*0uBe-^xSL!Iz|H`)OzMWjWzed0<M$!k%?00cB&VzxpsNXY2
zC5n5{K`DHEQ7-dwm#!ybMhR4X3|V!d>TMG80o;3vKR{Qn20r&)$l3xzz!*|4bMYBG
zNTacE4?#pEb8c;x6e+7iG<%OhIk%o7xoZ`XM#O8ct^UWOt&=Ws*W%ro^)|=(g1-9}
zULB(-zG|WwTw)L-C&|XdH%*8DG)w>`a=~NHW&@<HR+fwf>sGIJqWB`pF%D`Rx)*d6
z1<!L2)g=+_Z&KV0CJW)W{v7FAE~_m^VMea?Q%VKthzuGW<SAn`uf|bgrv4ity`nnN
zTem_d*k&T}nak_T`VZyEH*h!NdV_71ZAG6`HqsOdPd-}cj}Rc&LLm|ju7`X;5)<Te
z^7~kgT90-?#O@&9x}-HfKoyfid(fP8U9kG&kv$pWslR(tKj_-GmvFcVxea;BzbqvH
zOF*>0=wFNnoRz~4WRhNa<E9`}QbW@Uik!jlU?#c6>kM_sw++nvPXKoC`WLF>hYPVk
z=~IR_d3B4;GnfY29O6GhtmU0Qq_*MgB2(~Gx)%bnee&a(JOTb+4#~3%y;eDm4$!@f
z?zQi$jZ|hyapvS^TqAGR-5Gv;#T|e?abI)|=V`(^R)8{U>LlSlXagW!^zqkj@GH;;
z5hTllRvb}(fJbYR`v2o%Bwxf{Roq;nv8m=#1UqJ)+!^3VElY|_>zN@N)f<)M18{~!
zUzYD_vk@C@8@0E0Ure#kkWkj-h;`%`w)dm8&um&S8y(aXz$~xxm`o7NOacNZhFps%
zfZH5T!j%Ys)__RhGC@ew#Q|b9*a7qm6|*w0SxuXV6sVpAa;tngf2Rvc?qtJd0{Mns
zcF#wA8h|q@^<5q;B2g>ueuhW)DhukuZM?5|i*bV=dHPzjR6NT+{=}^|w<*3dIy$Et
zug)1SmTNDS?Q2B-B9b1&|KR{pMwM;GeAeRD(oP!@0IQSN@-P4R3M7z#ydd(v-b6)q
zyhOdo_nVe=CIPo@pr0)=%oVcTEi3wNW~$9i^}sfP<l4R9$Az?LK!5O1MwEnO019o_
zlcmQq4Xop#r*m=t5bDf?q{KJPzX$3pgVN?tgrtT5dJm9kN&RSA%%b8shdW!OxY7z=
z8(6;0Mdg+0=iS=|C@^?hV++=OfeE8k_d~pfN^wshpIZ|H=M6N|&OczRjY#Few8RQu
z4*>P*CeT0gFShA6ycp$4_gc*Kw)sLDat>d4>erCsT*|^<L`y-|6^a|zT+&X7Z?=nm
z>)v9QrBFz?%YN)Hlz{^WnMQl;;ZAxdO-K{dIVmp_Ls6i>m&~w`X}?~9EvYX}plGx2
zKK-ymo5d6Qrs;PB6x6#KJs?m;*-o`8=fl`cu<=Sd%V}`DV#D<92U(t<Q3oE;m&@!i
zEf#=j3ItV@k*&X8F4Z-7BPS|vv)?E&w48nf31m(@Yl4-Lw<IT)Pyp}Iye%?GJ;~5c
z{LG%*r5i7wABC)xdC+{o?rof&)Ax&IYUJOxA(3=Agyhe*_3PU7k3f?IzAZ^~O-l)C
z?khri<V=Ui@6t<NEh`fozFZ9NAW7r8oZ{-nJ)ckAhNtrb9GARo+<Cbiy~}$gIo0Ct
zb`+nB$06N>dSEgI1mbzEP}P3)z#%b39;dF5v^BUuW)Hnz7MBhc9=}yE>2(W^=f*a?
zq^)2}S*)=Hl;dHcM4)qPXs17zp&A0yeBSw+R(k<maEpHYOJrF~$@(ea#u;flTgmJy
zU<EiXR65ku;Z#cJ;%FC-9_4S%^Dp`I7-*leOEIljmSx_AXI-g)75NRITV`Ws^Dyi(
zZu`}DR<)}!zmKI>cpk3zg^-GW<lB$Pn2{J!l7+NzHFAXe6QgMy$C&NS;E+>~69^o{
zXq+%--~a$2yr%)L-RF7J$vDm?P)3u5<MC-wl6b&pxtD4uGL%0mRT>2JW-o?$-x~Hs
zgC-#Fx&-0f+OyS;8{`XgOue!jMPRYzK#{{YkX5Dw`Lz@^pg}RlUdn8!>fHGSDsBG^
z#w?+P$`hYDbWKPjSy)fHiIeXd8{O=v=gM>mZTH~4v_gkWIMDJGVB;D&=J99Y$)BBA
z#_K5O5G!K<#`S2U3Xj`JikeBwQvN%BuWs(vUY<adZk-nP@@>8oUac!w%`bajrz9be
zHx9Al#_2Oar?uFX8UYYM7f1jnJ*-Sh_!1AYag-Cmhq7TtLN^aWvHbmWx4NZXdK$R=
zrGzP<*^ORJA0o3Hc#nG3#lswGQ{|A4FQtY4a#yo&qQ!;B-r*RCOFW2t8qNj*l@j8l
z01RN{&lyTnTs%W)eGXPIo4$&hZVHnJe6u{PKsSRDEi?M{*aWH|_ajoKCdo8vE4oEP
zrQsS4774TXb~uFq@&49gWk69wsIOhgYK##bWdM9(bfy6FRQ>8cuJ&oO#!6!MHVM@=
z?RZ!yn;aS0GT&Se<iP~=TRV+pD%O(dfyi2}(_R|36(7O*k;{$X$LxvIw%6IDgVRB(
z3bI>x5xrN{edq&7en((n_XKlgJ5AwIibL@+qTnx)9z<0iv3=n!<%hZT6ZEs`5whoi
zBs=FSaYW=su0kf9R@2Y83+U0IqC05rh+&;*P7X4)9W>uOD^EfiZtA;GamaY5Mnn1K
z(z7{3KTV$eCj`@k_*?sGg8Sn)_?Zm!B}h0?oMqph3*(F;qOOLm_tBW`S9)6ovE;z}
zB&8&-w!KHyCs6Wt-{yQNg5>P+Kz0X?@p`vv@Z+^6Y;YFGjpWr{hv33NXC@-&fFZ(^
z2E3}i><ma041Tfdl6{Qw<CujH3iKAYF)rc0D%nx1af55i8E_PToE%togaaq#@GCMg
zK?OOMk`ls~Qa%>AhDEqfY<&#t!y~`@o3dnI{ahCYz-7-K@Gv86iuh&l;g~`}u0cmD
zfryGtuW-JpnHUklsx#l!402)(ELaqW&`eZTJ`0v)xz1~P#Z`s<9As+OYk(_<f5%ia
z{gI7dpo4doYQ2!_PIT)$0+-+M<lXFE5PdfzRLws|&OUV+tN8(FTJML;rd)EH^u3xa
zHAi4C0MSe)%+CPkb~qJY7KN|lS8;>()3~xrxOH|}a}2rU<squK6g7elWG0PDGN*Sn
z-C(^tDSFMvj%g>R7PV8!^DPMa+PK^6n^Ux3Bb>>HE-TK4`fx=**vL{O0bGq9*h2&}
zXbOd==zA-!os3mN8Xmh^U(c{rgl5KQM&S6+%|eBW`O>VvV#lSk)#c1N+;X1em6CM?
z7P&i_he~+7IedxZhGqO15my=L?(1Jd2UC1pCW@10K;%Qy(Fb(z<yTks-~G#b^}%Aw
z7orAN9hD0^{S+X8x8$npZgmvzgV_Mdwq8eNgQFk9_q>Zg=Dj|P#{QVrsqHnid+${6
z0!?MSH!T)gz0-_1-w;i=&67Hm?=L4~nGBuQO)>MGK?I~ME4k*FASf2lA!H9es4B7S
zWth`2DS+rY-7er<blw{kzH0^Q4A>0uW%D!VzG>O;_^dMAi}NMpRj@xDcQWp}<mne<
zlNa4Fp(o%go+vIF31<SN$GHdt{p8SW?E5wKUkK%(fc>=e+EDN1T)ZkmhhqE07d9kF
zU1{_z+Jb-xo()KxNwVFji;Hc1x(o$BRxQBQPlwsAg+<#k0M7n0V<8HSKmY)iEhY{V
zi1m(d039%w&i8`H*&+)KpS8<~puqv<Y#x3|Uz4lOUHF<I9DML-f~$m{m;!|gfDWU>
zQ$`WWtDfV#2BQZamNljP$~AM%M-bE!!~S;F4U$aIJJ;HDxJJcd;mcpG3?rMv6Sz=S
zmdYqGN56bZi}M(^eg=#UW10f~vC2I7)(>wgRu_^_jRVFzWd_$IZV`-Se?UE-uRvot
z@sK>Li~K4&Zb95>duONH>epgf&k+nqSY3I#WfeoYS@Qvg-P|fN^$;Rm4eH5eJS~f6
zF<rNFoh6H^p<C5JmZ+kPghcZw2lz@rY9dlsNnNL80LEK3qnz*(93wU+20o|0mglgA
zGxG4l!uF*f>7yI{aLA12Y_b?pQ{UkTI|#f(-8BeXiDqS@m4*zQ716q})B2aFrV$UP
zGKRE~K<0qVkZP%0ls4D2;s}aw59_UIXWT#6Wd7ficcBp!CbSi!Q?T?`iZSYp9C~ja
z&f}J}2*U*tg(^SQO7mqv>S<VO5z84X7A1b?5N_GcQII?0`Ug>yxoPtB50#c@ELGKS
zM;G^ZLP(9{pORrNl7$74Xlp1T4i(VJL9@*td0&~W2RqgC1KjvJC?=5qLpr7Eh4d=^
z*yE%l0~`3CCoGgb=9Z-rDu)XtO2vrIaA$)GA#=9?cY1mqsO<Hy)jqI?ZL7#*kZmC!
zou~R`m`Q|;1~#qIUf@lt_a@MJo?4Q8NF;z}1VHHc{cRG#5ltOBVYMlS8aqN9<SCg=
z9R+=0?3=vQ1=#s}==iBtd^H$4?H*&jpftchMB^7Of~)Etn<JX9MMU{_2&V!xxiDtO
zNVOm}%mqOe5ibe_kI(m%9kU*`TIR!WmJQu!FG}8^MpD>wr!Ytx!7;!HOmLVIpvigA
zQcNI@vC0V8eIgbJP63>U9D}^NdDQsr=!J#eIn;FH?nI>0|7e*f`>bT@gdo6>mIwo8
z_`J_7e6!AB>gj6Mj(`jKQ(8hidIT2dc!nv1&%~R3wpzi7+U}p{Y?U~7!tkUsk$)UY
zTA1z2V~bYl2MGyj_wlDd=T03pQ~MS8Wga}Yj<w?)FDyj5CWkd=uP3#9u7Wo;#_^&4
z704fl;&P2LSKT~e8(!Jq2y;XEW);|4Sz#~8Q_$M_@b#=#fS4AS-`3YO&|}Baw-){V
zzW98o1q_+wF6!!!ajy!58H5r>x+R4a`^QNetr?^Q&x0o?LPyb%{jx05{7iT+uzOd&
zqmIm9(Xd=l6&6zkeG3BM7MMFW(#V^i&+#U{+^QC_35u7yd*y&<_Fp-~HNh^IIO|f~
z$+Eu8aQ4(N&x#zqsV)4#c?;mt5~R`$0VNv+PKEPL1N@FR_7{b7vc}clP|@^dMfbO{
z26`R;=TiPTcdo?_=w@lG`oY#=|LQsv$0zS~{?kzLt8x4*B+z`k0viFrcxsBB&=F+-
z0Em64&^e#Fx+LQyyW2Dn8jY}!UQ^-MOr|#Oz}d!PX}>~iaB%1_3hYo+Q^{#CsP}=E
zpFHI_V9O!V#ZS)H4s9KDvDf>kvYOq8WGZd4g6gV(PvLcrjv!+9%m*WZxQIQ`A83c!
zkmvy1LaV2%dDkxa?x#+FAbQb$1~RRjDgAZDL?OBTo5vXHAFd%Xs9k<Cs4*r)iDbZO
zbT`in3Efi8`x0RkD-M*UydoqH%7Uo`{qBKELWyxfXMG&DRJ7?g#MjVKm~zj}>1mkA
z0rvh9X;RDAzz6>Mz8eB5w2|J=6f639&;T195bSL$k($H(|De_JD!y(41%S;fmV#(l
z=T{KuN~j22V`&fE%CrqT0IcY`bF@s{z}RJUQ%w(@8oM7MU9E563?C<vFk)C_)Nh4^
z4eX@@O>cPXZ}XB?>FC6!@mf=2OzB1k6$>B;sJ(FAnROE=UkVAkXf550&4D67DqoAq
zM_*y#e`@(bv&Ni9sc=I*pdara_U!>69C7{+y9^|->c^OMii>N>RQ%~(wv*jq7d8km
zlI*C#%ki<Kj@7#M%~k9oO*z+DD5e4yuonokm4^AAbp0dLgmdz;VOiY|lUeeW*VqIw
zm5iGT_-E5p4{Orh$9V1)u`&`69bb|J$5kJ)TY>7zYKpKC_6SNdp&QDmE#gNJG4pQM
zQP^>W^X&lQe~vOKFfQ6)9=2nt&4tJUm^vAXgp0QU?j!k4Pfb^D93*_bhHhbuJcHXu
z9U)-A3GK!Wcc55(HeWy@DOFp#jCAImQ4;W@$8mVJSKTNjUDNxjVogXA((9dUu+k9q
z;)0-^oTc!S$n4Pb-St%aGYSg3f6dFz3V<C~daxx?|3gh{f_XjlCAjw{KMp5O!CrjK
z#f$*4$HXp+q9?V7nonRW^u1qBxwFw^?}iz8RXWO!L$2Y_G$E+BZpYC-!TO1Vobg~~
zxRujC!1TI%F`f=?y~2JJrH$;3vxrMKbNT_kTPOE#ANh|@(2&bTYr0F&ReC!Ed~p~F
z#4h#yZ$>g$N;DZgpi*%9!&#j$OnPigtjy+Ce3-!C8)T8-+!h*c=9a?U<`e(3-k4<@
zti6`2g+z@k!uK~LA!b`4^+@_09=cRV_8~Y)A<Z2}a|?qm4M9EtRm;(*KUrPt2c2$n
zMe|pvNwDud9|+rPZz%9R$5*45-A9928CjWY+GWb<_Y|Vqb8Xax8zjTF2URWrpKMAb
zO;Z@R29Q1ZofbFtDIf!$N*urjhEE=QH25A)(=UR_MZmu`ea{Ei<Kpbs8Rn+dqe*Nl
zvZRXmfc|3#F$^zpAqUw740?5L3?!+_QyX1`0IwIwdfk4XuH)T#0F!{y=HB&HrfgdD
zU(cQQA3s?s$P(iZf?la)Qwm6_j?;n4PKT{O?%;_G3U%@hU(GBuhwb)vZ{5rJ&`xJa
zs~040NuzCmZ0PvH^jWg|=QD@fGi8aOy|i#f>gwY-s-dL`PXjv9$mkfxJ*Sqg$^myM
zTdxe%jp7E^Z#jdqCgri6+vQOUVe3H|Szed_-6sXOpo_y%vwooH2q4jks(Il&2R_6a
z1T{hR0kn7fd;tGaO<SfXuz{q204+$+1~gc^=(={w$&uy0<N>J7*CWg(e641@3iM@A
zM&zgCvZrKdc#H1B&=}tXUDPfi5LpNU^<LB>X=)Y8`Ox?&@s=(m(H?(0?xA@|?2}rO
z#;KWez|>!mliq4=&9>OqHLOVBEXO`|nfjaYh!ude)c^$LS@}brTo1COHC`ta4@lV`
zep8@jag*cgYUXTBQzNj^pAXve$wG94Di$#rO>Mg%1oR!h$AprGUhqv7tEnS0e)vFB
zqrX>J=b2COs0Yq`k;jCeC_p)Q!Dlyp@W2c~<rMOS555AEIpU;1<rk*_@&=imj~IR)
zZq<y7H0jYu5If;wI7S|EExk}svk0zcuwXfPW`F<+2TC-@(C*Y8bYOusf}>)E-X1D2
z($%N44+WD?E+Dd0+79G+<K2XuY!6WL@LcFv-vT2+U|el<y}tV!nZe`H_%0z+Jw+OP
zw=^F4|Kg+?n64xwg1{aTt6&A16_Y#0V8T8+Uo#8mw%i6J#C5WB_@I8ao(#K)F6qvD
ziESNc`XgU03CNB$wB`u@=OK@kQT!UW2bPy(R1|rwc6mJ*jeQx1eeqFwfWMmXr7r)d
z^P2-jxkXN*$7vJ=LLw=65=|Q%2vt)`*aK0c`*CozqB1#VH6W$Qu<`&4PNDTcnGCA5
z34SbSpQUf=P&F(TM8|z)NzFZ3=uX}!1{u~uer3}vAt_oOV|hi*O?b<Prsq6+`P0HD
z=?$;Y-k6B&hI(B|-00lCGSJ>&TT6><|AiD`pjpztv=0QZWOR#`{P(<MO5^_J`T0(8
ze;&oOuiwqExsPZzJn0uFIECD2=XS#&3r$sB{k+>Hi(N2|6L&zfC5&G20e7d%PrHcE
zEuq5k>C=jRkI12IbS(RFFA1ozm`>0pz%FdQZt;s+Lly)Zk^-tln;dzQF40U~QF2);
zh|gk8B;U79;hSKX*WgZSupWpQrNwIajr6<&*!Wv>6zSb*`~@j}@}N-v2iHx7uN8nH
zV`FAr2A(i?6aKB(OO$o4k?^M{t|U(^GjgX+{A`9}*YeB%r*m!3YYE~AIs`i`35(WP
zDqpqzTuYdI9fh1PuJ&OQl79RC?9&%+)w*i%jDT%{C=q%I#<iiIGNYn|^#iR0?)gC9
znyz}Nz?=t?L29hX+~=C;p<%h|gHI17lZ((mA(*xA1S9A{<*W~Qyn`o@Nn|++6iZ1C
zp~LeZ3?!x^_x~z0&nb@xBIr1NZ|*X6V-=Wi<)n}#8#KS_&{-yJ(y8^)Z(#%0ttbx=
zla73yifh($&i{Haek@d$NHp~7UYLJN_@kEiHl6D8w88)T<!H$5pPs%oRhOrp1~v|C
zLw;V-7q#m(BQiOu?g#qzo^K!o((F}5g3%>ctO`mTKi#o(1unqp_3?OOKwy8x2w&td
zqp$v)=BkQ#Hfb9O7f4L$NYv~tXU3i2@W<$5p}IPI{FQhTSk+5Qd~n}<t~N#IVPONQ
z8os7z(^%EvP>=&pcbr9k{fs9P0d@g9Elh^YRg3ghwn=>CAz1IyOA9+6wV*LP$IlP|
z=cW;{-e&f%0`D0#YGTPZv`XnuX*tD(7;c=#*q$W7aNr14D0`mJ7j%BS|Le2qlq^()
zAP@v?oIz=@<NMvk%!kw}jbBh^M%}f7D0%n%=VL43iNk4NWPaqG%%2o*L}IrWOHhb;
zY{S1^Mc6ptEZ<UBkJw0~iCnb0xh3bYP#5lu+WC{qzURWu?NJhx_gPCAMCl4ofh;xY
zTtK^rz)qX%7|GQ6u#mOyEV5oP^aviK6t3<D!Y)$zl5R$B>=|fdl}ohTitruzfLx`(
zSs6f`Kmu3T2r0La;hr2x3FUQDF;zk_WQAnVMcL_3{MkUfoUu>fNHw4D&RefC==~w^
z^kJ~X$sGVEx9YI52LDm{l$NZV?H!)4HUnKV=BNDKL98;I9DbFPX43N>b&ev<J=D4`
z;PGDkIwrDb9+v1YwC9B4;Rr0U?zu~}8FFT(MMha%fy1utU4PxxafdnSR@M$f^kcSI
zZXAt+V9$=Ov{Tv~C(eAzED9jA3%2~xt$i&Y9&~Ql>6(NuPj~cu%{58~l!-~2OzS>;
zAJK)tK!-?L#G(|p!@_pR#<R9>nF;{n1p>wl?rY)W=Pa%Qcudtd4OVIN>3hv%sSa@(
zg)PMdmw4aMkU*j#qM$b_f&h+W_@_<r^^~L8mChp`<38U<pW0);&9~I$6iRkdK14WS
z=J>9O<)>KOrB7ioLqIOV7vOW5hynB2ijjtcDun#8A9%?$eF%USN_R@Eq`(i0MT}A;
zL-Y6zUC72pq24%&;56I8e`rx8mFMLXUd&ek!bj{mnxqCL9whC=Db{*YA-DCNTkNT3
z+!DT6E_U%rYM|;_$9H}TcS=+j(xUJL8Iu)NH_(c8uqnqA3c*E<A*elkkbAQ>?k5xV
zsdoZ@e>shV^dpamo=BAR6bEZ!%sQ(M0Fu=+o}#l6tLS+jT~^r}@DOJxa9bZ}-dN~m
zE&vNJ>E{4_^x7c{O{g`{RfnF3YN+N2M*NFk=Xh(3$Qrl^2FB+W6dHv&LmUk97vZrB
zmX^BOy{7wgs@VRewBdwCXUTn5oWvO+<Uw&SGi3(l!*Tnj)D=Td6s2HO>DmDwM={zF
zG4Qj2hqKURJ3$phfp$U={#WF5$BPcnrx&K~7^t;z7Qie!k9|f)g9^FfXZ|Zw=G8?(
zt~-mVvwgnuea~NW01YyJeRrv1>aN&icUgIzUg-BtK3=Hl>~j(;Rm_1RlbjUynt#fu
z6`h=T+{<H{F=E&#hScy)&8#sC35F-L-H5D^X#}dgNm#0d`TX6!Rr1D;tDkxTgV$QF
zNo15i$S+kg_2(*w{Eq~#MKA|%8qTOxkKuC2_9I^lnVIN9kES%fZQBMT^_05TwspP$
zGnPQE<)i()^^cN6;xRUEq(Z=~+1<e)HW<0E_{ZW*mUK@(tjHQTphPE`Qu#Ny(8O<Q
zlYt}Ly-5+Una3VykW19~J<Tqg)>4J;aT-=7Q7ZUIt1Q4IdQjUvpb5F^c7<s;I8fIM
z86hQzP^a-jv~lC<qI&zM5C!O7{EN0>%)mBKWA2`@UDQk`VxKyPz;=3j$O?~7OhNo0
zVb3T43Gk1{-+5+n$Uol|Q3^^K<F>W95pm1RSIjZb>)Uq~K_AS*RwhkZ*n<1K84;G{
zN6n%rpKq8RND&=-;JK=ZPYmIyt!tiM+KyP5UlTf`Zo|m5^?ij6{aGSaZ|J2QQ!ksm
z!{9l%ER|7VeOuCL9El<6Jo2gw#pgQ9DH8@2*v_wJmn***I8j*UpR8{W+&si>YC%XU
zmA@S)9&M7{?0{)kyZn!n^{~B_SOT+!ZjEvyXC^@2wD<h89_gE0|DDK*y!_uqj23}0
z=O4|i<fcEl9PZxIb=Fq$Zm`6E9FVOp%+J0x8ts;;mXr%+L^_B_I>)b{fr}9tR;Nkd
zl;wnyAvfu`5wVfOIXe4#CeM!Z-S)JITK!ZpkRrZ}>a*~f1PEdT3pDkxlHl+^gxMJ&
z`=i>WVws3-w%WX;Mt3zzyh?9cEa;6tN$`B6!b;qT!<X%2ElyQ<E9(<wKC6P7TTovr
zo;!fm{rHO;`$x7;{w|SE6j@-as7nCh#I?7{S{biT@lps$jIc$;Rp2^pPqL_(^)QR$
zNub!rg!y^KzofNrz&eZofEoJ2-rI08TTH@xoV4qc9UiK91~oVn3PkIHK5Mfyz3Pq2
zX=IbzGWtI}z=xOnhgz$4bA+-0&c+?0<hN5RKOFJc1<;hR>wxg=VsTLr9dc)tE3=>G
zRF3NmQ>(saY8!tQ%oE+g94qRR<M0EpNzDOrv!oiQ++);a&rL|wyeMu~WJCbuWP~wS
z63oc82C%_sqDTNjcYy#-ZXWVTn4`y`90{kOx=yEvz^Wg$@Hc2$U_~qD-+XJbA0Vgi
z>l3fADaHtmhnt!_N&>D)A}pO*asN-ju<F=FOMVI`03+wB6168j!eX#u1!`^xSRuCz
z=1i{!z`A9?0qk7VD?6prF;KF^aBDYnk=IDBg4QTA2{d%rIpgV$w_7egP*&LLAWQoD
zP^PgOK|?apSqyBz_<-t4LNR;1*3rH2ki}~5w%5v)2&+P#s^pkyVH3rHwkS`Wbrei7
zsd4cN7yfFOpI9Thvo>uE^o{NMo=|ep&U*c4l;Q9@;Edd=>h7iLNU$iazfKCCYrMCv
zQ#k=m#4_TdCXx&1`w>jre{oO2!@l^Tk#0g~amV0w@*=94YvjEgonA5`0NmAbWZH2(
zpaTF5UvI>H9zVjh>>Sa|54FkvN3O|@-ZvpSY$)ju^xbW-Xqj_O)bjf6#}fz&QnC8(
zh8dzpYy&vSN%Vr%_xFbo6^7FQrWm5_%Ed_3;QGJ4b-24=D{==G<vmWNx#ti5LOP$(
zE2rbvNsFr>hYkravoPqHpa)^nZbD518A+UXg_McED+8tYVz&J^!Z_*W-yUFgV=-9i
zAgGhOtMr<#5v?7G!9gk`E!1K|7v`H~OFcS{I2v1W;ozPCm(TalydoMmT80;DILM{1
zte=~GP;iR#;>rCFxlQd+=9c%B4^T{Wy!9E#WFF(*ZW#<AzmhCfib`3SQFpG4xR#ih
zG<rRud!6^3!Bl9xh2x{fVDKTYAg`Avg4S`7MfeBbO2l4z(5z7OA+Dx|sFc4nEdbHg
z>aUq#92ocC{?l)83gHPzVl9}Mj1fB5me5p$5WEV(sS3am=w1T(EL24NzR&)uP>47J
zzEyHSTjzAE6Q=BRD7L#;<*7<xQEp}Y%y-n)BIAiQO_66=N$EvP+U#AxgJro?QmL(P
zg9G9b(uJ!u<}%NT_e#PXg_+!wxQE4Au$N+ffGVrMvC7pHWgryb`R}6dxnP*q3(6G0
zFzmFq^bi&DyyD)!&2xhaU1ht3wIjDRV}%#FpV@s8R!;_3dt{=@72H&l4vZ`jDUr#4
z(Z?m1Nwh`{zyMonR)3Mk1&g=6OK)nJf-q9$>H3q*biN%<D6U7@l~+q`cOxbPSQl2e
zL`6rPb6<o8qiUUq=CI2qdA(?*xci$_u)yQW5ka`Dj+*NooI(ttL$Ne~pf~_204SB^
zL!pzq+xg(YFTf2Q(IKUrFVNO~z@Qft{cqTus$ud#SGI7C8LU5e2e?KP^TUvz@@37V
zZV>cwt*<C#x>}TkrXR}ZUIpsrqQE@So7=h^U3_my_XI+?>Q{TfTs&+Fz-)(983zDn
zHocRS0FG;7dbBD4@ux1o>`-SaN)$%~A3{0c6#cT8K2itd^7xPwFPoU)xKx;~*&oyB
zY#6XE%*BL|AIZR@+<Ij3k3@X>)5NfcKP!%R3j?@10PCHf+`L>%bs3go@O&IErwEL$
zGu~R=000aIiiQdQFS66&yAa?dpQ>ZW2EEE(>~?#FmOgxkC{x2skX2GEq!%}PVcY*&
z@r1I4Xla=Udq&y;oP4uU{(p2#{3SSM7vVWlWJpm+{<+exnzfjp$qrO0N}WH`A9mb&
z5BS*zf!^hE4y>K+E}-k0_kkR0QEyHFRSm?0KY@lsfWLuo7d?S`H@XP4m|pJ62&iKs
z01OBNdcwggdXVPWmH&1p&YP)4I-g-)9n9pjE@<`p2Wd2_BXhPrw=SPTFkUP~vopF7
zLb^mRMzh*4*P&f!1^upc_^6K*<h>WkTyhXSrlQ4GrJy%1Ke4lEeHyt9ou@1If%qNF
z!FRH*BAhkVG5G-`WoLQ*Yw{ANjQIK}ehBTrKsFj2s?G0O1GQ*w&&G^ubySnxpcaX~
zbObW-qli6c_70{oKM)tZDdIuS(EtceO#}AP1=!T8#)`{^^9Yo20?RE<jo#w4H>;;Q
zU%hbzSNKsKM+si05j#2$oLE+anb5#sjg!F$```a+32Uc=!jya*kLF}f+bGE&o&ve7
zAW-s=X?lgj0Ml(5Ix<wzl|hVp&))mHkiaYFl7d0vBEHm_JE?n)&8u)!zh9+ZWu(>N
z5-s*{)PY!_(iBY+TD??F9JZx{voT;`JSA?Zt6pTv33@Y2xU2NDA^V-Dt~h7#cBB3*
zzJ^Gp#jy^qn_9Bw-zh*R)?ov>Yt8>s$B>;FR{{fD?JqS9TS8K6Lukb@Qqks^7pI+e
zC;Od)w$Lr)FDRK^`j_n{G*3VlM^Y&tuQZotK2n-@S%75N@I+AnwOISlKjAt8mv2?a
zuRt6(nAzI+$^|Gve=fvePu*d{#w&xZWGaX-8f&Tm=EPIyMTk2mr`?2~vcEH!l?`Yk
z=}-}S2#8d`K^hBDp7j&wO^jNSV-q%!202MR_->1q{%%$Y1aYt91CR%bk6Ap8i?|wW
zv;notH_LS6W$s09jdzI;rTd_wn@V%!PDM49vbcR3+qUID=&n05Qzr1w0Unk70Sxjp
zb8laBZozdjq|Pfx`kNE;j((J*Qx<AXfViXu)UXtYCI*t-<(sC?Qp@BJ@HhVQH$_BA
zuKPBc8(bC6@6c%Nv&33GW+Ah`@p;Qcm|w?F<&kCTkbCqD2~^9=k<A0UW2a6OKi7!5
zQWbaw(~MwXnt-*WzCe2n!wuYqk;R!~oG-Ek|MEh`39J>gl&W3b^QTc#$9RS2aLx4y
z=PO6rs#{8ChS8tx*a&FGn?wXiU@iVln8AJeI3eMzD`p@`JFjY6*Vt77=7YJy{8{sM
z=MA32?KdF-Y@J>dbyj&LSJIrToN=?)>3ft;X2LZ@DSw?K$pS3;Qr{BXKkSwk^8F0Q
zP@@4Jkn3r=sa@}&hG!cwBdCtgz7hY_hV$F@Q-a#QlH&k+6RpdhYL0-z1m|<|z+*ah
zMVO>E?y6d9PPpQnYJAohPYBkcYTc)2EOG*4m$Q%Ybs%7lj4LzQRb~ZhQ%~z{Y+%`P
zcw$k=%soqxzZ$%|l>-4*&EPWmy6H?qZRtEag@N{gjk_aD*D|T6q!Iu;gD%BJ)q`>W
z$kjHG&N$cHB4Ts44yB=tOsfHXE$K8o>5^VtC~nuweW5gL(8F$}&%P~$PYHkk4i5<6
zu|d~&GT&bkPRdN}1E9eCy-{rif3pL|@h+kZ$Hwuo4v9Cnf8Ddc!7pMpQyj%nEAw?A
zKU-b@{{TUzte%@0;2;!Vgi;U17Pg~;x)J`}S&-L_a?brW<7ctHzkEZ*YZWU+utEJ_
zS(q+wU4>{&sfvxgh4+E>vfh2_&Rn9VOf}>@B0)&0OHDioKRAWbz-JS(w%Q36paLx<
zzu#3#I)OV5Y+F@|#R6s0H_0Z8C{^F6t5A#!wtE>(ceIjeZgg56gi%a}^mUCfIpNm>
zLA=N{-lqi(1bfb=2hdTtN&s))<|;o~8IHGKOf1H9jY(x_l|laUdc3y@!T*Fvm@M`U
z+pb*EB?mO@FsA6Rv3AGCn=uE42lyCqx8cl)7Eoyi>b@>4D+4Y%Ax;aHxw<vRt7iSM
zVaZb#4*;-f4lQ&?x{q|GynuU-12FBk0*7L<9p<waGp;!QIPvCmF0EGy!2it5`$R_}
zXcbsT;IaC1=}WKoh;t5Q*0}ES4(Hx<iP*fss9Ewnfw%<(B6}L)foC9}fS57)07nXa
zyPnviKPKCic>e@edm6RFM^k^PibOCTZXvVKrma_<Y!;M2$JlvlG##5>^inbydSFt!
zq$^>kAh-{~K|wNWCme&a<oqd3_W;^yW?R6;6L$!utlh%9qlD0x6Rj?8WR00pGN&;}
zLn8}daP6!Po269DY)Af7A;u&FO)riC?k_iY%phv1+nz?Mxhs*}dnKjlhLb-%{dN@%
zuEAsIe-VbNjdGA&APUT5kpp15=|h2AwBb{#G}GY>pR$~w`XUM|7Zab(2>cDGAf{>4
zV404u&fuz6bZ~#bAe7Ou9||5(0Lgdp`8moQr4dS6T+{_pU33A>fTAM8)7haC|4F#v
zFAj3%$IYH5y6$$G$d3f9a<gAtlAOOwjA&3IprJUp9<-nld9#lgbK8A=^})kzIB7Ak
zGodIz@_AgTu%Af76Jg9zkF6k{b8#E8p+&K*<iF`rFi8PWYs>X!nfdF(eeZzlR<>1#
z4Iim(I3V?IcL+<+01necZAI|^rm1`}t|;e{*=-R7I(4rxU(Z#@CjFAHcZI6C{#ig`
zDp#W)Nh{eN=a)CI)tZ`FS#R?oUh&hWrPOdBFLbA*sihNEHh-d7g?^~plyCj@TS+=L
z<MXCc!cxTbRMR@N#76n<DHXg4xQibNX>tIbcN0E;W(6dswQ~*TILg9tgnA;_6k&=e
zj5ly~q@0R^;s7HTw;444{=iFAym9ATG3-S_ML&7LM0y{{K)@*R8MBKY<g7sgC|!)m
zArnlR>=ZvG|HSJ@f5?5jn<tb*2aNT^6ALLW(B)PQqIg2qoAy1JG*Xx?ue(Q#F2o8J
zjKH_VR*rN44LG8@nt(M+8aKS+G`S{GRA?0+_GzDkl6A+QBRBduLgt&M;c|({M>%Og
zcv?%RWxwNwPzNSj%ey9W5?}jL(pG5R&KJmiIFqowXS=X~W9L+-foW<VRq-p7q>d^D
zL}vl-HzSYRlq}t__4}_-S%2D4P#kGwk{j5c$Jhz|9n?-RRwu)N7awl%k+{5=f6_<g
z*X#|u&m;8eogpb#ra`6bSA5%dwc-SK$D=~c!*3gW>7ShE42wB?L*zEVKKehTEOBF)
zKrr(i>)fXx5Xvo5@_XgOMQj~%&Z{ftn{Uo1%at;YIWQ{<3d_>i)oalto4aX{LCnlx
z6%2N*un#WA(4<l3h7qy9F*GxJP!%qsP)%ST_8eB8zh9eo@kzI#{uxz4>;PpDpEVCZ
zP{rDom6-0AWuA`Pc>(uE)M)W8NeNRHL;^nzFSLDlIaQFwW#24A`1J-2Diq7J+kw6=
zAQ%TI$AUN7eItpg?e;;RE{!9-Rv!9circzyEfWk$?!C0RnmZ7;ND{-Cmfa{dO<Suc
z8@U)`Qf?59>V^A^SI@+Tv|+2}x}xx(ymChF^Y>`hxeLJ*-_}Jo_`Pj>%@dmosO^RQ
z09!MRpbJ@)yT>y2K&0Qjl#>S<@!{&EW=eC;O{;ph2KQBxB+oWYap%xckA>I!;3GsY
z%?}q#vYkEK3}Y9fofEsn)(&F~LvVhMX6UBQg#%5&qdfZSKq(Bh(mfCLMYu{lJaDUs
zRqzWX@r_!KLoJ-{FWQg<U81uKqg$Ud%7gJQlu1CS|F9PRAihncen*@3;|Aq|y$;<0
z0#R2F%~uCtLd?+-Gve<o!9=k^9`>Dv6jpvHV3h*P(Urd$JBpR|4&!C@N2X=Q+QCE-
ztUiOXI!KyWHG5B-x+a7pfHQwQ7yJLiqeq<|_IQJOWn_qYeENHAFsC1@;(&}N9G&9_
zw;EoDZdn`D53U8EZ<LbTtrfx$ZN)gZSnquvM$BmMSksRw3G!M>*Yg-kmi&XNGjGum
zD2R}sOUJYoSK*m;t^_8O;9lHL+lC0#*R?_*(nvaS4oWdT3bsn&+Dv!$zZ9trkjs<8
z0edFwV*@LBF|Tt$;D!DDt3%=ax{@#^zFL$Zi44*Lau~rMj&6Lnqf>!JVa6y#vTurg
z<24Y!+$|WIHbV4o9t5+Am{kN3h`NJmjcY!QfHBs`bF|7_FCg7=Nzkx~H0UBn$BTK9
z4^bSeMrXirHH>+4&QWyE(cP>j(A>~*g^m6eH2+nr4%_V7`{5wY4wD!f38YMzl&Z2{
zTuDH)r6L;ZKABO?GTNlKgBnXE=$8f_(|n*3xs9)gM5Mb-vWIN5w<A=xPKfrP#;j&I
z79JnDZ3I31>=Cpo*O2k-m#pd;<~~9lSkWI@|1qPxR0vuOmw^4xs9!WbccRjj8$|;?
z#dUnF#3ty)%FQ0*UONaU#GBpOhs~*??tV48!Qy9@=UnC`?XiO;5U9!O2MBKuYJ^>0
z@Cnw4r>zYoJMUh=3yU~~(EHz!aqAS7J#9*{b-#X_Jq#8fD7rOw_u9=KSivh2XQ$Dm
zeb;f!;sEVMpxDVNa~Qb+>5IQR%v6$s8)~Lr@-e4+`j?t+lau;;^E2M-v#NvO@x^=b
zQUsVwPwsr<&OU#=oJM11SOc#yx3stKk`#Yya9?NRD+n44c5aOZ{dC=b8eVg8dWsSt
z4G|%6zhVeVsRz(RFRt`HexN-`(N%{yXAWDvRky)D9e@i}-W6kq;bq4JUvpEiPbJ=W
zAfX4E+t^uM`Z7o(6J#U&OKP!ChQQRMRnGoAm}5}9w98k5cntbr>kW{QM~U#CH=D%P
zCD@rBe|HPXO@Y$q_K_fRXZ^iF2&$mX)1v=7FH?468Ne~k#Zh1nGigbrpI*tzd)}!I
zn7~?QaR|lBx(V^*ase*IrEM1iN&|SK9Ey>a9b**((8*7+k<lk>i<~4S&0>jw7^4Fk
z`J!|{OZ4%hQHxl}0L-4Qo-f+|ryjyG?WY*kfQ5vLUh!D|nPB%?i)0hQbf8?}u)2$>
zXDf~DKJUm=RMAy`U(DgO914e0Nn>lCci|g>^<#dpp-&4EQvM;d&|XQf?uglg_FYsf
zWwoAAyo{OSqne?dOXphu_x>aCe2Y$5&INwyfJqT|RP`H#fiG1(`*K>U_^q=80~71n
z*S`q55Pt9lsZDkM`(0`6@N-c_t-DVbP67E5Z@~I;QNpPWgtH|>1V{EXG)zZQu|{d<
zlQ#P5Ca#6r-g5NT4?Ph6UN|cCiwG64ZD1|4H_r}DMdd02hYU)bw@bWAFiMy?zjUf;
zeZSfR4P5$(NVn-mc>JCkd?kZiw0zcQNCtfUelNEco3`kUsh-uofrSn(bH~_*>VJ1|
zFKZ@a9#X%AdJsP*7G`DnolGBO?dB&An3?9_niV*jr^(bOwSf!MB3)*w=u3a$fP`z0
ziE~Ut%_Pzi98T{e6z${__u0fGr5uhg6ad1EfX*8J&Y=M7wFuO$<YwzoQbZN|NL4Sg
zi3d)K5p3D8R75pGrqquIkFizEp@^XIb=V%^M@t)hfj95A^<GqrPN<2nh9li%c>Q6i
z3EKM`@ef@=AH^TCkLVD6N!-TWorymz?mMeVHINM?!J@Zv$cE9R4e=%VxBCr<pOjvJ
zb|SGIXBt4N3q6>l?*d?cUs@OZX7!6kBWubL%D7`n2p`S;agoCH7ww4ld43h?%8g<@
zjdWP7`a#i6dTZSFLm4bQibZ5D|9MCdT3bq=hXmz)NtfYwexuQ)mDpWuSTc=#!J^g7
zlR}NYF@=hm;F__B<s<SSI#LXk%hU<hwJ}n}7JTn9?FX8yuxrL@bjWyj6i|qTF=AQ&
zpJiBFtridhxjf0f_VPzcKO$}ersK7U{l}jvQdof8|Jm~AY*92yePOI|qgVa|f9b_z
z6fY*42sw-4I@cGnw2(@_ca}-qRW2qqQ6|vdQae9As-Jf}6fc1%9O%8bHA^=Ty8O`?
zfr-RpLnGD$&H<HE><?9_$XHeICJ5_8Q^JbCm-1`C?aQ0*Q<J$#ymemRy9e5b#M;Dk
zn7y(TZ0vO6PbZ%&dfeQ@!bM_kF=kl3{7GX?B`|WnF39Pg7o`>An73m(ImBcAfy@;k
zYifV-I_B@20HF=hUM+AcvR!aK+&Hct!l4=aO%3(N0c!k~AJ-?eG$NQz&jaU<187$R
zNgqj5Idf~<u3lMx=+Ej>!$S^h<+qwE_WDJrXztM^VZPm(H{C$m8KTfSd$NVH3jZai
zAH=tVd@LKsn_gY2Iaik&cKmy?Dobx%2+W|+ae~VBKCWpR;c}%HcYX5zs#z@V#ec?3
z72J*Abx!yWePiXx=1lYK`%7oBL(ZAMts7UdcW)<Ry2bXWfhg-16<se1EPM^MPjCv)
zT$L5(D$kvPcl(a|wr0G4lOs4gLaY2exY})WCn@2%$43)V5hnFsG2z^|J|1wDBjbYa
zmpZ0bwo5b@kYZPaC7Uyh4LHy8z{zKwVXvF<+RRA}DQMb>qvQ`NeXOu4^N9FeXhO7x
z5?92+DkzfJ>OKKZ2r|Vr{hY<ccPI;^<><q*nu&U2krHm{MFg<=xzpaHHcGyf#Tqj8
z$^cB%D-JLWl#G3G6~ZkmXiuw@X_j_i;j=}Ss{#b9GI++d4(s>=Gcy8*W`*yDfcbyw
zTc^7ZZ|XrET}+>D=d<c<NvNC&l|6tifNMcnR)k1xw)%V|0&k>&Z3-E8Q{ZuEzDaP-
z=;m_7Xf4w@zkAwj^(-P67)q;CO{36p2g5YMJ#i7q>G&zu<p+vpz=tgR?8nS9Wh}-}
zgf2Wr0e|4~7_QwVpU?@s@9T^2VHp$=iqmzV*6J1lfMWWfu!d3$<dwxY;C{y%*<H)x
zbsd=o@D`Apb2grKui*bvQQivOak=b9N{0@654GWchc9&3v7N_iUXs9asR*ol&L%*y
z6o%_jCBc5ZfkLj7!b%ccMm8MMrJ1I%YK160C8R>k*puY}cFuv56#()2bMuK8H^r^-
z|FP4kh=a{|pWB*@wisn}x7MTOMm4+2r8#exDK>|SFn9vFEYNjW2yuA%){2#Qf67kh
z5sYXYsA*TTNZ~jArDR>b3CV<{h3LEUEKDQ5m~;fl-^_oRq__qpaT1Jn^ze7ykCB28
zgeSbIt~Mbul1Ne2e=L8^q?3=Jvp4YnmHK^aKAaM~6@qlfH8}U^(K)s)Aq>LL4d;`0
zs;>ybF-sxv`~xq<?e>w;P9~7A=ETALeB=;YSY6pL0O0jGOj<D6Vi}%Eo1qum)J9<I
zn2OP)ngSw6`ZA|>X_`i%Knl~g$(B7ScNyO{8{k59Xucf-(KPhmva~C*Lh{IzJz{bE
zx}Ta>SDD(tji$c>mSl9P(lmW9tpf<UN<KtV)@S->!%m6FcwzmS@p|LU%xFXc?T36o
zB&NzWxKAe+&HmK`ps&03`T!#B74EYkoRc$8exVnKVDw^W>=*-(soWCS9;O(A?j;UW
z^b=jR^1{LJf7R%q662bh>_YQjvSL)i^2hUpCN110tvnR&zGFGZiL6H*%IuK6l|u@{
zmh->rKj?<~s1WMOxzl|Qd0^cqibOe4c4WWp$QO~+LmM|5A?$4ZHUie=XUJ?>E~|_{
z<7Ay;UdYTJN~bIMzoZH3$QrPYqL948=p1E9YJIUuN{C*z{}9>mcddcd1z#eLUJ!pM
zz@DL4K{-pT7T6Dd5L5ctO{9<f|JP8lSPnBJRfvq6_M76802dv0?Qh{dJtzbqDEwAg
z>JHwHL7}s?7%E!wILBtp<>Ffnd2nFOd&w2Wys#SiaG&XYJNhDM@jA8*eeT7?a^qRZ
zU{_{{AC`Gof{qqS9Zg;+%eCToyyQf~x@!(QJNxpoSQ&yTLyuI+2sX)PM9OAvrT0t%
z6{?|HtRd8lVG$NJ5@az2qw8QMPz+uZHN5wx<0x!@ij$&!IG2I~O%#%=J5F_HpP>N3
z3`Y9a*L_<>=iqlFzZ|fUcrIo!D&MyG(>}1M+{HKLD2NyWrn@@SR%}jDL$tgYCWo<b
z^J9=Vv$Ba<!ja&)<?+YA467>GM+{Wc>iVLG*O-Tw=R?D?y2%ifX9pZPxsXLK0Y5Bw
z-!iV6d%5th^=w&xD-#?{b3(bB)nq;_74rxDBC`bQFkaQcTMnmFj?A0;sv`r7prWKI
z>9f{!-cJ!A5LJjfpRy#d*CH-nyw9eCFxCvI%~sZd6-(PG0p=e<@_;wLVy2xU6JGa1
z)C>RH`kl4Z_sQd}5tAWz=z3g@3E5$mEbs_6F)-ytGL<<{UG@#IrhjzP7YBQpflCZ(
zH|qztv9J-2(*dN}SH~1EfpJx4STU_9YA2V`hQDTd?e|kE;7I$(SOW^o5Z`0GCh;^p
zyZgB9%6cNR<BB|L$TYj78}omw6mO*%1&`Q+WoruuTt|RwVjL{E)Q5$$SJ!tdI|%yF
zcld2B@OklmaB8UbN5a(M;1S9sb>vm(4Lo+vAJ7q%CVGz7(lH$DMB5q>{18V8y(g(*
zz<sY$aZx^&)Px!ZKNp2@Jov$kL~KKmE=^0;$s-&e3B3#|g5!ez{-qJxVyeW$CjIU4
zW@Cs`hX=)~3z*uZKZDMst-!kf!G2{yxCFpZ;{@L!(ir$4nrGvrHFxG?s6dfnd>N<0
zYpwdMdQ$d_8Dq};wQ7O&+sFg}7+Oq%zU=e3zgc|F?HS7Z;EP0Et!L+IrH3;Lp=b$B
z2icNUT{sl!yW|R(zidE>7rsfqo`IjB<GiHtGTlSjYxCOO9C8_$junhP7hGZlz|cB1
z-+FnLbK0gIHOfJ7)bm7hrC5wxr*4~PEf$J~0s+i71$LQN>q(tgIm#Uu3nuOR%2U<i
zrzeeQsDg$op7%6&h`z^P)J!{T11AAGW^aj3zcxYO=bKYqRuqmW2pI_vjlPa~#1zn8
zH2dQeeex`C=lm|K$J7(5aPFquR@arsaag)EdgyJ60O<Och+%GLdf~9;rt1y%Jy?&~
zJDq$(`^7LoOgM%$gg)tMbFDZ&bwPfDEU53&-0-22$^aaz&5Y5SW{~6WdNcW~z0U2w
zGa+`$;rZ-eAi2Y!)3CTW`wTh*q7(qMnI>S23{%M>{P#1MWXHao>KCZqm-huV!f@S_
zSuFP(ytsb%NiZy!0G!8-7-w#KvZ)nxbs{QjX5C<}rV))8Q?6YpR|#U3`=8*Tc!MX=
zG3v$?<}V~7iWXbtE}#Z{x#8OXP5k*euwRt3A441au@(*zCb%L8=!B&XtG7>y6j0J>
z=ztwwgMbINdx&E_R?U(E<zp7<6S|$*s3%O!u0pLjfOGqJoIUDM#<LJ#SW1i874!4M
zBy|Iso+F1HIRdggpqzd~&rozLFBITIUl1>>#5EX6Q8mgK_rCgR0U%nG{Y`AOR+h#O
zw+>yb+nOJ>;mUA)!$O?k4g2t%2zG%iU9;%#-l<OH(x4hD>M<UuZ|C&~L&4JyTaza3
zVLT#pUftY3rMqc;NTYH2E?R_q27|d8u5s!GPg2nv2K_+rrQu;Jut%m=5B&{}+vEn|
z^5*YBs<VAie1)S7j4iJan7A}olAej3uE`<r1O&!V-p1!=`qXv3GwB^YkrsWE-eoBM
zgh#+KrA6N+es>%rz5g#6VW6g#DB_CTBNMoCWd`)P!tTYDpYsa|tMOF;=G;ttU?7*8
zvuo7*CJXQ(^?_SSwEO2?LOTUJUiV1ygWAjLs1GCH1lj$Do>YjcbF`^HY`fRuGCmfv
zz@ayGIaROtge(CO`gQqS5QEwgBntBL`yX5L!t9dWTC>2I(0dvfzznWG_&ecC81yAh
zX-#sC%-#>bl>t_5ni$pLq6Nu0O^_vSsO%EYe<XYXd!4}C+iu&k;_q*d8c83P1UuoX
ze`f?<3(5Z0n`A2boI5%!`8W1u2y&T<l2up244~2t%9pFH^w2nCg0;>DU{*$Qd~Zy`
zQsVCC9z;ZElc+a-%faLzIZruk#><)YyA0ED6^Xn6FF?@0E7GL%Hs3OpiOycIJ&mHC
zkW~cP0J{Nx;-&1LJ_;HR*k_?w@MnJ9wlADkWuSo62T)1f$+?-ITxjniE6$AS9k!)t
zd}i>o;(^HWCH9;xD$S>Sic5IDPEiNyn>==9c6r8Z#wJr>5vZ`TrlCyvQXRPl{3YmL
zCh>J%)x{z&=~+gM|NXpS$M4+j6Ha055?lYZ(s>X}U!uZB1FPTJ#7jtC<B;=WqwI)Q
zkbthrkTIxYneIus^vkzY8pL|6xsrjv7ssrjM7vF=0<13RnBD!y_Lxl@acea1XeubL
z)L}R_di?{C@&H;c)f4?xH7!LUylKuQ=&f(xk+~kksUJw0x3T)hYHkq2I`vOT_FDPZ
zgxq4z)m(+CebtpJH|L`wf#6I?lXJH^2Wx$qu|KI+45bs#Hm7zoTzYTwNsE!WsbZ;h
z@<eXK{zUwN%%aaG<|6^8fXO4qQbm~uZ{z`3mjp5*OaA4%vfyV|VVN?C+1HzO<K5Pc
z0o0Pw?`BI|6HoTyW-+dhKf9EEX#X^&=76&4R4H|N)TcsHXmey-yrwH!<cwN6@Ho(6
znzHfr;d%izJ$xiw(SR!k*xBIyL?5zPjcLP5!CUT3E8k$97VQNl-^mosX`G%$DGt<8
zd)QZ}uZuPj1$fLviXqWz@(tgHyqqCs_S*F*8B*r;LP0R3vq_TH(-Jm-6|6ga1qjY@
z2Lct*2A^26uKBj9l-qja>*cMEE_4S0JFt}g0Hv;~gT0kq;#-uX9mw=2-|{7(qn9ot
zQV{b+h{q34g@3sFd?joyF!=EVgV}G?L3h*i@raTC+EXj7;_Bx{FnBS=TEW7n2n<hX
z05BQd+J344pUk&AxkH=^iVT+<<zXTkCj$u5uQu@F|5eNc<U3j^m<0WO`5k@IGFu~x
ztquRa=@mb^HA!i1F0P?-e+4>sT(;r1ht7sl?9$3^hELE3<!<GO-wxakD$fmPZP3^t
zhTB=9ajxcHcW7^Ain!;~QC7Tp?{V4{vMP_(HKqvWW@0|wp#MPPVZ2NxL6?#v>4LSf
z6MmUPMXK5tvfrH7TEM;Ue<k7H4&SrWvP0%Rlf44G;<Tchhhi^kt87G{F2_Naw)3wy
zhDSMk@E+|05Dx~r^~(&!E6B@xkR~E5*=Dg}Hdnj{K=XxC!s9hS<HPR25sVA0x@<0q
zu>$3-7VUD~FFfqix+F43-63MvaZ=(}x>NN+#utZP277yv&fRu?GR^RY8%!9)8&eB7
z5_HbCNyA)5ivOp5D*3f|z7xQM0~Ri@y<Q)EME7=iZ#vn7R07um17yDYwXBt|@)R-N
zD<59+T|bX^&Uc}BJEprh&GzFFjDzEH(^gVLx(K?-<)70)Mej9*%b_CE57dl#JcH_A
z;Mh)O@il!FS*u-9WyETTeGHPiSlY|7<mBW~m=i64X@z2w2e3%NwS~-W&y?_0>O}+%
z!eqH_?PO+)!Xh}QE$m>^_ZGsDn=Bu+igU^>L|6AV^AHX+y0iv)36JhZ<>KB^S@Y~+
zx+-ueKE8}e8np6#H+F6m)bq86)Y~X6l}}=BI$9{9<^KP;7YvNXQcni{qY`)Rtwr5r
z+VKBt#VyDP27+6ll08zp?1KM7Wz8ZDuX!I7G1*@VEZsC~@nTv4=*F>%o${|$Uc(@s
zA{n9CSO_a<3xh)d6%NOL*@Dap2uEPn9$7&h{xxh<+e#7JdcCC#4NFsQK^|S;-iTr9
zy{|HgqKWfl1ke&b{^CnWBjf+qNA?^jROpks_aG%gMFWq7wy~lG-{{pJEt#6><Z+AT
zF-om?Ri30N{dJad8*pgKBhJh#FbyhH>b)R?LV8&2ZvuNE-gmL50Q+97p=8(XC9Cu#
z6l#u<wsn8OtjxEuv^>K}OlpZ#bO-{$Xc;`R5l<8xv%fCXx(&07G6e`90ZT_&xRvPa
z_WJzilKw#4GwD!R&B&;dx`}MtI|aPYp8p_2&M^rqA=DC>$$@-T49Kv=lx%Pi58dcV
zMQo+qRx(@l29tuocNzwZF?`VL2GHbQpYr;^JF8FD%cfi2Ac?IZpFe{|{eH?+n{Nxb
zwC8WbNM>Q1ms9ad?XM)z$sRn0#~<q^;N^jw9?n{C%<A*$KSkXm1X7`=fGc9wh^94=
zh8&AsRF3Yqu~>eU8B+|>I0YUP5qOF~L`ZvhBItBkahVa395BYw;fmt1n4Osg)Y57~
z&KX`%s=CEol&>1q)|7;U=5`ficZHeP8fJ;~7Uw6OC9#;Ju%|>RWW0gDYKb#SD{R8i
zbQ)g3{Yx;{z1N$Z?b<^<P#IIDj2j_pzdj>oOO0-pT?FGF-`wy4xjw^96qQwr2Oxe?
zs4aG*xUJ3wvPFVzT=Rg-T2<0qEj_)6)39<nHFssEGbQ6h@CXEc#$%0Dc@9MQ8dac`
z69qY#?iigiL>K}xN?1w}xb)L75ch#!LGDZGj5HpIxEnDSfS3g6UBV33-^;s}hienR
z5$3CZdlUs#Z>q?a9bTwG(nQ^ngrUy?P@I!Zx|6<wubfLHqPK6SuYri&0sS=`#?0sZ
znB{HUbL;mfjmI-xbQmLfUF1{UXbW~mMrl(kIeqP0^<U_>umSPxS}sDGoFZgjnij>W
zf<Bgd+b_gP)X0VS-;EUn)jRV$c^T*?)PA4>Hg3`OSZ9Q4uEg*kws2qr(eXf<UA|dT
zx<dE~Ci{<w*A%pvS0159hD*fCkaoc)zKW9ZR_Q%cdj~P(1Prngv#2~g{Zw3%#6mu3
z0(cgH0Vts0SpEEnhYLx7Bfmao<T%<jCCSV*;2i-<=w|GM6#bh-=wV#6a68XXUW%9S
zEb-d|u~TQNlwFafLlM97Fr}H?&Le|-d-y*tN+03*>Zbzz7&>A1GKYhN!@n9^VtL2U
z+Anymyk(1mbH(BuR;iit68`Ik4DkERjpYSuIP3b>0q^v`Xn#1kr#m)&hM}rP_MhNO
zs#n-eUQ`7bOjn**eSfAhV7&AywMQzi^)+6(C2R=UUl7|gj?ZBAy0hGcVM!WmxecTo
zmLdRM+@;of8=kEr5DzMxFpr<i3ju_nw3EgUf(aCt%pP|Hnr{M1Cn!M)qkfy3lqP%1
z3-i<aG*mKr@trDb4WD4|!cdX51FcCcpOtHS1QSfRlc|3P$_^-J0nPX5eHcgJOGon8
z&apj?j$iP9AIb(cg9hs)>kIa=WQf?1>Cl-tu-dE|4(usTS~)JRgWlInj}DDgc9K@+
z0y$F?11M>8Kk>C=0^v>WA6P*0pYLy}Rc6ezf2t*=sPk>u`%6(*{_j$1lHEP)M1;b#
zjVJD{N*cbMC?k_jx?u!_-~<Fg6g&tbYCSS~Tr@2WGK8G1wH#ogYUvcshJ?n6@|M3|
zNLexPs24tZX@xJ{%rtN|+!31njxyxb-(rDHF43>LcG*@dB3&2cVoqu{&BITp<!>@W
zu^(M+_|KU=|1C29mT4VfoP=FS12dLUAK|2xWp^-4FHeGKR>(4ldf-`)vWc}KEI@sZ
zq@@*7Ge*p214n1*<ds3s%zGod|11(UkEy#*_Q=Tm2NyecegQqtpI`VjXg1cm0a+Hr
zaMInQ3!#E~D)Ma$SvLw?^a90>h~el2XR9Rdk|pyc%_y)9#KrF{Q~PpOT0cF-+|%4X
z1^Jxkjqu6(n!!jFCzN63C_uV*0>IEaeW3!+GST`>13D7`Jk&EXUw(7W3-qB>W?4uc
zl6jL!+*8J(#BAmN%V-n4$jR&E#WR!wCogWupj63UJSl;ypURZT<L@H@3sM<i<G7ny
zaMyBM*z_^xKe7j2Ih7e2YTw@a?q=)dY29j24@&)X>oK~Aqd3uv8y2zpq%@fM3B@Z0
z+9}uelJf11Y$cFJ3M81&0t#giw4!|vmeR9RE!#zlxUiBlLcdD%@?FfJ(BdaLzU4kq
z->35F-Lbt->5fEdsbu&{HJvS<D}3Z*=B9U+o<&#c&|X7ghtHrrjCjp2T195ZravxE
zhb>w|;kK5uz#go2pPtJOqu}{6g{G`I;$zef@LJ*#@`g}4RK>;AnvACD<<xhppFd=N
zX^+T5d8x1XBGX<ZCwKWKxD1*hH<-01K^^I+3%v4}l$JB*X#<LHiDg5gYn>O20G$7N
z`ySVP5l<SKtWg~HA0%YV$2dg09squWD}G>7u#8A#14>jX_J@v>+0m)t^9B=el_v^z
z`P@cWnzn6H#!em~y-#Ts?DkcBtw4&ehlQMOH&8-=9)_yZAY47fW@9(#Q2vWRY%pl)
zxT{{h2U4C03<QRtM{X@v(Wi~Au#a$n?JJNY`ql_Q{3Di1WHSJ{Oy&cNo7+b?anlO1
zaGbA5Q@FsLraEgXn(iB<JF~_C>2Xnd*nK3j=%`w%?OkF!)5%3yf)>dLV*v2;i%w~W
zZ2b-D*5_iJt<%%c_N~;-2Jvh8Ztjgj9&PX8Ia{X-uwQXy``ld#{}IzNXMO;n6wCGI
zWPWTPf~+3E7UhDsbK%8jr?~!BufM&eIy+86ld2^BYvA>&R@vBcMuH3pTKS>S&t#Oj
z<M@t-GoBL>HFaQ56EbBx%`LTkwcgGEb)4KxK*L~TD~Rf>9*&NC?4=;lEI%#|ejn4&
zG~@|vD_ws#<5!Uhi>HA)ZS1bASq|4HsYqIQsyV28{`F+&vz3R7;U|mxUKqeXbVe9k
zA-p*SSiT@~3IqakJETjB+9V-<)?KTI2L=h|7Tj2Rdg%Q9S^8|>Roo$WiQpPzzI+o{
zlq`|8xt2VrOa|#xcKw?(oZ;+RT*_ATr05>W0g8_>b06M7<0Cd|MyMsU9i(Ty+)zK0
z%(r(i&>*`ZUME3d_Pg2{-MX=v_a930$`vu`+)RfWrQ28`n0t79<lcXDWaJrlN-h_m
z+J!3iCXC{*<Co@>h~#G%ur%jQwVze90~MjiM{HW?H$hhhkATU)+=WMxY(7x0j3?>O
zZ~0`>IVXP-m9yG`N)f+kYyFmgfSQHUl@ZVj2`$)|$Le($gJgg-lYfr|EfRsa8wl1!
zGlEt6PL1VTiJNPiSqj_?4Nn)++CB^Y+cqC-l$|FBwi<jlRgT2aAK2?ZC1)H$g)uas
z!T(|6%unaPA2uOw?a%V>C~`@fPle}g%TfVx{uem0>)Z5T7fdh#;XgKOC3Sehb&xv3
zsd@DgB}AuU6yik!If?BKrfVvPX^$~tDadJQ<7Vhb2(?q-N@+wkS-nAwdBY7mNe9Ty
z?I6Ry1BD@H4RjqVpK=*GmEZ~TZ)-Qv)n6rU>sY?mF|dUynZoSFL8FM9L34<&PFI>v
zXj^q)0+-G!{Da5<!40;y_fpkn2RkBSYK|`HxGLBGq<Ng*y{Ve5b;qh+qSrPpH7eMQ
zdW7aNhsS3%vy;il6ME;ur>dxFeLHZZDy=rv3iD(%@E`(EMiuL@T7Oj=zs>SFwtDuU
zUh3S(YO(Snvfr<~h2D@%@THrcRXB^VVI<O8?9spNhIk8o`gE`=f?UUP*F5;&ks}_s
zA7?n^nhhht+j_ITgEhx4cE!ugKXY+<&D@QRu;{<TDvL*DjM|eWZJEZU5_!mZGH2-R
z)J7*8u}I7zZ>7!6QiCFn3SqDMl#J7@Z19(azne?#__p5}@ew2+!TE?pxoJ}Q2FW5s
zfwVEot$QCSy&CBo(Z0>b*X!pYCP@M)v-rIx(X=OrtI(1BgzOTy1i0g0&A}*e9aa6+
zrDBD-L7qMwST4^YU`!dqG8G<+a>^fR8S2tRQi&hi@GQOlq>v|AQQf6R2)jBuc@8~d
zrY@lG$ayl9#39W$WtuQT$-Rm()O3;~8$@E}kW8JmJ89rDNp7?|nGv`S2{sjQCbC6)
zj6VD+31easLKu8A5FW7yFnA|pDkY`pS2r2lfl$oK2Z?hdiplNB{GX);nHD(Z3PZh=
zy6Pu0D-F_i5C>c+g=hjHKdfN-<r2=n5NxOhsMCGs+tg2#D$3NW^UFEHF1FTri0Shz
z?1<0lW<AZIe-(HL{6B)aAYk<#G3nI!m-V0_fxx<UF5GR(`jAvv4GFFCe3xni<@|1C
zic{4m?UysToKXj3>dN4wF{^xe`g|fbi}7KqZ$h>4zyVebfev6aHEZ>PD^*Jcv75ir
zD6>1s&`529vT)>4H%%pE40f!ubqL5mnA+xHIEThqhf5hI1iC-}uHGufW)Jm~Ri^2E
zm3PUVK!no~)4qV4m|Lc!j&v4!#Tq#7PRf7J*0}<FyQ^u*vT!*i5?~Md--9<zK_SPI
zFs~2Ci8K_Zkk(^tGUgsB6bqBB3nZEk%Ezg3byLA;MyTFn<W3O`0~xv6QycDSbz9ek
z1RDbwA_s04Vv}QU277h!qbZFqQK{(YUZ8sv4kAlBG*JaEK?rDKnbbGR_M9c5Us3F?
zC$pPl$Bx=N(GS9rSb2f>CpAh2FhRC|cOTpOEl~YK*>*FDZ7erR+*%k{zK)$=qMa1O
zew;N4tl<|LWR^n~+RVy?{(_AxPa$=)-V}>tBgy~a4kw_vZLCw_7ewNaJfKIbT&abw
zZbx+`A6TXq7QEZ@uUzU*trQTCg9RZFLO)-Y8ewA_hu_?ymUX#_yY*PW@!iK7Q6LJW
zUGr`>0sMn^Q>Rq8vno4&mn9am+$d=+G9XK8nOGeZ_#2*h-Vl;cMwtMRdg!N2O>!{9
zP{K-m{{O~_F=55v=68wpsy*3nqMpE7cT_>Pyu^<4Csw5bt_(Cy>RwCqvuM%@JDO`9
za2Bs{G?6T&Ba}T@#a|}WjmwY}_<-h3MvD*~M5E-VRp_b4&)69*nJVIv-DNF{o)>e~
zzaDS^2hVu`1MNN+FF?}x`2Ke~@-Z5;Xcb+0vC;y}BCEEyZdK7PQx1$sDbQ(c$wCA1
z)tf&ilN!G7ZJgy8Kkb4_IRFZ3?fAMEw&~O8ET+<lU>iM(w0;2?_*=#II-BOZj7ij#
zHp~bfL{<Mj_(J=iFGhDD$NYpU@pA}jIX*uWEf&s6pIDWUpX{SNE_Db%t2efLqrX<<
zi3Gd&A)#k2S&xfTfiZ&CWtT&{sR!-==YvC+(J#^rU@Cmr47xKc#}xliiW4Ka|9(r(
zi5G|oNWj2|_m4{4k|Q&p@eZ}fkKXBT5=R7X68UZ)Ud?GDtxoa|U|OyaYn+GF-}_wB
z10Fh|7F1>%7th5~x3?+lP8OrP!qV$QidxP#T&mMH<`{*V5k3;6-LW~`VZ55&=wUi5
zF~#YFu6Xgp^V!5cqsulIq158(P(q680zkGtwO6u$Ml1{_4!*Z}@C2>v`jDZK0c1kO
zirgReK!lk_QGw_Qb6KYs7Dkz^M?(;j*F!Br*&Ej|wZ}AtT!|0mL-;>%lULQ+=({{F
zGAXqUUBxFlbZ&f8W0o1Q-R7Gr0rrWs)15${4sKR3)P~8kGcmBVx7@%X8PEm(ZNeJE
z**;UTxLfIj`nN+rgA6XC9w=b#azJh!U(rd@QD09&|5l2{MJ}`B2ZxM_w(yd?FXJ1}
z<ndn2e1ehe=>KgO(sHq>0%(=UdG5@Zs@Qr+X0AddH2J0D|BbitizK1LC}^2YOY8}e
zPr$-wMDRk|U;S@<W?{RF(t)wkRAo+rS8O!2%}{k%s_82R3OG3l7|^|bf0onq8yiGF
zaKSnCqSW5=5*7!~oopy5d|U7W$J@o4d&-*PNSu1v%ESCXQf;i@p}+-Sb4=&Faj|rz
ztd#=Ytcb$GXCQV2%aWjYagdH?S93WRf25?}Y~YoCz06Jf)X7Cl)$j64m|K@{5Q{rH
zGFq#RJRpUrxO+AH<Op3+Z}#bv8~G_aJeH=Nvc?zM-b3%Y*2h!-dJYPSQooU^VHgGy
z1=eH&u8k+p6*K7zowy?7DDu?5Q=jeljY9HcALOA67%CZv;;EU(_@+XVH}SH;hV;Kw
zqBlNzd_8C3)X2+^MWuWd3M)JE&BD|*B68~)x`bKYysL}?!Dj1QGz+%YhKN;gF{bh6
zuo|H$WF{huFBzKL?<8i=cwkEg*gsSkI11I-)`w#vW7|X`I&X<kOJ-@4Y7P;_40s%k
z^Eh(`S|LdCl|lqJgBK+_dl!-|;zpc~J?}Jk6&dvUZo4BbrgNochNxi@s_ekwWHDSj
zmjh5^(+VauDx#e72aJ#-v7Bd<MfUK_qQy&8qN^J3kY9t2+B_Z{XEPcRSw-5I2<fUq
zHgJ(#340hunPgZ~*Awl`4HqqQ;W8vDYAk{JT=UsQk6>PxX4Gs7AZE3`Z4$o|8qcM(
zNcs7UvY07le?}{u^^pokx+W;JB!H(gj|UU<O<tpCi6w8lUm|E2>>7tYrh9#TMowa;
zd)%04dve;F1}b+-2=eI)Q}lr#q$S`sfqTNco}2SOzfrKyp{!m9quI14aQ(IMZaO`0
z;>@n%@e!aaZY_i!nkjOv2!=Hg&9JHFIUgD4C>W?Oh)rem^QOd=&a%T!=`!8uZLQ}%
zQ1!N$2yvsL*j5|IhXAma`s@R@tBh|cr?iQdOQg0F8-;#JMglw-dmWzz#DS>I5=<nE
z4(3@K0g>YhT3nDj#F}8z7;f~(LfnSj+7&xEs$Sz}7O}eJUJx78{iA;5zl$fd9xkS2
zTC(8}TtL$+CK+-$duiG$<w#^_dKJ8zc|wivIVo`Agl8xTR?{8Fj6MhAZ%vPZpl+_g
zgM1ivuLWe`dIMNxbRMeFosF4<5Nao{CQKbWe;(`GDv*R0#R;?n-Ni)z9V}n0@vM39
zpt_QBy&T%~vuC-KVjcIQPb12GotP73I4-LZZiT9<SzN7hZx#r7!!hT<UuF<mY##t^
z%NzHkGM#zhenyUAr$uQiVt8AYOVm<W#PRmY6FSQSV-Z%KHp%7b(V2QC>CQO@x(z>%
zo3|X&L~v=`l{%!wo+w6p(<Onrpdl=_C+&KY2@r<Cxc~)L3%01v;HPX{VISe0F#hYl
zxZQ-}<m;j>3FiiVjB~2TOHUVqbg1t<_E2oRIstGnjrnCSU;jh`z7EYnz>ad$M4)j?
zAM#nx?n-nZ|J~HIJ`>iH8p=(p&5vYd+~$j_X2j8^3`JqA7;5IVwtBPgup!Lhi|?(#
z!MO?%{5&TyWAA0OErcPr<;wQQe8$IWg}rR*(L;rB-=W5=<=-LeleE?ii(6Q`H7Tbm
zf|seOarxv6igj_Zw)ZdpyRu&1sH2Y#JG}ah>!Y09uWmf>xR*Dn7)5vSPQLCJ9YS)-
zH*$7@n5+XJG><ejMkU4vde0rD1g{ST_5po>Nv_a1i1ZJ@h-WZ02AoO<gf^$Rw0f7Z
z>B2PmfYY#SIFrT+i;oZ?aV~ZZcrB`h$i5YFLR&(*6|Wcew{QWmo|n_e^%MQUZCT<?
zhQ~8uwKk}XS8m%qr0piVNYGfqUIiY*$KcyCIu`9mCbF7GHLtqiNBqZIr3KLLTIxil
zU_(qmX8b?<2nJ1OXl7W+G&+gCDy8r#E~I_FsM%T_af;4<{Y7Gu&$^VwE;4$1_#4B5
z0>4Bh;#hi<a+Z9rD(c3h3Dp%5apXQVGf35*P5KCE8%+4m7J@<yS$|3@f1!AtHOf`u
z*pjom6B(AtZ`Ia*3h^kxBgEPZZ7iRi*ZOb2Z7Dt3F+Xq=d&#O^Mj+a^_W$v$i7Jcp
z%|+}5&@L;vGJ>IU9$+>e)3_d#WCJncG8{%T8#2}23IFqqwMDjDGr}7xCZ^=!%=8ej
zNH&LtrJzW_#2relM3pQk$*!9usV!gD5GCrXd<K*NKxVm~?uP~TS>zrD+ub*svp?rR
zb;E|ZU>A__ay1kxD|dG8;_H~T0H3Rp5-S}D5~~@$K~%#H06fCY!!8)VcFhYXzp2*n
zxqM^*eVf-w8(SUI^e(pp&TVp+?g33kWg!EoW0#x)Vu%1T!Tn7$l3VWbZ>6eRm)3B{
zW*mYp6w#P;Vg;PTF!*Ugvvm}~ke^mhgALnCH<=SOw4=xUPuj)>T*uqNTaGp!s+(mB
z2qovD$GsfzaU|};9AFD(Yj6&d5qPl`iODBMCY^}8U3mV<tOn2!3D4!9EJgu7x9!@a
zd@upk%V5!Hth<WQnui*H$Qm)z7y;i=S3%qmHz72hY!TRE!M;-o+Yyu;U{dJuJs3Bv
z!K)?*YM*{np7Rph&h;5nYv#Xgvnzs9u0+VY0o8YU&_!T3OfVWRWy=Rhh<xjL$c$gi
z$n+g|RGKPhLzaGuuuTIho)-}^tr2zml2P(SkEmj9(K|bAwxOU}vqh+Hn_wf(L|!QI
zemKT$)E?ORLk)a?0kHmu2r_mc@W#Fdn9GK2Ke^vs2!P%q#o$9O8f9nOQ&DvyJON~&
ztafloum;Iw@&;1ZD^3=gQsCIr$EVCbkb?b+*zh}afe;EQV-nA5i~+aAE&n-u4RhPd
z3~`KvzHVF4ah=Fm&&n3XAA-`5zESAY9;_k<5%9K`6*(R*@3Tg8sexY3xA)4aqGp;!
zpt{EW!Y!SPVKH2=!K)Wk&L0aKs}gYmN3?Ri+NrvAm1o(w+wcTFpgK9tJ59z^3S2pj
zyu=O)vs4LCFR&o_>N3?dr4}NGb|vMbV+>u`ux2cByTB7Q_feY!d{7N;C9*VSxhFH!
zL@o6vR=}2)E2GqMeuL@vUt61N0C;lm^~(pa2tsNY?r?<(Pr$@V3}OeW33lyy*qa)S
zBoI54I>%NAQBZR`nU4J<R@$aN753<&U{FLHW1qAs@b0oLIsdnHo!TcFVB@`|3r@N$
z(SkCps%?qPwSIsHs-Hp|{Sv15i*RyNKp#P`wttwesSe;!XEPC4HR1(%g+)xEEN``q
z>Q$?q6}H?D5e-qVLty;hn_KrWgL<jvWCn;R1~I;A3?Pn&Ypbo3mLTIR#1<_D-ZOjM
zykhWmz|h;?<}Y0l5Mh{FX=(GvL>z8QO1V$rsWw@p=48g1lS2KlX};~fhgh-Fo}D93
zg^{MToe(qen+wC?W!S9+A)Iz`DDlB0>Ev4RSAcxKF`M&YT!0pX3fKi>lZzD>&eiAj
zD&zN76b>GLq^aZl!w7*jKsCfO;E@Eu8yuPd{89#fE_038S(YK?rT)fF@lt)naPpNO
zJDJ0PERTr^377>e6c<5NaV!!9q5F)ip7f70&d5~HArG-`T)jjaq+JLNCA_fV;UJ_v
zZEyi6plqVQ5Vxn6wlO-xYcl9aWTU7htO{ixehRcFGc@WArHrpDne@DEW`SL=ZcK87
zc%{;KDnPsLT!%RXWHy1$ujnSpX3x6kN<28hjzD>lH&1fr=2;ECWI__QS7M(GECP-<
zN_}uQ7Vbug$}^`o@|o`*+>t`z>6u>WpR_a~nq)vzYw3tlMrr!%lxdFpUx=(^rNJQX
zf+exT8_A5sy(dIYWSM9v->_brd>xhwnjL0D3!%SDiM@}JH@mG@NlqE+K!ptjNdpjH
zH21->ASUW5y-aTz(4^82RP3>+D;HK1SVTQ*QR3uRHlx@3m7#{|;XqvD2u9>=8~qww
zciVjr9V%cxp`udxj5CY#Fvh=WtT|9g;@GyI0bRo+_w;A>`6wiUY^Am_5N>xVE!E)#
zUC}|BG&$g<RiO;UBo0oVRNK<_I2K$JrZvm0_JYZ+?w^z;`xe0=GNYMxl*lkU!B^47
z7SPdU!tr!Ap0xm3mBusQO$X?iy4!hM6nce2P2F}KZ9{C27_?YdaAj4|T84ze5Kr5}
z*9OKMpuapUy*m;Mp+@YGBj=fG493jvHI_E_0S<1b(5hl1*A|qHhEo|og}$zwyqXlF
z!C!wGDHu9vFm}s!L7Lk>K)*+)Kf1ex7=Xvit<v~zKd_8fCUL#=s!_F?8ZkeOD%2aS
zki`2Wjh!3XbAF$C_ODRiFTGvv;*|PC&;9C{y#vK#ea`Xc1vR_cK-sQ1N;GOHseOxw
zoS{lGEK)ZHg)oCpY32n@0HzK2|8!iyomJfvvTgJR!X|2v+CB8DPw~kE$S#0j1o9Ih
z;{Nvr1BfrSF{pGdG0;L*WDSoTaU#Y#J!!^)P4vf%cHl$i=Q?mM9eASOs(4eTe4fES
zY7hk`ulIq=e9O-gCv=0tT^T;%LX_WAn0(M-k9CB}mk|UxNYjf?Hmbh*6s=kYV82-I
zo&Rd0kWlJEJe7GS#F)J!Tq7Mh^y3bQ#jUPsjwYxkcOPi{PL9COXp>6s=Tx^Z|GWWp
zwWf1IUBeW3<7_ou8^+^WOE#J;vNV1kgsKh<lg*7^xJCn7{Jgcg&ULFC@N@-T^$1z{
z2UKCLeU<aw(z)+E1MS$Uu{EM-TR>D4_qM9oCU$^8CEDH*Qk8L4Tl)uFti%@xvT%gE
zT`bMGOg99-$<_N#;0%BSe9LA|6FDFAQ_Iqux?ixjDSS;``cfZFezzqQXid^l_fNtH
zU8$(Lr~I8DUR#mO`rvgZf^(02#4^6@D-r|6xW#O8Br7($6jK82OEvbwfJ!m!e3VB2
zb(Uec))n5`WikCzlk>e9NOlYU=z^7eueqyIX$z;-Qe~?*_rjR2hW3;J)zZ}ciLc17
z>sS~Ht_RMM5LgC+Yu{sSp!zPFIXsLornC6I6w3CTtYV1J^;R2Q+nf9MViGL*b)fR(
zBQl4$Azzgn?)$I|MpEm}Hc2nw(?lgPgX<d`h#jJY2efLhqs+Gy>;dNpMX(^=G}<+j
z^Yo*1Cg)mUmKZ0-XT7W~$(5OjWW1{y=as^i5ORgp1c4d!lnM_tvo|NbU27^e`yb<v
zQD=D``TWx{Kp}zF28FG#51FBK`{H{GoM;xngNo7(RzH6I_zO64<tzy1r#)pI;-~(2
zoiZKrdPnJ>y>2u>&!Y+CDOf$sm?5lJWawvt97K5QzeQUJqw+F>_Y1a>xHsZeswwko
zl4-T+^3~lWM`Eh5uiP6Fni>cMyY!}w3-C5sV;dfh716W9uW`AYGDmMF{I*s`i~XS<
zh=apDtoWO41Ntx40aWypMsCq|{wOEw@}K$zl#a!X-rQMx9$taL&rQTxC{ZYupntX@
zhpH{~+5$vBImgg%=HS{2IZCcUqSalMC2?r*4BjRMoOt^)YHwk2UcIBbdXz@1)PBHp
z0MsfVv1Uo1B_aohO_I@EoyM40F2!n@AaW1|(aBIW4Txft1Q2!^wm_dYZ=d!1HhV($
zg*gywg~8^ZV`xYT7Q&`gRmflh=Xfn=S-2;>ooy$M+HM!wVuIoZV*ayP9x?@f$0w1y
z+C8rKK)e#hc&P#eU3sHe{{8YC0u=;$^5^a7-G*ro9Z|_T)>j>>vtW#VXXcum1ULvy
zY;s)uZ~=|%Z*Vp5U<Udy)KYGLmV%F7;eC?n7_Lc2&rSi4&aqt{?7l9PDX0g(zN>q+
z!^D^fd!=}$Ofn@ofdVM7x}erEMd()(LxkVSrC-#!qgviQ!qu{S2tr_n{xeP61AJ<8
zdoee(CTk@;Z4-PUc5h?Y)SU(p^p#Xlx{32O6!Jwu#%BVO8(Yd~j_k+Pj?d+=k1-v1
zt&?UnpV5sV6mWNITvC`ROLl7o^dF$3GHh%Md)|u{oGSJyA7kYXFST+Ob{}&Wf-=Rs
zyGE8mW>4e6pkrCRZ|BqVNrZF&i8;g+|6!O<-)2{4F;;REi$FIG*9PE%;0SUvmGW%a
zOVt)3%*dRyDlPlvpP)wi7GuNrao!xb(4!R>sS;jo_(WysQhcB}b3Br*lQuUWk$Jwk
zN>mRNyJ?QfnHuwDEDgk(X0zA~c2_GrgfYgOZ=608W<aQKCWuzaGC!=_!Dca0<sl}%
zTyuMe??Cr(+)Wj&*@MfD7B{C7%_6RqzS4h&d(^-bMcZ&kG5zJle94@?zEr69O;Vu?
zGlxc6{-qc0x3=F{cQ{cIvBv(qutIhd-X~5ixod8f1%I!o94kxzcOp0p!lPm4Z_MW^
zx%p#%z+`)+wS=!PeTe6$W9Hz@beeO_^T3`}BY~M$*ib)l-9p}PBw=wg-h$GuNw@e)
z;;tuW7SDW!s?6;D0c>NimnKq-J<%sI-}xoCDZ6XFG3PDpzL*8vNjC>dij;NWYPAa#
z^}c0|Ta<NKVcM~>IGvJUC}Xk3Y>pv<JXi*UaAiBFC6zSqW_{%A-lFfc^AFhG%EfC(
zI#G%u^_B<2jCV3McZAZguU4DpV{w0S=>a>lE%+!hG@OI-*jqRxMnNtp{Z!NTDJW?_
zK@8kWC6WC0_oR#OZo+sJdrpHFkxl&+{FitG87zF66^;f<e?m|$a_2M8gk<;sVwRMG
zQQ}ACqDlX-4QGwd$=yM`cMRdT^{w`A?BF&Kl{54LIew4@pOd@ju}+pA)0f3-!n`0x
zEJr068h0*DkZGr6Fj7}kEf%&LuXC+G=#-rXjhzc&UlJ98pYh*;iUlKlY|xGgiNYA3
z;Y}VvMNkuU%oNPlNy=|_cGDe<c^XS2pIrR5*!Gc$HjN(0kl6)Lxa%e-9@*7{atE|>
zMq^J@u*_oO8!0>ieL=OMaiNev1MqN<5fB}rfpl(l`+@OtY}$$;k)wIwp^Dz$sji_&
zn7RIce3JB3LZq^da5zwW^q-oEXoQ6ZjEek8Jo5P-j=YYo-ZfpKEp^xG@1+f9*7Osg
z@lhA~u8^1rl6CL!MKC3FLG@K)ENMbqE$E~WYv*q;<3YH^>(5S`S*0^Tr-$>u>F$>A
zxvVzK{gf{WZbUfEywi(~DwzMeX45B%HRz`CoaJ!hifHC2Y-<t45w-!a=bY7#5%wBK
z+yLx9t6%&<Jo?#@B5S#KF7)&`%zhHM!nFQ^mBXi?Gykh;0qi~rHUI{@SP?@OYW_Kg
z-%}q?Nq$X@aIR6h3)oA;@REu%k|5)WK918e9$@fuDGb0_Q%u8c>5Z$PI6jLW={o7{
z8pibU2JEbh&HDl*COPPynKV7+z-fKLOwqIYuwaRSukVl|+7}v<mjE}`WjtZ3W4oY8
zZ}+0Q!%!f@i-OWEzUG7Q(JB-1G)#aWu0+D+(pmHeB>yGIi&OloFoHed!mo~^k(?zp
z;?l13|H)>iC?SjeR1D!sFpvU;48CAB(u<=sONl_VNxa!!)+?7nnI*+T_L7o1icF%U
zXoA&f&-YF9yufQ~grJ4cO8zsHz?1toY(`cs*KtkhS+V#+03ibd*NYOtU5eVv$smLH
zh*CLQeV?%qru6@H!;h?o*VnkO-7^yUw^Z;S^JPsWkR|Fl#9B|4s4KSF#Y?wHK_zXN
zKUFu$YC~@N<lhR=nW-E|L@6j+^n*=oFfRY@u#j-5&$T#>1X;2Fg5XQdyg2W}Z^tb{
z-r`lXP{lf_3NitEx+h>Vs9jKVsz|&?NNi!D#~6ze>Y2&H`@vT2gbLy>M!devH-!i;
z02exkJQ~0OvOqi8QOR;hyY?E_!hv6V*Zy;1Wm#t0k8dk_0>3pcW?SF2qgcRD%PQsm
z206g=wxiY@o|LVCB*w)4xG7N_&1WFM=uHJ6txHTwqPzx+JTB;otSJkSB83Bxr9wV-
zX|wBpMeNz8`N4H8*?sTI;bY81EO@gt!Q-1IGWHHB`7k@9gFZZrMZu5snYxKvx*nR4
z7`KB(NnJiM5v4!|tpAMw&GGACu~QX55S$KA_G(^AuInp9#Xjl4o?(R-E=nHwY{YYV
z$4s@Y-kAbh#~M<{(e$GJJY}4C^!7EjK+k7bn8T1;>CXOM+ysgX#g?^w;4w2~g;ol6
zT_S@aWZq4qR$4C%rf{`Sg;C1t!53x(?4MeW9t|RD9DG%<;^J*joKkVtO;fN~BH){T
zM?*kia6tIf+i-X=Kx<<a-(Y!#wnP}{c;goH$OGhT4#eH98=#fCqw!xZcqwZjL-m2{
zjB*|;AYdS*Q^uYCgZMU{<h3Q~dH7J|e9_9o-r3c*hJ=wpVD%0uF}nwm^`hS+TzA!O
zsOy}wT1Wu1BD>pELl)dKTbGLZ@L?h0HO!yKfhujL3c%E*=*fH`#S1wosfAF1`RL!Z
z4#A$^l+D1zUB4NYUdz>Fj?zJ77pmxDjQAsLYm`;9mTyMBFoxz%?K29s&nqi&cfxBH
z@W;y99f({XgFXe0tSTaGh~qhB^T2|U4YNDC8!y8Tuj6U;-b;=&kQXuE1zs4=o&H&q
zT7Lkqjp3UI!h$O6IzHhb7Vju6vFbCsrWP4<)Sa%Wm6tp6`uLN1d5SRF!lJe^D3r|@
zzAB?}QCB$*_r-Fg;!}H>%pup9K5@<Z2y9JeJG_?P8GJ`$>GyzBMBI01##~K)yV?rV
z=w3Jdsk$vI38(WhGjlc4S2oR!_;$_WsrT^ae%fhNj|J7>(D$30|Iu`j{=2Kr(7!L4
z8N_rHt8Mgoys%E~#+I^|CP67h7DSLBBS;45wsF+02OKdCn_Jg5OPy2<J>q9#`sIfn
zq~;N}P{mwg1dU&4EI-RSa3a;o%FN0yf4`-=XZ>7Zh+&35l%H_>H4G*p=kP{v;V`yE
zWmh>{BsCQ!<U@J#!Yq;zNrmz!Z$8UNlB4I}RgvpOpbS4WFu+&{$mmLCeZzKhMIIEe
zC<%J~1FfQli+u0UgZoERM|l&za6gGx>lKbiuqIF2W_%LK7LSGKx4D5ZrqDH0X0<S5
z;4ugl^hWPgmxY@o?h-ICyXnTs#`9Xh%X0giJ$$b>Y=;r)=s<p1N^<hTPZ`=f)!|`H
zy*^(6rdF128-TrbiIRKe0&oSPG@N;({|Iz_e<{jDO9X=WRU00H)On6e-k`rsiC{WD
z01opSb`;0?)mHyVmWcWu!<tLTjfWR228zLdA+=yot0Gg6*?9%SQ_#Z`xh!z6gp1aF
z0_G3JpB3u3C^hxjCzb3jdEm0Ibo)HZY%zfX*yP*+bt2wb7s;Vu^v5fYk5O)lm23+N
zk)mDE65&0=wE3|Hu<G?<<f@!t9G31?@}<|_kSM=ytv0>pu3zy;h|I`}2MCZ%#-m7`
zUDB)(r0nctxN8Vn8Qu4#tWwJeF#hMc?dSUac$d@pRqx#iXj;6HgeEh4@S-V2#ADP#
zH7Rf(aN&9}4%BgchPImf^kc=Ey!8+|GzGO+ijEN`@-Devr+lx(u(aq}_B>W3WS@4O
zeYR<`1|lmtD7za}w*Cg5hv70YEM1wd{gy7uP^&uyk5<p2cB)|RF(xE3Tx%hNVROr7
z<QjbEScQ0rEpZF9*K~EISlzyDrb>kk7m>^s9>+y|WNssP`71bMA=vYH&jKl1E8Q02
z@#p2QhsQYg7^)F7XJv*6(LR~(NL%(jwGXI>4$KpR2w1s?Y<lQhVCF#|j9M_1fItnF
z@1G~OMq5bJj-U2r9pxLKN~sh6vg1SBfDGqQ!j>B%)htj|q#6{XOumF08+QMHN`Qqk
zhn48)@6h6D>5wuPnc^<aaTav!jd`j~rA2o!Vz=99i=j&aFqYU@RbtTzdzkK$8dV`l
z)Thx6gh1eF!}AE-GK<Eoj?WDdk9=|qYs0YyQuc+`wsQLbVwd#q=ZOoU@EKVd)D)x$
zr-HQb@ly}cOX~3BmRE4$cFHQC2z+V!Mp6@0)GkB4X1$Ulm5wjVOR`T1LJN>deo`H7
zt;CCFLRQ==>$939jIrYdqe+vNS6plZK8D><DzT+Qb<%Ptyp07+ng*BDYw)EJg&_nl
zMYb{QSF9)QUS6`=W#6T|01x}9Z2XyJ;?R5i4`~Qu#ODwsp4?i{ok1d}Ibfy%{iet)
zlfdZ(ejIzbhjQOgH`)%|sO$zp5A|(LG_ezgpsu9agcXLl)@J~E%xL~|$+wPp!M(Y@
zAu)_=RhD6rKC=Y+lbW)h7m7%G1TTonXlvZ*FkJmd-D`e^hTe#IdN5pKeylbtWmg!d
z_4Tk!sT+RKx5F6@26?9!k>5~C2oo9N5jOnof}%ADNT{rQ91M*RFcGf@<dr*zC+4lp
zx7)QlfNg@AualmqjGMhxmSb+%%@Deh>-Zq`dfAEU?3w|}4VO^-7L*?c^l;eZB>5d4
zmg-j{?t;7pXhG<9=nOWNF<g8ee6oG61wL}INBbVrAZ5AR8~g%9$Uiql#1-=i%JV`-
zV=zR-U6BUc*?^`~y&Z%GJUUZ4>Q5ZquQRj}!p$pyTAe@YNvj`eQj{`MQ66BZne5va
ztYW9PmB9%C2ej(Bv-wAjwEG0|>qkFB_QxdD^w6mixd7kGx@T?vZy8bqtuIUtpH0K9
z-LhBR$FW}yo&DtXh3W@KL*J$0Bd131gDEBs0aCaw((?mW;j+zBAUR4X*`2B9l0N&f
zlZT_c6fXQh;I@s%pJfJ;nLu@pN-q4Wd{Vg#ICLk!ySFSJ2#MW*H}Snrxo35|j5ETO
zRZ99=ym5&ix4+0AQrv7cf3&BKWgqt~FuS%m@yBfd&XfO=_3A^!Iqv+Ofxca9;lt`O
zMg7@spQ$i;q)M-4QKAvML*VN&`5i~BDXTb5vd<LOi?WIh>&G6=$&@SLj;KCWtU56I
z0m@b~sqXj3ZjITlu|JH3>mgn{r#Nc^o}u2&6aw`69ci_+bIu{>hQhBt-rd;y@qMEu
z=gk$P%B$lhmt3DaLo`M1ca<!bzo)rAKTJ#icqnol=#)-rMsH?C7vq|5&C%>*T%u<=
z+r_i@%EVxQh+|YOm}h}lAjDUHA%<U$5?3o&4>L?3=@nh58nZbDWU)%<A~L)m{646J
zvYj`YrCJgnv<>gpt?JH*2mujMOF*3?k5M*Pt!OW~mcrQ#0NKPN(NgQC-vIhq)*IhK
zq(D#*xWpPVa9}M{MrWQI=;?__2nz#)MaQ4Iqiv_d61KKp=p}9)P%C(Opj>^ey#S1M
z?&gasBA9!ECVrn7YK(geoQN1c6Y;*}&4233%Lyi9%38RVi4#wjfFPQ5hT-u~i|FPB
zIKf0S%xa>ioTghd(WmX!KFGIE9)qnHQz)asH|iZv*MF!3n1|)m$HQ*vR1F7{XEtsV
zmY5O3zUVo)74y<lRqvseD8SOYsFX!(A#xs{bMMOpT+~YED=qk60YKdiM4uGb?&Ps4
z+-s-mpB@)4@3TSA(w1Xmf(<H1)^F>#YJ*H<fcecA719b_WS|gEV&2!7glV%FP%!Z%
z2K%wZOO$xy7+V!Fg}0y3$b^>K2~*RHSPV@IvoH(XHSvh@C=-+PV*89$NBryOn#+lm
z<|Z43tE@CD($Cq`F<QS4Qer)A2&sPABQvtxr*D3q<{O^>niFc1V+3_^8GQJRTj=Wn
zun~UqU`s~UWqcGn2~9s9)styZ_Zn2-e6~HEPl=cDe{sV67y4h6cTY#$$b|BY&Z_0>
zNOaQ(`xMdpdpd@wnaK)nJdst##E2eMaVGsTFyLt@)nJljX3VLMDJa1#jmw^D8C5K+
z!adxcnUZ^gTESG<S-Y3<>aLy>C}5F<sFnzKR|NF4*QKLwNY51>S+siUCf&n?WW>^k
zFbM>T=bRgyn+W20{aXHU@lpvieN$oWGuL7GUFek2XuJ@FSYd*MEirJPDpK?6Yuzbd
z8Nl`cPcMDPSKlly2vTeg^cJTwW1#p;F~$o!VR;vdT5kqx-3zD^w4jK@>??tj=Pwi>
z@Xj@1-wN|+yg)FZEPST|&955^@gU$JaVniIZHEJRNIwhJ*6#H;&q27^BT`>PLkf_J
z<*J@u=>+v}@FsHv)Ulug!}f5t(eXyp{s8k(xKld9K5WHN01D7+T+jWnAhJ9-bj%bM
z*}1N`*ucS2R=j}Pz-YRHeYo(p_1OHJJ?71a3_Lx2H$$UXsq<UKPyd5)PDCR~adszF
z1rZbIAu7uZkvXmPe|+E#gT8!~iC@P@z~WI{*6jE`uK~~$aN5s_Suz|o7W9{+2m&6A
zoWess^nTo3DcpstDnFaSJ8tU_Sr&{=Xu!adlhj=ld`jAorB~q{Jl0Lm_((g)`kukz
zK&L5Z96z6J$271WhSMlYIS@W9nGjoxgD(>u<>hRIF|rUvQDR>Yg5lv=MK|^6BG$fP
zlLhZudv%|_20IEV!sv)&oKQ%<(;Lw19PVb(`zw~$qa=kG+>5k;n_B?aH3@!id;chP
z;PF)u(hTap!m4kMF*_SwNR~TLY9-!$Rb6dTV!<SJb?FX?tg$Fb?XC>QmL&f-BhBx~
zh0O4Ft>Yu;3q<mj&M)pWFR*4?pU)G%<qDD+nhZpYUu5GhmuO!glh8|b@l(pdl799e
zl$<>pn9o&y8iex<5ha2v%L`xcqsngJ+u*#@g;RJhdPC>J0i4l@N2?*nwqw#dxA-0&
zNtI`Tv~s?qWsRLsvJ&m<Pd<A9-2VdMSJqK#du|Hdoh1Z0OjXS}k2T7Ox*?xHi)m)Y
zTWiO-`K`A_xfi;ZRuWrT8bLmx&bF3PvF(hrqmRxgR0~6f^<79rqW`p!=QlRWL@UlI
z$C9$lS4f=fwBaD7Yos;Rj|7oKasT{A2n;F^xRWNYSk^>HVl_<2NxYAq&6T2$*9?s_
zNjxEshMNOMK>!HL$J+Ca^yUQ23<ov~;ZWYtD~Xo1$XcB8^OjODZV8Z?S}7lN1xm#J
zPAn*@fY6kejtF5$F7%+_*!nQek{wim-$nsrKf$_^9~PtA-Kf_pL`i6E;xl$dG01l!
zj+Z+i`2_uQ<O7qO5AjyyJ9#P1kp})pVQlmSiLgpi{b@pG$>z!I7R&c$6616H&aL4$
z^V~(Yu1pLHzcPR=CCuE2aGm?yWAAnsB-S`@-R~2P2Bt1~yHRc+X6DetYDA!d88jij
z*zj9A<4lNDuY5Hb%!RXYCe1$P$3fVjehl$yl99N>1bWi?yPooV*(|x<5pX%uMuqu-
zbjY^dSgJ#hL);}y1EhZcJI;IGFHN;Cr_e@Uo>Ud@u)0##)@#s0b54+@#H<vmxSrz)
zPoE@IBQ!+vZyAxQFuw+&;z9@+yFCFt@XR^qEG<Jj$t_G~e!XmT7%IJg=I4L*vw(=S
zfX0sK@B&Dw0)QT}mIM%D?TY6M8G<s~F|0%w<T1;m;NhOz*HYQB^Q;?NV2Xx;v_0AF
zLMTO(;Adg>6z~Q)Q#KSWX}UDxe&R9B>$79*jX_OBnpL8RzwPRzOyv-7Kzq@IBy|_V
z?nE(@>UheO6K_o)p)J!A_zpsX3zbevYjZ_PGqT|Y-e#=Dc=Wu|h(o~*3&<IuQa;El
zCS^gmjzZgcnM^9?`FfDDADH>!aFK&x*nT}_`wRUj_}%rK>Y36KkKwSHHOa7=)NZz-
z547IB#1far*!d(cs9~@orcL|2HqqO@@a39z_DyJ#78-d>`soRq{pIiY%qjT?<uges
zF9)(b=HMKs4AJ-wAKRb>Q#urKMV$l|NQg<=Tti!=O-TbPuq1-(sG+mbZ2AZY&!Uu{
zv5*kMJVaYnsJzRb_U;2gi4<4N8f|0%g5wv*N_Ws8tlz#?brC7HcQV(c;`Czkw4a-R
zF(ijT;B`aNZ2TZeXclOo`(_F`FH5wI_7H)dHy9ID4Lq<a4PE`V>rvshrW>EylsRw7
zje<Q?Gx4)cIP_!ji$%pYYMy-77hfw!T>s8J&>&tr_g6N_jl97Ll+ADV0LwZ?0n0Kf
zHu9BL1RKD?;<gtos?|-9;3Hko@4KZpdJ31)?_f#TB4Jx36choxQ|*M@ffRldpK7v~
z(u=zF^Mu67KBse+<#UpBLc6hq@MV3nCn+VVtKcYu!iSiR>q%QS5s%49PX{Xt8<2+n
zHYdcJ%Zg6e(pnLMzjtiZ_Lk`ou6^@)$bA@m(AWP7^yo7HT|lD04m9ERR_s<&1y+?a
z|FZy3wfIS46umc|b~XI%3MZEC7W0N(%EiV#-xHmlVXbsIPzyB#MxXfdFF=^$k#?Rj
z^W;cmUa2=>&1_3~V;RmMo|V5$$8=`C^Z-7sRJ1p@-V1ZX?r}KsEFnNUY+FMuAc--v
z(A!ooJ<6*xZ}bLCld<B|nW)_xGgY{5+V1e*5<F?4@TSs@p0aLSD}U+jbd{+5au_HE
zcWcVWEoWK(4FI~#om`>?9eS-CzT+%Xp>UP+$N0<WlmKtdRr*1|EdpycE>e;ev<n+0
zZ7X9+-O8O2$o;^#w14X?6H}376vfMToaowgaEcwz4GO140XyTDi($l|pOR`Yd+!4H
z`~x!s7IHw*_<l)ubF;$UB%PUSYxtd<wTNoZYM%BD2tVM~5LOo!7=6$f*#^i$gxEvf
z3dN<bVa5|rRME}sJThQ%8yRz1@$MMiG8a!=0t{eThFS5=)(e>Lt|1)g3D}@b=@t@I
zB)qg-aIM_|O`a~l8FubUd)hucI&f(&tgycT2)bX5z-9*~tFb;asLsTI9X}}1CxUFc
z1dOp#w_Qfuul9Vl7iqHIjZx-O>sBwrcPG1q{U}|GH}FRm5ggY<VHOTaffSjPIHuGw
zm7VVDUDt`nR{#w}z!0<%pe-bgV2Y?x!xTbCghcz0*^;Yuy60^(0vv`rm63sVI69$A
z`*!`sX_d4!swwFBbmSia`y$2yJT)I!Y9YSU0*QcOe;`JSYAInVbkuh#T@l_qsZ9h?
zL~itR=I7eOYjOaiCTw(z{6=d$%HF-KIwkJ?i3UOyrs+sanmzj6i?ZyM5fvbBs!;gt
z@QqYbCr<KQYL$s(mK?3;VV~?T3upj8l0uq$B#|6Zh#W26-F<Li_onj=b?!o@z(PP4
zmn9WC3QY|yMjku1Ft1Zhkd{2?10@z7NMScsJ9uZpsrzk7o2AOAa<|~cm}D#$0zaII
z3YQS{uP^yjt)=yf5s#5q+y`D$>yen)#+Hz0B!sn9O|>RvsD4wOeMaqQd~VC}Wiqn-
zN21(PI)R#5^6H5MTDAwe*ET7~#Q>ZE#1hMd^T3eO7&=583|wjFc9(ydy3%Y6Ud_wa
zy4mDff)RCG^QlonkfDxGzSpYxw8t-2imLQ<5QF^u<lZq;&Nv)Cw9TaKjUSz66XLVq
zxF<qS9JZgjPq1w07}a3GkU(zg@Z}7RW=xq^EXSdZQa-2@D}U6M39dCG)l}<S68<`#
zj`Z=1cGE>EzdCe}^M+{hjZD4`LcDZ^c=*W_u{XoekaI!^-6$uv&pLTpqML*muG<m#
z^h=g5*PaB2w^=Z_y1%DY7=E}IGeA)Ufp^E~FVrr_AZhtH=$OH-S+5R3KEn&ECE+c8
zIh`V)5HuJ@OLZ9~?M%E@%MOxG%h=ssLo`epn?TmZq;JdJOwbE+Y7h>@{6$QTH~L5^
zF2X63oU0%_poxd_0xP%C_NIv9qt;t_Gy}XL=SMa2n{#$hhNvJxhg`xSX%fAoTVnX(
zZ8}b-Ut<vtm$>ko6y`T(@VTcmJ3#KF46kJ=sx6y-<BA%EM2##Lbv*aH;gI>qa%{8B
ztrHpK8P6k<b3S;}j5yy9Rc!?rJgGdx@F|Ds6?-GCe>tI4KRhF(31QO-TH4ZYxdSd|
z>DWcVQ@19l#Wyxk@yi9w4cVtzR;fr;v(31$;DCE#OAN*g{Y2n9lnqo1il`1?sW;Go
zuV)3#JG%!Npq*LD=Z423(shsZ8vqgUAt+$sdkO!{m$3Ik-fQ$R^I8ZPjRtYiun#<r
zM96s><TC>INq;UUlaYqt8I`<1VZ9E&c&Tr9O`hs_*z?CY);PwoVPz&LyF3-r$m$%g
z5K1y;#JR<=AD`-+4V|LWp*pRk>F#n}wzx;E>6q?(+`#u#YZ6v`mng;P7qMAC+orWx
z93tDWbJA9j^j?P3mi$MK-TPlnR}YhW*(_R_RDlALH2YK<mMwI6^W51zk7_N7$UKCw
zN?lare%Q2IJK0SW6r=53Yq0}krMH}rSal=O?WnWyT>not-7qh^S`!_T0^Y0iNW03F
z$;^7@VrFf~aZ4}88u;4vOyIi{9Fm6jB+O#QX$vXSvu0YcjTmB#u@Q|)I-XW-s5LR_
zlZ`3De*0|WoD7cKojhbhv!0!KGE-?AOB#dsV4On4ZvxWe%IX)*6&C<RHKON^wNWjE
zm5_ZRNzu$tptYB~f^6$)tO(uA8d?SQ*(BTIH2mtf8*;Lmkn-pjiCY^VA=+&fpJOSQ
zEr9~-zsu^(Lz8zry@dW~s~TVuD(xG@1=`XClcIW4Q>FiLvp4SNSmsxC7*-STcPzU}
zv#vpU`-fV^5u~r9g!2jrL7=hiKt56i3Xq`?6Rht?w~cY|=3aX5imM4A=qmfj6{(M>
zC;>d{q2DW~7x3*9!-|DXHg^QH&PBik5W}&#gUBZyp{y-VsIceGYBX3gtG41H_p-$|
zn*Z@R)G$5OoaEm0(&K2)Zm3R)N-eOpfM+8;?p1%0KNr$~7^ZyT`t!C|N2cUW4^s!&
zoj$`z5Xe9UZnzX79f9@P&==fh%N#%<W%TvhR3=1g@2rfzYQVnxCXvUA?#0REuc_BT
z+fKBdSvccS<N~>d>uMTWnr=R`6>OH>j!>KcUb*Q73Q~$YHd~^X);E%IBc^Ev4waBy
zDS|v(=#3~bM`9vegZmyLkYW!%=O*8p^V4F0VLAVXK%?eTRk<yUCLKf;1PM~T>HTC*
zFy;5Yv6NeO2c!Z86~cW93$e3l+W7tuI<r59&^+AeIZ??b4rI!D1*V;52FF{CL_8>x
zYj^_YXkog}8JeX_Rv@_QLka*3orT4TZ_Co^_0^r&v~ZkRM05@^dL$dOj_7GB@t`cJ
zUMnd5Hw=V~Nd2G#L}AsWaDVRm4Z_q44;$^*MT#rb5Q6BLC5t}~@14ZhQ)X|bH8}-i
zYJhF+h04q)o`iO^SPN$^^s#<w;hMr8wv-M+EiJ|D&%Gz9{nNxCO@Pvs)>ZOi<_o*E
zqJT5*vB=2H!ofdhzK=9>zgTBI_(9_1TWM9FY)ws54@?OEy{H(!xR@W2#O?emnhW_U
ziiw`(ZaUpzQ*RQT4^>!5c**8Aju-#R^CFu_#nT~imW?35Qt~yuxAmotY$89g@gy?7
zS}#060a<yIcgF=rSDcm;wX@EF&CH%vT6a7$NNMyi54))-{QPh*SBr2UfEKi6OPnY?
zR2Hc4;BmK&GS7Q>x#JyBq=YW`eriszIPK6!`T>5&Nn9(TQchq~)hoOve_hq5U|=i3
z&9_^8uJXOfgUgVy<P*jRROqUU(8$nNrH`#OSsGzK*C1BT6p3Kd9z|$F)0Q{3*pE7y
zx1j--Zso(lH{=$xw{`0?!$J=AxzyFFc)sfdpe*JiJ=5$Pr&U<A-2JxOg*R9<u>4aJ
zCJw@I&Lnu+D^ghoOw*&@Cz&v4eZ6A2;ZpIpGdyE$x(!CRZ^-VljX2Tgtl8udr`@(n
zCv+W&Xc>`UsJjVOq0(#Ju8B-<7B4`I2w*1|cV#)fYc~U)_{iaZ*sVjAAHZCJ_29gp
zSCK~4xHGpUv^k6IVC_hfrV~{z^+v4DDxwLF8*48s%&=*=BrND`ev!`!R@Hez&`cwv
zj9okqmADGXZ(|CE>^qN$VS}JDU9sU@DZ?d8f<elrNg3*abv(4y?p~jqB1T`9b>(Dr
z;R-CmOG9T}2QRsfoWsPXldab;**Nbr<{9Lzdv1Ehs-GUhFXKm^;FUQ~1G>qofIu$M
zw_kt}FeI-O4cF%@)M+&&wPPqAj8Sqm)wigrt9xnBum<cCH7r#trSK_~1e&HW2Gy{@
zS}iAg;_qa=?mbQ}^NTqJV~i8v2^H~I{dw6QZW!sIx(J-jwqI}&v(THAZDGMy83TB`
zHV37e^Yc7X1+J@EJsTnGfkM$#^?m+Wq8c^Fk*t{DDA$-sGj;4D78GwN<2pVS9i6b8
zegAf|A|`voYX;YAk+gtLk1vT!x3#8nc)HSo6ZBqDPJAgfT7N|q{s>^T0txLF5O~MR
z;5K=q&(Z9w4b+*=)fJGw%N`?1o;5Ll#3YMDzx#iK?#9%}hh?vK>Gt;Z2xoE=!}z0L
z9x9i@mykDVu#cuXBTj1EZihI{OoYP+3FeXP8)Q(Bwk8ZXN(Om0UKO1<UDG6GsN_gj
z7CnT_yiMX^Ztz(d?IjcF++w=E?^JdeRlh9tI>3~y+lzar;$1JL3=Q6Xr|wtbDZ0Ny
zl&2A3gvx>gI(Mlokxt}+jxvz9c6l#0mW+~=tK63bv*b*Xy%~Jl838Z^M7~=<B8ulN
zPHN5;`NMCwto({g-ewWWv!8soL81&OAO|v2vE%fY>XFxu!q-PBoGF1w@QMRx?fV9k
z8oY(DVc?$qd9WwOyL3R0ACCzuz=uN|w5eYkeYmIDW{%06F$c<WSUMcDMXm=ohu$WI
zJ%<aec)qr7Q2E|h<SrFXAuii|2!81Z3p$LmgoW^n#>zjWrQ-I9cKU=0K!<EgKk9zZ
z;QwlNEs{577m-8POd-RSq<pU#?`?w~Lx3hfXhbQxufN6uLh}x8{3m8(|Ir&j88GLz
z-?R(pdD7boO>lOV*bSy^g?)r?8zN-W(q4>Y;M0(2nN!Yj=B!hExwkd@_zuH)v4+q8
zjMW0n-pTZxW<KOJ(99S$NnY9jQL=NVVKXa1ajUI9ki%tmqG!?|`ydJ|04JiW<207A
zs#HC(9FSH?LRLT04PWBopX9-Q5a*+3HfAB74&!d?447N1fo9z7CK*yz(@A8(msfdM
zA_S8p?o_{l1YDog^8>Eq%bnSTiI9MUkDg79?cpS0sU@A%eUotNL+yF4O0RqmI*Qm_
zZGt#%H_0wDg=%?oCJ+Pe_cyVHNta~=eRUq&8@Z6t+X(X<(C{}Q1jIBK#5rwv(c>oq
zByfS@{&0;ApQ0TxdZ#tx6_A8?Ag#2Tx|jhsjO&L6q;jf{PeguY#r;fra@KOyxY++x
zg{u{6c08E|N2+Ct>B@6Fl;955FQpkv%Ne?m#LmtJE|73%*zB|GI<6X7isl?H*A~A%
zxV)yJA&u7%y5aK%mVW=yppB>Pc$h;7a40ppXNDONnwG>EC;^rFoN<WfEAY<CQ_F0A
z=mE9k@dhqCmt79_StClX*)V~hM$6ZW4)V{()#e`RVZNP(hX}y^qsVDTNrip+d8^;E
z4|$H$nCP02Gxdv}RTp__LuZ2EgxeFKJh-6Ym7%`UmQ>(-^QF|X0oRM|HEce3Lr=<2
zf0V!vr<)IW7XY?u<vj_Z;XN$&uAr96%+c3+7EiJOU&6IBr<ynRf>gh*Vu9$c-lQRt
zB6lm_Bf-Yhl8SS>{8Up@F{IC%eosM2H;ZK)FLN8{nJdFqWdV)g5lN}#SnAihD^FiY
znH`)25fQqAqQTfiQ^_F^@Hsy0_Dx^8gLb*>ti0>-PegwjP!mgqm-z7$!*rxGZQ!E!
z5{tW{Z78B(+)9-|4xlT#`pUYWcsi7g0g;nM8OUf{<ia|ac;juJi6h!CWI$DR8+shG
z)!-O2r67KY(|mTmGQbJbemrggWVsQJgN<lf(}6K6diu9n3{8SVKTX^WS$KRav~;>D
z3th`8wi8V~dlD_!ZCoI#C&mJa@~<ZSXw+njBlY064@5ys=CJTKq3ZW0)nsb=^7R1C
zl(y4H`&ywo>x+Ehf0=pMMfq|%NMpzL`AL22{t1uIljdG@I5+_7%G9UMA(z#Q78ud2
zF%*q<h(Atr63jPZx!&y}6L#5m)CNCU06ZG2z9yJR+1p>>k2sLIUFj}Q2PR#r&lIT%
zz`?05^ZE66U_LG#ZaG~gl4y!)=hAeCv$0CMt*FwX)8N!6QRqaXi!0~BeQ*RQxpLoo
z|2|kb>6l$wi9u^=n;<C{R{NR10$YY61zfxVv_-H~@JoAPOE(O&IZq<@wKxTFd*z){
zi|c;1DD>Nl4@Bqs_b`0lcwNp82?8Yf&~=uwrG}829WPzUWiCR=!XgP8^nU7Z0=muN
z5+tPT@3~R2k0Xj>gn!LWN=Mxel|Oekb^@BEOx#CgkR?1U-t_PKP^sk-^j^T*@|yO`
z&SlVbjTD+eFE&TOu1{Uv1seYINxd&cN5~&PRE-!FK}L)(Fgqq8RM0US%X?AC@~46a
z(+kDg;yQOCc5vLPdDiO<lU!?z|5NIs6G{;lA^uxlw_p0}cl))a4M;z0tDQ38Uocs9
zJ;ob2Q+Ii^P+_a;si&~cb6IHd7+k2ZAs9Ph==(<z*pUJ)4w#{2;S!$Z7j^Ak1T{ux
z?~A@jAoHh2dNH=Sz}?iqs5q+Dx0reJTMS?|71@+L-HR70da>N^f+cr}rrBKa@Kdx9
zn05M6{DI7$o$|;~eIohf4hk^=o|S7jYRoQ062v*`Ah6NuJmcy>d_fww7T$!v290!H
z|4cTu*MZ`i3D)vkUNcW#QG}oM5rDSwhN=K!Eg@HjC_C&jlW0@r-&}tO8bI|E`1cs6
zVOf#_hzpw9{9`M!Y})jKo>WMDZ|x*Ia@m>uxq+&8Of1%`B2`flxU~PuWU-OvF>5*N
zmd|`3L#}Hr`(yE(%<n#;U)y}It6KxywZR*<ba$dncon&RrdMS;vb6Z;%<(u2zo|Cc
zd)7-@0xv6zkh>j+<_ajIKt8O@CIen?42@^a<`r1EFy`Ju0faX*;`C&mXmC|@tzQ0)
zK`kb+zhrsX0WmN4)vj=dC<$8cfq0AU(!unB8pV}VpGByNvhZz%Q+LMXjGqpL;get4
zke$`neXRjtyJM`)ZC!Xzz&`(T&9T=bR$xVRq<mfG=*_G(KY5L~FwwV>i!W9c%wf@l
zpcQ_SQkxy#_;(ki%GkuC`bc7QePX-Qg9w_{_O-=z=viUCaBz%z8_$BEk5SG&f-(~X
zEBJs>B7AcNZ+u_+S6y0*iJeiFR+MT>joW8!-%w943~EdUOy8tUaUYx(msF!sKyiB@
z#(#@_UiWU=q$0@z;1M?wi)zBi!KIl}H{#gm%ZJPHLp{uUI<Q|02~U73&6;hQAS}Zf
zTpG-*g_oy799?}k_D;RzxqRHDqFa#6Q|#5Fbe^tan7;Ah(nf)PFO$C2z1egRFRT^?
zK>K<3r`nuLleiB32tn}#c~9k`{iD?I0$r^&T=(nP8kGS~Um!HpY5)A13;!x!UX&=5
zsu<kdJueuxFoMcU`WP~mY#{KTO4FmM+u16_PY0@z^-~R6?^$$<QdIc|0e1|O7D#pq
zw@%`9SC1C%w<DD<t@c74j23`;qeB*_%%&{RMilzswBdb-B{Sh=g!F6b;cUtulJZ3W
zJfJ|Z5oGGw6WCx$=Apng-D+^&8>N1-A<>YQbhqyTs!^<4o`e@?MLUP9*~EhgEebZ8
za)d;mdB6ZWrLNLj)~qMa`Wyycl>~lNkL;SpIsw%h`1$wVqCy*U?c@a`vmgrrPd=4X
zJ)`_IR5MCd#$pSlb%BR7dn1SIBR5*7yY#YYwF8;AX2-~oJB*v!1<3I>2~LuTCJrm9
z*5Lz2^Q|`z_axaYbtb2|>+o8(wQ=J|#y(&fNY{+0`W$pv5meOT<>dtm6o%b@5!#cN
ziwHe$GeQ#$+njycd?ob#S3V;}lp##`N~0VRH`+8nLnGwox|3Gpf8S64`#EG}z7KBX
z)W_sB5Y-!t$ZdVztdW{{NHI~YqqN8(^{qdZ4JY_GH^9wF@-sc5h2wa1N2`&;V_bn_
z78<f(9r+0%3i-l&UoP+{FF!h8_j5tULp{k5KQ(n-=10urvmimd^#KUaSy)m62(u{7
zKWkwm#;;EG@Pk-w!qUW&Dwk&PLL1H}n?p#C0Ova=V+2C8R}H-5%VggKcx~q^C-D^(
z&T<7kB!i7{%p??alW|+Iy~j+xfHs6&r>7kB&4d>$ox<7g8^x)r4Z{TH@r#pMurli2
zqvq<Z=6N16pUvKy%cP26_H@)P?42&-5X9&cr5LSO4f=4TD*P}F;gYL8zR<P$Gz!l`
zJ;%ue?qS2Y<_ROrlibX5Y$BLnCruOEIfONQSUwI?YnzcX4S|Ejz|<>A%M^K5B^flb
zjlV>e3iZy*SL+u(hqB2q#e5p6G*mhvF6HB6*yRLwH>daoh#VE>G)x@Y)H4~&c^P2I
zgcn3+;#8vZ4!ey&%yYPLH8p)}J2wlp4Y8+V8sPJoHD{YTZ#6CzR&GPE=M~iklA4;!
zxL~0`3Y)UT-pz9H6ac`j_8%Z`Gd*VkQntD-cJxOXO2lMMt?Ujr<9VFW`pQwle~OY3
zr#M_p({Sum5XCn?EN%eaJ(lbg&{u?f;<;RRtp;Ki?1_%w*BMdf^U${omTDOQamP7T
zcc<9<7=h`FWn{qux)ovr6!xOJJAOur6_v<Qy8;8^hRynYIji4Dn_JLdAOx^U8*D7w
zG6Cm_seQZ>tXOR@8QsrkSqMkj=l{Unrry(ePo(!B072FbMZYzbP0yBnVu-6S@V2~L
zhm0w{oo==8W`BCm1odx`3rUB>-tk&~EwGpiP-pj~bKNP^BkwC*{spLkIK<Mgp)E!3
zZ$s9m<XL3xIgL||eBgZ|N1wKxMl853q9q%1gJ`yuuCq@=jLKa5_}=atV7JsEQ<Tr_
zSlk$}MF)%@T(NSeM+eR~O?>GD51Ua-*qALhq4ae#U|PuY5k%<Beq}ccVQ@z+l*?Hf
z_HYHkq9Z6&n3gy(47M6Pd`G96b82>yViDNn6A7ptQWdPJNfD)oPIPwcfshC3#<zN*
z@x0??7GCSqVetLku|507BCUM{Rs8kHY^hlsnvtqgt%+&d4PaEFiXZJxEO0XvEg&__
zu&{;v3Oo6Ga}BXOWtHF-G-4s97nWjt-a0ey7Vgv=hAgvU+M#tqm8?o5!FySGQ!f7@
zqI9B+^`0O<!GLp&_Fhun1KM6c>s>G%^EdFosTmtAt7bOLKZkVJ68zGEtB6l{EP_5G
zP((f3dJI99lwO0-)ePBOQ({BllFofK0dtME&|C*wIrn;(s{iXm==}B*w2^(8k*BW`
zH#!*ia1M%@AnoKEx$T+&MI(>rAS>9iPQd&;{d!p@U!~FzGp%jhOX0%Y9M}LYrNK-B
z|EGgjE*7H?mKAiA;c0+$is8INVY;sh<Pgo?_g^OkxO-rK0n~XQ06fgP6o=XW5s>A$
zG3}0e^82ry`F>|X8+6QbE}`*rZ`BZXhoGS)^`W26?^mB*=vumwfZ-{7twYi4Ef6Q)
z>grqkxs-tf3><08ze|^Yrsty48I{(WDreXn*K6YFB-&*!F2yc-<uTG>iZVXs@OnRe
zfAeH`kut@?#p1G2rR1U--uv9$3G1v2|E^zQwq7UYIKD!yqD=#B6UaB{^{x($*AIJ#
z7w3&38)`d*R1Hmt>3g*<s9{WmEtzPMQs|rL`x#ExV9EvlA*QFbH|O({m8^s)+`BL&
zP!t?%93L`rF^$g9^u{N!a%*T&$HBUFS=RAW)H%S~&x{7GEwjiy|5Djy1-fT;V>7Sm
z-0pm4e@VQ1kD5cs&Tym9ySGEJa-`(*VkD}1B6d$m<yabyn;nUP4C)E;ZVH@L)17Ec
z;9fG1Y&f0&8l<{BRrAIXnyX^*T8^Y)ap|fq0I$Vk2Q~S90IN^@Sn_Re@u-=HqZ<b-
zr!3N^9(}LU%d{1ZDFD|~0x=d8jy5(qX%z&!=Lg#Y2Nfd9xXS%cK+*zbm<C}qQ6++$
zr_4jMUVM^$JH(QZAXleaN2gEzB>r1ljTB<E>=$P}UWqLEaX{y*$Q*b&z?2GN^xrFL
zguK$nxx*)}Rg_X&<PMWH=KxieInt~rUG@Cmcf<Bt_Fc$Tg>A|8s>Ke{A(9UL6tTAg
z=eL74S7fk;0%&!hud!1)sd-jngtne={Fq4-ksRyjz5hB0(??eAT(g>TatiG)xgg>4
zW&0RBq!=5Qs%2MvQRbVsYDAh~+vBNH=j-nMy{kpX01JCeH5)5WFX#UWG@AfGviD?O
zd-+#*35cx9E$3yZQ9RLUyU*lyc07zAGB6yG0q&l%qlf{9{zV5Vd+{|vdh;~n{cW>W
zV8+ifS-0IAo>y<47=I`xT+g&iMFktI)R-)F^Zy;ZQLF$UO?r0)qSNS;&yDpL8-2Lw
z*P#_;OBfNcF=IMUni<k95}JHca-<E_G1kR&-NeJ})-hcDMl&pdx*|p87K!-wG!FK+
z;7YoxbJR&cKWUbB6rWsC4i9Wto_<%Jn9u{ZPKEEiYTts6mtHW&#h7xUxwIk@6|HZ2
znM)dg27_u9p->VCGp=Fj&`-d6Guv|{ITQRFUB_Ew;}}3vOEWWqM#M@u6jpv35|UrU
zg!k_Yb#%2;j+wyye%csKQYHpEZtEvYXyQ-Nc5j)FLh<u?zxOjrBl0!BfJrIpuWuR{
zgSdY>^(~jOgm~@4C87PyRs_m<5j7PljPJ#aNwhAu7b@z=CQn(Tt*!8|;;qgoEHS)M
zc3{(-Td<X^pqk4)k(d^;F|?8a@*N0%*j#`)9fz9rT>v-Okr{T)4KE=O+d<Eh>PL>r
z`uH}q-iN`F#g7|?F@777@8?OboK^E}wcq0+EHD*HSuAJRLr)5M<)WngjK&+Fejyfl
zgwyC#Ut&hDhn*9iq`w1MDRL;FsO*pyLLbg4pxBHUZ^`E%%-&z^p1-VCEWNm0J_O}2
zoAyo-c+Ti#@7guz!TX2)i#~KUvHc(O2~yG#bOt$NfED9CND`WV9EdCAx$Tm<X#b*-
zrpvV&lvF;J$fk~bTv~-I>$dt-xVoBE*{A<s@vqriz3u(zk@jZ&mS_=yR7}&+Y(+1$
zj=yasP>_Ol-bYd#rmz!tJi$xIZ=HH^ct_)4qc-S07ag1}k>uvvQA`H5f(CKy4^XN^
zA2qa8s!8f9aO1$KPNj=Lv72Yq*X}5zGR32A9jJP9riXADXn-x@K~Uj<U^SX8xRGCc
z9TUr%9nkHUsfO?>sLV<qL2e<bHsJ;C()L*86PolGyRr#wA^qTCQ?Q7*U4m?JJ}kx_
zo$FlWdJ^FR(p9|{?w;Ag>Eld)&!}-}vRLZ9XUA0bPJG9ghSe&@t<|?;F&v{vMnjh$
zM+b+2ju$kIhrQmWcPRcHx$B2)%Dh!rQnw!1@ZF5>Y(mr}ZI0>oh$I6wN@U|E1a)v%
zHY?!g)i?{yr%rnNY4%2>e5jp@C?d6)hTZPx@mNk5sJ@yYe?DrSX^#JKK<qM+0Rw6+
zI*TN|DcWZ$)+mPW!K{7|^$_JB0rV*P6tLt){lGg?5aQrHxH^Z3Xiw5oKO3=n4U2{~
z4>Y<P>MAX`2$HHZL)FV$hDT?|$iV`UiBAka4$|-MTFjXH>^C%|Zr>b4(nPYnibSn0
z7G0zFxSDoiS7LGz0O`KeYsV1f3+4I3znS={qYfs0n2$&6xQTcgX8SEv+r9kLAM7L6
zSB+t~G&3aem{-mekHA!}miAq|up#RPv*NKsE6<%E1bP4f3Ee1HayF{HW$b8$jVCch
z=m9smE3YBxf50;mR5Q{9dPJ{uxtJLz##5+IY5;Gjm&M=q=ZTqr;VaMw>5AB<F(NFc
zIRwSyYr3yu9#QKr5XhgL$uW;+dG2XqJUZ7~^?tn>j@NT{As})ojtN(_J2s`s!IzNP
zd!foDWn*c@>5a;&jKqk)5k&sRu0k0F23aVpwTtC~?9>qoRpl1kJuU0_3v&HW>T_3S
zX2J;|T1#;7i+Wxe47%RQG|oS-zyT1EzjMQ~bDSM1o&-31Y&WI$29tQxmf-C%(n8kr
zx%q*GIMwx61^PxRJ{14it*1^opTUu-n~uCd{0(i&Ha0o@O}I$upBxOYgtisL%0T-n
zGJqlZ-uw=gVzM&j(!*Z+_tS%O8hcU|b!|#rT5mH`7saoVD<g6PBzTH*SM6ODPQl_d
z*KoH62y=keW7xPKopHZ|Q#dAp=h3atG#}m*OFCkxeK8~wR~mn03)NQPsyL!7?13Qc
zSezMSIRI?YleHhSF9OPn6j0C5rQIhlf;dQSYChB$Cu3@uRE$9pF1dZN1t8fa4O{?<
z@L5rs(Bf~az8m}@+ORP##g|98!0N0z)1$0mOe0-RFoI$kt(mU`&YB0Ok8Rakf}sVs
z4a1Q`uO(t$KSrOse8b$iy89e?ex&inR81KOnT#<g1#Z(zUra2B<0@g(H4dwmaz&i?
z<nYSrBZsg|S?pxDtijeA1)cDM)C(-vC+x0JR3&QUo=Ye_0OlW@!I*0MZhPSb+~xPj
zS?me*9@Et&Ici=m_G=9D3P_|#t|C1^+iBdv(+wkf0P2!f_><x&i;ogE2>IcWq!dYi
z>)hJLRNdN3|46`q<j5ggjuC66K_vRbWgSji=R7*Oo$`Iynbq<3^yytfXHdoW{4-|*
zQw~CA1V;}8$3Ua5R+IlZ?cUOk>`TmZWdFl8*l30+;k2KLLvkl|FnSA)r>Av042*t(
zU-%;jzWL6B4gIh?8v~oyS1-o1P~qCsB7&g9Q)Mx28h}NU_p9LDSDsvOwIcKpWCJ?g
zWD)%!0fXq&x+|TcUV{kAKlW}Z72hE^I`w$hN1l|p?V%^{j4VcR<Mwv1iC;DIRn8LV
zqVND9#L=8i=-iPjUF|z%j=`j|ING=(mc)`Vgw%(O%hgA0Bc+ZuCO8a66xa|ncJ{sx
zH9tI0G5dQ%vie!nG8o*zWZLUbK_rK6@DH^tC|Csx$npQ!St<GCM7K@?FxpD5k+|s^
z7IHq2T$fSg{sl3pCXs@gCT1^ih7?8qr|4Y;##-oS+%mm9a$_Hx^*V|u+Wmq~xDRej
z^KoT86VRA3qa%+Zx~XyDmpFjizD-!>FWee=lq@<LoCOU;a5woBzfa|e;3Vm@428`a
z!%kvSFB~q8opcZG>b7ODc$7Hiih$)oF*Vyt&N<`Tm8a1I4ul4RFI|J@ye&RAXk)HU
zf21UGMn#i+3b^q6@Et>t^}z#sW;Wfy2_H6SajIv+Vij3^^8dT{GS=kuHe|GjWG`{5
zOu=Q|>@=`*pr<dO$R?9udL$6(aVm0oh!Dm~?V5zg76QkLaB1WBS7|JEEnicfmy5R$
z*BD*^QNg|Ad2Xw}@urldP&41}&Xg{a;<}&2dpecYHXfm7L4k<SJ^9mGwVrO+bXnAP
zB&`oTG8ph=(asU?2fUHdH`~9}ekWE;r;`A-+d+H0asHUVMg!!x=2sH%l)tC;yKP<1
z5!=0s;l2DzLEsJ6?MksWz1lyM$+K$U5Z{Q#Zp@u&fa4>ZFB)Dr+tHgrb&4d=W_g8z
z!^*Mb{>J8LF>PU_+bNcO1C<msYu0vOomooJ$Gd4$fSIoaVX|qYi*i~sY0<Rw+jd}r
zd62QYOIa-oWd1>|w<75zp3=ZG!v6WL{`!lMA=}=@H~n>aCp}1YJuL`D$7u~K*@LY}
zl@Yf^5&0m~E?ez`>S9k@d3V!7Jd%eV=zb!T{)1?}XA8uyfM+&O6wF^#xMYbGw{M42
zVES}}9Tj189-oncOvrI`m8{+G*&yMmvU9)JHMW5LVrJsbB049M)zhljL|<s}n8}2(
zN`jy0l4687T7Yd+!4L%pZh`-lBBdi-Z42Yb5ehH~p7impn3FT4-VY|P5JI6PZ(|C1
z40%Wi=MgnkeUx@_hTSU7<t_2bCM}MBf#b%_HykIQ#U!uIf^)a$hY;>75{)ZUD{NLk
z^kN;7?|FK}j19;sGW&xFc63k^!i<|z&P0q*&7#>4MrWSRVPyEFP^4;lz@lwZXW~A|
zf9!)8#5uqXmsb)KD@T(Sp%xX_V<Ge-dBc6N-R)ieF0NL7lqh)8EppZY;x>xIRpH8T
zt`P{r20en+wr!TUuEM@2^n@R>rh}i&)5Em;Z1aeirtNfNn;mf9L>NrE6FtBc`)O!z
zYlPtw*4|muG^oo*HcDZKOdES%T_feW8Wy|u72H_ZTuvFD17q~?CU*cGQ3`)<fC=NJ
zh7R1Fw;VokyxJ13{;VlC%I({PTlk{k)3PqZ9G+^foJbt>zH;uI$mLI1bK!FytWMrc
zo<iDzMxA(eXLI>t-Oi*Pn^Vk#kk<4l8e#D`+->5kZFC<McH`OsYa9_-8<BrQ%b_e<
zH~aI_tlb*Yb@5BnkwRh6(BEpxCvHa{R-#(<+j(A`pEF-9x+ML&vQR-6b8~@H0oJiE
zP}+n#d`-}oDD|Su;AERkB|t@$+xW0i>DrD2sIum5Nxv3Ho#_62+>*%k-l={+BP1}T
z8{CSzErsEF#G!U3W!Om~LL4K5jwebUx6Kp5q4Y)~U&Yy5H~A@qR&Gat9O!L-r-=9F
zZn9I~n{)N%#$Y_he9PoTt&%AahDCuQJ%QyD^o71>ajOjzc`F4M9`89T<bA19RU0}{
z1>jzF7~NnR$$)h{igk{xulgU061{H&FMLOZjhO^NnGZGkrsVDkf=b32`|T;Jdr5&4
zCBXBu{jF`MB&ASXyGh@U6Ik#IAeHU$QAAV69u_~Pu!ypcvjC(0k%}j2_NwKtW~kNu
z3?V<=(o(`MjB&+P3x8^7lWhp3`NrsPR{2~C1K^#>)kze$VzepAc*JLN%6^{3Cw%jx
zW7}a_d;G!SY9CF{quA_Y((U9g`Ty1<p!<lH+3oPv9(`Bf;x&qB^_KH#6c@Nk#Y?jo
z`A`ADlm5gZFhDZkILy$%V_fX;i}@in+#0ys#fm<c7SuN$mC)mFY6hzZu>MEw^o^8u
zhiSv!e4fKp;GyXZxQ!V?QEE@0V`9=sTyu%et5Jzc*M9;-$QXfLP?P9aUOD?0u<;|y
zMz>p}FThGd|K%s7cc@IPytCI$q)?j-H7({$N{VH6^A}XnSKmnnr7pU0I~fN39Yjc7
ze+%kBl-0JGUtS=)Q4J7v|E}sP@sHtLougeT92%NUPbGYspK5WL;w!TrYu(;P&R65*
zS<Bk$fU(Q{Ha0$66EJ01v9H{%=<zh+Lrphu4qCx8A|x3~AW0pKjT=Tb$gRY*N#0fW
z;B~_Q#_mNhH2zu$WV1~u5e5u#>j_dJc?g;6wkg&&4R~cb)PhL@DAM<l7~yup-l5?z
z8UgUsmAig1qD-4go?lh3bPWz{88B$+;@;vJje-R&{}lB9j5$kf;UHz=&|~I7XEN=S
z;G@84+k#Ice{*p(+Bf^a2JeLN-lmRk7nIEwY<K3Rw~X*${+-2GuItv~ryQ0yV0<IA
z@qI+Y^!g@i>MgA}Y8vpJHDM5qdY!e$`<?6q+|#{I;GvvpaHYys6hv7HDMw*?7&V#M
z|2JzyWY2L8Q*fAO=K=8dvlxE?mChroxvQm^yU-esqUOESs!(B&C})G;;y33DRi9Lx
zd4*4syC>^+c8)<vZbB;DM90Ps{vQ?kEW#DcHXorr2dL5#W#&jv8G%BV7kwmeqUhG3
zQyw%utR}7Pvj91$rx3QF?6yseA-Vy&<H~&o0rKx$MCcO>f9<^PT=Bq3jvy8u>F=$5
zb{RWk$2gn()!BhSeYqE8NIGHa0a&>U+xDS;+3#E4|Dlw)sxFrHxL+G_$7QQcGzKi`
z?6d-=2uLCf`N`u{1{p=cuo-O368ltvyi9~dgd^b4<(iLxVKgPoE7jsQMM(pS&6FQ0
zghwhau*R1clB>(trNM6VvZ;oWbfQcVG^*>%T3Bv5!`}lGw}rjIobF){XtPX%M=D!!
zw1YT`grEH+3_CNFpoe{ezaW!BCq$=`UjX?3Pz!|$ZXm(6^KDf4=dCbuqkXGJI5~EZ
zLT&AEt*|V=;14wnZ!16MLCrTF*#{-}uJ_po6*731ccsd7ha{w8bw|~J>tP!_ZUE%&
zAuNC&4o$Y4mEa3mKnP8;CU{#>7^Uwh#U*>`Dc_q%kF(q9!a%&~AMiSJsx6Oq9J{{4
zha}e6PA{3t=4E78l2#plw^Tn;Q&rXik)&s%)ip7$#Go}^v8PoX80<2zMY*~}K8IXg
zNG#p~XJ<ijPtVr*#8+OI)FOjbPv>d)?kBgK;clfM%d;G<e~cx>hll%kuL6A7kT^J<
zx~w775qjv5KW$aM;y_&IfB{vJH3!hzC<e`u{m~FK^0bA7M#hdQY!hxqKMAtH2@QIz
zR*MfpX#uJ-e!?UkTTjg|R=)>=lxXAkC0M{7Nlo>R;4F1g^+|N$TYT+Y+ghCo_$_iM
z&Y+AC0@t}qUSt;i0IIPhThk){kp;Zp1bxH=2x`g~J<{p4^^>?S>v41sxVHIPt^xTh
zGa`#+IKBjTF&Dbvq$t*-jtD|Nd)}7;%UTU;NZMM4lyhQ$LO5(0wt8J>kisR|?D|GE
ze2LOOkP_@-$N<9ant;?lphp~{p+GsV3w=v&m=wDm-UT~-V2+bOjuGD=g(r%5I|6=z
z9i`5L2!rQ+r4+N%An||Zn9mlqSG~lmnWU(Ix30pRkvi9SH9ERM0JM1*sA`YH@>|^I
z?l2kNA&6~evgSB*OiQ@lz8+nGxJ0M%k)O8+hq>vbQ!3D^ZwQ#&7(q7qy3jB`j&`J?
zjz|2jv6PTa8s65^47Kr23E3L1Z%_-j!p~0^jr5nWK@gwPEvd3eBHG8SFTBX@TOg-m
zdJXian7S(IC6J=7P*G3XCg|@V{gZxsBRPiR_xRv>w#?D2CD>#0QIjStE{k8j6P5_R
z`-OCUjSE2h&a7#pNJ}XhrUW>QJ4aV%3)^;?sY16HfN5}54nouUStcGHKwe4bEGr70
zQ+{^Nx?Pz)NGIo`xhyh-^g&S}rDpRw8!{AjVwp7{n@@Btc0?lr*ut!7Td5i&rqxiQ
zq-oErHDiq^FFEMDM09n!Dx1e_Z1g=g6G#MF7+e}$;ge*(VMROUD)5V<IWL#7mPCg-
zCBz0@A*_3~-^Ekth0Y!x>I%pR7@nL7fb0fP>J;b<FFM}6#GpO!)ZyHVdx<6YTFpFg
zm8lwC)gXVo`<AgVon{a#U@rxgNND(DBm_+U_mI`-Lo!Eg^A=G)$~eF@Tr!A1Yyml7
zrIj<Fm!PXo2vkZM@n5K2({9`khmI;M5HFT;$2^51QXIv)8EV%(6cL*!W!CQum9dlS
zu8T&bSy0a{J#8tD>*S>!<>+pKpsoLolFyNfOG8bhk$RFmBE=*)&<pUi=R}aq;MMd@
zf^^v8^MRX0JJnW*4&B_i@*It^%VFAMSz6d#_5a3Ceeah++tPWwfH!IuK((2n1@_W`
z0FBQuiyNScb5~jC(s?u?pPE)Ri_Inr`Mcu$b_Hx$D@B_0GK!2r_db6h+F9T4+*Dd!
zg#nrNAr`RK@kuWsl40CHV7RX^f*`K-ta>BX;r)-&eU1~nMPRsXrV5`=riWNx;Ber=
zF{aVcRIPkzGiDoPl)-)g5A2CuK{2Seh{9AloZc2yAxpx-|JheraF-AY>Nf6_{{e<D
zceK+$KN$u64zw<K!}~K0ZEL6vLtP)Sde-F#>XFwZi3u>+B3f3WPf9?^j165U9<VTq
z@<&;!?TbmP>KZd7UEQ__0v&c+KFJL@Vm!L|xO)1fMQpGfV8#Y?L*%pZM;&sw-=o9i
zX&nL=e+2lAuX-M_SPhOnQa%rB2E;@-Rh|*4F@3$T8F;1I{pG1%+kw$>I6b=17*3Im
zjUG*>B;8}0%ok)ti`x~s)2^T}{SxOAZXod4@fhL{DeyJ>!%=d;qq-WeX=zZ5{Cx;6
z-xyd=DB{aYPrwVaeSHx5QZ+6sC&}`~=COc=<@qoe(l%3zhED^q_+qJhgaumG^$27P
zCTTo~gp;}GV4Hpz9Gz2jDZ>S?BAhO7;^V*D2}7<}#g%tz<*ln<X}|{w!x$~j1}Ut}
zndG6Dh<jMO1Iht|Az_NksdePgqN_YMyg8IfJZnr0!t4`@&Cg!l9UI_M4lk{IfPaVc
zRJlI;d@|}hI`a`A)?=(%MS?K8`x&TZgYgS5hXFqGR%jK5oQ<D^w-~%y0?JGpekPDA
zbm{G~xSv*7!Xg>7J``P?mcq@asZoCHczAFK(Df%*5ce{gldCCpmLE`bhtn2&J1YzE
z#D6$jVU#q)J_bPy93;Uek0>fsT`^80EYlFfs`h2D{od*dSNh!yo}5`rDG0fGT*d07
z;}&?Yz$H-h_K4do;M3mUFH%o<hgpY5k*7_g_39axZs`e;p<M>DN*J5(W^c>5G3yru
zcLa=xDhc#{|2|^)FjcJdo2sH)LF)%2>UtLiT#bnwR_obvt3Z4o&b+Fs__@KelbM3K
zh%|h2!q5Bos;nqB@rG-Z(PS2rFH9E2OXAu)@qtRUO(z$FOC@|XNem11WY2(*z`6e-
zd530fo%<5ezx8UA#Q4IN3jXEP#=G9dSvK5Ip`>U!t)-v&nTk&iOqz3zOEqq+fb)s*
zM)P8VmyDl^8EN@)I*b#Vg*^%iOzSdfh8xN%?&5*m9u#az=kNXXlR$u$hVwhR!l{G&
zi)D6&!c}!q@ipsY)|iAjXUT#T%LMq^7FASEzJ089p^|ls;pj*9WQL<rh&t0KQo~U&
zOr97gU8LwHjfi{5n<c}!MC+auumBTGB^>;W1)<o%!^ok<^X^^rqZHZax!3BLMH^2V
zC0$hoC+Oext3sy0uoYH!WDp&v5h2p8yMQZOpbf{5#kWQQ2<rYhFIH!w%kQK|{x&Z^
z;r3Gg;Im%0if|r=J|CahgWDTMu$p)PVUj^aTTh)wn{t%vg0NWS#pFfaN&$CJI<P&#
zEyZOpS%`4j@O6r)W8J-gXVt@k1BLQtjAq6nf{1H0$VROO&JmZ_HoKvNzNl>(AW-vp
zxq{ox{OPc)X0`v6wySK$jMgL(@j@DG%FH1TH|0j8y*Z29(JC$RLZ^;b^$I2yrs0r7
z{!7K+F-v<j&7@N;_8u2!iJE@&r*vw3<c=HdS}4N8e0VN;0daq7K#0x2f>WKfI-mCr
zZ&V;6mJRlj0ukqhK>i4fT}_yqJ;W{RZ<a>|-W;3=_1XzAwi_aGotr;~CdYnk2ZaL=
zUp#mj;6j>$0$ffzs`{;*@bnSwiWUc|bKfBh^xSj1_y{#w`V~Hb3tLBn-(c^AT9*?(
znZ<4se!u)lRyEHS?L*#Bn&xs-0(V~n*F~{vjUKi@F8<XmHv7`ZM#5@F_yYYex0yF?
ziWMZ;GZQlok23TiMx-24j*=Bb*EAj|fR!UWTe7hCU|_^kE;A$tcyzZ+xo`L(SZ`tI
z-M%1!j_>IH>~_Z?*H=E;0b9x}S303Pw7M7Klh6W=K)k0GJ(y%5Rs$G=9Y=D>@8PT)
z`Z3(e@olOfK#ez;6!sj~;^>p$n(}RqIIE)b(wI7Wh}N;-^RPg+AiCGQ5K!r_z0|~U
z;!lLbzPZ1&bnnIz;U599KMr4|T+Q@(ZF8zjcQm5hJe^!OXm*IHB<-vwry4So8Q=<j
zf5^dcQW)e|(an16YI5C^>MIu_vQxk2<;#m9Gn`|T(wk5{zg_)u?;TB7pEq6-a2%Q=
zX%TCM&$*hGA@{IYAc=sWfEU5=X4o}S8N^$R);eM0c<)K552OZ?SbGnEIp<?vkp}Vp
z5<gPo)Z22;6omDW0r<BjaoYM)K?SbuJxR9T<8Keoo;3VTlAw8HLudAo$|UAjh>f`>
zlg>0|TGx!kOtD{2>L6`d!U>Zxf`Lv;a*d?;4Y-1%s75L8W=X%)MiB?HjG#2e3V-1R
zgak51ywtmGak+6n#zc!?anZ%O&3MB*@g{Vb<KJ1N&v~n~<5vndtOngR{)?U|qMP2&
zGgejly4s0xu)Cz)>-;AwjW64tzzw5|P>yB`x7wtP6dz9{*EQc3n+;F1xT!fHyp+ZO
zz}oslZOy1dmLdnv`_*gwFI}Q}6qzHoC=A9RJcxuOW>bGSYHQbJeT299qcG)t{qKbt
ziN8F^yDprlCNjL-r3p!v@{sizs2`e-Ol}vG)nazy{u8?V(s8<QRy6_pJp{vzudbR9
z6W@oS_t3RvdwmuS+q_D^&}Nlt1Bn?<36661oGC$xXcAsKZMh>O5>{~RLSiiSar(K$
zr00lJt1L{_381CwB934KIk&c<>G`2a8LzR!@)_8GBgxY=Fybm_r|<Ip1r?lMc52k{
ztSc@Jy8yBEAk=OXJD1u^xK;C_fOt)A<HU1fN7cI`E&VEKa-t1*0`RDoCqHvg`glw=
z_VQj5Pg$sdNVT|7fNIClDs`Ep#;*u$cHZZmHWX!0*!NVNl8VM4UdXpJnw)h8+>3OG
z9Go7Fe|L?fBP4}buu9-q;*!e5*lEBl6O!abKN^Ng%7n8>J3(c#Va(H{$j=)CxaMJZ
z!%&eZXfxsfznV6=YEk3=e{~ON7{_C$xeBMekrbW(H(|wZa=vLngJ;rSMC3))n!n}U
z5(!skDi7LM<T^qX8x?v5Ve8dlU=6LCs1n~yeiQ+oP33eX6Y^K{%UJ#0FR{mRX(NN_
zU6eA=^9s^BRaXUx@<xONTpO1HmrEV<;4x_G6zE!d7;_A5X!U#F|I+K?CG8crh2M7C
z6TvuQOkJH&+_39_ARs&=ww1kvfZq4OI97=+W$P1QhG3U}rf9m$F=M?EQAo1DIN>Nq
z`!=`eN)IB1kt}utkK`fsNNtI@d*#&4E>0F}HO}i|Gy4|Z8S-meEv!y`fU=LhbVxht
zDT^?;n@y_HqbFn&7>~>aZ*ifUIYV!1rNK7~c8-*po3uNE5K&H2y(aBQ_<$h4^O?)Q
znN1!|rKDrx=Mo~es!kex=NX=|jZ-f$r_=i>R0WY`-y%9`&oGoJwsGlw*(TZ9T(1Cl
zG7B99`2V%_bZhx!JH*Lu<JP0$lsCMBhW<CV0<~fsE2MpDHHV6H23%?hC^SYi!K#$I
z1GR02b*derd4c~^s2Y=^!JwWeMl(QNHKtLkTJL0HDV0*?uD+NiBpHtD-n%x7i^E2N
zc8MZkC&ei~yaQNQw3ulrn5Y?u6IMKm;1qW<y`@@jCa}tBnppt4QVZI%rIJ!t-9WvJ
z_ocGIT*tsq&}H+~#i?hsR}m@NSVNPP&z<1L3OCRx&ROV@ga~-BZtca#0F-VGhnLRI
zJkfgL+u0%g$s*aqoC!K!VZiR?`i*xAa)ZIg0QsudpK{y4fnd6Qmr+um34}x12#Xz?
z5{Y=d13R@N6b<D6v-vu~sP&Nu?w$}`7RmyMME}3xqoo}kbok@1G3!d)M6Dn^#0Q2S
zH-4mz+u!ceXju)=gmT_vMgJu=b}L6{Zwx4@!H*5=t3<!#!u;mVJ!%2(cz`6rW6@Z4
ztDJ;?TA@d<RjO0E_y+@fT2;zY2&TEFb`DFU#A6pMdqO<c`yVpf+zPln6@F*JnLa1S
z+@j!!7zL|^BrLcx+8GY!L*%~&V)=O78B*vTyU*U4T@7I2v&*P;@~0*`x3T9~E^M{;
z08;zQ`5jm>cno*Mt^2^$u6b^7=12)V4itKC!C-a$5>lrt-)8Jtf11wEqmODGfq!c=
zqTXT0DWBvU7wpubY#W-y7*mb{7$+{XRV_1BR~cWdYAyyPkrJD<bnhRRo6CIXEcLKk
z>r>~TKRmY(2crO60*S!yIZKrWl`ZLy$SVJo@}bvI>qX4&q=~cA@OLtS+vwNiCIHV`
zY_sWWR}U$M%r4H&M$%SnTSpI7gs(s`wZj-LH*f&+rY_tM$_TF?!<wF>hTA(_-Mq@Q
zImW3ju4)<UMxFpMyD>=q4|aC-i_b)YLB5aceDTRwA^>4Pp1%<2Hj2TMT=4}RR{e7&
zaf5n?Ic-(~)s}EPGux#rDeP)3{WO+}4_NpV68nqFi@^7?tV_;^3!0l5?hN?goO18(
z%vVP*zIm&Wr26cTj4c#5L1c?^=XPN|!E83`$E-}QTkRJ+kji5@Mi7)L>#K=#_qvD?
zQ8sijGP!er3wMy!%wREhXpuq^l`c)!jyIfTnN+7mWCA0K)NcCN)0u0BnoeRImo-nl
zTvj7V^WV9fnNp1EO(H`8Pz!uE97in}g5qG1S4VRj3RRSnR(r}N+z8W-js-VeO5wm$
ztI8Ypn<6SOu8P&GWbjk}oUHI8X}uHXTJ($(;Zq?rF4G`A@^F6w4~cz!x?Y;l3EY5O
zC8IF4X7hyYY8PW^$h3`*M7mzflBFq8OdDOJ_j1X$JGk(9b>$=Z+i4*tB~tfRHvYpR
z@%Sgof$)Hc?w77r&ARfjZ`L!n;R~`&H7VOEAjFy$`WEV|u)%1^!QU8v)bCEgUN3UR
zUi_N`$MVV>hvFOUb2yXnN{k@r4F=OF?Dbs3sFEb>9{~gci3oR|{-<Hj)SDwg0$s?!
z|C!0RA;(z6azFTik4`j-2saR$CeuI-l`rP6Cpf|sU}_I~Fe^|$#PjGv_Otek!WSGI
zimyYVI;hWxg_UNDSuRhWSX`XmW)XN;Pa*F&Wj9>fMQ5OJhPUnKdID%qIj%cF+)MPz
zuhjS$^H4}v6uXNyJ9plMOZSH2L<NgDtQ>TjPPlAjyC+pftPGt9{Rr=gtmTKG=sgJ5
zUf9EUH~b9_gho6Mp%7`&r%+-CJ2@wU757{fq0yoa-_NQLSuXJE@xOS}`-C*J5kHtO
zTMXEJ=EQ`-4smX9RTf*v!`UU1!M6|b=SP3cpG8ZD`s>nnWFNgmij`sN5wpR&8Fj#=
zwQcjT{n*m2Q_5VjGoR3|Zr}noyLL3+w5%}M^^w~pqc%M+eG}N*oB02m#{4z*cHLT$
z!)&Q)-~+UW0ejQGi|HH?AGVgInsM+(#BGZ2io5>%;>7$G4NzC~8h?ZT<%pxY;^Zg?
zVQwHh0}YCI%LBB6m?bttIY^aJG4*_i6!KHa-?P&Ni=!Ai49cKtU^z)Ymbou-K7c0a
zJdGo-m6C#>R3E=`yoQyV0~r96%=~Y_d&eS!10V$HG|RWIktO+(<OZw^Hb-3C-3NU7
zC8Xzh=JJ<nr{zVTx`0dJ9cRMJ>df+QaKqa#Vn-17QJn0B05*wiFf$_!XWo))4_|-4
z$XJ#s2d=F4_~$iUfy?bA7;w@IW3gHng?lu&A)}4mEU@~cWEYh_?~+*9&~OR#CI-v7
z8ZQ`eQh>ixNhc-i-!jtB)nP5?UvszRJQZjDGFW&#j+Fn|fvcgev!<uDXDd4t@{n0n
z;(xZr|0j$BRaTGpD+GxIP|SC5@mrF^S->YPkz_TxqPm|dM*uS&O+$<C09$?sfBM(v
zov{RykA>DjEv#56?>y_>0}4wj9NLKB3j+26n`mgBOaHxt%QLqnkYv#wr`o~6BBg+V
za!nY4($WrzG3oyVOg$BXAFVeo_xSl$jDm`&1O{WdJb;^1x`AvuqV}n*JV($FsXl)i
zmfW2gh%o{k-DT4}CP#QR$PWDnT%iPn#KAB#Lst9YGIN*)c)52D*&b$sPjFfoXFB*u
z+ml^G5IfXjQ>u5vC;BKj5hPO(LGX`8<h_LS+J$;+rtC(Easrs%?z2*)gd=t7tfZ0V
zsa2;_m@Q0ZW`f0<5iCdN9B{-pz`U6}<fGD^qJ&df3M0lM$63@VqM;w;k>_C7Oge+j
z-|6a~Gp~d5yt((sz7JQQp=aubN-B{>=pOQals5aN{{??`sFlevlgK2wOUnvZ%I5dI
zZtY7mGI^SMR!AN2j~Lyy;gM%k2eC{^dK`Vxl%9Xo7s`xTKFx<-VyWOzt5|!2+x;Fy
zFli&8mKD1->Wl)Hnspgvv69G4fussw&F9#&NeDV;&FqRl8NpK|iR-aDr<X?%O>hET
zt6|TE_1S#^JQOfp=U}zp0b~d0)HN)U32_mY;VYghIqL2fEk8RO`1d#wRkyvPNhn|o
zsk_*h{91;Y`m|>Ser4J=w4ujI?<9E|Jp#A*A%#Fe&d;YrEag1jH;Y;fo%d0PEk5o3
zLa$>E!hj_QeKR>As|pAwFT_=5$`jv55#0CbE5Nj92hQbrMG|*lrgBW|borf4(s84N
z{6F1%`BP#d6&9w;=CN$3GDIlSjoSCxS9~8;ZU|u*pc|B4r`gI74VGm3J6Ri|2hDS@
z+6qD0uRjqoNR21&+Fg+y`VFwI*|rgw?MU~5PMX5oX01G!ZOTwsZq)-y55nOWm(qK7
z0{62js{7v(7$OH-Ky5{zSSE?Nde{FkoFYB!nk(`oWru=rS->E13Ut$VsegPsIf=^(
zui16>o|&+HLH7|a>nvrpAHS%||7wQF4`pHXCWT82a+pPWqE^+dn^k*Z9Zjk1a+ETB
zw$Ud8If4bkA^fy;MoEu%)b$uU_WPygF2Pja=#LBXhn&vh>?ad3AD8B}``WO+U%rZ*
z`qKEa64O}<N<1rZ;0I4*RNy+qH!dhM*8tbb^Icrl^IRV<z^UZ*n)eQ{c$wF#ddj(i
zpllLQ$RqUC4Ck=#e-JcQ`L|5dLGmj#yJG<+=V@4N|DJ5uyb4(W1|TGC>6BZ3H`o-E
ztkk_Y(&+USF=*fiA}mjg`2;s+RNNPp=td+jz*|(0?_$)Hp9FsY@`7rwe_GF%^V1eO
zKvn3}2dr50R2N00sjIR6-Iu#=EqYgdm}i-u7hOa(3#~W}g#T%Uq^*7*${S~-P!1qQ
z?!OUZ;8gT|3AM*cql6-wu((%M;w<1uSU)*L@zB;n4k<LRW+a36yH5p8Ra}8FR7U2h
zv(UecT*&LM`7cIhBSlZdvPSqIQzL0WGL?qz2E$Hn5*vgMHtk-^zfEyB7>AGRmgxbJ
zHeSYdXiUE0&1`scgo2PC6^-Gr*Ik%WI!WqDflZ-;!^@l}X6qIDifsU#mY~)sq(&uZ
z$5b|9^-Lc#?H;`E8PP6h3|Mov@3uu0&!4lZ^#5t>KM{}nvp#xS-p7}{^f)Zsptr5v
z(g?>rHD+n5rWE94|5QiivUPYVWwicq0O~A5Y3ZH?biLBFn;{z=XNVaa3q`VQ0b_M^
z%ogys_Q+cRKs)ZRV%QR$tW;-W+drBGqE7%r;)~}TyY4NiGhIrUN1{g+K)y=Sy*4jm
zQiHdO0;S4B8ti3u%@NyR3DW=~_omSygaoW2Dtya1EsDeUP)(UO*i`l7bwb_*;b*^g
zxocu@O@_&Y*yBP{&fUOtll`9Cz-qNjQi=?NP8A#e_;s@Bj2S64;{I^?m>^)hz1A+|
zc>Iazv=?6M>{3~><>dJTAT=1>;Kxegf<LX&S7PWAr>XyYi5snHnT}eTf~-^Jciw(j
zW&JV`s57P2g!HH{irB)p7b@6b?v4vJen6k(4G1vwr~7xbD^o_GC83<0e|2Z()faiX
z^;AgXgd!1@E5MIAb2Pr$z<8dTr5QZ_{@a2$^b)B`#L3gisNdd6#iG>VN#IF(n%E-n
z%uRctXDJCfG}&O;EPfd4Qho`*q_TW4Bs`^t&;Dt>H#=xsJ8nZBzu;<t8EcOQ#%SJ}
zqF&YV_h@wSkc2eg4VhK~&ab`*OHa7HV~}33FK#Em0vQr!?$^S}2y1<`vR*wsSuhKL
zc4$Agz7h^wz$;Rlfi@STTy@OR7#AqBkUl8Zwz9VMGoEjTBVQx}Q1EaUvp`*GD~6jp
zL{udtV|*hhvB{C<7lmb{ZHFeq#Mr<z`@F&I*EpdB$lO}O#^e`i@KnpV!<KYX*DULv
z&NGRvK|u7zKTddJLaP(Wyu~o3P~$GhjtWGyZM<~gs2uuC##f<Yw)ya~q9;C^(?R!q
z3q8k-2VPEnKQFwDQbkMky>*=Ka9DtE+E!1YAezQgK)D2i+JHg%<&V3AMad~a^Ua`R
zdX@@R#zt5We7b!`Tdv}otz%{}B2rRXW|*;f?2%YNeqKQrKrfP~#o(OxrmLt<^^0oX
zkL{DXKY>`nYQiqgvCZPQj7C$tNuH!4#+UUs{!{J^G?mT?Wsf3*7)Ow+d$@;dN*wIF
zn|IJkn$rJk6<gG@#96Ne16$~d27rR1OQmo5$x<bcXGI42BhXFS7rEc*NcILZA1J`!
ze+xn1=6fK>7FCL0gwhbKW?K2J%A~VeiaOqWkI`yv4_*xKx$pbAmTEKZJ>!5G&l=&V
z`*_wMq%6Bi%wS)$(9|bzFraG5S8NHD0g$woguRkB^kzTX;}7%?(Y&guP=NM94$Fie
zQ)Gr{m>C1hs~3_I_~lAuv{wBONMJB8_=!Pp9xRc9bizk8#F1GJMqR#YrO;!F%QKYl
z*!>!k&$#_={*jY*6m)ta0~nOaYsHNIj38csXmo3T`pOOe3Y_iemTWXiD!20k`d=*0
z&1x++Yce5!1DyRMtn13oaL=xqBFA0Qx&K9v>#ipGIA~3)fE%VZL+#IcAoUAE+(N!s
zScILSA9ycXRWn*5M<}3+d|v&|sSs4D3eh6_r-4{=A$UV-%}i1Vm)(KW8*jQees_GU
z?Y+OLTb2m`*OK=W=`t|@ZsAnYJQO?4l)f}f>or6%+H9G-)?I7#09o_u2Jp#Q$et7J
z&7H@6<WBkhBEF?P$JsHkgqq5)!8`e1PmBApkU}2oY;X`|^M>A|of6@`WcMor&@yN?
zdr*G9D25d6HWyJ_icLU_*KN$=(#;d=<Mz^RNnHbomJAA688Ab)mC#_BDvXD^7FV9$
zk&xoHK|@3Ij$<Au0RTu3s|2tHALV*J+Dv~Am#ifJ3X8@Hys-rElC1x~4BnRG5KhzR
z&F!6^C5lZ3vX**p_BFPnQT_0p2DAspR;Zdb*XGZl+h;~o3$EIHF0b!d5#ChKuiitO
zkhr^N6Yx6(A?Sb?HSwk?qLNit+_-p-N(~8q<GS4+$K+o|)!EWbX9*c2_94Fhbjg$;
zQc{jp)Yf0HE61RtT;MuN1l*8upBaIxkjrl`cD27TKf$&it|{On2TucMw74`K(Zaki
zBWeA<v*aGb|L5mj=&^D$fhxtguPuXhtz9c15foZj;@VM)Hj_P@xjse!hFFzF^tbLd
zpU2@0{KVdmqIJfsqnE1u?Ahp!grFxi1Qk`QBQCu@mQk3^)MkjVYw-H4wDSW}<^mWn
zTI;yuvV!7s+Hp?Sy*wR-lA5+3`8RKYv5@HcSJvW%?V5XsH$D^d!}MNJpJ~H=6naPU
z6bit(r3m9v&{&!3yX(AQWuGoe2{c|ubMVV&rC8lpHtimg_9_gd*|*tR4q{1;01Kou
zX9njY+tOq`Ab1_HtGu51Tq4_0UO^V<vWotRSAdav@`dus;Yud!{j9xtpYJ<L$CvcW
zDPRCr3%;W~B76>sE}HrIX>$v40ZEaHCr3~4XUh+V3evYVpTH`xB|f5rHMlJFzu7F3
zigvh+Nv79!f)%1Q8DMiUjWRd{ejZ4eS{$Zu;{FZSxQ7~U?U))K9*6L8%1wb`spNk9
z{N86p>iKN3e-}nCts2UX?S#oYRYf)gcMPHZA{g7S+U?xQ?G`#1w{JJr@rgO1>zhXt
zUHOBNfY!?>aSJOWFbNJfx}0|O?3l7XK}=)3#Df1?N>_)H{|9PLNtVn&cLkB96@YFW
zupfa3JLtW-n)M&IHlLNRXd<dq#U=c2d2MHOZ_?6;mrS(%f273&XI4%xi1m>1KR!}-
z*cPung+#?>p(5~W?<W5SpXx5C=yh9U@yhQ1M{_w*cT`JW0z5dJw-D&VRA;KsF>T-3
z&<tWxkG#c@^gNL+K}MFgA13(r7n}d(VwD__4FJ4J$^dCH4VxmjibuhiTSifxEAC=6
zTZ(&oOm50FiV8vQZUXmK!HV;FL}%BDF826@5pwUiI5j&`bn2qcO4KeU@(`l>FNtiG
zmZ`{k<oBS6z2rjXbG^y{HnWY7d!~o-`D5?9FkZ(Nabyae`&OMuF?&l((bm8t?~0fj
z4>Z*1_693ASYe<V^RaX=)N=*leDTf@Bo!lxQ4P-XpUOH5iXIIyM(g=+dGf5-j`q!U
zjd0xXA-4rvKplmfPEfG6i(WHGRO8-^85dVTmNI(eVYU~lF4nNo#=QR%t}Ix5VQT4#
zUiouEuT#ws0A+*?CI(aWN#}Cn$}MvR_lejbX#OWBdji;Rc2wpVNoKh$XMnE)h#yf_
zC|GyD3ZSP~`|xY;&}6lhED^>Z5J^)+bW+nm`NyD?Tp?bB&+baD0Z}w5zbf0PDyXb|
zHh3}Y<>rDMXloomsO^ovBdXNr)vX9R9*)8mdsB`Uh=?F*(&{Kto_Y3+$Vm;2JG-&*
zDvZqy<Sl$n!v>nnNaUc$q8xN0ZjuJ@1cK7|_#m!@9-B+~2$`L>jb}^b=Yspim(2J}
zfDO>**O)(neBXMLu^qZUTWJJ9a^Pv{{$!B`HPlWSsr*rL2mBu^mx+b+ok$bAJ>Kzq
z0mZVe&CDe;;W;F8cUc_%?T!>_Ze?U_?43wT2rc6cF<^`=k{+lpf;NQ>6mx(J8r?-4
zx;_6*!Y=a=8Rt6_Wcie*F`1X}s&3{5USWxD**D3*w1YOO$6s>L_rNvOIN}iVkXpm{
zYkD3*-1(YHOGcHy&g~XZg0@Ho+gjZ9zGMJbcya56h=%_^u0r$kn}*6E#*A1PC=OQJ
zuA0Rk`g;qU`luRQk7Nf{$|*>=hhE&kj+S;Hw=*gc`m^`bkL)e}%aDc$^JguXG(<Zr
z+KIF8pK9H}?&tFx{a6`rYyZku&u-A?n-lckKsyyPjVpL{FA4Qz|Kfp`n`pb)EB(yC
z28upB>SB$(YWDs-p_Sh(F)O|9HzSn4Fk*_Y7M=vS#`H8w|G*PxPhXn%xAGxZ5xR&*
zPp0j*Ko?dxA}Z1<s5%=52r?3Qa+LYd3m7hOLV-Da6&`B-fIJ5PnMleGA-wyLF{MLo
zuO_1MTZ@`PxR?x1b1Icc^W9rPY>NZGit9$*+Ar7oj&zT8ClP_#Kj=oQxQi2o_Vodw
zF!{B6Qk`7H0#o^~OP~8e=|C5XndN3(#!U&5!vYaRq2W7}ohXGs0yqfGrfHmYMLV9k
z$_M9o>)G6e47_~M#?#U?5@VIUwQb-?@ydh0xp4N<I#%}`qMIockm8Q@Mb(5*dJktq
zIP-KqQg>XkydZ(BT+a8#%S6vP3z-cAl4dZ}2ru~mW$u^)Kg_t-gj-)a(T~$V%av*g
znxpTahcUsI*Hai?%8EMR4MzFNf7;Q8<6n$~f0Raqf35AdazD@O#E=kFbAc9plY}b<
z2)&1^Fth(tV95Bk9$WwO6vm`TglseI!-<PMDRR(Kn&27rJqaw0*xg^Ksz+2*XER*w
z?tBcalY2QYz}PXR1%KQ_gbqytA&~m0_`v`v<)0PmJD(&WMVsV2X~8T6u)fTa)$!Yp
zMJ)W!<6NEPcDAsQ2*hlMdKF_>S0w@)$wow7VZI`UI;2sJT?3}5ttkVy?{H^nIAytV
zd9}PL&!q;&g&okyA%x8jK1!b+B~ob4q70Uz(WNFZR`{$iZqy17H`43#bDQ|WO3VUK
zvgM%U#kM`$lZ^QGQS1pzj08jUE);hA#sr0{?=MuU`lNneaBmxl>TcHI1WS0~{u&Y_
zyYN)OVS!r^?zfFr*}qfAq2gx0$3NRE;BMjS4_@44?Sm>n10IlGeF$z5`4y9V_P59>
z;_Zt?_{L)Vl+IgBqwTqlnRn5FQYFEgy}|qp5k+*H)H+5kZJ?nYls}xXTtMR;#Q%l<
zCy9j+^P;_VOt<+~g_OF+5z`tvHFcAKRX9;R{HFJI798No*i%tw@i7fr$gV6Yc<uus
zn8F~q-$SBH)8DZ`A%)4lHRZabp5BnzL5)ezW2?IgxSjmK8YgT~pwIimdL{O2E!U?L
z!vv`^bKeb%Xd!Ya^EBzQLMF;qx<;(w=VOTQy5kfGo%yS;V|h|pr<aX6s5uu(dwwxP
zaH(-Ank5+`7uMv(fS{OC6`zA$lW@@FVYh+sw!g<-OW$)-nchnWrfO!2R+t#D<RLS?
zrz&C#BKv5Re~=ubbnkwQ^syHm2mxS=erQrjPm)+}4)O=8qj96`nH=XKIt9M$uhX-_
zF@Vv8TYtP@6#OfGdrUfgddMZZ>fNDZqBvRB|9SuDB6wTbj~7d53&)7ucI&ujnJ7Dc
zKQfROpyP*O#YcCiT&O5%*jKkML{9GT0U6K3w5XVxzA<JH^wK$aV&Vv>n4)~V#Mu+J
zfVX~Q(sjC;BRrw>P~fDXNK;jc2k)gpFw2iaM}SI==Ny_3)`7AS8-(=Y2U@74!R}5z
z>CO)IAN@s8v?@KV-Xhf^Z)@6%EnGxN7hhXqwlGGHFFHaH)S}6LfpDv|=Lj6pazsN#
z<Sjtq<bh_|M)oAwM@EssLO`cvwB(Z%dbvjru@uL>SJz`5FL?oH;-71Vn_y~Uuel8u
z-o5wxl(ke{<A&Q_h~`y%MW?^M`@dmuTDXNUKw;cSpKfW+sMVNR{Rl{eK(2~<#*Ti^
zU#Es`5yr1X)gL1J!PH0YMyH!V^_;5Z{Je&twa~=bdS+Lj6AqE#YGE=?WpjE9I`yCR
zV`S@3G44{jDW6jm5NJ}Z!~P^vFl8YZMoxOz1L~-m{L}kK@<=X$H7&Hmw_I(BbNgvY
z+}c({>}CdR9y|5umRhbfa^BrLL_@pK&M1nYOh?!E*$#Oiq2b0_OiPoN2BS97v}#nM
za7g;ULCns}K&+KPOiP3{K1T$v9dJzq8Gx@l45;lp*!^0)lPI3+2P3Kj0YR6$eGYS#
zjOqS^*gz3q%<IJ^!sE`!S*<(8b#5Juj0ZgN=3guy`vb2B3Iw2lRgVlCe)~?iw?!SE
z1(Rb?t{{tC;UgkT{2yn?WR=1aqeQDY@+sPC1IIsSv$h}{v;h57qH+HMg4VNHlymy@
z@lI&W*Ay9uQ8+vV!&XZi#EiYCgFQJD{kmAq6}vs7wCnJ8kCTcMlbB&ZIPH6MXs&q|
zPm<d$hvUmvci|E9k|<+!>e6Wvc3h)$iid>@xJ8HADIDI*8EW$S91qqik++3f1<>#K
zTU*B24Q-p5A?E!R(>}^BPc=~y2PUh`SZ^!)?ue3WmslilZN<>1K`OHXL{G`nj59;h
zJu?V7h_Q5gh;YmFKB8za^;@q~`VhR2krwRk$t{21WIq_!0q3BwU~JEv87TLcG%*bR
zM1<}#v6aw}^;9`8PPO64+%k*wr!ie+oNEv7m4Th{<;QSz*e2awy&ArOlY#~p9ls+Q
zLt?p4v^}V>(5aJ`bxPu82SLt$<sr;E6B!4DUbUrh90hcu_^GYKR7K#LYWw=t>6G%K
z>R9uq(Molcu@$DQ)PFz#@DQpfO+`%DF9}DY#!;&506ykAEA|#v{9qJghXz>Ef$@`(
zZXjbi?<xw&=0#hg)@7wviKVPY1^w<LxiH;Y++{QBJ0IJ7?bP70KB>a4qZ=hSdMq^`
za7IpS`tjYr!`~p@SRICPmqtuN+ZTLn)NNz*;R^Ycj&`qd2lkJL$-$s5_nzI=XO;fB
zc_I(edSp1Koke>_#hp#~)vW`y;Xh&g5cnom$=z#$eoP!$Xh4us)UjzJj&I}&aTlSq
zBvEj{n+_q5C1l5+)(Z#liqxs;q1gukO7Zii{qpBd4Pe`3V`TJ(FMjn_Z#3jI+Lh~G
z-8)J>B{sTTTBgvTarL>Aa-XM-&DA=;KF6YLn@Y)Wa~2X|$EzVm*6DLZO<d%8cXJbH
z4=~9~->}zXVs_e-n&gTF!#du@V49yHwz3HU{|J1`ge{G_C95$jn>QF{$495?`uHL;
z26FCL2vFv(Gi_l@@#V9nL&o;xY{?eRQo!0vdK9G4SbO9P^noT*8Z_$7=iu`>t=QMC
z$tgsA<+RU&jaO4idiISAFw{F`g$q!6O;-pzuxlv`09BxwLn7&B+@a*F_m;Vw#%fi{
z<4MX2JhYWUZe`G3YzK6{Jy^e;=*fZ%gP@^X`{EF>A*|Gru_hDGA5>2e-u;fxX~OU*
z^|?O2me9D+YaL`ADTF{bTBMaP2V6(5Uv6OBr^g}0ON(2c{N#P)$=Uk=+nCMtp*rT`
z1XQy-B@w~?l01Z*_{JXAi+lvTi;P#U`F(OKZZ?OhOr85Mz$L5*eqQ^lDWs9SF5_I4
z+5s6Uq_U_kSpsW#sKo(kez~}CjLXVbnh@MNb~K)1d2j)*qw5Fs5@5_6CUOw`p_`jz
zWmo{ls}4FI)B`0K^Q)i+vw%a=AM(~!ViGbDAOIH{sb6mTYzCKwpoUTOXwGQ16DBo0
zeHu%NW6_F)dBQNThTfcVPHs_*1ZgKmuUJU3JhmiHb1|k>1WNzb!11}Y6(VppiKR!P
z+A)9pM)vbO^ZP#7*L{dOM5~iE%@X#$FWbX_0>9K29|qPGNHVFnh?%p-Q(U4yNZGCl
zg{C{M8vvXJ4?;>1UCV{Rt`FtEfFlAA#*21v>cUK4hZFp{#@|r|^Ypdm72>mFAiG!#
zl3V>DR_=*gfw?kN@jTCoGI6Nn8>zW}lEa?*Ed;tOl~<Ga;E2c}oaPc2spN#}&TRN@
zKK8b=J#c+Qa@L|bGT{iSJ1y=f*w~mTj~WXb6_1>`3vg_mP%ROWOE{>Pxtrz6RL$eL
ziRT`SDZYWuM7qu!!z%pkE(M0UBQzj5J;5T-#?J>*m{!gDQC=nzAJgE=L!_0$Q-yZr
zhB@Kc-hIHu{pa|@Xw8WuaR*SQAXHZ07C8p4rAdE{f8h`ME~6TB8k{L{C;8)S(#j|?
z<H)Z{7|P9?LK0!p96wcw06nY`t@G9w(NzSqfe41{)wKD(v$2F?dhWDuVebl}^j{yd
zPRyTiAAn1(FS=w;dI_(MCY1fsFaHJXa6ph!;w6YNRR`8)!rfkfT{xw`foH9rQ5OL}
z5K>Hjl|9Z3I_Q`HezJI&U-W^$j0pQ@^qP1ST-^6rb|hq2t*F6qu-~&-QT=RB6zUut
zqLFm0^|M!+HvJN~grZbX+!V|(8eY}s-6tI(LIHhgZ0B3HD4e6D34evnP@q6b2a3gB
zxVUqOp^74TyULtBxle*g(C4E(;3L*K$(Crfqg1GqQ#dzM<6oS(Yi1I@cZRue*p>Ca
z7PZvLgcF9u{1nHINezLnaeUAImny8W3w~FSF|3dPEpm2wD6P7D<Sn2C;0Rh4MCXIY
zMnMj_!4^NA$4;?ce?wG|hsrB4<pKZt;;|Bv#CN<{An}MBY(~BG@HYLOZn2H?P4Bcu
z3WA(riZrCCT#==U1NC}<rX5K;-6h;Yl)hgpvvZ!-F_mPR9f4;<bi1{=v}0bw8~;4s
zod0F@mzXU|X<5&p2-E7h-CBPFV~_!FSgOZ#l#kT>NN6>Jt{&Ap#De$bIfIn&Cjc53
zooWvwgSOhR&bRmwo!18*AS)ObUyAo?_lJ%Wlje7m0AurXr8!ARTQEvm#(m4&j5vKI
zEWVLnvHcFx*xlx8Fpx$2HIHm*{a_O`ZSpU`001nY01Dv2{nh%0H}?b>vX`P3U9rL~
z@0Ja6=mbc#JV983hvq0Q$e9bz{76a?i<805?7eeIJoxIdWQzzDgRZX8o=x^;(&+ZI
zXWE6^+3LpGl^2d)*rkC|Yeb;iF->4cl>495l3l^6!(e?jVSFpkbyGtL7YCLQX@~*r
z6kE$_z18|TKI~m4dT1mBwE7LaX0|3Sg6%CyfZzanTx*-a2lRAK6{h-HCfhQ+NL!LU
zk#sabDP~MFLmzK}%*=>H_$d4@$uzkosqB-hk)%jFV=o)aD;C8h0YjBr>P63HITQ=Y
zKp*(<thqxn$Fn>h=^Iyr$x^I8I*=D2!^Ax+nm`K+m8201psgkp@o`nfMNszIc%!42
zyrh1{Nm_@EuDLhh${&*BMo#5+1!cn3Tz@t?_Eo^<8pM&Y<Jm3VoNQ3tn1dw>V{Gys
z3T#}A@qcEUrI#cNZf*%|^-FRz#p2^czkTn{7i}o@r_lA<l>IA%!~hpN>l}3O7qqsA
z=Gl6&|G;pBr(1+XJvk^@ojsTOMi-V~NJB|0?_d@-<FlwLPRS7}*Ao2W1|<O1N-p3g
z-XON}kfTX<irBy3nDTzw#$udFxOGQEGopvVFleuGm$kg)z(&s}+Ku0J8Vre%N*BbP
z3^sZ=M>0LkVw^V85lJyW2&zA-Kq6d&f$2mQTFRwZ=Ja29ty-Wjy|NA-2`jI_Vsd;;
zw!1gdnotW+|CMRAPfsQy)?hrPWMzHGZT;gnqq_?#9KAePQ69aM{c5cm0X=`x(GpC|
zIoUjN_bkktLV{*&M(<q!2F<UQNJ-+~U3O^QNhk&YA9)Zcm)QjEWg^^ulEe)#sQN3i
zMm-Fwh`H#33SS9-M>a+KsI2Qk6SJiI(&E6x*uVkp3KFu^7^ur|XUjRi?B%-zwQxdh
zE1s;g4kAg|pc!4Kf-7*3qJsr5LL?FAu~3#>$=-~4HVg+`#$;UwE@w4$75rAH*P87?
zNKVtbUd=L&QI&@ZHGDK2kyZp=qWgVFGFj_17y;g=2R)M!%a&|nm{0a5uIZW;Ed|~y
z-foXo>WZ9VR)fmT&4X+19Fxm62cgUG<HZ9vq$HCaEZLJ}VJBrvM?NrKD{uF9<0Io;
z>m#&{C+UJ)bHI2Jpb9V&H5WvrK~1dT<C5;jLR3~9r3y|8W`onIJc>CCgbTPbSN<Qu
z0BggDK=O2~)VwzI+r`r{iM;|B{7y!?laAQn^uPw16&L|@I-oIv9X-=gSlQS>RFhw<
zOqt(;4bb0-VI}+&zci-`yBClglKVMIuBO%b|0PEuk=mjaL<R#!A{HcI+pSyHzwY$G
zxRi+uTUN#Ma=Y_(1-8G|c&LnsAq+Mo1xF_I(MSJHlyxm4K(3=4l+&Xz9aA-PNh!Uy
ztXgCaC3m|i>5?oDf_qUD)>(k(!ia9EwDf|?+MUpWIyV37$Fg7jIRbo0BCVvnFOyHe
zrK6C(L;~mUm7xR0Gsd&GiI`i4CZnRhFmJfQUe0V+lPk$9$%^QP!^STH7McxtP^Tvr
z6~YjNxgv`X*f)~HgK3r~ocMPxzDPVqRyoP$9U!%{6^bqH+f?Jbaho=vffjNWb>O!@
z<*bzTOs~suBp#pfBMo)Z58?6@o7{2+kNZ(fThPr^jWk2R+*|Zzs?2ct!KC(V5Z9<e
zKekG=KdZB=2T-|u+i;LtH%f&kuN|eu^(+_;6<tBwL=-Z)q<}vS^be#;aX*#l(td@c
zJv>TbmN4J>(B9EhX0Y%`y&-9NJcqT6YQo}HicAQa$()9ahGqRU8%-|Y=(-EA+R`1_
zI>Kk+EYTz}SR!O2mWp2-dOR!uz$jZAvMW&y^N1~>+iAc#{=Bovo-|6$hzqL;2KW7U
zy9q-I#67eW|6`k&g@${1+r=*W735_1NVtkSK64Fa!}BbIo$kd<K3R>SB>~3B=ns+?
zfl%`$wK~kpzG89ECYd4eu~1$oWs|o{=$*yFZxwv<90pg0dkdWKG!c|g;~v@{``F+O
zEzf3&Zn$AXNXvKtbkjr*5(cVN+e_X<Vg1;?7oH#gmi606aDWH-_J3)e(*i56=1@66
z&m-*YqAp0~GTw|WxwmY`k3~hJhB1D~g0LG7@`#iZ@7l$|lLC~<mM{Myd?1yvC%6xo
zqQQhuY}$ddxOIUMUo!?iR;wl}m~?V5HeMY6>Q2>$Qt?6~ZuJ{AzUzcM&<_u~4uP>>
zjOg{ZiDfJfd}ZwgZZ!|3&`Y<RfONtG>|BO=;IltxX3=wwYcL<-W^>iV+%B^(Zw%?S
zhAbGg3}+O?@-6r*hDOHCl$L(R4osES<}g=y2a!ZW9-!-I@Pa6ia53vHEa2s;Sq#BP
zGKQMODG-M*@FJG^s;hR{qOOd9d@P#28S{b7V@p&B!nURZz*}xDk(Y<-K~7x_PwNLv
zPT+<CbIvt2LEuQ4n=twMlxc6|qDC7a(<DOCFskrZA%Y%RKAhQ|C<2w!a03^PRlEZ*
z+dfOaTK(@*w>@119TZ;lQxdjpr#1fTBK^c2p^6UW@oqME<X}IN;2l%Bq*|}*2X>>F
z=Ugw}tv&}|WYn}Iq_G+aKnYpQC2+*OV(V?<vqZqZ_-?o?Q;M09c~x$@iy^Q9fD)BE
zge?=-iCeO|cSA|_ZGWsg_iXnM6bqcv8$j>!-2_B_l9FL&w2o+oOjp)d8C~Ne5`g{G
zH8C{bZWa(MBJaR;7Y+LCDra%Gt9Y4j@)c+PV^apSgIVT@9=lsIO0)QRx>h498Mnn+
z-@X2j5~=x=0<;utv{ov7;)i04(8zp#!W<Hm$d4i_DP)EWfB?D0?n?ZjK;9Yuf_@kj
z=quN9$dmKY3*t5c$bFO0L~@{U<(ao@iI8FYIB;7@cF&=@kToT~S(~85Z63>EBVgoc
z#PJF*_2|Bz*3=jdkO_Bi1Evcs1N<yIJy(4kVyxuRpGcb@AVS3(Z<+z}aRzs$Yu@jq
za<ehSJou*J5=PhHj66}tU5>u(@ODA{$|qMbUnXA3bPJm$pU}BFn@ZwA1HV>!*MrC{
z$bm31@Jq=XH&ciLxBW4Ito1<U96%p{-}IXdq}B3y8CAy=GQm~s-;GURgfSj+5*AYI
zN+b%Il1Zidt=__C_%H^_iX&{k76%dM9b>+ulut$Ts3Hi>!d_!3m}7TCX?W=!_oimP
zWTnY=?1j3nmJwK8z|D*5aLC)4!Rc$W9fh*S<gI9J*En@Yk5@XLM$D*e*Il*nz=2jC
zy>hk1N&rlh(T)^4LCl|7TOxy^Vl{*TJ-}*P2jH$s@V>$8<}8T3+1B+Txu#&QKf16U
zcL}w{nDoV`EkDKgv12aTCh$dCJD>2i@WzeWX0xZeP-D{c7MveuA=bUX8o7#1gAFHT
zpqltn@Oya~oxK&;jqCfA=MG@Ho8S(!tSC=Sn@X<4-xT3@v9notyWsUOn33-42-B|b
zjoT1S1+VUTMIl+uRTRYf%E-6k&(*mbR!6S2(X1KNY%eQ$`=EK_fI!9hXPN#eZrVmn
z80eC7=pDa+t9U*zNgB_gTshb4N<xLVv>q!B4~AEilZO~ZCXM1c%;{wBafQ^#%(mk+
zeFeNX;oX)aL8UX7LsW=IDE)7Pin1K5Uc_ekv@vzSIt#qO)V*$Evv4#&Ffsrj8j*7u
zm&dlES6MT_3@2?|#eBxQhC88BG(H=*C+{;1Lvk3l^#4u}J!Fu>|KcJhOOuDrzNGYk
z7m6%tB}*lI-AT7~Rd7V}W|SjvA=9{gUBRyYfloYgdfyh_T@=gfbcpk^WFVgiqYVPY
zArhl(3;+kQ5$LWimj$36$y=uJzpo;}z*7v7^WRC>G|`LdJ>#vkY&Pf`U2TK+4@}YA
zvQkFzX^SfYOY$K>u+x;7s^gLJv>#M(dZzG>r6P|zQ!)n62>o<5YUaD)Y>{#gpC=&|
zT7r!mW&`lz-~(IKiyC!85!O>b;VxDLl8wkgJTDQpqb5LW#8o4xxogu#UyhBrz*{@X
zC~8$8GBpc4L005CsM9%t+eDG+OZlAWs`B?{gLN5t)Z}c@ZZ^FTm}6kilL{u(O_?1<
zt=;Y?L<5m!O-Nxyb7W1VbmQb8-#296KwCfn0Fxj902NS8R&fmEj#Y_9>?fl5I;4D>
zu->Oy@Ws@!k#G#uax{O_7#!u*DCe$&1hnj+8cA15UVTuX3>d`A#PnMB{$Go06&G30
z4Q}nWOzUzx=0;_J{y63g?q^Aq>#x1?^V=73z=-MHDg7uMcfW3k$@R^}>)q)d5*A$d
zu1dikhT6}JXxy&sH&)~VWH~qHp=uo`hd=J+<XMA=c63A(KWFw(ilEb^;pMtu&8%D$
z?oM4>8nVwe`UkH_v~LD(O>d$PFQ_Far5xqlut)ypc#MbV!eMiG^~s+_PzlW2DaMG*
zPuI2=Sq38mD=|g|Lt+Pl7jx8w_l9@V({y?{-Sa(L?FshF%RvChjhwE^(?ZI_jpP02
zggu}m$g(A8b(nSKLdfjTZx<)glTu{BP55~V+UT_zWN@-bNvc8aHb#0F9!?w9AITV6
zWAcD=o&Kc^ws18+C7=7V7gl;y?V!a81t)j_BTfLlBKUa%nR|C-{s(=u<;>d>X$RPa
zyT*wKN|Cq@Kd4oS@VX=b5p#N(_;nr?g*DHEQ6D8@e;IDhK>#hz%eE^81(z59Yo2-P
zM2~USY_ik?SLYaVLN_~RR#d1c&EF$S%dwU6%AF<zEdVXH1Mh#MmTxVnm=^csA~0i4
z3b*Z@K!`Y;Ji>~UY2Y<`26qnKf#wKRO%^D4gMDKV!6&tI@R^1L+kUB*z;&+-TYN+~
z90s#J+Zyg`UUbs7JC(53E$4fZQycX~#QfwrO)o*?Hdbb{plI^)?>K;K6|I9BA66~y
z!t^}3Wn2sHaq~bn5V^sisXhQ`Ra>2}rqX5(Bz#7W#tsMKCg`4qze&pWE8HxQK-MEK
zH^5CqYIXp1BrvY^YPRJ4heaJxR6Zr-nfsjY??x+cHpuKNT%Y+~OAd?z|CAyQ&=_Lm
z=bXaG%%b7UP#Q4HubO_;5P*FuFM8Zur%UF?W;zLZ7X`?j?6t&MkjHw(Yewp#5Wr$|
zb+%EVri}be_foB|7D!HKezCEJ=0P<T`{yrb&Bm?{XUqtw2i0K6Q+{m%SEiUx0cW!K
zLkMl}VR(vDt~~fTsJT`3QuKEp8(H3+%+U=~$IRvQNUKAtT!Qk<1M@q<t6Md<z%ce#
zB1iijZ(C2X^ln2<Y9VCt>Hyc-_U{4;YpUa0a@68F6dzxxRRlX^)L2XQNCr6Zse_MX
z;g;BcW7R9k$(i|6ewpMbn1TyVvxNPp=wI`E8f{|PI$3x=@o@ToUi$SLz5Qd)1`Qn-
zoOhmI7~DXG;~lO5tg&B|a~j<qiCl%U0g{-0VRxLt2b0-Bj+d@%(CtvorMysc{$qd}
z>G4!gT?{x~Fp)!1NJ$Yr%d<uM3hiq(syB$N?T-m5WD6kE*@$gve#nyuxE|2|?M!3>
z(M<=8n0}T)O%?E`VEMJS9OeWI!#c<6jo7Ylq3R|@6_{Akk#sQv#IRFLsV{J$fFE^1
zHZv|S{P1UbldZjnd2gT*H@0#px~7eYorR~qE%-g8bV@+FqXhgvU_d+(|54&Y;AzD~
z@S8DX8S4QZ>`?}G9`~cIJHpn~%m6rg({~t|2%I3nhG`-DI9zYi)G&qZp%=P2{?g9_
zMn}v+MD0-3gA^{Eb11yP282x;e2E^6SQU`8WUewBy{yRJnxrN2U51D?8DZJHV`RF~
z*CED3*pzB?9DKdqQg@R$=kgny<wc{?=$sY|Z6#!9<?nkr*|)J;)8fKg3_q$QMN4R3
zd&(M4F{DEQjc2U42zYm1Yk3`D9~M$eT4(ici<zCYOD~YgjzCY+&7r@(*67%gTaG(d
zZ^Y0!+FtW+>*aSXodM%Js)F@FuI58=)7I%)aMl5+6<}AZ1T3m?Fu%Y8wxJMDuhG%e
zP*@x9^%4qEOLXX*!uoe!1u^&r4J|3h+QyXZdu*B?YDTkIrzl!y`?&>uX6Cf{zg27q
zZ318$BJ^1@SSAz){|sing>3P}nT@eBud2ekCXOce>MLvn?7K)N@FPNr{iNr6vFzd#
zNpbQ9eNRKNhW}PsQNJN0tqmEbqcb1?-j%tuMUI<jD~Q4cWEKTTn4vzfUMLxA&;S4c
z2-(^(F6lle6p$8N$40j)|6;D$o}qPlxX^x^%N+|Z4PHg|sKvcT#3*mkxd~R%;{Udp
zj=MWx4Wug_v;IrIUVhAqN+cJkTlN*|dw~3f@w^hp2sKML*xI4u#A5^-jdjUH=lx<I
zyESx}8<=n|o_0lG9h+K9*!iPXX%rzSC+!q{k@0fl;W#5dO|n%f(lm4>!g=a}q**PA
zp&fsw%2}c9{GrE`Pxb>1n!hI@rpJq(DG!b`-1vwxet80hN7yO9NAMi4rBj%%oa@fn
z_PGbfvQ>fmZUXggJYvjk98Oiz);v7Qs1y<I$bVO$YICDADU@`P!hFpnRHz6D0*!<T
zh=D(OHZl)q)Wv_p<h+4=jq{TVQfpBU#ET037jvKJd(k;T<$tsdrVKA9F|>`R7LOxF
z72D#=sXRHA(a!Cj#&c7_DpY}Y0Hinj-(g{B-avsQJyl*gxLz|pu7!yplet#KR4uz4
zpT2OU178`0W>A}H@MkMbE;p)-0$Z9Jtx?l$&rx!&`pQ9wnb<Th-IdBSa&Ss2O6e-*
z<w|7E7PyZDm&?lD!4O&UwgP{Y#5G^jt55>pVpn{jbVBSE(8579F3UpsCXDKL$F5Ve
zXSvLRFhl`tB!K1w9r(cY0L_}>8Ey3|W?c-A`~L%hm(A_}LEP|de+vSpliAN>!NGJ;
z+;~A{6aCA8qH(`H--7emh(VJmZ3JWu4I3C}cQ;>zMdm>#r8V35kKdanaz<1oO`M_$
z!A{N1cww={HWW`)neO5?`K3l;MKC2L&xRF0FPMwPlMF{qLQIj~Pvf)={3dAcW5aIO
zg|@Kww+6%=iidD(DXZY;Rt2zawOPR2@+L@~w=q7~KFfz_$U(@>qp&lP^vC~ej3#ZJ
zD<1d<5v`<|4YvER((lo)K~w;2p)uVWs^isLUw25)PgX*({A?W1%rj+zws<ojI@6F_
z=W=HFl!ak5wZV4000?YOdi%;QIY<fUm0T|jwSMks3IHR1{DU}sG_R!*MM>l+*si0A
z7M_n_8Ps=N^T8fOY*)p4NBB{)7eeQ14)Bev2TVIjDqa|q@<$CZX+2(GnxD1Cgv<9S
zH`{pO^4qQ|aO~Fz=i$7{_w)MkLG^5ye|Wn<ih1by{O@937D8N2pR4yKpb@%>pE=16
zq3q(Ce^i>n4XJy+r#h*31PF^AWV}56{KDjEl#X@JqG{O6d0GV=P{G!ksG1w|r$Fs*
z$$cxAUFgwVm*{KjMtFc#n&z*ekW@W*HgrOkNR%I?p-x2Ktf$EJ#X9^jM{bka4siIN
z>b3|_O^%HcHu{e=eki^HLx%mm0+Il@m0~Z=Wn*)Z3KE+MQc18H*9*lJ!DhAlh=+i<
zW2Hz7M@6*)s(|)6ti5)4|4I}52u@ms^LItp++T-24Gw>iWJMh%?Od9xDv6F`calRr
z{+GjU{mzK$!OvB=n6o74o{I^{Lh*NqgBy$i)O&B3lAxw0=4}%l694NZps$8XUMwxz
z(y08o><>La#iceB#VJ5~TMti<jBUAcR<}}Tg$wDu_pt|EEG3*i{)>v#rpk~Pf_@{v
zRaYwM5}ms={G4@5x8qN@Df48?N8KTfcFK2o7#y+jR;k&*c){<DUa2Ce`UPn%Ow+Xp
zq=hRqx~(|+zX}hJ+85kD+5snLDQgIdLo2>;UEZ2nxB#O(JD%Ze%**9W<ho2KqHPNx
z*x8%|=7?_3M5mYeL5iu2A_Wf{PBvE|h6M<qv}ak)KTjC%yAmi1EJl|9>80G8J9SFT
zELkn!k;)UQpr!&U$Vah+X%w|u%~4tF?yyWR-D>+xmuoq7YpUbs9a>#t&$QQVw4KRF
zsO^d5#KY@lCJGwO{toi^N0eS>`Wiwk^S`W)iK{8|@iGdc*H_zTVUv&eo-b9$p!>VC
z!%+Q{&B4j&BLOM`650O!-N)bti_?ISroo`rGIh+cFj?!%O);?i+B=^|=&aCvPz^fp
zMrP3xAELw4bdz@G%)9d#6qR%17%VJ7V`BB1!UPrZC193}gV7t(V^vo?96tfO%A`_^
zXL#a`*K`6?^TaS}uCM+@DAa%ha<%UJ`ml8mZGkn8T@-QvFx(m|r#RMwq5024Vsw}t
z>&^B45PM}84|NiE`~p$JDW@UYLXR6TA91JfPd8<B#X(7RhC@{B5HUzBTU1CUHQ6GN
zMS1`L00?E29*MIcC=;d9oLGE}>#MsCLLLADDBS{Af)EJY<F>Mz(-veQ_sQb@rJe=@
zfboONH>jb+H{{>yq;ve<dQ8P*GtT_!h`uB0Om&D`aM(@t$Uhs>C-fPiCo{cT5pvj>
z57HMUPx7E1O|@ps%M_Ov&r9cX^Cl(iWONIkPsvDgGMRWD`Z5`kUWR$?Va>Hg?C{?x
z?*6YVf+CnOEIm($iDAIH(fXfrumoM+umjW$fTvh0{~DAbYF=)SC9T%<w#Lv?qy~NA
z+F=h-U}XT+oN&mv409Dg!}=ud8pZSPx8jfc+s_YRM*zA8ic(!J#Jk80ZL=%8hh#T<
zQ4jn}j-GmQIg4BjBJ%s5aixwwIrV^?+>A|pFRyt{hxFi)Sjo%bM6%wx#-;et3qXK)
zWysiwpxwPmJV@%rHaF%j<V)k79gSnZ(ari}h`HEj<m^rF0Ra_?u8w=X8bPs7LNwf$
z>u375dE39rNx<lKRsHCk4>;W7DN{g}Hgk8W<boA(9{%{55c{w*|3n&^!_MgLLHLVh
zg7A_X#un0)xfCO5O5kzbHKPL)tSd&*E!A;9%Ef?I8sX>i56K~NhP(Kv!+cuw5~G0}
zB;SdCOB@kI`9?xaHxV3oKftb4uDn~6!a-GwAI&k+{Fwy{(@Fvu&!$MvL0n>cS;b>=
zZ*_OfWRX-ol!W&}cD;cyFqsa$i3eO9Y?yHCX=DeDGiho8f7FZkc-G6X5Q@KQkfUNI
zYje{f(q7{toR4&-o^~B^^W<V$|C@6yEp<6h<Mp|q`}k%~?2Cq=7GHuTD^Ucj!5@5H
zxX_GEfw_R+bDQ&KE+ycBF^PGS>s7LWBhHF*zB%S2xq9<aZ7DUYI$MV=keb%_Fnu37
zdKtjA{8WP7Sw21asaa&AID~0Zpa43%$>yMYRxwqTS|N;<9<UBHFNg4mBuApWIF2XX
zbwt|^4%2qQ3QPHil`stWwOLmmr0OTf#KSeYMy&WSKL|t#u&co0c)@3S+O%9JCJqJj
zxj%dY4Kk8H(~_P8NlIER)n<6z8AegV6nM@2O@zW?DjXtIp*!~H-wV?a6UmPN^Z^Vu
z5D^?!FE%t3+WiHVetpO==&@U$KK=n>^HLjI>6&>Dvg8j{dM)?Z*z=9lQ(6y6;;XK;
zj~T<~9l<|8^>t9^%o?DtC7e4hWT2n5L0GvC#Q4x$km+Nt0uFVW51IT}%nm-&PSH53
zHO4mA=8<I&j{Qe>f^V1|+;k@iaVyq|?39Z&wh?3~KTE7x-{osNUGh7#y%&6k97AGu
zSr7n&Jht;DZNd>2Vdu(^FQ96Yi74E+-et}L^8Uy2F{JxHVn3g{wDYd2PJ3z?yrk{w
zE;wEpWD2M@gb2m{VO7ir1~8UtvXrAKTHQHpP}lM7^T81CxIvsS7b7WYTjEv{l}BrO
z?I0WL)1VD^3>z*WFnOCbHly>h+v@oGYu{FVr9A+sZ=)4FW!E6A-z}SAJJ*KGGqTmC
z2laDp%1|}!5u{0}VfWUIt_kksE4VOb`&|C~!3?g!*a~mV_SiT$8q3}^Xtz7|>krj$
zUm8YKKI4)LNWsxO#HbkC1Rc1Vae8h_f``e}YebCalNTVl=V|dIW7v&EuiUl9cFcRm
z`WYmk7_F7s#vSSffu-o0KsQQPli3&d_2zAUIQn)ALB*#9QA;nM2}<b0z#2chh&{1R
z>keBf{)KzU63;>Wd4+Ai-9}_IRLce;j9l&#wP5dnXB>tAIY7q0K^<u22$5%8l}hFy
zIry8_di}b5vE_VI=^z>2ti83;-x1zCf{J+!h355ndS;Do`eE+6x)+|Xakpk`z!!{k
zrU3vIG4_*0V^)m3RiJUo$Vd)7JI9~+R^CbQ?OZ~AwBMz|=x<mD9ssu6pipB?#U-Sc
zVhH~`?BGI_UHRg8`u#?wsZu~}O+$>b_sC>rE^M6vvHNJNIK0*>28Zk&$TYO!5yTST
zh^{{8+i0>Z2uuXk%fF(J3xO|3EN^Jo?yJff_%CsMYO0P5Emj8DWUg_+56%Fz--o5F
z=?6W>#MwW9dJ$zO!c4Ek6HibXUxghgIPWEh3^7-PUI2DONGyb@I6WE=#ptwCv2U=z
zjA6|unB;8~4@{`Z0W8tI@fBT>fDy+#VnJGE-g$6g+JkkY9C}#ejp*PyiW^~x6+FPU
zIS~X^0V4}A0094h4XDv;%PS|m`jBmm%&h$4fta7_b)pmh$5&={I(aqET5Gng%y6A|
zI9ORg%o>+4@B0F?2n#qEa$SlduK~7|;&HAzqN5b?#A}HgjbVI1m;TfTkHma3Bu(@q
zozk)|<4^XC^pXv0Tb-Be)b@aX)>O2nbhpg~a50-kc0zd2p)0=6Qb!06v>|}?c>s#S
zGf^o6EFxei{Zfq!<hZjvqOpA6l|di8M^0HtIMJJhO2?84pa?-f&9bapJ!VGQta3&6
zn&rRGX>1Fgul5FLp(Neb@DaB~x<fR|jZJ8T1X1us%1s#l_mKw*s^P~oiSz(u_I$lV
z+Ewgh16TRU1t&_(LoTy$oqbV%y3{OpYdEF);Y1c@OIS7+^^N}UW}-kToKb_pyAoRh
zz2udgiJd?6qM171g;7j);%rkSeW6sToF!7mrQs*+`1v>mZqR4D2lPx#btNmvJK2NL
z1M+BHm!N;MQbN0W(_B`gk)v(y+sSbw9|&-dzRD2Xkcy-4+rFmcb>Mgrwsw$rSL%;l
zVzT0$!R;9u6x#S#{3jc~h7sA@d*Lrr8}?5pK3f2l5Vg8w!PoLPm{qQ!F~{UAf5p1$
zC>acLxX{&Dp{ns9{chk_|I}mcY%mCizj*r)e$iLm_dSNMnvp8qhRX;!z~e0EwG{LZ
zT2{z0(5KOPUA^vYLFS&FtRB@DUF79#k9_IK^JN40WvOy_`quCt5QMKvzLExPIc+%P
zI8htEpDD3G@t;VQ7PW17*~SLHS~8grG9VJR5{R4N&@VFngt<Sehuph>0cmR~i2`0<
zvIYcM4|bA^IvfK=dyG%dLz6L>9px0_LmNm-1aM@#j71|;PA=tJoXiD23$evBK3$e(
zeeRBT>>kBq$!ZMGnnyDKC*eMCBLqRVaR<psr2bm*x?9zpDGC%7X*dDO%73HSPh+{-
zLqEwo^(}N&n5LY7EP55A2!2C!r<@g#ybN*W-<Ao9R*An`r1hBla!tKwV#GM@ZafIF
z>p6Wp3C(EOq9{=j?>G{#d?ikcc`&l52Lu1CV<IKY08(Lo!F=9Ss@5A1q~FpBfS+0*
zQcKOvqz$2iTav1i<Qf)DjS)}sFG!Y8>pwN{6Ac5m4PnbSn*CnsW@~)|`ES$=KzJGN
z^(F%R#d|QM?m>q-qrkcgp6|T=mvZt>AQQBbqa|p@k{DfTkXapi)~*s`tW5-)i;+{r
z_+TJi7oZ)k6!W~{h9{=qfO|Ls>MpDb{E^{sfg}t!tG1oSw|?XQZ2P_+It)0j<9>b0
zAos=g{C};lY!4T7#790-?(IBOYu{YW^lcwVMnTuQI@tAX-~rUYX-)-?J3E6mB|4^3
zI_4&Wkc<Q&l($D`Vm0BOLtrTztgcEQ%D`uN=M^^7a;lWw#ZkOe4}Wvx08vD1!Yg1S
zU|#N$iU<P{RI}exwQOH-<<deL_4qNPyD=SJeL-YYHR)m?vvObn=n{$!tD=D}>-=0-
z`LP29wh-%yh)7YVRKG6tpPSx&IS!F40WyvnlnqCt)CF<p*fS86K&FD8;67P*a@Mc;
zR5GDq*Y`J`fc(8Za_ytwp+BdYR%Hy(n)@4B@(n|}TwpgJvIX1!vvr8wQu6XFOPQF$
zAs%hHu&%aEH$W=2Ls5&BiQb7Ew;x&g=KQO2ru^IfXNAm}iBdZ<V~QW{nUKQH>oxoP
zt1fCEE2z~}AD-6DG=ubOuCk~2t$mxsnKL`s1y~ce*`|*C#8%N`ZZzLC7vci4m-PeJ
zRx~|;Jowy0{B>G5qpCrMI<8|cz4-h3^qmD+4~Eg^9CU>>gZMf*)37|1>^;Bh*G?mY
zzf#KuwG~uen3vBfH}~T6LwvDi&FH@&3U>dhFB1GP*8!etpt1Ir;r~|ArjM?8CW4CY
zd;2$&(HHju`~PB#T0elPn*b!1bILESJUJ<iZu7J9jQ%X9zcQky%&&b+1g%=A6CiRw
zS9{aJoeVnq=LKGTJ;?drHN>mpTM*bt)_LK?JUjW1h1EbbJ@7@CjOlqeWn=;`HWNOg
zO2nb=GfB8}1(Nh2zs(_LB3!*7f_Fnq>)>j^{vhNY(tdUDFcxqWWiA?lEbX;1ExcJQ
zP&Lsb1nljrrm8$bAk+l~5mv#A?YG|PqGNSnIA*ZXsC9^$NjF(idDxE?pc7{h!`Gzj
z%!Nk@v7+p_7fR<JFY($(3nmgSpCG>ZaFf6Q006^bzyWQUGkZd3`YiEtK*HHI%vZOQ
z4G<Yud%W=J66(kl>zui^t2KGFqMg~CnRbsKKTM-0<?n{VV~6_$;Otz+({Dv(@AfgX
zitZU-=drW?sFBZ(Ww$bE1wel%;bW1E%|`1q8L(8<OCa0P?tR^|o&8UcZkz{5eh}=q
zcYauAq`6##R_07Y2xp|zMi+OcgaRVz6w+${9jTpP6PX1Y!jwvk_Te8D(rBZavsOCH
zY9I-lwcS8okNXuT?AD)8l-~XpPC{_FaC)S9z$~=ML{y|mVhU^>m<f8c@s_#EO=GWS
z%AJMQKftwCrRQx$(k<kDhd5bmYtEYjnaPMLtr!NezLDTINIc3594!`DiCQjV^3ily
zc7|RYIr=^6UO50_Sy{f+v6DGV`CU|j7t_bvx4AG?=$34B0-7hmAmguLw&>s<Z%lz2
zR2G%Y*Z_cv(jfPnS|!LD@L@ou$e1etv?sm}hZqdG@rhr~>6roWH^ENnC&To?U`<?a
z#ZP0*e4>;dRZlaDt4l991u%k#(Cs;a?c)mL7jLyXy@I;3p|=x43BTqDuwP3)(wd%-
z^r5r$TSV9Gl(y`%=qpp+TA5Rxw-<nv&W3FZM(lc^zzGlC|8pUH8#cR{+9_1B5&?3P
z`<`Ez+2pTw|7}WDF6$$Myv*624dg}}==rm<B@DnQGD1Yp^z;IagPFiwp|#FIfEKO&
z&`S}~_x2^)(LizjeWzkzXl6*`ZYWZg2s>NwvEYoVR8I{;m;#^SkTa$F(ZcmG&rSJW
zEdPeuRjF-Y{opOk(7q+8jTpZh8G~ixwy}3shY>XH#-(f1CELf;A6Jq;@S2v>*p-Qi
zob1psmf2wn(rZ#j{r6`Hh<Zz`+y^RzRKD_#Abj^xm>d~-ikEaYUEpN-_-E$CL~Fd=
zL(LIMKCKL37;p5F^;SF(DNv6~19VcBgCG)*YOO=Xzv6eu0Ru%+7DKKbu`R$7G#HxP
zBh<UWN1w0=qP&yXl#UT^jX4ZKG6oodfWV8GCW~L<er^%T)ORY1j|0%4($d8<_RJ4E
z1hjhwE=4VHxZ-By_nObKE#z5E&NX(GHcmPJh?@|%yCS$KA=e^4*p&70jB@#<#$CJr
z_$Zx3ibFG7#(FzeW<u6?w2jE5ZalUJlQiW(61<Ph=Qarvixfxxer$AZs!WwonR$So
z9J<basT<V|5XzoB<_z-DjH-w=n|cZ3hH+F(qRhST*nCRrBH?E2Qg2^czAe4iSW)Y<
zEDCio0JUi|M!Dvv$%CCM0OJ3P?H+Lxk1V{y)i*!woMd`x-1JW5@u_V`g4mLYbd^H>
zqXS5w+@$G06eR}sQ^;@fW|GmSMR8SoMTk}en3P+&Bt&>$kD8@HX;C?M+0{Y72IhIW
z)%a+5Se`41pD~>lH7Y`j1i4|BQ4lu*+y%aH-?J_Qt9!)KaBaZO3A*c9PY9H}6U>m@
z!9F=))E<!o<ah=}k5f{Wt?e*q{zP0&V5hDaPdU~Ry2J(rx(^gi2{lD|S{KGwZ6_OY
zwwLYt-B`y3Y|hTYJ)DmE*xvc5)@hvHR#$wG43eX9VMoz~viOrv??V2&3swMu7({u4
z*=lx=&Fjo%4F^7d>nD4sbN~_5pYofEEy`)^$hV-Nal}ZZ;MHk5M<sCrC}pbe)jV|-
z$|l3E!7(T-u<;Al<<GZ#?qzt#lK>;i_Cp%)ei)07MODT<<|pP;Ka!E<2ty5QCNax2
zpT&K<9hw)@2Pd;CMVN^fT*)#6d7dQtGpZVRgp;H`$w%4*u>nGYN%R02DqjVq_ZK|3
zXcx{V4ZP)q-=%S<KMWu-;2a80MgKBf9A?iQ?oaW<mEzUxOH5Y06kOGnaFhA%rpP*L
zCXt%}So&$9VdysrZYJ1O-<+sM)-VZHL*L)Q1z$uzHk6>LPHfBzNExV%Ob@@sCiJ!!
zKGuYzA@ve)d!kt=a@YJ)m?|}sg}d}r4=~66SkbtqIO#IyvhPAz?Fneg{fv0;PU&(U
z=y3U&A@W|JSj{!^HMfe*|5JgA-00wn3adCQ)7Xk}tcVIHqX)BfdwTtr&>i*a2i}iJ
zBG#!4;~3U@kWXZgv?cFoouxIC;A@x(#6C?aBE)yOHKDkHVQ%^gBvPOYVLd%8e0_8c
z90KarSt>P36G&!}vj!Zsn-?H^fRdRZ0000001h-s00gJRxRaPzlRK*p&l49}mVo!a
zRb!LGTO<M7#7R6o2<H(Cop5m^PF@Vj&ApZoHj;CogtbRR__0#=cKvV6^J`=L+yf7E
z+YWtUX|#jg<!MAd<Hlvg@9f>Oi^`duxwtn@FLyLh$RFI2OHL5dkFc|1Wc_k2GQF2e
zvTb&5j#7P+=eZ9r;JgPq_cf6;5U-drP~R;IDpRf;!g8uN3@~3FGMswRxRUFAOwA>C
z%qkPUX*a$X5%40zZzzngv)2-336e>4L*Bff>u2B(0nen=?4#9r(oUrQQ;H!X2Zlup
z-0V`Q^iX4^(DY=YGeP*P{i*#aZLKSeCnZ`J!TMBa_QDm|@4a!K%L#-#BJ0dpouf6k
z4_9+OP{Z+$Xadhe2hJ~@+7PZn9Tr>pS#9K9FXuK4O@L)y0Zg&c`k!CM<2~O5l#Vgf
z*K0AAmQo<URXOgE@t2tfH19`hPkq%Qfg*_?>>}I`)!<dHMq<Je&I3spzDC>}U!ftY
z40a)bG>fO@s%r`2@Pd2!TC&`E6Fz?tkf$B+rRq95RoKCb806gGxu)1R)WWIyCszc*
z*-o%Zso0DBp`|ysb*^pTlnraSJHoEgJA`gRGa_vD9u+Zo_5hhzRA+`q>lP>IVv5A|
z=v?{*qZ6zsh-|n0aQ1=qg82($hStBNW8OfuH)XDIYiFD5ZXsC6=uXoOFNP4fH+&sk
zq0Yb-8lZZtrGSP|Eo`St<ip19`(fKG0gaM{xd8ojs_@6bbZfRr+`CGnk+!q}=Kg>F
zm(528HVgm__&RQfCbM=JS!QlgiO>5@u#@6|Qk*<7Ez(lRznFIR8?U*9Jtm#LP3wU8
zBhN~BzyJ==2PP~8LVAps$bx&gR#s;p#$8*t7-<{%&ZA%B#~^0%Yui-+)eQ)CodRWV
z>WbjB0FYcNZ-u%>!(FAd2M-+%WP!K>?%_J=jfD!|Mc<xx;CORo8{SB25-kI%^>|OP
z@6=l_3M0N74R4xYx~xnlnBV{i?)V2RvR?(Hyef6CRP&EZkI)U}YRqPT!=l_})-NNR
zKu&FMKEDA5y>vqzE~{q0N^3E8KYGKHo1CLE98K!tUBOkhHCt}WT;;WA+Eg)|N(>mz
zzu87>_M*wMb4`3JxjLG_#HBML-u@mBZDx`DYVhV|3{WkWEC)&M3(zjXb=Y&_!oS}m
zPrD-m(wyP!NK}ZoCCqE0kA}u{d<BBPusJTnWzRtW3#XciWB54Jkh+nwtWBaTlx=(*
z1={|wwYwgSpOmxaY51eFQaiP2P>t|xoWX9Lt}lkqGVMx5`Sgq=J!n)w&Akw{emacg
zdsuDF=^_^U;y`+yC5UUQ45{WxW@x5Hx@rCuC$D>9!6p@1%DOd_OlUs=chqN>ees1~
zCEypZ-0(CYqcH*%rXZ1}&3+O?a@A@2wt%myVay{^p`xu@YbwOk8C=$F^52oHR5z~3
zI(?XBX<WN9@x$d<m<)&^YR-Jy$_!-M!|LclLXt~GC%}9Jr@hie&~EU=Kk{s$ocEaC
z8iY?v%e1?=#omrhO;<yPflWluqp)FQ!T0K1vGS5{fbL#Z5t$x??y1MjJ+Z*bKR%tK
z^<v|e=#v%WmgHqtgyx{Rr5MIf%EZA?ppE1hT|fH@DUcoS66R%cW^UO<KYIfurV75z
zcN}`|Fb{A@6=2X(24+@M1TaVU%^@I`)J4Gn{N73w0Kp5*RVnu@e}3)7i4OOq_LZHo
zGpUkz)r3J?FgOvWs5h7Jn<^u14<Soppzun9`jgGk*eNZB+09RmQTe^PpEa%|op5+9
zrR*F5+_QGl?Y<gTZh-q4XG6yx8pihIGzS4(rJKz#(BY3Akq<nIW(>^(n#~(R7ZdO`
zB_B7{HX>Ay!%6ksHg+aPkY45~IOy1zXRTC^)N61}-Hp2PlFAU0Y+jp8uS1K59kLJR
z|FTKk{36<>I?A*aByG%NVaM{H>~^{Fqbz1ur_Pg(R1sdBn%OC`s_n)jwu>PykR45O
z7KxEA%>0GCgs8h?0L*IVY3|Ay?7U#5^0|ZL%xnd#hH<juyw1`Qu^|9v><N7DvdXBO
zgQwVufPS=Hx%kA-<_%7H1_3H%p|<E`Y+a$ipFcS;aM;+`m<|u@oV2*6003;D0008J
zC7~lNj8iBs3LS9rT8(2{N`2c(OTYUQXG?v*iB~4t9`0hAkC=NLS6m!8Y&g?`@On(F
z`|{Z4UIa^`Qpdv#B}<tbVw1HJz!5ou6$t8V^f33*b5f8+OfGp@w>^>-8EvIOQ_+li
z7Jf5hl4q!K9n4+_xzeA#0UCwjZONg0+n_O4E#KLsEjgjzLP<T0VU3i;YOjk<WGsPM
z|D2l;5Pc4&v3y(><*zrc774Wu4f#`r?d#6?cpu+3PjxCX91F#afB_C7NP01?l?*0f
zwc(c9`Go@W(hD#)MMLCnu$qS5@>$UaZ@-va`r;QRVAXO8M6qaSIR7m~_P|X7b6A>4
zXON1VP^lhQ(}g(R!^J&e-Gu_1?Q@+vHE%<kc`s<g_$CX=idmsGuBLI)$}raXQEtHQ
zaT=-LEl%2;K$(4|v=!6N8xoMw@+yi0REml$r>S&CQrCW4r#pYd9#76q+Z#(0rG>lN
z5v<NygMM#|E6Mq=TIUg~E55>IEQ1gG*6w&APsKU$9n$*<`sEtKgPhp^(bOv_Z~CAh
z%3X?H-gR1=BNt*R9L<O~CVPD+pwi422%KD!b{}b90I~icbc158C2BC55kc6Q@FWR5
zFc+w+f<2W0Fh1kAb@n_gfE>IQozP}L(57tXud3AEcW3p)9celr?)PKQOHb=!05l0^
zL+!Z3X1OLj)YxkW-Xp7oyVW>?Z>fWeV7A)^V}yrU+gfpmY2oQPzzQn7$Q}e#{?W#I
zs(5Powbo)%nt2l-=Tws0(nbmaPQf85vA6JLw;{*l{!|mL#F_01X}>c}!^md3q4?fY
z{L|$}>H&fH?PI(yGBNmZm&73~(fzvpET$e#8X^!-dao(|q-mP_4^>ENW&|IZXqf-U
zI{%xK&96MwZ=KpSLgpe+^;entJd&V<K<P}YQnOE$;gU`SuTp`Vuwbi8VVaAoS)eR}
z$Pw(ocazDN@$WFr*Zl{N*Cj^@0Ho;zT{El~;xLr?2`+fbrW%1TsSlc^K6^UqX0UhE
zS77V4x)U5}kvz{R(X)B)b%lpcw)%UNf6QDlk!6g~#`_9+N)6O)VJ+dz(hCHzpXWBO
z#Enz<fG<+)FS}op<+GV+ovUO4H2n9PCHa+u)--AX@pCnS<><7P@PbGZkVv8O&}I*z
zHnj1N`~GR&127TzhueZ@x#2&Y(}u8!+z(I(ZXQ7Cq|XM8H&FE!d-BlwSm??uB3Kb_
zGhkO5kJ4PkqYmO|=6en=Rakf*P4^;QbbLubUBmb87)`BVng<7|5O}FfakUxH?iQv4
zH{$e85xd0&b`8%t1k!pFA1bY3PmEd<-wX&1r2O>>nI!1qj?*(P5H(n9Yi(l)IyyNO
zC1|$&if2<-=4=^uCz%TPXx!VOQ1n{?LqEjP4DF~YL{#gPCTcxLun3oWk@`bR2W<t(
z|0e}*_pb{A7V}>f2*hVwR+l_s993K~h*?$g0%jn5w#ygWbKFQND?s%6Yp)Vx%Oy^p
zj(Ui%E#nSgTm!|pRUv0Cn*SYi*N-<&ZYtkX>9ApHRWEa<<jwnuMpVmiz;mGP2$+?g
zi-Q_v(lhX1nzuMaZ2Cn=aOF{ELCFS*KZD(4tHY8vx;nA_pAzz8oIXk@E2dWs{Hi6S
zF)NUsinlFG&ZZ|9`-9>@AM&X=JNZ{T`qWyn_W2i-rE&p{|588N5^zGqdvHG@qm%bN
zeT+-Ulkere^graGB&A7r0@gMW@k(SG8C8y~kZq)IFFYUYF2B%BF<_Cnv*d&}41e{A
zh=VE`cWE7l-AKcIfHpq(71)SPnCB(LINHti+=&bSmYM1oH(i;iB&OvIZMTKu|A&CD
z9A>-of*kF_+jyx4-!Dt)4-b~(FnurICsENzz{!v|jXRdsMTOo>qXn*`F&&$}F0>X!
z%W~<ivMIF$dsx?cx4gat=!?RIaf>ghP&R+WLF8CIT<x_vKb^R;8Ey(lCSA=>3lCeD
z9WQ4+U<I2KzHTLI7O24mJ%<+o7XOjEh8h`Ocd?Jcy5-UOSL0l<<~`xPtTpmDeZoB1
z=buWRc=Lg0{55@gxomPe#U#Ec#haT_#;Ya%sadOUGgA|oZ%+l5u$U0L14HV;+2{ia
zL@pqQL{u*+w)FjH-jLyu@x@+IgfJ)#DhTkpGV-I-{xtzz*YzkuLl0G1-N^X_u&v8q
zMsBHQA*}l3OqL|0t-+T7oql#<+4N9Yi$DMX0022pYST}_ya0k<6UrZU3VVtcq(>R{
zgZ=@Q)T0}jkga^8wki!6VST6?7D2`VX)e{foq(}3J#>K#{?|=w$fk<*)t3-b!!%*W
zPkDzNK#`ZZf{_sXVw9=lp2rn~fWo&$^etf{h?J-PNbLlD_v;j%p}uR*ahI@_c`HoT
z1ARy`nKg~}nTNK%`9HO;0lZQDC1^4qji0Sv8fUmkGYnz=n%xkVJ~m^E>I%!KT3230
zCVonSF5}>4ZQWN&Qg@%Q(MhtRbl6zSWIO^Qq4k4Ry{_6Jju0?$K*B<M4M8WW?R*>;
zUkg(np0p=~gXrhOTOBNuO^9UdhnT}%G3zs>`aJLur?(6aHIgj7|L8SR#7_JTx!6xh
z?7_U3h(h>B@KFz3oB1u!V5*f(%>$JlddI@*VaF(&_BC=me%iWHli;{5`^H-z1c~6+
zzkwh(EA8W@_f~45HF3E=PZZaNV#WlXpurI8$lmB{++NL&C58@@s6KmK*TE?j4a1KU
z81ETynJnvIEC7o3>Pu9BK7`u5$0t>VRQ3TnuvWL3T-@*7qO62c0EcD(f~J4=%_$J=
zCOKsrmqqF3+iwjt5^GsjwaiRm%<d{bMA4R>w5O)S7-aG81Q*PtBd#lm%n^!^o!Dm&
zctKPC4>Qr#QXdI?q@ENVNgg`)Mh%9dD-pgeS*I*}2Zr23R9cmT0ik-avKrnaJ_j~a
zFN_e*;WX}O1kcXBD?>0_8l;wGH`;^aoV}zqi=|_HzSF%NtZQ5b$C~XaZg2e~h}{CW
zA?n{g?V~RlvODE%qav7^h_WN7z$&cjT@+l+e<VKC0(L~s;(q!mvUOF~#{LD6P7es9
zt%FG{5N)9K<B<c^ED)oWGw;y%)PNI`7~u&<{z6Irtp?CGXP*zFRY0+hMmUTk)61B7
zj@rB2C<HIE00h*Vxf+x$I()^QHx%_tOc}B3)R{j|YSQw4h)v<#>je7iJ#6UU86PNK
z6IPDkgtOA-UP7GeC1R()ktJaRjT-b1z+RYkq=3}d&I1-jFzy>}rpY2=iskzA&VEMA
z_$~F2Ok-fLr4Ukfl3-5@8_Si?BDHMNi%Vk?%DDtKcc~mwPw@6KI3cdS<-F8WcKzf>
zuxy<oF&-}a2XC;;QsVf>t|sl*JL@?K$x!`?ooY&4Yil7s6$DpYSR6O~9qa|6C`t%o
z+Jz|{_B2#0$?ebL*955$SB{FQV*gO}t+;7hJ3fA%^L3!>bI|QTm1zbZ;4twcJ{t;X
zjqWWhxqq*WZ4Df6zf#epl>FF=QEB`R*={!tB2?Pi9#n%`>LIdy_MdvZk{92m+uSZ-
zMTk>@1(bZJslF>e(6`htf=Lo!{jXO#h2F2YNmK}pIIomlyRqV^8h@yRY<Ia=cTP1r
zVr$fM{HArhiMlxPHG|en&JM;*Yo6#Y(;-MZE#`q3^%M4@`PrOIMvV^2(j}MJD6`Ks
z#nZJA@3qVnuV#|1-^n69Np=!zQm)va7IBGUwmdw^c6R0OilwjV5P^vIB$1KFO>%?#
zoQ!FumyQmK_39LyswHrWm0GXzlpuG9iK&$hfWIdB8DP=BnBZz=&&jd2`gMox+QjXN
zqDOH{nm{d5J_5cC(bG(ftnuY64wsnwJb`l{<wf4eq2ws>6h6}R09FAr5O$-d&0Cf-
z=@y@}5V5q$wn-l`Q(LQup+%^_uKi4syKecVvsuc8dt6;>jXoeG)4YSZYFS>FZaWz*
z`AgmSRZgVVhu4Hl7p@(66)d9o`+shJJ!oq*TeE9&ex|FLZ`-2L{N~sPH2aMTOJ1`T
zlcyU0s?TAtBI6Z<k@{O1=v}5rUsx?_`}2t}PC#;2Td22LO6C}f3qYcYL6xnTDjCP2
zi8$p~a}OkU$o<;>b7Z9XA{+_9Wx|8J<cboEDi;~5T^EL?kxfD$mZW^ijH^fEAc+?(
zBWa74-qV$@x?_rFQ+NYrRU%H~VEIJOS{?&5pj!4BPyoV~s8*&c#(yZ|<YbIWUQ(NW
zK^8<`hu*TU5hIy@B4KnOXn^0-@@WAc+n`~7;#E(l$<CwUTl9@uHq+v<c0@|NU1)_X
zAvWv+_#MoLy5+k{bE&M<XZwQWtuEVQY-iQb`-C`gB4A2Ke0@gDd5owJHfsZ80eDY-
zPZM&w7&84beKY<FZGoWy;=f--U-1s%=o0KUC>;UVAR#O~i<R0;kb?ZnY(7kE5t=P5
zyC47n0snrPbCw?N^ORi5n#9TV!jf9CpPsjH9jS*~YC!`@%?edwsC|L6eyH=*L{jbG
z7}26nP*kfV$tYh_j1uF)^->+^<#C$-LV%ZeQrYxc(BtEe>*>n4YXA$#S^CI|c5YSV
zlhp*JP#$ktlb3vMYHLlgY*Rl&T^iFZ=Y+rXGvm^5@&Fm(a1`ND2qlISGx=DR<1&|~
zTP8wPD;jk`wzGbyP`DF}iDMyQdh;%fRv~?I{IP-us@{Wef+uo}te$z3WPe0w+Z!Zd
zl(|Thzps(L60OsG6Pi>Y*b{h<pFF*$jCGNJENX{XZ6{$AGF7!Iqh+$X4}(vINz2Oh
zWA2s8Itx{24e2+^=1|qgZn0fp`4}z9BEd`+zw6syMdBQ%0d{S1NY#61mTD|MI{+U{
zd?dJ5v;qSz9;T_jAqFj?V5Q3=pN4AP#)s;WOo{hhs8j$aX|e&tC1HNKh%R%2PynPi
z&k*_x6|5~G%(xA4Yx7k?8?{!V#Y<~OtWer!^U1nC3xezqtKlDSgZ~lcAM30Wwel*s
zIICC`w*h&$!8QzQDpu2oi3J=hZJux&4cX1N69uG>n5><uRe**W(lAiG=usJ?GqjED
z=u0PegI5EdomQu3o12I}Xwi<g=Om$+s<X&x2m7!kRcl50H#!s}We7);bn7@>zSiP)
z|Fvr>n12ZQSEP>B_8l*B&x`p!lG*WabxFx#9<duVIWvC&cXL`KJQb+y-;&;HoH+lW
z>>0|bnVjYNs~a^&EivII7e!A#R;C6Ux3iII07s~jR<YpoD{oh-p(g`>(1(j#C(C7M
zYzmOfW|3pCHNMXQwOC{rY@+~rIi9QLoV(C*;u!NC9xDj4$l+oj$5&E#!fUNsLeF`E
zatmb5ZvKI=*W+*^7}+&0sn6g|g=xo`xsQpcYY+fC%$+m%ZXKEqzfLvvqlyyW0{zyf
zj#kPX$BxJV)hV%N!5q6XVGAlMo_{UJAcAAQn<Mxi0YVnCpwax;m;M5G0Wn@k9%rdY
zG3clOrPyn%MKW1W&X7B}VgE?Jn}uzpvbc5WG%_x8A2dLBE#`YA$?X>D!=oxmB<cI|
zTJ1A-uX%TT>?TAU%5X2*oT%^rHU!or6lb`DRal$<LAVXf+0=pdFveTY8i9l^Dr1!e
za-akf2%=^a|0O^Y%Qvp)-KpRuwK7|}w_E@JQ8A+9P&X(DOvw5(Yo&dVYB=~>Pc>}A
zuTPPERvApnmbPG=MEbQ0$Z>;;6ixTXI%eNBM=l-w_<^q26=evu{@Bu%oHbKKI$z9U
zRFk##6q7RA>Ok$pdtHaSVbs~0G1W8Se3qcC+Xl06XG4wP-?WbgHgeS9H24w3`cq)n
zXEGz>@5Gf}$dt!$N*@9<hy69d3BYq?a8AH4+6n;Ygux#8<0CzCD0Qnc4I}~tiJd5+
zpAkPGHrvk(7!gd#Y?BhW%<lK+MFCJxp#u0p4zs~ONYI)Oc+Nzj`()o{k<gtXm7vgi
zQr{G|u|m^N)W)O7R>e~Y)U}o9-tia|q4~LSv(Tp#dDFmmjy2~Q8OJGEW8K5p)r9`J
zQHf(Icn`-T&FdF<pTXPq20#6q2dr`nM4lv^aA&>n+}`S-oGq?NzsNcGx5Hsge<k}K
zN=;{OZTz5l4~~tnBLEZLEudL2;ngpvzQJ>#f&dqO^>@L#%U;-I6}1kAP~#~FZ6usA
z78ws|&<SY=HC(LwXfBSUvM}*k15Z>9Ll{2e(;^o7twd{T)mwLT994&NozzYHJj$3o
zIq-R-iA`DeL%b+i>`cko1*L;#+K`}XZc7|!_Yy34kl3O|9Dj)zc)M@I-s(mMxunnB
zKKa8C;}`*8n@;dgGL}@kiCZ&N#^IBt_iJuZh@g`0X^~j#g;(UJgS4`Bg$^R=%q=?g
znh}GX*57CM%n1NJigI(jF5%Rl6NP-eoC^*I3bKD!7X;M?EgfgR%f%`dlq7Hc&no&3
zj>r~&h$X;lJz%(7c1y~H)~iW?&voJSMI~e!KCR`3QBM72KP$+{cDj68ow2@SKOJb`
zLI{bC#B*J1e^k|naGc%3p_>`$8+ZB)q7~7tw?Y2Z5Q(&ML`uZA@_YJo*;xBbPu)nd
zbhjGBWlC0}jz}Vw4w~<=EY$p%{mK}MeRld7`)$@rO>MvE+w`u#5FD<R7V?EF8w`$a
zeH}k9sgcA`1<y)GICf;}3%T#zYd|#)!+C85RZL{V&?@C<l6s>p1p00*uqj$&nP0A8
z_IPQAP+Wm`n4%J;X}-rTmDvM#FNuXtiK$u84L7z&5kr64l>?B}J+}pE;+grp$qgGw
zmU#6o+pD&X&oPzR&71*6fhx`W%<K|7dt;f5kwuM)0DugWMUN4R(%(pz^T2?&h<xt$
zR@Gu&U;qqfIDlC|CQu9>ksi$W?Qg56xsTa&!OZ}8OXH2t<|F)!N;p}_yC-XN+aI4b
z;KAIoyK<QR=9e!ah-~^RV;62^eOiCtX1+a*o|$EpCM;uv^{3>o<((yTVrSig_D1@5
z8VmqpQJDX~!$l#VukKXNXWR-AqDpHa)1f^6D77*g8_UR1quTn16Uho2a^Vb=8<8aA
z0TPT?5(uF*hS{BKZtG^W$!rVV_0S#~7#f-qV`5v*uzs`>WxqEh2KP?CE~hSXf=kxQ
zqk;%2m1qFy%4dG%4NV6ZsKIksfQnmQ-bd99-Y0!1^`?%s5;>rQAng4wszOzzD;Gd@
z6qk<$MN2jW7SwCd71A$$q>l9}Aad771yHIe8ZO=%{8ZMx02OHZH|W_E!ovCm#c{xT
zKLIE8Mr5i;@7Hc|QfE)ZaY<gc0+xkV+cJ!L4mb?sVDnL-Ol0_C3YS~eq2H&6Ka#a{
zoa*PJ9jPyY!oK`i?e@=wAfGAKh#s$}KvtUwt>>HNmvlwc>XSut%ga2F<4-1OA~ndc
zA8QwGXS(HsG}ZDO*kONG(v|kT1_&b$QRqhWFoBWQ&lS4Sr}%i|hz(7W{+3MBOyCZ(
zB`16D1yL&LPA`<u`T&@gMlWE@7quhOj~Ch5$?C;Fw}e~|LdDa&kUZr>s|K&Rd={I5
zD`2Q2;%iMnKqE0@IN-1w_eG==fsfS-1f02OzBJVaqbTdAN{%U`75Tm(I~7#fpgW9%
z_v;mCK*iw*h|-nTI5_)=3`U7}+z2@<t4NZ=JLu^D&oPw3sv8M}^_2AGuQ7817vV8U
zYKY^ZzwEguih=j%;q8J8X+^@k&^3%vtL=h~yj><o`B%bJ|FRl=!vC&_Bsgy94L`^!
z9&mC^yrqM0+7-OPntXGlWw#_!aLE2LIoah@<UQaP73q`(_J5zOpU;#s*YB^mQa*)9
zp{Y4JAAe{~*(CQIZ|S&AEC!#}sWFtYr;RyB`EV++X`fz`hy~D91$X=~OK?DEoRJun
zb}d@|;%GDW;W(ZS_czW_`VWm?$q8Z}FTG3-CfHD?rmPc>oe3qw6w6_(rD%GHakcLy
z6k{|V=Mg23rOjTbZ2*}hfjH1w%b10tkl60|_UZa`D3;1^5Dio+hxEXYbNG;vE-ngm
z3&-c10TFu)_oE~nQF_-SlKXm29D)z3=V@=eC%EA-<ZiNJ-O;2lV{k?(@JL8jzyIk+
zr#nWHutC>|&#>mh0yyx5KHN0WwLiC-_<|q+pOhfds{i(^>XHqiF8`jjb&w5FJr-}^
zERmEAU0faZ@H^|0VRFTcRLJ&DP%u@c;{W~)6E%O+lQrmg1Ts5C>pU+Rj2d?t%On8G
z_^Z$@B6wPbJ=p%)+$mL?<~-ca3OprQEz*~Gd=4&2L?}J9UGWf0r)DWv-1cFB^M|fm
zZBJ?D_a1@|H7rW%r30&nDq&!%SJ(h#d(MXrB<wV+%gFc;kvJ>g!ty{LrI<ZxFW0cr
z4dDLOxJ3NpcoCJkamRWM>-tk#sFvyD#3%$3!F-4<{NX>_ie@pwVmis?s`LP|`Zf$h
zx|5E#m)|eXb-pAPD|0fXfNWJGyU(ZCbY^?^oLd7RkUe_0)$eed(8>@3vHjF*w3EPf
zBZ9^OUl-O^#<@#@NAFykMRgq>S*Wg(G9O>J40)q}K>4-P@>Zr8F0jB6fngBZX3isl
zSBI@=frRrfJ|q~isG2;u{VTiaE{z@3mUDaJ&+Ymeby`d&F#WoJs#4{A7AA7WEuwL0
z&(@c+(U`SWY@PD~0YJ?O629e3aq^#DJ~M9=KJOVckd6>51iWC2jBr9$;DY|aVgaun
z-hC%5zRqM4WA^3w>Kexr@}Ry+m7&k3=|)R{9{^kRJP>a_1SK__NxX>*1WxL2p9gl!
zgB7JBBy7`Ti66^lf{dN39P*d}^GwWW)=k;FcnkLwTUn_T(gvtMS+hAIO!Ed{RV=4-
z5S*&j6eSr!Ol{Fjw>Sx{oSPL}c`r%SQ7a>h%V2OI8KG(<$P(Bvz;)kqhfwijsnyVJ
z2@zME(_UrtG@xz`rh_}jJ-$?<YoVGDsArVr@pbmz0oEjI5O6d&q~g>DD{#FV9Io-b
z3*P2WQ8z8t!hrCbev@!QRA7?(X}p{O1e`4LNdzA@yeYVM^#s*EYt_f!mz5d;x}{Xx
zt*=Qf4v0`*)Hd#-Q+4?P>T-8oVG@>z<6~^6o#;^NS)Zjm%Z<!~rv!7})2@&4TYIG2
zyr`nKE&&@%(U`+j@uQirKpT46a83`S=u<8|@&Ilh8kX1BP-m2p5-4?Yf}Q8ARlUE*
zOX}Y19_0hQ*0Pl{#l@D>f8ify+&I=d3i#NNtz2c+(GLT#7=Ve`9_z}*0Ye$YUw<Me
z50)VW#@*C!QGxQ-&~NM=aSs4{E9D7N)4XPnBw@|__T32C0keL(kbnRIoNfbP5sKNh
z)j<g*?qEmtPI45K0)`w%!2ggY@epo&-nL?#&$rS)h8+dGaE)ubf(C<KRJj1F-LHHr
zYPsTi*aG|U3q~|PwWXB#B8Zr*9pad<_~a*9YB}R?X3N5x^}8mqqf!0o`KJ_>t)cUD
zqa!~Rp+$JJwGKH|SP2MsR@SU-9BGM}L-}~=VIkB}DAledlLH@{P{4Dq62ZyMmZO=9
zIz=sJOpWy?6M?EQ=1NA6AUjIXAiQ_dCk5n|hOVKh&%e@(rRQ6zp;E!W_|zE5m2Ubx
zqS(|)t`RECTARCPc9wdW0~oWFyAdASZsljCD#HCyvSnl59o`zlFo+KA0&;mUgk+9d
zMX}Plw4=oD&oum~%nCV=$5zq&JtAbIIzweUo962$(xNk{-u5LAJ*(mL$9b>n!G1y&
zUT+A@Mn1ab%S<01-Bn7X%;4S<XB*ZwXv%x<I^ew}9D)}ojDn=uKHb={OtWb=?J78@
ziAFZG`P@kPjik)r4aJk(Kel!F9IVA(A#2bBIK0u*{TGJS%SmQad@M%-y9a7afnJ{o
zX2F>=O&b{pzdo0$y?OKVfSxxybBg#uJ-raaEYA|<^K6~u?)$q#g}HKpHKBQsE-pUp
zw;6{|Kcy%Xjm_mWHF6E@y(M`Xmjf26s*UfTC<RjvQ-H4~qlX~8lLfXtonYGiapf5u
zVJT9f_x1C?0l4!MxU(a~{&6$ygiE$T-hEpOcFxVo)W!)Nl(ZJkxFb2GL{)L(4yTJS
zk6(8QBHSsQ|MoyWH}2LV7{fAN5M=lu#@pWe!nxeKv)hZdRej;6{oS1Vb4x4jWx~gq
zdu{D&3g>kA1P@G3Y#UH&5_m^9_-WHMt+e{fD<V6i701ZD&;;f&v`<-2Ib(}bO`LIp
zm@^91!886qJ>@UeNDzPN0c8!Gee`nII16&WUw9=<wL9<k4H5MCeB%70Gq9!LoH*U$
zo%MDnB#_0Bs11I3iza=fex`0UiMfvKHl_gPWjhJL5f_2fu56h6bGMx{q93SPs_$#_
zr2Kyscz;R1MFsc>8<%qUtqyC=)Vcj<_3Qf*JR1_MPTPE~^p**Q&5To%F?HrOzH(8Z
z2aZPA<DBs%&rV-Jq~aE-2?~z@r=%G2*a8ybHa<*T+VVq%sDDIMy=rVbUt>mitKVrF
z$PIG$&q=O<!kCcU*0nY1mU6wAw9O91w+2!?d)rdjVGubvlN&Y7|Chp+Wwt8lwc)ln
zT$y}BdaMKFbMPv&_E{(jr^4IqINkbl&KD9G#N^MC%a#}A;WY90S%8xnV#pD?1FuwG
z53^qVyh7>c^Tth+v)|>^Vf-#EjJ!^ExQo`LvARo-&dHdZU_CP_%`O0HMrh&*1V)Yz
zB&~i#YU}#L=Ao-|qAd3dSb)vvMr_DSJ$pOtz5vc?41LAJ&v3hLE6pg~^m^DxLn^RJ
zB>b*1<iAgs$xF0Wr1@U6=eYhS3_o)(EGnzKLD{_iZ*S=Tt;M50A;MHmu}-mrQBx+^
zmA4jPKB*fh%l4vV9qAcN_3$`a=hZoNnc@zZ0^RLcq+0ix(_<NPD3F|to+b@@JX04J
zKSwk|I6@aL^+h!Kb@o;1tT8We1&kF9)t%H-+gnxxkXOs9?XUdcvIo}Sj9#;ancn1i
zHts_WA<D5smP8%J@^N8Pp|7(0Sn%C6mbe2bws+(Wlxj!Gy-P%pFlx4$9U<Fg8YM^6
zAXlYia&Y6;%S&1<4|F0(<O<_P`w0R;>YPj)$5?BxQ*EeMeULQj&ZNdb6xwH+J&uD?
z`IJ`TJz2XZ48d{<kuH7%apbv&x9VJQtEvqjt^yF*SFAd*nxM)dLW|aPTIM$-UvH^4
z<(Di~j1aMTvVYLYVJ?epsJ=uARs-a&%pTJ|^mp{>z`J#0qJdt@PgM&(Qz<G(9(me1
z+43~yw5b={i2O<5p~EX%K-k&Z46mk7DO7F=Dh^K?;jaqAQdT~N>5Qf?tZ`-J2WIaY
zZ{y+N24fBV)=aE?!j~&9HhBL#=a7%V&}OtfW!`4%41yy|E!RTGStv>7Tu5`)>nQ@f
z;B^FtJ$FEo_nn9WBMR(5Ks8X#lOHwSS62n)@=(VVnN4KsCjf-%dc}{j>sDV>b;}LX
zwwwZgt^2Ji@DZEvMQJ<J%5gs??3QHNO&`U=(hOz}aDpp!@qodB$o%j)a}ld1vT6}R
zo~O5vKq|I!pVl+LKY7?Z*@|Yv_p#q!46DHH#rJ(j<}&#z^r^VXyGFrdbS(6i$&0*>
ztFPqu8C(2kcW8aC`mPpvLi&2XPp_3&+p-68*4w5iNDM1UOTy3KZRvPxypa(sH;LL*
z=|@&S4(m`Cn??9)(Y`X%{%|Ga#NMV7e6@^f{~TemeMp)SMR_0;aMjBQ-tL<b`57<$
z>l+c*FwdpRv-uk!wi;N=-%C@J7UGN;^&%=@dC%3CR!2JA^V@TyS;yvUfW5VUwom#9
z0Y{_YPDdPBo>;cWsAim;TE-fmno!b@_!0Z8q~T=b?ur8onV7%%=@gorzC0ypVz=Hf
z{@>{8oM%e8g_EEts2SjCVoV3H$_`hK92G>$oVKR8BU-XzO~l!WGP7`C_{hP)ugOpb
zAjC^27%e56Dh^glQ&E&tzhH%3l`S}@K_U$SPC$SF0Fnp;xm8Q43QlAZ#0*IS0F*7e
z;$YR)%k!FVGd#><U?rN~Cs$^OUbp`+?Wo8?u0iYe9A?>C9>0Zs$4{);(=VyQ1DpqR
zmNiqsRQgVzJyR@h9mE_l3eG%lVz8@iyw^_C>QTthCQtV=D{WFq){4HF^YH|sdd|5{
z<ek<nxR-$spFq=>i_`kqw8v~P6z=;kSJA5IvySCz2sW1Q)p7QW0@Wk`j5@ycN~^M^
zCb|a!8*}`GtXgKUR2s^S*|0?A7$LJ_`ki%UOx&6k(=A2NJjAg*1i=RkNk=A~))bMA
zPd6O1-Gv=PR@wo|4hT~Zx{h8*UG5DYd%|x~_7cxF5&^*9*4Uk}Ir{>-i@coU$~|$^
zc1t{5Bq7?UVA!Hkf(kKi|8Iowe?-O?5^RYQ>9{G365s$U*mNomL!QsB>&#7+xay9<
z@QTNDV^bNX{-$Jh7yxzft*C~U#EYR~BQID;*iYhI8_m(+VPmFQYSza~uvt8wDcT`m
zN4d<c@V&s;urnvuN#=9sbc?ygbNvAD@Nh4CjZ(&ah><?$3^(L`F#uor?o7YZpeVYU
zo;vcc_j{|f(u);tMCAAh(nd;dv+5BWARgi<qMUNNoARsIfmLXS3_kD{PciMc9yOs>
zNvZ%f`ku>4vh^hkd2-opM-hlE>e$qVpAE-@K@pF`nEk~z8QaEY6R|Ieet!N<{Q`p-
z%g~_Z7(WFbiVeDe2rXwAXf}X`$2Do#f17kiQ4v0}Mn|w9UUx&Qr=K^MUnEkLU-~Vz
zQ<GT+DP-l9l))cw+pgA=2n7ZNMgiDJTW}LXndem2TTssfkv0Q-G?4n>Mut%Q%wgt*
zw}A;IDm->$eqR)b-k3w#XbOi}E0te1b;<YuT4AG)v!<_>B+-&wwxIB9rJtX5v<VZ=
zt4m)!AlAD0-@b)=UYt{?{Am{d@_;byug$-XUmuJzscLQHk-@8ic6@FO$#F*)=+oO*
zm_{xAz0S(QS0S6LV`9|`aZHcce9Gox9)gso?Zj*D`5qAI>asEeZhZ{v$A;gi5>}(B
zIKzEf{bH7aZjKOev(aTJCl?k=I7eB;6GuF-Wb1<{bJUDfQN97sP_WA^0;fa{(*r4N
z>Y3(2Ynm|~%5;o)YF)b2J!8{fMy8|}ylmiAf}bpzMBkD(%wSpm-U><iFQFSkQQOjX
z5+we10m|?K6`?8gx$<lT3UI18^p(3F3D15mZt5%d34grH0;=t?br~Ce0=WsTB+kI&
z(z<k7h2tMNxbd1yf#oM+0Wg+<ANmd_jzs=X1VTcx+yPjsRipj=+!Puu3mHyBC)1+7
zN$n2h@*hCIs&!1^cpN)7EYH1qc047Ve0cfL6r&mD%?*wde$?Xt(I4Qb2Q_S7^)VLZ
z;3v}<a8Vo}m6?LSozo9b_wKF0Ed{GKN*}xVujFQJYs0GvQ9X5ZRs~`yQ>POsdYxuY
z&VHCS$=&>Qt6&1yl4obP%~#CL`Vns+QJ^t*kVJ2$qR58+{7D433)nh=!rV-2$G(<5
z#7+t}Gw6~kWk&cm#;1w~$*a2OTWpQyG~^ETfs#Y7IN++2h+ZFT{S=%mHFwGSDa7T0
z85yo-iwC%GX<I8otDMpi?<XklXK;<^u@oe~V$%+N;*E3K^D8)}|NP)FS{RT5IkcW^
z?0`8dcRbB}8Syb4VblQd!0v(fxx+07z7HsI10PMtWt1I72BOC4{;^2oqZ@bACqmFk
zJ<#=I<K|Tsl<4!2-bW(tEKNnj4y!CIIx1H#__qdojrdi&ru8hG1if+toCZgcPn=aM
z-U-Z$eUvPE?|<`n|D+IsKDaH6-DI>?e+Kr}9=-L`u>nGY8kZV8sgM(Z=b78CaRky+
za#(=A0HxvNw2@ruPzJi8U6JLP9t75ebWXzWr@eA|WU>(<M^uqqwqa#W&}s)+QAlDT
zWn09ACnOU=`0b&58j8IwUV*2cI4alg#WIfg<Ua+!!`L78<tMT0lC=7TL3lKgJQyWB
z8aiGP?7g4=KRt<Ys3we|U36<Fg%H8MmlyGV9u#}BbPkSfru{(_tG)ly+!ZvjYzmny
zRl@I=pYpsiGE%*61EN>d>l@RGAa!mTEf1(M;^b;{+N9-%=S-Ib)<f8Kv$&#R`3!pl
z?keT6J^lqq&d@ta)aG$P(fosfP^?x%hAa6lz6r2TB3fC^EWf3tE;I<5)Hr1Gd;;P0
zt;Y0Z>E$E$VBbZ8icfaFWzBal+J+rjz@PM^{ul<zl^a|9$+hTB{{e;4`nyq2&D3@+
z&kIx?%K_Nn_+R=Wt+!zuWg_9BHmi(}kH_<HbV`J9)E(svXpTi9T{PtQSP>WNM8||6
z3Poo+)|Hvt0`4Vd6MYSWN+J(appcNqqER#z{p!O5%8pHVc{VQ^=_L%t|5>Hu@x~8_
z_xJ{r%8jo~&tz@B9SpC4fS(hQ6TB8cQeh>C#SFXh_*$1kR|WlN#*5tvX?S9B_T-E$
zXCX&a3F7Csij?OKx#z@ZZO(PDGI!IRY5zxVS<0qk=j5~p1aazQSQIzjJg_hT0KqTU
zzyQa900mAq<S&2hL0QwGo;9KKK5)7ThF6q3&Jg}i`Zbo|8vo$2Sub-RHY?VC=Uxt5
z9M#-{C+u{J(Tr9;h`}^y+Z5=nZJy8GVN`^J>8NAg1(?O{a=q`Kf3{8Ls53jxR{%{w
zvcC$b4@^yTYgUs)mo;8aAmLYtjhM2$e9}4^KAR!~Fri<CZJE>diYbHknMNWZie?iU
z(=?kqd8A>$fa`IU`LN(Amo?QKCkd;j0<eG$3VaoZ3pRVwWO-)NE#{N;E4k~y23EN}
z(AEAZw_VR*W3w=~9D3+aCS~!%&xs3rKxa$v*_tr1IaLzBLS0C*diLQtX(~BsBRnlI
zU{UBXI>6WRV^PuIJ1tGN>opx**G}H_R+VdTU!GaHipypIqrLMZ7w(X<6_HTLfz_9z
z>#1kEsb_E<zy{6EY)DO{AiL2;*^aVa`;Q1tCVYJ9o9rGF2y~4u&>BXP)z|}8#K}+{
zd5!MKND?RQ9A;ZueKIvMLvh14<v0Unn$WqWLt>rMRLNl`RgH0ubIx4}d25Qh5!KXi
z<bZ{8=W!Ov23%8otLCR|#`Nu7QGnIDumQec6ox51Mp_Ly2fVsimy&vO?$%k>a?|%R
z=Fita0VFKEX&~K+?ekqK7T`G?%Dl1mP#mY}zX^n;Bb#qa`P~w$umP9`fYa>=A?I>h
zOs}Dp8vV3!6#!*uBXZLgU!Gntf}ayfmOPl`S$>cjX|5l|1BNx-#pQGj-d-eySIXZn
zPT+Kl-l`={9}s9DEzY*Kwf(3l3uiGU`pS}oM>m4+Cl$(pHX+tJuUW=&36xC<Y)T84
zqcn-e%)%Y;9vAX5_Z3Pc^8-u=lQdysU3w_!jqmwn(w+;gfNs6!|1QDAp(*;c9-lRD
za+I$(Sm>61zP6Rr<M7R4d0*V)$xlf`LXV2RTX)`Xo+g?7B9s2JfM!Wc->vOu2DCmA
zKwtRoeLB<-%2;?Y!+QcbGa=-Mi-aQdQLg7=MV~)3t``fHCcD#m{>!_mq#OVyxGHau
zakq+P1D}qae!mBpTlmhn&0bjPXWT;ekmQNd+UUa^5yeKTf_eh_XyC=G31eGh!*gf{
z@)#ow2i2gl!Wp(0?+?Hluvq`QD+47#`^;QliL_aJ8bNiHq?IWiz6SjQ{iMn6;IUds
zFhgRv=b}Yk?o<M;B+NT7nXPELoKIw>Oe&<NuJV&0BO+RELZcs*c-PvJOK!)w&fR4p
zQ<}Ga)S@;zNdjopEZ<{l47+t=Nr$eDYeAVi>Q--BYgNTP<-wM5@D!?_eOP(TI5`C`
z3ESIfJLAxe(AUP=oNC$RVT-kMt`a;Q=L!FZvRU|O6=WS^r(s$**fCu_5)AVR0>BsD
zt{(ruV3xf&<nF-0+b4q@e_DLcJuqhg1_ozJM&wW($K|1%rW<1rF*fyecWbqXw_V{b
zPwzEod7d@+U^aw1WtO~zU(}K@G!C5kz|T#%FO)3OShQ<s{u2iZ2+6=J>mL(a5ng%P
zw@dO$ebbqCkzFMA%C7J(jlVKn)$JZbE<DvO+C~zgGw7p`JnMFpGXMQYFG||JvE*rd
zXzBDuOZ@Qq#y{>7OEx+fN_mPCHMMXd+cd*oee{UwOE~sTUQmjlJI3;#X;6SBZjM~k
zcGIl|TrGAaFyZ@jlmz}2eZMbz8xvvrlq~4GaQoYqj@%n;_-7APfis?YbAGDiOORW(
z1Q@C@RWh}*&+e$R+{co@u}|NitAwZ&YvpbGdwPT<o=CG9BplVyYnEu-j+0S_$@^eA
zKi(tVRPzQBO4ei=1@^|^zN$3!6gKbIHng^*tL+Xj{;kR(0MNqt@%l8X<)QOmkYIxV
zXe0XeDf==4;%KLZa4GNdj2twJ?lqFg?*c!sFpWE2y9a3o_>zB@l`^r~&LKN6^o>s+
zfe7&P1T3Yl5-PG-#%<xS0QX+9^P~t20ir^r@wM^NOlzIedU{f6AXsTF641q2%)5U@
z24#3U$=MI~DpHf<hA~o1=$W>dF2WVa{oY{#u^0WZ$dQbX^RoDRs10rzhS<d8%`-L7
zB?P7cfr|1Pp%6_LRPe`CxYeu<mJZysbgZpKp|L?y;PQJ}b_e<N>g?%y5H$JcH^FRI
zo4%#`rSPw59wOs{uYTm>Rq$JusbNJDKKTpI$_q$Rw48lUO{gdNQ-L!zeurdm(8<qy
zqEsRM5gHMTFYj=|U-mhtBLt8bM>gCVQv9{1rUqT<RGnp$Ml+y1T-ABw6}Z|{OJy&2
z&g>$`%IpN}tG3c!qDgHB)P*C@8S)ol<k`oKF?vjmOYo4=aShp3{9~+E17o|P+M{$=
zWH*GqNlm3DTjuvm@AFpNlz!ew+PctbJIN;;+O{s9R+E3ZLF%mj4>i%!Il)E&hW~L4
z`1rpQBvQJyGHyE3Y*NgGGf9Xue~xm@4RJ;~7L0&)=n<@4c+Liud)V7d8jFXJ^}H+*
ziF5h6+vtZZ(Os~3uSO=*M0~NyZeNd*u6jM)XMWA=?gwa3cQk!|Cx;4aE9gWY!rwVQ
z)ulfjH6%<|vPTW&PD{=xIeL`(y?FPp9hJvV{5L0@Y$62`v*dcgJ8dmFRiv5S4oihq
zJ;`v<qXEIo(o<qR*K*fQ7-YUYQkZZmK$1Y4(zLz;TY7&P&eN@SLHdc9zyg<z+b94>
z(f|MjVg!=wSL^(47dwAG)K1-Y{tZZQj0AuqAs-dKS8VDCak@)0S($nZ2kqT8A>fQ>
zBd}%<Je(Q#$3v*McPhwRUP~cBq-82?Ai>Pc4Lisy!1*rI^w)l#$D9x@RLE2XF(cg4
zVmzM_B^7Au!Kk9T#T;9)2&xwx7YM?k49@?9G47UqD1}WTJ{x$BUSuVb+<?r^rbtlS
zzfO@b(<B>1KP4NHOIuv052AUPy<=azQ#WMpNZS-)lw$q!g5w!FvzqE4#cIkpT>7(F
zEokELOY}>1V!*%efgp1e6`M?PKz4tOLj+$^gQ7^xXye+H9>Y~iRji?g7lOLfEz0T?
zE?BMoo0>@uR9KMFg)JS=qdMuXuPs|^qRUzyf81+a9pKl~IN2vM`A0QQBSbV7bHbH0
z+?gG-0?MMw91TK!0T<+s!g8#s6EPS^EH=Mblq7?482#!5iiBF2Znp4Q^O-;#PWQXg
zzf&emqfY_6gSlx;uU|p`%Ahnpg7N2qkFcxWygfKk*L%?alN*zh*%mRp8sk3V>*#@Z
zol7#c-9j=%^*iw#UrEg~O&hn=BgNYX^OKN8wK??&)McY{z7;ZkScG3FiT%7F1rORV
z%SU*b5hhmyA9AOQIhh<MXAP_7G20U4*0Ou_GzLQvfH`nqG?PX4o$>-$n#J4&q{N+X
z^oCc`H7)WnB0E`7>BHb3l_D{_{^#N^3AyMx$sxoS<lwLDS^1G3J|AXTA(G0W7D$^$
zNSit*0-oXz+!G7XntUq#RPu|C{U50{tMGx}W!8Qa;g84cty(Ruvhb{(>TKTCeCbSt
zf}J|SY9~AYZbJ>UdS25t(KzGK>99TxD`xDXv{>l=wd6y9rbcG$L0uH>)-2`2auaZ#
zs?!3WMov!^VKQ_UF21jH0lncp0Xk-;&s23Pl6G1-v1;;@*B4P0D?lXSK0eH{$FnR`
zh?t8_x1<i>mJF-EkNdNR#{T|Lkc+YoYX9-<P=|Krin85`gOk!&9`n5pFeDxmj7-67
zLWFqIBelq6&Q)@z`!6A!B7@gRRg@2Rj{TDJJS9@4fw^7*x)5tqQSM!w!ahlCI7ypS
zb>TZNGeZCi@Rk6#eSBp5z?8}9ax5CjmxubDHkEe{S&G|`B?ESMn10JLy=oX&lTpEP
z7cSi$J?c#++Y0{1$v3?xN+^m=y5!T>4$PMM|KzW3Q$N-`wfx0rXJiUcX0uTgYR$LI
zW2)KbN}uhsz4BS?7{my`1T$b~_bVJX!CDPWFQ!9gr4v4iKTcsZ+D?3wlME`V%_DmT
zWG(7&iPT1Ljp$EOyoVJkVC<&703#y5!8#a)1BO1f8e_NcAspe-uy(3`Id#PXw&5KA
z`z>+29@70ae7EOjxbV0}<ioaLQF7J=>W;s+S4{d?A-@8Kc{iJo5uEhG0%u((cTaJ@
z(Uz?-R=>W-{V&SrEU&zW9mFHyc#m-}9*KtC1kn3MVlF(e0nD;jY7gQ)c@M}evE5J#
z6YyC!L>yr?PN>t%l4Rb4!UP)jqpcOo%UH2&-_gV=&<_)u-zR?MBq9ko=#=rQuSA7i
z7Y9*d%T#}?otD{{$KSIjL{jJy`_^dgkx7>>KKi*}+XICS!7;kq)hGulCzm&XWQ}-6
z$aIM#-MrVBYl}as;*?owb6d#e5mrP*-sU1$y(ZkwI)Sl~l?@5h0~xAm+d(y@AY>sY
zQ@{1UBO|*xp$z=Ym0ybIjiP(_|KwGReD@a+7j;>0rX7)Mi>A-~xu{R+nsqu`uo(@k
z_Cr!NXR`eIK|6^2LE(@ZNknHb10|ch#@K1m#p(BK<YNn5cogJ(-+d~k5WH#L`*#IW
zT<N&<GazxFq8vo2R9su-)T*E9dI&Ity|qulAfCx=mj<4|6Pk;z2${m+D06g7g8>Tx
zpS|4{SKxm3UxS!9-uhrj_3|q1Qg+AfPDc~jg>*1pKu-+o(QeLD=LfpBw=d($t}LQ0
zb&kA`y#-4<g%=~bGB9jo*HK@Bc@dVO09$13DG|>>gK>r{_+w$OZgPZy+q@KLi(m9E
zmhJ56z~^{BmWD;l`U^b=S@W~a({QaNH^K;$8|FtU!%NX{X;}1embg4Fdqtuws#TCA
zaQGKjeA3T%5`Nw?2if$!8YHN%?wDRG66iDJT~a}LY|j9e163paN|Xbj+g~p`?)Hz)
zu>jPAS&Z^COi1&}N{mP@-$0ST+dlo05!oY_3==KNH&a4Rn+MLS=Cx}J9HYV-^<fum
z?%z-}J5xyH50He0Syfm-oH97&xY1}u;!^VS3$mxgqd;Hyt7zzRK_GzxzK%n7pOga?
zuSy=u@I--T4K5b^riPO8FY(3DIsBRdn{yao;}}M5DMItU^bP=MLT|#^#aNdYmsx$K
zeFIu^g3fm-BAnzp{|=MP8RTjj<8M^^AS6Q`7Z?R@XY|mk+MNvtpLkD-6nqnZnEciV
zzPPhhX98+eXa<P0=NSt1rj}GmzJ~tpyVldDJi8`!O_t>a5;5%r+?mq?_!a)6Hg*{$
zVdc#)zVt3|(qM7gNUu$$U(#6SGjuX<D==U#NfC5qD@954&9YkQ#RdVc3l8d}lS7CZ
z8XqxOoQJY}>NC{MzE9bVx||(Ei6S;JZvcRy8fCL7C<t*~g{y0&pa}1YB;QN|B`+OV
zp5`0putm~=Yff9s*LEe-oUa(#s9V6$-~a#sA2eVu8VD)}jEPv`f{R?MnhmuJ(Og7v
zk(@te$ef*v{R`?&KEXZK@ram1khM2pIyK~^B>}Q~V`Z6Iq-!3YtxmUkr5)K^V!xfz
zYj*yQ86#m4E2l=v_Jn|+%_gIC8q)GteuEFQ_|8=mwnx%sg``#odFu!BOLY>&vhWaQ
zW`BfK_6&q9Z8E~UBS1v3-j!Dg(8l_eM&s9$q?1<9+&{-tl70%BD5ds=!m+SsLBT6-
z?GQMZd!h_G410&S;ux1;QS7&0n-YoPObNGHY9T<94T&6r{gw>i&*LtxR2_r3Pgp8-
z0^EJevGut!Sxpu8a7*j}Yyk{_$&|CZYzHoZBPc-lznCyHLR#?4!UUfs5aer*0D3T<
zx*pmOaI9OQ^?0RL5A`41Kspr&O6|0m_^1*QW7;h^pO!&%_n8@))_$Y;7=wx)dmHnB
z=T-k^aToMBUo6DE0GI76=W;zXaVikp5vg&&EqdiKa1+e0sm4D^D0jEaQ#J@fHQxh_
zXu|O@iM&EV3d)OVAbtr#<?3a&1OZpJ=TnQ!Hn2xeieeq(spPLTT~xzI`BmnXfAQ>m
zHrB03hGg-&E-?W=FO*O$;yK&1h+{%Ou&l;{(;mL1AX5}w_kE@wK0I(dwgD>~6L&+%
zwXkQdDVc(Ao)a#{ZB=GTX{QC~);uq`J8uNU;a}Gyry=P@nrFXBJ_?CJNWTXWgUr_O
z8;}EsZnQ~h%9y(YqSKKVF#K$0O<)$oU@Py+MC!h*eTnJ))kn8HlZPmA2yA2Nh5q{7
z9(TO6L%T@q9WV|D{mB`cK<`pxvL-933@2l?X6FK2q0)D~0adasd9Fc4)kPlCi2+JB
zQAQ(<VaBsK5*ac1%t6p()&T>x#E9H~(x6UbNt3_xSFJX8@vc1kKEYC|p$;v!Xu0|F
zU`%&qr;TNKc<(iS=ECs!Hmb;x9zu$~r>}`1GvG>beW0quy18XyK{X_|Qgk!ZdGOY6
zo<oo9Ax4uvC5ei8=$BN_o?IHEa{9s9pDFEulR+%@y<F%8&a;HVy$=d(7gNXQd$8U3
ztOIT2C}%{(0f~wY`TFVSXUz;dVNN}pD!2F$_rNz_z#cRSO{0(Uu9&f0wOYuS_YcG=
zY{WCCbMoj6%N&mfeztF1NqD=VOb`1ff{R}hl<N9wPq9BoxeY!1jDo3lOKX#^e^ZY?
zT0F2On`BJ33S@<I#2tx^Ji_-WL|j$t^4rY>!Gf<Vp$9Y=YI0UNHf!OtBxf_-2=pn+
zPQQ(^6TZUP97CP`_DC4ojP6pwJ*ROy*Gm1O`Ru67DP{jc^U7F++bLRXBnZgQU|^2Q
z=yNBs0%#^dNg8FOQe7GTL|qWTHvJS@-!lY2u3Lh<5-kM`h<R<}qs>`htlWvN3Bf|(
zxCVYtU^mIScaarcR+&9XV=W!>-Jrp1pZOk_D%Ug@YLpDd0m$Hi9>?;2qi5GdXWX4S
zUr4ldE!us9cj#kAq^zad+|5%H2wwmsQ@sB$pZOD#JpVx<p+tOc6A%Ix=<%p}MV4t+
zPxq$GO9m3YTh9S%ZH^-h!0Yvi;4@J(j7M>;29xr$$GC@O29XC^mH}>%p5Wp3FI*s(
z${emG<l`ioT_G(pBy(<>amF$6r3KhHtU5Z0Ry<Vz{0T}<tb_+@uwOxizbqKzbTCv^
zA?!RM!TW9-s!OND`@4A}7)fv_VPhB?9v^e#8s2D%3hrWMxFQTf5-3^XjUuAf|G^*?
zI-!McSzr1?c1fbtUul~jhyAbtW7ywhAFVEKIk>3U|12G2s?6vn=us)+;5nJ(uiHb-
z)E$@me@-U6n;&z<@35uDbmuZbioiQt{ZDZ1#s(AZ{{C`6i>(-=ph2#WJ!8C@3crb6
za=KhxTJYRD`v}-~5+J1x2vwe0N;kI?&aazku~=myJ6SVU?jqhKtQvQb*6Efx;c?aJ
z!T?uDl4yEMfs0M|Trz#8-bwIS#e`z4>gj6Nt5|c;RfuCCpb;Sy#2uPeinKttk*hB{
z3K`Hjj#p%k+&7zJWrXRw)BK5X#u)_gveELdv&YzOl+rs^_XaP!u{`#0(HiBrjEZSu
z5ahW6PMz5~&f6Iowx15?4Vt%hz^Q>zYUrA-2<Yo~UA0STMn(4)$wck;QIF`^g9)E`
zhp(>&Ts?-jK0Zdkj4ucPwI2d(5#}K0+vPBNGHld`>?zFVj?3+tBTn(;k!a~^C)ir{
z4cv#NBn)pbw&K)zS=NBQtofJ!)^*D9wLTtU5I^@Jy3?-UF9{$Ea3?)2!61Yx9-l(z
zX`g8r&S(R}18gSG-cJFLIq)T&@L!CGurhkpW08F-O*+tCx^Hl>IC1n&gww2^LJcZ<
zx>}~RH8aT_X*rPyOC5Ue-fvA;rnPa{K-6TXYAJ%9_>w|f_~cVsuR0BTF!;8l4rmCj
z(4tGtdZ*MpHaRcM-^VLhQ8>2j12l^d&JL#H!0-PaA|q|K@mHJHb=n2<OB-=e5ob}K
zaqJSO0)c}f&P5js)`w86=yher-4!<=&e;sqL((J%(boDye+4_*c30`PVP}KGre6T5
zXf#1i)sYwkSs;N1#~Ab+1skl1)2Hrkb|ZM#LXjbUNgV^>2#eVUx49UwD<1k=Uf6ws
zh+ZdNPy|6_76slWXm9|U!cI3#2OuJ;N(9QrVF&=t31n8~<Prb+PwXh*NaG2LZamzU
zM`ZU7Xff)_BrbRW00Gj!Nnqwm-QvRs<hdjY{z5ycNStoXzc$@ziO8;=usY{%Cj7?>
zM!dhQ1NnaQSP{w2tv7yNDqpf%ztDrO`oWKec^?a4t_dVH4+5yrVSXGm^u;RgbN8tg
zq!SKHB>MBr+pVEU*_=|ttWT5t?^^7#>Oy2p1*a?v;q;ET-xa;cRPw)6JMdy!fbJ@>
zEx1>^ZonXc?o~P)%-JZ4LA*cRLlGpa?r0`}K_%9-_2s{UAqm}+H9tt~y^@gKaW3dI
zyz2?+k&eEKHS6KW+9N0hUfKjIR3tgujsFX@W7~R)^uk;m8(0pcKCYg$Rv81&=c)cL
z@~}?Uat)0<@$<iimf<CG@Q-@=F$kJ*6)4N=H$KL|bhoZ2+e!~Pb%aa)vC*hisiDb|
zfn<_P=D3tpCH36JI26bb0nvOH-(%chl3uXv{eGs8MI<VY!6m^RP#xnfnHw*=Z_$js
zUa*T;hii}MMj4;&isJR=hR$^pbVFLAC!f-(55{F5y7BZ!3?v}*vUiuQpKTdJy+U;T
z<W*D{%35_yj3p!*RA-zcpVBY?exOvr6d<x*Ibl!5k_D)CH$WCpA(h1)`Ld{$-5^gI
z(vtG~+;@*bl5K4eBC4c)4)&}jpPaC=c5uN~B~v>3-a4i;D0vqg`(YG6jYMd(b7#k}
zUi+~+?gDGV1+@rEF_9h)m49)yxqA*|WuSw)tUK9wq|2zNX!`cViv2Kr>K&Z*343FI
zP%2Y|-BmpO3>E({&0v>X-8aaCo3~ZgEPE_G<!*(s=v$;Sx^VR3GSB+m6LapiCJF~0
z{^GEhgYOhaha-0$MuxV^3+u#dOgDc3AlGFF$KA8f7W+H*u9aVD&F}<;2vW*1g~<^N
z2s#3HYBrEu$9x*BwC~T1C!6!CQ>+o@I>A7hj^_=q!|(4Ozgj<jeM<YbYC(MDAER|d
zNTEe|rzwd|f1pz^a2R_Cl&Eg8Io!25vR1|5c|e#bH<;w4TSZiN!k{xp09dQ%0d)ls
zRhu;uXHh3^A$-kk@AVSDe8Y#Jw08Cq^*0zv#lW0#cw!zKN-O%P++zpK)a+~5LR8)3
zyNNr_>QR>hAH@rp@0K`wgG!)K7-GmkkC?NoHh7&@3MABvvN(RMtw2hsxSX`=yc4#h
zZ43s>GQ#E8LMLiNDb>wcq9D>y6=1_!1_6>nN;2^bqJ2S^{dBYpY&~k;N~;|Q<i`Xh
zo^?X`E*ds|cqc(I)9lLas6El}V%wXhY#47K4;$s;kw$LXbCyx*ey{j!1LqEdj;T_M
z(**l3?<Y^4S<kO`jE6u5QMngbFtGv(u#&dK9uP8f1y^1w{!%y+gAi^+Ra%sy)In;W
z0IVJy=ON%4<27AhcvrxBLh(U;U<fG%ZOC7dep12s`Yb`-(Njy4CKFcSkXY@S4ShFt
z)vZ$|h1PNFc1ST@nBX7G<`~IWw&p{=UrxZkXFu4I3L&5q<`NjSbu6~SUgVo*tC}J~
zxpUj73;9W?L;1qR0eJx22^!&2e-{ydm}EP&8WL`)f3s)lf&}XI_*_VLDaa7|2AN90
zRx4H7NzH*OP`yhJl#r^fF-^u|4)V6qT+<D<PM#b1uqMP9lZW2NAohh4q-w-(52z{N
z)$@|67uuyV{5t=W64xW8DQ;g7T9Q6B6Q>pq`XUaECC=A2Wf$8EU+p2?ofaG^CkxK8
z!%;>s120vkDvzY-v-Ur7jCkg~wKe(r<0wompLP!B_Ub+vNc?lz7m(&->qR0_6cH7}
ztnu|$=;zCGFztB!9tOF9r22r37vmGnzZ}zRaXE95`vI?YP6ZvHGgq_A#v!`YI7bwu
z^%BG^OsN{>)qBHxy5aj^iZ*!kc5QIqG*J9E7-*Kwzk>Mpti-h#Yr3nFgto23P&?|i
zbpL)#d8B=id|AbMW@x73I^g)mHAw)iamp_Kx8sOiBUlm<wG=<KjRgoI8q~86d0Q!z
zfkV%c$oK11=+Idl-4<DpMChr(`cj>2N$`ZvHn%mn9&)+z6!tL^>MYLknAlCZAk@m<
zSn1$hvOF(yw;2MOiEGCOC+2d1$*QV+4N0WegVPAl;*ah(&iuG2xKPpI`p_57pq=t#
zn_&Xr&VhAL(M*)2+eSk@M2yRifRtRZ^>Gf-D730en;o+~A(`Beqz}N#Q1=lG!vJQ*
zZVL=@u%_7HKa9Cg0{hUNZn|?};c(*CA|}Q2k@T3>im#F~kT@8@ZyRsTLOzWV@*|2i
zcGlg~oE0BUzdS50SMZ#1NihCu;HImyv>27OBsCK!U+h~h3)~GvK;MAR8*0H;Fn?EV
zztF#NT({XD?}f5=)N~m<TYg9VfcXzotV+oi=#PXnQ}7XMoU5Hwy)mVtnABM{Wd%Y_
z@d^zRS95C#?pUd)5I0;nbvq!YFT{ueMU;5vhMAP|9DM9BD~K|AGAPyo*KnO^n!Wae
zSJ#G<Y}omFi=hSpGIN73G;1wQnLQeng%;b5b`7?QV)r{ToBiu%YA_((Nmm_@tD1J;
zdB~%b$ojW6W}Zx(KoUD`=!9@JzBH8)E>zlemlmUJa*e{QW3KQ=X<MOGbDhhE+0#jK
zy`NGr`O<}O@;v)$i?owiBWA~8XIFm5iSXR?gi$PevgPSyOe5k(OG^#W9R}}h5e71}
z9_}>5HM{6kMfo2Wyt(2NtICl3!laHfP$TD)*xAa)G$T|_+aG2L6KA>uPgWL0CztXP
zLDEwN3nwG*WK65XWy=PPM;Wpq-<>{{qb+lw5hv*?ZJzf#;f5FC?+v1FUO{hojag!r
z3^}+Y=$U)s)Bpeg7z=w_iV9h%-k2LFQLni+K&~oVTeAlA_8x=y!IC3(CoG(H4VQ+#
zYvBDw%fFipn%AqFLnV8I2aZ<%(XptJykBARi$Ful=8u@nHIqNrik;V@%pA&Gc&dG|
zqF1Mwg#EzIkj|8lL<%lhHnmn7Vs5MqCjk*3bHX2F1K0S~Ks~9%()6{IPDD*|%)e_M
zUv|%qQO~#J?5DwEele=)=i1mjV7gew9Gp2<Gz^;S+Zi82q|{&sUTOmsFGD^|19MQp
zoj6(T2k8(fZ@aQ@`PF~^WSAn|u}ii2rm=M-fFrB_iiQ;S77!uhElAFR&CfFl7>D4T
zjzBw_VJ#46elw=>P<P9yuB^wokZL9@JmX>wAwrucTuM{kjK0*RvE)s|sEwNsb>S<D
zqB0~l*j7Z#`tgOCvXijb+%RxfR=Iz|QASA*tEcUXi2u69L_KsPh(&WYhruL(_MW<6
zioRK4sN7+w>m6#`#fIk7Cn#0=9)89qGr7%lh?>XDrJJS=n(o7e^*Ey6A3=v7*OI4B
z`=^H}bhhP*vWur3=yz&EC%$k964MQQO$RE1&B&Dl7N%*bCdQN21(||B@T9-PVOL6p
zx{^IP-lV#=U|Y+gArk%3750&O-Jx1^UVPSAIUN)_7zuE)z(dw|q@d$1F1x+0H(&J7
z&oX61IjbYnTdm*jTE?~!cG!v}A}c{(lpY@6>j1S}CuIWoRuDtrk_AapS#1jdAR~B{
zBlJ{`&iPgyx+wu$aIf`%hLqRova=u^V%~A3ab*b}le4IO*}RKgFdE>Vp)J4tl=_Zk
z0fc)E`1c`i7}pRiVBqj{Nuw7YcZeh>>{3BVl!8hk?NMLYpFAuPsXHEcIBG05SUSZy
z6*$}HT*lKOcC;BhCEMierNuK%?=oUjoYc$2llc93(ox2lsjbm^Y@;}stx{W8V=R@n
zbI%qjB{#Q7^}4BEL)rFk5zizkYL&%Ef84#~j`BMC<?$~wE1a)(p`U^weMU#<7BWf?
z`IJ`X5`HN1%E}b2N`b|MIDA(eaSPEywZE)O%BaOv<~#S(t0BHL5H%n9Z-Iq7Ye9K#
zkK5lOgt8gcy%xUJ&`c$(IrfbOJQpQH4~18mM0+)kX-2j2^eiVWA$_dlhNbLd#n=E0
zCJDC~x)={pAbMlA9K0=9M)|roL51BDUto|LC{QtJue$*!r7v0_3^ES{%(jeU0<It~
z?WMzcduT8xV7hXxNIvmoe|bw-W}5{BHk^?SC*FiZ_e+be#6tP1@dj1Es_gJ1sc(M7
zyPZccLp}NvpDRe?4^gK^f`3wIk%$sv4>5y?pyq<!_?2)+N&OBGD^ZrEf4UHzasD3H
zNNiabgq_%L&GQjBdyXGaX->wcISJ+<R`}5y`a=is3Y)$aPYE^!-%wr-k*c_&LHO8%
znSML+=Gn?hOuyf@wvGVlCA@#5z#NpMKZ<#{VfqJK<nt&^Txp!(H)v@92_MV=N?{Z+
z2OoTuS66k5`<vz;%mbZO@dR4{1|bbkw0HBVak)diqN%Eubr$YkzX}m-z-qwtDxtAh
z0d@G7-<w;>48EKjH2m|PkvR*i$-PP=9jULH>eN7AOe1Q`pROTR=r^VxgamlJ|AvLo
zh#{DCoM9v5d`t}S`@eVMI^9~=s!BF6m7mXH--neyaBxPObTq89b8_)Wa|G?zS@H-h
z0PtU`Ad`O3)j5Y>a75;?{?7^L)B|P!6w=6-;^5I&;P9OMp)@uUk;56ej;Dk?$VdY9
z_>N97>>OS=WVOl+s&^29^$pM*-1f)@L4wA#tQ6^>gdD(_b-_2y2#`PxNU&zuXmGp4
zkA&gB@XHW$t09R^g1y(PeKIR|Gh^$EV!9b9ub{&=@wI+JE6py~KllQ#fk*haPL21d
z%+##XVVo<ftG!Kyuhl5c-Tc_(Ck)F;7mubw(=JZl(R&lT&k=VtLgtr*Ky*?(85nEV
z`B<GiG(?s`JY!^X=V+sd>w0rUnClL0_t2*A<Bi55NklX|($ri;WPWdss`=hCFluRd
zYqAEYe~-qP9!xTjN8LJ;L*7MMJ7XcFFuy<s63&(Y#skfn+*$BY0XIYo)-myc*Tp-(
zu+-9f2Q>)lnNN|)6NkgV52x{^rt@*!>kOmV&E$aNI21qoLRNL#;_dp=hITq1$@=Rm
z9Sc$`-B<X|5ueI6w1yk1lhY=ksepv-Qz#i(e+u7m2E-TZq}Tghs*=dgk3@#+Fuzfh
zq#=@DbgIgUg)rgI)QGz;s69w3I*f4MUyE(|?gwF>`HCQpU6SlY70D~|9P=ce8{=1T
ztM?4t8&qDoYT$cw>TExO`G7^cxb$h~%|fe!-An*DnE10XZu1fEx0r7P8m1N;_~Dl(
zq$eqMYP``Tz57?Ea1hu6;RyT#oMVjx6HS-x`}{s>@@Wc>V`w!8B@TK5p15BNfyb3*
z3abM@0prTZ$cd1aTGh?%)TW;}`WvfeFCBNAfxka->kk`h|5#M(sK)}af@(Pxp5mkA
zKe-1*oxdKRfvq~?<mh3d71_|Z$pB<U*fH<v``X6~{ZmXGC+&zbW|#srGypZL#co3n
z>WP<wt7%Zls+@Gw$)fY>q4A6->nCotQbTr2BDt+$$JO;~hk)0L>#tR1JaKE+P7f&@
z>D(jO!H<_$JS?~_OR?%c4(3vLKf9dG$gw*)^wp$cv3kIy_A(Tg&f_i4K&k;x$4kg3
zm1|6p6)@khrCYyRGnUNI((xn>-WMq7;s!~n+t@@H4zmF!^-QhE1GvH#mP8l2BUY6m
zQ>NAc001#5S^v4JrVh@nEh{WhEDwlofW<xjWv5?GZ@9*-i+E_vC5$i{Z8*c99%bJ#
zsL&Hb$5y=&EdLSa#5-@M)WWA&NmMG2bMqMld}<h00$ZFoe`OQDUm$%Uai%vJq#3m9
zWm@2(Bf8(U+eVEezZ$r$qLw=51Le!+w2z=L#bL$Mm@c7;k%}981-6BVsf(a+hyl2w
z^eoa}1yUC#Eg*z+n?<ZN5Z5q2-fB})07dHtG{S{&@tPWTnn>2OB0j5|op@=b1Xk0Q
zs`&b+707;-F5;7+JbxfuU-FI(1~ip(>`90YW<gR3oM1J3M~ly$8xl>vc&ymH@UhXp
z>SLo?*>=V*>Pk@uXM|MH<t9262@+;x)_|}p-YSCFjwd4|kDB`g)nO?icHoLiE-xb#
z8gXZ_mF|E7<Z&XwU^nM^$r!&5Mo+79aIO^T))bZ4J|Wvf$y+<}mjZ`*Qx}PWMsq~T
z7pqu&I0Iwe46vyOD(fN_PQ*Hjbw-W`BdUKdfaeC>BUKXmriq(|lEwhswq>*xjXOSd
z^i99&H}%|7pg{T-M?-Kx^-N(!gKp~$#Vr%juR`hfc(DxhSRDsvGjPdm$vm2qS-N@T
z0vm+<pQi`o`9w3zmdOG{9`dqU1aM1<YDnxE*D2<H$2OB|pzs<7=fpXem4YOyW{XyG
zQ)8rN?(Va>b^J{ZJtyT9GT_*$07SBt{X<S3vF@L~QVD*V0h^^8EDhT*+Q#BI9lAVn
zD)9B@lp_Pbcp1Y3?tT}kHe7&bM1K$MWU#S1mr#jh!Ko~;L3>h?=MBZkY)D62ct`RB
zMWH~yx`o&;)+o0+*pPPqLVY3v04PlYr3^VXQZRzUZ}iO$IkB^y9C{qhzM*_Nq0$24
z*Ww9L%Nk{jHFa<GHF#hpzWs;4Hwb|nt=lSwdy-y?-p<aCaq%I{oj%3A26Jn%^MDNK
z@+M}D2zD>m5-mwEAQH=m|0srv_3|@gl3!AMXe8UtNMn(YsI_CZv0hRI34;XTd2Cl4
zN#YV4{P4{Y(iY5T&+hY<jRUCvCji%$LKtMyixUJmGr(k56;et^w1XgCRA&B(zQ^s{
zljZhaRkogG-`g0esR`GKYzAOb$0U7YRO17G&tq-ntCF$BHVUmHb)9DPn;yY(+mDrW
zHYg|r4;J2LhVcL6{|R}uY^ptr#Z0<|9?ez%tc>Ye<2_H97hWRQH{cR%{KLx$TP3<U
zhvE|OA<rCi%a21k5*M_uJh-3j#_gnX*qd%pNfLK;&FK$NF9CUc=F^LMs<mnuAUbwc
zVR%GFgwiq;bpkRIica=ErakcyUQ|0+X1lGsqRdrX?szGV6FQh=keN$n6_W2H$F-+=
zCE<oY@98`J+{Fy({aa{EC|Wiy_(RYyivoS;pC_IA?A0_4))_Kb8L<ExgonP>XHM;i
z1k_^a9AH!-PK%n&=(uUI-kNQ(KrdumKU!bKh5wdif}zJ9&(r79i@F(x?D;~LhEa-z
zC5a&Cl<*|aC7}0V5Q0$IIoj?IF8*#bC;Q+x8wunkYAZC<Q%RTJHVPgD9Ht1uFd~8&
zT3htWlkUZoxf4{_(HeA0K>uMtfH$)@soVy)SfNUHTjqKy0Hli^rLjy;PF~v0?^l_+
ztl6%WorRZ&mOT4{)(`G4a}?jDDmh}B?ZV?xM%EY4-rW}3sZ7jbGt`EQL47vRme7Q(
zCdMVc&abpMChag~zj0}vPRyF^J(rXLb=z2a8p|uLpb?5CnsI8QO_na*p5T=B1NnnU
z?+HZOI6?{W$zjoV+@qR?Kx0e#7=+#JS}JilOhd?KUnR|d40J`Sk`EF?_xS60KFsPM
z^4X+@OEBc+-Z%v;4}5_sbM4+qNiFQnXwKl3CMoJ^(6i^h!f~aNwSA85WLm;$^R935
zoA`5MD@@Ms+M0Z};Eq^r8xWh^7&mYM`Pgf5<zTT+J$ngT`%XE;W-TpCf4T`GGn~Su
zC$SfwWIj(~%qLD6VC#3SKO!n$1gF|QukfjlDWh8?2SzlxSuHHyj8!%^&#}7QraQL7
zAt<P^Xe6}|o8^HMPa4(L7E*CmBuVN4#f9G$XoHuJR;~l6tVBj<(j;BxSM%9E=depU
zD%SMNvGy9P>RstXu^N+#!tN$18sa{uWJl$m%B!d}drECj<3N|()+adBitzZhjW*Df
zviGA-eV3sb<`}(Oyo9mQ$B!W*m2BX)V84$R5l9Obw&^5>krUbqIJWk6m}9M*(8Oli
zddTuCBQ$247R42#>D=Ka+jY`-(cD`$?iEa}cLKQ_4S|)%46?4X%M0$6HQmHR?|@Cr
zkuebG9xQ1Ds*Zhjbw#~i?j}wUp%=f<tQ>}Xqz-P<>_;5cJD`=13SAP3f%B2+GxFOS
zPVVX7NJmfd(4hTzGanG3U0)@7N9P&%xt_>d!_D+SHM_XtZ!e1{y0{?d_!qyREn5Lm
zVU8p^jE)pWk+AgqJ7zpOgNlRgi&}-a!6ri3y~88I1^>PAK5F7C#n;sqG7@kdoI4!b
z@?MAUvpqwRq$JZBd6J8f`E5=q)0zkwOx|_AN`^Bh%$K_xk{c!ZJ^8(CN!j!{Rj=Ja
z((INJ)gX}ZONpgaU297B9~o;^aJ2dzPe&_IZ*H+$m{3>G7;vX80lEgDT2bxjJzU;B
z%w$Z-yKiDixZ_=TUs!Y@WWe?YRP=XV+yhC<8N(cZS;(xSLpVJh8>F~D;?~pkseDdk
zZayBXz~JARLNsnxT2~jQ%j&vUaKY25KA;7p+5iA1v+tse9dhp@PrH5a+1=uyK**E^
ziZ?lgjA#7kd}s&<9pPx!HiKUcw+BaNo-cQoVQ54LPwj<^rr>M8vr|WY?SJoDM&vTd
zG94f{KxXlTZjqU5D7%cix_*YUiUMF50{egf00yo$F@I-?ySL#%0Mf53FqoX<N2$&$
z?<$3|-Z-~-;f55OQ5&fhD;!gm$kqK?8TG9-;&hdZ=*>0)FD19eyvMRTi3FNjhU|7h
z^USNoh3L5N`dVl<1Q`I~wGj!T6McTkPvC)R<nz}zN}Ev&xS+~Ud9Y#*kkS4mQYCn*
zy8zU-)D_Gi25%=uB9;-`Ii3NrEvZY2cVRL>P3DVqPZ2Km@6Xd<uePKA=m6$8=>MUW
zDIt;U%~F|=9!>MZx6O*W7_{6Eiy4N#i{-Ubq`Vq<Ii=7HW`*Zcp$syZxXyHd)CJ_q
z86I&4xEHoqTwpX(u`2Jz>k44BszYBD^k51zv1{}+tx(h5Qni}TE9+CTzVbnOB&KNt
z#+9r0#&w8a6`2?bE?>(#2vqQ=$_>$rw^yDLf|KT^m~G_rI#xC1{5Jn)qq9@+sCHjX
z{Dan>@Yb*&)#v+ghG|M!;5>rlG12&D?9Vxfc#S8Vbtu?@Q3-niZ>3<Og%e_BIuTuF
zLuVX=!x<4JWJAATI|!ChM<St3qg8aY1#M6B4B!UsDb#$-UM2;&o?bp;TbkTxS7-gT
zhIrZt@nDaC9?`@pH-%Y`fR|5|+H!B>1%Yd}7{t+WjvAcb`|~tu;|>N<?7R$pSTrRZ
zs-1cdqY6r@g@gx4L^X%EW9Tv^wJwo8W@RNkO>QEewwy{%ZXGxN3|2!LZn#Mhj5;dO
zk3L+*B|s=8@|zs2x;YlZ1FlhMJsnCRQ;93!)&S}&@}X<(&uavjYR3YPBa@UTVGL?-
z6nOwho^bd-*jk)Eo?(Bm;2?b?nA*y~>*)cKMbqMfHWGOm6*6X{>YCwBo!Kg8jUz=2
zEX5DCyx4Y+uoKeMOxUI*!$Z#3HkcTmcy&RZR*n>qWDw0>A)e7SZ%?C$x!WMyOrr?L
zuuR^-wy>YNyVcN7-P&`?Od+5I9v;8gyTiU+leb@s*L#j4*z~U4m|sIkV|BkvS4-O2
z36hZ?S)>^}FjW<>p6lkFr1YpXH`0<KSFsm2Z@Da7C{UNgQX)y=rA<M}<KbhRg6$_t
zNI;jJzZl|;`By^Q8=3cT9e*2|IHE;Ua|3V^<3P%3Aw%<eGopIW?i3T3{Qn@fKu6@$
zB5N?Wk3={bZ7-;p@hy@H)V~YYZ~zidpChjZU{j?h)>Qj;qJ&sB+h6Nh$&mHlpZ5zq
z<F0J20thzxUTdCLp5}9VM-(UHk7|Uz0>Fw1*$g_p(rY?Rv7(i)*u?2WXKb$Ht~n`!
z(}v32?O5fxlZ^#(RkcpPRTbKDC3}@w1qIG;{(-lxOn?FEOtu)@MB+AhVk2b)t5e4X
zU|=|_yX>^t3|_*J3l<lJ?+#V(<Uq{rIus<uDOUp?%@zY?<LL${s-JmTqOw-0SbZFz
zi|x0`&Hg!<ifV;%lKzeJP*x-0^B(Vg13*eBH?3;qpRzHM<Vt59!bfQ(78?3$EbPf_
zkr#yyaF=E-v<EEJk(P@Sc^AP1IUMDp&|o&mhwm%LXPxu=J|CKIvfpZ34{b4j4Qvr%
zeAoThGv)qK)7E=x3plMS;s(B&Qv$djM<97Q^mHf6*q0o7eJHZ;=y{L^+wEhDY~1BD
zaL$0#JH5iQt25`wEvpKuVsu7RRNZ1Ffd2vRQL`s**Y-f8dJZiEZGFgd)HIjkIOFv%
z;O&=oH=kan&PSV{a<=-V&?k_3M9yyCPI*Epv3~GEt79wC%^iO{4t1oSx9MSfDZ6b3
zwOvC!Q?pMR0GIPZ<PkU!`>Bln=;~EBHo3jew~m1lyfZ1yS9yc}P@szeUIgma`It<3
zJT@Ni0<vtyWI6(uHbzl;k)frLufxZ<oK`}v1S}Q@MZxPwt^yl`-<eo`iZBF%v&{&S
zfmEl;5cLYN)@m+;F(`XYm4$2M7wi|itI$6Pf_9q|8Ihvc&k6dXrS|3=ys_SIq}``8
zx^s%^FEA5x1c`s3uK#|ag(#p<nRwIvNE9hYARHhU6<I}%hl;JPe+k&QswR1}mVNIb
z5san$$&|9&FX`qBR?8B?&UHkrY8Em)q&Nd{#=p+MFl<gXIsIGj>k#|>?XsWpAQP5k
zkY^u0{W0C-J5$P-HIZZi_X|j>k4#)1(2^}X$wKZIe)z&%fm;|+PC>;Wd-eKgJOiBH
zM$k*~zd;~=f8z+Q?V=(?SK-tt>x9(XZ^hwp1qK63<~WxtbC&Bz5O#tv?}kLw{<YZu
zr>vmY_w$@-`w<jZBjiB_pdoo(K;<PI!>Sc8=$~U{6Nsf!OD0u#TG5aQY5;BMp-j0+
z<gY;km5Pm<Q_|`m2hj6+m<$kh=Wz|=&H7>bBxdRpI{INGDqFTw5Ur9YqXYF{>shwt
zqV;fD^Cd+mt@-yoXyR8cF)Qv}iu$J%B<QP{QYKsYAhrx)rihSF7n1#htuKNh0d+?e
zu#Pt9sWVApY6oos_HcgP$v<rpI{a7YiE-_7Ij5~dhC#vtS8a&sd%BPSlSWNf#VCm1
z`rwD%b>K({6g`1qq>k|2N>yvv8}pXDM^roVfnzvGg?@7wqEDcwlg*f7VM0}o{P14(
z)!AhK3Fbz@+jn&2qD~Y>Y|KO@#B_@XH2@6(3hkAGwwCSHrD;|)IDSE-o6)H4vTMpK
z#KVRx{$)2T^G!xJh`k%#O}zWq4%;B1?lw2sC-0UJ*u%5)?p-Pru#e}J@+kIm{qp;8
zXcbTBYNef3g24JR@-1v8PHTZo0KfnwPt5NnG3%^A>?5s-uSjnf^x0I?fB*C8*}Pr0
z;-xs~!hF-rQy}sLIk6ds(+<PiB66V`unReg4)<PWeknqoza=!p&gCu;wY=l~f4O;>
z8t1cYu1I!%X$R1i3?g!kT)X}OR)OC?>gW_QrK=}BfngDty#N3b?VgT4M?qWQ4ps2k
zMh{0(=!~5(<Fv6Pf~eTvgTB;Vba^KImf9+PPEa7sF^www3p!7}ga_d9!<RRU_VvP6
zW63I<xpLhl3ZSoXLeZBWX6sQn*XF&stwO=)ihBytm}>_5#9egf9GdS9Gb4L+04h`n
zKfG>DNt6|Adr0k9)^^3H(b)Q=Gx4Tnh&thqIoBi!LR3Xtp1k@b?_1;|mD15Sw)$jZ
zZV9b>V&VKt{zf@pN7Zub^NAzjdytH+tC>xUFr@BCi}^5iu?vHEu}ns4T@oX)xo0B8
z$}dkZxw+}TI0x`vEvNwp+sgUk^=X7Cih{^0DjgOZbx>;BjT6maUdQy%u%xz2pxuoq
zCt#$(5shYs#vqy--mdpVJJgH$W^N)u|87Bh(X3{l^d`w~_7EG-*sWnPxJdWm>AIuC
z&gBtzm`LwKh1TuRvsWt2pVfSD6On@t(5|L14t{LhGi*!9RQ*>mbX0(jlsZpq5oJlO
zh#EPo70VFn8;sIC0p->$SA#bTCmDOkQ4npfK|*Y#S71sgyW4v$S(@Vg+aD?|isfwI
z^>s43FedOe$Has9>Qe%gv!py@-Jh)HkWPt{<T|N&>WQeUF8dZND6d5zq9=BdkIp77
zEyt}KlciqI8Fbkh<x2i#0vM!)I+Y$^^$^BpfV{J)8dHA%+ij4n$&2bCI0<n2EMaoS
zgmwjHl)hkj>?K3y+Z+<Ed%FtEQH;(IOgb4YKp#9uUXaF3HOyx64qYs4o^p5D@%y@r
z%hdXYQ_?q*U0qPa4DSww1}vYi1SzsqxTPDMvUc|6Q-b9-+n-+9dIvGu3;tw%s?WfU
zA$;aqlii}+Bc`altmZ_o(ra^sWw>y=IB%%rf%8lP_Ycw7JStW&+{&^%C5A0OELXWz
zb>-Vz``W;=>XKuDAeL>04K&;2952!o{<HN-<vdzz`e%Qscd^w7_o5TyS4{rgcf?uf
z*4V(AGLh+Xd+H-Ritx7DqMN1|6L@7Bdg}!azciywhe67+LK?LAjb~asL&l;Kfgf03
zhfnb#h|tj&Np0;Mc>CrcTyfb^FH}oZn1zC|K{X^c;*%=-!!nA`{mXn^R@XZKFpKDl
z$zMxiM*H1#!^P68B_1vuHtfNY(lPh7gc>jO!k6*i?b<_TmMmy!N|?#m`xFW~F#oHb
z^+7}(sq=PvL>?P!k<czq`&-bNA-R6i-Y%4~DLeu_hbyO>d%T+4%dVc0B}P&$G2*Yo
zv<-b#%#u4X;C+U$jx3@SZ+S$J3=HLS)vt-rBIqois;QY+9`&Mn2Tm$s?iUy&InHN_
z$bf<8<X3}7U+-LF&nkXI&d&r-Wg2dsaiL|b0291ZQbO-5V;@CQrgZRwW#UaBRMu}d
z6C`CAU6z7hkGjHSOWIVPDDNC}U?{nFEea1?v2+Qfuul-j6%R6>-cz5k&J?M&;301w
zMRXhTl95^?i-SdKw{K_wgy1yG{3TOTMz)D5NUrYl0;>mZC-bdpfoTw?F;MlC4%p;U
zJSM{X<G1|+#w)H{6CE4#VftcOuD&@|qJQ^y0Ud%~xr)FCk_Fqy;DVZA=K7o5BR^w9
z?zE#ZS+RX=2E`^(Wi&8;e@%0k&@pW}oP+<a%r89^zF9%cqDNtu(p>`w^qkXAEh~*#
z!}QqXZ%W}=X%p?tzkN9Xi-7r$n?|Wxd;JZcE6NO)Us0+pIWu-Y%Jtvq&X;=cpEne5
zEM*!N-^by-X){mJz*K;b?Yi*X|7*=xsy6xLKGk`&({X#)yHm5WhLzQzXVg&Ue}pJA
zNCbO|p6d*~93>H*HA}+dyvD@BU;Hpi%FdG_uz8!WgIu)6URhmx>m24XTT<4K$G%(M
zIdRCfZOOJ#_IXOHzur1f2<6nZ)4pTb!2}7uUQW(D&+zN5;#1A&$0xvu+Ff}7>x%S+
zOuG$SShf<Hsh*p{a2(Kfy_0djf3}!?5%I?6=RvYzy;rK`-Ihjza@ndV6iA)QH<TeG
zg~E~n<@O8(mn9PsQ7;%Q#8EHcl2H?7epr-SOm+TmV{B+LtsE7?%BMpt9gC9sbHfVW
z%(x!r{eZ~}@ydU$!<-T`7xuMaA2U$B;nT~e23A{taGhWk)=yIogG4@Bs@uE~=(LiE
zO+}N{tXY{ysAr^XlK<Ie$0#}xvWq$4V0@spe7EuGqiP6RQ$r&rD-a*E=YD}x5U&0+
zc?xcLe^SIxlFX91uE%)1Wqr0t!XH>(v$kED{wuq92!jTq*8z?zI!!)24DAW8>BrZ{
z59xhOj5mFnmsh<qNrR;g>N*v*yA*rAyHNYJMa^CSJwU?0V@74gB_00Hcia>;6Hti8
z7VM;>qpbTQ!k)>vg69r47lBXN=5i{T%5-I215Z+J%yi^A2no0njOAXD(vbzhI}$nC
zBaos{{_jV1#@B<R__^@8;(V0D-L4NtCJY{yJmT(_@~ieacq~Ln7f9>zONZV3{8`nS
zE&)W$3IA(|6hXcOVBjZJ=2F|OZeT^hY9btU1xjMr+Jo~jss?@uo6Q4Yt+wsp8DW&T
z6!;D77H(&=07g_?-;m$b_;PXXbC4$lT((ADacB}o>qA87rhA|bXp#`$a=(%0MI7zJ
zF^)*o#0}ht|9?=gXRvIN!#H2)C9rKJs^F6|hMjolgN0KSkb(b8Wh4N8EH-o@3U}jh
z=vk#iLTC}+-s400+WIPuB+Hs3UEULC&>F2<lfb|BcfX}n?<|R&oFDnCZR|4VU`dWN
zqQ+5|n#P={wPNZ4Oa3d)T6vMCN*%@!jX0Rr^IJU@gMwo>qKw#8-RtOHqd=Aj_b5!t
zby&kc79Wqfv$Cx>djH(RHHfbBhr{du>pztEV1NJ@bE%&V)f9Qju6>Zq9sk5S8J%ju
zH-f~V*jXX9bgM!65L}IQ=+-^^;E3La1VQuqO`?Eq73!LWAi9#l)zG02K6z7n<Q$`_
z?aEWJ*Z^`MhRZn{IkP<$_lrjttuViso{i@QZbxJ$V)Y5wl4$Q}^hrsu*9$N02D7^0
zfGl$W000)dfZS~LknSNTp^+ho$a@hFKXO6X4MIbN(yBQ*g{TKUkUfNQiF(=k9Z3RE
zwwIqNfn>Bxp(oweOkm2EDq{+1)w~ZoYgC4i<SK2P*x1btPJ4{>MR7QHd#+GD8>l!c
z$@Y`C#AWi_AvEmIG<hF%wb@@8R(m$|H9ib9X*Wd-GcsDos4-#Q_|=_<cgF{O-*-Hx
z`GWmib3&AWD|lr8MD&4HA}zqRtiDu&D!PoVCeZ|<e;+1;o<zqc?Tl;Gbsv(skRwR=
zkI3I)!bOq;ehX#Z{4%Y>abHSz+vHIkj*|s0G~4v%7GBU|M7G!JC>V(c&Kuh;ycC|;
zbF2;7egJ7j#4aQqIkYTGpo@&BK4za$=mjAtV}v4vWb8c6DqXmf@sHBvBIlx{*?%{E
z45~5i@k;j^dz$h1>CF$`IwRG0BFP83HGv*uTb|Ak)dX?^K~^45WzJ@Tp)VKO?##E{
z=cPLxq%%GIt?_{Vkk+q*O}|eK$8!r$+>8W0%lL=ffC&OBFWPPvrD5%%W|cP!wEdwj
zL!Di|(YvtAd!nq{r|<|*AvJ&Uii8l}aOn;4$u62r<f9W+ye+?m$AvKJT>|yTx$nnl
zysAIz101diG9iE>b?0Zv6<RDsY8Bd2N{4(zjfw=BQ^t}uuS+hDqNDtm>mbKY0#HS!
zpcq?t4BMaGDJS2>c3y;_>9(xUbbGi)%BO~@8@7-E;Vm)vUx6IqA8aBuP2R>~9ZI7H
zLw}C}uZzUaMiIAMS!6=Anuz|jb7N-@6EAB#^pkXigJa=?X>V9Z>82eGuwJNd_sXvB
z>KA=|GTmQ%flb!M+tPYb;Pg^#$L48P0MPX+*GnR0a|Uo(tunI?qetJHLhSeEAY%fn
z9g6DPP$h?zs}Zg&E$~&v8Q(#>$R21nWA<yN%!P#v?NliGyBX6+xfx=`LU+$FtE===
z-!T0c7mT;;`%d`4ZG|61x?ID|eYi<Tub)?;UZBS?hTOli^)7K}jIyr1+1@{xM>^%e
z9k1?Wcc&_RRfnDQQ55WwUAM+QWP6gan1n89Jd%2d(jd%TfONyCRUB~&&*7&F+-JU>
zl7Ee6@0~RID(Q(++3&NCq(2&@&?-BLUrvIOxyNn4+;hjgm7x#p5dt=(F(BV};Aonv
zNB4_+`TbLXSLuZKxt#c@nX?{IJ%dgnHD!oH5m`y84)p;~tWQyRHYeKqXoJs6w?Pb0
z*JE<F0PI0Ai%^w{rj~?fz|&3qO}|*oOnI*{b~hkQ#F$p`k8)^siiJPA$;&?s`0@u`
zt6^K9K|u!`fan3=z-IK*A0DWh6d+%xIVILy2f~N%NdWIs_Q0q!Y}nn$E$O*1Q#g~Q
zvtf|EAj%Y*TK+%P!B)PagW)%?H;q{LcN8-r(eGa+xCHzplNNgG3!N?w!vg$cZ6X-}
z0Usvdow%_kAss+akO6iHUHyP0J)v*$1ZsTjA^avPLnWk-s9pLzaaQ`qGli@JeKHtP
z(YWfl)TJkAB`<S+Zsgu!1(o%fY5_g<QUPs>m$9d7*+nWaYXopb>lkM!gd#g=H%Q=q
zl+_+|re*%E@L$Kmi*Cg#=pr5og2BGXpz$lK7btThTg^WPRK%Ehe*8fcRo2^=0qMEp
zcDS(CQ%gYpESmfu$h(H3^{uVZ_ie{_Or<%fjLjw2t*>W3;k_>R`(9RtvzOu^y(lau
zND-V*y%cv_e2dQ^Mko?B-44RGF17G#vEkl#hqO0H#Z2?nwU@oLMoXL%?0m=(RdE`9
z6{P0lVM}QZLZ)}ow5eeAMoKVTWIor@>m<Dbe1#Hcy)=Mk^^C-3Vh)kLFfLD^8@+-7
zyKGtDZj{2djXQoIJuizQ$R<;AXtmO2Hhnk<3GQ%K3DGqpoWv98?^Z3ejYF|q8Yo!w
zcF=6n(u1?NhL}*2v=Y!$mLwz53ugPZ2>njPR$tEwCN2<0RoGU8(O+|f*J-{t+qVa}
z<2l<<S40T*hNb={!qfN%oC(E#K5T^sE~*RCBG9}{szN}%;WaD_Y0Vx-COt^^17GuC
z3RH}+C^*Km&XMJd%!L{?%9~&~!U%Y9*rQJjz6H4Aj<fhbBef!*)9j%5Rk7QzN02#~
z$p12V#_g+bGk~OXpI)HMWs26duE783)8>&9A>g$yQ}SS2N1DpBqO!4-GG18%j@<Xe
zq?*2P>nI5Et~XQ*KbnQnl_CX$8M=0XVi<8nvC>;=Qw(AQYYuFcaUUi6v|)x8gJ|lF
zx+qAx5rDpr+=H?r74eib##0>3ElG`Qx4Szmy~ckB0bBo0&}(`)bO@)djGMZk`1wZY
z7D9zlZY0up3|WvAx~4&!eRL><EO}0IZo-U<tRLxD*paDn0SfX|kYUVHN?H)3O`?&b
zWV>qo_qodb9%a}%mG}B44xP26fWUL+dII`Q8a)ilPlJg4&_3TQ3R?A<EKNd17-fYv
zci9QBjx2P&v!@6DE-x+Rf(%lp;mQmcv>Wm)zU3K6l_Z;JGMf7tIpBytYys{M0*&{;
z>%+{|oDzTfWcZy@AM*r3rF%#IaY=w&r(<E+V8*eW7=JWQC=!Sd>-q7h;$#p?iA_jd
zQQ(#T%_~g)fW*J7f+2>dXx>j6LNmzDkb0TltWu9(o(zWxNtRGoyj)l-zv_wwNIFvK
zQd?Bq0@(S3JV5vHeVO@JtM70C#vnoOnwrz1$aMcgSe!gJRQ->$1B47<ip^TI={&bg
z!06St8}Eu3TQKK6kieVRVMOSy$d$F~r);K=Ll&zsql;QXG5pF^1Ii#fXfjwpiL3&a
z#`+{(APTo5s09C3VHW?KhrsQei%9%A<*cmw>N7xYWLL(be*5-2X>`Gt(Qm6XDk{GI
zzC>28-P|)&PAfnpO2n>LDu+*i_$~G0`2*=xSf+S(S3yraEQ=Wq!2khFC3K{Y@jlhW
z2X<g$xi9R$Gb9{tP!xJ#dw|G;Y{VS=%TPh}k(~CPAYQzybj3TG4*@}q8>xXZ)8^g;
zim0pXDy-F?v(8~_8)r$V_yX`KEpt!1TmDF8&x5)1)pJ~>t(cAU?>5FE$;9RZ^AEN^
z>UstexHV!k3^QW`^N(;^J*e{sEm+(dQjnZNmHv1#b&(nKf$Jnr)tGJ%1*yG}BBH7d
zC#y{c@rk?C72J`9EJ>JXTx~(e$g-0f|Lblg=Dsn;1nAWH4H&XZDA7RBnjL3ggdjgB
z9RC8mIy=k2(?RL|rWy(QSJ<VAPRudU*kg0DB#<$Q5u4E${<UwX^@%&yUW_e{S~{Eq
z@AuqjbWkF{sbeQRpnXS(h2h0cHlde{2_aFjV$qe(gwk{}EHaCN@8xbodZL46;3Oy-
zG8x$--qIUHvmqkDp`C+G<DS|>3Z|iF(X~{hve^Ymh}jbhGa_iN{o0ZThYOxCf(|{{
zN%M0nJ>dP8yum_fPaUmYe^2r1Qh|Zr8~X(#Y-(U5`1thAfV{|4y3xWpv5w>dxcz1A
zw^ODXtOG*2#gAGbHHDNXxNN6f_@wwMFIH~E=7h_&I@d4y_|f*r8#EKbS3UP5%%?hL
z2cR;?VCA2jQy7L@XsyLnZ7F{N=$3HO?g`9aZJ422){mrlGZAB_<g&t9=7{0eDrWw|
zJ#IdQC_Kqae*CjL0MfboVmO2u7Fn{e!%j`+*xo#tMh9=1F$a@-0R#v1T0i%vkIG8M
z!S-r`<RvfMbrFv;JQ<XLe9q5u&vY4wR^2NYs@02{xh5_s=h~r`SurWTLxKQlk1s5B
zxDT7Gfq152C#E=+wgCNI&F6nA*;pyXw-x!_d|<EQ5jSBAc~d5V59cLENuAX3n7D(D
zm7@tF?TDKYVH(xO$J$7C?Rju*WGmDX%9J5hSb{Q%Btr5icx_d)rXmf*W-?@1Z+01$
z%8K*%ssFk*t&x9wd+i@8wy!L|sS)hJ{0C+!O(LB2-jCR#WV~=hu=Sqpqu8svx;N%#
zzzqM%yd|{udlKc)NUi=@bN)c~HxToEGMAWGnO1Z#D#YSmQ2?KL!tZ9(^Z3M|;c%ML
zvd?tyH|<}YlO!pp{`^d~123njuN%S|mUT)L(in?PQV_^Qe7cy!u|sE^m-u{%;5&1H
zBwD6?Unmk=AbhS})4n{Q2-()i6YP2Yw0WXAiV2qk0PK!1vJZcxro(_p(>>-+H+ve=
zL4!ZHE58Ch`)$2Jnt*5&f(dw=SB+RZnHe!@kYv*^s6__|d!yP!2;t0gh8-hK>n1FK
z`Ih%4OT0x(tR{p~#l;UB{+GaTX6EQJ^Op>=fHbw?DD$KMs#b?Sk;vSF2pW<Tt+4q|
z3bFRAo53@byK|u~gYR72(acwp)7ip6xlkd*Z6@_4p>6IDv5zR2w_|9w)SFpDctC-f
z1HUbX50ZG+M>O71q=cAAQBrq=$V&JSdSHP%1|R^Cg=GG>fUeXDBu9B=eJ4Yq%Vx2k
zSdvvS+v;V^wqVN@rv1<WVQ5S2KmVkcUw(OCf~(r4wxx^iOcl7hrpr=UHSRfCQHzaC
zmkLTCohip}su?=XYs0t2sWA@XkOSsR1ZFGXn|tqXc=p6Q{E)}c1{kdJCmvGmclBG3
zZJQP|lS{DhD^yiFpz%rg@fpf3gTVm;mkllw1Z34GHlWxGF*}Mg1Y+bEQc($`^;l|J
zOt(9Ecsa_@<Xuzq{b_jv2KX^q1Ol4JL@yc;!6<*>nm5@s&nQ`5jUyDMK=YSrbYDTe
zNCZ;blQtdLaCmAXKT=oNL$vhG)Dh|6foqdFI<bj1SvE+^e<A3Wy3WTV`ZbPC+;5BR
zV{KqcoXUp&Cl$L1rT$D_J$=tEG0<wkUBcC5Pn!-$ej7G8@T4d7sS;j7#Io#KcUBeP
z<iotet*o$l51GWYICV^BliaUolGFqcqqhrjB?9AS2n;{Av$JwWCi?+@`x-};Wt?b0
zrZGO<Lc!1SQD0)eo<N-m9tor8TPt)vyk@((-&G{s%+`&1isL@3n(_8<r5if{znk}e
zdSfsLnRRni&ZY-+2!{RjnW$s6smGg?hc9gc8l4&;<RNs|<V!y%`WD6N+g-AfO;{Zd
z1@v02vI8{2ja}G?A}$Qzm%;i<%O=meM2h!qyTj!l_n@eIQ>`p@9>Oa-6q>Tk2gaBd
z$B1<_LZPVymbTw-QuXqtE;F*S74eS%WCnIie6b@qBw_*iSZ8~!+(K?E<;#rKI#lAp
zZCU~ViEcuf<z7-<EI$1lB`%y=mG9(yH@REY+J9vtAu~a;Cc^|}QsH^IBb;)<f|2b8
zp-btjHm!8(xs^X`YYCW?t^+Fn6^T7E*P(ne)Of3h-lC{BoG{~UvFqY8W5NhA{w^+<
z6dQmJDkL=T6oT4Yyry>-G-Xu+Zy*yG$k`3#zoAz5Y}Ri&lW|CGwv0J-WFCM~EwN0G
zXD<d9;5Zdsf}gRZaO7qp=l!8tJhd8;!RH#oaEp-iXrcrHxyjeFpr9B6g}otQ?d#da
z(38$#mol0)dz+(#Y$(9f{t^Qx2tDJ*KY>Z>6L7ydraTS6CWD+@?@jd?VSazME(O_(
zMqdqd`+~P=FX#bie2m6#SCQCQe)lZ@q@*ya2|ay&wd^=Lbg7tF6&i+ZUvejGQ9kGZ
zQG*c2;%!^>r>WwzbbEX+l1wu~T?ehly`1@zXB;+zCP=_Tv)8+f44iYL14?G`GgVQ9
zjY6P92)Jzf3`zz&3v>aHFJmX?@O!QaSLf>gZ+A?-45=X9QWW1z<=lAYz4j0zKT-RM
zd9z=Fprz4M9|kEA*i4!1cW>4{ow?CORv2|JAgAiP;i(1#gZf7|tGG1K{C0vrc>^!B
z;e9F^jjp-DKHt^=v_-VE>@7)q1B%~mzP4w$m=X=F9<KTy`<9MM&6b4LIHhvD$RWuW
zm)gGEOy#fWe<4#*W@wGbXKs=AMpJ9wF7*s2!OiG}_}_p5g=Mz#IeQ;l><+9yH$paM
zyhR$xABj-tZqF>SbD?2Abs(5cuZA7++DixfD7!6hG6jLk8X}d?sX2lskTf#r4_WeC
zmRM&d;Usuf=AE>#hKV{9p%|N5r#UL;>N>t3N)x~Z3H-1xAX$Es{T^{c5z4>b%pa&x
zjjS?Ab>+nrK1-da%e}B%&W_1hm)mjQNx|L+V=zt*K4Hngva-bCZS@7)94NRh8+w4@
zD~~kYhYo*4=X_C(+gPit{MqkG=E?B(R;*oc<YgvlmlWR@=O~X|rYw5&_V2hjl;G6l
zh9>=S;Y2H397<fSD}@xTqt_kfVzO8j|EKQ)R8ZTzoh2<u$o*Ao$dU@)eKV=bEgg?w
zOs`AF=&rGXh5W0Kns)Z<F@bM5?}+H~IRVK8KJG!ZYw!`Zi5g}oH<EZL<(-NFeu;}6
z!T)RqWe^+1foaNU191rNsS0eE!cY&uOLB0Ie;t2>;{KHjt@Iq{dhq5sSi-zq8GMy}
z6p2<cP-2CAtTifWNogzXZyhn+WPFEiV{Mm<k(Mp5&03yif95#HG9h{piGIMbjNU%p
zgQp`--j&#k0|jMu5s?r<*L$_11AK5fVRf8Q>^hMcWd%*(tz|7zic@ntL`H%_e$`DD
zuzQOYoA7qbonV3)eF)WoJ_A7~KzP{QBm+%S(}9`gY~q{4tDBRpG3dMnQ%Y~`h0iX_
zz*luHLYam!$P{3q_w+2bPg&vytFRM5!)jQPZ($=$JLg<9H`t%<@#JDeRN>F1k}l>>
zg#L;;_ZlC(McB~>@RHk8wy;qZa4{w=Dzq^RsM4>eqaJDvr|w@~YpP>Lnh-fqt`FvH
z8mG&Fw9CF{I{UPybxOhQyr}DO-}I3Q_Qp8J_SZ=yV!T@F5#d5iWdzv39y^P^UnwMJ
zwpon=#=R^`9`tkE=WNQ^va8*QDPf=rX~ze)79&#@`rU&dbd?>ErG*VxRt;DLw*V<%
zEU6F6a~lU-0H_hE)iMre4a1>1Ebl^J@&wVk-hxrMY(1RWUY@@SXoz=J0Y%-qS%AMG
z7JTgCCsTVJ;^GTZD503hGze*q4QQ<UeOt#L2HA>`>%$Q@=7%$PG@LWrLuz~$!X03?
z(M`&bLW7n5W*>%VsMz6Q>$D6O1$UF;Qez6H)smfW@OA|$I4o>7WElRuz(x67sNuLo
zq<-!GDw=?YqSjhcpZa;Q4i87r6M3v!LrwmYl?_z*0dbs8Y-y{dJ~Ej(LX|qYFQC|<
zzz`4S!}JbApX=37qN~3eD;5;Kvs_R0U(ZhpD2N&&wTYri13T%+y+h~}mk!GPc6X<&
zY&F6O|ALA+6k0r%^5>sCInOCQtItjVYNjkjn9573d6&u$#pIc+!&D&%H!Nf`bFp}Y
zVVs)f1KaX~qY`KOB3ULG)qeto`N6)x2U>F@C1lOf!iFz;lO`iF@<_1GQkC|DR!<mF
zh(8}iW5M9X5r1@$%cu~U{3&#<Ds}-p9p+F<wm_k^EIHsgeclfK?~UR|zhAESmo<U4
z1w77J5_Lkj@Fg{tyS)F*Ssj3AfY$W^Hq^BpB(_$X!%)nqx}MknH+O?wmt=JzbW-4U
z&6=)r+ew8Y46oZ8apN2MFgp8%wS;6<lT=~yH)qY@?susM1_^MmL`ZN?e$510`v<>$
zYdm`zp$%QJnuM@()4+;zDelc=iRL&3HyM6{Pp!z(D;_kRjP2L16sItq(ERWCgKi&a
zc1tnY2SEN7%6#BQMJ{8~^Fw}gJ?^g1O0LaiHo}}Ra|rX)RyP%7st?V&<=_-|8b!P)
zE)_++Q&V@3q<XAj1gpIu{_*;co|5lyLGg;>U+ag%&Uhhaas3lix)sCg`i%CI3x73|
z!okuf89bz764R8kG-_UffCLgO1g=Ut?9t2ug9v{t8sP*O<4~8D;Mn%MUsIYK7LkGl
zns)?Fx}?kQUQ>D%0|dTg?i){6vAvmRDPDV9)8tdK-NU^-2dz*4f<CS?n4+NC)3tbH
z9lqzmmbH#tnmS%zb;J-b!Gq019!Sw2p0&nB<dU~ngP=7ai|E+btZ}z9e=AzPquwXa
z2aKU1GwRW02uq{61wJ02vTrQJv0ue2uS9ScGk2#;qrn(}UY}BbaU!xX5iW17_YIp~
z3SzUg`SPl1t7)dfZPJn(1#T1;H<<HjXV=wv8M!$s&l{Rd)L@QDOcy}pACPCjC>b6F
z_uF};14;O^LE%z8;3?ZG6&%7M!c{gZvO~C3wp;R8`-{;Fq(7~sYgFRQqkj*F5t4ei
z>*hM#yrzVl80te}__)Zh7=TFBEeYiJyXD8OBz+<HJjV;OHnmDVv4x+<u*^japU3wI
zJX<A678r^<8`R|nGpk`^U?yNL54tszo-;oZ-OYw?53vVRkJrr)-{~0JV-%Om9a^LT
zKx`)bdLt@SbWZ;ICugS}C`T#Lu=8a}h^4=khaygp?6c{Wj4KxjzSPuug0!7ER*<VN
zAT>dCCgy!pCh6eHi&V&jtJRTal52ig_VMJV4zBv-Ok_<(CZV>`KpSc!CEn=<8h(*)
zhIa%CjAey&p-4q>lfabr(_rM@K$gYumy_~L?OrWCg{91r;JQinX<(V8LAy;w0^MPe
z-HO%s6Rb%Uv)%me^cjp~Y8zs6XzaiqDd~Z^DJ5hv+?4!FYy?sFiF*jXndEGEola2-
zv*)g~If%b_p$AsI9;d7@w(U#S9rQ8^(4b&nBc1&4ux>jo5Qef2Z8te*hNoQ^O-I>#
zlyWRuD^k1@c3BD%jmJdIht_6$IWcmpcPl?Hqv_)0TJT!~4lj)NTbRtq{BdFML}uSq
zKfp~5pVlv0x{+sz8I9<&ZUsBpz;ED8r<V-S%iDIF*h{uOhe2B>@E0!(YC7hCpEvnd
z;eYvpfV6((VBP;h!F?H}h7p)Yh|XU{eG9uRRAHC;^c{^3ksf#GLVW2+L`cy&2g>R}
z9<weirn)77yVd4v(0aWI=;_lFdAZUo%~;|(>M7Ts)ttv1Jxz_33xLy}^{vFer~lI=
zVk6LankCEqFz~Z^S!4O}{8DY{!*>L502v+RaE-2wf@{0in8GSVYcqGGkdREi-Z8YJ
zu2THQXJOyCckoKS)I;fStKsx$y)ek@aJUeLuc02^YA#pfeF`gMhF%N~h;P*Yq=Fuc
z`n3)?EedhayjvSnX_PFcHeqS>&I9ykC4*a>ug{sT$LaAKBpNk-s&s=IFbK2n2=u>8
z;8N$7x;*}6B7Ke(of022dP80XQ=on+wG-?4-&$L%bB`J43THET#m^>YYqS?t^{xME
z_Q~=uV0afk?Vo#vd}I{~r02}nB!XBJov`h!Q}*hh%(^Lu8~f5oh0&xe+s?~>E4as4
ziaCh>J0l;Y#<uCSK6y^!PAk)NBI3G6aF^kqVEIy>gZO*2aaI`>78s+jD}{S+F3+l5
zgy6EuVAYhgls!0owV5zG`Aj@e=h{U2zBuZ_mKX|@*SaVZ2Le^E8aAqJC9|}+42qab
zZZdi#D_0GZ`Pb609X+tzDpkzYyM_Rr#il*RNOv+kPu%4^E?OMu%!Lko9KL{=9sjVr
zsgY6Aw*CZ)P)QB@es?*j?b<3^gfofd+_!xi{8zX<&WSgK5NyQ%yUECv`*MqpPStiT
zNE+_(iJcj@K(h;*VV?A!(z0RyC0*{DnMbciY2rJeBhiHVu*l!I^j6TlK1m)0KY{J=
zUWV_CsukDQ)u!9qOr5Q$b;qc_h#!}qHqC=@m|i7YZOFA6I)B^(cpxjM6!Z~*n|SBU
zdd`L~oPxFCAQqMBMHw29wt|BHGP%ahd27L8uTV648(oKv-c?NycYet-&M3=%qP_^W
zYEdu(Q!LKKPMGONui@({_S^hur0n)9b5>-(Q3ijhm;c<1Sr3D1j|M-^JRIUD3eav!
zU_XZD`m(_tsy7|Y=gDwY=~)=1a<aPs0zTXZ;xYA^7qvT*IW+h8+849-t!0Z)gh7I1
zHd<3z7xBl2O(5Aw?livG=OFb9TdP5h7VQwQ@8$Ibn3m+MSUPy3V*JIEl*bnN5c81y
z`XaiSS4I_QYPq{TAT07b^6Fv^mhQ&+THfRaevsPVIso*+0Yn9pu-zS`gaUMfa~uD+
z_@#!4fq&xTW@8NGK~UKZnkVmeWqh9y*`zZAawv>NBjdq@LLqV11Ot0X?F6jrs<U&1
zMz49sb7R7p$TP>+4V}<OEq|>2Xv@QWAx(%GqDQMEU@q7hHGAYKeOi}-^P@O?B9NJ5
zE^(VLj|8yQed<V(Md!c|d1DOOtB<a!V>BHW?_~)~Dj3pfS~OP~x}X>Foc1u6Z~y$k
z>|Sl_zikFSj6cz1Bv<Pp(!$v>!=#(We%<hP`twFH(;jSr=<$}zFPO~80KE<M<w~#W
z;Fqn<>}%?bt~g=;+_l5NPoPd7^iU3!$T$}x@wt6rw<=GIbNoM#W*x@HY7eA#-b_k;
zXVg-Kfps%b4SZ~IiXafDwfC@>!nIHbmmlFo-y$9cTuNY+U_>9NwaJG39`zz%d<7B3
z6NLstEL-LC(4<iwk5{6DVJu@&xoMVy;uH|B7J%nE#Sl#0q=zO`0nn~TUB1ZGRuftJ
zJtzQz@@m0!YMtf3oVomCHP$K3$eU*mfw;ApkS=7CdN$(PEJI(X7o3}xJ6UUTT|;L5
zdhMyHZbidn$%7s_QTz=*)sL(bwy?_;CgV#$ij!*E3h^!2fHEim01X)2*xprgc|L2e
zGyiHlb4vf8^oIQIFwLGbnOQriD4evKAofb{M*NkB%a{NaphGfPeT3B^`eBVIp#bU_
zME0=2Fdg!2&+eBg*s(4_Yy%i9@4s+3^UYVVikLsDbLXl=V^EYn5QE#0L*L!Xln~u^
z-LoB<Ns|}uhVaLGw1@{O1LnMo-2T}?T;CnTGsN78i*fB)BUT=WQea-nH`|G?Tt_x?
z*QNQBY5ePKoOdJGeXy&m&u62**kWOUcIv<HLhSIOW^sU7&NA^l*Ohv3>OJAN>Rz(U
zy}raH(z=1#C+aGV^}P%jq|Z0A;p(bZ2EP?Ke7*9iyKUm^0eD?(y<l2_trWh|cu-;)
zlE96wtmrRPb8=OF<J_iqU;no)a?)VG;J-%QP90)99>%aJXQ(vtBH7I)+kMBe_NA(w
zm-M+x^Rz_xEfTEc;q%BuIXA?};5%M+35&ZO=$tKOByLcprcBd0D5S$+Dw(o4{Lj#(
zQ=!r}#wlE25YwD_m;w5}$>2W^BbN=_8<ChFf%(L^N}rWRC!cRHL23VYPxtYEQ7j>U
z7r((%!aeF|n-zm!Ig*HtxR=7df>w&<U<{)o91T-gr57Ln><0LP(4!QfGVwAMX+0N(
zGL!q4%N0z!4_@HG>&By`q+SNryE`Zfu%#)voXGE!RKr;X_TouXZP-r+Yvg<UJ({O#
zt;DFvfVUD~f~OYMwl~9c;JOJ?PGWLVlw*XovPgiE(lI$`Rgh`BUmQ$uYQh-T9IL{F
z8%`aQ0Zl`gM;rN?K#yI1GT%ueA6W3g?{hr;1Ydy_M90=IDO&dU?o`LZ?ps^(zuJxZ
zTaz_doC}POH_y>srIW~-fbD;b==MrnhGBr&;<y`SAb^m!YOqWU0CZ2_zXAYjW4+eR
z{*Jxi;}F#SC1A{k@xhYN>B&AM)Y7}m-K1bphqm6IQBJ0`P$9(PBu*q;FkhF#X}iNj
z$@{rP)NV^vh4=^*Dl`9A`gz@#O^m2Zn(zR*0EsZ6j%fHC$p=dZK5b<N-yXqaVM0Yp
z%@juYR1@>O5R+hlCcN3u_E*kKhAOBHxm>||S`~tXAsd1%Tpkgxc_xE6<uAT^`YGy{
z*8GN4L1zCn!kN4TR(Haa)!*tWBt&4;byykY!BQwWzx~5PYXA^eyeQBW-jAVa-VIN<
zVgAl-%TC`XgWZL1kDc^7trsPvXSVozdXm-BqzDSGJcNep=0PSAOa>jultB+-h#eYB
zk4De9*=dXOhAKv9wjz(AUHqijm-$Jp*E~XqzUo!;*+>RaGQ4AY#bnfX66;B5Ag!;B
zZQ%SQLm%T?y)!m<9JQ|}m;DZ}>z!n?A#1<$9j!HHygEge^WQ;gyd0$p#HZ%<^>V)u
zOyyHX)SfR6NEFg}kTWjIrED9i%WlZQMDI!Ce?(AUZ{FLA%V$rqwvGQXO&knZ^PH0j
z<xjcNtrh2e(ivrmpB}xNhd_@fYt}wC0;R3;z2rG5Vq!{bJ7x%StmKR=xk+*j-4{-h
z(^(pS+OZackdVj6@xBuq?Tqj%!E*E(N!HF8*nh}!nBb6<aEu+wh6AWXHypU%LLMC0
zPS1@e-glEk{7eH{ObLJmIh4|roR=P397()#ez+-9feY2;20wNva3ZgDaTsbqdqcT5
zhHBZnCWvI&?{aEQAaJ!y%Lq1L*dI!W{NeYP6F9MrpGXIhrxR4B?^xV4fgUeW!9GPf
zcrZBX*2L*l+TG@5<|=+j+s>XOtv-j0XWw*AE2-WRNll1Y{oOl;?q9a1uX*TU!KM|#
zsokE2$!*HyRtlX40x#UeI(+M173$vtV#8YxI3UgrvNjuAFv4GLGk<JmC{+!ba;)W7
zUY3XJ5IlX{tplshuc4a%&0Mi8O#2GeVmWOzg|5dT4(kopb5KV(lLz5v7P;LC<;^&Z
zyeiizjbnA*vzK+}Gyk~U_N-CR_ODbRi-7g91MshHm~$O&>`RHJwx}5o(>qg_P*<^0
zqp{g-I4_`$Ca9^&XC(3e0wRk{GINI*p1}jpJApbP`J?_1&7y9nz*u#mB2Zb_eRC`m
zbYVdA4!>c8^jgzC_7>QK4Ho`9QGL9Jx_b|CfbcLJ!gs@4q4qj(Pra`MS3?!_HngV<
zGsO87`dj`l_w;rg)&N_qDb$CI<*PEE%xmNB64+GX`ILRq^Ra)b`|V+gKqv`^x|*oS
z9T%>>`zAf}hBtAMBg{Tcl%9LhfhwP_Wj>5s@0PRd&IhUpsOro#F*B>aU}!CO7Ki!x
zF#xHR622Om+D{FJ7)R51=%{9NnDsv@sC5mCb6^_6TBN*EMKBVk2D!;E7zqswkk(J6
z6I+Fa&co()wc!j@GKmih1=Eqi62n(vpc&a1jkkzpxjsSH8;!s@BU|6wE)f}<JKSs{
zsf?EC*Xnj^YWM)Jg!Qk8qEq~<v;dM}(c_Mn=lUex1O!C1o??ZfJ@ZX<<Q;DO6OpC;
z+6;&3yp7PuI;cp`Xgei?XCtv=&wc2<d;7D=+C`Toll6`R$o%f(=Z=&RQ=r_AY!8jK
zS`dRyXvD}?@_0v3*k1}2VaB+^*0jNrW57AlG5j0yfs~MY%d#@QK<IAtI2@O&1OdAI
zsKw^2%A1}?5;*fO*6<3WWo<%(ZoJ6$<fg$rvCNK>HHD&OHCdKVp+}5d_}8MU5^CMh
zPc7KgC`^&df7!S^1Ge0KkcgI(Fmt&gBhuB2{u8V$ajD{p62(#NNUefRitT6pOpmQ3
ziSw0FX-&z11={DbyovKJ!p<zt1>yQ0ZB&+ysk3bKjaZiSi2w&bUUa-=bvps*-r1Ue
z`S9(SDEuIU@KhV7FTuU;8AQO(I8u013cEyQwuI(!$lW4rnN&J1(=a(rySBaoVy0wC
zR9nL0%SL$P*T@g0zkOWs|H3UYp{17e40ZHA3zTcy{}l|7?*!Gbz}jk=_$*l#UoCQl
z^MvpHjvJ0f-W&qD@=nQ23*|uBrSMx2r)Zinxb(LJKPg+r5KnC3hMh_WlBtY1-eQZ?
zr4oZWa&R!VI`HF7;591jv9)UCllzLt#Z<Q@6g>1GH`OgtRxi}AYqcd|h{yKGzJz^5
zOJTWfa}adX)mNXp@d%#7S6L%;v}3L8!&Q8R&90*{S&`!Gq}1*RM_+C~gs-6!Z<nAH
z8Ch*%9t$s@ax{^00#AhN0?bzxR7ArR`<f-!Lo^b1YR2&jHlP>xLJBq!RL*|RXr#!a
z2`RatJA08KZ31O^&5mBES-OU3peB5v`LJ=GHx*8vn{S5xGbd7RE0{lQoUkQz=g|XT
z1;2b-o7JuY)Tskk+cQ)0kPs!aiavV)tu&wIVDF#JYF;*|wuavKopp1I57O``0yP&I
zbcRa4#ynsd0f<b|q&@$xp+l@xNy-c2yksvhD|;Kh_f{SXp90rbuf)~YV$c@Cvt45L
z`kJn3xDU{&+v@(>T!Kj7H=qaQ-VqTxWp(c<D>Em(i>+)EU6p(VGP7oAreMj!pQv<o
zhWfW6WP^q$rD)BDxQ4++W@TEAXK2Ctgp7eoxj?K3RVf0R(;JuP#P>J8mZ(&pngITm
zbK+)!|I@QRhn;H^XOIWPP<L!{RVZU8z#lI)SwMoLYC)y0T}^J^d!(Ev8e<`VN1;8E
z-=k2^Sw<vlIT1i$I$LXXY=$s30H9g6j&^!=<cSUrNP&B~Df2A~FnSHgCp@<wq4G7?
zo)&CtZYz%f<Od|ES>T%aq8pVDh<ua4X)aw^Fm6FFDQj*3AY<p7^$n}%eF7?4U`*(A
zjW{yS^ZP^xm?trc$C8j`gN*{gs|p3s?Cp_i?L?m;P<vNn<PMb`+@*xL!SWS6e*``g
zMQ9Yt?TbCqB~%a;h7l92U2Sw0OA;5yuPiRR0$S~#!l;(bzzym;uM3eEoS&c=vKE+~
zg&efWeOcW)c2N#F76hLA#xYYDs;YTK@V-HAb7N>QDj2vqQ&sOTu-953qh7kiofXr3
zNCkuIJQ=5l+p=^MWgQsWRYbm@kYobp#bLF6j*qsCfPW+UmT4a-!<+O<9G5@&5C?qt
zcE$sEgqQ<o3w{S&dH9gHAk!s-<y?bR8N|sRu1wPmyz<+Mc$dwuLOwJ@479>*+K188
z{lsV0$PxAk;{ajQiYr%7`evnn^!=4)oCby)=<H{Ncqy0#M<o=zDKsBaC_`Ic`Q@=@
zgCz)^$T6hWgvD`sAedU*)`DF701$_7fx%bz>ie9XGxvC^PNndnGHula2FgK`i$-@@
zvJ`I%G_hou4ng`=I-y|*_i%jX-Zewu0yDxp6Zyb%wAvEl+sYnbQ3z%v8KI~ul5|68
zA2Spo_lj3x4<)X|Mf6rnhVCB+5m?1xFom=@Zz8_<CnVSa0|9X^RAp>PQJCNtT~+TC
zFH4jv9pL89+~sHz(Pl;YDRGFW8*Ssmert`2AVMJYARVbF0DIw4`aT7bjtVReBvjnb
z<O}pibt!?u*m&*GeTjt7HwO8(S8=rxBzEV%&mjxN@Aqp#Z=8TIf*P%&)~M2ovQmwl
z$D~)#HeK2^^@KGZy5YiG`g#Bw<_%)3!vF6{BC}44cW%Vbo_fSsWX9A<NezzvdkkO=
z%aFdWUmIq^?!1b{k){v)dLA3st4Ao)%L?x~4~wV*mUytz`_C|`$0ya~M^0R8pjKI^
z2xD?SxaNV;+V~F(F}&rbRIn0(S|{y7zKp?D`tpdIW$kKCyb{ZUN73{Wk=FH5*8zcN
zA@6{uK+CZzgQ3;n@PR0~iC7vbM=aO?PqfA^a99)GqAvu-pZ(}H^-a<YN}=&n#QbEA
z!4O!AfP^ntugf`+y0z;>%U-^Xuz&wsM@Kv@SW3O}U_$O1<yRV)c_WuB0IG@d%k;v3
zffTS~L6)W038@-P%Ot)BaJk%^ZEzmdWbQ7z%A;xoicwk_8q)I!)fvkQ%&CG>)K=2Z
zW_c@<*VI67nUZyig;qIBbn(8Y@yd;QB`Hi55kY;2g&nxCU4N-zkJsInIOOWpT$Y0-
z8$^kF6MpUcCk@X^)HbrVv)GKE<P?N_dF8TkFwQTFy8yQ?ce~vk*@Uksur8MKqzQlq
zLbUa3Gf}01Y`>w1iri*7fnU$CjI#^Cx8ym41IjfV?;eFjI<UJn3J=*}ZxHaj`{Vz5
z6{#Z>$__l^GZo_U`Xhh`#kSB7YAJOA>VxiW_=`U;#Z$cf&DJOwj&q1)6~4xXlDfBP
zRmdksjhXeGI5x7Rb^4;(a8)qre#<47sh$<bR{<9t%_9wqGPNJSLYH%#L)mJGAS)e=
z*8F&S@M)mb<DVJ@9r5w$^f|9VToOnyrc-^s;`KXCZ(?Q_pJ}WQ%|XZ_D(vEhA`Hg&
z&799rj*^a+zJvnaizA#=1*;nXgnKp+@v`r04Q_t;9UCTZFxvw%l(^ed^1*uG4W4wl
znsBfO0^a^e^=F+QNg=N-x@{%9TA-joUMAp+d3ZYy49tuB?ZXC~HaWQ_Wqv{He+|~u
zw*|?iaKyXm`jNdkYA5h3V;l>Bi&~>WCfb<i%7e<AdqT6$@PeqfMj*3U+OSZvX_iH~
z0rPko>*yq7!0NQr$cn~YHPUZ)@4hI+MU(Lssg~Cb$F(<~h<@Y%fjF#}eLG0fmvx5=
zSOLzqvi%0@Y<fr}A&fcyQ@Ced+-$X2aW#~KN#2L$dU|d4*n?4Vtfz!m0tL4#*>Ij&
zTSCtY=?a^%ce=&0AH|KLqT<|z<T(Z-!8CivWjX%gpJcQ`!r_qF^tQmPR#{IhWEAS+
zl0;b#HT$eM|4}7(ejS4&jXLKRbAekwEmE4khF!`;GXemQcT+}pt<%am7<_Ge;MJd{
z%4?^P^-N=0Pfy%>RqCh?2MWAgZrB>BeKG}@<e<Mdr1U$Lozx&hmDP3$Ef$h7b6<=*
zdHdQ_QT5wvF0SShO4tf1kOnwQfWc3odKK=X(BbW#u;*oPH4IE(VwRs<-T4ZKxHK}o
zWSQU;HKsEf4n{3nu_x>Mg{Z(cI$Jy6bf2tukVT=0+Xw&(X&;*<)}`-&FuFBH3XCZr
z65AJ}r6JkG6BX>?AV$~>G*_er_;ETu5>>h9Sa>Q9*NH6xa2B=YoiPXDt#0zJn>-Do
z9tiaCT<=oUfLA%q(PelOdrN*V;g&=}eQ@QKW&{Vv-mSZ{j)RC%-eW?&;4>I7X-t&_
zz~Po~0hBJk`&q^KP>P1y$q_5zW(2C=zIrJnW0}@+_8<>%Cm!xPNp&7;dFjGICIQt&
zK*(+PzyZK3=xH$ccYX<OnY#Ux0ud5k*G|SkAmnpD;mEX7r)1CnV(^awHSd}nkwI=g
ziAw~Nt2R%Zl$RmNO}SM9`l5*`2i~EOUY?J2eaHw&_BIblHoF#QNfJm`BGdBv|HeiY
zHqwi1M35sfK<2q-bSzhgeJ)B#z+M8pi)fP2_v39nl#KQ57*cpNsYn@Ul*eVnR(f2F
z6>N&*dKTqwrr}RWs1B*A!;~{(iFxd!iah0}G6uoYQMF+LU}Ls=MyDximWf-tJ+g)*
ztP08J?e;CR<w-tq@0*iL1mlZ?r>(!N$u)moF0A#O_ih^;1eK*4hHdE*z<^ox`OND*
z&JPHLY2P?vll*fxmsl?MAc?-nysB1^f0*?gbJrD*Vu8zQdTIVB0;ieExG6o-TET=A
z<$2}2C$0}rK#j$E$>2J0skR~nanNEkD3xx=$N7$5Jm%k?>;dDkkI6^RQ|g{&Oa#Uf
zLWPwaer)IuIH3kq+gQJXyPHVTSq!+0W1ZX16Uis{ihzwPr;H$+i*1W?=<k{nH13wS
z>4b0DF0pqiGUQOb{Ip|RKsx77C6nWo1?oO!tY>Rcr&k7f5zMp;2BcS`s{_5K$wF6K
zijv-ZYE6*2jf?d<msW8+9Dr$sBtH5bQoUm+v&jKz&G4YR=AUzvE!>EM!soMoS>9)M
zY3Y-9JwnIT6T@`NWN@2V`iM5dk?5$&V(B(GbS7r6m$~U={)0V+l?UqS2p)<(c{97l
z%Bl6$#-KCC+f2sT{IM?*cR?O%GN^n<kY|YiDQE)wrgMvDI)163+5^wgMuM5V2y%Fz
zYVnb-<{}0|;uB{(eJES{bQOl<i-xCi!rNrM$0^eCpFd89<-|Q<J9V7#rLabXeYWgX
z<R29@_wD-j;#LzNq<PKfIjQmIPUY=v>%PK)c^)5waBC*_m*L42HzAANB5CUF^0gEA
zl*0|R;jE%HX2G5g0V>0Kfpua2%u8_LlxDE!22AK0_8f<QN2|_6$~+Ma@T#~Zvk!2i
zZ}fm*fO`<BgB0F_$uVhaq29^4iAyRe))#4O(ALzcY$Wipt`l!3!J4pNB~Rr|1-3>T
zA^3R1+M4S!0{CRVXh#sHTMmE4LpBsTHDX`#W6K|WYVfjva7p-K!_iMnQ&8aQV8e2i
z<Re{6P^fwk4H`2%8}K}L$4T2`76mmqR=u2Gj}+%}ZMbS_d*_>MXOR|FVOPmAS9-O;
zI6X&+O<MM6T(-V}zY@G<KMi9>w9<Jr5+s=))TLpm?zkf@ua*JCP<bP%*N%L2-(;UY
z*W)#7+9~>cE84|6NUYxJ)OeLWsMHbT0eEi){2;r;CvU^u@zon-cQzu5<fPMIP^_D-
zXFkN6JJdHxuvI#c89$FZnB59{Z|>8l?tX}*#op|{Cw`wgvsL^9E^uD~+kszuXSV*y
z@Idt%=+(Sc^N0xe22MBg3JyMk_5f}U`nb4ejdauNx7mr8>8Lq2;+eZ(T7bX=*@<3M
zZ0YPiXQf@Zc;xp#8q1f?+;L{2bCdgMa)1O-LtPYFg%j3VwV^L&y%vtYZSq*MH8viS
zUUs<smqlxQsI9^xSXTgKvNq6rYnCEFrHk^DU@Ff?)n#-GbLFhOCOK=|Do6mBl**1x
zz(@+FdCT6(;{M1oylx|~oY>JwF}W1t*0G1ZMx?>uU9{CH6HJ*Z7p1tv`;{^2C?&!1
zdjuV`rdigJ($*K|T`K=Xzt=5DtxYD2wxz<ONq=<}4!sI|4UrGJTG;tjzvkxZJLztr
z6R)PNR+g&^Ag=0`1TiRww~sHOl%aQ{pPIKi_|jiazRw{H|HE(vCUd`VL;T$BxYW&V
zO*$SZ`!;My5G<({azS#_&dhj5sDMo|aYWf=8EP$p-og$*QaR7~ovSJDpjq_JEEK#Q
zG`*dN$GJw}e!)=?$zFfS{>Cc&?g4N&8c3hDYwiA#O{*-&m~w1k`z66tP-v2-1GB1h
z%>h&i+H!?gryCxgoyAqrvTJPsNmA{(tOf9t6OMow<Zkz2a7Y=rd4O!x@f9EAB?v#3
z`G>Qs;rAGrjQOTpvnCI<Bm@>emu>F{(7z<ke^$zEeLVXyw$=1eO%oa!oYFMbN<ooX
zGLQwvl<o1pH!1T8H&+A8yT=VMv<-0J=XbI0IS-gCLQ5tU6M<IGf~@X@>oF$&u_UW#
zFxeph^GhYTA=3c>t~Wxvxij;icSTvu=C=->M&%Wa`xS%ev~uLk(BT8lHg1*{*aF^{
z6n-_03_N$o8zR^#zMD$bxi0$ROU&FJmW^gai3~MOWQBPX`!JW60ykS0Q!0q{P8r%l
z6x0`p4f=FzeZ&RsqSL>TSIU83K6U<$dI1B#((6k~%1!elY`-MN`f)G)IT<=k3Hj=Z
zc-!2E%wz$$!T3I|SyH<btRIW?m<JotyPJz>dR}*wDHaJ|K!0IBimyNdFN&BC^RG50
zlsvP&Vf$Sx#XZ``)1<@sRTt0<!y3sAk1<@qC0$TJCs{bUV7;aSp<TU}m|klF)wC>|
zEJx5&#?#Hpta7g^nn?Q6$emU@{BSMNY3t#_;eeS^K<$c1vQ8n(&}lNmM=%0CcheYK
zyv)6=ho%Og=Cfp4NzMPB_tkWTBc>d-EXPg?2>MIH&RW}OeY^5$QMq5uIk75B-r{Un
zlHH$BO6xI)=E^>_$JFi}h#knxR>th&DP>OLCTF#{+FS`|oa95?Pl2vt&h^1PFK3vd
zQE;;+7X{{1HHBpmtS(i#S@_YDKdD;YsgeeqMSo?6N*gB}mp`DSKp8?mTKScNNbV<e
zm<Qr!ZPLoY{&L^WOOnRoN!96yhK_f13A;U6q9j!Oe0M1!_kQf#ErpfLHmaJ-e=NyB
z=oym~E=i&hLodc#=^$d~V_1ElQ=bwlW=a6L^#!3<RA*O?U_SjvaBTV{+d73iZmk+9
z(y83*DFeEi>m3l1bkrpL!8@@E1_8=(CQLRBk*7^H&Mp-f4-)J3WH%=76oj9JnNM@R
zNtv&7tTLQ)HYoMf#4G3a%)G<zg?%x3=Ywg{z68!22hIx(@Ci)&Bnyd)za)mDX4GBf
zDu400v0&ELo={i>V?&;$*Is;O55d~6>=4p=bLp#SKB&VuLGzZ%M|t6-S>9ToS@i$w
z`J5dU@CW(^`Mt81TIXP`caWU?1mrt-$U4w|_0(qg4MZZ#C`qX|4;Hc7^P{WOQo?LQ
z*gC1KPju+pvZJ}x!8iIbea6>mz4=rIS&QX{R}g$|(a9AwL({($>be_U*-n61dBM{g
zUWV0l%f`$Qu8GBqovc8}(8rHFm#FaTvxf_eS=!wndxlVfxo1>a`jv^g;Kj^vYK6U1
zP%&i6Bp3ItPxzU9d@!Yj$vn3r0So+{(V)Qct7B?sfg0)qoeU4OX5`K>MFg3V6kGIp
z!NYl!djC36mF}Bit%|>p*U?PgToZ$`jb~0_ZAGEcItZOhfG4En?P_nTw;9!fK<T5p
zah)KBVGY9@U?5*bPOQjn_maC$s=oCJh1EcgUqFF%%jNHh$Nqu{C}Ee6FQKY>iku0c
z{;(G8ZD=wcN32X22+k~NBH^>7>1W4mSt8RToYeibJJyQ3j@L)OSRaS@sFJy)AVGCE
z8Oo@s|Bk_Bvy}iWW`+EySlZ>^;+9Jo;GeVpScFX!l|Ck!K#rF`2~II2tl|uGf1>uB
z#CwH=x+)l}E?QAE2k0&;qg60P>&wodL<HInxFC(|L`)jW-#dMbXCZjib=0!={n;q|
zp^H{iV6h78eLH`I;@MMGRTJ49Im;5(9<S<wJ(1Y_ycW?;KkpB@!>^~n5ijM{XtNpy
zU65qGm!(GL3pw|39~3yRjgNuqEa}!v)DmnH(_@JpabFR4!Tg=qHWKa9w}l2SqV)1=
zVZDY>-L3nordjBR@jL|#HE=g!cK=^U#$K{$XgkbAp|~=5<#IcIcMOAUda}Ef&R2E1
zPWn<XY_ZAC#%NHVwo=YKwKua7CR9ggNLj_k<|H7%Sbd18{PCu&LiO~4Ny#Y=^8h_S
z!oThTRPtRzns$r)3VqYbcy4ilZXrAd^*&HyeWQQ3``^&&ozW)n+$~37e{TaZ`#AGO
zd`_@QMDz4C_FqwTO_Y}0kRGoD@#eVe$WqL|YWE3t1;Nb!MUl;ofdw^A{{Ev-_7n5{
zgta2R&50O8#U8hMaA^Wo!xmWZ&$xWUoaDaRs(4QQFnOX*2Rc`Q;HOwjcXx<Sl;qNx
zo9Hb?m5LRQ8T$-FS}T`;6P90T3FF^=B|@!wHBfT6xFjjCF0;?wK!~cIX^iJv9dj^Z
zVX6wUz^AHS<MbI~N*g8NC74>Q^C=Tdf$Ox}fgXM(v`W$~0lhs~2G>9fX=r>Q-jFI4
zORt3kF277S-horHh$K|Q%x)@g`TaC-;@fsWlse`RCG828V(REW#8iPtJW+)zlW7v0
zFsX=KV4E5wb6QYH<eqmVGYehEmZJYU>g-HPw{RJT^|@J71~hYtM|~`Mo+%2fv|Za2
zo`^zX3=e%z@>CkZACULJhd<00K>$SL@R(39c~d+R%HCo!pQQ{(g0ppsQ+#HExI8H7
ze7Z}D{ha(jM1NP>1{>4^-b3)DtkMEWByRdVebo#MCBU0my|$W9iztRpl>(lMJQ|H1
z2-sE0<<Wi2Bq`fa7e)s1Nm?B*+EqOdko0<DZHOgLiXhI4B)^f?OMI&26>th6g=4Dj
z*OGb53o&u8@?Tym0@!p!uJ1)4d0*4X<Ba97r|RflV<!rs+qe=m>9dUdjQ_Z=oHXQ9
zfKrz02T73g#sz$esY}7n%@8{=kl`<_Z!<v$C?}Hv5Koui=o-t(A#0vTMrVC*f_gN~
zjMnC}b@?fCxZ;M69vT~GeWVKhZpk%GAX#ft(I5wMu6+!__m=wxDVRklq4Y*iBC<-&
z06~q8XBK)O!H@{39_l4D%lV^8ZIrC|l7W9XU431k<$HjC*zM8jh`%hG(B)LSF(mxm
zE)!o}bT`IT-U08GkpdSA$4MIewjjs^?4(8YWz++pmm_=8Io_TJw?H1anm<AfQ|s`e
zVJQ?zoG<tkfc3s&JY#|(akXt~UO<e~ogpNhdzhu{&uHX8Mmeh0KT0VkTRvHa5IU@t
z>3<DOF(jvrEbj}B9ow<!%YJV_opLt%glc;20<oM==smivYhU_26SOg%?=)uYY~q5|
z(e6f+F}+(!wf%Yl-#UPU0NNAyR7`kf2J0K{EFrJn2Ol~e@)E&WU*LMAXsxl@-}+z9
z^cmQ;$IjK$Gp+piRtfWjoV?wCaqHZesXb8#tqC0sgZYQv(XB>boq@AD(@mEXuYV1;
z6z`7<Ol9DUHwv&5LR4dB-P$TxK#w^<lmFl|v=md>1w{zZdY}`)UOa#Q1D&R^`9P>0
zl{NNu9l&d8Cl6BU0)o_G+8NFh(}7!@&uR0en>rxm^29~sNa<lCGu2BCKILfu@<?}q
zS+}=D{2k3I;b-rS+JroWFb}o&>`cI#HY&y{XnbP$ZY~RDjdlK2*THXZSvK_evnZyT
zJWz%m=26G>8Worzr!ATL?A*lq8m{pDNZ(HB83OPtjvfBU{kIV1zxEF<)Myy$hBf9}
z<w?xenxJ2%THvdmNT3Pprwjq7fq0<rMx9Ec0Sdw3euSwna(9c^+Abe?+Bgc>O~PZ_
z_7T&T99bVBJSC--H=4@HLo)ZY$Ffo>rmo?I9kxDdZg$-17O+hyz>kI40hX_km5W<^
zf3`~H=FFQ{-VjAAhLA|fBNc4ilfZdm<&e{mMVq90Qk1;;6hU}*(L3iA&>8Hd%dbq{
zvCxE2wSA}$rXNq_Q`+agF0DFC6N|~-MBW4PjywJRM^^w)9U{(p#kq%fCK%8ylg6X#
zEJaog?ZI<!Q0X;dP(|1<lYUz?IQ`F}viAemR7NnO$#q2kS7oODgBlrB_@Hv#z!qV;
z9A5tpa7Fonf8>yw$MQ!^Pv@#vsTKp&Wqh0_Pp=iE5aN;g>cP*pM~r3A9>2x^@`eHi
zF2krQ=5<Uzdv$C3u#WO_-32H_Tx1Gw{e6n72q>}HAHvPniXici4{*3`@Xp1ZGfM&}
zMW1_8(q-pjeI4!gd4Ez@tuq|%+K0E<r)mJ<_43Jv9`-pj<-R?`<C6*c<0zJ8%nb+n
zdK}4>x`!Lim356mCh<X=7d|sW?OvERQ{><8Kks<x!#DczMhi>eI+}A-<4T$Hw3kJo
zecFbGzq<Dt>t9UmAOKc2J@03biPWsOgmWsd_G#=<4%z{;1rkhrcxoiBVkHEGWuYd|
z(Nlyg|IpW`#C|esBpP$!jLF_3Pj>;GQPoF4d29^eqe)pf!%faPX<>$e3~TFGEjkc1
z@3@7i+1}q}XNP#!;RGf@r~U)?#)wB_uSr)Hp7F6-)ElGRMX0hsI_m%nti~t)<0N;^
zgf6IXY<X6!!(V*YyBW5&a%pl^OWPz_)`C254@7f9CJsV`(&0G=mG%!~;n)A{hlydh
z*)A5~IE*9%fnfKX(a)MTAk(^AB|%4>8OD6OIFYp5FYJ<L^trLgrm5hiUbCjbzm}0t
z;pFWyA(j7B%ge9hc_5bM`J%|&hiSHyouyu$hsGmrcV!z_>i97HiZjNYzp?73)GlgC
z*vyKbjIYK~?MIo{VrG8qVIF9VyQc}FTzlnP7pj=(kOIqpv+8bQIMJ0tlW{<?91Kw<
zrR=*jZwZs7OsPbOmBhA=i)@n0qepTwej_26Z|l2MKk<-4KI;2T%L-Wd+yInMfU&>B
zC2r(s2tUZhe@4)W?H4AE**k!ny;Agbb$LEMX{V$wqA;K<zBPA<H0TI5f}Y(XQN@RB
za+=yl34ysc53+{LJ$R_Rp$!s}oaCx;=icXe<XVh_6QXB8$FGKCM7+8nxsNG;(6{}Z
zmZ5fG{mhM(D~*}8%eB@`pWQdRBM6TMY*K2bUoiqs^9hC&=tNj3OQAoOV6%IMxU^G*
z@Ir+aIt7392Jb6UHEcSSN39p`z8Lku<_uF#A?%j^ul{@UDP-5%Jd8wV>MRS3c?Z)(
zNyPQ9F$8qRIu}mFTaT0!1*{$^skfo%yzUNj5eM}tfpq+j2^O8-n_*ehUY8=|yhORR
z&R-rcFV9|Sqred#*^#I4mlT&SrHn};d(z-#kuOKR7!)8M>ai<$y>py=-U-1MFjz#M
zkS}xLVBz;&6~}`SJDud&*R!qVPiRlLexOHY)X|Q0d39T4pC|!ngwVxcYVRe#P1%}+
zxYEHqv~3FA8Ln7IG2W<#pZSi24EkY=`-dJiQkTHb>uc>_bfGs!Q$}=mBn|*DPLNZT
zB%_!{x%O_q=SDB(3Dh;(>0&XPz)SXTtB7yrQ(<<dB*Q_l_`#D=UNh0Bg*+6->+b;3
z&Yz8c0LTNfi+2!WGHrD`z>ez?kBFdt(z`FBOaT*Tc@^-z<jK;40R2}^9rizLUntbm
z*8@?sX6#%FLE8Xonh<q??wvjdbO(%Ex}0<~=#J7TOrYJZUUPSm?#F1_scOmw&o$YC
z@<xz>NNMVDFo<&`YEc<)DKU!xf%WddFHSR}j_gT;612_0iokHzw=ruOboZfKO4pv3
zS`sZqC>h40X-9XXD}ez-!Hzw$1u6c8H_rUIW!Wh=o3<DacV>q@*bh}Qg(C5YT{2BB
z7dFo$R63%oN>1y~jsCXIeam`-tP8hm6=A7o`dl&_OV@2>&1{(WL1Y2-i)R_`vyXf|
z9kh8kgIxL)A^3Fu-)<K=GZ_cYgYQFHuuk``O7A(jr%$4H8CCYO;ceZAKH1RKzng&3
z8qN|P>t}+>4H_-<#8nNDo;2d#Fa^szB*j<pgJi8kH!5V<@)i@lH_{JMz|8K(6D~3K
zgl)A7w3h-G4R#5zfJY8^7or#^N{bmHrYj8n{@zQY5F*}U<VHKz8+2&aRiql&(u#9g
zq%F)Ya$8<{)mC-6djCLbIn)V+TXDi~oj>|iA~4wrEvxzxCH6EPMc|tT{hl%Rm)DKD
z#oN6zV#i#`i#=Q}&S~+jrn*Z@92oUo4w)y2<z)+D;FZE9t(}PZQE#lWuqfK$^G6%W
z0S4En6B#Z`4VPuq&%$5-nI$h)FUc1F3c@&vyn`T0uT#0^(<gIb(8jQLeV{7OMTz>D
z_H%4y3?IdgCz5bAY8TG~+r{S<HFaig%|1}Q&ep<O0|XSNW8sf0ABVbFjYaE86|pM|
zKZa2;W`xzWLDR<Qs>Sa8N-gX+FVAfV;y!D1nzDR4OWCSN^-(vSj~xduwtSRQDt!9G
zu+k7+q~T1J)%F+>sR)HKqWZeUv$8z}o*)Sgv4JkHLyj*X&H$CtGbDOXs|_FN)~z>A
zU!j6$3oq?GQPSL19slPTV8rQby!lRK;Ubxg0?Tabwi^3kP2sm7f3#~gr$q|m^3X!*
zpLUNpT+bRQUQ-g+ldyZ*YlDL0Ww<`mPl=~2n1;%V`b=o%-KdNmgAkW%u>UM(Vz#<R
zShu@%zU4ykSZ9E8omE88R;!6ybfr^l^GMB)G<Elp3+`&<4fX24{xcup(D5aE(1xIJ
z!$V54SBlwoSwZ0H2nb=wkxsxmLMQ=xN6kEI6T1Xn9#|gAe-%d+cP77+%q8MUof_q-
z^a0%Az->%Z)R|7TNeH*mR(F`Q-Vk*z<=7l&Ax-WXUzT7n-UXG-dJXIZ*ncl(1EHV(
z+70w-)57`9e{D0KWb<15lXR5HX7F=r3w3#!f&cPe$>joZz$M5qH2(J;382J#6&yao
zx?zh4Ds|%~gf|v0(XeIwt`dFFoa2UB_$j&emGc_f!xk+zKRH^N3`xMHFnPhryZ~&P
z=RncEB@>y&{|N0ZyfuK4lSJUB(e(Hvk|Z@yVT`Xr<yT1BDjIH4qw{WWJ4oe2*+TXo
zTKyWF6(DquYC>nC4WeV(K7G4pRl;s=>$qORf)P+NKW=ie5<r!IastK4g&wpGIsHX`
zt31!Xfr|(V0XR6Q{;3q-nRFV>*;iObsQ|XdeR`RKd=w&seEiJlh1Yb_Tr117dl0a6
z4S%#Z)3|tH9!{-mL5i$<ZuY+9<~6b>hKY>!jk@5qv!(M3?cz^h-dtu+ozdAw{L~%m
z#(nPwuro8Ouya?EGTP};nz*-{s@%y|P$)(K1qDQOjA*X)R*HvI6U14c!|@hje#JWP
z+@S(rv@z`Kx;Dk;)$V=nCOGKWIHa9eLvqh+?c<B97A(^bQQn<}>Kc>({bBbx9?3OR
z)f<p6cyVgV<D7_2LqpAYmUQ?zQ><9!G&)T0yoOVY5U5t3!0x)KTu+2EQ)gBYOx9xY
z|Crp@M+KxPm3-F_h9?PvaKzOXEE>ogN(>$^SBN00M*5w#ot!8|*5-?Bs=XXnOL`iA
zF%=(3!q?wSkqdT`#~yO?#s1#lQsks?&lAZeV>bbhj&@;(e`wy|k=VYZyCn|jZewRK
z-z{!N3-qtrKms!g#GmA9hB31boaCaKOs^PqhQ>zvoe05`-qRVCuIUWa02FHWs093~
z<HOiE4*jLiu~;patNA|FUi<E#4_mz-ousyF)VG16bhO^ob~s|<*!j#B`mDwyGBc0r
zFHZa)Rd`~RLWZEuW+X+CZ39csnX8QlzB-qb(o48a;g%+VMWy?2{9)H&1%OU2Lj*V(
zd-QF0JP&djTZk?2G`Ap1bB#>qjF`}gUH<_Hv7CR(u{D(wOr*zp5LSMw!br{7Wlyp=
zKhtBT!p?%W3=`8g<{ZZ|>TmC`>4XX@32xfxORfbW=~iL}x813#l33>~C4n;KbXDjU
z^|JN1wQKWAAl)GD{QIc9*}VI0Po1>wpP=Avjdg(>x!pRES2JZKP=6`vI$f!+SGuwW
z6m4nrCc-N{QAU}EHkS3-cvZIQ2G|c9I{r3u)>9Lvc@<1E>9ksQkGlK3VE%<aG6>sn
z$-z2$*sQgkFsr>MI~T<0g(vp6^|Epate5RPQ}5-A$a9b%cYO>5Kpr`~n5pwDckLg7
z`z3{ntjxDEDq7`f@3*)btwn|lgDtRsZ++y7=&}*+gZqa`Cl0#>+}jE?<>08Kjtu|F
z@lK#rP`AGmpiT|{RAnWzOOZ-M(-{)3XrlS1@s}gF)z;e|5lGTSb^^p*8bjM7n>f>j
zidm}o727}erDS&ups>=G6jW&)VPP9nX74r+5q>UEdGogm8Nu_Pf};S0%@RpAS&LZF
z63%|EeA%T2%Y!h4^7#DHH6g=x7UgzXX?))yv|5(Af>k9e5|jH<<J{ta);<tD>CD2I
zGYibl(Y98j*F^Va8*?6?Cm^|5+f>V<lgvYg#{xiz%cA`P$@U+x+6W5)?TgDt5ZvH<
z;I(ASZIcPGl-7d*+@U!c9LPTGO>ub@^yI~sZLiyH@0+tot*fSAPlNh%ii);m%WneV
z>bGzp-je5ji*tz)b~Jm{TN}`)npzARQ{o45!gkO{;x(D8Z1qXeD&Q{%UN%EWNFpar
zUr)Fw;qN(Q1NdURNQPp-)^Q=@I!D4hkegGjl2CDLMUNu<ah)w^xM9K)q8-B5@*YlF
zC!Na9jw@g!Z=8{fDz>TP1P&8gA9G+|){bCuW?teP8RT%M-J%6cG(e2`!-*8rl(jo6
zWaf-}fzcZ<=EK!CB~%{8Y`d#i2i%$uq6d@)f#<G?)cqAhP(*wd9S54IZha(;1SAX=
z%9D~TyS7)F9p6r&%3y?IBHV8Q9}pkGHSh;zaQ|t!nJ-%c|08P1<z*I(c+3LXFRB1K
zTP2T)#WnjBz0KmEDg1HbT3~*PFAt=mU${KSAMLlbqN!?yX7g~?wSt4z&5gEvAIb=T
zSbXZ>wl3cxJ8;>FyrY0lc(tEvh?!PJf7t^_f+bG|c8m5!<tKfx;zgK#Yjx(V&YeSl
zj#<L@_m&W(jI#>P=$IJI3Z(uOEO(|qvvlzMe46T_66j69oRrA8wL8|T>5iAbKtUWw
zKbN9iu9<|_W4x18cBBW;k1`ne>xj}PjyGqloF`JTj|;VX2A|qpgLvV-qZ3B{59*?g
z(oHZW({*Z8L8C!zD6Bas^)X?GgWqQ__7&LM(aa?|&)F<Gu3k_Kd`8;Zw@}F?D%u_a
zLpPLYI_{>`n%}ctp0MwlDfuoHJo#9!AFk30qZXs;PA<fK>S$IpGR$y=glXYGEs{K@
z8mVZl`Nt{N+;(JQVB}JPh;fQ>s6{VVW=ANg5d1>t-EGD7?=sOG9Gfsrwgy!uz(RRU
z`q(tXx^WlWCG?6=D#<`!gv-8zw*3y_WWx$-jOrgygFFQVAf0nW>X&E@b5nqLG{U@K
z;+z(bI(mwLr;YKEB_DR1067U}`64YZ6*xfuXC<vAlqO}{wf*E0yv#~Kl*q?rL}EaD
z#V}6cnBcVtm$z$uDI{C;v=Iuy<XZtct=t=$ef0BPu*a1418|e>&6R!A9-f?|y>RD9
z7BvM0Q@-)&#ff7y!i%&3<7yOw56P-{cb)Y1R7_QSe-cNBVT&zM_p)g@(U}4JLg`se
zBd9nzFIsz13nBWvmr>p0ppgBHWxvpQKwVu@2`+DSHN6&O4b%IUBA-HD@WO1vTifs)
zt-p0Y#HldE<H2r&g@U?tu;EjMTo9b;SClK?|6d^0PLDdg*2Cl<*v;RxiMdhaJMa;7
zc&|76S%*FZ>Kr1b8@x2;PK^2pe{cvZSzE<0*kCTs_vNB;EXFDxQ~E*Cv=Emhr`Nb%
zw(9Fzd%gIo0n7M03WR)QVZ#Uc`KRcqLJ$QJCa~7=tOlhnNZ1UJ1%Wzx1m@)Zr|c%M
zYbi+HQjN<BG4!a87XgKPPK0mkgl52|4HB(p*cq{C7aUUDwOt0wo#PQLE{%$YAQ^d6
z*l+A2yrCpI7anwC`WfgqB<A1M*Vo{S4@uD=n5~xKpI0BrE)yb`o7#obwB1_Sm$Nv@
z4?<wE+u0apy9@O%yTKAb^G)_g%rlKcO|IvTLMv>P;slTvT;R9XGHmFkyt49;+`SWJ
zfo%{-t3)4aLMZ`MXd>n)g3;ST<JB1w+`Z?A!Wdvcbx;%~&&$_R5+`IUuv=DM6b*8m
zpscTMI$dY;Z9EhEm`cN{xz-w*junU|5t&(8i#e((@un$ieDL%+FHU;(!L6o?KRV72
zgHVJ}0#5*+(Kcv!^vo^kw7;`1nov`cHi?Xy>@7DttkZ`i)X7Uq(Z5F|*Cu==VF3mS
zO3s37{aev=Pkh<SVO|I{!T~%uLm2C<G!jG(h}wuhJv_5?7$N}F0@}`GAmRYDd=Hc^
zo+nsa0QsK<IFt(^yYYS(2ZjN_m}fgL&{ag2Jb)KUTsop34*oUD5kY``in0K98EWaM
zMFX{X@C}cX^euSI+J<IUu8j%}!s#oNxcH@eGxA0!yb7=L3fH}>WT8-RZ*o8ec2<2j
z(SY?MSWdpEWz!rblnFX#juO>7CHSK|9yP+*q<52gqe?Ow&%C2y@%l0YQ>K_dBO7!Y
zB|(41&W{YyrHXGruqSa(kViAnZX&2IJdTsL$jaZ$WcZK*h<0il`s4m-S`Vmdd;gYN
z=U0ZzWA}wJKj%)oFvzJnH&3H~^U#pd+~P3zXx*arb*JoqPuiVlc|T^uG`o8jgkiHi
z&&{rWaZqkK3G`Y49+WHMmOED04Iv8>B1M43k!0s=zIXF!1rMPl4Q09WkR*6S=>jtQ
zI`K@qM?_YOBOlP<jt4AN=h<ee^U04u4NqFy3VnKxCxK<!DN}@b`bpC*_qBUJM#w#?
zR=+i&c@lQA?IG}<Oiir3g^54d;J;TAiZ(~49wJ$;z}XYHvqqkWgEiP>=hpc`Mk3bh
z{2sALXm5scIX0maIqaE!r=Cx!)XJc-722CY4pQgdFdM#9HA^}?N!ETF>Gk|`i=2$D
z@r1+SWGoj~b`+)pghej)9L5Y5D!^cS45-9=wP0RUQLj4)yujLd%OZsN8~=Bm?w?uV
z6X$TPXon!#TB4w=B3(2x;54vN{7)k&+SB$fwj^=cYlsG3jsD3={#ErBFS7tPGXYC&
z^RS8W)<Uwr?2%wMS$`dZAkk%JS%0~#0h2?3n2T_Ic(1;#Z0K5r5-um|r#Ilu2VKL&
z0$^0~bYAy}*}{p)>nt4X-0tnux}Mp+EGSHgo)4JOFzAKefggcuT9nJ5RH+h)$(6?`
z+`lXAY>}>^kza3#@Wv@&Sxu72d2f1TyicQ((RF&d#96`h?WX;43DN5-{#idiJ;MD*
z3yG;B)o!D#WDVEfmA{3^Pa)fBwfl-alYuW3K>O9k#}{?#=>cH)*FmKn?(gWyP_1{O
zR=!t%O>pJT|NU{Am%`DEGqE;fVrwJ$p7g=tb^#2o_lEC$X$YHaQi)i|%!5fvhJrNN
zK~jw`&qgmym*CGOj-LkCc3XhR@Ol>&L6fSbl#OX&D0dqYlnkb>^+gBRW>;l$^ELBi
z(Euz=U^C5^x)K&ZHH;o%*1et_b|JkgL4gLg?!yf4K>}~70BI!F>tDxHr98$<IN1M1
zKA2sfuhYgDZ|cgDx=r<aP+FL6wy|n0SWLmc;Bi=21!~w@$<7ke@sb^A)`tt!`IhLn
zWo3Hi0~WGhQ9o^DPheGp=!!k-C_3hfSxd#6ibyo^cGtnVSXFWHiO-a^wKN{gBx$tp
zcEU-Tp)*~^>3v=rsJ5f_jX!)dm7dz@a>Cu0sMH{c7FcPuu0|^H9H6immn%ZA8NQ-B
zXyrbAuMEJ4TTRQ*>^P4KLr<MY0Z|I)t3NX3@sl3VD3X9YVd*>!<J}^fFp{9D*TX&`
z@N+e-T~4uWw3@_*kfy@MPy6(s_WFcD3Ds^T<3T37bL}rPE2WY})ckZJPyZuXCI-vh
z0#R`2nNv!WD7u;F5{%|;P@5SZdrivjg`2-!$?ntpay(=0hrE=UTuClqz-p;w@l-P5
z#Sl(6$$+Za1~Mdjo(uC6_Zz}fu~;kJ9I9NA>}J7#mc9llyP<xz^h}P%H=hR7GNKN=
z1rb9M(|7O5!GKd7B{VzBX?@4_ViamzraD=daG`}EBw6jXDIVC>aL~($h?F-6GKBKI
zt%(roQXp$|!Bx?q+?t05T#1zP&vo1-EG)nAr%Ec|Oe_?`x7wio;l*brhfg~Z=)4Nq
z9}kd5{VI$n2Vw=1nQ*t&9TB@`cTjgq28F1xlF!p;Ma}he<NKEWW>f+oGl>bF`p`&u
zQaZT!OO#(5H~-qSw{wUs7?SCxAEmmev5`L|by7u_mmYIEBpV)TeDzutZ4F{y%*5K*
z8H9$A&qHbq4BLkO(gY(crMcQb`^r{GUt@fS#&|R5I{;R?D8f+2M>^KY1PfTpN^0P8
zSl>4o`g3O%o~C~6(SSbwOJxafJ;uJ;Y$jGSSCP?kaeRg(?vMkEQ)2$~@?1frvZC^@
zAGaq#yz%OSB*%VtG}FSdQCXr{E5xNtdP;;K*X!K6v`C0<{tP2Q(e^l6j(NbAC@^=G
z42XIxkOe;A%x9R+d1FIaU5D)}n5T~qFIdpDca%8{#M485>y__)1FQLyeS^typx53Z
zYF5PTWmW$qYGb%PvUtD1g=j6mJBgiUphGxK^Yx_;_hqxOkt@NT$=2f}W8wt&L>B7B
z=Z}%^$gJMnw17T+%h7&Id3GHcT1rlm2F!;GS7*^bfqBk7@+C`&Vy-3~dbM3)d%O)}
zbF*}wC+a$&Dw!SHjMP(SiBfZE2<;_2w)Fyse;E8=?pSyq9lr^icFeVB43sRFtv!5+
zkeV`Ghs}UXvNDh8=w(w}ZLNlqg_>wlY5gZ>YPDpv5EAH{${^2I4R8oEQL~)uG03Ex
zm1xzLGU(~~5n*+PV-V*9Q1vS7V*%>!=mEb1?>1*I+5Eumv_JxRVF9A29*;SenQmB{
zc#*z|_g5bV;?+1uGi)U1uOy|y)-~w+tz^_}Q|jIDXVN~ojIt`I)FL@CeCPlNEl=+q
zqLMADS7hW<Ad2ul`#5?7gSLosl6BSZSn4s)q404>FlWGapTkF^r^v8v!jGla3Q|Gj
zk!d;;dJI>zX;y&6bQh^EwUQW6t*PNz1NEhsL&GviO|?V7^_^w2!W*On$lGE%g)Y*Q
zjzwQVBcTJs)Dz#ByS(B|L0J#Fi8YO8z|i)<wp#2^BV2Z@bDS}kp$Vz4axx`Zyag4s
zoBne>faz2ofoyLjl)w%!fy3G0_%L=B1RoS}!w{~;A1B>`cf`p^hE0;PnpZWRm(XQ<
zx;RrT$G!Qg^p(5F<7ag0wq)r*+)J7+Ihy<~hx~@nle`_53;PQ2-WbKtKDP3slMNl8
zvL}swPE)jH0rHI5y^4@OSxSKGGGZ*R3x2KcShGDM+9Fiv+IoAkYHx4?#E>?)%>~%r
zH5P>M!yncb5;W50!tdTThtSGKF)P1dvpEKnSLi=5jzQ-!9@($E7$84`4&*$FLTfMM
zoksCWY!2_kM6g3jfFT3HFR^;}kboztfI8Es5-E<%@t9Dq!sWJ8rlt~`@v-?Z!=kdA
zo{AiJ+xdb{R?fW;T8=CRj!NMEB!tl3_Db9p{QIKIDzeLM&E}-ivi#v{fMyT3j{VX$
zy!~@r_DMxEkSbi&Qx=vf=oTcP)Yz`W^S2eZR6V5*+-MYwv`~8MDTuS_2p)xe9-vQM
z`!HU+$-?AC{obuKy)^{KQ%(VAkPfEu?&N{B(-BAWMVTNXQPlz`Sc@s6$HGJ{?*lvM
z+z}4-#{&Te0%dI0Mk=Qwat{2|vOD3C<L7voXX}EgBct1e1#-Bc$V5QUY*zG_H7he(
z{4}Z=4m(q43FkfMIMS`Tz5`qDiEc;l#=ZDzG2;1{QNCdnm#*oo1s3rGVf`<kv`U5z
zSOLw#!lu9uO!tsg?Y%^YGK*rKYC(F!k?>|U_SS6jk=d42mm^ataY+cQ#N+V`@RCtT
zm?z2{ku9>E!<%d=%Lk^_$M9MMH&{ux(}M0=+Wx)l@`r{A5k!%y(2If33Wy_!-M~OC
z=S`3jpaX_*;K)nNuSnZbGp&<X8GcujvLgQ^jq7DJPlO<$QuC}!e*g|fJ<>=kb#<R}
z&`!nR^=mSO95_UcP(;z#(3YkiM@TaoI>g~V?Y6`%qKHj^t@Z6HW$EEk@H<X{-;Gov
zSWFe@lf0c6y+<}j<76vJji5$&6135L${7{r0^qVK2ucuxv%xBAah9*La0_{5kx^w|
zc?7%wG};y6dm8IH<zzqv))!}pn#$XIHTl$ZWh3jXX~X<7SN*G0rr!%xEl+(2B^*0G
z7~y+vO*l<pH2%-+V~a#^iG=r>jhLYy+Uf-Hb0@8lQQSO4(3TF__>9rkxfkDh%Q<6R
zw6@0A2n}U)KAu2fc5>LzePKuq5k0o;O;Q`M#QK8ec4tx^`SM@m9CEqRAA{a=LN7oL
zN?gOX4SfxUkl5i1il8lEV>*-_9o;HRMvW;le`&xUY3_?)32aIKQ5@sFj+IpC#E{;D
zE}W|-`B7ZvP^S&iA@nTJ!6}Q}UHHASW4$ete$h{AoJ@08rb#+@hmE1aILFd-b?6!e
zoWm#fZ)hX)wc@a**_!svD$vRJH6N{c3Wi^=e>eCGm->`ZB>$&?XAge(d$6r##33Ps
zq^#T&-x15B1^IdR|JSC_-wE~j`L0o^u2k%LPiP0WX=2qC9P$}6QKDAOg8&1x3Q`<{
zgQ>aau?xZf=C0YPn9ZUAZvU$l#5nItviO=hWkZ<bJh&CAf`4f3B)8J<R0p&w3Ho_}
zF+kz#w2hc^GunvZ#RBG&wCRzNVi+jl!gb`1^|cqOnrpe_L162__d8HqnZM7zdqtfL
zO$C9s2*QG9c%gX2h*;;+^%n8M*w}Q&H5IPOley7070F10JwEeUy1=x?I{Q0LR1Ph+
zh!E%p5g(u1@HW*{&ApDKWJ##8;z;CiSP91<57Pj4SKI)7vDR;1l<QG`oNX1c>-Lj|
zP95Rg68D<2ECvcu{-U!3wH451#sD!=sm#=8A$KRwq#V98+BV3Pw32uMH9pc$1NJyi
zveT#@34$X|%An`)-ghiy^I_x>9aCu~>>t02*yzW#r6AEE4R5}+D{@(N)=tSnC(_@A
zy(9KJp%*P%y}{1p&iDG4p-*mDg#8>d0xbxtL)f>_R1vB@v&OR*y6yntOiMgVtsp+a
z{JqZ7jX<hT9sNgud`R3TDH7~^OZ^M!*fgBky2$d@+w5-bfx*9U#sxOf?Bl&RhiFc=
zR`u`gl&QE&&c(O&#1?%w|51TMQLRj&Nb|-AZ)=X$8}rTV$X_4~xeDnR9*BDU!{oO7
z^mKcdxPBDWHv;Js;Xdtia4W!sklx<ET7A-Fi^i^0p|=_x#igoH1;)?gDDne>yT2R7
zZjhT;6Kc$!>84L^jQDPV{DXoJMTHTQVKYs-!qHrTXC^8^n5Xl+AW+1rcs{U<^*r?9
zBI%vOVfi3ZOzUq=Q)oiA3?Rad9U2N?)>WlpVlWuaz_Vi{4g6pPZ<Fd2MM_*Oge(;1
zu$At3m+FOx958H+dObAOKWckhl3s`Pm_<x$2*Vx-$maSk&oK3;Kf1!c)W?5W|DU%M
z(}11qAX+iKhdkk%FP3W<;g-02q6qFK1Q>T#Uj<uNMi``OPUus(ydjbebQE#mAhV8C
z%TIDNB&I@%GtauE08Ju(yq_M*HMrCK;FcFbJ$JFTLITA2(E<S{WK*|dGnGzA#Ux`s
zIiul6h&ZU^c1U%h#ym48CCG9g&ca`SfZC^71?BzN;MgKZrr|milj(?F67GyUmVW@8
zJ#$4PD$lrw?kZswGC~0S)TiqxeB$K&#Eanr8#XmP6}vz}Qp(pM2z3I|ip<f;QNhL|
zC?S-y``34VIJpA&2WLN2*E*VVu<&z#b(%~LlJAb$j+^FMOyFO7=G)wC!9qlj!_mD7
zC%K3}*U-QQCtE*7DaG|l;m*FAt_s{d`5c)alc4Du5x!%9`yXaY!>9dHDzXUY{KJNH
zpRFoSxHQ9R=7_mau+1%F!$!|Q==LaMA_M#97d-s0Jx4<-Bnq~MsZ3o1X+Xg!S4GUr
z8oGMwFwc!MUz}s?6I~>|fVTldbx@R5b^I26T8ThoZ9h#h_}u{pV_-SZq%$yFBia!U
zecUPyV&nmDZt`rP-?MdDPNk5a;rSOk48lPBM!0vZT+-ytg)6Ir5Lx(?WlPXkPoZgM
zrI_XERlh@y_S*4rc9#&I(o<O@^po;K6K1Ptm}p{aP4|$KC-HCW+qqzu-xtW#KnICD
zysr;eWxH7F7K<VVu2(7uCXF%HS9wYSS>sU&%9y){zG%!XEq~2C3#gH!Z|-}r(>L{|
zGtyc-3GbFn(%BI`Zf-V`flV9B_dxsp3ee)!5^PkwH9m=TL>j6nXL;prx{4Um8U$Yc
z^gY{|Mi*KPl<wwtHUF?c9-IxsFb*x<E50Pu9*`&H8dw*HpM{v)et)uXdT33Vcm?57
z>R!Wxn!Mu|<H&-8i289Q+=xZ)jcurcfcN%xHI6(7`Avd?OV0EeGyk=^-#pgIZo=Gz
zgbt1CKz!+)%qSx<iLjzoOtq`!7u7DdQq}$(iv<E0aTyv(dz!IR-WCE)C$m8*^iz5{
z7_xa65f40s#RpUZPO%u|oZ>BG2MZ^%>l#V}d!C@)LWNM-^^FZ2W?NC>ByKZAG9$rx
zzC~KgFpDbzUE)GNNU~1BcdV;CdUsS?LqQp6>_5|$7qfMrc6ll2f;d<)P5|!|PZJna
z0^z>lbjl>VAw36u5|+$DBM1a35`FCok_uDIEptz9$f$@8;Ob{;#(JbZB@aDp)kTEr
zSgV|(Y<=8M_X<em2%l<ee9v`SKSNuJN$W@Tu5vc0;WqE2zn_{WZn($r@^0T0G!TrF
zSh12QvG*}`q9^Wy!A$^DHk9WIFP^~`<;DCwpS9q|!sAroL!u(_b}<2Khi`z->0B6!
zFk#-aVEMb1G*dvHXOL1BR=tkEf=$^Md*{<<|1JW=2S{?09A+Fi$TgudM$N!XOk*1c
zE~c<SdZrhOw_wxD@0l;&tCw_eX#J}a<KI`$5xmhU1@rO-1XP|^i^riOtO9-Zm+Tzw
zu)~nw0k~EEZR2TU{s*WsW6qU{jppADav7r|I;d#rO!>`e_DMYCrh%RP&{L}{Yg=#W
zT6@-pjrVNdUT|Qve?$&0jZ~Nt#1&r3NH~UmB)`4>U<q7oH4l7d!CY3|p8<)#gnr?%
z{z8v}==tY_iZpPD*L8Lm=w1?43o-ljfD_i!U}EhW1s)>h94qq<7NDSH5!L~^!(w*0
z9+qhBCND{-WmU$V@%^gD0t*$TWF4(1p)w&{5ZME47z^azf7GuU{OfrjCYg##YhNJI
zwy;rzh%*Lkb(WzmjdbH(PboYn)*@`FE)+ricNz<h(-uG#D-IKMX{{@HDlB$(!sfkv
zasG@T-JTN+F_3t&>HPiJ-jKi_z6fvKx+iKy5dm(pinsyZr&rGu_}-s#*{=2w{!U2D
zX<NcWVXpjykyAv&#Ok1*l>kSYMBmEvc~Ivq4;=7qXJq@Z3dy+r>*OOcI+LOnLh;rD
z>`nbrC?*|!vI}!cESlqQMONkL;V~h+u}AF3o)Ob45ZPX=n-v87T(REd=)RI#XgmD4
zP*Oq4kI|0wNh1Q?Vhg6r*5Pp>e%ZB$CG7r@CfB9kFPx1qv==m@*!H)Yo@Qoyef3Da
z(9B*9NM6h87x0c@o)JeU#)}_}50$M2_a~=i{88qcOi$)OId>!<W_$-ZenWc?3T-O;
zA6+^szDU?d;W|wCkH=+`kGQOb>{wC;Eg^et&ntb-=M}*7!29m288#~)FYnyjA_n%Y
za+v##%Wyu{Z62h_aa`O~83!3Si-e0Si*r_qw|r$${d|fh-9-6bDr8`m!Dj7<NB0T2
zBX4t^5=vpnMLw${7QRmzd{Yo3?b*k9Z3QyW!$)mSl&Z%rS_mTa+nle#s9=~+M`qKW
zeaw?Cde&Zoy^1}<5}sM_MD`@{$+*_c1qCUR{Yl=AFj*^wj^<=>M{&11p!t;rv!QiP
zFydcQ#|kU#C4+m8fZJCs8h6Z!>3<~59R7Q2e-T`8&{bfQ`<6L44dgKeei{z13Kv$g
zS76)+xl*W?cS>O*#x7i>fkLG&a*-NWRD{!&E#2o$ns!*~3Ieo7)@q^kd*2j28FL1o
zm9nr_1{=p~=;LMyKTrP|CWWv)4$$7OBc}TmhzHTkyW!=Q28Tx`%q?+b@6m`{T=#WW
zeAI6!nKoCmHo)iv!j9}YzwwKuu65ALiY>NtN#TR6Vqsk}GBI$Sj)l$5hg4xpnDzL4
zMCCyXROqIU_K-y&FnQSyyHAJ{1J?cF?c5r9hh=wIC&@h-A&I#hnP4gHJd1PJ4v6~;
z%&8j$@YO_^bh}bNFwzq5St~Y@3p4u!GQjh*z^7(3Pi>*kNCH_-pJ)lBBgk-A@t&n9
zyXH=eSoR_@y6SA;>j2+6ltNgUjyI(NN<~y6z%$$vsUT?^MaLE+e%}eo-~!g;FEt#J
zQyn%bSp=AZ*J*t#D3*ab`w`?sK@v6KR~`tKV>&~uX^O1Gx6njbG3PODsA>GczGhcK
zlkV9s^zac$C(7N*Z)O9DeyX+$nh;*4?o63dC$lb0P+D)z9#i+Uaxp!4G?G-~FsTbJ
zuCx7wOCgv-1+ZyK8dP;|Zw08)@`!*G-tXRHaAiDPpBrZ=pgiOzR=i$MKCrf4&sU9!
z#?hTMUqjp$T=8~0e_8IJqT8HSxcO;!dZ}pN9^Ep*xWoOv{)!+5ltyGYA%yd2advp!
zmB!DlBuGL_EgP<5mpld?d@L0JgN7`D<aijIQe!WznErprAFkYG<~G9vaDzu4NdrGA
z9KyYxZ(WX}#D#zE3>wdMD_E)qtru3-(S(axU%agu$30(!$j8Ynm!(IYOdejoNUINT
zKRnVIz*j|W${Spgj45w<`&-9z@17}@RHJ@*4u+n7oG%>gV>Uy(@2tLSJCSO#?@>Oe
zH@8%hNR2k?&7as2A}$I7>`;pOdF?_UpQanrk?zKfw#%jeomza-@pH@94>uA08=|>E
zju!W~!B_rxYY7S|S!LvwzLC~gSDV^ebTr!;{+5tKk{DmjG(tvFuwXXdWSNL5uP+(K
z?)z2`DQmI55WC*SgW@PMftc)-rJYEc(ut@n(zEr#96oT|*%cAB@s`}D6sQ>(dMVR}
zR2-sI&ak-ZlAfKeel{9_FLYpHM8Kf0f{IGKb6qR3i4hvQ#YwpUZu~u)t~_yBV~I;2
zZ(Bk#0OP!6!lFR>>h5kL%B{2|LykCa(z_Aaf-&N<=*KE_8T>KlpRR&Sf}7fJp(=dB
zS_Vs=Rt@7Om#$uTvDqdnf4&tCO#5f1epAb|Z%H9uaoA2+zD5QZ)7Pbdm!W&8qBshD
z_3fY5&2j}}noUDrP!2J*txx8E7mV|)n%4?V?1f0%CFO>5aa&bsrBe;u(OOuUi9!-G
zhNa=}6foHCMR=s*qX*3pxPye9gO0qC(Tx^96?;+ydUQUegpB>*VaT@ZOl?JplrI-u
zj5*CJpcOs2@E<L}tOg#)Y!!<dw~<LYvTQgqu$(0;BAIjV@ly=S0TwJcP)HIO=;O=A
z5jA7U>U8~J#!Jv|Lh{e0a3=TRAIw`UrBDVWlUu;1XB6U4#T<l9pG{&!8D6D#Aa_as
zAp3_(1zdi<Ez?fQ2*~IR3ePHx*98c5AkzUoHHt=IH)gIsZC)Nxz(pb{xAN`i-HphD
zFIoq-Ba8lQUP6x^vOKnZh6Y&-h)c`3KoVy~=FWGNx@p1juB9)caCmb+2K?7s0n5nm
ztO!SRA?XaJEx`%S+wwBtU_u3F2=NBDK~GUF7x3t2Ls}P3fFmEK10Eppm*M&r{Q5bN
zQ~w|NY*lr{W8^RT>l#D09$u5(ZG;pS09e+DGS4e=O?Y-yHqeMv8~4*5UN+R(;KREU
zi%#%PzrbF(Xfm%s-RosM@|aK^7KSHaCt6r^j%O=1Eo;)j_NZW)UqVfp0{_N0<c)4+
z)leMOP0S6h6G}5{Nlj!Z4R6C#zq4Gyc}q$q&y6MPqYGL!6lY1jVn$b`m3uqkWvv6P
z;l}GC==sc=>GJ2^u4Hysj=Vn%$cxy8>U5^6@;z!m8HC!W(9zukP?Xxyq8ZU|Jn1n?
zx`0G*6pi_Lx|jE+TxlQ)8S6orY-<U7lMD?V^AVjfn34n~Vg5ifj5>kXa@x7KF2MZN
zy|3lH`eTbhFuQ0_iQVEx-(y5!7mGo<ns_5DEMd5Kr5(2V8g6`Kg_Df2qomLWSHTLP
z1@%Ks_bNZw<n@nFvD7z48$Gc^=yjMyqC&Ft;t!?At5*wde*mv`vpVvI$x#VQoLUsL
zKTyA17;by}DKHF!HyVr`W<_H6;nNo!QX~~dA(iAoB#`wmZodxk6~vS?N2jEi9j}Q5
z<3Fo$=wX|^rTlRJzt7C4x4*<JUo6{L<M+YRAI&009k4cX?J7XTeWR785-DkdxohNj
z8H}Oy9^T0g#}N+%#U;0DzM?Yaaxk&1p{K^%+aW%XTi4qDf<eXmrc}xLq0wD5H5D!j
z(e@Dy#!4((b;G3(Mz3BB|4EG5%BPGTuSJcS>f`30fWJH?2^DD8l1(0blds?vsrO@z
zo5R!xss-n6lW%A$rLIWwylO|YI-hZ*Ig;Fv`f<02q(vq$y*1IqgWHj#>20epSeDUE
z-0i!-HHTs8J_^l8R1uRI5#}h7=hpNUURv^#gLR{6d#+|T4PIo{m(=b6Lh*=d&E`}r
zQrVs&|A9haG#VD7Z0WEsP)Eq6k!e7kq#g$D{n*KOwi`OSGfyk86Dr8lNg*?O9rak>
z@Lq5Xd99lrGWaY>0+x>FCN}{zK}_e&^KAtg7w-5<^rz8$H~aUCnK0%@Fgg1&lhb}>
zwz^&Z(W6{S;XEXuW;FEnJGQ&G>BWwaR7yGSt<yne>g67Lsgq0sn94qy?*KdH-{LIV
zGsSLPZk?5+x6d=EX{K~?RY6e0NRz+A(%jxmpuZukT}GT{A1iUZS?D)Lfl%$2TQ&X!
zdkInJRKW3J(b^SkPqFrZls!7RLySej^Wry20wfZ6cPm=S!pHcq!I*$}QVOk_F4fhh
zvx^Q&$TR4`#3TcZ{d6M!pWW~7*0ge31KEt0#jW77_>sC?%P9w6Wy$^~Md{3)Ph>R8
z=<-0%I5TxonFL<p6TWz$WcNN=(nYd~{4$J$v2D*CYEhEms_Jldlk{Yk2LB3p@W3g*
zA9}&cvpjt*CXy%UbE#9XfI^V0!O3%8851GS!?18Apj;!ApoVobu7YW5&~J_(?Xxjb
z_NM$fVI02^K_GP)c=c4a^5u*%boOzyirKcJ@UVI$G(P;yWCelrfutsMUwvq34I+eH
zub=XS>~$;V0s?L<NUzPqlVWaQ8OoxQnMD2@UX@!J-f_ZwERDwV-7)bF-wT-1P{$8h
z+-Sh|LsBapU)xuZV6Y(l2)qXFq$A7HG1n8%eB=1~EeT`V1<?GLOe64(Lsto}`CRj|
z;*Ww3bsLAG1rVO5AkA6@v9b{HvEaS*X5}LK^!?`d_T}h4UfUlA%vJylv)o<w1Km7Y
zN<(hef4b{C8?qzMb&qOZoR31HYCtAqp1dFj=yoHbb;&fM78cO=uY~+G6k+&rU~`@o
zO&xlJa(iU)>rSNtKIesOMR8tmY+cuYx*wz_IR+x`46_Y75)Hq}B+`pt^4b8?`d@BZ
zoQ)%~GrboH$;~u?5D9oEQ&28=H<To_8ziA;jnnd8hT;%gyKO&TcCyO;^U7PsWDmBF
zsLNaMd8MME;3`^vlg2Eu0nx>q_nzD42fY4SSa9u@tU<CDY=eWZf`Hl1FQWH{cbI6j
zi}OlRDgZ|~E_NHpV0#)K^*Nqr=0B>0jBw9H8_uzJze-@xt{Z?d;Tc1ltL02N)?GGx
zyVUhstK1vP*i3m9D1^PMbEWd|rq!X_Ir=hHX{EV&oEjt0rILy@_3(9Y0&D<XuEoUT
z$y@k;)*JD8kvR_&SIfC9MR?}P4O!At9fW7GAwvA-<2Od5KfH$P`7GsUMo$*ee#?*<
zLSYV**DO|XRP5q~V;SY(l98Gywjo6&3QP;}t&pk2<iQKV22UErx0FU69;A<;blJDe
zM^3|iu6Ox;U6Qh?ECxq+2Z>!RRXzjX3)-(t5ciNR756(PJ{VHsQqRsIJD28}hTP^D
zIt|89FoLg|9i(^{V~tBwfg<<g5&y<g*>Rz|2$j(zJ0^=|c{+rdP0(f|RvGx$PY($S
zlLM0-oL;vsn@KtuqrwF!s3B9}j<Pvn5w~I{OK`sE3S}z+6S}IxV{=3@j%YapOf9Ac
z^;+?&w5nGR8)9E%qE_0@FgNywx@`?qH%_adkIRLg<uj`5oggM6C{??L@P%$8Z$h_u
zDB#J^{&R?|Zj1L(At-(?vs5Wh<C?9D)2GD;9+rRiiP5wMn|?sLJ{gsM@L;;Q7#Ry=
zbN`Oz-8U$Y<-gmKF@&PNfAqVk9@OfRd@~En#EyboBc8HMtO?eVI^!(iCKf%OE9d9r
zx`^oEnn|i}`Q^eW%`^LdmL65PV-3*WQIT0)xzdsV0AtYxK>=s8ULu!e>cR4DNbdhy
z()dg{%s^nsQZV{QgwO6-8=EIEG(E^vnyTWU{!AdL)!`*Lp0_ja!Py~rK!bp%nN{RE
zlma+XU7tR3Q<K$5XOr7(D@me^2r-!t0ev@7Hpo&a0xKBuI%fL=k4K|pw!!YP@e;M<
zwp4w$QATTE;oOG8vokR>P~4VDvW3<Z+^`OUR|){RgU)oSR`O!KayHG$<>!cJDPWJq
z8n+uF4*wi)m$-1*M6L9SjD!}Lfv&mbfCRu<;&^*BHm`%@WRc->Q**^(#LiEQ%w_??
zLcFRVte$Nk$z2cILkWfiFHH0gu#l0nvR{QKPrhF}*q>5-=Q(r#)AYR7C3@Sn$y=wl
zb5bwV50g96AbB1l(0G86KeGG#hZK#G#HS?lYo=3BScw)nf6T>HwGpq`R=9eefVOg}
z<m?R2c(j5StzyzMXbv;xZkBK6jg%5$H4+dzDtA6j|Aqrb&`Vwf@ZQ=gNYW^dEg6Dk
z?q3l^KFKbIoXIcs1~zCkI7q13?Z=m~0KKh{4Ydl7cZ&q*caV4!)7i+KqU+&%8X>Jf
zOiBm;2n{FV>2kuO{SuP0F)WgY7T6w%GE({gU014<O@9F_vTxuL*BFYD??|@3J7kEh
zmU;Eb1rLqs^WVKiwiKG2Ss(0409W^8d?&><<}OT}jd2-^FQ&MQI9yCf!>o#sk4z{2
zUzih)E`b&A;G?9~z7xuNM@aGt2kBz|L-c8;K&7q3OV5rCk1nMn!f!Q$ET)(({UO4r
zw6Um>>7Zg5tyxm9dIG#G`Pj}aMChUpUo53hutWzFbJog>s~%=H-_lN|Rw7zr8>d-O
ziI?MrrNB2|WqUTP%GWp?EjfEfc0-MS&!(F>Wv9ua&SV*mEKR*XO*AQNHL6t-;VBr(
z8fJ$m#Uq96Nw&k}aOcG;gQWlSB$3v{5~o@m>Jd;^So*_^*9QEFNKdYA1$%0m>&rDe
zO!sb%T=Jpv1Hm@s0(7obpYClorrF(jhMthGcKmTjZ^l}ojX*d#H`<*Xm7AF9oxxom
zs^+qelk}1f#DN{#f!d=DG7zyQdGGq%%{ex7rJi-i%_lEu=dSr^h!9Jh;rq=;om`Oy
zC7x}O;TmJoeH{Cnq~=BdD?rr0V*e0zWM_#5$`CU!uvd;??diaC{G$3yu7;!TIJ^hV
z+3cW;6JjIMuFR0!?1=T>KtPiT3A;YF&<G?kQPR9>Wi%x$2KHa=&jRp9C9Y6OszxZ-
zSQyZB$~Zmb-#~E^tNsN766eL{n2z2t2~E<yb1P%oH$h<lk|`XAFYFSB?7%i?IVIWc
zj&*j?kje;}^e~}nB-E1CrjgICASB@wTY+O?R*p(3Nwgo{dcb8p#YPNlj744Mgkb7n
zRh6ENElTR@nkP&pBR28K;Yf)^G5g2T!uswA?IUX}PC*>gwmsMSI343bjd^)EMHS&_
z8z~5!OU<{t7GN0zt($jV^{Hdnbs`OCX?2(Yh;=c)c<$XU4Z2C*yq5CLqG8H|65kaz
zR$SB?DfuBSyNkPfms!)x?TX=}8iHgDMbIOf^$URjC$h_tqVuj#X75=R$>wd~&H@C@
z83z=#97bOYKo*3*lc?oG>bO{z1ke+KO=e~IX$5x^aUI3V@4R~NyxkO4r5_~Z6!_aj
zd`#KwNt-%XG;UA~DdInyizI{W&h%S&BqX3*D%pW;y&Je@q!O?;)^d%ZDoA>fw0uZz
z;5(=SX#->^^d0Gs>02vx&rg#Y*zz_vgzwDJs+36WFUSlo5>|R6-jLvg?wSuMWoQEf
z!j!j3@~YtZ0UUP^N2_k53PQ86TD3N>24-HtlRhc9Gc7*$G$ZbfQs_(%rj8uxu^|Wi
zukfGWJA{1evy%X{Y-e@cT>}5yZNw;69ziYqNvgyjN6is(E!JZ@H|a;=&_877gat;r
zp91T-=38F`$^+i2krLAEnE##0Ot0r1FfIyz1O~HY%@N+M3A;)LFsKeMk#q#gVVxHW
zx{Wd*`3u+9SNMEzV$imtH;w+4cji6OY19?_(O)f{<@u|g6yR(=eE&W_#93n<+%$0<
z8q{l?<70XBP(u*LY|j=u(b?BtN#LJHSsC-J`901js!Hpj`qfuI3sKc?=md~$_988e
z2+IvNY&TcQ7kys;Mu=Xc_EvW*l2?Uu&^ygjtcwmchc-xZ{u5hCZ8gHz%|j)&aqcGY
zXL^i45^04>)`#WS_m$)s_NKhVl5yknf2i5wM>P5)TUj(uROAfQ>?aN>YFLAjI94br
zp_I2-=DD1otQQUa1<{`OmLIa?5!c}O@v97}6NaS-#yI{~Nta^rnG>lzugPpViV%zV
zx0d+KY%9oKpU72+rNiBaXiOFdus>(>FLc5|{kI*;cP)np;wDu~*2Cb|)@>7YZ?)$8
zo=m8%F83nV460P@MsT^i-pZ?XOQ;6*m6_9b2J2)OZwPOS%V|_V0u<H`dWlTWNBudo
zfg<kK`3^yV%n*XX>y7@$8vqx38`hmIcdHEsRw_s)ig0ZvigE!tnS7x<y5g0+<ExB4
zIiX#WdwI2RjkeH?8us$^^H^6`0l*dQs9ze=pyk9^HxK%Hq1W=Rx{PUyd5YUkldhez
z?yJ`^%xX`bhf4`0gs}eu|C1SVwZ$6#wSU8EP-w@2ES2@p@j^=Gq77FvF9$Ud^I6dO
zUtrE;gin0Q1pM%&0SIDI4+95r>VWLXOthZ$<nJz=Q-bl<-Fl+Qh>HO5F@Ce>0O(XT
zDCbbj*_JBD3P-w8QvnAQ>636HhPt+8$B1TaBm@pKiJarYM?+~6+vnc};W!ol!BF!8
zz>!vAz@k(eZhu?id!iIzSJZ(94odsb<z9KdlSnztxKVFtDmj2xT9cGIl;G*-u)Xal
zb|&-U=&Qwbpn9QitpRLp-ns9&Pw&RmzYMDHdQF|9Q0g!@9b$vDwmIVAfff)1|2haU
zU@7uRTJz#{8I8{P`Zav61Ef@lp(lcG5Rq6hS`^7W(A{eQiO3k;ds5iXL{07>(tK1Z
z4N=ze2qxuJ@v(v)wRMrLVa#g9+WbcN$$W_Y=CjG4178Vu0|Z^&lx2uzBtM$8=<0FI
zXsGC{QWMd|kcKFjU&0*u`X{j5=9<pho?cRz_3A1?xpsUH`gMSObs;{uSSANfo8K+D
zf5sEy(Z9&Q;&v4YUCf7)How<kyFd~56{4e0oVxV<ArCXq9?fT}JG(KRGth|dA?G}x
zx`i&jl3G4K!))yC1(}V$8H63rnfXILS{VXF9F4W?R-o_~-JJa+Xn$^n;5)jZ0k3q{
z_@$xx64KMLY)&5k!FxHEp<;={UsgY)b>;X^_6Yk~1(;WUvaJy34pcFKVJBtHraAB|
z99t?`$Yricbv}W^Vf???ZOR5T1L^q8EsF3qQu*^h(q{}(2~`uQ{E==NWy0hewaQr|
zKv&J=5kneIlYyAlUi*wmTCT6wPYASIuGEs|8*43EiVTUP(XVTTcBwS5H>$7|f_33!
zVM(bcwsSY5ZVHGY6a>({XVcwG8@^Cowu-0Yr@9o2cfV!vd?4KaL0|par_mDH@^({D
z_Bk3JklS={5|RA<mG(=)1+oOjSs&cpYsf^}Yph^O{nE245p+V0f^=klR(KyeVmb`T
z6na9TBkB#7*ucKo9ImDvSI~}7b1E@)L;m%S%$ALtd;_2h-!$jpFYl*?fyk{q%8_=_
zgNW;-NdcqzAJuU?RCQVi=5&w1RpbPLVNFK?ml}}bvs09f*RV?4BUR;gSVRs(FwUS@
z+hPMfhr)yknDWDU5&j@*eJcO|1Kab^IyUtrrS0*ztvVtL79<|7l~EKYOE6zv--|4L
z(WJ!98<e=A^716pH>5Mze|d7##HhWff;Cwk>lVJRXGUM4ghawo3;4a6R4LCeQ!FJR
zJX3x`QBw~H&?M|@>!kU$zaPS6QG{z%Od@F(e71!g?Fl67L18YmGps{UYI$NH=zUvr
zck^H_mE0{=!3|Vx?}W=pziyhj!>d3Gr<_%(mM#In9iS*dnN{u?{2mPPH^eLDJy=$5
zBQnw);66?SDp@HhlM)KyJuXpkLRjv~5XOEl?F-RKl74$scm!zGhvL$cpV1^g?{ilX
zI>I0RR%JQ4z@yb52M+79_oW@dA~t4gKnX1y`fH6(O5#;b#i8gEhuRK!t7SIYMcc)?
zLi#o*VCf@5p%2UDFdR=A&K%AW>w<<<#-&39P?peB3qC_l4pN1DIw))R*Sn8lkLVjc
zGv}PN>EV$x;V8jz%XDlNqGV~sg2zUz&@)hpuok0e1}q2r_N68h`fXx@<n=vBl~{Q>
zS_>iLgPbJLXE+GdoDhY5!Gl_XgyIfeM|cg|nuD4rIg22i6>rH#PoOv(jD3O@jG2<S
zZ@o^!(LXOeUrHd*Y+DH?OJKnK9QgBadVW<qB?@vN3Hio-u5yq$wUNYoBxX$*U02-t
zrq74iAYleg;RcLh!Glg)sXyd1ITc}MCJnL9hv{-Zj)krN7^ODP2yU00NozpK9N9>Q
zVo3l+fMQTfLpoowC;6ZJAr0*xCtCH4@oeu&_!-zj^mqZ@U<Z~OhL>sb*{%w*xsg=?
zNkMGddR6AiPEyG@Q@B-9i!pqvi^(5WLAHOcQtbA9lg7YR)R8Ed$2SA|l2^sf)YWrb
z&BK%_>;FjO!o%o&`b8+A<J3Qw^}PWVaw9}q&6Eg}I(|FHWQB&+u4n7MumP5H9i3jE
zo&$}arB7)lmmVxGGX>jDB<6ZNMv(dKnVfoL*hT7zcb5s<#;$BfIMnLRs%!5Ue(jAF
z62c}tc2y(LUsY{xNN;jV4Bmyg%B!>a#Y63*(r7#aQ^O(9y?l|YUaF#-v_~Qu`z4Ns
z6;SiHyYqGsX`{Y>g^+T-llzh_U0y^3G$#NbFe4GD$*!E}rmUH6T`B-_-c=iu@M;qT
z2!0~Jv^oG@50ww^A$oM$b^m=vC8~8w4Vefx1g;diP>=ja@9#pZH^}f2S#Y>ptpwp<
zbQ|vfoy68akSirmPX~OYqJWr0c#fuSbYV*r6djEMN_d-)?BhFHGco38;OA@Q&^fIQ
z1~p21@S|<}O>4^`f$S9Kh7zVzd3El$-Q~T-0rSO2A3UsL6jL=emkf*|<8M?IR;i|F
z!|iVSBZxZ51paf#kbI_KrvyB0)>*K&C8;>f!j92eMRU}?DRmppp@B-jq*y^?<%~($
zmL%=ha6cxYlq5KE*!sZJJ4-GthP-$dK;J~xH~O0aZqE|5RQboT(lzSZWPeGT4<%Lj
zY_9@*@hlrrys~ZbFVd8a7^8m3ZR=%!v`iNQGvJXg^7G#<`y`05fS-O8);Py3f3Yoc
zBipG39{rmI7oQUuZje_qT8$jRtoJw`xVn8Of=JS_ZT~60R|eo5ZiResnu5e?`VjtR
zlfCWn5FaIcS%>t*44#q4bj)?8s1G$w!Lcsv!X68sC*@XvLwGnL;iS}q#w{&`&pP7<
z`O;B5fV`F0dp@-U?W(AZxhgca<ttojyBM(HYrZ6QstF<tiGnGKR6-G2HM_N<fIg4=
zrJyLH4@eZcZ@m`n1<7bPMbj%SJ+S}FLs;c$W<`eu$)3KHXws{)-ig|?KX;ngXG0gF
zml8ol+txH!DzGT&-tR5cS-IUk`;XRbY{(T3Xxs>{XPVF6L9`)sgjW%^VOT6D*^TW-
z|Ds%v@VJ_W&GzDQy~ICgxON>&5Efm&tn{Bh!OwTI7;g&^{PlLOm2g0f7Aa$ja;)kt
z)#Wh1@gh+<#j}Yg-{Q2URr!}ll4udvfHhyan5XBk4ttSuMMx|Z-UY0n3CnPTAeV$%
z*Va%*WFUvqrX_E`VH{WndQ(^f2AFpvDDs(K>ThNjN6pi47?B5W`MDU!64*ZNJwf;-
zChzRPnw6f<+)H5NE+CxpoJgrFbpt<`CZCATujPY;kQ7BxFb+b`15w%DoM||Z?#yHx
ztH56=+OjMngQ;g2+L<kPrhn?Io)efsZPv$khqgxi@i*P{Fm!!OZm~<U!s*tVtg^R~
zY@yJ!tOKM|w{+cs<CwYCOqz`k>TA}q^m-bKD#*N%jDGfLBhxH^nRuGzI~+>EV)^-Y
zt&*@~RD8vo!NzTr)ra$BgKDy>MyivVE>r+5X!{4$<4*))>#NJG+kk-!*q{>0_{GB>
zYV5ju6Mpg|rS>txc?n5|bro|4y?AjWiK#ZR(LSFvd~{7uAeh-q2llzqYv6&g9vH7J
zXVrxQu`bkHc$P!CtHyy$m<2Y!BP;<LuB0t@;+?$hbR4^)VIop>W2@yQU1Zi_Z1Ygk
zkAg)C95l@_i;JST&^<}FsK25X`G0(m<f;#ZLwXT|@qV-vJ%ScdPOtl{w2Lw!nho}D
zr}PxM`m+G@FEC02LI73;Urc8yK8#;2a5!$s-p%|KXER*Zecl*auovTR3;lAJht76+
zPntJ``)$iQ_cZ<y)UWVnAnVUM{h&{4BR|58*SHA|Iys=<Y*@N{>(SlgNekubWDp5j
zxCQ|#IV)C}#zx&=3`wf<6a&PAP(Db9Ydgy{yjLS0{wQocXgMJlfZr-Q;m41k!h@bv
z8f6UVXeV@0hsHA|p>PI4VI=LKMH?7=ec}<m`{MQUlxAjD#5$-m5nzq8bUJcp0H;%t
zl@IE1x&FbqUdm4!zxZN6XDx=wEG+qR@3a*L3-C5&`m;B419+Sh1uzXxdk$q5TZxYc
z*?r}6ZD%>NT6^htK(u5>D^$RLW*Ff31WU)M*B{UrMCuOd?>rq5kjSaY*~WFq|94Gr
z@Eclx?gphlNpt)^P3Bx>-vuSPTB4e3VC{*1RxG0u9jaxaiqp>zbk2<B64v(>UMFF(
zj%?(_2F2l-NtmCJrTn;}#lCG5G*-$>v?#A{%Piu#fTcW1+QaNS{2J@k43TcjqT!U4
z<wb81i*ofO`dgVnIkUYJYV_tB#!B>gtIx`l2sI4*-2qnnd#Z&w<Eb>zRhO#4xu}&&
zwq@l7#ZMjh$Ijish3AGdf(mUkR=`-Z8IV*s&x^!c$I;pb8EZLyDT6|9n*g=}0AZRl
z55hdH6+;^3*2oP+maEcRy$3sGLz#>2=wyZgA{aLQ-&!yfNZ2p0&<^Ci>-fjY%1vuO
z*u{MD2P@n$-y{c;t_sO$5TjYBCWK_RXe}3qR>>EjGf;#10#-;xo%#Rt3x?kBs71oF
z1tVnN+)&FffbhwM_SWh&P^xm?e?EWPCd!!14WLtznc%yPU?Nly@c1~q<-3!oS*$AE
zMdOA;dtbkhrYfH{47zNHT>hI0Iltl+VTP(GGQJzN7frp=e1MNdzBxtdsZbh_Y1VB&
zih{*QI1dT5T!bE~8cS^h<XvSFLA3W&>x;KaAeP_1!poalIYMHt=o_Otd#B(U2C=0!
za_o3Of~d(%mqzH~DTT^fo5m|Wk#c~$0{pB4sL`)$QQZ>=%?5*!3UYqGcsu|<;6;}c
z;5(U(WuKXNGF<i-p;>8Gs01*iE8Xp_tl6_X&H$7xp<>BJR(9(iJt8qBRSzFx?+C|>
z!2O#zN`<7#F&En2_R-FLHvRZGVb*C>gECBk%_2z5QWt_Mp8ELm=FaZL=D&-6cOeJ7
z?I1mL35s4&4L}tf&JfpZl?27Ex-H+e{HO>=|D)gFd{&%U?`H+)rm@>SRq2L|jVkT@
za}fU(mkZP;2>NEz!FGPs5Ev~78V)R^KXArBXhhJzVl&5aLUA|*vk|EBck-#d*zSQC
zu{bzPU=eN>tOQ4;$(v_Q`xi?Q6i4fFRV%F>H@>c<qguZtmHd^zc3TWA!{7OVN&r#L
zp1`X!NYbc4LT^ZiH0E3GKHIt|3PIsdwDEwQ1Vr)+=P)%i+v-khM-)oq(k3?s9j7#l
z3G`AK+VS|9B82`$U$zgJ-yHP8b`~C<@|A+c>Zc&c5$emU_s%}pmE7=|lK)PiF_yYQ
zsKr{939ZiOu0JM~YPinW5Euypx$Q?=W9E#w$@8*+AfbL!p?{j4mf^1nri)K;V8|7F
zS-%4@JGtYfk}R`yI(=79o1*5SL;F5>rnYgd1SIf6jH52ZmJD5ds+J|Ui5YF#s}<D_
zgEog45g&J}I_@t>xubDv;EVn&O$4T7m$i57)w1ZcN&?k&2db8FGSFMwxb6A5wqIew
zf(dM7T9qil#XGK3je8GEnm;;d`VUU@Fs!Q0Ev4;X-#B=8X%Ond!I73)z@ZYi^pp|s
z5B+V45CEsLmYKVOZ2zk*do;cL3Ee7L&0)1$O4w^1_PD%1MoiZ*x622*yO=`MX8bdg
z9~-(F+MX6qiziRoYfy3pcPJ-{Ebx(8jmRAy88xwpMx`I4mN45bD^nP@zR&!@{I8wb
z(}n=g^An@0aOb_vjj1xJezB}%Yb=CSmu|D%c7-gjh6e4`@7}!69{c8@Vi%O)ss7gi
zOK8=7uqU`-H)b0XB*UtB5a#U`B+Jrd{5((CjwHAAgRLP>$hq!pJr#-B4cen<voAG1
zX-J9`OqG~kzd|-g#CcbGD6_ZBkeUa`hU}f_4+SJDR*p(M58`Xt#neRfQTud<L%MNy
z4|DK5NKemmGhLqMVIb!B93xb7{Pc+xj^nOkxj+4MN$~6@1h$xLWiVzzve0;*sCG(T
zkgC^z3>@xx3Zl?`6|b3xG&R#5f*XC@WnnQmgxLe1Ip0a~%kVY$uj%-l`0y_NllY}J
zJntOzyd{7_u*)0`_u#w4eXU6$SNgc9tYQYky$KT$cwHK*IS3i4<ssU3n)Bz@AA7jv
zKax#X9_=D~q$4$vu154pY4<I;cBdc%aN<Zc6pf+x7$)!q{*aN_j*E%TpDs%7;{Tt~
z5vW8e*#;gFQj<@l3j|sh{oq<4V_CB^G0t@vD~~dNpiqU~OL5!RiqhAxu5AQl`EhL(
ziO_tx$|jn<uW?9rR!gMZgocl*ENE$dqd5_TgQG}8Y5}YTCk%Sx{@si@Lwtb|+*WWU
zMFa5JtBashGkBT9b+F_N=ruV$Gx2POAV9jUZZ%iJn**)t%LafEMy6q#jw=minid_(
zN4Wr?s`L@SY|d~->@XZ6RW^Y|$4O+EQOg^<<MF?C5%-=%lcfiuU0g>lY0mK8`A43F
zMkccDhlv2J;QVpi($iE;tU-#<EqnR_=MtVy=jFLWV?|j|M%`bRp5|*04Lljgdc>O?
z5kCx!OzKl4_#^Gz!Pa~_Qaa?6B%;g*+WuTFm`q;KicI|GSMeo4xcG`WPXkR(UAp5>
z;Dx3JKBv;BHdTEN1z6o#uaI5OPByXV%;P41DI)Ii+%B&LA!*tQP@EQZ%?HJ65nowh
z5yr*)IH9=LLMDeK-(ZHwb`$u&F=BauZV`&LxG%&{L_8iq`?=$G!?&scoDt&Of!h<f
z`EewjU984lD+VjGgPp72R(S+fFS-7Fc5P?B;8b$hv65nK4eb~w`~WxZ1fi702ae%v
zp;QR)L2GVPz~RUeD)Ib8xI=ZX>^#1Dd#R6v>Y?P)KANg3G+xcJ(B;;{!$*qt?0})T
z8Oh6*zdRg?Hx>qzgw2#8V|#dg+>(TEZnA^#hgZNej-rh2g5|0<Cb(^A7)jc|U+#{Y
zpXO^TLp7}W0zB-weyZ=1B~5GL_t}Kov8`MlJE&FyU*%+yc8(Z21$~;QLIzY+6TTul
zji6x3Qf?uefKC|IsAh_Xm9ca0XUjTnjD#Hym%MvK8Sz8VR+f2m5`4?iTQdBbke0g(
z#UT<Vl=#y-DtbyVjJv!X=55c^QicLmlobrAGKTq*!^7wn@j)RT$2fu(Q3_M2xV$Cm
zKebD#RXo$My^Mvy2v``Py@(!bvn-!oqe*+cJ6;J|PMY@lk9sWsf_9=;W#7m$T7Ae?
z=c{cLss4DAdT3kKOe<hu?&8c)oXA_UT>+xqAmQ2A8bJ4fj;S)=^C2FcK8z}(?1!8T
z1-!^FdVFw`49J$}G3eW;H!7|j?I+AP%`$lPOMVmc`JzpqD+q}dtpYz`lErBnMa&Xu
z$TX)D&x38379oeyl<G1|IjIpPuN=Q4on@4`_Ig0T^HZ!^3u0;~LNIVOrev^Iti8ph
zcEIHXjU+UxBdu)dz@My34441rf{(USCHi3)DYYJqG$LXrGv=8ip^D8u<+;9FS11)F
zYu1wqCH@vlU9!>&u$UJ*igUhxazg)Ur<)~puy4#K%5=%K7nXdv6NR8cC|1|G(m(pj
z<_RXDxaLE93~%LEoW_s=C$0#pDo};|4cUN2Wj97D68r%~=jyU&t4PUK+!2k&bAkWj
z4b;IJa0ejlj+GMHxrvn(Ml1^G=HB#PP4^e=A#c!;{S5yd04s0UHBWm}P_Ycdl&DLs
zI>F^#T7aoH;;E-^<|P;Dg*BCNGo$s5yLhzZxXuqeZEA`of5Nj{Vcztt?z~@xwCg;^
z7m*@{22CIRSjz*@4?dk`(Ei)_U$1cXOgRU1P;QkSCpDE~2EP8Mwlw7ajLqbQk$$p@
zj?2L2)PezV?;=-Ntm@qY0DCOuYw&2aVF!pJXAizP&8UwD9;fH~|0C-}{0;|;o)zpE
zv`*J@)wOO_5}g}g)^?BAd`jNdmD9LZ4Pi4I;OpKVT^i!tPke$f9}3CUwSr)z-@>3y
zynzl+fn{eWYTOu!Z#52EF=ea`YIZlTyKoA_kfqOZ|K6&$t0#_OP0%IHjA-dg;OI&9
zjP9iCZDm#p=R;R$R#GIb$Jk0@HOA2=82FZ_iV;jX7X?u+oWe2lDpH8durPPnYJGu(
zBv=QXE*{*um@^bq%UQr&ja@5lDpZvFgtno7p)Z|kpl65J_i@!T@q{?%e2-K<c*N)G
zL`ZrBCmo|ZOVoS*@<NY&c{{ZGDDrICTW!j}ZQx#TJL^W`djCcum~gL!1TUF!N_pf^
z67n<Rgk9z*2Ik#@E8ftUp=osob>~R2ZUONE8uQv;nBcf|Q*C>S$5c)<WeSNN-nEoi
zGYi#d*Pd7kH+y9}HH^BK8=d0tq+}1yv+paa$cw^RTo;Ht{(ZmL4WNJPxqZvl@pUoU
znB^-oVLKq<Z@g1%Q?zfSAP3=%GqX9u0*6bvo23;Uc6)!KK-rh-=o){M)$Ovo<TrJ(
zM6G)|sl(~tu7uv0_!a5u{P=}B3gT6Zu2!Ta+*C?0SnQ>^p<zObl1oxLzHuD?(4OC~
z-9_4YHXoz4IsvQv($neioFw(JqnJAt#&5AJT5br+i*~D-$TBfMVsldNsl~d)Ho)yF
z@zBE45gTu9AozEuF|5pb*V}wPush<~#(O=5P1zZ2pr*>%Vd>`8djp>S35O$X_r?)t
z&{~4nYQj0&`<_~a_`)D>p+Nu03Fq`w8So?@8$3HTG6gp?8y`Y@H;$+`paI-Fo<}x_
z+!?urI%+~fkG*UCyH6R&w~-CIaT!<x=Fz>Kr=G~MZJ<1wyu{UWJAC*UlkyK0-xXfl
z&6^u`<P@|)AfT<MA39>c6stMcurhE5#gZrg@65rvn`R94+S{><`$R4#Wu#)!<yn72
zvpbq_vXb7RtqYHzBO6x=sE-`zP5>byMQ+Kq|8fn2lgY1b{Itd*Bp||#CQY(4s8ZML
zrE7wKQkts&XZ6$Xaz7<sjhJp$joh|_KzE6&WlBA9o3)*3gc#)navhkNor@aQ!B;OC
zIgEGs!6={nM%8H_-AAWpx#7^n_I_AnQW5A3i1?VuP%hSBwy7`MX(CHi4Ud3oCXwD(
z2|~`+Xa<EOFp`}JOmGg?9}yGM-qyH=PoXUnn@I><(~$XzIx+h_c0Dri@(eHk-^D%o
zybzD+UrpTykv2gf0rfg`P>ir&R(vY^hYzJI3ZbJphyAYUvmMz<8OgI%8e>c(gJMCJ
zMDaU!G<Q^GYwCcZebakV8?`q2w)RPkC|I%oLlKT@S(_DSVbDJj=ph8+v@W46tLpb0
zB0h1uFc87P(%CDIs0U<>sU#F|Nzc@Q0ZG+MP1_Mkq|L%wB*n@?#V)hNfJ*$5@=(W|
zUoo)gmQa_=fKz+((sOhJ6Zml07*$asF1B7|OZFvzs?b4e8Se!rJY>DOL%X-VgH-m5
z!P>4YzS0JD%%h;!>8@SyGH0tUv<18|Q<ZfVp!-6n5@8z-&-PL260Mk-Tk89l^QSH8
zoG45clX&xZ$O7RW+*s)LgSTq;a3fH7Z-#3aCtFjR@0|Z0>3mvfPz|q-JH{^C_;Jy1
zOG!zyyn_F;IAk0a&hp&w5I)OwcR+mLlfBXQPUhu$qVGn;bjvKH+GiSgu3Rd0s0i#f
zL!)~pOVf}roiyVhl9Oj+U^S>sL}{f%chGE9r2-si%k#`@zCAEvxB~)i3w2!_$^05i
z+Lk*v@{W{a{}Oh5dK7PMqn{ot*usthS7~ti#X3n(8MtIKCZ^s;ZY1InBBM9KO>->^
z+q>nXe4#%w*dQ4ZTDM$^DT~AQ&}$aV!&{`@+LJ8%pO9ZGW}nv+)LJ2+S8`aL>_t@T
zVsB~RFwj{s)wMMgj5HYPf^N1Rl{F|g=Tlm7J^zI61kS4J`h0}^3uQNU++ZkPXL8s!
zqf^y+26fPrC)spOYy!_PrDtlwbLjfi2U-5VD1Vcb@IDhn38swtjh0rt9>->8mFGKa
z<fPcA8jB(_k;EnwW1VBy-KX0LjB17fAu*`ULD=~Pud`s0g5H6Iq=ulyu7lgFB_nJ(
zsim?$uHb!!km%mdyTzB`(X5PD491jJ{OCBI`9`p-xfug%!MAkS1lGnLR(8}0F}a;h
zU^9#K0MbGrZM)>Xu5tmro8b1WDhwSZ$}8$_BX?3;ZJV6D)3`8CiMUM~mg|0aZJBs?
z$b)2osWW75HR^tjlv5$AC?ELa>VF7PwAk_Ac?RWVMPLw=&8&kmMiU#RZo@kglWlXf
zU>a|q^Lt!ovi%-<|6M$1j)s9!#uNX0=896!yT1#p!8Dw=mRndi+p`yjB?ENMLU<Rm
zZWs?R=?%O-RuvOaK1Ro`do=MA4+Bh(T`!1q{dWNbQrC+>Zmv`_=dw>uEl@Wdt6I~w
z1T2>*<KeNy2>r#-p=74=hs_`4zOG-m*DXfn^3O5>^4iDH{}kkctCyze#&>?P;ZB}G
zTEwjri1HuQXbg$7!9{x_=gn&<ehl>3|MKUqhh!pno*xkzry(a*-u_4_2rR;{v=W)O
z?6}JM3yKHQh2$dqC_;a|3|}_D?MuZ>ZkNF<pdBo=1SBPsyWv9GiHM_G@<gP8{ti$U
z<(+k5V*nVGkdvAuEtmIXni*K>^$5u&Z<0LlYn{=Edc|^b{FHWqgZFwIETN?0k*6MP
z6AIw6@H#sTP|bI22}ln}e186FAYRxIcK;&of+n{vG1(9tVi)s@^er{(Jnfl~)>4>q
z^D11M8|BOi(#~jm`&s4XCL1LN<`)m7inNl4`KhC3OOmM45mv`8i{Xb$KMd|l{|-Qw
zlfR1BTRJn;3#tl{P0fW?9i6{I^xn**F+}@b@~;N$6~g7m=Y3_JArKOW8pfMfqw_K&
z(kPw#2%wF;qw*N{pkz3<Nd<?<Ry(L!m`~FR^rN2AI*vAN_bqVri40Z49#b7z?<Bci
zZJ;~_bO65YdjVq>Vo?<4CK#>n$RKB*siGtts%-|0aYU8n6)iw8I-c^YY1~{ZAdCat
zPhQ1|u&EPo$+*HHCkG?lbTWrk7JL@^aboaYOfO=EjwDB1Ay?P33Mm94+fY3{CZ$f-
z0!PQCeK+TUS<pAxA46kvqTHrjfah|b_>K)>SD>pW43$4b5yFdKg;@@-ThYOB1VDnG
z%nNqJs}W$8Rbv%Q_gz~pFJIgx!Gdm;5ft(jW8oCz@*w`#+J@(G!FteH22TA~l(a_q
zUSZ3zrme|+f4dQVD?{-0U=*u$&RkIwF7(6dyuKB%*fQHy6<>_xa7I9iV5(;&IIm!!
zy^}a!G)&?7E;n(@J*N<GpXy6`HKZ`BxgfTH0!B9G73D8kwC{Zm=$QdZzA*t(xX;mE
z55ZAqS5k`uSdWh#dLLdc4!_<AxnBWHQe^k!@aF}hs_Y0p7jhEHW#h=yxUknn{tXiK
zsQ(R%#@R<*w>K6v7}igF#emN2xmPLE$Fw;N+zNGlHCZ5Zvp1JTAFSJgEl`V$f0zSZ
zL8<?WTty{A$dFABb4~V~uqn7m&R@SkZUXfT#64S2U?ipA*r?(N+x!;Li{ru+HCnEV
z?8v83jR*i?MO88IQ4F}tKDRi}NYYS~`$2?A*O`qH#_cT!6MCVp>W`|%n1#FX`V}+w
zZS<+CD1OkB#H$q*TB!R*DZs5+oH;WyJ%`7AfW@ub2fVEz^S^7Bti|88h_kr$p*nPO
z<f+*{tNh7BZBUl}I?oFzH6AVY6CDdz<d=ytys+%@gIg6ogyRcgP<f8IaEv}c9PFE|
zW=w8^S{$C}g=eE#_#@H+F&;*7qv4Bz-$G`Vk|zBsXfze|*1~a%_yZmK^<<3?15}D9
zY${3%^G@qlxqnaf7j6)5WYJ4RrSf^xt&(Ql3hV~0uebA<vRY1MljvBBml@?j$xSD0
zcZ@i{_2$(<{K4mV;HV)igw!=ybH0Hvy#cYaekDSHg%aMJQ@nNAzE@5mvKX%N0KlNh
zocZ!M*TRh~1^!z-hX{F4Lqo%}$uJZ*%QKi<pN(l=$Bp%6Pr$vey@_YDY;s10yOrmk
z9_3U!H|rv}6$hpA)jbl@+TdCl7ewd}0@`gW(@A$v)C!4*)0th?;xUSpuvQ-9O8?4t
z)H&phXd}HQ$Ks(p(f_9{KvaOJK98&^qb>sXjk(m@qz&CmnpMqx^BP7gQ|X?q@|;{I
z9w&i-(tZD}DNXFKa<6K*R^HFpEO-pft@ICZd7V5_!D4=;Ayi?o4}RA6>r(i@VzlOV
z#5d(DQ!P%;ds@Xc4rhOO)i{5S>?XV)Ud6DGCVq;J<^i{S^f7q#hLn%2`UH^#N-Qpa
zH~PTB@qzY&o;2QGTqNGbgVY+a2~J#}-U6w)n)+*F9R!o=K8TPoFh&UL8E)f5QFhg}
zk(>;qT+xsQlsMji(vB|2mI1neE4jdYwj<PgRpKW_FEFt*aazxDDfFBC+4wl0TC*Gm
z?cg4W>?I@Brvns{4_D2O&#Wu~9Bgs%{mo&0z~|F&<n%PVKAvpH&Ddzp*x%;~GW1n?
zmy&q?Nk<IxJ6oCkR#kFBMv`rTfVZ{O=_!wrPhocZ7_nu79OQEvK4(y+7}V`fz~UY-
z^ha8BN;}v}Bx|UWl5B%r(x+);LlTmK5<)%8eZm#1frGW!F4EnCWrb?%O7a5YusKM*
zfWb|yFsTrU#otuY4@=RBRUZ#IULg40P<Sd#Pzm|d`}1&ey!?P;6`9Sgps^ljv>Y=f
zSpj=czwQoJvIBsF@$DsbV~2;_{@;?xVm@`WTD{7Cq6|y39FX`o4pF^(3bG64`K^hs
z7#owMYw+K|3j(erXvBxr1SCF7DqE4R;;R9Lt%mtIOJv<psJkQh_8r}*2_fK&Dn;{V
z`hvgZ+!x9v7jr3gruN&bfu!$DtNo9HSRKEtj2;#`nKmS}wXi|%2hM6Dr8&8Y2_SU&
zZ5vNn<vHcO?wdXl5S0~{YlgUJj3D~Kh+}*(g+)lstFh=S<ljM55P6hT@`CUrt||A|
z>q(gBIv(GK>;0Gr=i`EVF5;z6n~iRLHao&3IO(Z%7I$1**Ah_4RTA}DnnMi4VAp$X
z@b9p4tbv@T8Wj0pVp~J)kewPB^$bz^ytO=b9<|VjH7~IRpst_2l-L=>M55v^v>Snj
z+wkShbdUh|7}67!wn=Vfo?FHw6a8n?c@=*yQ?m5zqG(9W=(x+Hm>$oZ=>FArJ-OOJ
zkI}PL_rcneOL%14F(s1bZZh>@tz<x7nV)<3Kr;;+U2nJ6u>mTw_^6A!G5(}W#2uw3
z>q#vVPLOeZw@l9y&jZk|4SvU3h{OI&W`K^cA-w40w5?a3{_tlP|NV3rdp%dNz9>P~
zV6<TQv*2p12Y`*x>@M9b>BKXFp)OxRA0_BsYoJj!HG~<>m22x8g^Y|$7s*Pn6qU5N
z)RwGHeBOc-EjHlsL|^T2dG#cCC{FkhhDdL2nrtf1Gde^dc($G8zGc-To4TeVo+Nb5
zez;H$fT(2oU*9u8kZvEUjSm4CnTGY67Q;L*&{FwMR^qY}YrZSV7aAVR{O5{ZpIw4f
zrlKYH_?ChV#!L+jmlMgs`MgCuwGXkMwGjHvq-otX9X}ugwyAFq5)w2`i@$IqGpF_j
zC#qEBTFpYN4=yXVAAMJ`I@6LToPYtPMJQ6f4ge|my<C-OXgoR|)tKoS@-^<I^G*xI
z8Cu+Yyi1~<o$)JqR{Q}5Na6zv(Tm39^`dAu;7c;M*|3NXo@k6ui<(CNtsCcB&SmY1
z<By=)N|u*$%la)32G?=V<N>8lAYbGs<VjFWD!}mB_0|z2Zxib^NHZuI-s@>Q5{RaH
zh#VZQh1BgT3g)2V*D0n6hD4H#%NAOMW*+UOU=Wud7r@T(2!v<Qn43mm-*unkG2TO1
zbs?{jiV^#_T-#6p`@YNPCcfs3R6R@DZjzwaMJ*+dZ7$w3x&pD8nxebcZT_eRkd25y
zL08v5k&`rXxb>GQ2N<*nbiDi=D*coE_{}RCG&*IV6q}(B_C{cXMzu)ywK6-|iSw!R
zNARe5XtP;=`jV1JTm<(e7I&g&{c{<|B4p5n<d~c;PvSwlN(|U^b)^th%gp*eSTl-|
zNq8Z#b6s-6MkV%178Wpt1=t{s1mdNj3{8l9?O<v}1ZHJ{$3a<M^9ajQo|So_XoqD7
zdmLJ85MS#eoAmi<QHTEY1(eh$@#zC|AtAI%+4WFP%|=|ew<r$I<B;s)>bMO|fdSM7
zJrNT2%|rPwI@p8Hi?G`j2;k)l1EYd%-FHY2lX3rrD6Ygb&b>#ia*R5Uq4^|mY2Dwn
zw1x%~!S}llTzJUE#3Zz7Y8VN-gJ!j*Yd_h{Oejc^P6}QhE}q>oYgI5C{OXiC`Y4<w
zcYUWfhm<jy*YpC%Z&i=oYr9!5?!4wzvp%tzYZ3#XiKCOcY9I7hQonaQq90I9O{?&v
zm>URBZ}s?4428RaJri2?gtS1OVI*oh?G9=<04f94(#}f*Nr&|0YyS1@?0|Do;AIO<
zZ4{GLvPxGTb_pb58jT;k86wJAGM&ejE~Re<#`dHF>i}>o5FW9Tb#Az}iH~P&6uVyw
z-v=^@vKWeSkAe5=cq|=w8QxMtp8AifkFp;Nu>pe+1zL6?usFzWFLjK!of4<iro$nc
z{MH%hei#=9@1C~DrETSTd59j-2q4FC{R)c(LBL}%EbkPJ1N2;3jz~X@5opF~#+;QG
zz>qX!<?wme(BK7N$MJs72R@$)`5KY`7NkbkiV@-i=ZJkDI+CZDflT93mkO)wM0fOE
z8)IYTmx9N-GZ+-b7CD{?|CY~@BK&mzzbQ}-;I25m$>%IFE5<9L{o&c}o=BfKxjSgw
zDTpGVP>Jpf0~E-|ot4LKUv6T4#KiV=f~$CXgb7IXJwbfpV?SPImFtqf@YKKAXUmFC
z)$^`G&m<WPYUNk$l2=Mow3HS5J&>Y|14wA)yjZav^2;=tIO+NATcn>G*o08I+OlCY
z?saGr;ZmaLGJ{gYP>S{<i&}O)!tTp+kF<jyiM`KX0yjpDkv$!4X2*z$rk8?!Xn$d5
zdPuSPdF8~p9j}@xbJ()8ARD=by6I4zSbxF#uWvI{Re26PLZgfpc{BAh!cw&xR0M?p
z+s1y=9_dzUE<$ZKR=Gypy&2GKWl+1Kwh*u~e^eoH4%)+WvlngvkQULgHuyp9jLnVk
zKdmIl-*L_5IUlZ*woFUAYcZEGkx;NUC9E(fyIECrw~U6u5J#4<zqGlj-bT415ZFE&
z%7wMNB>nxb?O0We47YO)Br=RNdbF!dQmxbG8aF;$4kDINi7g4G``ZM^0GJo%#_{GJ
zOpx1esl<sKcv*^~)z;Q>B6=oFo#}>BQ=t~liHgIGX%;Gy_OK9gYw1(ReM^1U5cw+>
zY3DrLbd(JFoC)k6Ler&zJtcc0$?#GU$pbeF<W*BVyPiXNASJ#*KF5ofyt89DkRdll
zu*3idz+VKdEJl4d{nXa2+B;-_Gpy@yFteOL7Vo$CinSA*AzktZ<g*-Vx9x7vT@V-T
z74$;k9n5R<n*N>rz&bR@NWpgy*a6VZUqUVU+5PqOU#W7@0IZABHodoZUlKaq{kV2y
zb2R`i;T2-p{P92tnn;FMdz?$e4yQ<WzApHSWaPqe&1@u3@l@kODM9$1{DZ#=y#cN7
zfuuBc)XDdzg2^Q?)YMtL^Fo%zrTo^;!`~@K`gLxoa|&nCZLSr<r~$!Bo*@^O-|MLy
zu@4V@?)fN8s1gDLg7!VJ)P@gx_%8h6ua$6DTzc~WE0d+UuBtcYW?x`VEOW}hi;eVo
z%Q;T5M0)zZx4heK@4|mV@v1e^oa3_ZK}wFEAC&CMQ8uY2OGB+a<p|gzYev8HK*Xq^
z1<ehI{Arnj{*|H=U#joI=g`;Wl0Df0^xIj~td#pTXIEw-SIAU-SUe|?;&!m>P%)sd
zyStj-t-S!Ve6&9~aW2BG*SVoT*3apNL%YJ*9&>8zg?R;jv~FebyGmASA#=N1o(Rn$
zCF3k15-{S_E5<%4fw#Pu0{lnR0^E<oSz2Wm8_DLHk&DP9&$9lSQb0-?1bL(udlv-q
zpgVV5CD{&8@U48Tp?3nt4n@X=O6Pn2?|Q~;MG`|Ic~+RaN3vp*w?ExRx@_1SUM{}%
z<Kgg0yHX~5Y_<(DS$GJaBW*?0S{*px;|tF@N(eCp#|x+Pt_28MGPhZlMMFmYr)t%Q
zRH%(QHM`Z3t}A}u9+o)8Xop${u{czJ0QX2PuHRpF@q-^5D%38bszXd4#>;)XYdWC-
zH6JRSq|t7J9dsW$mTY@QvJFULT}2GItURfDgP%iY3)szi-~9Vz4>6p?&v(E5?Vwe@
zB}Y3=6&K8mjhZabVKo<whn99G!Lo?U70tE3^f<<}eoSlqr0%Z?w|yrOx)j%}Yx!Ro
zBe7LT`6<(X#1aewtRpYIL6?s%MR94lp42O&ts|@`V))e;-WNc2w{z#(@Ni5$dY9KU
zi<YP|^2pm%2~3(U*9w4GE*>Cl`@2ygH#it<dMfme-5}n(4+s9%80|-v#tArDy}W9l
zJ%9arf883J4$&Lx^Jln*nW1X9d5iFU;)-lMd?!kgW&K}f1_>4;MRFD+o+WW;v*&!T
z)HYQB;u?dX=(nueW18|QG{mVp87<4)3^jJ4lON|y(TXN=)m0QKrV~>Hke4-=!6VzD
zj8xxBPs(01uTh7nECNaL>=Zwd%mzH1e*J+J&HFzFGrx^?|NGMNKOsrZqSV0ABJaxd
zNeIn7Qlf*H@hAvSJ)jLBawh1KdGdEs*KLL^hTBiG;9e-cw^e6Xxdu^e|HdjjB(9v%
z=^cOgxzdu`fd%mSRh#eNFlOmv3`QB{p|sK?2I}ys11uUV^T`nwP!I}N^#1x9eEgA&
z)AQ+d=-R8Qow@!J=`BIFt-Xgb`>gwmkk@5W;58f}x58CO?z5DiHq<O<fKOCMUa;BW
z-Qg_Jx4$hekEJFUTp0F4GQQth-szdA#AJ~?Kkh|xq?Fx7e01~*hh9$hEvck&^N@%@
zqESsH9~Yyhq(|#|WOT@9O+?{~b;AP7CIKMB%xilTqCL_r_|EDi;lD(eJ)1#u-%xr^
z=E3x1_WsqLJd@YMXj9C`2Z~IE^q)!5E-V<!ErY5qnkSF?($>Sl!r4PjF*Ks=-VAEG
zoJuzETE$O74_t44A2LG)9kIp92VsU#!%XPYLmhj?3-G=BpFZ7+C4xD{3s-yqIRJHV
z<G1q+2bCdC(C<n^E{rPi`bp80)^L1BH9QCvK@8`H@$@+1cS-gEI0L>PuLtyPUA<7x
ze`ZSuqsU^-4$<9DCxg9D+1?%z!JD`s3CGn!xMHN}<(v4T=dT4Qni~i(V6(gq<<)P4
zg8a#C#sRsko}d_QRgAbLA*COm7gAXd{Y3-K*B4q^oe>Ny3~Pmet_cr`;i&d>$FcC)
zi9ypOHAvuqa3}F)zB!EksQp!E<@WC1`0(`Qbq*K{b0xFUi)obB`$D&7On~%*W;n*G
zv>=iNTw7^@Ml!Ra^QO=D!8SKckq15k3Bu|8LO`*0;#;#-#Sw;Vz`;hoR7O=p>;P6N
zKY}gCxnH1+=#B=q;ki5v&{5&&!Mltm0M7Mx7jR}UTE6^Jd|li5rd7JA?I7Ib(b<_|
zBjl0+1E^)mSL-$@($qg9IzA+NVc*fM{5Oqu{2!0Au%$k@%U{HR(Oh!vCO@M3%sK6#
zLr~14u%p0i?zRukgYHXM@>p3;1nM$8+9MSN0I7WP+F>zsJbnIYKwMe&2?^^PC@?(D
zhITwpj17fqYr3KoUDM0+WU<C{F@**_mFr_$ZUu+iJE3#C?y;%`NYVmz`nR~-)e}zL
z!z|kc)YDx-X!QpMW#tYWBX?Ia)D`7HzsY7K@0TDfd_+nhyJw6|^3-ZpiMmcciT{Kf
zlBU^~s!jwbz#gcX72<#gr$%w@Px%R{GMfl-=on?V^2p;^2Xv37eE6!O00MgGD%M6h
z<E8#j;IRNMz$pkd225L|rUDGHu?k%Ef9&@Z0hj*Da-)NIJOKuM9}9TG_oWQa{vQ)~
zNoAyX>EWhmjr?#U87*)P*>m72LU~s^5LMtlIFE6qDi){8U6W??9Ssp!gg00*BusbF
zUC`W35)g($6sMG3KZ=hh?3n8*s<#n7of#xaE!qSv>(V95A2>_>;fvl?^UA^$BTedd
zRhV6~N<k7Y@N{@e-5DhOhyRV%Zp9N|O>jdgUDT+b*R_a5!fqKY#c&lAV9Kx}&!sG#
zs!xW$-SgNKVTxK}(l?7%d<R#^**Xd>h`FU6uMXv6y_%#dcMG@C)a$X)S$69W7-d>{
z%_cXD{gwZ9k-@MkaPY@gHSG^<bs(#=a!mXFTRHXD77!h0q(v<!H0xf!j7A{d0bb_A
z_L>fqTpy=hTS&Q!H;8=CX8WTG)tp+ktWxbV5GvOfi;0<DiN@(=g1`ep$lf}EcNT_C
zLWt-L%~z+IOs$qVjmGabd&D|<3mi?DmvwZ3I0;FAddLv?4F}2eE*-86rvjWs=t07^
z_8xi?K*>=xNd>b+ah`fF@9$(<aw%C)H}8x26)RpaQ?Prc+iv({w*HkKtC-d+%V-Q#
zmgG4Ec+2{JIb>x~RL~a>dmNcSa0UnkS=*ib-zO&i>HhN41Z~=*`X<z<=jyeGoU>-V
zqOk3ENI@>^Xy(If2@N6zsQ2AQzQl6VOl!Wg(&&-hjrt|jF)Is{;uYAgMh?SL2!?ta
z53MUmUS(yET{V#i?rly8y%^DZOJaCTY3oFYL4a&eh<fceXWm!BCihB{Zn6+#DISaN
z01gHbiG!`Vr;*8%0CSPA?j`ELe7x9DS)gLV&O$K-@@0)#{QyaxKM2PZu42(R&L!?w
zGtb9MeL&|}|M4dR8tHCg{HNB>%@oauphkj{x)22M^&(-fhx51{I!hf!-q;ls!2XaW
zt&j>!34BgRzZ~PoSgog8KB_(O=0v{Jl?4?fpBXEQ5d#Nko20is#uD#Y9@HZHf49(u
zah1}v{hy~B4;IS}PQQ~Hl(X}0)r<VO>XbE!84D~JLJ;`&%Tay+Q#t~MFZ)k<KmjxM
z^9*J9@bOlE?{W+|ue?(3D9R_x{?9+qNLH0j#36X-U7o?&5jiL#TDOR9Yzjre)4E+q
z{%)%wvt<c+ZqYC5QysN)Q#=@gB~c*k?^q}983FNgECwWC$qadK3JcQvtb0K-1!$KF
zaIkPWLxVG#vnSP^@1;vAdqs5krN}~SHQ^ykSaDg*gy@q(XGPi}_0BeBnr8WOZaaLQ
z0Xi@!WZmL)=X(APQ)m6`)GA#G9f)VC5bX&d%0_%1X?dAISylhL93#pJ(Pi<@1Z-c$
z-rj5UH8lmPBA6eGMRqqnR0?ORMcPsU7hdyt2ON^iwjP-h2+g;9mTyLub6m5wMa`Q&
z7lhe@4LXov+0Cj=31%J<vclTRnm}+XYL)@iFl5%mF3keoK&Khl1?CC6n5?g3!yoCn
zR9z8fkh9uQc`ZMT$wyL3hFlr86q%KCh(=<$tV$)=v9idNw(=sTjFQe)p9fxPN5|hh
zwTsx|-SJT7qoR?Lo62#1o)?jbfu*XO23aFn`AS{_x?mBP&Y{3DNA>Q|j8f{$Mj8TO
z`*Bom=C{=f+uO4Bb@1kq!;j;(w~xJtZs4e#4tR-({$$@}$M4xmgIO*^JPZcz6egFI
z*3sk)Mo{DtQGQdz&^=U*_eihu@vX{%(lVlT;a9%pJYjQZhFeJVb-lj_Vs8f9r8C{_
zQly1UCnKzszRqFwjSiQ3b657sm~50W;sSfEowH2$ZGs#tU}X`dJvp86l7o=`Ixc7W
zkd7$Br$wUCXa+Ezd}x#9i(;+{<n5{L{qKyIx0nXtvfn~Y-fWVV%`%6^=CYC`=t&pb
z!Fhfg=Rc&T*p+;+P`!F|%_b{z5ovuLh7FKPoun(d(Cw#;A4KcErRf^cW)hDY=E2Ly
zWoU(rplb=waA?Frg`{3Nc#s|)eU}l<WDJjY1AAv|&RUE|T<JJ3@>QUydZK`)9<wc<
zFw}t=kfH^^0gLA6Vqy$l_=C&wJ>cU3C;bRv&7T-=GuP)aCkNKUl>dY9Qp(Ohx7|c4
z-c$OlZYza?s;>~GOU)7hK0v|0gNxCIhJ?qPDt4Zd@U)2$i%bJv;Ud=z{E;;h`R`Mv
znYcL>LZurpvb2zc=KdZ(<RM>Euz*?=ChFtreQ{1t=q@jdhCxt-Bba|}2W?$^K>1;u
zOC--n5@r6<a|mIaR<niG<70k-kpRldl`vWPOwk!V6z1yc2)1@?bvPCKmkF`w-;Y!{
z7EPu3RD8~dxDX_)t<}745+L%1e8Us_+M)*iw5RZf3zAdDFs;K=Zo!8D6TpVxz8OrY
zqX1JAxa;M0LiH#!<~<nM`!}i&HPSnuUX||~4ES&m`^$&X5$$9nxPw|_$%gAf=AYS+
zR93>NF@3XcZf1r=qy_mNfB`ZE>;4Ky_IW8^;DIF*Kp#u3b|aF(ivjlecUhg4Ex>QN
zRh_Go5^>@e+;`gEQa((0r!5~^o%=&vflVRIf%h5u&AQ$W_@q_#-A?ees>$c$Mk^r2
zcDu1$A7%F0IJ|Ho{tf-ykw^eCfdly=q46q(QD&U`XvCl%qzo$F_tRk+boJ_hHkM>)
z4$DJCtnTE9u3j@gwKqKdU<*&GXYN*uZYnfDrc`DnLtkTeb()117;Rv$`fJc`j3M*M
zf}?z#2{5IM2IcClf;4@{<pq5<&Pt_M=NJ#tWyyG7=>)7Kr>G)UNf7`gJ5UvS7k<06
z?ls7|f4e+Ej$?8Qj~1rOh#}udQZ=J!=AC=Slz(h?u&?a@i(axF#gXY#2R2W#HZK8A
zET=s^;53jMnu!VpFmz?3#(wJ|@8X|NC!KRYN1#O2=!4mihHKw0bZGc30zZCvYKA&j
z!vT^F$nGk4T{J{xo6BPlEEh{mFW$SU^Y0}^akZ$ps-YYWm8r7M>Jgy`Z+%i-vC{0@
zF%qbwgeqA4#pMVKF?U#=egpy%1$nZbB^!#Q|LuK6RX)N~?&DG9gF<nk&dkjXUI5LD
z@?41daWX48dV5N@A-gr6JfnmXyq0Mudk(nMZw64ByT+)lBYB6lwU%Oxxsek^+!uFw
zqtVHsErr!7Wo>gtw$-+AX&X_LGZz|FKxc3&RZnZl?ytDT`^`V;3;5Yl9MvLm&y=-H
zGv>Z~00wPj`LzA?@+I@K!!D%CWsuNi1J;=-e3XzU)vAKvq&6PZkrD&m|6@Z_iLIvr
z6BI7@sfL0oqdxg0NW^spk#~DK0uG8?CQy@#@BO)Ksj*1<WKjmOA=5xH+?c+ClO6=5
zpW(VoEXdm?Ye$?&#|n6v#5)tI?Rlfm1!Pn+^9#c;bjg@*%cv4=fw=hkoNCoBjdyC!
zM_vW+RfT;uG*+o4cySSQB;gyH_vT?I2o9aPk&6cNx&<z{K^oC`|4<Nixx{eB7fQUJ
zw;#th%;+1eIV+1N$S%ICtO0KDjsPK`oEpne%S4N}Y^%Lx%n9t<<*(G8O?*Kzj@6q>
z#xinTJRr3{v`PU`^*GQ*Ac|D+x=rBZGixh05DIJBDdw0ok_?{{N65z-OVC_>Was0F
zc@;`p2QBC&5d^^PjNET$8xI4&O9oo1^+iU-GHvL-FQ42LgJVB7ol>`Mxgu5=fddU(
zP0&(n(BqBc@LBa;6*9Q6lsu1{)5S!d&fZU$d;|~^^hJREUn&RlD2!Q>I#a2_NX_*!
zr|>jFov*-Sgn<ZS5=7Ene=eNFr_bw*@8E!Z+N0+dSf~-IlS*dMs6QAEb0;#)hB#~0
z<KR(w7*hndv`(NKRIlo8ri+e{!EzAnb_R}Ci#1fTps)=DWth!&LOC39yhIzRWkcCQ
zDJX{-aYd#-CfkS4^LMX@MG5~O^vv!}c$rRi-r*BCcUKNVyh$ugVGa&H0O-kz=$VXC
z5^a--_i>@8gxPK5=4hw(-Ww&^2L}geJh=P%0554kC;#rUXx)zeddCm9EQNhDimS<A
z0^ATKYau&s1a$J}uEcwT??*Mu=c4*M3C$i){m_myV*hQe8;^Spg%|0F(Wf_RV75>)
z98`rH%_I5tF}5Mkw@}qam0P!)6dRqwtM?&D47$Z)Baiop2Hf^*Mu_%j)Z|aaWFM0Y
zLnSgJ*fO#sK^BkR2Nw_$wjNA2%SVsCJ}+-mn6}|~3}2Q(zZgv24cR3+o&hbf8XvMv
zP6^45!LRJAqsa2#Lf6e@h6H#oiy^>h9_M|X5<ULn-Hl}Nq_s9Uus^m2%CTg7ega<<
zbN$@`#BjYW+^*e(7j*FO{37NbW<;7ME2b?byAwrzWfq^ehR|j=fX>yIxOIh;;WH)y
zb{3Pa%DA(&GzFDWO!9C>5VK>s+PEl%<f_RW+=lD7`vuYE*KiW#;Ow!jfA4wvJ-c{*
z03HE_)DK>bpoJ~@P_41h>pcs_{e>BYtvfzn)z^?@LUYUp?0$&#fNacVD1R9$yaF@|
z75|c?bljU|u@iDYnAN;?z!TjD;R**FJ}au{jy$-eWYP9wPACqT_hDjBo^`apm90VX
zuf=3`|JJj<k@xiR*C`}?ML0jm>>D!zVaE<fz|qxB99GfDu?}+DjkL~bYGR#&<Bvg~
zNZ@N`E;~?4sOW~fcVD7?x4~GGn=;a}Ce&%ov`^#>QnbNcqU*1;wQF2205nPuDnwF}
zyjmz{dUSy8)MMxC>MxGOwYK-F=XmsO$yq3Wtv6Z!BgFJ?+{A_iFqa`Ovt9y%+Mg@7
zxhpfjmo??dX+_Ty{i^H>7sfywdxnVAl+HjSn4G#g7&7b_=wHvBiKGjpmm)FDHV2RK
z+cQ`d9bX`1K<RuX)6Cq@`CVZv#b41SAPy|~e(z!C6)N8=u&~2uu+PVM`$(OZ$<}B@
znzi%6Cs45`(Lr-bPET|MvNZR;UCz;ER*k#vtzj^n$nU7<vFT5<alzcvemyj>Lia)x
z6Qk<($LO$z@l~s*G|Izeta1nKJ+Qf=angX!1y;%bp~J)yx~ab)w@hjMGvm^$^^vRj
zNF5G?8s{oj_|@KmgB>eK9arXLqkrnk45F=P>&dY_ZBYjrMYa3d;x)|_1k39Z9mHL<
zloz7-`kgR-Qi^!2KRAP9C9+E%90}V?0g}ugdSW>HdYCwuCzI8W9<og1`uHOjH*y+X
zDML)k^kvet3^d@z#mv+|&VU+8Q*ea!gBKZ(&BN3GCzsLf3gh425>a&x(!*3u_r-7$
zroMD=?RwtLi1+|u)lYgHjCvQmeYhV4i9Ztz1;^1e)_^d2L{cENEtHBH^zqi%3DU-n
zP6exL`h^7+d101pVC8+Z;8X)${oYOg4<V|DwSs1W)eyfA)gNiW`;;<MLHBcMw0p$e
z0iIfN&XAKegd6a`P1rhTDh!YtW{x;)8+IIs&(M<woP5^c;aY>L02cDNsOvKDVI{F1
zyl&K}5G53W=83v0Vr~wLh^7R_QV5|I=%7-fvJpy!aG8Kp%ZVBm1tpFkQ13o75{YXG
zQj2oz3!nRf*R|Bi{5-%Ln^378n9Qq(;BtqqJ(E-Gk}Zm4FEnk5D}&2Eg6;6J*A*JB
zb(xHViBqy;rL?Ii1t$69gb4x4*(&V;kr6G_8Sebn7DKTg@2A9&T>W4!moCuSe=s>X
zqM;*a#dz<m;gPa_FS?6w4c3wDNTys*%+D1w7w0<b#I6$Dx$|4=*(p5eh5af7B`!l+
z$fzFrs!{SY`!ToG^*(j9#J2(ymDAJkhxyTp-Ew#l&`4&22P}qivXmvISFf)EDG=SF
zVv5F;>mRZ>r1;~&L02QmAj7E%BZ$!sr2=%L;IYiU?cat#<qx)xz;s<`pL8$_(bDzk
z?{9ha4gjj8UQo4R|1uMuB>*IH7brY2YZdPKZdKteoYn-9E6Q^v4u1qj$1s7ZVD%87
zhjSX;C+#*TKb}?hEx|)Z=Na+a<!!M3YMIu}!d4S2krXDmqGCb;`jVPiB60q`CIgZT
zVrXi}XrHgh^`UEjBT+NbO=|)rbKU=E<BL2-i$29m&Jg+5i~f<{SFpOlT2u#Vi;}&j
zlJ2)k>x#@~0C+B_Y^@Rlv)FQRC?I6g%Gu&JvI?I@0EFc?bs-nStV8^WQ(CUY?x`Fs
zC5kf_QVQ<F!sh(80TNx-rp?}$Pc>eJatbBc!y(}BgZS&#b@)^KJE{)#ImBEoUKFQM
z<NgEtg=>P|pSR6s)xtlww-~+-Non{?=d+?SLRq)iyJtTt=fLS&Og5S1vxs)1z~2=d
ztCt)q>Ypc|sZjt>^|d7wDSRK&fw#ycEzu2z)6O<v=T@qM8T89*o52?D^tYMlBwEwM
zhh>&9(NNl_onXK96=GAj-Z3T&w75;dMd^XD{>^b=ubR?P=~km@;9b#7&mjOEF0(Ja
zlIh@uvcBW^GSal+Hx22P&iCy?n+7R#q#LUMD98ZOCMFS`3+M5#GW`dBLOE}xP%TA(
zE@$qY;seS`*Gv?O{Nv5}(lRassh?;Y#@7#%bHJCR>spVg4>n4m%~M*NZ74*9t3R3}
z9ni9AS^h>6po}lx<Gbp80g}^dF{Xl+hSBajB|>YW^1<*v;Y31GgQ&?yR|Io3!oQ8;
zGpl#t*~YKGa%_dce)D}`U6z*6QBv8Xde*)q8SN3s&@tV2Lr5ad6*f~;8I#=IjZ&Is
zPLEtmvkLC%J?d1ym{x{G<qFYhzN-eqz%GYEw2I6vFT;?R3EfN($2{M8&mzNI8{dQA
zDy6FI&mF*OQ<&YsV^PYOEAFfRI`{hnx|w-}=bzx}!S_*Of#?txUoYOrYV>FBsma@q
zPNmXsdre&OK!8d;7m_8%bR{-?q+t(wVuOh!0MGey_JDK1V{OQrV?UZnS_o1PCI!Ct
zRZ`aXL~aX(NX1xUrFYGsm^yHKCP&WaBhoFwN8Cx{YA@eu&@8y&BNt^2w}`$<Yft?u
zGKII@oybtf@o`rM5?`L0-{osV#GR|2aNE*v(J?6iFj=R~r`e%2`!;dNJ~p@B0RXnp
zX3*TN_YtB!6(7_5E1mj~RkgG+b6)OfO$VxXgoRs;=kZPq`+$YHC4`vWyx6G3MUIYc
zilwTkUz{1YuNDZaIZDzvaod^l<>L7CVS1j`%T(SmZTGKH-^H-iO|JknqlUR{O42ia
z%=skmYYI-<#2I0tJVDVi=W_c0hu0DUe@b>{=bmO7@~b{Q&&OU*PQNas-sJ37M%TYx
zeZ^d;wZRjw!4v~&>QVIX(S^ZqZh_?7$f5OOaENUg8X8k-X(KJ}S)dJ;p(oarCF;IO
zbLXYGvq0Ohf9RRZ*>f@90^j2y7ZEFL0A6SXAyLjyEaI1)fTQ#`kqFo?F|5r$19tf9
zTmCdv@T%TcEZ9|HHw@`jNM*H4-oab*sIfEdh-4E;Q<n9A|9j+VKziW1XbkGAO<kK5
z`@<5<fNOs4TB1yN*~|9s{4~stfZ)IYIMCgxIpY?0-r_Xj?%~zd9?V3jNTZAcXUjZN
zN^aW3cOs}zVnE`9Nk;#QfRqx;ET4+Y$xu~lsG*r-NmX7=)2P`$A7C&N%NeE<5i7!?
zwty9-_j}9j3IS}VV-#dgJr!mZ3@`YG#@trRR?L}R{gdYJ|CQ-pYb>K@J?BV|C0$@o
zOGA|Njc3@Fru-o7^n~h*7D4oi1P&MT_A5^TD*Lymlb8)+`MVM?*mv+JGpCLy;R3s2
z;Bo`okO1G3j8IwH0iddz-|7)TQ!4T3i_SS05RN)~eA5i!{QE^$uQ_5<>JkYED~ma<
zYd-opV4b7!L#zobtw$79QgBW5BS;(3whVY_&@WJTo%%jyxdkoKDCZjt8Bh({JGRGH
zEpf!o0txzlu<STy#RJ%a4LuF@Sc4Dce!7&z(zlGH@sucs5T6~n>XDtFT!RH{e6HC*
zNQkd=1lN`5>d`e?*&n*LhXWtcqVw2+gyxVsFfT!4YVmi0rXaxH8^DKg-pb})EyAx~
z@06Zc+^=?@+#~y;Fy(X7!62FM#FPE0#5U;x0)HiMpljhSs8>biOq>8eK7OJg@^cbW
z*ZSWeULAUI#Ty~XAMt1|XdKM!+WKJ)uYr}jbo~HBhAQ0ruW#v6^fi;E{Oi@G;Uzqx
z_y@8u7*X6K0&~!*EHu{5Wwcoxq{rN?M2>~{E*6u^#rC5a)?@j{qBmmDqX>+%bC*Jl
z#6q6S7dsW*QP972?%^yeHtoHG0>P6K=5kHMt`6H>m{ghH=umnUArz!k1^(E%@L(;N
zgypny<-MP?!N&TQnmg|9C$a{zF=r8>%23md-gYN!+W((GX*2a&)kD`V3<NezytjL$
zNOy|kxm3NbeeSlH2swK1RH7v&HmsS%1!$>Rh)0`x3x?5tO?6tf&7#&?Jw^}xnb2ds
zy8T$pYEA`Ai{e^NJF!oZe2(My;J*CC-er7m)Scq%k&B-Z$3cFLzbS{4z`|58)5T0u
zS5%s>*o7FmV52B~X!C_*sFhn1l_mhZpfecIv$`|q&Na6mD-F#LduTfa6Ok+zdS%?J
z%C`o;K1f|{H6Ma0L1}q}Lbbv51ozh{QS69|D|(=sy`MzAP*{VIfH|nS$AHYJ>r%Zw
z&G|L0GD~=rb{onSm0)N<#q@$5i~G<IUfl<6#);-j1WLoT<fj1Ds9;4v!ys!Wcj4I1
z8PZWagj;QKQ5yx@E&=@w#@Z<_u?hU^Nx5D3SUt}N!r@&ENmx0p%@l1{gc=h>c(JBQ
zRt=DovV)`%I7tMo571r_VZ&cj{>{&^_gd`{t_&AM6XF@ZxMc=l`cRU%(Dq7}yN=U&
z()uF8c#UaXxWwph>_Pq~1YWW(@|k}~b{82Bxz)l-$jtjuy7gXA8khJ|;~5Cukbq88
zY}&>aY3prMnCH3>(1FA>2=wr=cj6Kh1eNEvSZM8tFpUwfmqszHk>SE%_Pl)fH_eM8
zJJfo`cBV?Ajv^(dFGzBPdeeD*2o5QQc&toF6pG4I3x*RjxdGqio^qM;WsjhJ_S=0H
z-))2nhMe2Gf6i4ASp|?|X@br_2V98yYwU9t#Eq{s2CqLaH|M1c7<Jd)k8x_TQo5KK
zgWj<0Il+U5f~fNj8kSm=q2|kh_QP<+hh-Le-$gV2-z|wCD9KC`IOv+a8heQ77wep(
zrvx}ae6*b(dT($gJ?Rz+Q?~)jPW5RQ5J!ySg%N7L8o<zk;lX=u*9v*u%1jQ-lEiai
zMp({s%QSRj(=b8no{QTK$54oE{ANdtT3ub556tGA4z7dq^-W`zOcPW-O|h@*NaJtk
z@Hg0l=7x!i`tvM<CYD9V(f#EX{(?cF2r9p#;I_oLT&Hb@qBR5~uNo{{MJ#TD>Kflr
z!wig`A0|mrE6Vpyv9%qYBvcJ@30$i$sO%AR&UWMN7R_Po0+W*P4)$%3Ulxa#(sa&4
zYq4IIM=G`*f-8ln>K|46lZs0ah2oc#?^l5O<2@;@-_zN4i^g6zSwPDqmJX8F4*y1f
z<Q)7%oH$5h0<=#Sn|tPrZ|w7DxTC!Y6jmN0g$@>9#n6YY9OJrABILnb*NYh_H1t%p
z%TG|mi<A<s_H$8vg?r>mv1m3A%=gh@y&*>b;@Q;kE)3()Do>?1rnUJrW0lO7GM-&m
zwSJaSGCuZib-KjC9H@%7v{2nM)HF0AhM)FvLcN;0Y6p4uwT`6v5p$au?;*Xn2mk#=
za4Hv37)B`YN|Oy<LUO{|ia+-F)J744=M^g8-1#lEK%y25Bv9K#P6>zUWP`b4MX4yh
z)-`;^IU(n>$<^mg;Hobdo=`nNaS4^RE$B{bd8E5CYgoe#HrKn%DSm44wE1(si)gPd
z4cY@WjH&jow?xlG(Iq)8VgJ}qx5%;{72z0!{t<ZICOr3969#1qq6p{29*+STfD0;e
zte3BP@NweFtD$BVhR_Lfz}<?*+WN~H7()<CC2ui){UgA>i|He#`Xu322Scu>(TG5z
z@w}vrxk_G$s6Fgu(Ao3)jO05qxswoajFl;|#^ACR*uhknJ;L)wf?u^oR$;pv%(i!v
zr6?gSb0b*MW|LNOn)JO#!URpg%g8R=f0#j7E9p#9;O3_3aQjM2tSL-<ylhW5lUaq|
ze*!moQ7ZE9m*oFrsEix4E83aGw%wPQ2sA$yNAV|#obElm#~?=g$jul*@bAe)W?~nb
zI8`QxTC)SYrN5LxbBV7L@1ahHph-BF!ZWB=hs$$GU(Vh$d%Sy#uro{wP1jWL2JMsk
ze>R_<x}Y0codVuI<)i2G^bZ@jlxQN7yQ)q>YNfC`V^c{9CQ<Zy;u9KgR9<5%y#j4)
zJr1Lljyb}f3!}Vkfom6zgbkTUHZdK-8+~#ZJ|3sd1MeEwA<soH23zj76DG0CcJDXT
zDX68CcsU+{se29`4z&&5`R$8jnrq4h^22gwjC^f$f-phK#>an~7pQ&5LBo;M&GEX2
z?<tl{WL7is&TwR|>9vKZaoAD5itjGQP(SEG>T;dR-bo=GIo%5Rtq2n1{Cj+pnApz3
zIB%a9t_YIgU|dn*N$l|cu10z;qP!zZ#ag8)JVU6^H29$QBe|C)M6s#MaNi3RPvm@j
zg7(}Y>TcD`!pOlOS3?E%U$sN*l!dR~0@7Z%W;??84I=82nCkT?&h~7;K0ry?>z1Mf
zxmSl^;!i<1H}U3Nxo1`0p2rxNlmB{(y8B*Quhlytyr8>RB_Fr3(GQupqFc?%#a|Cm
zFHp7-4m7YHi1ZyK73sOSYm+6W3$ec2{L;a4g$Qr_8uz*^(dUH|r$E>S8m8nYRWhG_
zKVF~I8o5YruRpoTgdg^e_tGJ|64lVB7>z3vZ(!s8GzVs{T7#nje_g&!A1==WV7a*J
ze+YSU*5ws#$s!qN*67Ae7)vgH5Ym-rPT5`X_jvm5pdy|+$nj7EX7j;lRFVjpHwt?>
zwY%JL^J!^96+yYL1t~hw5CQqAQx<e7f+CghsiQoFMBaBzxY|72%B(EX(ov~KaP`Y_
zb}0~V<?&YOy&qgIysJ1!lPL0gG-g|5w4@|p7>E)%J*Cx~Y_&A$vlaEq^sTE@WbSgJ
z<WC}*AH^Jrt%|BrGkGRvNu4OM{3J_X6US#1RvmB)+i-(-llChT(NN;d1I+vwhp$Nu
zC<5l?i`1X_u7=LBJjLyp`DQY8mhUdD&`>K(#ZM)HTEaIVEsA<QniWbCCcmAR(^kY#
zx)5YM*tpNy=>dD-zlw8IP{)Ve^0|6iPEN!28w{bJ6eAPL{Y~1Q?3fyx<S(*7?<9kQ
zw3cV20vJNuwzk@8ksH{512&FJhOX~ICnJmNd2p6%0E1I8%Vq2ll}lMJ^=YOCz6kD!
zQAj(8lkS{QYQXje2+HIZxPsgxsjPkc@#bIb3)hEnT_%dP;`BSfK5vh6jMvkE)o~59
z2<)&5vIMh?zBjCcrQqFR1N*SIk0P92!?=fk?y<3v)Bsj6Cw}AjdV`8xbR$NU_pt%c
zO+Mnz8Z&d|_SQUa4P>q-GOd<cWT@pv3^i8_nqP%E%X@T+@50hXz%0V*oJ>Ygc%AsR
z8xot|OxSuC?`~?yQE5Ou>RUr-oN&H^ejKt6h&npC)3b_V*#%^yzOI2cR}|J%4%4n7
z5=8E_hgTl?eLT{J;3(D$=kploqV}6uxC+9Zsp0W@kkWLZs4+=~6b1`i+ce;#9uYSU
z4O#M-#0#XY()h8%d)M>;^tJ+j)LZn_da%Rmw<>=&tsoAow^>B|sJ?J{UlB-wNM$LK
zrVgF?AQ8M$_1@hI6Q_drlat`miUXcdwsM5o_-{C=K%@-O&WlUc9%0qr`XIBjS|fI2
zP$MCN?WBztrg~V@@^HKNM!;zD#J%57Dg*62j2Km=SxlJpXt)SZ!`;rD2txGo$=q>b
z16Wp%=5C3dVWYh06t>J(MVrWgtp=C8`fIX_p*bYv$9snvhS6CXPELvZO*WEtRqFl?
z(+(J;`uR$rp$rOc0P-hgZU65#R}~^p$=atAD(iZmD{ByiY5N?4yM`R2rfKQohu2V3
zVIr=W8r4LO-`2SL{$hW49-%o00fq(8ng)RW7MVeQg;aSLM9|>DqWSB*#=29?vW#v~
zL7~xO6wr@B`%mj*Q<%cj6}U-+Kvc5rBd2Ih3tN-A9yHSnrOjQXL`zFUWn(p#5+>ie
z@NPo*uK@!r#Capx?dyP$CAA%1J`>1hh(R6Oc%w7qSj6Xg43_hCa-c$4l3AN2Yo(Ao
z`ddmwS|<jvab$FUt!`{~d+=e3SQdN$wFjj9X|HSx7#l{F$t#EzNdQz_Nh+v1uRBP!
zYEBCE%ib%NG*r0&dE20l&zkZ|e&Ig3`+6{}J9rzUJ8EH|aEI-6IS+G*IeC~K__a(n
zOLT3tXUI|fBq$+{$$<^^O<-(mWn%TMXf9RQsVUkPhL}~~MIMI>)Y-s7tOV2GkT-s{
zm!kv$$LyI#<{<EqpA(0U5#vrm5`fu0Fe#Ei@e(tU&Q8CSqw(;#PiR5A&|G4>9=xLg
z+5{BJlpV0schQPr6>pVyF@)y9)+{y#&jsqF>USLgI|(R45j{Qc72&t@dNhg3OP!DD
z76Kv7c-fS(x93wu#8!!xD|IHPDG1h3Vk>oC!{eq3Izn@)cxb`)2P`Wg!!f>zGvFr-
zKlu~}uDHwl>sY+kU3v)f-{GAJz~hO}g?zq4tfnbM=z;sq2D8c++AQlyj8E$1dA^$Y
zG+6i8NSS~#X=P+RqysV}?<SdMZGHEmqU?mjkTVMd`JbHKuPR8i0ay$tfLk0hMmRws
z*yqcS08bqIN1s5-@!T}K?crpa?kOk`eCTavcL)$A9dbyJ!K2(qgnWKUlMfCMuGlL<
zEEH8yLO;+!EtG5Q9)X;e6F|y$*5t7yWO3$`%xMBP$lf~$YnC%xwn7zk;0Q_7<dG#B
zy_-+C?U=h;-`Bb4z7>4pX9BHf0u*q*LQX?V$Jysj+mt@Y?ZSMb*NO2vp<f<>pkCDR
zN)xulm#((n!#>-35H_?*d`~n~3Roxqt}A1}NQ<og4~N<M?FHQp3%4M#DRFyu=6YL4
zBZDrFg9wa3Qn?Y6#+mqthejdY#~X1GzWv#=orD~&@!Bg;VReA5J(H)ie4z5;eVo%&
z`Xt@3Wns^H#Q|`HvcxMNk(d5Gb<)!dzb3bL#`>wX;4IV=|G0eSc1M$8yK*;TN^^;6
zY*6fe0A$6G=-43z(LucEDXpt7z~QK8+pieRvhx5!e>A-zP$hokqTXwnc%i-LcZWYG
zp(C3JMd{cctzca^Uh9^98c+qaSuSM(g^0yK6JqzO=GG)*Mrm1C%IQurC~!9`A`C(j
zp;kp#^G))WJXr=lIo!&GHD30|>_`%#9zIO?t_wG@K>!jqSC(#!EBWItVGvN|9paQ=
zwRN1x(rwPoeEU*OdT-4ijbo3$K!R9}4?un4UlIj@8+-^I4AmtuE~>h8FKP;6pwT3>
zwGnzOM)TEYmYN``ia;pQsUoW;v9+rTx3Qg$I)eJxvTny?EmsaHZC<fQd6>+oG>k7R
z%!(f*r0*NE09YR8F6GUO3|w*_4Rw4X!4$Ix-zb5mg^4X7c%B7`!Fq>L=0)mKA`(Ds
zVprscdqKgQ$Z+i3+1_fRxwZt{Ms}JM7RDMaqz{+n7r>=Gk3WQfZ|$YX)GrA9h1gU8
z<!pz$&@TTUUbaU&&sHZ+ZZamA1{JxJiq(Qa`^*EK8{g}NR)FZ5y-H&bAN%iud~!*!
zpyYBOkC4>L?U_q8F`|Qr1U98n41D)}eZqoh%$O#~FwfpcrD9)Su>+%uc($+6#9^Gv
zd)%J9Vuif;V0AJfe&{CQR5jI)-X93A!Bi5GOKI~t&(cF!IVz&tMhds4GGw9K1XnjA
z712ICZ#Tyl729#;y*9-tFg=0TY*-iOmACK(YAuiKT2AT>f*$*bjR34C$8k$uj~n1$
z?wff>>N;6#9d734`r_+w__P4DY}KLZT&yPg+p$Z$Dp&yWBShxm297+iTk!mFo0?@r
zrlksBdL8Hd>#Zf?l@+u%Jm-QdR2)PVE!5{0A|1New<%`Z%&z{OmLoHi7ClcwgHYFF
zE?`PLG~=|cl}`^@t5mI<KI~|27lbc$NW~F+JqK@mF3Q=2w(VrLnv@oc^=2HN_B_i)
zOGk?T)r=Nz%x$Pki<bkM4u119wkO^%s6<D&qnT+{x*u+4`f{=A)QUf<OEjl%SzGPw
z7if%^1MA<i3o|JISB6(%Ma_PoiG-o^7ix$7aQEm!#a!B$fwE9XvHl+L%+H6Cr78fk
z(Pb1lRmBUqt`cueTKX)M96`<coh^=;G{fc-VsEpnUKCGwPFD}ruYXnmL0wOT5QG#e
z!#SSuz0dYd4mozCiuWG6$|~3ogHY~~R{pW8Ik#S`a#F|YZ>gXfhy;|Zvdgm6Bosvh
zoxfaD19clJ=fgbtleH9#0||r{9d#qNtPQWG4*j5&MLW4eb~Ha_8oSFBR0R`=^MOE)
zKuScXLPlEiR`z+9Th5GC@-vCa&1^&{19>$?BR=);`Y%CJwU-_h;@S<EY<Xym3=U1V
zAXam6NkSLZ8p4c&&>6SILY*EIFt2|p)ue1<eHgX@IB&Re{Dbc>JRDXIbSUz1_aLo}
z7yAo(Vw?pMDXkB<wTJutJ`t<$OCEm$Ys)N9_?{j@ok~8InZfk<^t^60txvp|uI;Ju
zO4x4OPG&U>EyYUt7@L+ElRRO9b_<_n?J#~5a~TzE|DKhMA4>J0heZ9yTt`ia)`CtD
z8SerT^COEy^~`dG7u6asEl^et+6I!fqNx0;N=kUaaVkKre2@Yye{i|16uSbDJ!UTn
zgH_CtHSs7xo#z5T|4{XDdnd^nMMn||Jl9`Txf53{!UBk_Zq-W}WlH0SGkGYh!eIe;
zyOa4Sz>6{2x`_3JlMz_Qh`vR-3PLP;<1M+8QIy8BH{>-Zi&+bvG<CDp!MQ`$OD7nZ
zxNCG1U#WqAsONb-jQ!`QXRu5zihUiCNYNU?x%<~kX|exlfx2WO%4oaMRt<-M&MQjZ
z7OlkxAvvmalS7RPq&yhB+iKJ68Kkbe-iu-n^eL-ZAre!0o(ZvrE4EeP(lhFI!`hD5
zEu&LRl!n0@Y$u&1;Praj=6HvSiVono5FC?Okvx-k6*hDG$?oUvySD*|-@GQaq8Q0{
z0)++GudUl2u7bcA<;E17->-SuMf)7q)0!(uF4?@soDCyeF0EXfTC3>BSSgOD%rUuF
zyVU0U|G{d~z#fIaGEL?SYl8bXTS%>A2aCJ<+kpZ*!^R>uk$7l`)E^J(Ld}b<W}0$P
z6T##=T9wUW?Fkomh3PLBLik<tAJU_Atr|s^p*df7u(+{aB>sCaYT04$_nH8>rtH3A
z-+6!BQjCsP1P}&IP=oc*7?aQROG7|v!M7$>UJG)Y$uOsAOCWy^4{3%r%;%IVw;~j^
zxa7&Ho1b3RJCjEyzkNpkxqGDpg)hW!zjLSaJ>SRM!jD_?<(0K!?l)BJrKEYrCa|g{
zBh)x;m0F>nPD?F|IMOpA1wIxXt?o17_Pt~hS&~zqv$wloJ?nZpv5{@M{-!e$#91_@
zkD^00%wj8zLbf;p!AkXHk)Rh8hN?RBsdRiA+#@NOl+lv1%8Bo9xDs(te#hCSXuYd(
zbnDJ^FiUiEWsLfd&WaCdJ*Yv1#Rqh_(pHlQcq~bw1i)^zo*snclk&ac?0=Y<UaOdh
zJ|D%K)9|(ZDy?<Dr+>>~_Yw=T$|r4NBHydifZ2C1m`he3JYA1yU5MtllW<nL<okn6
z3zV1koq}CPeYAdqB}i&A-q@s1YC`@}2{xHC{wk*W>&cN^+4%JaLzIdi#i6k_1B;#_
zHf09OjS$!`(>PYcp>+wo*k$q{MIwzK{Dw}Ax(c{hu9AZXc9G-pER-D?KBxyX6E@My
zLvnF`>^McOzLxhC=CmVQDEw@1qjAZ)f&A7+C<;dLs$Ej)6SfGstj5t$@9bwk(>NG%
z(!gXIuJ#tuzjW_Cd(9zce|^BXQ$l))PHm$>Q+720il+}dYWvdG=fz&*((}_BG%WNs
z75vR5a$^t(#wyYxRx?V(xr-+>GtB>Xp0c}=s`Gf~HUxY#g#%X0J;d>PWZ6bzE(J^)
z@l|4c0TOoJKw$dOU!)7(iReY%v;4!tMFWI!qUTIA`1T(T@9XKQv2E~d^1c+A7V|;Q
zdGn>}{O%T$nKux>&>+my9Y4)sjlh4zb;$hYhI&`Vlb9L3xS#tj`dGG7YV_PC>~bGq
zJ*=JO9}8tn<$3H{Hlj2xJd@+bS%BFAj#kn$>cCT&*1p$f_oe>bck}&{;00yx83qt#
zFEP(a)O#C1u{9IlPw9n4_&DI#KDC%=#~5+=P(S>H+#g*~lSGUp9&)iO8}m72pV@TC
z#CBv-k9|=_c9#H$LrF;A?|^l7j0Ex#_pu%2fV5)-y~w|_)Hu)|iAaLaetH#+pF=*?
z%t1$LI2*SVkEv1tYLW+N0tQ|Q7(zOwt5P{ho-My&ARHAvAp`^6tr-`_IAN{E441(~
zO=m5^)6NzZ<-wVk%>MRdh&Tvq;K{}e|I@EM&R@npmP$g#IrRK_kQv46lScv-P?OEB
zCk5waECMRcpRVn?7gLT$*{z_Hk#hq~cQ{Z!x9SfS60Avl_--;@oYkCClvWfW;C?F~
zOga4naU;ExQJ;YDrL7~WVCc6I>F0)El(x}oTs(uV;=+LHX)&Y%6&bl(PYtAH2HNtB
z7ZXTrg0#%DplWC4r1@~Tkgp=Lx8di@e_-BE;A&s>Lnsas^co6!6^)<5tbAt2B#@Z1
z7tJwDlavHL^^iOxC$SH3lS4tiXbnWj%su(|QWS2*lz^GA7;h4P)dc>)5i4;KXw24Y
z+~FO*f}@eSHR*uz(KlLL!wUjen?jo=R8oo-(N|V8aO<Ra%%%)*-!<SN>3?g9@$?tf
zhtrA7dw~{YM>+A7CKg#_QY}RqM2fKIHKJLiQX9`|K?S~?6);3L@+r#Y`>NRB0{GT#
z65H#E{dwO{2DoBf=~HUef4lH|7~Y^ajTA{fL*WqCzSJD14`?{A{Ygttvpn-p{D+o2
zlY5C9IAYvi!KDfQ{_@}3$=G5D3bq-}b^;lZ>vd;me1zyk;0(g{K_<I3x<!f_p-Yw#
zg^coQn%l>eYf-z%xUqoJ-j7fwZ*jddOPl+Yq0kJX?1J>|u_L;N;||P&izL!Z**jDt
zaeeu%JILujMBm}Uq9r^AS{jDIukg_s?;p7_olMqdw}q}J!CC!>H*x_c;lWog4YB5a
z+NgNM8v2rChqH+*+e~vHzmEWEf`@-TH%nT9$!61o&1h0k9F<qQ{h>+ao`m^jZPI}6
zxCY>1*Sc_%`mGKowKZYsc`vEbU^5xr-?TTum$U@Z!$8kyJWvnTIO>D7M?+R77bXqi
zI2)c23UQVVOPflN+C#nA*EST2V}F2g40LBo=J}Brj{<?Vy?fJ=juQ<v3{JZ0@4Ul~
ziCVR8FI>BR&^YdvU5WUWHEpgJTNkiB;qKl+2!RDmisixH2X-`g)ob~MQ#J1a*G`##
zNrvqSOPh_X#s2l?JZp{7rM+eOXmU+l9%S!yC)Z&}{kGO)2@_DY7rHO{^gKWJTdzIm
znI)yIn(x*^?Mk2(4t8&u8N>Aoq83FtWi@Emr|*Ns>MHfQYL#m1wxiFr36Fd8q7|5X
zX(42iDF<k^i4XswfV}<tf{lN1@Bz0D%Fh3V@?(oiBKzIC0{>1+?&2gj`<JD$6(RKM
zHv(0UIx_NBpct>u31J+rCBP=ohD{QGEipQnx<E;DX{6_xX)tpJUnv)v?Fpa}VUT3z
zj&D_9Vh3OPrV$EB5wZ&G2beQ}6*f<_puSX|f~0{r_0trIa<~7MsXDP+!v<%yUEEPu
z)@|f0CEL{zWt+C=b(A5zo{kbg;FgEYU0_lDD@}2+T+ms#Q$Qd~t{P>|#uLLJ0USC#
z+hW<>xzW*^SPxmovWL9izWRqWJU|7LGoj|HP!)*o=T|7_)mJfzRrP%9rN?wy?FxP+
zI-D%Ln81vwNIg_#QqTx+6A}NDGK`bs;@$t!XVi}9g*!E{P2t}DNLIO;LG`Z5h_9S0
zv$u=x{8eg{P`&Z{NAy7*7wqs%xefT^EO8zih4&Q?ntIH1JZ}O?B;?*94=VEk<GB+X
z4AE_BH@N<hSGa~&K`&!x;SEF?TtRJUl&Xa4^9~c(I9x3|$ZJbW9dq|9xn|#ikifc^
z)@5PQx#5I4Pnt@Vi7b(+PuShC%Aqs$PX<L+#OvrfQ~(}(_zu*xQAWQs!VB~8WYhdq
zdOQz+y1%5onaBFEhUxx}&dFQStIOVS0Tn`Tvh{NA+O8HD<XHn2JFeEgfCN9YAP;C_
z#-aJX+(UbFP&Cb;Cuf}Iv<q}oz17oDcrmLEb*=+RZd{MvQMv4D2y&ACK8zK+nyXlQ
zKA6IudjtiQa7=2ZFRPc(prVqm)#u~W2)qxroTGE@IC{GuU`B%L;Ci+V#puNWY2w!k
zlg^9XX3AgjJ1#S+{zgI>1}GufkKQN!qxngg?>@KV*jh2I$(gcQmO8y~(|MB|Ql>*y
zeQdIUc7Z~wg|18!@n?eUfF_2u&D=Ia8OieHJnI&fuuN*tu={o|5z0rO<a}EzH9&AJ
zLA><wrC($QEZ;GxAl`)o<MWIpH;QI%mAaGA2ubcLZLn7+H|##I!4C*AZ1#CKz|1dz
zw9r*mdSCcaiSqeXQm>1$)cyM3cA_BL<V{%F_i}zWK?F6an`-|+P>T9;5$4t9Eux}V
zxkEeemyr3v>n7VB-nfJnr%Wk2X4#X<yedmXw7Ex%R#+91t!sN!t{HPF9_CuzX`wb^
zcRaPNW;HUno12V6&obT;@Ids6PGtFydvm@W)}>bwHYN|SyA%PIfEhn5IEJ~gRBRo3
zL?0q{;H?P8mVe6AVn#miPRgq_?hcqLAV29-_W^4V8eF-p0$4Jz>+fW*$EpWe!rp-=
zB9c<*NFMfSo1Oj}d=x4+F5em$E+E*bL|ZRD$yzpChsCOzel1LW?Zry6Uznl8)j8|t
zDeWbN9v8ZEPLwWB$%;69cmG?R$C?ug{1v!o&HIjRxcAPG`v*mj+wUQ5B~H59Ear%S
zv3O<wCo51XhTMe6D^S+%HxxA(LcKz857it2q`XwWec)j&7Lw2%3Y-NIsXUtP4RTdN
z_U$>v{@qi?o$)lcB-%~GlTQ!+OC+Im33}nQ@^eSa5EsKRv^nuIt;X;`$rYeL$NxnS
ziq*Y;J*a(|-}23AUp^iE6*P;9=ZoHMKDMP!n6)v@wSZL5nSaCk){ldl+xZp(xQSe%
zfj5a8v6mh#4X49NjgTl_U0q1>!e-IzI3E*>s3U|IbfL8^#%1%Yf{%Lu;kX(Hs-TN;
z`CBa6$#kN53={G%0KR$RGV@q3+*bFuIE6I0`SLfrq1B02$oLyxj+12E5(r!c_|tY6
z*!?0a&Z{n!;ZgL%DcKC0$9nT5(25rbZtF$GMjRkD1tQGc{Ke{<hFVA~zrP!94TL17
zXu!Hjbf|}0tvR!cO2JWWL*b(c1LwzQ@SdJ5I@ui68_z`RgqY;04_#-k2o=)Q8pSd6
ziQs6lPpfE2Q@>rejSQd#QXG0@ocp@{iw-cfg)<&Q{^x4uBxpsY?c=G7RexzvLIS~X
zE}r=0b3bb3J-jQ4Lj@s29oXY{cV9O<QaH&q9nG3hCkG83;4)_|y)6ESxY#voqZhB8
z<NM+qp?FGZ*skQ&(SeUB&xWcs6Q5Hu2-wOfc|2x_NHXE2_IDFZm%2zdlNQIRU-NMJ
z?a_uMqvNe9Q&$<NcR`g+{4V*X>F$cH^iYG~D*Wx7G5<yhqiUHA(+tNNE^ef7T9oal
zdt+`L5sV`}QOcrb1QP-I?MVx+@p+TR9vgRp*kMfq2xeC5x?aPCya6$}HmURP3Bi>#
z$#cy$43YAJ5?5%uM6gO1rss+FNDw*UhBDs%uMrODRLknJjVJUZt$Umv_=E_Kx&B;5
z=;&sctSihbPzN19RSA%i88lZ>xVpM^atZ(w(2z*T$8T9&Q}`oM5T~4so1-F-ESDU5
z=MI@N%0@^?l)!^6p>RK&4JE#~g4Fv&{=+yLSdO@m$39RFFy;2c+n3UPMWZTRD#wWt
zlXL;6M`S8rq6wtk4Lr-GA-({?*CIchu{QrPa7AgfF%8o%Ue1|4By|HH%oW5uUNLXD
zE$0w=itN$`<1JeHZht&-+fTk@rVi5(H{l2Zn5Rv2jBXrKDRBPKgTB=*LnCQah<DR-
z?1_6tow?(*;ov#S8c<2FePrT1yxVyS{Swp^g^;Qq$u(9Fem&k6?OVOuiNLpYea54q
z4<rsDp~{ZPYkdCryTy{IHkA5@sfjw$FQ@_CBTT1jlGDtsK*|~@m1TNM5Uek*KTXF1
z*)Q$Ld~$l5@ZJ|}G}WTEz$XkK#SM&Z2E6q`J+T_Q5-+GDMnYxi_IfAZ!!i3YokAZ|
z**uGBpqLj#E?{06Pla`|D&t4q;cV>6;xm5uPZ@+v@*jMe;$*rRLJaK&-yj^JPE=cJ
z>vNlV45Wc}6J{?fH48HRSHqyvW*fWFU=(F+5We+AYE_&)<10|>)X>&t13RSY0Cr&6
zY<F2|cyA5O2V)U7_7V=^u@?9nDtlm3eNBcAnB|vtB)I*{4B2Fe@B>Q|(?*l>!N^Hf
zk6l5Mo%Bu3lOaWFVVgYR%Md|sXS~Imd;_F#)Fu<>ow{?k?u128(Y>ck$@es90S;7O
z+5r`IDZ4z61aEe%eOD`eIUH`)5GEVGr-HjLNOU-0m`M%bMBgX}2tG!xc@B<acW>Ot
zO-d5}e(fRhfg)Sd4E7MG7!?dF(SV>CF%R)La>ho$bZ<YGdo|il)@11taOoab_1h>|
zf6%w5ehVc3ot*u*oo}-pltcF3L@}QY+%B+#0<o6bO@|<(-w=VHHBufC=vhe&Z>uZa
zYqp|{-7M_p?t-^|ee6S<==cW(Ecbm-AqW5^@#KMsHVL~!2jDIZ=S7xNfJoyeFYHv_
zvNnH&nPNm&YV<)}N&*?z%P}K3G-FYl`F1>UD4!Xd1GgtRmtW5W#BN%CF<b<QzWRIn
zuEQa+0P!N$!p1NcC1eXv7^V57Q*Pwp(tTJQErz}v)Igr0@IDg8O9VOuxf~w<+BeGv
zKf-nkWhAU_oZZnW;aE`r=sJaOZW(KtU;9G_{ier?)-swT)Rr@EAa}i2FzB962Auag
z9J(SxWc;byl)D3$N1n>R2!nT#Cot)DgEx!=jrp;`*(sI)+2i7##0{Yr#~MadI)1FK
zxz2nrM>p<;!NrFEIP({hS}_IT1WA@CEjuQ93&3CmnghukIJGXa7`vk78DSKegII?3
zu%;pq6iSaoL(I@GX?ZD3HSoQk<La~oAIjyqH!-?m#llBFdwTYcT}t0!R9oYYRp*7o
zW6$}e#k~VK_p<n!+xDb_@JUow&l?~IQ(?B|2$%_x4UwxaL6LR$ROf;i@dG)#zOA<W
zPf_DKPlg!o)LYe=%E&0+rTV%~e8ZH3y3tBhY%l7K&@R9XH1`0Q4*^VEV9P{bwezdJ
z-v{X&^DX}7w3PP2&pw-6JCVLfW~``dRn~dq$%(pk9_29kJc}4OW3l@2(Q4SD-+FA(
zJmY2V?RWlwnv}mb+2O_1>;Bjc!<4Y^!c-+dlV%-jn47n<f{TVrW^V=Ox^VgCO<=HT
zsmvk=VAsMkO>KPV#(!UI82Ah??Oy0IN<i0lKtmG{&ihfr!kc~y2kxa}XTDjzYIw;f
zN1gf%VpO^w37O&lMW3Uf)TXZH;q&;MBiH0(d(smaM)liJ%bO9xPrg8boD6Z?nAKX8
z@yEhsiUkRAP<$|Ci2zY0Q2Zp&VPYO)rd@XiYFV_yIwGj=p-YaFyNV7HUddNx#1scg
zk)8A)>+;^s*pud+zfn(hHOELbz>vT3Ut@B*7u|UohbEvSl%DGTbg3)_qV<{qMqg*g
zS$V`jBBZvmBXnbF|1t?aN$ES>P>UCkPT*)Y35q}5KW#yPS0Z_#or$7K$isg?gkaHn
z1EzcE3@d_5qN+0kD7fVmrV@++LA);7*S<I>52x=#4WVX$MDI^8GhLX%#m911rE9y_
zBR00b;%no%&uu<rN4A9CY{id|mp`E2fM?^GtnqN8Jvo|Lm*r-+mC?d&?(zXFbS&pm
zRWmc7zrY=V?1Sr0_3FC4hJ1K<cq`(ksg85KtCi4@ni{rWCP}?5i>)e-ut1h2sPY<x
zsx-lv`_A`UT8Bipi@0U<T-H4Q^6>kS@ZVit1-Gm~DJAiAalcz>>6fzJTsd~sn|HZe
zC%(!ug4wW}KgA#?vq_u>@*FAHO^Q|}N7&H`<*f~vU-t%$L~4k-2bk5vnx|drje?cE
zp?gAMEJA_URxG5*YlXxs<8~oJ_Otk<7@r*wQRi#<X(fGSHWk@iLE+CVaUi4QNto(D
z7EVE8c{4?Vz;gBd&YbiE0KW$m2&pNZ`!w8-=8mCF5FdlUQCABpc&p<L_txu>9+I_J
zUn_Zy##2r#mE@}tI_V%_wCgTrk{@e;Ta4FQ0O;+u>(D(wX@>Owj;hqnF+?b723xC}
z7&i;o_+>H+w@3V0kjXrsM2Cx8;UWi>i@_;gf4{JNF=2Hb`wgB(z`7^^bD*mK5az2M
zzT8LE?Kp+nzj8SR8dhL!tewKKxZ#?6|I?I)==ez}GYn#slsMsPK@F^`3)E3ayzY;M
zH72hpNi|-=8!FZ^MOlEAt1_1y=?(EbaB(?wK+Ceua!BbfDVf+=7(onS{VzLro=NlP
zE!0lR>(#bFSkT>Ly)#6PS`jRS;L}X*Xh=a_emR8vUN>KXNDZ6A<g*n?<q^j4_)1b0
zMNdA#eAS*Eo^;-!T>VBB(w5SUiSbb}E2G9ewG5kSd5dYax-^hrxD1_fTrkf8?jF7)
ze<b;{IB`=5cnIU3`Z;3%H*q=@vTTaJ`+}1WgrD^-s^oy?oe3{{S6tFzLKDqBQ@4ns
zS*FW>&UQ2tw#aGTyGi*UD#)w@jbt9a<nKE-F_K5N5~EVh!;>(Cf|r%QkplGHu`{mC
zrC*4eO+X8%&}s<NNiIk82}$lpM9*Dy`zR>Y+@I49w*zcmU_R(PXY(O3OeNx-qZFFy
zW*Ka6(0|tVFRDt_ZCJ9P+tHDFklx&SkKn)vtJQDXrm6I=4oU@Sh|^iYoK9#Lfl6O5
zRFCZcz--Gm(il&Sz$@eLP+MMt&OES4uZQ_)1TpiOM`N<>H<^NBnV0JQ7j;fNF%?Ww
z*mVbj)r=>HYpdO@EKw0Vnd;029-AAoP}Z$GVceaAf_awBpzD-k+{@Kw)bpEUDB6b8
zNF0^qT=qvNEaPX$Byo=x<~GxOA8D9Is%q>YjI51pl8_^EM+HWXlbD9{?B?G4=9O0y
z=ldO-WCzbV!MKe^9!VXIbK`@ef8(Bk&U%ses<aGX;LUcRCfmLf@UcjnnFloE<yNjN
z8vN(qtI+Mqg-Iy%X4_WOEOq@g9;}qZn{x`RXq1RbdRq*(7_x^Ax~hBG+6#^>>m_pN
zsLYDoh1D<PCCV-GkJ#R;=UBartI8m^@06;zs1=tCIA~)rsyvlcy;Qqn91^cb@!UH$
z`IE#kYcr)4N~%4ge)eFEX-#Aj=j?(`o!lX&>k>bpylW%2OWq$Kx#G$T)5ydiHMsnm
z1lxe^Ymw?~iaOCs5JiP_H%x4G1vcNYu*<VIA0zkv@2LPYK+M00%o$`O@Cz4I{*h;S
zb<4;}t}U&?C4##uLZ3&<lU*xdv{C|F#1>>9@{!LRA#F1O$2?T^SQB1%P@RPU@aCI_
zc10QGS#a6Fkwc&vOZlLFMzV|mR1m;6!k1MBHhlPL^aZ1^{Y!%~MK{i21a0B_w<pdF
zw%(3$SfO8)es5b3<_4A><c3NX1KvqKdyV~TM10SU@s)WEX5<PKWPpj+wna=gD+-m@
z!U8XPVjRNE0gov+ea(`G?bES$PUz)+=V)j~_ktU_^z)F;t$CRO)5tnUWy!L)+$_Q~
z3=m$Dh_EC2|6|3jG&k_-CE~h$o4?IbZkb^0#1xAvEqr&BQdM&oL8IYmBVFu7Wc>_z
z3CCZ4k_-WOfG_B>w~~*=a*_?m;-qeH0zCDc-X}Ilh7IiM?DQ+F2wv3O@e{BjQ7*xH
zE#uTVTe^vq9Ij3x32|kgkLrXYJ7akLDkJas-q9ACxP<q~6z!M8|GN0(#`XqWHOT0!
zsr$~^$Ks#<2|<O$Rh6&$jSbP^)JVaQ`RLRLt{SjEn3c@$9%8}8UqKaQX?33`I*Q?_
zq;>)T2;gCnAi*hZzHb?Y-x7*yN1GvVcve`=56rXafkT9}hI3gV6!&`?wn@twF>%Dh
zNwEKRq;%x?1l14TC|Aa*VZ|^8+O4t=p@ZmpfsS#JiGZ|0N$4zq_pWmw{GL}<z|J5P
zn67OVuDW?f4lW|9s`zJVlI%Z7RlS{$uaPv5HnxqDS%rF-=kPGO=evaEygWnADnEZr
zZUsoCI8!QXXlPyOf8e(QCdvYVV=mfvU<w&0kkk(zP%-*X)c4ZSG>U@q<0XiOrM(|v
zWX_{m$8uyDQE+dTi^M7msmh~j*=1WI2&p=0I3=sjj$7YEVZsX%be81?31t6-O*4tY
z<Y!HmUO0bwEhJ~@xObl(7u)lh*bq?L8Dv~(znw|97z!#c>LcAJ4)e7{KU13>od*0l
zXG)FIRO{TT^k@MGS1s}{Rv)8iXTX`K-q$Qohl9NQR~$I<g#yqRg#~{g1G!WOn-J-D
z^F55!wEn`v_Zm*|vf>%K)_D1Tfo1unMH;r!S`5{(A@$5Lk#|hX{2u`E2%cHnJVOZs
z`d~gE5sAF_sQ0`s)Dj!3o)o6&l^|JxiUzJ|S<GR#<PCPYYP!x>FiXlJGn+nCYW!UC
zwG}984@g(9Mc$iD^TABmCQ+@v)IzLZ<Shz3z1VvKInC=FF+$-3x$#>QbeT&ErncLL
zzYcmRp)o=M;v1%pm}<lblBt#XYdp)|^-MCRqagRvw^UiwFsZLrj;Ey(f6mPif+eSn
z`OmiMwD6x;OU$wz`3WMW4Ln-4RHXZk2adGUYGuw(rsW|~cSZ@gI*utLjP%BNt$qwC
z8ahPtDR1QZ38cQ)T^mPS8fCrnlXHcF?z$JQNr&%aT<$w6@k^st{CpMyLCuv62maXC
z5}VacRI>~wQ}Bhso74D0+yMPTs^bPymHt>bC>-l{?#4(-3MoT<Wx$US04$i~lW069
z#2}TX^)MwN`)FmAi?M@)O&hBNV`&W9JY=Ox`;SJhfna98OAxIb-w_Q(SjEqM*RnnB
z81mie3DwZxvC3W-uaUdLX6snlC^hu467kOqVYd6R<0-ZQGBT>&m-#G{3{vm?fChNz
zhVjx~#@B-O+IZn3M~cUFXHCrfL*mx*-LLT(aQo;F_If<fttR|in!@sSzH#Lh_hHMI
zT|@{@p>1>~BRHcYLXe|i;6^y3#LGTNpja%&^Sny$FBMoakX25QcMmf(g=kV-G)t<2
z!QvXrWVIB_ES?~*n%72N<n^T9=fr*LUdB2?uCR|BiOphBJKCe$4F|$(kZ&zmi{jad
z2c^n0Hr?QNaXlSv%x^n?^ENQCXOf4Lb48RUGC)W}urX{)oUlcg_^^HdOQU=R4*+ET
zWDYA9mB9*yD*rJNHd@4R8G9WUD0o8L4>{T|-YJ=9MY0YJxMqG;CL!Ph4)1l_)e2hG
z=Qf@(=Rn6Iiz}QuSp;R*f)?<P`TR9@SRDnzfZ~6mS+3aCHms@Tx0FccbPgz=2?PVV
zF^6c?0j0fW#Gib`PeB$`NUwGS!S}*ngpXboGH5+QrK+rd6=N$9oyd)Jk+(5Yq{2;K
zfT5s(b&Jb#_?_TIpb%5VHUbot2RhBq0&CGIld?L?&SogxZmjcLb=a_(mfukOYjP1u
zOTtJC)6;7nQ;!z+j<%DewwqFvJa)S?eRx$Tb_287E+9p#KNOmj-vkKr2AIaN2{1{O
zM(UvN`W<#M+WYmFdn_*Y(x)!b0)?D!LJfh~LUT#Nh%PVtPix~VV6BZyF$G~iRx)h1
zo`?aqtrtS-8||x;3`$t^ZY}3@1WGga(#ND%39D;=jKP6yc0_@Nvt6<P^j$%Ohdjek
z7zqV4ci^R&5!<A)(Pk;nPpk3GZG%?kfXUFd3h_8%JC1Cc^+fnKc=($Z^3n=T&~+;J
zW8v=UCx}UJsv8uplaN%Q6>+aN%W>!>H4JwF;(>4@!wl;LhUY`eoiK_RRn_fqyP&(Q
zg`!a<7S-+20>YYKV_A~@)~iw+>S)_33`5cw^V>K#px$Hm5386ru%Ie65uk<5G{UXU
zJ8jdNmp|@V9WVu}l}zmQkH!$h{lIMe1aMbvKEp}H>rK}YiT4XveGiB!bP5ls1#0V-
zT$=%!sT{*QDJHv@w}aXSj4m_tIZ3C*^f7CR(j2+~5s(Asoq6yjUs&c>@*AaCq&^;K
z(97wd%*K(=_Ae*^#@4ldx671de}c<}AAl#QpIIx^Pd>f(31eQcm6mVkt{&*;=C0J+
zak7t5W<<Sufe^fam>Q-*7)+2N`P#=(?|_1Q#L1w1Vy9GbyeaNFBWJis0fF8XK77z*
z3t!+Z`ll$v9z2>)pJPFa>xpKb-cj%o(E`iLI?|jHjKw@UQm+p2FdbY4<257a!yA+^
zZ6Qz65Jt5Q-&8%D*FU-{$)0@wdF3mJ`jNeBOBY!xhpv{Q(DST~tMvG*J%dWeZ9kRt
z#9%BN*y^CP?n*neG@Hg&RyGqDvWwdPxT~s@uV2MV{!QMk7!|517c(23JtGS^H9nCW
zmUTk9nLpKTv~l>^+7s`#4A((!@{i&uNy#MUavYx^b;;-)dQ`lnvqVcMBZ@(@6W@EC
zPZu&iLTGUJhAz-gd@pv=&-?8niPjyb4S@&b{Q%`c%o+vJr-ElV^6Z?F0knzEGd;7l
z+-4WrvZf_+Chff9%j4bcC2UFbLkuf17(Q+{vQf%AbZRbtip8X&s#`xv%spV4?`8?l
ztF{|Bw&!(iTkgaWR77=II7FlkR%Ai49i^<CDFoD(3p73HDsPAQ6B-q8y>cM$gx@zb
ze`%r)8atk_S7^rITYB{i;g8J=aGydQ8UKHR3t~XA#(OoJU4pHU^zB^r3In0G?zQlx
zf^K(Gp9xRg+@SW%X8v#KmVkXDz~1ZrDa>rzGwd)O`$b;@F)K5R;i8mB)lZ(oUgH7K
z=UEljew!7c$Yj+Wpj1;QERDVMJTa{?O-_eqeB`<w{O*x=z}N+rWQQNkop6=VCDn&l
zUHx#nAK|!E+5@k>jG{G@hR0BgX{iZGf07)IT%za%Z)Urt`%a%whQ4|qvzUTTL!|OJ
z!Qy>_pDhNThDcDSBr)ulc|nITRzSQCh(fp!D<yf1z6G+@?D7MTg4nv=9pKRA<RzSu
z`{ZIqV=d5@+a=g^X4tBk>nX~kt&63dq?Qoj_!T%7gptT{nUbQ^!rz-V_~H}>(ye)&
zk)g?+0qA8v&2*QNf)q^{a>YrE5l<NytLL%4l9qsI8=7!D;E&4(J%<_5B*m;33cFz8
zZeOf<a7ezV1-%P0Ph;gymG4pFL`?<T1j;jTshak7IKqPPkI870=3&S3`)F<94Ip7s
z3p&`X@^t(%rsM5;+`l>KTOPGg2+*bB#U^681)fz*Qiq;(aGIO3&17uHq}EqGpfH!%
z2ikksYB<Ybefs`h27YJDWa}b?R^dt5on;UJw+*n4lU}Uh*Uup<*M;f(W80oLi&c9X
zm(x7cNMVBOAQE2qtE(Z-q--O9XstBI7R#m<ox@1HP{duTU2Qa-d}<!ZHjb3QsiVCY
zB2k#!{;xlRq>|!(zb$^}WdjqcPGN|YI-9Vx_3<fAiP>pV-%EmN+5QQO=%V#f0>sQ`
zy3p~@>yltJ5<(9GGADj{w&38S5T_8VPn#fwSWhTWWJ1qzpA7nwtW0NFl{h|F&2_D1
z_p&8*6Gt7|T?tB>S~TgM9YA<;AF;MQe?0f8=Ow5kDZyo7F&Lt~{De@{qVC$e&3nbH
zcQrX<^0qc9Cz)a)-U*p_10ear%B~G&yD6fSspmgpy=VfiITE4Zb%fNKKAU<mTTX@v
z6{pg0YaCtb500Xta*7XUf<y4uj7gLT)XvdpH^uw`RoAiIduN+BY_E;_d<d6Db25-U
ztsQj!he?l$m8x!IXt}Scdj$cD&8@~27UMqd>=qfA+Uo|FPyxtpKVEL-c8PNXJ1%4v
zxnVkU!R=q-{bZ@)L?I!S?#tt|Lb2-MW5t3J*BnVJaCnQ$uew<Ye-~*V^eynT8s4Ab
zs+^l>H_O7D&zfwS?oEp1LlB&vqf?nn?~<W;N3316UABF0hbgm-w2d8^xCzO5r1C~K
z2vhmZ_)hGz5$R(7QkWt#zIXsl{L7i|%3YFK8Y3@9MLPy%wK!=t>W#=T4l-`O`Y_}L
z>ICy*-81AB52fAt#N~n}7Zro4E*2A3n&bG#L?)ojCX$|!48YA%wY~%rtZI+3IAR4E
zLk9z&hX6!m8Fn6W3`uF8M33NcVpIwDXPBx_TDhTKik@QFl3vEmq$LX>xFn6xUbTaL
zr0vbe2@|l_DTshg?V@jO21kBvx7KyWZ)B43PTqbuRs2YvmPU}BhvuPN`$6E{`9F-)
z$syuLOOBBfNl}m2J=1IQQxZ}s7Smz$m_yj(ZL4+lqhu%yr&#j&b&WVOK(r$`OT+~~
z2z@Y<LO>jUY4CHqYP-hO@d2W>V!bgZ#6Pl_a(l*@SNz7>2owkm$zy^vAs`T`X%7dn
zidj%S+oJ33eU4D|HtgVzZgxCC8h400DHPB?a%zii6^z!IYQQo=G@Ykp%xPgc%<2?c
z8+cuuGulZ-SN0yK7hLT2dX2cH=FE1UqR`K^>9&W^$Hd2e^s#A)VUY~5KM~ol5mp}v
ztZ%UX{Ez7?2;L!_lu%_DZX}Hxy-TU}>`5B2>WcFN%{9_h%GT|98$s$lKDZ4}|Fm3<
za7+kR2nQ&e=RSCsoGsP83ie6f>%l0UGKx8@P2gmSu3@Ae@k+*l<s(-=uyz21!ve1C
zEj94|O7c9aKL0FC3<BLPpsqGY_X{ZS()ro4I)gqr((Ir5FdUe-Op0icKPIPnkW3KF
zNKk|6eWYyjRG>i!^^Kv7e~=$Ns0S;z5+3cZrbh6Py9}5rma8Vjdd>{7%N;>$9!~s}
zb&^NjJo+K+atyXN$f~UdX*v@qNB9)MykX~Ub(mB|P&(sN@^H^7mFx`RG74*S%b(71
zA>WdWg3HUZsSvLQCQ~$@!@xGIq?WnkvEA(>Km>(1p0(U@oiyC<s{4<mXpN^K<Grvq
zSC>pt$i&r+&`Coa&6WF?I{}K~U2sqduOhMTbNgYRCFH=OTvA*B3iE;+*a$=+)zH*e
zQsNcgI6-0g1V35d`rpiTbUL1L!KEucWCDD{hu{A^e6U=ROo4ko(nskTF~T_P_Z^bj
z&>%{S3}-y6CB4)YIR>S=Nk3kE^}TR!$=)(&4#sEgCWWzQA)0AU=5x>(%zk6fsj64z
zT1=nkcl};)<=}1!k4>tYt(D7Vlfp4f0)nf14)MaG>+~OmL@KDbEX70_bg$|RwcMa!
zd+ZCYg<IY0i3B#|$lm4NMu^uzY_MDoKrfS33YDH+JgzO<|7Nab<8w9A^}UPsaFZ@W
z5HxH9ujhyNBz_N4iG`y!+tL!$+AQQ;0FzU>)vcijmfClaUpBVruUMXOS8ht>;#Ej|
zCrg<X3NPaIHu-|iZ%8-~wDCywW17#pV9At!tDb-^HJ|h@DV=%?uX&Dni=8tG3+2SR
zfJ3KTD4OjaK?H;jU@^oZCbJ2qNI9bTSE!#Nvc(Cz*_Bi}6(c3DU>>%g7Jt+!oUMVC
zmCtwEst{eIR&T<!!XrnlKE7q7;`%F;ogL@|IovYbwwm*!pOGyJE`3;Ymza{RY+1u%
zA$oLP#}Aky_7b+{y8Ia~N7j*XWcRBpsBm{&t;i@Px0s~UNydL4>#0DKmpQ3x`D!O5
zWb9N@n$(5>xG0j5x9A2YXZ*lJx{=a+Y-8wUP&+2ESSxa4s@4yT5tSBTl4z8k3vs8g
za`u<Zh5R-AeK!4CIy;d5XI+k)q-Loo+f{)g`EhPN$iap$YVBAeWJsPNqp5`OUsym9
zdO_2rq7IpRLlPRzMO&wC*dTW+=*Je9=g)432{v^e^cIyBC(0w~s4+SEsZO<!PC!s!
z<usgdVr`DagIm+Hh(bP1xxcv?_W=7=H&Gf4)_q7G0CWc{p!93o<v!Z9utMra01LPM
zhQMIUmbpKCTMNMe1D0)X%t227B&^8dn=Dmf2EKPOaO=fcK^6k#ZyUp6jR91@QMLAJ
znWgXX>u~B3LUQ!j9N3mr{F|L@I~pW5_A<pZ-^H7n=aBUor<Q|1B&E{bm1{jS);mZc
z*-Vg;8Ekc6fCwnYLnPfY-6QN4E^3y7<~=1Fp`RF;o~|_b6%NC$CrAoQ++B4}+xm&>
zG9@>2r`{j~PtZ>ku=>%p&zTnl&T_EfRiZ;D!%ka@pz%S}iUoz+C6&~UNSmB{LWPtg
zsVP(ozQS~VrXn9aUs+F#K)LQtEs`YBT>aWQX?`z3%Yk2WUx8Z;IW%L8Pq`ljr)ww!
ze-1redAKrE<wA)emZ3l|ONZOLY`Z_MBP+{YnhTj79fh11ve2KU2=MoBcBIq_F;Ri(
zB4UxW*^tWsKR{46UHX7JMe6bVP&F%RPMzDkBXANHtLif=sx1-yR@lo5%(o`tmcA5F
z+8yDbj?2U~(%JLu2L@Lpo6@-!G<k%*CQ~~3m%%H>b$|aVtOwm42uaeJ?x2zrIb58c
zoOzo9f01BMcu2!$vmyedH|!n4QWK7T=s#l?Z2ZH|CM6_^CZ-6kJ3G(vq-@aSYiIba
z?|&1gJOuM)yQ0Q5748vgQiPgHtZZ?r*jp0ljxJ71;n$=S(U!wFwMdM(vf=pW*Ghq>
zu$%H83L^FJHa6xPifW-9oOpw(A=i`nnz!!UABoI4AyR4bFIBQkEoA&fDylNkFzc3T
zD&7*gK)n&qhCHuIfA_PL{|}u=YNLawcTC`ytnpc>MXL4M9u5Pdi?Q$0IbbX*-0Fz)
z3xMQ^o#Rc|i44GYn1OJr4gIwqb9k~bqnG74bgzdA*aB;hIcKwI(zOM`HsSK~pv#6M
zoT3FTb(Os<nuHKqU6Pwwx?O>Ai+O*+Y0r%$Q5}(a@7*Tw@j<WMOsG}*?EHj)0HG^0
ztIu~qSsW9>VlCqI90n<$i!%?$RF&Vdl<%VMkQv#6mXD;sfueKF%NLE5t-B0y!Vp}{
zso4N(Bz!6)HHD|(*VX<OrO<~Nn97M#W+1EdvginFJ_iHL-daECB;^ZptA5VcI~g44
zw6vxl**&Dd40x^t!~FkTqt0yRC4-i!o>K2Z{XxB*i+)y+xl8j{k3qO`$P*xk9Z+fF
zcWhc7m#^vBr2m?!7Yx3nJvU0ZRQ{G#AzF8V?4iHi<k(4sStHJ>mva|kwkc@^6)9>U
zbH?*ZY|f(!hn$nWUoZ}Y<Q=Q>qBrXdUy<!#H0pB(x_?KB3%&m?=PgA1-`e$h$j6Px
z(p%AEBOoLN;SxlFX;vYyy>}3a9(Zm0H?5=K$o>jkB3#~G+ehqVS0l0W!SDof(HJ<K
z!sMOIS}b?<O_OizQSG)72aM1k(<iGSR>gGlpBqZF(!@H^!fWAIP@Fo+DIgT+=Y`6I
z@4d7KIhV`{=Yj2Sl_UYyiG(>3g+LO<aDl%J)8w+~Jf;~iWtTww7L3LEV<GPHr9&Zo
z0k((J$q%mxai$-1V3DQ+;X)(P4N29$8hI<{o#8yBV%a<ys+;}3{+A&=ch5n+NZUR3
zyZh2Vpe)&U`@F&P)1!Q*p|{$H?pW5tj{5>#_<ZD9*}bK&AoyF_I`ADO=Y#2>0Wo4U
z3e;U$#%f>a|GKDK{C6}3T%}8ojrQ}WeJ@Tdk7JT+m?h)Yiji^EL^1C1$rYht)t3D6
zvxJ1qzH?uYt!JsdesBRicHUN&I5WJD>;hHT&SZ`R<X~p3KeyjZW5}{9FHE<+n5`Ho
z?{$c(0@=P?f(8nU;Ot-4A}NvL{I28sIuwY@^P%)lhzDM!+-AZ}!qoZGPj1n3K2pAC
zxS7N6?{}o3MyW1wx^#fjd<7sDz~d{ea2Uk2RggN+&zeKRx?C6rHadyfX5eyU&kExs
zM5o4b3<7@-a~t!TMmP1CjQ%oh)uaCwj>Jn7=AkFKxUZUP`)#bq4I#t=3W6*477|Gt
zV?z2R%dkPa30*)0X|L3n=zC#we2m`5W>_+ZXv+f<dMNP#ohF=)k(%93GtA^zUu9Bo
zv;wbs<H$fqV<1YElyBNEy>9c&cLLgIQIKQdc^>9<o3=kETIB`D6#&Yhx!MMRco*X&
z{aX%2VFP80s;1$^CXSG&n^?8Pa+g$WKKHJxV+xP_FqUKx;bA(?xovU1?7@H(`EP$}
z)4|CLJs4J!v6-FCP?J8~u`W=-lYe=p@kz6`2z6Tbx@rsBSM?pjBuj4;xz(IR>&}b$
z^&T#SEo*yd(W-;04T=(j;=1nLsvjk0hE-cAEH55-M}t1_j_3KAcspv5&q|YLpU=!C
z!(@O!x|;frDutHeCJ+cYsh~04>4*sg%uO1MQDR^%gk*|q8_+=I@ju@8NBN{w<W4EG
zkBk$em}pC)qMUM^rE#2EpCu=uTW%U{Si%61{y@(S8BWK|I<T`@r6@aZ@7t(6eVSAl
z-u)9<qQS_#Swa;bx9+!V7zNwwCpLy7nB*+_hC8}Ks<vywP0?zi<6U=Q!bE2ym!Cl}
zE8Y-QSgax9qqZ?7@Rido?Ua+z$M>M476Nw?M=ZP-!anE?U!Q%4OFt6~C4HC^?PHA+
z^QD>MMAEK-uc?AI0NKc|f9WG`>(C<F%LHgRVJG^@FHKezfT}+|9OeQ9R-v(9CrH{c
ziez6~2aFcIco6HTS07FXb~>21BC@NTomv6RZp)M*h#(MlpqdV#^G;l-?s<heYctO&
z2P60c404N=Eh~1j5c8>a*A`N9%$Qa)0~qz!JnZCLX-CZI2V(+@4MNHV_xd<R&S(xJ
z*Kd*ii_SdID3<9%^eIyP9I>ruwdl;FD+4iEn&`uW2Q6W^hQzGw<k}Nw6gIU}u#%K$
z{3yc4k!;MmuwS*=tBg^p?JIDU6uzP1CM;&||9dq({#|Ki0(skn<K+d9+2zZgS*YkX
zBpQU&-Bq*%fRj2fh+5IN-Ev`#0Ezj^_+2<%xRQ?;T-E(kWOp+1P>wQ2g3^bJzR?R0
zP;p8T4~sZF6zHG((tRPwhej_Am=4ScdkWeA0DZjOe{}yolo~l7Rp9*3+ItA(dm+dZ
zQWxTumbGj!BhWj2etPT8GD~eF71G;hsquT>;q5Ar8G#IpFdQcKnd=omb$V(wj_SFM
ze#?(dXamkt<g7>$Kju56thKzyG$znheX<<9I2@`BJY&4}W68-1nf&y=JN8%z$VxQC
ziR^Ai^R1RjV&gFXSONMI*o!2hw$a)1phZus`yQ8)jm9l!&k0O)MN*^LHpM%aLPo~$
z-~YyHMI68!X39?Rb9{-4Nb3U&wTRldRNjTO@IDlDps|V1VQCC5gwMRpXoG#l9o7N3
zGt4R-yOKM$kNTHE2`(eSA70OAC?0DYecQ9%BdTM;hEXDn$<lr}Ecf-`G={$rS5SGf
zpg_*l*+(7b2i?%ph)rQUUZp!K@rf;<5#+Gmvp%iqu<+Dmyi{;**Y%b%4N|fUQmtcL
zaRj=Li;V4#%-?VBU#8(n%1?f<tw6C&9d3j(2KXeFj_n5UBTHy0O{n!k%}p&vcslB)
zlsdPEfa-lnXeS9sFCncmkR08r^BvFcbaJOdU6YssCZ|mmeP_h0NpGEkwMrCgfO7~*
z$-}-f%zl%ad3N&2`!iP5T$+#KUtG`=p3va7IZ3>`dNgMDEtXY=hm2Xat>iqafqTX8
z;wqyLrsIf1kc9)X7IlS?!P}=?ga*6F3LN<eFi;s6ZFrRkruL2*ct#OFj#`o*`XS}2
zVpz&ActFLFKl{~R*)0f=ptaN}N>%l7tS?j`f-YF>{oVOagcX@YBJVeW%378i-@qps
z^}!@lv8iK)=la@(1Mfg}Q9!lmuatK|*EbGZ!V0QnB!uvj5hwC31|;KwC&JkVh|~&h
z)hXuZ&Mj;E<(B6m-b$&8YWat%rS9ccw?Hz9$L7X1x=%8rB0b#8o%jU$(>s|lSF9{^
zQ3d70B6Iwx_7%I6=;s&UrFQWVLa#_f>hKrLA9+aMpTwU86+sbBc|^tKzVMWWfdJxI
zVM=INeqB0nTzhdm$;6YA%ix}YTgZzCg5Oh~wV<sJ&T*66)@kyBusOzb$6RXL7$QzY
z&$0baj=ubkzTjx!D2rOdH;Hs?Y4Kjm4j*ZkrkDs$pbXdFA<Mc}uoxbuFw0?Hj+hDi
z=pLYy#TBF~6pZ*|-2H08^eoM(FI;=&5Zi#FtB(^q)<gT56f6u~klF6M7S>QQu-UE*
zjtTk~U9be){>vW3n3=XOs%=)5UTN-`qpS7Ymcz>@O-iwWgfD|F4MO;%m?>P@e+R)D
z)EscE?PR6)<vjS>Xz2$&YH9EWq^EAy;rX!pi-NFaF@0=7AB~gZ9+jTm|1u)VA~9%~
zrVY$FRDV+QK>@$b_o0Q`foi9mjPIy7WUR%swKr>QsM?@1JGI*uDn+e`1cMqjx>Igd
zP0vj}I`En&uwe2^@xt08HVjQLeS}ni(VqQ&zcHM!Sq0FNF=+;^|Jqqbo?XG|YQ?-5
zzZUPyZDJ0+7PYUOsT`#-{=B$(w-d(kqnOVB8=2A-Zw4J2XqsS$(9l(Buv`*~2{t9*
zNU3y55PoexIkNfrKzh0I3LD`U*kR<Umu0?jFtLnAzzhWOT$(7#h5FU%r@H1<&3#;_
zMHNY0M*zO)tUlxf(1_Y@p-y9cKz!p+@`U@r%lb)j$CCiuR$L_C`U9OxM19c{SjfM;
zdX5*7iOBXKSzp)@nxMAboWX6(q)no-xIU(zhkp8T%?o-y9_O<6%{{b$W+;Qd?!_mT
z{+mR$RKntzFYp?21@)yaP{GR1`xeSJq@CUFt%y|K@Pz5hJOCX1)&GNc)`L;k<&R#7
zJrvLZb%bg8!f)dSVqz|QFx709rng}LPTX3QuR5~QJL_As*xS*56XYSZjXiHwY+m3l
zb-cDBH=T0wECo!Up5hsZAvR?p)M@d7r^)uyYoQ32!f~Y32ph5p<D@|iew)^&({IoE
zV`uFLX%kTUH#4HwvGMT<NkxX&NwvFvpSup}r6%$Q_-f{!)yzjQbCV*x{=6!jyciQ^
z7=mT&e)a`aCz?jA-GdsKJ3a3+G0MLv#*iYMt|p50O1A)Zg9E6}U=~KWWq)S8eH*c}
z_B%+eRczfH#P2y6pFh8EH=o{7fUOIVZ3Kk-0kn{KGV+a}kbvwcdcS-u(7<wOB2ml#
zyWcdXIJR)L<8k;y3vU8J4pxGv?OhPN`L9lL79X%nmI=oTYR4#zr7z0=UG@5JwR6y>
zJ<}6V=@uZ=AA^sJzn29sC_9ihX<-c+*|<;iLzgAmM;Kfq%a4K0Ruj`5Me>B^iw9E7
zpu&H(MO9@+Pb~HD3HQ;ftA4zFXyBf*6uStdXmP-)W1*^>aL`NoJL|!CgV-VhZjcEy
z+F4U1^IL1$c_OJ^1cOV*p***jF1%DUW2staVs_$gG_kDqeX7}4b_q@z3!%#%M$$B^
zV#WwbzrNQ{jkQOKNdm!1bwo>t+I_<?VGBn{(yq7c%rDJL5Y<K;*}Fj|k458YDED&h
z9x#N+GqZ98j8_e4f6vpjq;MtW99!cZ<Qp~GP}kI3OZ2&@<OVEqubeo13t?6vH?y@C
zZl47#sxLie7N(~UuslS=Ps{n71*T8w7Uv$Wv2LUtw2kykPe;X?WuZDZgdclUBLi!g
zTG&ck^wqAO(4L8KgPdqno>jS>&G`JIa@IU9jwGTiCPXI9nPm!k_oCIkZ-Mr7C(iYO
zGrXro(a(!~Hj)A*W70wrP9ut-VtXI2k9>>|lM|NT@EbLOvhA1u;Ojjv&VPx@X7QU`
zZKV0r^)4|tL-qJ)v@v20h7)?&uW|+_X8K~pH*+=_q#0Ke2H2*ZKO8_A<F1hiU`z$p
zsFeRT>5{NQ<g3LXpG7cv0BRMh@!<4{{MVpBL-wiU=l@}>kELMT#2%K7YdRFFQTQtP
z?P4XEg>2YCtw_TX^=x+yV&G8adY>v3@w%Hl-D0O=<B}+y6>oask<gj(mK`ZO`aOz9
z4gtG1B&Mvb8Qu5{Z6=v;_TVvK<b)s|KTHL!$*ekrgeAQ-Hj)l@TRGmc^8L?n%$*#A
zkc-G?5bGJALIzQB>OFgoX?lE0v%~%yq(Rx_v`9M1M10so`gwr5p(Fxb5Cd^(5cqx%
zP<RswV96(VlhujZw-HXsn$7%=_HLCp#oT#Mw0U<$LLQGli&wE%cxo~KoPor@6EdC3
zktmE!3kgIS5czC&hze9IZ?{)FFu!hNmS!9V^40eMS(evW7yiHx<B0g)SZRJL6;P%M
zA!U(YoXKtdUxAUW(^4{`S@Lj&o(nHCXnDH^ah)w=rO%jx1znSdHnhmV1t5}7WdOZ(
zAtiHEw_t{7F4Yo)g0R4WEJ{h1HK!aiG;7%}w5@jk6AAmiX;A(Mic>EKdXJJktTAPM
zki^@0$%qqx04Os!NAm}5sCmKT1=MV4fmz2u1E7v4S#MUz0*_eMxvgUaO8Dtd|M6ay
zH0Hdl26?G%&YglAI{Pu?sLfaA&{9)_Q&_9*<4_lgPZ4T}-nkYD63?35aUA&E3MIZ1
zm=f=3s>C0935A~<UxQjnQ$wZrC)*btD#wh#43wc}2``vpn#i(rV@`1m?s{G9lr&I=
zj2I5~xwVNb4eLB4jVbLOu>&$K1<N5@E}H6bj$g{f`CXaQiR2b}xx<t(+^U<1Ht{R|
z^-`SG+50dU?BM_Ik#<;XrpoE5laC<>rB8)lNcy;T^ov$HDb+XuU6@hLNoS_{uXO3}
zW-8vIU%X2TXbk!{a>*RZR#lZK^z*c*gRf^%b^2{N*3q2a2uuD|+@&5siVOw9cBy9<
zp;`vB5P4##21~A-u0pz!AC|v3#)R80q{yYZaXE{l?io}_EU=T+y|I~)dpSOu4OZ$K
zcbN-PQnTARo)mg3-@FaMUTkL*f1A^au=$P3ZIk*i)qYTc#N%cx9c~Iu;kJ{~88q9%
z%V28)Qb9~kqv#^5Qs($_A{RP>ksc&K7}ND`48aq$wd)h$NG?eO^Lv-!-K|EiGLSBT
zx38?;hm$ZDezrpE-7_V-mRKEXe<nYTn<7U{tXnSd@tN?a&x~_l&3;UN{Ob!<hu~Ez
za2{GzO|^Yd&9<q9FmxFsVfR<cFVoCVAb>YQO@l#IAjtS8(PCAlDft&J07O*yKLHd!
zp&qEkLKR<w)w=$yJv4Qg-gPUH2BGlnO?`rG6DU@Bv*Lx@-%3pA#{h??chpfHZ9v&d
zd%M3p`p5`298T0`p>5Vp!&Xf++aA1PqjuTO4(7#=!53_6#jH`j&iAQ{ZSK_LH)^Pw
zMwkP2yh(x*@KQ9T{gGaN1{P!RE!jV?G49tMgp>%j$rOAgU|q-Fo^WfxDqR68sywF^
zSznLc8j>95>#Qs?7V)bE?OBwlIs&sH3;l(|b$eVu<~ZF!G30s`dF6qq+HueZJ&Jx`
zu4CeLke3>5)~(q|u28Of>FG3W-7R1Vfn*%XPI=ySYia-4uMKr#Lr3SV4t}gL-{NMV
zBx6gnFwCyG12G%^swY5Dpr3U5qU#X}6+-Y3>aZUNoT9@_fmQ_SD(Sqk*HK7bEH0FX
z`w;y;tB3$ANV+F$PqF`x4H8cTAxnaGW-0BaW4YHB5u85surLZe`ddKcINx?RkhN7K
z9MouVX>SE|fjM=@HkUYWisSiw%~GkJtTTBUlA$i`{6oDM!u)Y{3^uowN>L#G61LfH
zS|)*Oeg?KhwgJY8!>>OZLxMD9S$4j~G7kf>?X_RQA9G4Xi*mAXt?8ODxiJMWi9NAX
zOIwt!AH7(bVP*eMl?idl2D(Km*R8S53P8E~$FPNCA%8ZboO}6h+k;e<DsZue_k2^#
zgYj?fi{^Qc8wE9hwzn!@V%70vn=AmQ{aR0igJkQ|K1H5xZ^Ps05I~K0m2*jRU!CT$
zt#Hb-u-!i5x36w|z2Z9eZ%g@cV)<kSeRJ=PrTW82#sW?h!`PlVDPv^+F1bSk1Y{s^
z@Y(+b|J`uKeuPfIcPgpXp#^b_oeXrn5@jC7eS_D+!cQSn<z`WPJdmmdZVH*2RKol?
z8Pc1Pr}Z$SmQt>f@84b}X>e>DGq}|l3CzI)<>@+>ETFTm<{z(GFJMh#5bT^nj&?Y0
z!fAYhv%zDm{H?$iN-V7I3XA(893L``UELR!Dhy2*-yCoWGg6<s_?eaSn!#-MNgfmC
zw3?6+I{<0myO*`unAuCVJRxYHTYA85Reti}KdRs-yHER^#-k#0Id}r+Ve}ZJ{|WP7
zvGrEb!Z`_?l|fubEoN}E%C46~r4=|Er>$zI`@VLX{fZ+!?PEMZ=M*+NJq1_A!fLZ8
zRdt@^%QIjo6^;1Pkyy$7oYO7~lm8R&pScg14d*YKzKBVyrg_0eLW1&i5xOXSaGejQ
zR*?ds&IbMnQVq-(s8EL*C6kcP3;6Nuy4(xg`+hFD^iDgePH|kp0RpKbN$IRJx_E@+
zi?FlvtJP@z#LwPu`Z>&C_4`YWhI1JXfJ*i(3Gyy}sMdeJ*XlNId9qa_r!BoDCQ$4A
z9wsbl%|;a-lv#NUm#6=E#|B3J_#>vpQC4a)87Vz<WMzpEX7_+kY77-O_#D+H3mo8R
zy)GGwl&TNaAdmU*%n4MG6vl$4vY*o;7Ov?t`246+wSnxn(m=!vE+;qAPY*vx`bzmd
zYyPpboaEbsMv%Ol-K?0Vg4RZ#Q$@YV?`J$7--w}BopAs>&fO1ON<|~YD|H?ni%NAj
zBjlhpt=;Ab88856;SF}_wApU3!A$hoDTq6>jVz^J_1JVJN~<)_>4WIyzh`DNTxG9h
zfLIh4UHm;#{Bgj<Phg%OjSax4Pv)1icPCa!LDBPHs0Jacc{MdfOt@KJm4zL+sb|bZ
za`b!A(p_+LhVj~kR8%bh@d_Yl2nqEO#xpOYT`#Uv;)zAa!?*_7#ksBEq_CmJ{U4_Q
zKm+`H&x=(8GRwvo>%7@llBx0H))k70sbdWAXnCHXWeob9k6XKZ9>M$h-tsc5M($Ah
zUmEYG(M0ztzrzmtn!aMfy(496PdijZ?#lU(8D6HQ1kt((|8Nh<f_(1m5Y8jz$gN^w
zlC!sgNzj7ewLnjIR3S^TG|&Dp5PURCrYnx$*5xy4KMT^tRQ4c^7oW3v*eQK6ab$U!
zYqo0nuWkJo+fVJacg2@wgsCe8vlQpZhf|Ml$M&U0>3PD*CG#r7lA(qy`2>%QP}mD;
zIY)JD?t+m{?tkh@V#Dbi4>c;jrts@axuEi;ob%w$cpI(Y;wX~gVG_L#X|QRz%ailI
z_l{jC8g~%>JJXAu`--#Z;G>BsL06s(gf<{=ehQcV$b+>p&Ecy9<9kC!GA8=tm}Zvz
z{96#15CX_b4ML#N%_Dl8@J2Gu*DUU`Zg5|KMH~$9IqQzq3CHFMEp^(==LxCiK}i5%
zA|t~bGe<&2Glq;u?>`B2v{6LH!6d}urH10(O3nfoQ5#{DfMV10tHVFC|7RRW=HvmW
zIdKWt8^q0&#;n${K=-Nc4y`k`JvVJ~#W@MT1+R&|ku_Ja<W<zL*yAJN;2vX;A;h0P
zQy?BTna)|2Tv6G=oOKGlb`MLV6IX;1>An)`FVaqFT+m8%uS77rSYnHo++AG4m%p4M
zk2{oIAOVcb=TZh_@d+jfE>nGP)T60wU%j3?gO-wu0GLsUF8rRjqV0z#S4Ok{Uv*^2
zmkzT+TG?4S59tvPg21E!SXY!Vv7Z38-d+E1fG8qY@H;JDqBacGfPo>eOMINGTX|SS
zQ^A1y6dq&I93E{V2!BXo9(+AeXYeSZ>^r!#cVgw0S&)+x_Ui}HiKM|9zMr~W-9A&H
zln?n&$p$6np2(Mo-fI`LAltKk6X;7y4Nf=Ed)*`63<1uB>%!d?xy^9}02gY~*PMVR
zoo#w{f`)o+f+z;|x^hB*+NMtcxEhr%kzy;e%n^|-v;pyaq2zm|Xrpm4z9UzUC$|QS
z$Yg#B=>V^(C1}A_8GJU$>Raqmb)%UouROOy1|S)bv>ks1o!rRMC;6V3xA`F)w>T3_
zDP=fUxp{cs6H3vF!$zhZ@{k{K|8rMa3%<QYU)R>#GsCBwNiTGsGlP6Yf6Pq0*1gmF
za8O9{ALm$}HLii%RlHgH+7_<*j8|Z|<r-jT8}hXNV3~WtZ4I_dQkW@2yW)7ovuEwl
zbnjnBy9y=nGRwS0oJ&rzVSIDgJFxYajrhfhT^4x6t;j>m{4F)KCI@oa$f9@Tf%K~M
zZRraqQr~g*zAqDOGcFS3(WNnQF;zuDJDX(qmXXZ&pKF>_NJSpL77&i|RbmozA}3~#
zP}O=?X^6WLAk$eTe<>%=wzyGGT%i9jXq{r3es9YC>8l1&{Lc;CT4@V(i#dnLQS{-?
zyXj7fL}TseoO`V7>P=6Rj;E`Rc5oR2@ouxh&<n-xgu|kwacF$l!e;e+pqP8hD7v|&
zI5Qeaf|t=G>Lk*LqgK(|N~Gd{7inVs0qRHR#2YX!>fha;Y@);mLo050?yK_KcQxmE
zpdTe{z_mV28oZ2WOIWhbGof`V&<866|5T^{LUsW(@2!}Fsq|*G<?2B+M(%Mp;3JSO
zxX=F`QXsx9nzRDht>hpBF|HKixJA=;okJkhgt{RArRwSxiz*ms(EZ8qe42A8zP|Rb
z?ay-Sn8VMR>q?|8nk{ji<5Xb})UxhGf1|qic29%Z$m(HEF{nC8%|ATU5QabNb37ft
zbQ#b`AqkRNXEN#{Qhsxo4?|>O9u>O*|45;rhI`<>;MgQb2~u{mYIgsjgG?(lxJPJL
zgqsi+B#Q&cL;9rG%*-jYo|KKMOba6}Ff~N87(i&(r-iEsyRUT;U|;7-J{0J$ju2Yu
z!WeBS*Is)m{a(B?Sns-Kd`n%%9<FU{D7714H#_;F$(p8{A4SU^fc4dM)mV7yQ;8^%
zTwL0N2pdujjnxtewkjAD=mjy5{GVl+0yExhN`6d?{)O>4V*|qMr1WdzGf}q<%Fl-5
zt3kA}!i+@vWhdDiziZkovB~Vm6-O22Q-$jy`c=fwn)G%2NHDkiS;-pWclvpo7<;MW
zMRch~%46W)v4Jo{?_y$b=nUL}kO16bW(?vF(ziZ`gOZ%<Ew{N@b`5k<4Ie1xPlr6s
z`mDh*_|?lTf+lDDA9)jp8&?gCyV)xlQCMYfZ>7ReIZ+Ee-I@EL)-}TJ2v}Xb*nnS}
zI{3+JO$O)5CQ-wPAhmovP6rTYLR(CvWLqGM_apgH0dI1CIZJ6^Ox_M1pmv^g93*H`
zz-Why(^UC>yMeGJWfKFPbgXY)?qoRAMlQz)E^QcB^~T^2xf-y9v1eA4us{osaZ^l1
zSHez333*vRs!s1n`)?*T*H;8y)|WPOnB=0TZ7-6331Vb#&xN<I)7tXH99-e~V-uc=
zNp%Aqp#b=uiuLeE4OSApZ%P_yX%-8yf5K@oUG{rB*>frdplNBjPK7WRERBz<Qq9w`
zgvar$f>}W^S1ed8fA&1IE;LzflgriIi7*vqX{4$`EyqN?--g|*4vhNt<eCuF>{$_W
z3ciwzFP>dZ&P^M1^qMWod=Qr#z3Jjd0U3Wjcel)u{DPT2lUOJc8RPqPhI>T4N^-wj
zY<l3=f2q;+Gxq?_)=QN*D7PHS=;5OeI>MLLL0rE+ZC8U`GVf>%5uz8!(<*&&Sr;tc
zf<TWnHv}W5D4n}s_8Wq@X@Vn0VCpN#7m_`1Mw@Ub@ttL`#r$u}L{9zHV{-<c)n<d}
zpN$Ku2);_#<H^~zHeJ9XI>@{Dexk`QMg6LQs{|rE$~^|tzGNG%A)ww{nNOJ?!04z_
zQy-B2LLqcbrF?!;9m45Q4>MdHmnbtSW#>A!Wt)ZqY#eN?v?Nw^z%`{#Zl%p5IvT3r
zE}t=#iit2zWMoyy4ZyxV@J;!QnTMv%R7PL6a8+Oh3gRM!Fh%M0GQ;f>3=$bt{OYR!
zR<E}>&}05S5nnS`#(ZW+tbEHLow=J1cAE5yEdAcO^#!eI_X`FQ;m_u`Fv2UdCkgJu
z+)E(y4rBRVS<15TU~OI1T~H_`L}*Lz>1+fanIg#_X%L=vjN>S)>#QJR5iU))(qNJx
z2x|o2rV}|KbrHnF{v!}Sa{&M{l?*k)w6A4nU81sb`Dx|^$a7mXt))0ZSGz_GpMAf{
z2)5krqa(k_e)Ad~jGp2eHA$fyJfE2sdC)=aDaRKwq>|a96GGA9!&pRYl*sT?MrQ!3
z+J|xS6=@AcrU)tzG+)n^DeKC6Bp5Vk-mvnRx1IZUM8P{O2hUx2A=tX>t$gqV8d9AK
z6#;J8>!0)@5s=LX8XoSFk9en^PyaRcBYsWmy_#<!-7rgPD*0$|Q&2)ia-vv(3T3L^
z`0nap-zS!<$5alEfd05rn@97$h(w_4R*jGukz7<|qh3RsS(JBxJ8D9}=zp2;0l8}m
zlZ12=<`bSS=p4=kh7JgQYWC+^@$swxke_Wi8<~)WAB}OWIo4*_`8p6H)!5}-H9tbI
ze-?zDwcid28)<v0Gjy~V^&O>Yn^ey`Nf(6Fz)mh*E=_usKEwSr?{5Q&{=qE4Gxqpp
zXYjFD5%g?ufC*h#@ZbOn;^i&-Zbj2XTbJ5Hdg8>KG|#6?E_sh03Z3aG5Fz*Eg3`I%
z96)Pd#6%TJJ;d1<y&k|Xs~{A9B~d2=n^_GXg{qPCVNVV{F(l7RLVt!d1us_Q&Y{QU
zjdXEMrdaXYtH}~ywuS2S4z+&YzPD7`0IIZfA$FkDcwB@dUpxNnE+)q{5ty>3xzyj`
zi|)tZ^G*4q7#d*GKIn@-Imle{^6P53d1`v1_j3E4MX^o>i%kAmw>eOT<=DWdd*yOk
zZLk%i95g+&4R<J1Hzgxkv=8MB4K+Tyf@58P23S4o6kG&k?F35@mZAu$dY)Y{qacA(
z{8~A#=y<D03)V67&`XH6<`?Y~X0-CxTwlz$O$T^JffEtasfaMiBaasFkA}>n0OQ~5
zB9|g1Q4+$de_gc_5;kQOT!N3s))2?UdXr&u*zW?B*~FmN734;G&c>en2xXA@?yY?&
z={yREpJU*%h)&7h3Nf69ug9m~2t;-r#_dgMjbz(tMSbv~4NLo}5%*yFrDFog`*C5y
z?{E*gpIyP*!)|wD+FVwZmzZ{~T7x2<Yt_KJpzX)@8sBb2+r%ddaGHWwuOOn(D=sqZ
zdS$JVBBB2l%QWhLBArau)%r~uT>V{e>7=Gms!E!}nuD;3eLk4)xw`W3b96R=955n|
za+x`H#q~{pIls(3Hn_Zg&`XR3RuLb8d+LQkpEC3?VG6cQYjPP8T3tONzV%jt5eb6w
zkjw4f|LPS&HGM(0M56&J#N|_^F%99;fhtB-WyPAAWW}lw8Nd^!eRymoz^*~HQ+c4T
z$k?Qq?n6mx`@J|eoR(H8=7MHE;(iPc(SvQEW;>2JC>_Vw&X~9vLsbpgo?qXOLvj3-
zm0+|aPnl|L*y-6${!>ZQvc54glfu;nVCwE!J!eO9C;N;g|L?$}^f#!q{aTt1`7Twr
zlh~oC3OzEwoX+U9Y4eS6XXeqcU<k;K5A`syR>8&Q_C?}_`RS-{K{6`hZ;}az<{dWV
zFpW@uaGfNP37nn5?QFw>z2MpkTC(}U>N6?CudolmQGGfqVfVO(el!Dw%X{L|vy|fK
znj#b}i7!M!7Z#lG$yQP+WVYJUF{~@v*f1yt9x7?>yHvr2`lC^xWYj6n4_Fs+GL<Vb
zmOCoIWV|G+Yvf(}M4HU-=+UH=t<&YJ-qdNipOwNhO}(a36<#)^qN@MHAVJOu?7g9>
z58@*&E+KpxInn(lp!nL*(_{}?oTXYHCCQ82i*dviBUKa#l#(#V_u1@8-$cKwa9hA}
zXr=&8lYvX*^ODzb{LfQ5`o1*BY^`>ZmF3ESg*WqXIGo~e#81cVP}9xs@pj89t0QK@
z`mCuab#t_|!H7v5{oaE6xcE&(cCg5nrS(ZMSb4TjKo!^Ha@wv79Va$~Z*0&353PDh
zFFM?=IJI@><fC)Y#A1|`Cs&e7(QI%^?iu4&-Uw%;sg7<)Zmn`_$Kc_q*4Ngetc_@5
zTsAw!x8zHf3%CHj96u>)>F(v<rJ-WF7-IVTS_l`;Ks+i_D&6BOc<ZgFArY<h@021{
zxEDiwj}G0uDnjT5NtUvb><GIh-N&>}ItJe^W7RYkb}ETE6wSXUIX7`|$54#$ZS;!A
z_l_v|Sc?dN)K)5D<F6#A*LP)A?DZYLSD!g1^mWrIa$z{F2(0Di8TvoFlCokCO2_pC
zdxpkw2?z4J6MO_Qpu9u0{*~;ep;@e}?tWIVrOMdeQDqmm(V6S54m$B{Hx$_EQY`lD
zk}KvsQ<g8ko`Dj;CT=Gk(FCJ$;R|e@fM+Fv$@)RkRW+S)r%vqCcI}zKn+8EE#>3G&
z5T@<`Hq;Q5)zHOSSO?{mOsnSV$<7e3DVv);A&-oH1w{8$4Y~OSIV*;JDFZrL2Ggz2
zP!5dvT4AA`17G#88>8Z?abYomz-QGf7bJ>&c%(_!%Lq~^K?yIoC<tvnI51kYA<xoq
z)6T4dr<*^73_BpiL(T>OqNe<D0=%+e9TF<eU{M>NSx7xVCt38J&xh$gXm#D;0cy@)
zvQTPmqT>!#F5}ljuyZB%rZrO+LR&Utg~rlE19HgYlWE){;YbXW+af;-*!uaPQGV&4
zxYvGbZ9TI+-v=!{_4RMX!dHZZ8|p7|uxIkWUk6A}cTWIjVW9<*pIE^H&#~p9O1<_c
z6Cdr5Jt$jr=FEp-FloXeJaAtzM{-VXZ_Y&i$_{-J=REsP7BFwZR(-BvoHv5EE>AX~
zP<6NdXhDkG%PgA9e;&h>?V`=)m1B(@xQrPwwS8FAq~P`y2xq8K8)<-oCB~XBDZai&
z)T0Fn1Ybf9=0vkG5)+@<$v?TNb02Gn?sGt(d@3nCWO|)w{4u0zUY337UD65e*yM_P
zg2*l>J0YSD%RRZzzC2qC@k2+*MwT!1abxn~U7h=TU7Klug6oR?cjy2?K)$~p4FM8s
z@j2TeNp&>^r6jO*<~=213{g@Jxpx0NO7=5d0}T;GRpgxIQ~IVquRfm=($agv0V1o-
zwa;)lqHg5>^W+njca0ip;!EJpGdR<Q<s)k2Y?D|onpwn2Pl7~bpCAZVIVGS3&u3$m
z+0F}HN?VX>f>$jhrK=}|zdsZ6;?z06>fHGT3qXsXW};GEPfx8ucK9Hi&J$H7n0AxX
zxSKaDOZYO(<$`$q6R-hXWf2l!AE#w$mf!SgLMAHT)MZ~g`U!^vEQ9Y_)tgwthcXb5
z=Ie+%e4wi+?$nS_p+j6)2{IVC(uz<GLN8VaHcLkW{56dN+EgNCzvp}SRRJ(?GYv=*
zJ9vzp41S5T9~rttjH8S4#7z7*{nZN=8#xRiEJV_`BB+ymvwVwYDJsznzjy8Tb$#}8
zYeSH35-Th~XN+V0L;$UlB*Ur^0LEh4_CJQoFZO@Ji7czBkqVtu(7B!zeSD<t#?>^%
zutOf%ym6r@y4!q%h$|)z%-l^OpBfBu6F%sS`ouY8%VVbPa#k$u?oPD$Oi2}LMiNur
zDKf<=bXAM7S)oby6abb$CE;P61<6&QlRowo%cFZ-&T8=G*aLMENCs#`Cz?3rHpL-I
zEY<{;wbd<RMu-)7kboGg;WiY0+u?;Gs63(bR%R90J<D}U&0@nvFFNAvib|wa9#^>;
z`7hk#9rJah*eOf__84o)8P$l;0cAR3R<_>{<5LREu3*!+$fCqap6WJ6gp<FCb8jb?
zxl`ga>P>6i$QmwcHxO0$RiBZ32QDX|JqiZpg&T@=G5l4nxQc%>Ee0DX+k+Syv<dJZ
z5@9%ATwi8X$uM1|g)JEHjT?2UR)z(b)ImdcjZRW68Fb3Fvf;CjNu}J|k$CRfwoH%m
z6}YllsACX`mQEnUkV}0;9wfms4_-%<E|}WAT3IYbRg0XXi!+OVzS@47$PDk;cZy>;
zxL8Nm%M0cY*0G^4f8uRdDc6qlAgFgnvm&zN2M9*DTTUUIMp#CnTL*`!&pcmTgsT6T
zdCO{f#N_r2%M2~;)m*cFj49ZlINMB!ZW-m)%PuqEPoWz1)et>a4#<>SJM!J4Vux~(
zXEFv&r9Taqg`y>woG-~mw&86nHvx~vMFF@@(4_N>)l6M7811s%gvAGmv8+o2@^Ibc
zoUHCDYMwQ1(LgLAF$9znGL<EK+P~7iQ9|;9hgPM576>HI4cFDGeanxx>WtIW!U#AP
z^P#E<qg}vJWjoJ3FhYvXJ3ryg(mw+3Q@(K2Xz&OZs53ggIS?8Or}McuZ~8jjZx3D6
zja*XTqTb!OnO`zC863_5k2=qBPi=p+*Bf($o!a!*b+TpC#*WMK*SxvveD_3@^jzKy
z>vkuNtPB$bA4t`_#1hKkC}?}MsD5Oi@_oD$MqG0z5A7_!au;(Ns?eCYQh?3Up?{DB
z+c4B^_(cx^DbqiNM>|-%=2jzpSQ~7I3PaH@4`hkR0C`^d1zC*vZfvRb(g!Nt9S05X
z`zUUOw-zB}HeN%Ug1{Hp=02FCCUGg0qFGLc%KpDJm9z@oMCqq-47_mKUPi7X1Tng<
zJpWnuX<;G=VxmuYp6-VKP<5$C(1w&F7*7~#FgKN5+g+-QU{Xak5}nw|>T|K-P*C=G
zRZ=gi@JNI|6oI;n?6bQc`kA)a#1}@<Qj(lYD&Go1T_2ag3?HxQU8#m*5TF_-sm4NW
z7tm4YhZkk(&{ko|)BV7%f3KQW93-_5TEY0s)VUT_qqx*nB!^S+g3C5JqV$zvX<haL
z^5)JEa}`s#iKyJguGeueB!^LyussG;D<r|x`c4k6xZz5cpha<7W0*EPlnBX8=y4kO
zg?wdRp<!vo8V3C#l>>ozMo<|<>#A=>$z5IsQvQQb6rxi7c6G5z4Mz7Pg5(wj-TKZQ
z#P{1k@3Yh{C^1)v9M2h9!#IL+U?f}nFBN5{1B)0|V}BtEPAv^6>`nU8cHS*F#)6so
z$9gd9eWr;#q;65pyF}AL!XIF0LZo;+n1d3l*__k8-7VR757bPszF$t52;E3W<uvxg
zE;|W@34nnzwI^ji<9htKcOXGulIni$be{6(Nul=L^TQRql1KL<c+a_Q`qa<uEO#x(
zj}*pXhXOOq>`H`Kg8F<JOz>^2LSi`OQf)+9GF~J(Xb;C~kBH^ZLGm_2=z%z@AcF3^
z+pRlxm5yXuCWR`l?lk}T`@3$O6+02N?Mdz6=j4~Z$WbDVj_rG@@FkXdY}%)9ng@zt
ztD~4?m57^xJ&ci{@&qn_{4mCxW-<;3V<nc8iY^ysnEz872@Eak4q=3YiZE&kcUUU2
zga8B)V!sy%NEfd_^pUA#lHIxF8R@FoVkM5`N*kSpXXkx8>Qk4tL~sjo<yt)>zCR~h
zK7_j!b;uJuI1bgx%%t|#{wtW&j#zo^{L1)pqJ&QjMx2mb()ZfBG5O&JMy70wWmGy}
z1f?IuhW@q<1=mQNkCBo6<C-|Rr&blG^fC_>?_Rf4w;+b`cJ}j2`n7-&(UmI?VT<5Q
zHl#mZd{C5H^Yt%9OflS)gm(Yt)?9H)7E3*^)8LDG<U~UVCNjW-@f#1jnhYx^)X=Ar
z^rzt?Hl#cX%7~4ky7>)^i^-<1eYr6|NlX6B33?lIO@X09)upshBtg)g008(d8$%)X
zbBIy3&tk~fH0@sA%rUZn{4>S0KFSh3UU8y7r>wla>7=LlMo7XYy}8Ad0N;OrakzKC
zR^@9hSYXli=4?r>%+T<5pjk!JHtsi&)j6%VLFC|2Iu`qJX-xldi^F%__tv>Pu3tKo
zz6S0Q$V{%$2sdbysp9=Jkn~oDI3+u}_WTB8_BMFH1Ee6@b3oiW44f4V0HpjC_AcMM
z5@*uPc~s+yeLzF;0@BsQYr{QgTc(&d;Ln{(J8Mc@*6+nr6+T=4%p46-IHedJptmaz
zsqN0`{Rp(EI#+bGH)7Qq?@!=jIjhoMU5Y#EJk4Yhfac#G1#~oo{q7T%c9FRzJe~H(
z1|S;NQ*f$F!^J+Ww!J8|x@Cc+L;ginNys9fGw~}dAHPGl4U^M49{j7#h^jd-T7w3L
z-~WZjIDq8a$0CkA#9iSW%QrRk{bl|6e#)seBEK@f4I=ii4&cMAhPZ%nVC%{c%;VfM
zXAP1G<xDmrYG4OToDvpLk~6y8-ylA#=nNwwJbe0)h=IZZVA=VtHOIp#4C)6l>h>Xc
zeniEe(uD$V9Tv;+2Pi!FOhRK$B?H^S8M5}zmsItmA+3$Az6l)d)r|ePzm#uhlXzN+
zBqoLzgmC^kG6ZnT8rM@=o#gIXL-@tFvk{E6g2<-JC)@N!#ZA4}2W|uE0lOWjN>?Ks
z=0{Dh@7zd3JqB0?Wrq|2>_rf)8;7Upr_>{nD9Qk0HTe(_@V1dTS>H6F>DE>#FJqHu
zlgDrnX~k$MHP8k2esA!*iIiEc1#(I17R{=^T_S@cW(ho9qpiv2Zk>Zuxqh3fxW*7y
zfv{)0z~$pI7i9nj7792Zx{sU8^TbvxSq97IIRuP+{3^|*YxU&A15&7r>6v>MBPee}
z+o5An^Vs8@*o2V7-gx*S!0<e11>tzK3Pc^yO7V<151tyBxwRjWvb4>fXi1tAz3YZh
zo-OZnLFXZD+*=kfe+Tl0=(37s?C-ly(U!lagPrO){?qeIJee^WHbrIo?e_|Vw%=<R
zY{YF(!%9nxC6x91N=CpF*h!pAlS?f}`Y{jtY<-P3B=wKqx&-%1Tc_S46;m>P(8@Ms
z1->iMcFVF#V8rjL$(C5MhUj4;;7m{I9vY#EE4p$umvNL3a+K)+1r7GTB}*Rh9NBP4
z+viBdw=AskxPji_l6;q_B)LNwkR76QnxQH`Mz8r%jYqUrWGf1BKXN!N9*Wzy_wvNa
zRqyHR1&^OL%HY?H>lfssidBIcDpo36Q?((eP!jmmMC6h9Hnmk_(Wd?rVjv9GW^F}0
zx1-a2?eHY*S5Lw)k-!9e27!eLR%IgTPrn1v8Y0dK&15{Dq-ZK61$$z0an>eR2WaB(
z3%7C+#a|%5dn%Mh0*Y-h=#_OuNv%DuR#o%yUQdA^CLV?K(C#CPPPB3vi?0hQL4BW;
z5i6Ee@qcH5OQ9QRl#|Fuy|McK#loF4vaM~)Ca|TM4P91{QJBuvgEls+51JB^&tH|i
zRUkCwM2pzjhq{{wf?RE4@w8G=^dyO7T!J=SaMpq;IsNg;`&+l4xA=%Y;jCV?pJKIS
zlnhjB1!D5Vm<R-P);Ktj<{sZ7(jW0$`LW=LHwQfBZ>~1m40tIQop#*Lt^Mr+4yQZe
z(;Krw=I!q*>021;=bz+UIEp1{W#hdXy5aqm(sm}d2O%~&1tM%A%~~%fg-{j&mgFFW
zsmkYhbvdxK%rDZ0n-8%mJkEPCE5<BmG3|h(P3MrQo&8#GNuxZqtu_@VBD(SmTpSw0
z3~)3_2^k~iMa@$P7x?CUUuc4|P-2JQRwTGxN-HJE{)@1}MKmLg<*qR!4$wUX$+C@a
zgh+u_UwD7^PNf5~j7Mq#haDewXrgw&7RIn@mHAfSkEw*ibkkC5LJ9*Skg_SXXc5Nd
z2vSw1O&5qSsj8J|dw4V}OOSnpG`1i+u62`Ss#r76o?b#7v-SQAP}jwWn3qrydItFy
zKXfkS{r!?$UmFe@{7YPGgH@`{Fz!Mwy>0t1Fcc-nJZS>?8fjF~c#CR?-;m+*eDr#p
zO*#%9Loyd<0nsVp?R>!PsbV5>O_@NxCkXV2d6qj^rIHl*q3o!bFSyG`#rUZCpX-oy
z08uK`Akq&akuQ6-OU6_Cl99lthMFLsIq>#*Nh@9h6np8z<RB+tDC6d{3Rl%YP<}i6
z{l>9=9`<3WuCIg@9R~Ed_)Fy?ixH6id%=KY+U?!no3z8c+tO5o&U4mttk#e{4W(@?
zbb>_7xSj^~CeY$gYjlj3MZk_{o_jX;>nYIdFU&Q6e55W`ll?E-LK25c4hn)1X%nK7
z;;c4*oKxXHr6>TqX~<ufb)MdJnrsScz$Ak-05Nn%6nGF+HcjS*Q8~D%5h(v?9&)BU
z)o`5}l4)2X)d;3oAFlEt?|ZjTQ~HvYSQf>H!#oKr%F8$SYQOWss2Tp8o5kuY&dm5u
z&`ZXHY`7uH@-hyBU3)Dvt*@Uc*u1jI7+|+lp4tF-`GP&+y&A$)gpd)IbXHtCI4_WN
zf=`&dgIF-y7ZSCi0cM8gxfO0FXNQm-OMbMy?V<L96c#85FznW}9|MP9%Gz;rE+|_I
zWdr03dj`bQr!j(pK)<;7O6#OW7d3*HI8UWtK61Bfcp3~~p%kH%2fg)^cFx`W3nlRK
zPjMJXxpr<+X-wvePIcucXpETRJ@CK~0veH3*ffIj!@BBvQupv(QD?Hl?HIU%O|>$<
zhghcNGslTEPy?|i<<s?zP#Yr=jljE>+HYmA9cz1}=pjiNRq`+;tq2FWr?B(83w1~4
zQ6k2SOIx*b^{-Qyfowb%5?=l_*$k<+@<UL>3Hqh_?;nuy;dF;;-91k?8W_X9o2mca
zY9_H9hEmhO$YEUe=^TpAjHyL95T+YEy$D~8-Cl%lBre)>%jEgqcwsf|vHHMmi>$ZU
zd;&GY0S)u^`OYh;hxnh0c5^=%cyO1feNpGAdVtkfnA#mZ-{)i;J&{3KY3n`wSJY2~
z!x?T^w55*5Z5yA9kI&9mN10)(PN@_RG~#Lno4w8u6zz#WP||wEV!j=*FJ9ARy(ORF
zhCQ=CTD`I=yT$oA>K-EZB#dupw=>sGiqwGgwR>+b%N94)*B<Z30k~fOfjI=K-f%y)
zW{IPzaV6S2T!K+ztE3ewVo8EE6CTp?Xf0V2nuZuy9pA?@83C=aLnapatSWQb_fJ(X
z+srs)5Md2<Z*Z78R2M1tQ@ede(NBRI<M2$k9DjN|R1sa^{1FRpP%srYOW={}2+z={
zb#Du}z^;}LwTpDKws*LSUsnPiZ8hV(xKH_m@czPTP;3Rnr&tYzfJ7<4iUKvA_<zAm
zFQPBg&6^y$S1dwtN#3!b?2PU?<GTj$ZAQ97j`keX5HhP?mv*GL0rtF+$tgn_u|+hq
z0xJYWVbEd=b=)UXz+mcPn#Wc8raEVSAdDB>Lk2yghU<th)4wnpf09d&B+`Et2pe<Y
z(e|a)d+*ruku;&og3@4g7D^zIMiy!<N3e%>ezb9+4om@v79_&rAU!i2Lc8B<Yia(L
zk)^hI#D-}}19(rDjzCJ&?l#MrglfYo;%Bl%J0$ouV%pG)=+}hB1tG>y>!1h0oojJZ
zrFR1a3;+)=U<;-8of<V*ceC@FD2yqfLo=)+7ZeF5rWZHKDmSYvf)ldP{}*MsMKpZ9
zdQ{d(9>Lf?mh3`H<<AbES2UZCK1q|tnl7!i)k{BliIU*CYwke>4Md#_o)^hmwDH`v
zOp|k6Y6S8%38E%5qNt>vq(i+vp->m-;y`%|XnEJ08iNvrSau9*;abM8vAjyo2LL(t
zc0;@rV|TY!r(|i#-)l)+m%;EylxcU_cIf)(S@XSeN`>kVP6gvx$fv<<EbWMS`ao`o
zFEFGKgf&WQ2c|z-<=l&;fd`AB(iy;AulQ(^&gY@?N=2~cYaJ((+u8_He+zc3CWlS9
z52=+UFY!5ihbOyz@}9{3Qc{7eAkr~T4w=2b>HTKOW>@6G&@1WUI?B~!FA8I{awEaS
zkyZI$>p->D8-)OOWlJ3~eXgH_5v6R%=*jetEAC{H+x*QjoO}77Wsr8&s@8j0YAUCW
z<K`Si3Y^r|-_>+&hFQe~DEcg7fIb#qrbTN)<w&PPU`D1`hgs1l3k{?K7l$yW0wvbc
zs+~kDP)wJWBg%Quful!3<LE-F))NR%M0Bj;n8gz1rE!1U!*$MN#F+mN1|%K@;|Dcn
zwLTc}K^_>XBodd38|k&1VGmXkJqLVq-lfJU?|ZnqrR&5a8=S<USFsMM<mS#rN6Asx
zUQs>?Az0ZNzgy?xca2vXil+x3fpBay!oltYD^js-4#rbi(_=|omS6C&Zvs^72`#Kv
z+DkmdJQ=&g81U*tqsakRSIRC?Q7HMO9n<HqB|LsgHGzwf(!D1dwEw0`qH1W!Yew(5
z0KSC4de{9!v!(w@yDA0e2j{A4pw&l``=L3wYEnwnVj`e>#kw3Xf(OKcpIyPigg|D9
z000s{1cZ2`wVIHzABL9V{$8gu<m&Np0R~|8W>9bpMHZFK;W4^g<=S1ouPp~DSO!k|
zaO)8L=vsN6osop^23lZ34Nm%A^}w~~{UfU1qyaF;YI^y+e(J`8_rtEk$4zKN%oZY`
zN5!8^g2eq-Jxp_C_d_?dX>H)_ldX}%hW@ou1^#e#xu1-Z;0!>I4dEulCk|v!P>0pk
zCjIM6c<Do^%}ZXJi>KKw#8Q+Z5Ris22O&byEaK}n*SdaxGY9B<A;kmkJ=tS~QoVi=
zA7yQMpCp9)183j>D|?Ul8H`rdk`5?Rh{r?u3gsPKhm*m1s?mL>)DkOF<>mhj;;U5Q
zmaQb%sbay}4v$I~*Bi~wt!Osrmh1owTMs@m=I_*@QJQt+6bYqjVo>cyJlc(6VqZoz
znYvN6`59QsBv{I*z>bt7%a3iKI}WuS93{k0#Cw>Gu~w!r3bIdcLKe!2qIyd=F22+J
zfWZguE(~@8_vrKMvWKIH9SUY@8*HS-M3R6pZ=0oEDW!$l$=S#<XDL;;ZA=_Wn(kr#
zP<rb+zo7VNtVA@w+i*|o)sYGwANCvJlN9cDW(*Bxm)0b0s0_j<T1^W*%V#v9PLlB&
z7pn9%j3wQ{sYZ`i10;!U(?#81U-GgCD!I*^(@6lqNQf5ef8l4i@OLMf)ld<1hy8pl
zCpiSU-1IEnO2!&4cZuoOO(5231XnQU?j}@#i3ES2PiY}f2Lu=Gsc-K2CY~X_i9;3+
zA^PFn4&fdEhMQ|>i5{~0nhy~e7}**e%i_Q@x#PiXE^h25UqXriwcWZx<`mUJUZGe1
z6xqDb*K-j4IN}Y(cdk26Y?t!v)^Ji?!U-?(!4h?EH?L`Z3!Q{%Z9bG)13zJ#ln9=>
zo#u&b!ZOwgxTulq`HCi7%kB;cvz&+)F*kasRbgCfCL(PGl!{fOIJL|@ir^nQPAKc=
zLZ%Yf3@_Rg$8=D;jo{W%g(8DypDW~YSA!H!)GH$)IyNXe0(Nuqiao#!UZbHZy;-MM
z_c1+Dv>e*qorN6FP2n&Nk5HjJO^7ox{jb9yU#IT;t^)pt0@ti4XB88t!OIv~0gbVw
zj`Pkxh)>yB+sqwf)rzDoz_hC4m>YwzQ^14?*#$;@5Cm`4ft5hYB>7@@epw1InEujc
z{EbiTX*)hC<f-;%PbFEU(sRaJW2diXc!OsRvHUV^lZuQ6-A~0b>QsFH9{iDsOI!jB
z%Th8NtXJOH6y1~?V?}B6YG$4}lA>0<1I{v4vir8UGQ!i?_1(Q5cWyIMG#>7e2>f(>
zB}$@+C<?WPc|6HzXOFLSTf%%~%T|(Ex8_}`zd{KkYHJ|4^_^VV92$HE&3h>9X^x%Q
z{iCCYa*5Rii-GfSgGDcxvS?$Exs@Rv{f;5pGgiD?4G`$*2I0*KiGU-9)4fb4AM||z
zvnz)`rfB<FHF5q#ml0{}D9i>$NM^al!y28YTc8l&%)O%CPb6zbMVU&z7mdTNLI*||
zr^k?5Oq?Bx^z~E*{YIVz@9p1*F5v44c28VZ{?RHujXGNWvkP+v-?!dG_@xEx#Uj@J
zW0M>wC|O0Y7$&`kKcDklybDOZwO{K8*r*I1I{8A-U3IUxZ5{wq=Ls2g8T&;HsNCwL
z<07FXfP8mHy#O7~<~741Lj?yj7wh7f)=c)`EI2}p3_}1WjZcsLfX%g3h9%mFZZTo#
zQ20ACWeGs3$4>je)RFtgosl7wbCtp6Vq%>s=5e%o<0stn&0@PGJ^d;M5<^!4Ynczo
z`)TJos-$AC#{5ENF$x*>(CdBqeAVkD;svKbr0Cv*vH1Bv_X`N7Bf&fAuvMq}*QE7L
zUqB8`g$?o#^OBXQK@W^#Ray#2aAU^<dTsVJafhm83+504oRxlIz<o5NMPA=TyBrPh
zO79EA_&k7=M-l*O7VY|5kFszbko_9pdnHbA19d6+o{uT~Rf5&@c#tmzfVBDt>R0oh
zqzk72(>4F%uZ$m<y<vip2p;vq9D?$I8(A1aD?C8WYR9m3dtcyvleUFZOW%TwrIH1m
zF!dMleHr>7$c4zcEkd^k9BvPhsQ;J*AH@|936gzdqP!qv@^R?PN9hRMwhGJF%T${P
z6;H|IKeXUL@b>B)u%&KrM_}g!o=*CVgj;T~YUZi0@f$%PIQxxP(pG|hRRY#<n5c~y
z&L%;Vq2b)BgeyM|`OP8q%>5_4g{Is{uFSM<T+%}osar4%YM4jm+Y%A=6;J071&4R3
zMw>g1F6+9R+ZLuOdO;V_k-Zr^?A)E2L<cG>2u)aAalW~>1^{)&h-EfM*XUl4ktiLX
z(;uJb6?NlFMV;Uza(a!fonB$SihzzJ(r@~K*IldLIL4IE=n7t22pZj)Dv3>x-*!g$
z#kY@<^%d;Pe;qs&ur&#OrekKKpZKAJk2oSL^$hoToi(m)JgEq9g_6vXYMigNCHk>)
zW1NF;Bla>t5W(|HSnqHTWXy%@;V;bNHc9w$OiB|ZJOSHNsry0fynQ&1>7DWuE44)Q
z9=00qf``GXpZ{JD2XZK~DSsm5mLd`(fg9G!L8X+sP_@=b2@SCiClU9hDhdXHB*l1>
zB>QP{HZTO^gWd`G$VNej4*fdQaY%gV2*T#!r{`jbulKM6b6e+!M;*+bU+p)qWnZ%1
zn?e^@Y!$1&G)dX<cHA?9;j>Wi31+V}JyvH3LoifTk}uY2D{AL}J=OdSbB~k#YfO&r
z?}aYsM*P!9xOBHw{LyR~A$7v|J*)rpPoYHpf{XaFfjV6VBCZ-m>$}J^YjJ_hz>u(_
zc4vf_dT>em&%Z181fZnm)y&r^_H|Y8Uw*mpy6{psgLA9>H1uB3(~On=Cl!mAhz&sb
zOlw&WzTtn%u`-nauXc{U*9YiTT0uj;+XtW$m?6{hMmqqOMRSO12i82Iuz-B&Oscsf
zsp}ASgy8{C4?Ah$X5GIr=!CsOvehdorGs)XYb7!X`cEGfdNwj8gM%4UzAP6^IMr_R
z39&RlgmDLOi#(s^i@70F()B34=g-6XmIBE*G=JmD`J=s${c*1bZjTd(J#Cn<a}ox~
zNLZgtWB_Re0gj1M$!@V9l@usL%QeSJdN=yV7Z|MDozK!X7ugRz4ecztiF3XNa;mhX
z&(0}q9+|7n1-aj;;90;B+L5AS2Vto#oA{DF1e9wrk%sl+>7}hduSJ9J$DjMvFgrwg
z7p`owI?TJfV}hSLPBr&RuYW%iEex9Jez15Qr5`iOX;Pu!6oz^}R^5#iJ}bg(^+ZY1
zv|MqgTw6TBQ{L?Mqr<8IstSm-QnEsS>L1C}oBJTx`gWg5K>lz(i|`NBQhsfG7iXym
zjA|gp0C<Jw-`Gt&pA$d4kGyZ(+;Os={HI*iO3uq`%4&BlzK!}x*b^@80*Z4I^w@oW
zzKzM<;e95pcZDN{F-1|-?$gD_#6TO6!k3TavKDk9HNxoQ%3$(4C%JvdAA5dhqA;!L
z0n>&s83-7j?H;0?Pf!>l{OLl*ukf6cK$J(yuceAS)$OyD>_SbEGW&jBqG}|i{CqRY
zHn~?I0iWMHosh<uq$`s?xeSbT)CNXL8D+^r4;&#~T7#%fd+C!>)()@;Z%y3>V+5SK
z;5=;^Gq)hF3Ov+8ZqKceRN_2IW?C9zuj3201|2`iDu-VhB=0l)GkO@=9%FDzo`N9X
z(v@NOSc+&I#^_bUZYd=W3+oA~qOfftvC~gd_anwiW$Nc>oPYW@K%sR*4a;N9xKZC6
zdF=#X?qS6)%cW^E%q)s?eT}_Y-Q2pdf|&n<VGR?MDi7miF)~-fS39S-K00~>xy_0%
z8*{%DB<M5Ch&z_merQE(-R~s&She5yxo;`t=Gmh*w7^2%TZY9`Bif_bN^xCXm&b>q
z+ar$vG+;JPidk)F#|`@m;@%SQx8r3<NHicNBy#G#ST?OGp|C(L^EmMrVJEg%$h>6B
zqkK2wa*2~UD}uM1taRBrSKzd23Nw0eeN_s`i8A^)G-GZM9*#ErT~<0o{q%Zf+4yQ@
zvN*~kWishwN~0K3a%OpCFul)>bJJY1M{9BqOh+e!AG_F{j*ap1Ux`&tIAG~Q@`d1P
z0$IA`S0@7cfa2?lgn%;u|C}=F&}_=}dX04=l#a;n8~+hsrY)0xNDs-`^vE2W%=ry!
zib5zRx$%YnhUh$Ew4>h3TOb><qg#a_Bi%w*wS9GX7c709<;u05`+DuKLKexCSfo8h
zG{jIq9pr`7Dv=(WBD{Y^;-uS6lA8d)Oy<yj*A@XhepLbdBF|9q?a*xN+I7nSV)YYh
zvC||){)u;yofPJ9o+I3xAkWwD+sWvt_Y;rDG+(9kkN%jhmkirjFV}R_^dewGfGBQe
zYWM*zT&SjE)&yBKBlM_~1djKylTCc^{)|IyJ=F{du02}-CHCf1^4ZtXh)u<T=mV$%
ziRf3{TsrkX%4KhCpLL9#Yu!$}Eh>3PXxOWFX!y6!Bl;P9YCf%%T>F-_5e9Obbg6{X
zX{iS+%tO&BSaw|8Ux?uoRJu*LdaA#-)UG?B!VCY1(^r+iqR-Q8%lQxOVQyS(3?Xly
z8m4w*5>$7$+A1<W1dW4*ZX4R-LE7Yt+H;5wo8{Chk_G7PR_(Juj}YXBOgwm1g$ZYw
zpX}2n?yyhNqUys<qUg=TmwmIq1lkNOrlHRR{~t<i^y@#1KOqPComb02_&LjQVhjUq
z6?B{m`jlvx29i;HmSH^#im=Ak`fFLHwq_=J=_qDiE4}Rnn@Q5LGpv9%Q7FtLu<8~#
zqjAcikF^eSk7vUzFY?(0Iv;}L2nE2=kCK}M$ejL~m-k9X=G5rEdhx(O;g3$KdekhA
zfo;@>wkfS4o{B(H?Vt-=KqH^7-I>M=(qld21T7`Vb!UPqH;$jV+JX5q(Q+9(APHkI
zq~*JOI|8mcLu}BXW*hBsTzAR|K=pLNKl)-6IJhM3ncp|*Ml-588ykgFOd0o^o)jpB
zP<B`*+C5h*A4+SNL4C86e_QWy@0LVA5Z&46LDUZ?B%czMA9KAvyi4Tfxm&FLzZ@vI
z{k7k*_7X{wdamjd`+{mo3T+&&<W`sKlRVT02P~<O%nSele^8?LXsF4h&A^8|*<cad
zpU;5Th?8-0KBSVda5tXJ<HzUokXE5x#Y4-5@2|sFCUj8@3qTIza}`Cnd(MTjB)!?G
z1viYh#SSrM;mw1nKwAO#$+=K_B&ms~zJZM?8*yC76IU|s5dTX!o;<$n$OIS{Y%aT;
zs&Jyuz#FKWX+IEqwF_<O>UsaW#^kZ38uTEY4WRkwtr2wCTLcwJ*c}_W;(uq_5+<;D
z%NOuz55Xf1bdgRjBn7>V^{n5=NlU0r?L9<(mMb7>Z=B$(-Q1Ou%fc(#RK=cHw4WL4
zZogsAIby607C4}96PpLaM{bLDDWLy)oNJPog2usTDP-+~R<@+d1IJ}L8XG-7M^%|T
z`_ffh&tOWkC$7&P03LXd;(eLeJ$|Z;4hvp{xjPm6+5S1TbDKe;sH2)?lq11Rc&&5I
z;(aS06g1Z7;qD~hDJVdJ6w>aI0~G7g|J&;@E7=n+feZ%RKeTp?q1tOvq${9S$suoo
z(3obzO%mg%I4oJDZWpFP+8_vCIDeQ{8S%N*>u-8&wEhR2Iq}gezCv#sr?29s&1Cvx
z&-uyiaCELvI2!OylcwGlQlXkT<H>o!&+?``4k9+Yh$&szb}kcwjfvg6Oakk;;zaG>
zGYn8X;j)_Xr)qzZwMtQwD1(!ViX5a;XO>U`z$ZU8F+prJPTPvz4+s9MXH>UTSm$SB
zsV4E4?+>16G|YAKtVr1YEiIa4a(xc&*kTN%aR;5qO{#7=y-P$AO>r1Ov8p5KBx>So
zb{`(rYn5t{9+VXLhuq3ErMMMsyPH75vrFe!)!95Vxs;;s%^Y2}=svTVf<T#l`!{xD
zXe)Z&tC$HitG&ID-88z!`w6e{EvL1An=iDs+aEL4=5q-Gk&l#_900$oG&2l@;fZsC
z0GC=o_1#991^*ke)5#wBO$>M;b`Wv+bnvxG#6Q73=(bj5j=}*nNVml9^4P5_Qs%sn
zA~?|N%cA#4Jzawc(hc8+O}V)R6cMfZ1`@FFh%bTb{7@FqOZm~N;p-lsCdKJ5X+KGO
zZW$&q77KSA>|WFtfa^SsoY?A(#^Ld#Pl+e&Kd__PBvuh>RQT4R7F6@Iw?!c<hcyPF
z|1de}VNK68Bz>$nL7GU?^Ws^u_*idHwUbLonn>$vs*h1&+6if<+=XEp70t2Mx5V2S
zL07CYpEbE~-tLn-Q*f0LZ!LsDeE#jw$!6n-B4yQSjdl|FreNtLqG6U|zast}%5AJu
zC$c3BpR;9epwKBT*gYSKH}fwL0Nwi^BL=l;`O_7Tq_K}~yb4g-;AnatViA5qWG>L!
z<{-kfN;V_T;)}!cJar0)!VCfQPHwTts9VWXSA!BHk@?Rt{^vsYkZd(+3o7rD^D<Bz
zKpC~x*+R=K^KBr>npB5A(z#=4)6;^5+P*sy)|GTo(C3!{wHXbC1I}};se6413e%l^
zK3#`^GbGARjo}YT2C}cGax)EL*u+^6TPG_rwa%+DHF5f#V6#SsGO33G^`I@T5l^6&
zJ+wTWdKfhhJS%ZO!6*3(-njL_eF^rw+T|SXcgnSe_1Dq-;j7{nC?vEk<7eU+_Ozy$
zN=%=TN`M6tEQt;C>VG<(IYIm1e?y=;&J30datnrUc7HZqp*oXIYxZ4ND30|9>+#C~
z$o9#dk^3|X^&?l2AGUXfvZrM+_FO<IbZ2zm%^mKb7ITw5-S8N{@$X3UTG-oCT0|kj
z<)<)aqnw4rU0DzVG9oN12?(rjMM=~g{q!SYqAgd`-?g%RY?E?6J=aNqU2trr6CuL#
z?n-e<c9wuu(Y2v!<L$F_N*q3s!7188cOPxDq7tcF${YSoFL~F?)0DE85q3<l`N<(B
zgM6r1E{Nz-<9ugGt7^5F;x^G_%)qz{Nw1S-iOJTf^b4*q4KAfre$bBor_zn~!L0a8
zDzjp~y2|*8e-&jycn_^2a6M06fPEQMEN$$PYbBg>pUopwOT6N<=*@JcT!B~IZg9Q0
zQkZ1bZ=UZV52{#~vh&-KdZ;KP=c9x7KfnhcwIt6%@428w7Yht3DASDX+HERyh9(7J
za)a0`pZT>uyYJv<@L^{*+J5rke2^zL`pA0<qpxU|j4tjSe5&dCWsFSN6aAu~bzkpW
z0fBXjSfjy|l6oPZ`V<J<dNn~@Q=L7miOL>oXlJtsjdXBww?;-xWk&Kb23l&k_HAxT
ze?)cZWZto1958~Crh~2=5wrz3TppPkM>0<xJ9{V9#YfsXTl~Gst-y!JL3EY92Hs=j
z%A+Xz2DwXEj(LVN(57<7wlIoNm{@AQJ{K0lC{1m@GMymy%SHCxZwsB8_l}W#WCkVu
ze71AWVY4<G{Fl0L#h#2~Zv5$pW}gI6NsV8kc8tvjx~dHvpKZ?D7)WB)Q5w6s8v#HB
zQhVHkFF*z--h%Afbd_Q|2Dm5_@xwZ0!%lbn&j+pdDHG9M{SuP!cEG$UV;phS6_x10
zqB(5Oahzhhsb6YWs-OP<fuDg-H=)SJ`RF=HEXP>Ig(u7if;ynE^xa>Zf5;JXOr-R+
zM*e2xf{EWw*AD?bW{wWUF=8KBk;wiS5gwFH5u~~j3nIP+C$*wUkh9uWDBp#WDQ})q
z-^8$b@Dqg`r4(yHAbEz1uzcqs%Fi&Gi!y=rl}JtBz4)$WantZ(Hwkmod_aqpGQHTe
zBPDAjtRVcOm93uuo7vq)1yzjp&S<^ikChyK$b$V@>9v*2V{j%Ma4>~hz*4~c{dtv)
z33p@%ZTbA!pL%4fc%6U{vML#Id!B(rp!qi>MbQ*%0M7r_921U86*W~Z3paCHYII>H
z!STyP&)f7p=84hHx%iV^;w|KVsI99Mls`k%IShPAXup&R2Y{lVJD04aFFF_EAFE&|
zIlS8j=`ZVmf&NR(;WdWE7hLktpVUhAG4OQhfnRZ2J6t{FCE>|p&NoEKp4cLo2ZQFP
zbHvM>PHgLa<`|s<WxV_$x+l{XHkiX!efn32vxc9**2YQQiAiHb(vk7Hx~3nWR?zv|
zl#BaTwtf#dfGF?JRF^S7*t}XP#cXrEPRtlLh>!4Y>S<n58UmaUJjuAf|C+PpZ{96C
z?7fu_EEyopFtf=?bb=I-P?`!P^zjEFSUdJ<=ew;cZ&bXN=%>~b?Z|lx^XX^1lBqs~
zB#Nrq#HHX;q=f?wGXe=bT5L6x^$P~@KE=q)=azQHt0@{n_jo%j{d#%X!=?K>_Ebw&
z+@m)(zFIwrSd@GqfeG3rHs2owi#(;k+?%*z5{W2Xam#z;FD8z(L>uH(>OEVItw@Gv
ztb3k3TjImgYnKVIDzn=iHmelk?RFpMGcUDCiXrY)s?=<W_2Rbb{BgYty0G(W>8>nO
zn3U!1xswC4SXK)bvDX(jw3UH@QDUDut9x>@?9LFF#lK_cqlcXF8H<uya}j&ZzujjG
zJ)5Dy`mwDebsvE|y;^dYBID>{TU^zQCdRVnx`bXXK{g<%ro;Ybu<BaV4Y+!UExDlh
zoNmOXhzYCgRP%_I>22irzbcuFxJ%(#Y0kYxIj>F2fds$${-D$7$XxVL<%h6}g^}bF
zB6xAGl8>G|j=iA+4rbZH6aE!_OVuWINnNDd9{x#(+g-Sx^d+9jk@yoCKK~}Tzmb==
z1et7NxCd}QpDOr}9!huM7@XikZ?SEj*nv1HAHO#k1y{BsJx8SSYdr-hj4CSjJU`?^
zd%tR9B5i&k=ypxYP=<}m9zWI@TIE&!#sT*t-{WVRkLXN0*Dxoh3WQuWhako#!h*;}
zg_sbO%6I|{gE|c|18i#|Q?_;ND0&P0mlIPyzC_$>|8wxiPrIb6Xh#2S6dG0PVSRNs
zxuZIQaZS5J&)Dz$wQvV-ZWJn0Qct;ix6^ky>AF+n;$=XXR2{}q&XS75w=)5=T>J_r
z%Y<R1;cy@OTLL?WkdpnX+<hU_qB)2ckaml?rc{HKyFtlf#)bx>0mo*RD)bEQSzNfA
z|C-7SJ#CA)j{p&HgO6At31l0<H~IAO;tgqepfS(gr(APC)AehvG1u-0a{%GLEm%_s
z-sw5us&&42yfRXOgqXLTgWu1aCtv?Dec}v_05Sd+-T)2}v9iu~!&<z_wv)T|V$G1j
zoS3Kjs&0cC5H_%JG^ngjjc{11Qys#=ucA3a67)jqLek+#rEt5J1U$gs_r}uv3=m(M
z#&ir!M}zsiDkc}zwAHv$!aKSidSA&)nYaVdKPP~-0l5~GJ{gpgsZF0~@~1a?7`2`g
zzpDPcQW1yPV(8HmOBcS`_6lHDa!YJvW#hyDPU5xh9u`i-@*o9L7ZA#;lm|!5kc0k=
z{!X*cZdJ#1cPq7O&^0fKK3CYyO1L^9t<(#?y<en@eulW1gWT1Wj1I$9t4JQ^E2MZ!
zdAi>S+x7uY0Y3o3#rSVp<dH)z;YYE8za{Zo9NqI)f~M1<SE4ZEurK%jHLjZ_fntCw
z8%IvI&^a)1`1nOz*a@*R{GJGbq_KyEg!h)-Xgup!M6sp@x|N{&H`R?!&Cg$nf-19h
zE~~{$(f`u+S`sS4MJ?MLs?EG8k>XQz*T<ePs@>uKx-VlPEgyHNnNfRa2W*VbUDL;c
zx+Cx6-vbLI?vEwIthod}wu1(@NOd6AoXUqAU~Ws?ta*GJzq$yx3#RKJaNF6)eRame
z4!(g{x~AWoY~N_%l{siQMGgj$<i~K?5P7}_03@T$=5*u$09vH<K7q1e27+}dHL0m7
z@a!vQlaT=unq(~p8@nn7v1B(pB~`*yl&0rmj4vAw9G<&n7=r6#^qE8s-306xJp?~{
zh?lr@Kb<weB>?Q800AcNwH&8H#+hR4x+t;0*ED*VvH8VpoZpDmcpr-0Qe$CQK%zCc
zO$X|bJ>EWHIcWN`MsbGGA&-I;0~#4je^_eW0ifoaOvhj#&NvXTAwak?d|AHxMU0&5
zj-Oi03F{7UtJPCqFhhMcn=L}_d5YvQj*|Jm!yiaqGyPPNS7tFy6XtIr)PI&shxICZ
zTS=J+gdM-h3csHeYEwwbsyCN3dlb1TpY)TPv@H)-*<%!48IzdP8hdrfkgM;dO+!h;
zsgXYqA}>W<!x{jnCJ{~u<xdhQ%-B70p73EceO|bO|HYkFN{V=OY@W0{wuNt6JoSUU
zTxeb4q&p;1W&p|PYwoM>dzBidSvE|l{nWK~Lzo4DHn6%rBb}iLo2MI_WXexli9pqX
z8S?MDiM<+^el$96+%GZ>Vlw;hKRz9yKP*n@I#jA=BB(kfkVriktO)VC%9*I}{<by^
z0UnqeW<_5$j$!w0OYOY)Y@U?$4Uk6&^`)Evf!nm07U6-n)t(d_R|Kg0#1QFKZf~ww
z%j~Li8isCsqv0@Q_u#Se8)}vp-tUM~aybsOvH7hovI>hW))Ym?@NLgpdY1c{D6r4O
zkZwE^SAUeHvVw0pd*`n+?*JMrcS04b9Z+&%#4%69!_>wkk6#jZaH~&3B>vV`ZVjp1
zQb4hFQx8Cnx6JyJC#}iP*rHFvA;)JSai{W5Xnb^hrm7FZ*a0h2XAPPh{3%3xnnaKC
zWsgHw2o%8;rHiXzn>tg0E7+Jgg6s41p+Jd;gD!L@l9h<~v6+!<nev1Ioo>*_H}OvI
z7~#QY|8?6BI%QTyQc|{Fc!GK=qC0lk;Y3O9nwA&y=c@uE;VBDk4|Vn*dJCJuYXlwY
z+dAC=l+)eQFw_LR??H=Fc?_r{*!l}Th|ti&pt%T496c$+x30VeU42>FhfiRDW$Q@L
z$AKs~*hr?L&L+OtEJoKpMTem1*YKTiIJHoL-*}(!>zC#bR9KJjP$`rV!>is%7WZdY
zXPJxy7_sIYx_iWzwKJ@SE+DA>wL~?QYg_4jy}?4j59@e?DOr4q^c^>aT}0Mo&BgLD
zkz>ry(^jd#Z`k|WWLCQ)kEbs;&DYu|8o|#Q=GEYFDad~UBWd*hYqZW<6+Wzcpua$s
z5#6(CsK@-AU{Lw>|M+I86w`I|{`6oqdH{zGbZXq3IjZBiG&D(*;XOZBhvbFL<oRqn
zs}yi2%%)f{97JZ*$yk?q6_9J{6GyV>mB(e88v^`1E8y|u_{&)B@~=m1UIF9y+EZZ`
zq8~<aX`6fj1{fr>Bwnp>FVV@d1egs-O$$Obr$9t5i?`jkug^<#nr4mIDo<i-qFpR0
zEEUW|`ny2}oTasK7Ex;q+-6LKy|yRIio<4VQwN{+e?4LpEMA!c-~j7u7Ydd+AC>Oa
zm{8WxRR7mB76td90hwPEDU-0wB(0EBl6&V*=!7d2fS<h3Clc39_B2je2nLr_ax1X~
zjJit4<?1z8F{xFU2_T9>7-aZ80J6U0Ko7xtub;my$DJ{tor%s9PUW43LDB>JFu46_
zjNm`_vM`J|z0?;S!*C?rJ>KU69bw|K{4#Z}W9OiN;n*P>Tzk2fW2?-gi@IciS@aAq
zdndsQ`iJ3*xQDn<jeFOCA%!nefaw)y1KQ*sir8U1Q9t_V_!J=!nYBooGc0Q8P4hi_
z;3KT0VEd2`jakWu@q#SK8{#;N2LZm?+}}QNu0Tt*^6q&GmQRkjt*(GuS@OQX&tF8x
zel+ZSOo>f9Gn3fPGWfpkso8A&yduBR_0X623Wf5Rl$Vk6WHmutPJomyu|Rrim1)!~
znz}z8K?=f@iGd0Q2j~-w>WzlgA1C-=M+bybiE3k8`lzaHaW}3|pXVkE%g}!h*bnXs
z^Nlo1P!7~*dfMXL`sqCF3;m8C!{7#220846wJCT!&v>OCJ`M@GwDG?*crqF1Xx8hO
zc14~O#40@sBsX#;^<`Xy_yhwHL30K2X+$Uotj$lbmg(^q`#Sw0{DC;@Gg3H|=o_ry
z)Q#MqCA%$i?h?rYOIcRU%*6qqBCC+f5Jo_E`6Mp=eUA^vq{NkPM!uv^2*LL;c4R~>
zm06*WwP^%H_|e_qR=9WrQ&|19L_UD1VuPZbPqs(}DTd?Aq1+?7o?aTx#GXIk5<&up
zEdCg-Yzb3adt5JEB{YGy39uUCwPk_HcZ&Ay3$#)XgKlP3Dm_OBRvm+oHS=oSgI0K@
zM+qub%WNwuV}PP5oSiEE!S2C;k}ajA+&&;@yFqhDzu~yEZx+lvMU_a-Jwv2A8fuC<
zs;8!mZ~^_&O@~aRdzmfBSdox>pE4tfrf&tZ=5r+fLfKssjocTS@Uf4Y>=>qY5D6nN
z1#&j}MM$Q}=YXoL%kfPD=YU-Y4Yy1hAI7F#*X!6(tK7;40+ia^LUgQnGYBn3=Lik2
zsVw6d{q`Sj*0Q9=e~wQ1Z|>BXH`J_L%?Er8>0|J^&9nttX19wH7GZlkv%>{KM_)bk
z&7;jZ_6s2`R!X03h|_hs4%~g_0MCuR*nmWk5Sbr=EA3Ztp2vQ+o;Y!sJ3hOcA#LPt
zttw>3a{zek?Pqq6_28xzQCJA5D-~j>;riv1uqH6?I))jSnyZi?>$#(_a7-G&<)oRq
z67=^GOJ^iNd@PhB3B4TKjA^cCGbkPyBA4}$YM>Rw1=_<Mk@`SOp7wqp&{P7@uKJ&Y
z>RsA{go*{OAO4x545>ga%PlMi9C+?309~({MY|<Vg7d-_XkU|^{r^4P$c8b^p?U&z
zpzgUk*?au-t8VBgNtjN2J*!^%tP$4Uv&**VDvhb0KJlJzWJW87{C6s)CNwQNFDifD
zz}X--_)wmTojc1uY8dnPp4HQ#eTEE$0||M(_iPG}&cd}aMChP%B67`BXi{a3a4?<I
z%nRm65SPsCWu>c$<?-=#fawv1+zfu+fsL+qZsMjB9r)$TkEeRVJU}Tfz{Uup5aif3
z&i1Kd_-ko=74@r#GJk~1w)6*(bJ$JWB^Rh@-@7YH*?|bVuGpSi;sWkH$FKci)|gD&
z43JJTB^udK3&`>R?rcwD=?K@|JzR?^^#?c2Cw|Fe5L`zz)0G`Z%58rKQL*AnF@w^f
zlZJnNR@T{3?#PnC9HQ7^vbOExQ=4tVGW6AHlm-qAB^y_XA9U0ec9ja)d|TjEM+k10
z&xvCK^sPqstO<-^Z*1P3{=D$TbM&6+bm<(a<Y>;c;+0GT6VvR4lJ?vrMh6fG$b?vQ
zq&)_#A4I>F{T^LDo2&_xq=%O*oi9MTDxi<rpqh|4L1t?jOHcP;%j=ncCa31@@r$*<
zVdWRYih^{2o62dIp&_;uD|6ots!VEP%$|}vdmiyG)U&ol^thuBVUIQ9`lwqTu&<@i
zGglhl;!xiEKHHk%wfn-2fZ=WEE+9)2Q`9|<44K0*pJ3X;grzba7azP~X8_(^i4Sl;
z7SQqI)FUGDNjCFVza)3e&c4{WC?mA$#`&xCwIO*Z^}1@v;vx4U>D_l+qaosMH-F24
z=DYdokKywRtFqhiHdPc1I>|6xvSQ2h0j(fxIVo&3G>Z>x=b4iHQ1!=}frsC_vMO4^
zy}+n)4^0I!1Q6z5mzH)6P-nr!gLYOCk89FLR)8B^$#t9rlWM6mw-q(@#8#TX0b!YO
zrB518+n&leLS9}X=dz`X<&TJuOwu&tl{Cnblod*T$(wDI*tM>WjaO!Qwc5;hcN#+b
z2r}T!+{Ye^_SE$>+-{n?zq-^b4x04rtMwMup~Ocl{vHK-Y;eW<$%-Up4KMny#55xO
zcm9CCIIDh;p>-`1z#kBt-)rM-hDzQa1uWZEDGLL@9cv1<5lEqx+v(wnl)Rb9j}vIC
zYP;wOa(sh(A41=}`#EAao_D~m5IF&~jhL17+oqXVMIgLQ9IMJyh<u8CFnHFM#vz`U
zbRkc{Ao!1&gZ%w0mA~9SLlete^bGA8t+Ht1#g!G6EfxBm60yLNHH0MxZ3P3%DrY5y
zguj`70M%29V@QD`h3wtwzV?W&vb;nfKjTADkM{RwHS%$(tVFJDdo0Z0pi^L92w@=I
zdfsK+#-Uhp!S0uII!~BtR(XeQymvewPeE)#;6@65&%UPsVo&bCh`hEt95ibgmwT!$
zDk20}bWvXD$~6(PQ;usfE+d04(o`MBi8W?m?>XkHt}n4ThEc+WThXj8SunAE6HS5%
zcR)!Y;r965Ub8PU`%-c_JGv#f&4!`|fP$>dO%r#er0WT(%vJB&5+%2=y{JD<_-Wd2
zwN$hcd0L4@u*M2{5}tAi(uA!0_jwCUUMb*<js2_hM<i$A6}7q`V{5x_#sD${LmYe^
zI3$X{uO!dt6BK-35Hg$s3h&<#^n$+ce^fl)&7)Z)E0PuI<dzsWA0pXn??pnc2UE(F
z#;MJ}``}?iDqH~FxDx9-(JFA3D0_v-z8G)t^}~}`PFGO1tl#GD%lMOoFqYw@V)_!H
zk4qs#0Z~`@n^L9B060L$zlJ*m`Z~q+|MibD3Nnb0l4U%R5c;?;Gu~CdxeciOs$vYo
zz>*oWdzO)oraEq;;C{=Cde*!|ZoWwB{U-cMvTi95uTI|WIRzp7DQ=&V(*xlNYv)p-
z*mZja?JxJs3JwIo^g=TjUtZhX?PC5M19GeLa@<#<ec~p@&l<}2WUkp2%qsdOmVQXR
zJp{)1AX|FnCo)MT>i-d~I0P4F)#|cu<@PN+BEJyHJ#Tt|fI7I?I?fO4KocGH31+Op
zA3H)E+%O5QM(Hjc*51GjRtUo;05fgHf%#GCehq~|cVM17si5Tji4UG>6(OD|^M}U$
zoGJgRe!rpFPEmvdfuo`$)2u!8yi<65RoiiuHJ2?VfS_K$@)VP@9rF6j`(f_LO%>gS
zdhzeZoJNm*U)<MgIE`f@aeb4%?y7Evh3P6sSX1n|C*`Hgj|s#szj_p6;UJ)?Nn^R&
zmvD){!=|B?5kyI*a0k%D*f&Wg2+T)|N%i0|yf+-OaT_}^#)m7jB;EJVM8}_D3KkHE
znX|+I0gkw;SRepYfU_G7$UzVT@`%?8KMK!jMdW%R<5j=F1?T{y^aG^oblxr0Szh2q
zvfu*^-F?Ou*Z@xcSZY<;93A3o^;8#x<mQg(+HlM|6u_$s3Po`QQ%MkeaXVc@Qg?Q)
z`9%OPD;Yw;AOxa86FTUrzp%T1pYzvzlI9@EimfNsR37_fcKr8p@EfN}VP8oQd#qc+
zobFQ_Sm&Kd!NDh=9D|E9CBI7Q>q}e>zj%M_)gh&0bU1yd<sl)MC_q&yhWLIBFpvWx
z6wac~S7RTZHL0KWpxz$T3Q1;awS9e#!L6vR<XslG-K)%KdPG-|9Q3mr%7^e3{VwP>
zC)R>4j<ylMnknrG1nI|M`RAVhz7fjk%E-77w_QMAPXrU^NeYUKu#CB9OW#;v>`>oC
z9kdxxHA9k*sF-KS+$rZp%S5B=sm^}UK?se?1b_25r0l_G9O1lzU70$_6^-N>pqb*v
zQwmfhP!YZOJkYO6MSnJO!gBH&x>$gVdGlda3U2F0cEa5ssLa3VB;9VVCFO?{<dQ=-
z(U&7GhAdv(-mHV#OwUo~itUO6Y*LJ0*J2bw(-mO<NR)t6+%pC#%%@lyo>34mVq=Gu
z^A}{NdV;>~|ABwD|2x{oTtf&)o{2cZM+#JVX)P|9({lkC3sWscS1eq1Cu>GUJZ-fw
z|DiNy9i}yjyw49iiC{E4jvG;92piIVr>Q6#OOo$}@aML6)h5yD-21x3`p@cN9I90G
zOc49Eia}jWjzBF|jn)DuawSZ^<44GR3&#!wO_Q~j0uVHTCabVZ1I`()P$pfuqL(&F
zkQ{nbP441<YcgA-GY%HWhk*VMM1pSMNX1np(svCDXliBPIc-AT*`yksv_HZe2|{H2
zU3~Mrvv4w#%IGmvJH%C1iA`lUr}Hy`RjljTPAK+#JFur_osh~~`%9($p})dQL<33H
z#}SUKLiVM%A@OorUbv#CoB2)8eF4||-q6T?t(zBczWPZy?#-wlPz*MZJTe_YED2;~
zUkM{21?F0p{3)k?a)|sd)E0^uD~b`WhVEHj>!S0Cuv`SY?^K4o22vSTx1miT?wAOY
zrT&xU*W%{J>P8tRARQ3QSWJEL)~giDcrcsxyHp{ua~6Ju>bvddQSIb#$q(5=Up<L?
z!iTGd*;S8BQ^AKQgF$6jU|WHwm6b3Mv|CB(dodzUv16$;$xL^Uii3sa5Ct;MRSKW0
zQtxIH>Lk=Pu~T;iS%D<kW_D`>ggQC=Wmv2jkT{VgqbPMX`l~{W_qPRH`tOQ@-|rO@
zg7!v_`2p_9i<RSngHINN_PSMXK<oJXFOt4{a<i%-O_AT!bdg0%>0&A6i##ivZ~cFX
z5TYE#B&S_Wx{P$`)X_u?g{ps(z@F@54d^z|S(9lM<jt_IA8134T+#ppUTSYrWbI=k
zvRbPIG!LG>C?A<8cMZ=E&cjIDr!k2Bbr|#IzAErnnjw5~yBpY+^dJhBJWlA(uK|KQ
zYt6lpxWA3Db<AGKaiXJhgBu}nd8d6Qb0M1s-)6o+MB?F1T?QIPpnl$XPb$w_HpDl8
zeHB-8mF9MHd|PjI|58ZYb}U-Om%uL_peLjxRz&IbeV-Vkw-)rCr=}O@F?I=#3gDpD
zflOo=DM0ffz6AK+dxp}lwC8M+Zp%eL#=$1(SA<aFS0gDe0w&oAYkON3U%&jw$+r{X
z_~Y(FiD^sJA|ptr(o9J@EY$#MHi+-gr+v90mB)i>7P$@ySsje-`>30=*cXj2`ll8S
zrorbN<%dX5A_A~G$w&0FVTaSb$UV7%UUM3=MAQZ*T;q1v%F(CREcL&QLxBkR<Hb*u
ze>?tQ8{MU^gjB;_@@t6mxVyz5LcWest|(zLIC*j&4N$<)%zDw~3EIOZ#55tSRAZ0~
z4-ltUV@6AEuGYPfaAw^9JYwpK9WH*?N2;sZ-rO`03p5K<qfNyqvr*{O$>fofszC33
znN<zu`GBx<Zg_gTJvK9g<}w+$+`#H<vekmc;j4J1G8k#2V&jRzyZk*1S83do&O^Tt
z0F5$68ghEL7W}kNY6jE7LEegfJoi!vD+$HO%ThS$05}BNi-odkFvkOw@0h@r^_7gC
zv5{F-<xylX-<dFLG=sx+DUa%VS^iOC2L9!VZrJe=$9OsrvVaT(YtW@BR*bh0oCK$X
z)0@~;FI*~*7WP94oZo&?mjTH%V(?+sB>Sv496Hu0dOt+rflRE`<^M002x2}TUfT)a
zYBB~|&+jpso97yaC%-n-suoF|Jq9}|`Kn-=@TfWIC$jMLBNErb2ZsJXj-#N9*?TuM
zv;c~-3CXZP>;DfNKM6b<#<s=6P@gtp+sd>=bJZE9+1^)Uz=iBh2_ALrPD}`5f@sy|
zMeVr>+8QW62-->_7u4U;f>zyQxdo$!mhw|k1%YAXF~K{C1WQ*cVAb!kMnj>pxmJ(H
zNN+|ZGQcQhHXl;#k!I3UM+6nW+;k~8r)~{Fur9jY%(a(rY`xGfvgTuk19Zi}*B!;`
zMqq=#c%>G^2l|o(q!)8&9Ss7mb3?tG{+ks|ZhWWXo8IKe=ns$&tHF-S|I=mk^vIE@
zd;o2`uc}247E?VU>r4Ht@X*H0jJf3aSIs_!HjK<61z;p<PV7w0=jMyKA1BC~xjeMx
zVQ&2owrnT%#+`(R)dw>h%a$TW%d`+Q8Zux8&4TSmSq*m^tQaj4`25{&mAlCuPA6X|
zWdJ^hm%qvgfgk<U1q%=;EtEDS+ton|pPh9e>$ULJ0#|*dNh|Z3WFoG1GvOTq9hVuS
z_XmGth7qk^!I_`+_BZoeZn5I%wqD0cJ4XRakw(1)6B^JHKNVo_=B`mfULcLbC)K9Z
zUsWLFQsYz^>F3-|$D!oeJ)K^33G=TpuDqqyhk7S{+Ilw#-CRmG67u{j<2#KP#J?4&
zjtv#Z<Q07Kp_&rpt+^f#`4IvFk$h5uQ%Y2&>ymfxo=sn(Q{HG2Ebui@D?RGUv#DJ!
z+bVs9a{KVv?A+haa{FHJRfgH~3-g=)ovvPfeaniuVjGtSd9j6kysSl{>|s{W6T?rv
z_}WM&YwMK4A(=frDm`Bn=?7IDts*1)Oj)O%n{My6q|mzt&Hj@Jrqb!5P^j%0%LpVV
zOUXf0i@)#xN3`YX`l<c5H?Bz}g`HBK#sI%r`|P~X=snFLqu6?*R=gBy6Td*JswF+-
zg=m*2PrrOwE~L3Pmm5sCT!=4aQuMfYAz#%3;uq5dZ*-eIQ50*OwX^)djKu#0J@t;I
z++wVy?EmC(CD2GyIgm^ZVD6kF)}v2_lj?3j)Qsv-%ZOKr-iYA4K|STSX;Hg{hl3xn
zFT5Z!>ti?M*J6n9k1u0j=fj4tnbn&!$1?EnP6=1Cw6HKdf${mE{Gp|vSL5Q3-}<7O
z2gYH}NlMh;HTPa;0FMQr5g4#no<Y#(OEhq0=J>A78sj!pW^YTFS*~V}99GtvQE3S-
zx5Zn^r^}`F0QV8%UK%2~A+25hEVT<94Stq=n8~xZV6Fh{w3c0WdJ-wzr&B-i&!5qg
zMrgbASFI~1Mf??rx1ynQFQfRgh@M~YvNM9UQq=QXhV{1*oD%TL?Go(TGbPn~ikn<6
zKdO$aT){BQ5&CaTPv@b*Ut;qrRK+NBACoRUr+g5iKfW)h1j_y;g&g>rY7d@mu8nwj
zaSD=*rMFc>o~a^xc2nvKfz_gm%P-{@G9GP8DLn|e5dV%mR3-P2`@Kt5f2hFI4jzXX
zkNe*}rv?=-)*J*tN7U))tR%h$m6f`7nJ&WYGI=rGgjuXsaOJ-hrq(92=%I}_^kovF
z)mY~!GV3lnY*Y{|D|@o@P56SX<QV=Fm?*U$p!g6baA!vGP3L1suq=Wu&u@Xit<zOD
zT+%F{b+KV2d|~@B(M>_hjyD+(MLRE(02n~Jj4SEw<yLDa)Pt3#j9(%Ol4r))Od19D
zh<>#&Mg<SwXKdqCptV0z2pj7dbV=b19HBu=ttk7&d9gD<5(ZNj;no&TUMO`f*QK@O
z7N>75O&epunq6Cf!k=Q`t}31^s6mAhVNH<1b5-0<xi&O_+3stX=4K6ZoL{a|3EPx*
zc}O`|h<uz;a@Jhl=EZN-+gUh+9BIZywA^x|`2NNt&`t=)dA-h5Ak3<F<E+>pFfq>1
zzA2Fggi;M*dyXwR?vQTnE=L_c25PHhil${qtwT&9p7>Q!5h%suCJVkKyma<u&ktl0
zC;c|#qertNJr0o`iP~~gs*mSwTP+^S=>hyho<3>GWEiCPlKtoJ4Y&=LaZZM=3DXA<
zsCA8mE<c;IrPUct>4YxQ5dDdm1m4HhNGGYT(RZ@MUI38og2XsUI#S?GBMdd{56|P}
zn4HM=B7*xW0leO#n!S4<6gzFeji_M1YTI1j5d!>dFJr@QkpL_(UTdIpyJyDjb@zlY
zR&+Auplj!?1GE+^MkU1G*ppI3z~P3on=JAtiPzl%!T&bYguVEy4BEOoUbr+P_iyJw
zh8#P7mB~sDQ){&)r@3ByFxnU=JOE!q0F=|dS|nq|y3cr&P(7;f1atx-N24z|AY@tP
z=XBBw2FmPTsO;16E2>@5<;DUxnA?PD?j>#zlJg4S&d?oq$P5TXEtzfM4l>o=b*rnL
zUA?rNeOPLPnTKikb8mP<AlLdtT<*r|C%zF6Vc^?eRS1Pm^PVFZQIKoulcjlpMmEpp
zuG4%Wfolfr8=k2}CLB~g&D{5GWuc4+hod)nbjka?4R2{=ZzTfe_mOkcrkiDvea~8=
zQqX!L>hhw3a4Vc+e-Hb*bsg!H9r>vvaE&XeDd1BZZx?r7uNG(Tg6x-LR$w!`;O3M>
z9@S!-fFbWfB$)_<jfB{d^Uo(~(^&~^oy@UkNxSOvQS&Uc&QX9r1%--V10XTB6_k5N
z)zM^d#@k%h-FhO$x~0|^T+Lf5|Ilg0H8VahQyNa3C$WTkC_*KwDUy<B?)HuGexD&O
z|H%22P$#xu+P0!pA0N;nOK+1{d-RNZ3`1=slIB<(0U4c#P6nk}rR{Jcr&QtDlun3)
zs!mt%Z}6yZUmwA-V&=aaZ26+~sBvG|mwUl7hh!vBB1AC6YzoWMPr}?W*QB{Yi<sp|
z1bNXRn1sOe1Q74vO4>mRC`9a`Vf)~4SdZ;{T;(2(9{BnD2*(iCiU0rr3gZAO)est-
zDI(j^kYX{*+g)%e)y)0$N(rUhwk5DKaF7COw00$_d4u9zX3ffGIUoRj-IZ0EGH+0#
z-9Ylon2Axh85g)s{6`?@Z$5^Z#EZcR<&~i~dvBlI*zYVNU`13dcN<ij<`4G}*MY9D
zAX{U%AcSc~&={QdybxQm=RfIblI4S{sC{UQV<&eSe)FS#-=I+1#b?w7-}_^YU#z3x
z`>5n;I5rv8?uB9#Qx#_Jl$*jb%=+3Y{Gu<FCCv53J?5=5KSN$sVaZyg*JG9ZNGjU|
zIV=e>CD37Wnt&&OK9n#SWG@LT)5t(rbOjxEzM1}#Bcg{x;G&@pH@%reDDwfg3{mbL
z$A|1<nwA>TD3#ByNF0(RY}#nQYuwKcu07ECf-Bk;k1H5cgveMlSl~*R_)&0>d@KBo
zC;WvDw{6fZ6|RO{=GR(w32rCnMr2>IFJzIUSv)nX4$uPB`QpwU$m#FrU7~qy<-=b9
zcJ9Hn;nI?nZLKZjF%jQb&gd5Y{nslhy?!lzko{im=#$ensVhkwkH#edls4a0DiD7l
zT79B(zJdAS=hgJZ-EYWw1SXoi@l?kcbebX94OW%0?WenQP#(lJ#}=^cuIrr96{NI+
z5)+#%xqyO|&Va)>tl0sB+c&#u6v0Kg?PP(i72lc@EJxE<<olee_`x5>)U0e5=nns(
zH6k!J6^c7nz_0OvZLX#MAX}|V&6Q_xGBp%;eP_95(P|8uK-J2jT3|LuLw`Zp*EMa<
zq6#BB7F#8!w|lzJrelZI*(?TV)bubz?89|m4w7QP_j?p?bHJEIbC)4y!$>!mg^b#q
z#hR8;p4sV*{a=_zd#<@9@Q$}~Zl`R^gnhieSkq_C-%$1wy5DYFxp-}I7G%#uY5rcS
zVrz?*3TF)xg%U81SeCkBT@?TtRz1>0W8805ISL41gzAL^@NcZF0*4j8*A8|o;-+DR
zc{+&GcPZEHiJoc~h-3-PiZ&wr*ub%$U07ihBJykaYogamf>obdF?S+gcgue<ZPO^Y
z8$I_g^^S@u-uQepp#7)jQb5EpT}>+4(phL<u^7FoAc{?3w!j9A^kgcPY|LeyB_n%Z
zM)~J<yltucMBZI=dhvZ+VEA%k?5)+@;;Oz~2Q02Oa=QBq38PCbzig$>Pdjp0Pm&m=
z1vN!ljXIv{O~b&burz3+x5Lg|S)NRt-%`DF34^c!5I|sQ9h4ZDuv7)_G2Ty&XUE8C
z30~fszhzahl<%t-=vh#DeMe7bH3ia@r}=kJj9_MsQ*;#h6Jl9=!cZq}LxhK_U%~h;
z^9W$J@0b*LCh}?-j(s>8W`wJ*C{5aM`wpSVM10%1Ii|R@kdq#BoJBbJx>gfYgCAYW
zs00BH<_zuj_bc|?{9rU<a<j95So1B=k>ZMCk@uEwfE>We=9pdH6wFh;j}<o3uJw?_
zR%$9Fn@Ztt7bek6A1opM0sG=X<SRfG_A?&0PLA%K11S@V(z4rqRF|M-$9ROZ*f_)G
zz)&%&(-YV6wUah<&sOHw!)MkzW>GpIj)VJnY0g8Te(}|zMG^<20dAiPNTrfNkNh%G
zC|H?N<$W$?d<mj}kzc{!Zlf`}$7P@4l3SQf=xKqCc%bOAP?b@7Xih9r;s2aO!jdU#
zgfF4h_w9aX=?@0^`UhU_Rhe}f3*{92d?Ok@PB^CJ^X`y$G^9&=G1cJ;=1mIXDC+B7
z6TczZN^+5uQrma2<bomfk$dL(l6#uMf6cf{z?x9gvznM3hH{yo_7Dc!2OYeNrhpIw
zBbI_`&Ln$~L|9@}G!s<pvf|#FHOrFzB+Ke@G|4T%H>$bMbq)4B9xIw<>J}qCOuK0z
z&<F?6=d)F^R_Y1|)8<P7gJ9NoS)CqgiQuKLQw=4WVI{Eeb0F6{9e(+pjWadn&pAU<
z^IC2|M(Cqm9w1yu;2J<<Ns43nb0}*lB?nckzcA7smtf3`Qcw9#Q!l+h+liIv4CaBm
z-SH`ekHcB3kwg<zl2*hDB<<DVJF$!rJe;?4v`u%nuF#aA2M&TR#E+U5?E@UM+F5r_
z|ADP<QnF<zoz1&>5xRdOt_C2;g#R;NJim%f2$R$S?E8}*HgrTQb>nN!m;&if2{C9S
zEP6Dc9>K$=6S{$GX6Z$Kn}pFSp3!G28dzRWdsv-XUK;cM!AiNP%-Ev+0h~_k%920e
zuPQXo_O;8{qFI&-2ciIyP89d;#z=Xo6LF6~+EQ6>z2=6xvjzK)L)wB;#tCpG1ax95
zsFLl>8t$cbI4i@AhrRw>U2GtygN*j5S2{bHsrA{NWUZh$@yc$+t$~UgG0l|A<ZbO!
zAq29KQys%Ngk^R<hgG`J07*l2%O`$BMT=BWEJQRyV{fQe0JILI)K$^iH|LG#!;#{P
ztp#?zd_$rUxK<sU!fLgNG<cA>-v4`xfN-v%Mi&RTrdMcG6>+(mao$~yzb_SF8dJC`
zjBO1WQ6baVkCfEHSwvE$u_3CvWoKy^%~&a>#VjVWg3aj3_Av%om;{jpoBaUOLztAK
zIkG2G*I^<be5;%QF`5}tfXefgLa7HaE-FIQxc)YLA10_##;F7gm4-l(3R{d&MdTBs
z;m^PTxITpx(J4IyA)=frowdo*QE?i3NYB_md3nAXeMuE<GFcX@0NnH9#N7FW(_^y=
zzeu+nts2YZL$e`kwiqmlpPW6P0-sJJocDuF&O{7xmmDN_6b0aDiEY|_dR=x`Dk9EM
z4t&i5GO6V{m8Ovku<ig@m<vznD_%idy+NnU|6qqCBC<h_PbdPK&+wJ}o)7piyyb>>
z*YeW(8wZ~lX4DfnaDjBDJSjk0E-!+jgGCE=34CT7AWwRevc|<646tMLbPAL09T946
zsD`%5a?(xSCmq82Hu+JEpdvUnqZrmT7wFL6X86|Xuc(zv%<W0A{A7N#Ye0)W-nl6K
zIRO#%LLEk@`>31YtA?5<oiqR@#^?Py?TmB0&7SY-9k+Oe>9!?m)D-4Uk6{6EdV-KG
zH@3QYBJE%~a?WcJk->(6E+e+v!|QXa?*>L(AI-ueS~(`E5CkLE1#GhA2~s-x1g29e
zo|-cx6&L{D15UXqlU?A`4(C_nJwK5b9tj<BrEXhg`ryS{y1-2dxcB?|7UnS+@!n94
zKBD1ODQheVWvxL4F!JN9#_|~SsBV32|64KUMoMn-{y0nh>p4}UlN9^jk-(*v^vQ?O
zy@f#$c{oW4+BNP|w1Sx#CG;5(HMbBFCHx%clTVBwO&E}?L5~(ltV*B<s=nh@dp(e8
z3%pNzk~$e^fkLM;lDu6*yjBefQ0gwg?hXZJXjbT4L^YgXsWOHq(+vxp!M(?VgeoNl
zk#4m!zb5xQ2dwtUe<dCdY5??F^}F)BU#vOTnLUeR?z4knDB3=FZbA-q9EFs$u|5nm
zFwajV%7f8W-Lla`iHxLnJ=(=PuN(Yf8MN?Tz^^)?83*!ylLX(Wv@De`JO8444C%<R
zAv1gO7<SSQ0$lDlJ>PAr>Zv<cy!xSNDH5p%Y2}Q%+4*Jr#nW3Jk$9#fpfDUS``kjD
z5i*3Dv>?N*{^OJd;GkQrYyG~faY@d<TOYKR48Rg>oLv&Akf7Nd;7Gqv41};zs{DBc
zp9?Tv<Uv9vDfLmdG3pQw%tgQ}d`iCU<w~91nW3A_A+JBH^N{9=hB7E1Wv$R@rqNa|
zgb~-Q`+9N2;zZ0LFpB^4?AHOV*WyUyJ6J39kQ_kcogPjlyo_jKS5F@+5k*(keANfb
zcCh3Nnbk+N>LcdUY8o1lGir~T56bq9+W87|)K29wf+Msc^?b6lNRHGCE^^TW8vDVw
z`-um?cYfUI#b}}|*TLd3a0+1bc-L={+E?nt3-rOs>*B*bI0$3%`wr{9=PQzmx;7MM
zzUE-Bx06E-6|+IEf(8b#%g539w6oo+S`}%haW@LtpG2PE5_OM#aPImvlRy(!ixmFn
z-@0Cn4=P8*^3%%UtEha`LuBjrAXHJmJcSzLu&IczquI*GE?PGie2HHNG}|ABn0cuN
zC{c2>@<b!qZ-ZRNio7QD*oy|{HB6Ic8_Pi)HH{ZmQQmH)RzXtq)~<W1wf)%Bgr=z{
zTL0Rt$$#OxHAKfGQ&=KAHuWzu$sspg1DO};)@G`l5EXxQoer~^A{x%uk_B-L#zJ}c
z<1(k;y=#}KZiz6*Y%V=A*DxvNZnoZ3m_z1gdU!hgj^TFVAO4mYU~@Es6#ceKu{SCL
zx;g*U<6fRTlni#1V?uOd@;={QRcqC^f{~|}-F6vKaBIf|@<kh(xUM$Zv0+c3n41l)
z{jB6SwQAs%1=7ysM8kiFP+M7M=6Cur!_$wnFEwS5*Xo+_K2^Q+O94GL<)at>SYk?%
zUU(z?q9=dgGw?M!Bu2RIoQdKer^i&}&kh{mQj&Rk4YdyqW*lg<fJ;M@prwG+5t+%?
z64knkhIme^?0J_G4wzqHV%w4^wuQ5|fbGbEY(5xv@5gh=Ki8ULU&h`Gw&=mb1ClYM
z!LqxOnhux|z@0l*o0fc3PXHg1JjQUi<Ve2&D%fgKO7=9E#k|EE6U@<@Ro@VM^;_WI
z=#y!gEg#<L@EX-{pU>UuaX{-ZDc>DsK;_|jZo%LQ?u!IlylUKtbf~MFaF~dahHGcy
z@NLSaCVNGNH_sgqn1Mx1XwY6|>7$dHYDbM(3>vUjZeL@)=BTx4zvc#<CkkHuLG&c`
zYWRCsHWASxPQlcniZ`&Em1cnhL}e_ODW);04*ZJ%xOQwcW3>KX4tD~Gl7bKAl}!cB
zVx12;M0i&xbkYQ%Z>cDtSYruv?*IX<000CW7)SsB0000R07oaNr!X*)sI3BDYqtPo
z1Hl)jK#&9g0D2b3L)Q=+&np4p2MHc}vDxmtTtc1bEZDeN7?}7|#8--R?h&$n0%G0Z
zQE&wr{(gM@2;$l%1lh(0j7ghSY+7Qq4kK<zL_HHz=i$eBh}!=<J6&PYa%8Fy*$(#i
zy#+jJXI%BlObjN0NO1Hv3`Cn%;&YdZD!0dgUGLt9br?`a1ikOBCki`MY{N)n^mi<z
zh_!5$e=t@H*5AEXRGOI%A99`2&ptE0O`Cmt?9AnMQ{l6=-oDUY5Ls@9k3sMdlRK{t
zxaDo!*=YiocEno!m&|(B7C@D5i%d3{?=p*}XC1L5TtbpV5}vmnMC$L{GP$SN{M8(v
zYCHOlaU|@%j)@p|>f`wwk?ZHemI<^jm;$&AG1tFgs9B*Ff$*nfg9N=T?fHWow_o>!
zEF%~9X*VNgaPky#C{W(M*KUu*O*Y6R9Z=2H9d_|TzwbXKgB1s;hEhnof18;@278w(
zx|1Y53Zd_Yh~97=N7;etH7j0ui8CIcI2nBLwD7;<*N(E<mmy_7_S+a*al`^_j#+F8
zvIwa@d7rai^^dd2|D>>JllZ1Rz!&C~{TwT9C6)(Hx2?iZz9E#EYEEzNjoY43W!&{=
zayp9bH=zg=x3ddumf+;^Gs4j~--W-TZW4F<pY;{g?;~%uocgfhww7OQVa1h57InMe
zDM3hvj2Bh@HXU)AZ|b+U!>IPk-w-72P5queb6v})Q5MMb^A>f6iT))F6&7nCfKG!v
z(%!2@JzBiOK3Hr*OfY=|ZP7J9r>H}5up5MUPAB51h`SKM1s-V7WxJjz#e+1{oRLP2
z__`lz44|+dG*_@A+f3ohXe?V0yjRUY88`M{^$pdwCHpU;E^s;Xu;-7El)~@{wP}RH
zD<B6;P*!7WVKOFc%(@-)VI0xKt6o?^tVnaikzRuzhKRvo-V!+r>MV?rLoRe~Y(%MZ
zk<B?hP!c_)kn6yGyw1(RdGB|_12!@x{AeX&APXC<Oq<KZ4}j+ONwHGur6vv~Py@U{
zH?kN{=YUz8OmTg*sf}YA4%zgDWI_`Ej@iCeb_@`4NTUxDjgOt}BR(w+?`6pKsmxom
zA5v=%N4U$`WzE<&pNnlDz<mzZoAu6njf*tVO8f*Cz*m2WKH4ReX&A~1azQ{B_m|_j
zCD(3W4+j80y0QY*?xXTP*3Vk=A;9-7>Z3$Td>wY&=iE+;lXf67reD|pc@B~8yZcb3
z#z(H(*B$;2<T{zhBW+ysdVHpI>h^t-RrashbWl7IK(Ts-`m+R5auT3NNo-Iu&Q5ak
ztmXn19~n_+@ATIa2~kGOe(A=Z97=P=_4s)7LU;01F1qz_2a4xBp!2Mu1Tk`nUjw9U
zf$-nVPcSO>?=7hX2|CgP<esCDc45VMhf-$4iF4OxkWr&5NY*T2%{#3aw#-S_B89s~
zUO>zPnmR+6>r6nq8ns&{)3I`XyZ4Uwqa|Jm`G{Ft52y~Hc`Tdb<%{+Ux=%3*-==af
z+hpwpfqjr!vHS577J6FZ5f(zq@}r4pBTa7U#+70qr(yOhTr_=1%S;U4{%X1YF6P*-
zh%RA@vfib;pfZQeH3(;;)gA5&&I=QgMmW`~nWZpJ_>iDeYn|rGu0_8`g~C5yx;kqO
zL=vF*n?X7D??(l<M-s+Wk9Tm`?tCUPxu_>gAvl1LXIuy{6eAs%GPY`q?iGW|VFs1r
z>X{q(>5GxhR_0pjA^MmUE`H!@1AUL!2;!sScmM@mSZJnolX&P5D3+bD+avYDK}D_q
z-SOkzR@|LmAgS+wt3zM5!%j%{a;7Qe{xli_NrTu@i=ceocw=H{v9gIh*bE^ns`O{~
z`9ln|Us^}eJ9okJ0kj@eqL#^_BsAWKXxq+pLs_}VJtfF>OgDwK!@YdxK&%^T4Fo>G
zJEHKmw9rO|mJpNXzLUL*=MTbG)p}d(togGLm^B2^AP=?fpMpa(lGugJDoi%Kb*92;
zUjXiFvE_x-jy~SyMHn#Ms>8Rk9|RjDvp5{iKDsS$1GlV;gYf?y7m-9Ne8}&r#pjW<
zQ{kiyzus+|C6-&tBBxgI3*(!<F;Bh)e*oqE!&R%itk6Ezw|g<M;C*jH>nY*2kKelj
zc8_CrKZ$qr=v|hg-{jmVz{N>{HMgX5B-lS>JeWkP>wBhLFu@qCbv8hP*j`*aJ#K-M
z;QF|rS$yXQ!lTHtlSZ@go~0~vR@561!2NUp6w_y9gWTy=fAp_wQ{sbB!RUXoWbHc}
z%d_MukTz_hnG)+g&f)(z%2m0f8Sj@v<#mL9be6`Cj`i_-ZiDk2=&V&FGSU%4r_?k;
z)Ha9;-N;_3zd??+@PtrkZ&@gI&WNn8wx+Ju8Cs-hSjdpidb7550DAAah<t6Z*KiNq
zB}E}~YVx}#!a09VCBLZjL_a8EX*8}PI-mca7do}loh@f`MYwmEkm;qx>0n)*gwof>
ztna@o-Iev06y9~chfBO#zJbSB6TA+AsH7bZz5S&CFxMYr6_t;t;8QU2O{Iu<&a9}C
zZ`iF@-MSDo><z?af#s0%!Y5)i2`_5~5;!u(=1{mSh_3?autzndr1AVLzzVofb3@G1
zIp?}A49L$IuZyvM0OY&!{m&u@crPtgG(Qp9NgH`LMJble7<QA>d`ZmMG(wCO>+OLN
zy@^Q!^eD{1zaZZyk}(H^|E#k&wCMIH_2ykbDjLd#=bt<Czvd+mo!KNGaKsTj<b+!s
z@yBNa1;<_L&y9SU89P#FPf^nVpfI5=c<WMZ%?+t7T+ou&n|XsjR{m-z4FlGO%7fU*
zGcDyh_rW9_^dR2y*XEywNTQ;O1;L6_rXClnRN>}U$^+XYP2rOjM=Kx{ymLk{>GF7e
ztwSsC-A7C%I$^Lgqz}mX8b90^zq0Y*nMF7!dJO~?`Tp+V%|Bo<X>5pCbwjFSEDX3F
z@#lJJg5s-SnQ2`|8qhi<9rj9>>OTU;<|1G@EUf{I(aR+XM{L7$SiiwQp(fE-17p-*
z<l~A3FvY5<rs>4f8wvCy+~wq%Mwb1$7_9!v>CDJpoO}a0vRta<ccT#9DYFx_EBUw0
zTrP}2c$*wolbH$Y0xUIY{*_O(XiDV>C>Ij>0v)MIR~YI$GBD%TfF_8u3#LN$)#N@_
zj{`e(`MzloYpKY<SUqrM<IG4eF`YkLm>W>jzRPW?9A=|_Wpd~5-|x)!T3yd?K~*tf
z)G)Ikf51i~=0%j{o}+02@Al>?avw+yY1KdU#n>ey%;x;0wCGP-KBs}mhMt{Y@B5Rr
z$L1rr1&;2;y-YchF)qg1$bC53coyGBxdb2+LugXnZZTBti!upM>)IAJG~axyO12@;
z$X8PvRrOQHw2rZn7s<9l=kt0q`o<j$3E4xfx3J|sOhwoDC*KS!;@@44IorFCn4xQ~
z?_W%aj3Kp~5e6OH2;=7#5~Zya>-2i-ZEDE(g%#(%1^84Ksy}jxWCEUXowZ)egVK~L
zZ0-2cDUk%HgzD4KPbBGVKnM+$SHCJRyI`>dj?Wi-)6(|D_f3w$)dekz@sbMq&qLW$
z2YdaXW)0%VGWv)|h!0@u=S}U4Ebm({?q*Nq@n&&y$)7dqF!Fp<XNe@#*mJrMUcifx
z-E&RkY7B<fW_~_%UB@Ko=`<u?8}oPxb1eb_5F~SEQszGGm<e;je;kHZ1Y-TZT67V5
zC%gLbtJ*%Xg9<G~%I7rXbKsnWW4>Cr%T`_?X!`7jAzbzon$Z#4tj+n>?Sn0WJ$kGl
zRe&1q{4h<a-6f+55|1`LYYFFsyL{ByaOBvtBJv)-prIi4dD%~7>v=Lmb$L&3zQtrr
z5r2PUaZBs>VU8(;!Mw^UjqcFcRPmu_&K0?+oCbwdQzlz}eQ)-kykek%YPasiAa93?
z9JS94;yx_ty|a!?Cq_~wcZDP_oKQ3X#H)%ugdf8lYU|L}{;EuZpa8ohHFUFIDChJ?
z3bZyNRY9bME5unRgIJDLgIElXt{@4{YX{gklZF-tcC$tDG&b|wC5egW%sJ}M9t^H%
zCGVr46(he40wINJt)4fN40L8pV@Ap`R+{<<Z(4e$hNX9>>z*n~Cv#aWS7N8%-Q}gn
zYJ3R#u$X}=gw6=BD7-IKAZ0yAhn{>0o~-P<%*Q?i3dNJ~q)t)mZ$fodoR1oj7$vAP
z5x$8R@P4tUjEX!VMSl|o04{{^dk@h*Sg>_vZJHAHUEfWldJGk^Q%R#sW$7u#6uw|k
zm7n!&_6rnnrA8ay0{HGV^`l~(TIkjUvCLac_wP0Fkgqh98sF&VYg{@5!UL5Rq1yRq
zb3-(T)MSSl(?609B2eM^u<bvN{(TZ9EJkhR`#m3Co+kQo_#r|s>;Ey}>fMJ?V-v;E
z(?3FW;o-RiXsj!iavefufG1V%5hA{H<uADU2TF{$;s}>k@)d$PX+l$M^p~IN_1HW=
zpdV*3M^0v39b~U_U?|QSe{Djy4qXaP9w2J-<;6$N>W;KsDaTIK8$3Ty)xq^XCG@6p
zWvA9VV$~8xJnO|5h!E|5wJ5A}<GL4=iUkd%r<cxOowVc9Gi*g(6FL;?D9|!;W87GY
z|7-hC;oK+RRuR2#3~93}Mhm1->~|sWRJC2vOfp;nm|~;_4wrCockbS`fgZ>%#CwBD
z(o4KN9Vf%4@qNSg@nu=gX>-CVqXup98>CSaZxJuZP{&S1s*W$JVlu@6w|?4Iv=!V!
zI;z!9SsAtgW-^=HFTKEAGp)>I0zY@~XQT+w`b#`{Xa0JYKcWox|CLffGWG0nP2(wE
zsBt3y%;C{f{hhDQYg>kb_BZfA|C!QSJXA@_qtm?|t<Kp~0H*yb9y3QMf?CB$oW`_5
z1Zj8H9+cenNj=c3ANqnQG|_Q9-0utE1dax{7;p#EumAu60Cj<SoVYp<7%<>j#XbN4
z3iZvEkR^2I(Br^shvdleeE`o)7tfAk%fP#(lEHW*5v0sIET)7FXR@aUpQVzU=7>oV
zsXQKGU0x(j06)e}IorH)I59?}en3j+Q@r+Z^a>nOf-mcgZ1wyF?+*w?Di#2NS4SoN
zDHffGH-?2YheqATQ%nzKYkY3cDF2ohNxc00@}-fBTbMNxc2l=MPS`-3WeR7cwAJ-6
zA9gWT#S~~Jub0z$R55dgUj#>g{=LZOuq#2yB-$T_AR1-2;w|MCE{`Kw)L_u%DPqZe
zxf1qaFx1<v^ydT6q;FFsP3~jLhD}QtbIjX9tMIz5Bkkh=XT?JC6T4XzD%SGTmP*B`
zMK;>-No!rt(71?izU@sU*OE*YjD3BokZ>ics2<JObG3L*Mn7Wexrxw{LW5vE(OO|`
zn6P|TE#S7lVCS3L%Boq%)2_C8dBffIOxjSS00r->bS4G<KZf?(5ZLIBU-+KXMcp{~
zpH$nZsecs<MEwOo%E}Wo<nc@Dq>DGnh?{KVN{~giCwy>X(J+<Xg1k{nLoYoM={X?@
zFp5T#bI{fInS7&`IraX=&rCw&7+SSQG<0$^9Q~N*x32hlt9uBD1&Fau%=@(cuc{pp
zk*MTx#G0NN&Z0C{SHlf61BcNLLN*D36!9LmK0N@(M9PK&h^MgO0Gtc9CrNE9=6Z-z
zm5Mrt{O3Hxgom7S&EByW-U-1OD(_~Uf&4HS-BV!Gdkxg$Xp#01oU!2A7q86Wo@N-~
zUhk+uIaY@f$hcG>D}yd;489Rss5lJ7m-}`)!nSnSB6yw2_Xz7*;nFKq6M{575`4-5
zUFq*;gev(AmW$+DQfKNp;%*EOB>ZshwKhPI%st$#5rhvXGV5hxduKK-MM#wkH64A*
zi@(o2nmhHQLEbXVhz>E5Vr7iT1wY9Mm;8X`r*>dY+63}#BGQ0DH)z&2mdd#Zws<N1
z(zBHkX-j!+hQc{O(WipKJX?0R-C)z~P)|hs4jqTxG7C6n4k6b6-~&(lLvNEBIjf-g
z<XM+;PM!HJO<}C^JQi#V;PheHch(H`N4i`)v8kP0T@-EYEEX_5hN@l+IP;tg$<vyZ
z6Tw4mG=<ln2ZMi72Wr(%liA~JW7i*c<dqglMh^C$rvW_X_1|IB$J0sWNZdGh%+X4M
zLkDDAwO|b>-I2GQtB%-a$mnOK<U+whIL}&Ge(`DE$T~WYl>Z_v9k8N(!Cw4FmDXSu
zVXXTah_;j^#gL|N8a5#Y7@$;Ok4Hx@N2$-q%ZIPnsecP&VK~`db(RNLorEk_C~kz4
zHDV}Q-eDK1vvLUuw~~x7V^X=MTGJ~K_QzS0=C7SmLS8tWJAC059hc|y9g;jT<$7+h
zwfq43{%l$CfJC7OGp%Sc*INOup;YcYV$cms|0kSh4h8Ey+yOQ*Q%dk_A_Um?Pxoed
za$AT37BdoM6-6Q1;o^JeVmlTSkRdmP&q1BPGu5u{WGRJ{OI=-qb4<SmK!;8MygxtC
z5S736h^WzD+;|kjXU-LJn;THJ%0(RBl8x!d!p~PGY!pTS4MhOT0L|uebQC{Z^U7x*
zotK)87b6x6@?lvzWIXJ>!SbM&Pl}GR9TCG$1F(4i(tRKg0$#rE8?^2<s9EGx^Y@+J
zvmNXGSn+gMmi86{X)W`DTxp=mooY?V+nZ}UX%~Su-v{<Q%uL5TJrQ6qYOZ)^$|D_3
zLh@)jL8Xie$mHi#tN`L2qO92IxthD=)Nc5n|G>Sx4R^J6mm=~HKaZzcRYxWJ6<Qb4
zHl)W}frau9v_oN4zn%luKiT#ffip*A=!7}ICi0w-S}XlkE<aQ0x>d&&<yldA`0#$<
zUo~CkX<f3&UCY{ZF>Y#*O7m8?%4O+UbSocBZy#oljcn}zR5t<xk+S}>d79Akx5zQa
z)Z51#d7Cj2mJ1Ku$unhCbL%+;wTg2)ZE>A9>{$r{$QKsd2{eS}-@3An(zvD$XLTAB
z9xr@A_oq@s>;9WADSccDoC-aaRnKsVik0yl{?tV}L*#Vm;*CV44L)+dc~LiFmiUF<
zo5Cv-2Ew)q-~)Kl)do1vY9De^ZYtCflh>xH!+Ab2COJ2}3udX2vpVF&#$U^`FOqQv
z7_Ne4oFJsfsgX`cz_euGqw?I7v0Yh^IsfPU2+=)t9h3DLRxQHkBA%^u$_bm*;i;Nv
z(+s$t)iPj;iOR8G#(}mt+Ty=Iy($U^FzASR;nbq?on}_aNy>;4;`<y=y5_VHCvInN
z(%CK1I;*2i`hOKbFv%_g&FB4yc17C3*CY1De0{p96Z>g8d@5QHd3u+!*hpUBP>O@6
z#%}G22N)z_UVD+9;tWSuHjTff*v@QK2?L*}f%%PIxeNr3PtvcwY+j@C1w5hz->hDr
z(h%~7*#2<!6$fyIa%}3Q)*<Ea3cwJkC$Rd&0d|3ozvUhxH3j73_cqi@e#hr4xx6Bi
z*9*!j<SMDpyv76WR*ZYm(l|A%A<I4Xyp~Nvv|UX^UH#A=;p#q4$1FmIqIhab$0+PY
zuwOG#gAA8@gH0VZu$4aPxTyI%xCh35L90iRm;Ro@0;Rrr`))Jt?|=^^mwF<g;=DpI
zlg=<A?5ux>7+gbyi$z6BenSDfS0gM$Y`4xZ^E+R>n<(?CaVA5VUbkUGIr1+7!S13u
zAw1jP%K)Xde=CigLweKat#1|T`)>Jt{BK~r#b!3gS2Yp)O6BG>*vWN-KU%d0Lf2rA
z!N1L$eh7c}fAn_?GI9cq#h%2s6eem+oHl;em4r5W3PL*)#6qbA{agy*@-qVbz#T5`
zT2h-6$?z`m8!U&Fu-F6tpeRD-`7+&+O*Wc62b;d11z@>T_>;I55OAV+`;WV+B3PS_
z<ab4iEfpb(wxi&(+!c!#Vmn>gTv2mW9*;#cc7zB4SXHs2?KIIfU~kyJfwpUQIHJp;
zq_9pO`eH1k)wYrn&M(bdmQ}`I-!E)Ge*(@`9eM+{v{LjfD=J6@gw(Er)7j93EsQm2
z6SvNqErLc1DW5}$`M?|_^WzBtWSH&@;E~-8gR{o$kG{Fw?**$MapbOaD3KT%9KMX`
z615SQ3Zj8DKVgO1#@qlzp$9-$aPL(dSCaraBrj1ZJVn#asw*dfW!^HG!P2n5`qMg*
z0X-~MQ<!7IS~-EYS!q8){1%tlHZ~Iceq7uhx8^E5M@~HCOy-w^WGU{$Q}{H{TFVPX
z<p&E5?CFS%F9=!cbd@^|R8Jg}%{9Fc3nTc-iROJ%C$u@bjoaG?m*G=?kt7lQA8y!P
zTc(<R*t==3Z9}Q|d>D{{B8Z){dbY)IJ$hJ{<J=fMlA?jgQ>Mx;PcA4bJ8iK-<D`|O
zT$snJTpXb)l;cu7l+_PuFjOj@lKHJ%?m3X#8om8y^Ym`OZ6P(lRk<N1N4{#J+!yyA
zi|PyY)1RU8$mrZvG8F0I)Q^}V%vie|sGixdU>X|5of8^2G6Jz=GRqI}gaG_rbJ+`>
z3)Wk;-Y9EX`BmU&8Giyv0d|uw`VC(Jo=ofR%|dF}qazv=5F`O{B9kEfQ^d%WK)bcT
zJTzGRB_G>+lIdR$@*SJuip83y`~?wzAVTCSkaq{VHqS39d0=jO<W0Z|z>g+buxq?J
zJ>-nvabOU~+P1Qed*dr@QdkDFq#loZe4a~O@bT;WnXG+|{{wD+`nAzX)Eav^ZrDY$
z57-tYphVi2FVc8_Zyc-W8_`psu!g<}N{}qLG)|t1><etJky@!pY*s-vJWWE87ogB+
zd7;4StTk5gsj~D1GC4QdR)*XylmXX<KXT21D>+h#e)9zeJ&B|+mD$F&;_WL2zR}U0
zM2#KqOBha=d^lmOE;iHS#!2);Pe<to`!|M|IPfy<kNUu2>HsB}E}I9eWxxe)Wq}AB
zC-QN+7{R!2amHM@oOHH4CXN|;XYS7+Na4w@6(z<+Cr?D*@gPXGZK@XwOye`F>OIm4
zFpO8R-PGWOu(nY8i64gt?W+pamvWUk4Yp|L@B-o}+92>LYm#3QJfeW*JZjKm&Xo`G
z82PrgbHKGY{i^%*umrICKGFqK8dbx%y2sPWy9i=z*G0F%PHlEB_C_pL@^ao}Qjgvz
z3_6m<6w~u@>~IrWa`aIgm3A@tfQ^mL&A?rm)az=zt(7VkOVL+l#nCk4ix;`k;6T`v
zYu65*&aC5;PW}E!y<u-TyW{v#<x~QllX++Ce`ycriVzDq4WcIWlgZ&>#XYYrW^ty4
z3i3ik{-Jr@uEin_B!DdL%g#6Vsx#lKH!6+6f08KGO2glybWNx&6zZs2OZ(J}l@lAt
zzjbNj6a;z(*_fR6g{3_sN9)vm3s7SrG*L-zzpWJBp22CsNAiGBhQayaeQdAyc1u}d
zEf-T!RRowu4zQ|pR*3F48+LBAMi?@9>nvmjx`+}SrnvqUvQZW8aqIlv)M-88%tR$M
zzQ<ZndM8t(xe8;@>^aQiZ-&Dxj^dyxg25F|jNyJqUZ8rnHq^gh#MXzLQ#i2Y2Lc#F
zlpvkK|2-gNvmwZeXY;)b02&>wEW|@3S4#olD4J-i)6_VxUz5zZ3Z6i<M0#<Q6!#}p
zEFn}CY9wYcn@!&QkA-gx65<xkX)#-VpJ34diJH()vei7n5q5>z^BhN~L(5jK2Go~@
z<x6w6(e=A;vZsLnmBso0jQ+z}g+4~Rmp}J`Hd*DF^2|xBY|r#fmlHh`we&^=AJjdB
zb;mUZnhauKn~PMKC~KK!;J?Nqkj-VtB)V9E)`%)ZpuQ?|`W*rtGq~^qHqw02y@8%%
z&<(lr<rLuf#4UVV30hwfFQ;l4guR{VdPT-X8*<)IN^x|sOu#^ZvNro+0m+a9o@`XD
zYaB1zV?)b5%IG1^D9{^h=dBZSlo+t2zy>1w{MQWg%UIbOF&Kb;ntt$Ja%jm_0wx`t
z%UgYv{`x`Xl@b5uWei<*7LgUR7q|YBW#-0wX>JC}!75)O000Rk3{n*U9xwm^MqoU(
z&}N|N0B{ZZB(2Fvu22XwW)J#8OYk--XiqgA>ZN`>ejBlN5Qy!v$AXJp?z!b%`^LeO
z1SZ7c?6H|ZOT~!1`jRN&7owy|@VR3(d)ISG8dVj2lAkb|k`;&v_GCh4bE-=bOE-zw
zy&;=VzXC(%0p)O)IJ!e@6Nx~z2pLZ^jLe~VPj<~kDh?Ztx&Tyg*I68&)j!JJ^3SpI
z(g9a9q*ert{O89Q+rJZ5lEaa3!R6TrLeLH-4UhsBwjtsnM!0Wk+%K}<rHsDtkM~i2
zi=Nt#3H*1PHx8K3L5^zOCSF1VeN$xBH)=jZ899@R>X=(SC=O@{M}cISTE<q~sZOzn
zcp71YMqR~y%r7Y*L?fcoA?4E@2Jn;6O;mTva9K)fLxF@ELG*|591-us&kU;#kw<}2
zDI6YK-&sIOs(v|>@QDX_>(e5mbI^pW)x_P8>6Zl)<g_B%cuF^DZmF#qiDg7Lomvtl
z;~Alr!Q=tE;WkVpgtzV}KG8w+Uj`30%x#yrN=|M}l0r?9K&Nf5Hx)VNm6b57F+$!*
z<5;E!1nl8wr^^8pYrl4oKLyvOJv^al8UR+@<8PG}H%;_$y36IL#12JaAs*caC>kUC
ztBgLH8zzrk<lc0zxdiYuzsFGXT;+xVE*8b;Q@_Mxu5p_FxKAj9Rv65q)OJ&qWXepe
z8V}ursL)Oo_!uiiRL{py`QE8T0m4-|8VfWK!#%!m0S`ga6i6)S9wCp|A(a0m63#z-
zasAe{oKt;Ka6)8|67iv_27?Gm^9W4R3mOmX97c={@=~d=^I6;)S*AN&IaUT%T4}Cr
zRopk_w&L~X653lfwN*gKIfbZ`4jkCA(wO4O-z}Dm3Vv{xD9PL7HN@)5*r-v8j{3yF
zmYc&0Pqqr5B&Y9#Pi+Q)vJsgVc(`vV{O{RBlq%a;td5vWg6-<Hlf-FU&J7>&EjQ~D
zry7?JOSOR3o8j$C6?kQ&yqtHDL<y}l<4HzeIea{YV}tJdM+jDuSOyJ^J&Y1td{=AC
zNvLseazT@{hJeer==gn8d%B*EjSNe;CWQuS^8JH#Nobrm6$t|*&qs1=uYtskRD5^k
z$-#Br7{#e;F;SM>U>n*}G8W8|i*KqZ%>Z9OpucV`{ODdLjs*m;*gtV>tew9vg=N(?
zCn&#Iz}{~)zy_0Gn{c<4br>;`T(hX&jq81ltt0@Low3uBox;M<n4wnDK<)e@Uy966
z&pIs(JCxh_!E|Q^M<!V$XM|HWzrhJ63g=>ZD1m_v$z$s~^il%oB=k!kBg|KVn6P-A
z);_STXhhkM^r~sK)8`AKS!WKJ*w_w8+Ni*_sMmkhY4DVE%s6gc++dR`f^m1y0hvz{
z^>O|vnQUBl>|X<5V{pTq5aA`eJIA3Bk1SQslcUS&m=3N^k(h<Z$Mo8$RQ^p$+(6RB
zS9g(;L5mPYY+}X<I4wn-5&Fm7_Qt~hH?;JFWiKU2h2G91NhLIqu&^)pjQS!{hXgXa
zE+}QcQzh(z_q7E~&p|(o9_Y)0>iDG;)ycHTZVIuotDW&@RnJn6FK07g=UBK#L@Hup
ziSe7}gt+{jwJ+vf_1Rg5%x%R4x%UIS9WZwPG~l^c`wtlo?~9Amr~!OivNu!Ljhdx^
z!)ny)TG2Hiqxt@JZ#Bhg7p`Q1=ka;i1*;=0tc5HA=W)Jdy*S(sLXBP9C7=94--Y_<
z6o4c^kZ9PoONET$n1fLNzO<FANrC?8D9;!3m(jF$YbxvbObyXP!Z35vwQw7Ou({a)
zF<%j<S>Bi{Z(?&(k3^E<Q;8pfgBm>1k?xC|ns+vZ^8sQ(#u9>~7jHi=glk#ea+Ro!
zWXdSO#n0zI3_}{y65x<VqvQ`Md9)oxV$gp8Cf-S&;_Iy5n@rWNO!xGshv4>xI2F>O
zo?2%ix$v%8_3%>t0eOKXg->P&T?U-0F{`>2(Z{HvNzwcsL<oo))}jCutqW!Cc5&(S
zSB+uc{OwD|1v9WfRJW{d*S%m_oz{$q=9qzP{A~z8KYh=@ICM|6ow6(V_B*_z-U@Q}
z8kP9R7ELU^MIiY$b2?oWw7-aFU?~#;`|o#QC?0I9sW;GgKAk0(B}Cus&U^{*F*I%P
zVm9t_9E5j#=yl!iRTRhfDf(L^m81<)4{~4$8oZQIql5N+1odv1Brm;sa@`JKYcw{6
zKqXs2GeoT?*2q}Vy(00P8Nb{VlgF+Cpv<k)BB&3ZX3#&n#u~32b^KgS$+-z;n$S5H
zm{C^0yR+9hyeTF2eQ0{MfgVvmP+;}N<_(w<^vky~7pXy)R#1f3tHH0Xt0Q+b*pg`a
zRK^TjU$XiwcxRu{1-0&;D<}NVhf4oDZfeN4nN1ntX}m3y{fTL+;?vcqV9ih%`yBv8
zcFK@p<@;@jj1c5M0Ap0iN~Gu1R?=Qu!kpB!>e1l7uyVG=>v!dc9lc0W-zJDQcHMfB
zUfLi;v|wh(mcRM7;^IN8;-hdMY~CYkl0Kx}fl`^}Q~#w{2sEsFM<JA>bO||uMl|<S
z+R9olz18ysU3#Ydr}E?%i6YQ|jY<6rb!fI+cgMX#_o4{l4{(VCGu1}66HWj3)EA|Q
zr0c8KjXocg@S|cAl?=o35gV)<r&Ym~M9}-xtu0<IBN;LErO`TC!Y$tDC(l5{PUQVB
zt<wCvDLAv5c2jzCs^uMa=l=QYTMW_J9!2qpX-TVLiWe|A6V=Wih#jA;^Qp`!LR|ix
z0}o+4WR&$R_26~M{T_J^BR9$#byWt15El6A>U*NC2}@BwjlCHD#mw=y;RGQ)Edh;z
z=bf)dMxsmib8I=pHY2u>&evXYlw0qC5ra|6h&pRmb!PUB`TOXWK;{CCY?UBb%y;h7
zIAiHuT5C=bG<$Ra(pP&ac`>Z0$-g)4y$;V@vui1+FLz$=XQ`X|wREmR)kZ{XGg`_v
zZeXHK4QyV!glAuqxx7i)KLE#9W-q2d7v%{()F_^3CAJkLU2>#LPj?`5+$@6l&f35o
z4u4zLqf&Fxc|~`+M`&^PV+ytuINe6p)Dh;unei0kLIttk)_&CUb>kkbO?IXq@Y2Hu
zSrI#|RGc@)Uon;+JJE1}Wb#ICDPVL2=QMD@m*%9NX`iqtO+0Tb9se9z9Mga&5b~c}
z?AyB1m?zYZ>kin<Rr!%$s5;t!JDi6|%xM7f0Py>6S@(6=-zSqs{<UdBJqVuW-KAwR
z3o=kjF0p^E-?XftA}dlW4iOA+2e<ci5T2XOgZ85g+L`Tp{g;F<J8~iYNt$tRFtOgE
z#8a#c(M9AwB>D0}nVcS2x=*o3kv=xk*X=Rmg8>;jO~VOC`Af3u9sqLmkj(c;{#T%D
z*GVkBIs>rLyM6J!M9b7d07wdT=jt}w^blOtMpH0j2s>+PW6iC1`$i9iqP-<Es2yP%
zhf~Qj5pBSUc-CMa_;!4lwE95ffm~supx*3}Ku}Ok{Lc5bT@UKmrHn{%CPelYE<qg`
zl}HMfaHDValI<uW^^Xb675i_{nXnsmZ|3<!G>V@}9s{Uf@xBw7D5!dz;`FAGVwizG
z{P{(e7fjQyi5-8__744YiF0>AZG-Qd$Mjm$qG$~oD+mC^j7Kf@&rU|bE2qmSf@;Go
zbHp?DhHj;=T1kEv%(`r7{`T^T0*TVROE9l-`xs;d6Re(63cL(bnc~t#4$S)9#088^
z`)%41_a_J&xuZQ~BlesN$|=9&hLtFFa;7=ldv`cTG&S=RlvT=#On^|~=I`+U9t>qQ
zJk-TCpN!9=cHOtn<1|h6^Kd+J{)%2oPDuGrXp*t!NX)DU`%wL1=EMei?uZ(@o^Rk6
zL6ZPx$Aw#Nu$loIRu4p!1*BR1spEY1!IVsms(A~-z5qA9AXC7gP8MZBDMiLcSlH~4
zI6$F*+frrX6VHjk&})-?z5K&v8)D<)`|YV6B=%ZWL(9czU!oT0Hqv~+Qks+Ynth?(
z`ztA1d~TvHB4vQ5QuYqZ>ZG98+Bag>n;B17^Q%Oa8FY<NV8`^;1*Sl@tXEU>C18-L
z3v>EXTaf%FCi<JYibt&>n0SMZ!?<5$l9@fU$$<itkrMK802eG+nlZu4dB`<%ZL^ED
zoxY?XMGQB}vQJ42m}|^0VEZScppt|_L82qa>`!OUy5!RnPpW1}LxPI}m+)jLgkQJ@
zBf#sq5EY02dD0BII41SmKPp_U)+r;sEpm)vcq5LG2VlK)qv8C{H7AbVT^2KInCD!7
z;c|7%-L+*0hai;S9`nfCdfeIzaTjL(^N0rkX!ua%@UU~O>WODmgKC3?M;M2W$WqKq
zA37z3n?_2{NXZ*@K(CeE2_@eKzG~+Fs=;B}wu0K_JO=FpP<J=!&%0yb7q^znydqeH
zC=ps2rRj>CewA6pQu`PEHLjO@gyietO1dEryoJA=*nCUM6|e=z2a=7g=l_>RE*1M&
z^A|*#@0f^uEg$Xl1>J)2nXu#&XXsF>hCVSTM%G~obyP!)!gCw<)nYYuqs%J(A-GEX
z65QKl!QnPEp>DUUaPhBT%q1vPiQKz$f*k5HP~q0y<Lkzk7-z<4vyX3IjQFr|GR)r2
zTFZx*8b{-3SAhtEI*w3#rHjBXyddiBvJ*^DN(Iz`#$CkA%IqljUo1bUV??}WW4saX
z*dJqbotHL9MB*U0SdDkF1(u=)zZCR7Ja%^q4;f3k1mz#JA_F{N%|=I+vS%lntd55}
zhN85NoZ8^wT!3)J!o_d-{#Rb&K#5g<eR!@>CePhauP%cznG$drtr8c(K;=yylsKxe
z&?)E=jFHO|c;v+OX@9ul8nge5hV}#HKt&@pXXX=LHQv&;qJqd~U@VYUf;ceqo(~N0
zoVKIio5#*j!VJyD!Y2F-+NWwgYw@xxW(kFPNw_rP0WFKuKmmAY-tB?103+Q_gj6)3
z00000CQnd+00`7vZZ3OloQl|S&1TGc#j7mwxMs8s=aD&&NQv)q>PAWqFIjHQ0Y3fJ
z*K{FyjYMps<E6gZyPqt~+=$4JSQj5;qMnVf5Zk^n83*3K;TM~dmbdqx;y+8cPVEuq
zcx7)A?5c)ylv)yW=)-UC%YXc1d#2G!KDZCEF9)XOu<XY0qlZx}vp6=T;@sFp3xB=$
zm0cy#3n=sFuhr<Xh*36=!pxl?A<F%DF%vG_+QCPnv3%+YBp6L0RoK=8QgQh$SaVC|
zeThmE!vgXsKwQm%=>b_p)s*t9Zt;a{A0vs@JUET_)s#7-MkH=KF`3RXCZv-#xnVC2
zJA@qFU8b<{<Y24pj!g0QpoU*fmFUnJY{|5#$t<r(`@Gec@Ppi?Qd4EzsqQ6)i?E<=
zJZQSLu&V#6tR~#7+KV-0EDW8CB<uKJX$<GagT;$~7s5nRl4zFgRxLmRp$ZgngOgE^
zYd52V<JQ7N-1Fmy*U4Hs5uDB382K+|iXzfhX)e(H{<n1WvEuDD%*FW(q_q&}*-y93
zr?dfhL>%II@ofZ63X8~BeVvtj&x?Z&CluB|u3BHzebRGv3<CR(v8mCJJA&Hx#ff^l
zIALTny~S2Lo+ua9%IADT(n4i6QxX<2#mad_rrGfOzIOq5Zm`r8_x=0>y?huCMD!G1
zRbkl%#1v8n`pUtmugBO~>V`O<mUMqm8sNVjyqTC%!%llK8a(kEr*mUpJ7E9P)5kYv
za{USJX*sASxM`-~k41}!^Ic^}!lbn}D`aqQo%CuL05)L)(t%tF0BlP^%wNfil{XzR
znDMAYG~iAa#bME&0-eX~?|5Mi+(C6R>>QR*kdq!jhZF--=X1sMo>MH6i#=}~eWG$d
z@*I4p1K^TVxMiy#`)>9a07<g9HU5jz%K5&cAp3H9DW9uXNX|dKFKaBO{W~y|YkEdh
ze4@5WnWipaRHf^II}3+1#Jz-(z$TM~tK@^X@GO|!fBB)TXe0@ZpE+myG`VLpyY_Md
za^Z<o0R#zc)7tA8s$DBLaazxz-%OSOQis%f$6xv5zF{wC-2lbQ0n|yo-om;GDa9{D
zj#aqJK3%3S9iKlaz9M?fVMBIM1GT=~4`7%{TE@Xc5U4o)Od$Dfc%+2_by?#EszY59
zuIy2%qVqMU8hec(|Gx0BDXQ4zf_*F4;aP=0@K*fx*y4TkZ&oIUDoO`dWz4#5JGXjT
z^xCuPz>s@gVx)moiWvpbN<&PB-_cD|g!tJ%4UI$Z2}{<(Du7QznyH=Oaa;s+pyyW_
z?BIV``WxRx{{$v8{Lk<>Yh>{}pi<Tm1+_yEj7i>nL=;GykTq@}^w0D3EKcyA4sP2T
zunDne(5#dV(nkV-OLR9Bh{DIlO~&S~OvHtM6k6J}u>_ptpK2adv#`DXuA8RJ9~CZ)
zM~&r>3k+&&B`J?h!V>!t=+wR-kI0cwR#PEKNDAY0LD`@jtAQH-gWZCr>AA$HJj9c~
zA<L}>HV(;gRaALzQ=*Y1+mfLEcmK2i&VR<P-p^|0M-!x4-qhW-Orp9mu{wcKBrMu`
z{j5-Irvk)}=5HC5qcKN@v&QPNAl;yE@N#$D^%sX^vSBV@{Xo&d5!p8x3gCy+7mMWL
zQhpt6>{n#Hu-Ft|{9@lVTawZ1kGDo$^+%#v4wN~80-F*P1oLntB43%aGSNcZ8;MTt
z{r?^6{pIv`^<;gIvUqiE_PNIYVSLw(U6@T=!fP&R`*!(IEY*C&B3zPdX5N0=WFZ)H
zSwxZIgS=Ka2mq~1T7zQF^w2txx_L$1vt~2U_x@OB$Ax!d5YQky11)r<YR&R2yH&DV
zmLdT*PG1E}E+~%L6QoA$7r3#@+IW)#C18R71E#yS@OiSxP?kr#*{@B&#kx^(`;~n3
z6C}D7!DjKo-(9xQ${;pn>Dzny_k~bBUognsWNCSa3gh?3`VIgUs$qWfmC!gR^{!E@
zbsIV`yXabsxt})M=)85}iQ|zSv4>v%*>kBZh<jbmqc-uFUv96eE?BIb*4T32%z8KX
zI4)6l35LijaWM){eXt{WVg{RDut(vwZ_(CT%L7FRp)?Uo8X47Rhb7>g&mInV0z>}X
zdu?3?d2TvE6t$-LFnbp6xfGT_xjD8B2=tJqc-2VUBpc4JBc`cqJ==D<SnZVIaPwZW
zgN$#}I2e<)B>U{mqQ}gVRe4n#-Z-pV5AwKaiu$yu__fP1s}^#-oO2cgyP~phG%_nz
ziq^o=ev{HMN};8uLBSHzR0nhhr)8)RWardG-srT{9xw0q$RJH9wxJBd{+oMu3D|8%
zk1|35nG_y0rYv5wxTfkXKb5#nxRh3A|F==-S;qe=-J&7hk!@eiifmL~wkE`JAWVeM
z0!}HN222f_8%*>lh)<cqx~_}85!lqa6~?TC9V!;XpT6aL=}N=*`da^SKyJ@qfXM4_
zbvyw$ZVK1c9pi<DsovBZ?rjN1&33m2(h?_$M>!YcT1eh@YO_zXMkE{@x{nrm3Krlx
z3<OT*!lQA#oN}6aEU3R0=XE=rdD0H|(``ln+r{AOUl!+60qb{7nlXK^|L4qD&pK@+
z^Y7#^Y&pG~cryn(p#nDIf{Dz0ZzH<{s5$bet+VnAy57VeRH7}fmnXMF^>KV)Bfc{k
zoS?8^;<U6fx&SUyUJaR@uzu0lIK94L45vW-i(a<dU^G9(H$G%}VClIiqnmLgvB1p_
zk`3Zhfom^ZVd!KGA^<W$huLKK+*x9A&n=B7qCXPI&(?Zw5ljp{GI2*BtEt!D#aFXJ
zHFb-}D%5b;xnezanV!WH$ZPW^@pDfvk))B${Z$X!M}89q+1n#fdYvx%n5Bi&82Jz5
z1HOD4G9e9EdCUiPPer=#=Sh^<kZQ~<(+KZ*R}o*>gF0t-_u3>M>{|a(4>M(=zb2D{
z){5&|L@SVbL*95)+T)n78Ww?C%Y=}mBd^uJ-va<0%n>zFSf?lEts}-9gTT&~f-Vyw
z)UgW(7dqzz4+d(TOp5QW5(`N`!6nC{p;WpbB4LoK_d#?2XZFT76te3}DepyY6{I4f
zf|ug)g<JDRNPP}0%)c8tPfK3E<PV+M`ZEo@Eh+D95Uw{q`Yh%-vC$;9Y)8li%;QZm
z!C%j#Pi!pS4m}W3JHW}Oe!&{(;;UtV#2{uuD>~ez@hxdhWbEb$Y+ftQx4A1<HY065
z46}?Jxr0~#LNpOoxznI`V+k#M{a^0)Oo4IAw~yWSUIbs6X!k~HMQDKK%ta~bA<?7B
zt-&ZzvNVO?Zzy1Is0CM+lFaL<9RktIi?&|w?IjNks}`_?bRR)4+iX6+x(xl1jBn_r
z+?E^fcisU4?Kd6$OElAeR-ru#8|BKSyo808-7d!-iEyW;QZ?maKtr*d#l8{{(X!KM
zi+V4K?s#%V*p#xF68C)5#hV6zqwTpD+klw^*LTji`9$C%lzRo9+bR5)=h~auQN;__
zAyM8?Gry)=RzUQIY#p`DsR(vVlVOJ8vA(Y)KYn~aW>he$()SdhNCLymF%6*0)x{G=
zcKX+qE2W*eimr3$W5i$NN+})#;KipteRa{FvzO3*qNm;g03<Ig|8NOH*<bMf19lFg
z$4d6dYiKxGUPTU1G803hAps00N-|SjBY4K3Lb|S7jCNP2Z4G?<x@MY^^`rF*Zi7VY
zapGPDk72o%uaKA9<n^$hp)uvfffGpxN26y><#Bs^YR>TdrL1rIrkV2%yLkaA*EuM!
zUpOi7-zK9Q>sJ^2E=h;eZp}0jRTVyD`gK>YwN*<wwuotly%+|y*Va&2^eF-y2kU7n
z6XzF3`J9@UU}{QUeKI3Dei-#i3?BPkVF#HzR1IuGHZ$C=<b;`mIFH;Ku>$>997OxX
z`YpR!3=>enR0A|I-t6MGKm?G$jN&2_<**x)hlC+HiVW=A_^Xa_+lKWzgFN>-s{*3H
z7rEV#7{Iybt=UHnO~w{0Hxd`Fa;v>}uYLn0<KfdykM1KnFN@_{I3=B@&%^}0{$qlq
zZ+;lmx?@p+eg8;a=$Q26z=e0;nxsRL$NN2Vv|fuJMIav!hPT0mz;E}&>9RvT{^G-a
ztuNIIzFXIDppy~NSm|DX%a)v*#=)PTg{eABNRFTh{!>dog$@^s1};x5SVy#LrPBDR
zFTl-9^-Z7lFrAG^#){UfhuA{kAB)UG5I9#7Umf0ErCnCRw1ARdsNkBj&{s^t9}_2>
zmG{1xK2zema6R4BIZPb-C~fCd>*mQF^xJr2L<FOQ?Io~wS%x^2@jpktKjZzc&H6-)
z>000V#n|oZ7}G>xwOsyn|8b~?iT1BZ=4T&BvR%OB?q8DxX&qLu_cnZfiXlP!KGIH0
zVoq)oZ^F^dwoOf#<IVBzgJ32$+pUf7FpD@>G;YgI!r56p@AM5QFWkXw+4fYrnQ6mW
znfnfBnum+6xlOoj+a9KLF3L*1pnC3@n%Kc2Ut(u=vID2!z7}q$j6NJyd3B6$3-p6i
zUGn<A1Buew885g0ujvG%#^0-$U2|m72>%-?dVkAxGP+JKqId{5h7i#-v3wPOLU6ah
zZY%tX*%i(ZCam0%g(3RoO3PMP1GFE4i@GQ|YGSHl)CY--UL9o;eY2|1+(R!t!tmT5
z9T&B}orV-`n@@Tkee+1p)!;(6b~MK!X`6NCyFA)kuRx~z-kK+$)jfado{0F}q%wN8
zs=<;6e@J{U=@*B<xfPVUq~RsbS_|#{xjo%UPq`cg8la~%=!IjlHMhmxc{)zJMXN_(
zn68X*LL!o?ul`%Z^`#B&HP7RMz_E$|mojz?Am>MQVQP<Svz6HbxU`D3?WwA||L17S
zJllNu>H8-ym)b=V$$N&?Jj$Pd`|)t=w$|2(46*-|(Gj8T?j#1AM)wg^xvG`)34w2d
zLeK0*o5L<fAr=#jDH!rqp;aECZj&@cfq{Gg001YEME?YuchCR;0005P8VhvAzuY;&
zHiU?GvK5fG?<a#*%rrEMcAt)eYgBCmGvz&0ZX@kFz%J_vh9VYt&UATo3l4c}3?X?0
z^|ByQV40@7bGc=zyu)sDK3whr<%}wS9^O~|;CKDCtXf+R1!s6c!olRK^1Gkth^;+y
zN4K5Us4!qq2G?%1L~W(GMWCucIzakpD!`p5^o!~Lr<?l9EQ`S=wy)0Zm{Kdt&?xT9
zz}Y1TENs&Nyp&()j+X{+CKvE{Ye+)V&y7)bwNhI!`tBLe0p0qU+eh3fD?Cctxprgb
zB_^%+a&eQ_-GqUp@*x<6QUGu^W#zD$;urmp?W*NcscY@;|F2m@-hW8xA!5!4=~$a^
zk0_zbwAZt(91g&O<x_|$@Dl`F8+))FKsC1sKjbxAkzES{TQ?ZeR@))X^q^8;G!>Q+
zK5qL?ZJT`elaoB0d1E$2&+6ehB$3bHg`Z+<_l4h(Ix2=<dIuZM=Vet6;0r*sIdI%1
zg}(T}L71BwFHgt%Q**mO>4Y(z5MnyWpXtHimIjzmggq=Hyf$g+Fw+h0b8Bwl4T_sk
z&<V#Ig98v+OiXo@Q9u{^pz#fK?U%bkHDav#{j&Me(-iL0JcBA%hfev_EnC`R-A>*O
zah5&dTIlLngWDEEg&&X;K9r#t#yq?LWSKIb^&H!2x=1CG7k*Zd6PyCAvBr`&#tR~T
z?E`=a+n`tV4h;L{v(`OzOXJbptIriytFt=(_7P~6Ht`W&6VFcN<^vk4lQ)G;9*sT}
zXS&<meBdi&Kl%6%zOO@2%)A^aPmVvPP73?l0kAoV;Y+6{=1&7$7-r)WI;zp$`P?yK
zqjUSJ^j)Tr??jC1kcvB1qL5^1^+8I-d+t_=Xo&5yn{*D*=y}#PL7HQ@3bKA`1d`!7
z#uI;wxMB*Bcps^_L<iOaZ*7{2nkEU$<n3;e>nMW8J0BTY@uN5$lB=D-8wQ4qZv3bV
zH-`mBb`oaiKWka9A`LiNrbj*ru7|MUu8SUKVM~MWyw11WtgT#EkzX;!u9W&ofc_fM
z*#BSmwr||h80h?VqG#7@nxZ_|%&rfVUNg-RSs)c3ModIH-(SkJq%uuUa3zIFw?F@&
z1T8@8(iJ*GeCruH0E3D>M7H{gs^UG)lr(JW*=X7jvX{o&z)6I~S`ej6Iu&GpYFSUR
z3rBHh_}$_tYvqO-f>ib#C+3}!$3u<;l)pjn6DC1#f&u4I4f)2#@R(5PE$70?KquI0
zuoi>JDh`v{i`3F*#!c%zhUT9!%G6uf0>&$1Q@uoMVcl#TjGs{)`CrV|6cHe49yS`t
zGZ#6)F;UD6e9QeKi^-A1aGV$;$pCXR#dMJWw3bDEvFyqzHI!Qir_HMs_uQpO<AD~P
z$jeSAF>jud7MG|Bbd$OE;qIO>H<oQcrdLNZf8%Rhqccb74jjqWB8{%ghCY3et8v?%
zc-in3=nF^gn%c#{S|IzW2tA(Dk(p`cP)EY7#E1qVM|U5Jx6LxM2hW}dGae}iXimD9
zvHUjB<O0n79(sYN2&v~v!{we?k^m2#ML&02exfeTM0a8s@5FsuP~)!?Tn`0C6)M@B
zNmw97ii8dut%kmEg@_GCT!?pCgxxQ*xx>A9MVV%hJIl8GNlFOZ7~7fn_&@TJ9HVV!
zj0c@S%V0HZwF@L94ZkE(M&RSlMCnZEz<D6M?@-(F&6SqwPeYj9VLJ1YXSVov8ii^&
zx(qF+<GEejaZqraD8YxN&H0$1F%KifZ7t#2EfI+<ckd6ssLhM%baA^bo;!*@WLCth
z%9Zwkt?sYKg(9M1Vvb~qc@%;Zibn&J{tF*6PY3rF{Vs`-M(!5aM>p#KCC*eCzeb|;
zuja?=d@i3SKPYMo8t*!+L}w5^t@bA8@gIsenm+HRp8F=rFXN~58US!9(crW`sP}V8
zn$~C$LKxx1z@aRqqK61G-#R!WfB6#?>|sJ{Al^Q&Y(E5|D?IW>=R5%VOD{->gL8O_
zLgZ>^y6m&=KyC)OjF0^%S70sviYdihTs4_Y&Lm?o8r;EDx7P?~S|DA!rY}!b;;8Yg
zB=_NRg(d!w*Qd+GG^Y!Z{A=sBXu&8nq45wRTmo^SO&|j{z1vEgbRD{>!kZ?a0qaNY
z*ix}pzDb6V`aOz4=qj+p>%1<gxAYB;uc1+&syhFrhp*36U$+5Gt7Ron&wQFOTjD6k
z#U?t`G*}3FgFB%lIt@yT-FG=(alg*$VV<s@e|%_mLvMn+B*E_i=i*)D2D@h}xPUiI
zxc8!Fn~lzCu|8p<b>_ohZ~^-vue@XaPAt$eXC@UL0kx#3*0Kyir1$9St`eXRldYla
z5eIL(TIv@stGWCiUV^#EO}n}!-sEEN%*f{gNg0^UAN+wj?e8doG$4LsVLKt0oUS#_
z)f!(&!+W6nEp<j;H7q)_7E*9;v@nrN@9*=Ux#TorYRoFeC1lb+kwJl#{&O=_12PxE
zQ89Hs6!^B$%~N^#HVV{fYor6?lFH!Mm276GHNutpz=Ect`DaT~-Mg8?G1t+&-Tf|~
z;k``HzWr)C?O}09ig`UU&v0txs#S<Vx95lfI}coMHmd!`XpXB~5PyP-f$CsKwgKLh
zDmxi8vj`9;Cm+G_#SSV?6n3C+x}@g&VoD=Sebwx!)8cjYCnA4~bpPfyod*T0{UAol
z<xma0p}XZDl4XYQeLC;)m1T=NJ2m=u*`ePx72yQGpn9fW)0H(|nAe_$^gd8{1zcd|
z)F`h*_8{cTfseS!J{l}pTEqK~t0%#RTWZpyEY-tIu9$fE7yB^Mf}D8F{5)^TA?gUl
zAWhx6v^v+d;LA$LB#uP8d(QJ+w|Tg3Uvr1PS$3R=QbU2M?LJvZEEhl}Am&MKa_GRv
zD|;SHB&iB1!XG_fjIkoQ^u^9~-Fx*fpCNJhh>3esA~MZ%A;9QmCW=06sq3TUjK=K9
zH)t2TA;3{V*kwQ7&iklZkLE7>rQ=mu%gc_0c~64zvlDfqNcebb3y*BtKUcj+SUXf%
zbo`ilK_@JW1a_qeSmkE4^lmT%FNqUxyOHBT>CFD}PvR7$r3tZ(H`A9yGy!_ZYg7Zx
z+n$j}L=g#*wj!a<F^TBsMXV>oDCu^dL#pe5WFSmJ46@X!@Kn;rNR@=4mU76d;O0AE
z=d!l{UOk2Qm;z@wQLP4tp`Wzm%E;~Jy$%3E#UwuB3^+-({G^J?O6~#wIo*}7?G+1A
zawq$JWa_h)7s_+)GI8#kBkD2N>H)k}Np{p9h+L2k?zv(s)H!TXUWZaTJBS|T`CX)k
zfJ{JqNo#?G)x?K8aNG80s0#3K-YoOn(x#%&T0!)fx9&vOCR-)QlF4JGZ3HnDNZsKE
zypiZfpAMsxHV7a&K}(SITzQkePAQ8x6k(>Hw9n{lj|e8Q68f{}zsZ@fpA=Z;1de1!
z^pf%356=7_&encBu}~}c<V|nL%AP=Cm)bMHDpJVYPNldjYb5{uLU_Ae2DY5#vO`PP
zbFc>|AFhQbbGyy!khwlGQV&eqMhI<7-B&DdSa=;9%rGGaW7uAd_y^r}BD%)bq^FU<
za9l__I$1oR;1pFUJS`Qm`YBCF0ugiAF~G>QolN!{^#j-AUM$8?s)YqA0fn(tC1x&D
zE(b-CIiT)qRb+l`IN@*u0;s5#4WD}iOd>CSr%G`ClZ6h0;K$7MEI8+-!3|aNi84Mi
zgYfjUG02<nvR)?6JCUT|RJXMuUQP~g?tvRbZ=afx!Xr|^^d;U&IbsSUY)k*oRLoDC
zAw=DPQh`QV2MG+pI_;QfHyn@CUCkHtFN&iwh6F97yl&pmL#6Bv8^}szy1B^KjC^B<
z|9VPU{@h93ajhZWup1WX4zRNS)Yk(&iYE+L_aIMqWA`bfD-H?j!pi<Hb44sFjlqjX
zIFmA2awmJY%CEV(-hqc?Xf<P{x4@NNrm}QkO#0bCEhFP`s|(hgpj?&yn`-~<Bvk-9
z+0f#yqtbFV^O@*)LDjD_*^f}uIQE{Cf(n@;pFFR0?OJ|?A^R6fnRwZT6Bd~O`@}4z
zMld{PV!Ggv9R$XU+$5Dw1rY0jp<hBT@Mx}a1a{z0dsL`Uf2&yt8|>B<(8i56EF{E^
zOpbdGPt3-sLE)P_D7j+1@AB3+d7pK{)V8;f)-YIWfnhgt_XS~K_OBrSjX(Zc`m*Ik
z2bID$Kei8EEX3$?2?#iw9g70LER~pkWeP0O)cD>OMkUy(r$T~saQt{0zg5fQNp4p9
zQ?p}>jOam#x>2avzmjTmPvF-4jL=)Am^(|`nF8c;Y>z@i8X!snL}1%ukign#Pm6Of
zeNfD@OMjRl?*s*zFk*=!Md}^v(nz8eXlmPkI?Z$MJ#4{zZr-MTCJ>gTW0q>K5okhu
zGCaJ_YHPneH<<Tdt3SHwk~VhPZ*=F`D}7t{cj<=J+E}K$C94`=`~kZUmsBB^-{&e=
zWWnOyMs3c^y7kly@xbIsD1l{3G9q#)UhsceS5lgWwxrNsU#{j+%Mr+BWE)?UQhkcr
ztXJV66r#mU^iymSwW2<0L+j<sTIGQ7Y`NE|jmAk6?yux0_=ZMzF&~C>4z85P5I|HK
zNYPb3MntucZLv`F0K4t*^h3&@N?m8R5V!xF?1H(CB8}rwOBF#he<7thjlFQF?9wDG
z>#`APNx)jP#p<1AovMFgUm7{0GI|L_S_*}WnpeyHNR%UJXqKm`1Fwd^#|a5qN7WFy
zE7AVz2=byN^9uK34q@TovrLk6g?6QC76^rD!Ji}4!gtd&_N_WRUFXOg4XnhZUbZw-
znK8RMU4YAf^w%2K$6$65mC#sl>~ftD^}eB8I9DK8!>y;m2wA?W|As^F(lDmEQ3T9r
zLK0xZ5ef#)3FJz{EHGWK2$50vc;MNwihfmSs6nHJn<B~ZE8>wZP5=S#01cm*qgvJy
zF+m+90RR945&!@I0r7e9C<7u8i<Tfj#ZhA3u}^p)#pkj|9U?;#^!k@hdC)#X(d$ZQ
zjs;-gd@G`j0<~BhdZ?gP{kh1WREo_#AE^>xV=h#WX=aN*e|sTvDKx^leaT$oESj;~
z#f%7jv${LOYL}m#N;5-dEr!KcKhI`!JB)Ra#Emn?(f?6rga-FN{OM^D8bco#4$)yQ
zDgkeip%Z!c)*f<FwDYttK~ome$NqfdO&7T+ndQ=H);`+7ZbqcKu%+}%Yi=%MSn=ao
z%M<39d5l(l{Gt(Rx0X*zJe;|+!72>t&AN&jQ@b0h8es@GzXe+2qrMy#*PcH2K=J)8
zZR&e={i+vkIpF=vY`XAbS`$+F**sBWE)*)M@o8j9GR;R<I>@wc@07#DUTeF1mZ{S^
zyKXqYXkQK%yOx>OVFBNlfM%9&d%e>)Z4tsUM~t9e+{8NdT2)qwSG!lu>mQ&2xDC6E
zP}K+JXRm(mMjfj_JEW1$1_UzP;%kaZq3cO;v%H}_pm_p<l)4DZhih2EyLDOH?#kU7
zo6X)Qd&1?<T`mHCaO@6o>2v2=XV5aJC{P?<Zn2=fIK;_$+@@-My+}d0^BS%k_lQ^@
z%7BV*BOc=p-e$&iHuHPs_WUQ2lAoAz3pw5IsHO6>oj<o&I+gsMsakbDdW?LfT@g7N
z87bbN!V7VzK)89=YDEL^$#EF+JgBdkNDla(m-ML#F`F3BN&50VIM|;HnL=A5T$YS8
z!@1SZ-hLKwOhE#7@YB8bcTPP8tXA1n?JrBnmY5UkMMZ3awx`#7YLwd<^Z#OW*!LKb
zt1h516v!Ha%5E-NC;-we?`Iy(P3@mE<50BHy}lH7d(!aJU%fpQ?jAs!V!~{srMI2s
z@MHXk`^p|Wc$N3YE9~IIf&zw@Am~jt+V7Nlce(O-i79)teSZpw&UtATb_+mwIJQj!
z%W$C*=L12&;5im|46AJXqc|Cj#;<HkGlWs$P?m_Y{_^VYC~=?Tacs(G{-1U`B9hlm
z{RWFYp=81`p5vE{r`xOQ$R?zsezN;xc%e^M_}KuF-)%4&y&lAS37yGedk&eGr>mJM
zhI%46rxoaM88Sa-qY`O-?v9Wld95d7osuJ9I0iPt!44}NZ}9O4UCi?<X%KNqwrfWU
zY7ersBLM@<5&d*vH=uxXif`*kq1dceQ??hLJ~^59KiH$33g<7fj`$c$h$Oj>%_cHJ
z%N|r|1!Q-bd<ybN^^}c||7u4ep{sEWXW1u9_Fgd>;o|3_Ml2(H&*ieMImL888Cl3K
zR{Ox=>~Z}bQ+b~T9YKzX0<sZ^-PX4)7jQzD2U@YEO=(rOl7lcYml6L@>rM<s#-=|!
zW@w_*mjk1r|F==^^mKHcWAnr+l_2~a;U3V}@m+=1)WB-Deoy<dD@bw@QtcxQ&M|SV
zYuB7gHNqhBW`sEmbot5aI?1a~z%tC%0@g0{ghRW$uJv;ItA}RN;<kv$X=*QH-f##%
zM%Hh0lr3cSfOZ`krXf$@`YA=Uerp+&ahq%E*qvOHl)?Fe8UZH~gYL-8N(ykBt#b?I
zWbTt_ipvFiS%U|Pb{_^6@XWi>9V<FO9yb@oA*@W<%8WH|+eFBNGowqzLh^{`ENeCE
zzf`GDwQ8H58ku}9o#)-p*H*M8q^FrA?x#s@60KG5m+L>N-&P*Tn~nX6P<aVmbf6=q
z^oSBqA7*Ifb=Yd#^7nDA8S0wcUv(?c01(}Fggj!itoUoP^h|PQhj0M(guO9KzaLYD
z#UAGTQCa3Q&$75p&b$Y)CDxbp=OA8k#GM28_*_OYa`j?!z1bJ}aFde^sK{I|1KVoH
z4l&aTKxax?l~s7F2UavDVNH_u$D*oXWK?Ey+@Ykbc<y?`15ao=NP<*5c-(dcz?K%1
zE6^5VskH8etZBr~ofz|%Syew^%5O3AcrBp61YfLL+R(t%TQx5_=3Gt+bvD)B&MwP?
z_|Aiu@n&@@j2D}4f^dq#s@Vr+2sKY@xksHBUn{+9&3atPdd-w7u#;(u`CTYT(a<~$
zo<qjsj*GD#4)|jK0IiOZz%S>-;cnBf)lx1M6|`D$Tiqd19)u!OauIngdptz>?XeXF
zJ|&($ZksH`1vk-hePZ?^e$9MSzbysm*<^KQpcD$GiTUL1yENb{pZxF@fsZ$&vZL+~
zM}hWEA_y6Q;~{)!`LhMf_&L`$Hu@23v<-*CH?=fc63H@DGKzl|pfkR`gKx>&lN3p8
zNnr<TsJH(qsnTU?jKW_GvioToT>%O<m?ZmTl_WK40175bJ5264&T5l5(O<eWELV@F
ze9m~UGl38o#h~)RLeK*Q-H8v`IbDcKJ#Fmr;?oC!>Km~0<$DVg(!X;4po6Xiyj~N{
z*Sb8(!NK72XMi8ds_nSturt?6k16?hlDBO@B>d$Dv$HEHA<IIVxaElLk0IUc@vEZ>
zVO2#fx7{|;7Pww^b0^~m>$vgwonDvKL_8fpnP{qxI2~;Ff=iPyk?Sg#Ky?E?`kuAB
zal;C&NLhgz+V<?{Zf^l+*-I|^OAAfS{HO{Px?TKJCa<s;=LG)t9wH~w>oPi10O-J?
zw+fSJt+g3U$tPdOu&r`R>6>5UWU3Y@L9#kq8}OSORHwdY3ud|GVaJBdJ60a9TSRE{
zgf(;?R9(p7G*CuXl>j7t7P2}8L1>@J*s+v=tPKYrqASb90`uQE_srC9!2v^BnmlaA
z{(^VddfnU>&zkj~Wrm>K7bo^DRfwKWNm?x9yCeqB8?{sJfP(y{XN$z@7WR{SFxP0-
zZB}_EbyVrGi($4X?W+qJlaTNchL8uX&U_jjI0)@POFPVfw4f?<99ca}>fm1T&3|$2
zB5wFOcHa;6!Y~eKdOtk0K%$fbXOy1)pPrXS_M;t|-*ZUa6u-%)*-7#SaCnj2zhL2=
zYrSqqTb*6Cz42TAgJzD0?Nq;wtA%q+F+jz#7X8Qr6$EA67ET(N3n=#h*QAU2WOYK@
z^Rev$1=-0Q^B+@D6*ts?zDcKp?Q*WpdZaLw$h@DZEfl4dAO5y2XM`_2ZQKg<{&@oJ
zYdj<-_hBqs<3Kn&B_cx@xbHA${zjL3@0+0#Zzpr8QW2S=txBBl>=DrVvEC1%Ou9!N
zD{4Tpt$qrn3|}R_a08_$`yF{A?LKhrmWmzXLSW2@Nd(HvYYd^p>)*!|#~iN_KC24D
zQ#m|?O|puZ=DsjNRP++Dg0)4)dy$TWVjtSrv!$&~8EhaytDYngI3@)mud3ft3i}X4
z<Pv4KyFdme&@L&rh57Y7>(?dv26p!mwuKT|HI-WKd}pc^H*0&{UrOu3-Q~!&W^pp&
z!zv4$Z=#_hGMvoLy5NZPh!BBbRfnK%2Z~d^Mf@88C2}gkW7A!ET2O+A$jvS)RSIb8
zX|}!<+f(U5fTGw0P=ygyc6ozK@7<!&eDeY$c^MSdhKF7$BHa6U&-iympvHhfaIVIT
zw;~LTA2HPL&A~f{_7nNFHMoGCBCD}0>oLh0czao)d{)Ob!Q{BA*6vm0jvoCvrGT)@
zGgn|9KTyaTMyzeo4H7%@FfHw~E6Y}oY2a^5ZEFUD0{^Xb5TVIzUUXM4jzy3;&vR3~
zLk+`1+WRO>XJ^eJIpkNSmyVqTlL3R^{KhQcfCFMnCUD|Pn2io?EC<I||4*y8Km4WV
zQc&YM4Bb+ZukQ|05W&;VIZ22AylRK^;ee`CK=C_ahu*?(v_w{wJ9FLy8+{7TWNw_p
z#DVi&Jv<aDtYU}{t7#GRiWz9Z_}}HDmTxj~UO06Hp`z4b%7OiKcd`Hm{0^5KxlkWz
z`+Ux~x_!Xhdc@Jg2l=x?u`EC%6$=Y&#clqH1&VUgQ6$=s(2^@DKO-6;fGNvhPlaF@
zjV(rW*2}xGQtyjYsOho=O2h?hzDDuY`qWp$4sP)4Cus_BsOvBS>(R0R7DO^dLMz2K
z)LyEr0iBxcWnKs0HsfYAhLx@94N-PpI?Z*Uiy8UBpz-TVJmNkA7A=5NBX>Ib?_DuR
zhL8*~)F)!;kOt-kd5U1e^LhC>jt|9Dt`kxtX87@1Q$(wTiWbKGYK4}Hts5ffcj(A7
zo+n^@J)aTEFzPWUTulLD9)9zJwE|~2KZni|@q)qPUcLCFY1IQO;*eq}a%NJ<Jnwms
zaAt8L*R%X__q}f1sxvSdKL6yc3~kCXYMKWi&gK6%8}mA{r%0ZkCOONAu|z}YtirL4
zEtVX0XFIoMB<yYvuPybHSr=i5(jB(<8KS%d21;Gc{-*IN%Z45P-ZT?aM~^=W+F1%$
zsEtrpa=IrnJNt6kMn-W|J_O_F^$%RczwVgpZ;JkaVC@|jinwe?G{;&V*=~gX;_(cc
z^|%i8uMW#UOpA3$QOAaBE*!gx^FTYO_%-Cq-evw6$?L8-Zzdz#!f)evUOlBxNvunv
zkdT(_SR5Gr(Pw~IqVS8`^wmB^|0d)L#Q)g?J+M#*2a}_Xe1bnL)qHWdTXIV<ORIWr
zGfG=OX>6*Y?Xj%3ZP^)Bd(y*h)(HTz|C`FJ#_i2^FX8W3VJ{>;*JhDBwO9jrQ1IzR
zM^q8Vj{;XjA1-=DrrjC%X2!h)lqP*CM;xr99?xj-TDVDLwrJRD|8pXIuen;rWf;ts
zoX!Y@NM~D7;)Y*N2hrx3ObVusMR!xa{=oe_b#WcTejl!od-x4d^Cqz86!L1&wg#(1
z7N$d9aznlBPXE7uA}FpDeU|$)PfXK4@r^4iY|Hlo@Hx9Z-!fGxum_pvjVD0jb=KX7
zFk<`5OsroXE<QN?UsAKL!ATBjpLzH5TEK47fK2umck?}XCr-NnT`i&bicTy1_`h+v
zb1?hQv?iJNTI5!~8a^3JX(lgfcU5-lLf{}Si$B>lw2C`TQSW}K`n8iFYbu@hrt@M2
zee3%-a}A0Ro@{ON2i`|Feo0tbnFV#qjf16D2N&A|YHa<+y(A#o7VpbJYhkh1LjfyU
z`sQ_`n)+H%$VQ51eMt`ZSMg!VDOyh%GV|Q(j+kCzZw4><JD*_&UaLIwloaX%5~b|P
zN;3-LLR0_%00000eHDNgvm|Kx3<;bfNjZ6Piaj?f4-BPtj*orYdWtS$di2m!JLh)Z
zhiIH@Xp9BQAaQFcGZdW{I{rKfS#jhm-YY4o#0Gt>32{yXz1Zi~M%CuVfZ4cK0qFGH
z#LrRPZCjeBDyHvqgss1_OoSfl9ntwWq%{6q?iZbWOd`D}?rV<XQ&X#WDLs4U!$$QF
zCksd=i_yBa<WXvCBCBErR(Q(Kj?~~`;*X)YX|`L~8UT$n`rju}>z0-5zo1YYbrd@B
ze@{xro(^&?%zTn`_%~5Be+3(u>ZOqrQ@|ts4r}Ju#<@rexBW<f0le{#vRHTA5=cu?
zAq0B5J*gOx>Q#&dc|DJ#UyelXvo)~Kju%a}d^Kvug)tk-gpWINhh($J-O(IZx?w`M
zVCAJQ>xoYNCLuJw^_`zmAo-Z;MBH3X(l-eBEd%xcUnjQqRH6>%v7K5979vz#J(hIV
zut$X(7-#+$Rc&-(R~9@GCHMpy`WR;i=2_D!#s1ePMvslW*3-6{l4qKkS`9%d23iM@
zweG0S>im|PR`^a6Do_ndKfXK$Mb#CUai4|)gCTE+$t@2$JX%NY36kT!^QO#mn<<Wj
z5T=9O<MEq`E$wdufctOPlw<tHtp^^q)gYT+t}1Yu<*|d>-KF4YNpYoE{kXFke55A0
zx@W9F-%Zj>=lP^p75C3^gjbd7&Vrc0Bjxc}tTj~_1+aJ9cLr%p8v2jmh`^van1!PW
zpHGLmf-{JtvjBWjoJ;5!=6oC5Z&YEPO!A7*uvxR-d<?Jc()9@_EVA%y2qM3d+2?CS
zbqna7z9v8qXRY&8R&3!JyEyrZR%{h(Bfz6x7d}i*x2xpJjP%c7zFw}Im%~&n)ttG#
zm=*CeT2Tb4T{BJi@(t_nfHYo^GDLBHdhG^eZ}zk~)p5?T-YKUxGx{QlI8({r*c)#=
zMD7puO|g<=sOH4_zMsMTYVavp0dQ(KaZk#xBDRFWsfHV^$jLrvsoYQ?(o2+fTjhoW
ziwn0$wbm^g{5BRoCC={2J|s!!RcfbLqfta5l6Tn=9|5`x#EL{)E7e;rVamW=xLo5l
z#5DgPZzOdWp>f`^FITQ<@ClL5nR+vcW3EiP?+CUZFn~{p`TC5rw(1l3G*p1cQNlMK
zY%z5rKn8ks=^?<s#_<kfE_@AJksTr7Z1r3|?_)FE(W(<<U-G<&GM}EC2HMkHhT5GX
z?rI`0P6ge1vMlN%r>p|m)wpG_uMk@uQL$v83#$uVON@2&&`g^EU5PWx$mBM=rL+Fs
z!$6#2t!Fhv7ou-&IKE~l9~IHdx#`1!)t_hY8=Cb#`6phgbnm5yt&jnMH)>|YvB?k_
z2#UwoD1heFK*J&Zmpr9c6mabjJsjA^7ILHfRaI_*RKuXJyk#bWXg-?gbY<NBnzPYP
z7L#-*RHDePiwT>x9xi~M<n1S2a28zsz1zD>{Ne%C|9jD=2zo6kLE0K^&4=mL*F#ni
zVoG&TZLzAl6OV=l^@4BEb8937Z%2r<m1Z}WF;~Sr@!<OeEU9yPavKN|q>^ie@-9M)
z4z_J{sLAR;kQt(ef@0&p2j_#K#rNA-!{#^q5~hva#wV_qPXXWF%_vROAn{02QpJU4
zJxE}ZumO0Y`2^W)BPSvXC75%3wqevy-kP)_!d-L?M7|^YG6RES1$wB2&%vHUJ!$Qq
zP<J@a$*CZ+D0PHW4Lxlw(9n>i-O&M@Ld2a-c(P~HaxP0Fs~hhLh`rw9ToDHzr+b7V
zR*n>CsxUDn!$gA8Q%zwS8+$m`M=y+!2FaTXb|;x-SvB5=GT%kg(Xp%2AYF_{t|WOR
zbQ1^vz#6g(+4S?owk@sIo*S_?U=vPYHEfZ*Ku?1<@O9D<%d+GR&}A+;$oZQU9&FMQ
zI;%qvWF6G+xMweB_tKcoMHwqPaJC)c33yruXRYx)f38QX&tDQJTVnv5HoVh+NL38k
zAk%qe-eS(w9W^4Z3~F1=m`iQdlVT@_DWa7p?=97QM~DKIVdp|r*>*D!7(~<$rsFKC
zF<1~cl(S}mG{o9VWv6H9+v<6Kkn>`V4%wT*tmBcT(Ny&$Qo!|pt=1)!zUiC#CSF{+
z_O=gysonn1wvIKn;kIudLgKmSiBPkCpE;NwvWn%6fB%Vl&|h=`Fcus)oR}_*MEZ!`
zul8Bq;2W+Q9w^hCNT8H6oker_`C~~NK208Bbr{3Xj}`yZc_@c3hxe^QV!!WG^Qf+d
z6>?IRrLVB?IUL?7aFe_<5}uio4X7SEM*Etc{!wo)+@uUJCiUy$n9hso+M*)ewey<;
z-`noX_7l$+(+!B@jv_woesa-gTvX=+cRA09#GGfoSZ*ie)u<0V9|wKe6hc;Z$5z7!
z>*n4d%Hy{%D(?i_$IpW*GvsJwS$Dq`mjR|qI{p2D|61jZ`LoV6rAlCDxK&m6X9$<7
zqMgO7Vdg`7Vd>JXM$ntsCYEGmq`xMIBX!bJeI;q<`E+bWfTF3_sp)F;9T(Os)wf-;
zm=jvc51y@Z_nlZL2Ry`5>Yr+$Gy`FNj#^sUiaPbG_DXu((ek8IU&>VLuHEVSUdV}j
z0)C*BI!)lI0oEk0UaYwnG36$8bY(JYkYE^-zZEPBE)qi_5NZk=4uO3`u=GgE1_9HL
zlhbRkj)xqw+#!f}!bQ0*ClfmMOiXz0sct&DZwl|+ErCO*Z|8Yjc9zr!Xd`gg6Mn@&
zCv*$i603;5-N9x%?n(uEnBL8=ehlYK<b<QVjblz$cA$TDmY*?}avd?2QxZLI?;H)0
z8rNoT9=b>ajEH`e!nq!F3ul$hm3cvbW=bx+x`NM&mIz$S$i?&XSkcsDi;c~c;J!5h
zG7FU4{DYmsub`#gs<{pu6&%0D(GcFuXaHtFnZM0G!e)*{p4wG^l6^&9KEj4ym7q4<
z?QyNx2Uasv<y{dvK=Y)XD%%d1wzi|n5q$_%x%X~Eh?+G9g7I$x=zd+TAE)7xrh&U4
zN)2%g-2h0J8R|BxNunEDu*ihXfacCWSq>0qA}*Od;CcmYim24fYX$}yoi_L19tDFY
z+Xq*FJNe}JiD}sNy8B(AT~=32hMA%j{SYg->_kILlIu8RBm2zdSX>Yr7htA(k{eTZ
z8ap*z?H&N5!pnKoMaiO2+au`8TdG6|j($GYRX!|OF&a+w_JQaXyi@p}?}RI|d27sc
zAe{v)*0<xiNELxd5o+jGnWIpreGX+!R1oGny|CpjFFp?<wk*6x1S(2g^t@KIaVV@w
zxcx6sD+fIkk;GI9&W4_wd&7ofdoL}DREGo2WFP3o+rGOy0a*if9-ZW@xQ?UF`@a|1
znGkp{S(2Y(!<hFWMDYo-r}ZFq&a-(!905BZ<nu@Jv)BG+b;9u7GBY^kbD|rxUYsO^
zs{!!h>q8M!1}K)W7efpM1M}WJ`*A&1_xOy^NRp<Nz3-w;QSnYzZ9OS^rv;k)AQ4oM
zL=Q*gIM}BEIc!6f4xG7sA1983?9@is)aXLxeg%>C`+BzD=OelgTi*_kR_c{_N)~q!
zWFjE5haEq4<$Y2AATuQ1Xr(Yzlgk3!*$jaQOXV+Refh6pJpn`Ha~%?KF)M{1ubwz^
zH+@wYOp_$-**z5KEj8E(e3e#3k^BE5K}Y+Jvf94F#N&w)>-sV^_%L(;h~bUyj8Fm{
zUVP=A)@ldcAi!|?q5Hz<%oeu>uTM7^1gF@d=5UwL$A#p5VY7XR_l^C-S_wjzvL&?e
zCF@LTYo+ob7FuZ$7}hAALZJmm?sSW9<uG2wgF`bWo<{b)0?K@kIF--GnRfs(%9z?W
z%pZ*x85CfmJ{iV1drN0HaG)M!z7utX(jywMB$ltTeSldG@g>JOH)-kDEj@#8kfYaS
zkLw!e?l6VGCwAhOQ%DTnwVKx5iKkJoA6}k{>d}j+7oeW0HMK0Ma%`14N`K~deC}#F
zpuoWEj0wpP@$7;sI`KS{IdyW_FI_Y+n7+17>cC&2fUOKnC3)*A?DzS|=T31J(0RKT
z;pGMw!e1A+rE&P|qAsbysSXra!L*)4{GIpW4S!>23s7HXz8P>IP42Y?{bx$0DEf}K
zWRjjRe&+TS8!AFf-^c@A@0@u{t=%Hn!qV@zX`O}=f3Gsd5qu48BPl!4Kl}wsoZzV1
z{<u_GK2b%~bRpZ4HGkjfZ2|cm))18CP$G1hoe5rmuUEO8I(dd%UcOr!ff61Ngf~Y|
ztW5_$wYsD*z<{0jDA*AULIf&Mx&?+z4p}R5`&}ZKVGsJw#h8|(6fRhpQVn$?qwkp*
z=_o^I|6%Lbc98dbfeb(P*tMw<K9vH>3`ZvTP&D%$zv91Pws92}W~+RnkaBl?qn-sx
z(cnT>*HeK-Ec#N?G@GSc^+k~uPc`8(xi&%20ue8AF7NiUrAdj(QBO=gMgXsEthT`9
zm6O|amLDLo7l`P&=!!UZZ6tyU)ekVvgX3k+c*7bmU#5PyLjEM-PBgO+Dri-#a(u{C
zZZ%CezTH$O+cU)UV%%`pdp7^P??c^CW{p9fvZ|^nw<Y;f(Q>uBt%hOil5m}Y&EW2H
zINh_5G^ip(OV6foy8i5b4|N_lQ^j0V47d&N{!EcG&oD96ojL+Uba=V1r!m_Lpfsqa
z_47=rS8gsGR=CKtuXNiI*a<beX<_8E<Ogmc+og(8*$Fg?Gq{7U7F^X`5iLQU*4A+O
zMS7`gz-1vd>q4>3!Vuh2h@pGRtE7x@$l!Gw3R7-<9=<|07x|<@6{pcHo;V<Z$-dl)
z{Sq+3jJ%?%Zi-HH{`XfX&n^l}N7eRETSVVt)hv<{M~#f39cF)#%^Yv@5lmZgC}I^F
zY4RlJffFlfdg_}%5)krZxf-yr0ca^@f4>3+pcjW#TujgOt!BeN5if~R2IS0*tNY?*
zCZuK?dpM5ref1tz&8v8j11o++BTx}YpkO?;|Br?^D@+$&V3xhcPv6QaXg6G8N1KoU
z021{!u&saq%Kian7?we0000000OAD>v?>l)#yzqWS+c)OW8k<54bJ2}!Hbaf%^{5d
zMMda6DbajP8gy8M{!z6}2kxdntLr2mK3I{MZe(wAY-qQm)I-Wb$Gx_lnFvxy-L6Af
zjv#`tzVmm~C$~n;M|u^KS&I#Je9+hgRkbiX`=KUrJMNl@w4%@Ms4ppv@1Yqy#R{Cz
zVFBe^LvNg#<TQ8YHX(#>9g)kumK+mzymAm;>${S$V~vlqpGFY#LZgAf(^Jcvuv|yl
z?7P(jGh)jU#NfeE80r9}?B&nA6$2Pp){`BE2`Fx99nB`j!T>YnZ*M?*1L_Op@6zeR
zU6}*(q-Z>(nrMvD{<l7$LX7{1x)4Q{0OW@&K=f<x&SS}K%jYGK>T9g#eXm-MC;jB=
zLbhYcMt!C4fLo9a0loi%!D<=;XW96Qzo3sA`%6~rYb_{{Ei+lrFiW}uauRU7j$*RJ
z&(41$DytFoZhHZL`w*<Zaa~Th>$;^#6?gwRCuhN309+aaS3$I(q^F0eyo7Yw7$#1Q
z7RFQP2W=Dz>f<eA(N|Z>Ft0|n<OVf6cLG;nec3pFWAOz1_g*{9msBW|@0C4pAPB{c
z3UXiq@33Cf13yHq<r-~_f0|*+_Hu&0unqeN;{!*ta5#d4HQ)p>_rK1FsjT<|S5=F1
zVV|IPe|}+UODoI&Bw2?=sBX+2533)6pkjlVmkVv;RKs87X*|lLbHdDvNQiR!@urnc
z$B}tXYFet#KjJrf{mz<JWk5D<(fQEvjFrZFAOW0Kj!|ImB<jkZgp(Rm<pIxGzuUeT
zns7DNgf3LS!20JmHd<J@bAwdEY%0w=ya=C=kdP}XFxdR@ie_h|ehs5j_+_uO9ROp~
zF59>`&@ggW#$?RbJMr8*;aTz!exa2PwVd_Sr&(_v!?i%g!wZbCBSNDKC-utb92Yjj
z%VGt{g;jBkVfANL(A<-eG62BRP8VpfA<C!_YPiP$=CP)Z==$GYJVN;+0X}^;r@A(y
zU`o0ANH%sm5r}E1N#0gO(#iA7TuONsZ~O|@y0-i(?#j8@*0?iw8vRP+rS7>27ILsj
zHo+gCoOgAWldlE4TJC?`onaxt6Ka6*Aq3r1YKQ-bsL!1ywaz+81hCVR?sWq4sdkfI
z*Lq1VPmQnhG6)YK?Xbe9kAp^UU-6CO$Mg$NSLpi-$#84;wv)+0C_x+tjQ(%O;9@0a
ztl#pWIEFf{3Av%=kgeqA3G-sdSu)18*S)WAboNeWV9`kC!=Nk~F>CUSjVe^Kpr#R0
z@znfDiqMkx2=qIEgP9djxl0-%OX*tdnCr1Du*7CJKaH{$X!OpZMq1Z@5VbENSiJO?
zDliT~*v>>=Jeo}y3xU@<=f5?OzqjR<W$r`y-nL3pp3!?uXAI-nFFXwA_aKGz_j3Gc
zKEjaHi?$y_wArO|-g6Q|>ga-jyx_Uk7F8_*vN-9o8z#5gZmffTXEPa9z|vk$-TF~&
zeY~U?QuK6Pb!W+_wC?Fb*6=;Eb%oS;uK0NV<G*wu5#nv%P68%Db=tS9aiQ%=KFrEU
z5lRqwXudbP{OgC<oZwj-p0yV%$H;40uHywkUBy3B5)@i4x$DsJnmh)a$Q`6Ns|qTn
zdXd?Rw5zJ;=<I_bpnf?rX^deg&2P9}ho)F2AsvB%-REp$E?9R<_@iyLsdHpGfBc{x
z<7o1XQss}wp_xs`{}~QaC#!>$clUmTra*jMd8V-McAFGGL6Zmwd%|Niow*Of=jhDA
z%BzrR?mSrHmsAvTzZ>pj1{a6gUoNtG-y>zw{3#{ahiy4(&IbFHz6m|gMw@SPJ%vLQ
z3S<jX-?Xgt7YqoU5xI|X315f{5@#XfZ8ri*0_PqJq?}Y7WSR;vtAD>Jhm$g$%yW_w
zwt~oarb;cxlYRtDa*crk-NfEltpHZJpXA<n^`FF!5qL!SSda9dXZ>Ns8PRhdNT=)x
z1hXjDc|vB!da{#6FLT}BkMsSA35Y{Y4gQ?@p5r$hVuCO4=tbZvF;3cZ<z&w#_F!DK
z(pHu~g*FvcQ*88henR>t3L|xLT2v6vl69S^FN$ZS4*e@ZhwOJMIEfPWr_%(kazITb
zB2u^ZFT8eI>Oca=4y|AW>Qb|W0cE@wDXp66;9u<7$ukcjKOa{y%v*>HnB)qKolhfv
zOrPWzFU1PpDVMu>YLj;rAB9}J=>7|lhgoVl4+g+!iW%?<=AIl4>9ZDzT7cY5`#Os6
z`8JsJyVTskSSUKIya-O~d48ePTU00H#Jx<kkV}e?rdwUKIri&0bZdvgg^u5%WQn=s
zmlh8<S)#@gA}k3sLeWJ6$FWC?phS99CQdcBm>aZ5;0+y0QqEs!|AyGP$hXNiXyjdK
zXIjEHP>b6%qoGCt?a&*1r^^RI&sSzXK=~hU5Z1f-`)bk7fn#b5``1~kbn70O+UI}D
z=pL<SM@yQ&!Tp^4*%BRwzbmtKN+Kd-G2wZtI;IW_oH>gJpBcUEG9pXQzh|jvm`r51
zAn9%!D)X(?rMx>PHfLMP5r4a}zfLV_jbE6%4hZsmST%a;Mzz|P-~ac8#eN+PeY@sY
zswFX@8p(A~6swP9US+V3JKEYGiL_k;S`~qA;aYWPr%SC;FZ_ocZa81$w56;;jyfM;
zE>zjF%c^_%wXe<ZRGXxV4Isi&i%pB5%G=%-H3a7SMVmw)SIHo>p)LF@`l032YV_Q(
zEwn(BRb@WEGj1w)SP>)z>EDeyu!2dkeUC((T+1VNh!6}%u$z8-f`cnJqy3Iqp|2dx
zTF8xOcNj9Yy1KVRlm1=<oRzM6^31GpKmVl?lBrJYN-WIXjFuaRuM9IUxm$LGXAfq=
zS&~ClP-+T|zXfq^vz;t%#B$)gzwo;lY|T(=IOBwtwPRk(a+m8+wsOC5aA2Q9P~Fm?
zEK9VG5EPJAV8F~2LT7r~7QVitHm`)mH$5?AHneHy+|sm#v&V0T<zjA`ScX4*OmqZE
zVDo?U!dkY<4DkF83S|k|V|Bkhh)D$s9$d%>m~Ml8&emihz4ahyK7U$3(g?m(?&3Ay
zSJ~Y;B>lfqdNIv8-t0{%oCkL-VuJ*gmKx{+Lb<UYj|o6$1F_^XP5gM*yD38{LM#Wc
zE?f?a#9$kIPtBAvu$I31><;Fw;~=JoKIbV%7+(>4djnBYeJDMK?UW4~Syl1kap49?
zu)t$Z7NN6xvIw-M?tiSw3sdwl=5%ri{?m!<!X*q)J_ceH?eV`uc|Ih$%*b9lb&>GX
z=D^>G`9N_2w_NAeXsjOuZW|&0s<>>-*Z3FZM8~wAFN`es^S4?>-w+Z)BL@EGeW++~
zFnS%`2OG}NyxL>4SHi(fV__q^VU@a;hkRId%Rx~4!Q!q3s<X~!^!aYbW#AP#$zkev
zD;PsNlMG082YXI<$wlGx{S=vpn7Y~|uOe~mDo=Wth)&Y{%9U+W&!HZ8>7~3h@dh}U
zw)o?Z|Jnlpm9bcGQ{$-62z>Nw5?oIxu6dcaBbK9P>kWnan8)qTv$|jnL9{TiYvz^{
z0Kn&l99gs7%|YT)Ug?L*y-Eli_nY1uYf|N70H@mjPO`kaPoXqgHs2Wk>CXJbSiiJd
z7h?r(rA4d>ZI7?Z>@rqoCrmDxc(Hemf|NFG;{%01cK=u3g1-3)H;bM)M!mvC#=xxW
z`yuBaYx~_6Z|&2q6o%X0hb8(Gdz)J~&<R38wxCE>ijA{{*=KI{rugu41f9ZC#HSmX
zga#)>G2RJ&l*oN*8X4H+qS-tC=-h?{?|PTH9P6kxoJi-p0Kc$E7e+%udIj<Ft==i-
zDG6iBlQ$vs!n1=AzqaPgGBqs7e^G)otoho5dLXiOV2O`@@<U~jyFVt(AAEyclPzx+
ztp5sar4lzJ>Q%`)C=SOd!E^924I+mCf>Ia*`Lw-d^S!ysn2w^J$pFiNrC6u&&HeQ{
zp5>HtN@Vif#Cc))@SxgqPNv{QV_pEN@hz+zjD?A0qk(n!1?3yQmfFRV|MA54^tRQ|
zTr%xYd%$iVIKdja@1h{M2XhGp|F$--Gz3v|*PA6aumz#>4Kz&{6Fc;Yq{{_M@q~&j
zG0V?=d+H3<VUJ6&1Tw11Fv|Yk1>GKDJ#5~;d1R53VR0+3Y$-=)tO~UmP0zcLmuIT9
zfI9AAFiVwbnLBb&(pY)z<r|3<^LvM@zOiK#){Kr69oL?!JOP_$QuzTbL=)9!yfR8Z
zr3H6<C+}hk;)XE7$aN^jY$MG`tN-bHdm*KEqzv_o>L(sEuD7&4B(U9c-tWq{-<_Xv
zlM?_#%o~;qR;i8mMO!IebSn>ce%MBqXm!6DzhGXkSx&!SCfb#rx1FrW0W+V`kObDq
zPAbk}gkR$05SY6h8qKRsRiSC^q<OTZat|xm`_eW$bQK(jb>-1GCL`qfA`V@=6LRZV
z&=PI^<wXqQAT;0M*Z6~fGn}-L%51ly;!b$2`D7KBDbt<keY(x$aPltI;fkWrt#?&h
zmAw~nnmfGn;Wm1&gtoB`!Q076b=@u}@}`BfiQ<Xp9jgkyzZFF7pD>(C)@qVi!F~gW
zB?6FAUPM)^uuFw(a28dx)bncRF=x(b)Uyp6MkywSxLg~3@1p|6HgkXjK#J`-K^FaJ
z{ntLsjxf)864dO>hxA;Wc86cxx$KpHjLC(Y0zkO6)Tm0O-0J2RWLLwkv(_F-?&52D
zq_ox7#Q!CW*J*Tst@K+Pfsk;Xv~-M-s`A039{PYY_cly9yBm<D^TmE^y&Uxk4jt-E
zy=T*9cd5Rc@_23c{gme&EGaCuKaUsa8Z2q=I=gpa#2Z31Gz1ou-6Fmy!^xc)tm|*`
zcqu!VfW|aps2g=Kcvp(&8l|$bbk)5_!*``GBtsvLYhd29*A*pL&d5A?RF(DxA6`S?
zySas|ixoRlT#)ggQ59Uq5hGf5fD***Q=Xt<fCGn5lK=ruap-a`?|Xm%0000000AVu
z;00a5&ycT`y{1g1n9Lym3ZJz>SalwzC3_q#`)A?UDm(-S=CrY7=ji|{xkt}@#^DeY
zhf@F;VQJzQoJivzHf5561jGW1xYM!q+v!7KbGN3o%KU^gwy;AW?Oggwy(#sC$$_Kq
zsxdYl>x{&s(k-+Fuh~&`F~l5fzq{WXzAEN})}HuUF`=3o#c3aQje#5PZJzcOp&-{v
z`n&aY|LAGu50s^pRu}5T&5P3Iec*-N(@bDlRTGr(;&gsscV8(|bN|f)Fn^|lYzGH5
z%AT0iqh)-$CVI=khEWF4!yaypGLxO3W7~L8Y*3d2rQ)JHn}%^;5QSO<nMKO8Z&bh>
zPBC*&#-&ti<g3vsEa!scTTk;OnMI7i3fOoOmQH49+Cb?O#j;7++(MKWR}G*d6}|}5
zD{ggt+VD)l1bQ`<##c1v_Qy2f@Wja@?a;auERQH|1Yx6ZwBeFOO@^DGo!tB-W~fqR
zuovi8%1ps3HGzn5XBz&{{ZTAN3S@-o>4E}3NaPShEoB?dU1d4ozi2zGj)IDh{RYK8
zl^99ypXJtZ@&`#6ylp{$KD#v&{rqF!iMI_vKX)3Sc1XuqzIrz^{<758deo_ir#osK
zR3_S9{qZ03i<~hFuB#BYiZvbgyJ^N((qUNoOY(n#jH;l9h%A8nfzkwT_HlR2OQ~k$
z5T(7r<-{_VuzzLZ4*ni^Ru%Wy#*T4GeZN<_(GSbKeuJb%b^zTz6<8*D*-VOf%tL@l
z;8?!bh;B0=5e=Z4S?Ub)873DRr?X_w=v=i^I-9DJLqA-0toN$wJSYjZ0CQkVq>K5H
zWGqkq+?AW7)`l>umFnzVIx(;uY$|Nv*S_kNh8(2`mM?Lb63E0i*{EEmLgKFen70zz
zUwi>1Xt)*?;{AH;^6eSf)P-5K{p^%?)-eyyD2n5J{bOze*`I|AEOA1(ahJ1ZfdQ*F
z`=Og1L295y`N=E`t@T}gCz!L#n3anW_h2pj&)yyCIK#6V-I)?a;PU~0#>0JBb?e63
zuS8BCZ@YQ?ncbCL{F+Qbb6eGzZ1MJl6~|UI809Jj56=+c?l^0Gr(dRwTtRk5!2ifl
zU3jvTo_1sB`||>|sr9P))$xI?qXZX8s*vsLRV}ithLU10+@Y4$w}#PdZ9C10x}-wJ
zCz}^mI;$^EFrnfy$LpjGKA`U-^>r%=36T(%GEy&6UR!fV;p~c-uklTpYj%?zBx)o&
zX*JYrr_0)1XRN95et#f)RXA^c9=-_9;d?nxQbgN)O~{kvWPW9S0NotLJ5?mA+7R|@
z$4VKiE1Uo8q4C09W|U{#K|5XAByu;%%1Vxh`q8eif1@3mQHNKBVfRAK;qmeQ@;O`B
z)|apcDBf)*`aj2i*9%FrH82UDg?r?!8jf}9C3CIEp*5F}u#N>4#&!%&y-?xxO8EU6
zMC0raGTJURBY-Z1M`)Da7$Tdz8nhV1K@@<<72Rb65}(@Be%{9NB|FV;wU%u-HPd(&
z83yDz^qvbaDa@1<z)r+NJm=cyC`%!YXH-2~(3zc^Aa!(hzapJKZX5_o{9~r;cmpl=
z0On|k&LBxN(_a{wa(>ib-OkUc+howhR=kK!M+-d5F`D;Ee7brmV6(ZvozswjEi2dS
zd_Chz)QL&3U}6;<<hANJRSrIU@Z2|>zVcLqCy3IkSLe7B@y}z#butS5FtGpvp4wjn
z3{Gv0$iiF;`DpZM+%cz<h2AjoDT*S2ptl9gP*)Xx2+wY8qg(D}+NCJe^cm=%+uA87
zLQXOnDlf6z!4Hy>Q&0LOwHN*DgU&#p)*r=lV=x$Rp4y&Pa_dUq0|j@;S9+hB9PTo=
zp&<Hk1>VG0n4)+{ti;DnWo99Ky<_v1=aa|ZWY=O**1KCN4v6*B6F9D#3xvL2iR3<2
z?PL-p<fmi1^`i@oz;u#|6?S=U`KJvuvI9VhXkySQUNrr*wi7cDU)7Wz7PHH*aJQ?l
zy*&do1SOgWjPcE!8qvGty&ButsQe8_IK`I{Jpn0gg&@H+UL8*NV&nVi>or$oD|&)C
zo2qHfx%CU*i<n$%+Q!;mvSqpjdr}DJu$z=9gj-=8!*`)CXH1r{=m2qo2|}kBk#?|!
zWdoh~+OTX6)(TCS%&UtVKJISt33~57E@}k-r41md;&Meu&ORo2OJ5rN?;w>VTxbW<
zUoLrGzy8>bl-W|6JR7isu#LI+^JJ4f!bFb65Kcz*m1SB2(p|+rtdFh5v%smazxS9z
zvIhs-5{_Iq9!%zNamj2?9<w&aLDBa;&bCNMQDL43>?3hac3T;RyHS#z`33hLMlw>2
zKa&Pn2gEny%`0tPhuXcQ^qx0#snJy|1|fqQe4B?$>nmJMKKxZA9VZ%%I%PSkdcj6w
z^eY$m=lwVrxHcT+CVQ^7RrQrmjEQ@_%E;IOxQ75zq{HqKRJowknOi<NagC~EY)UfX
zE#0q8w@yc5_t@j@hDz_gT@pUPo)iARDBf{?&LU>u)(UPnJeFPCQsaJr{OCTDfF?ta
z(zu}TkXqpjsLhDf)Z-b<=yd{Y<s0vO8nys-lR8mGynxLjk(eg`xtp@VGat7Pt_jX{
z^@z|zfwX{E(1k0HM|t65wp6b~f@dZJ!f=uf2=z$Ds&5nz>RZC)Re#){yBKXY_xc}-
zs|@f*<LCoI*#asJI3a_aXbM@>w95q8Vg8eew9cbtbqrVo)ZFL{E3tud7Q8^KSTwOQ
zyy?{wB}+Ojk~4PSkrLgBxtdRMlG<JwSbLb}$_S9-(!#>5AJN^4$t`wD!LW^eMk$vk
z)sJYqpvd)CdibWVdCG8amNT`a_HK$WYd`DyYj^iFel2DJzE2qOa~>-hg@|rG<-41d
z{gDm1JzSbEy<{K|)?zBLu@q3*fs{|o(@(lO7yea4`X6TP>L7(cIrmGw`Tc*=AMmC(
za(Yn+TMly75y~Hl&QFMO`8zdFvZ97vjY6I<%c0D>ZpG=^Nv=ug0P?o}dTJ>*SeeTq
z_O*sM`Gbgm?<~J^#2enaAy3xid*Th!!6i{5#T=<Xh8;w&1g=Gi2}ukXbs+4`2UUd3
zQ^ng<)&7<^3G@iE-EcLGJC_6ck57+tXfdG^h?(QBS!<trtR4anKcvh683j;fJR*Tu
zU8yT&s4geSjrMCnP7e}<ONaMKwYt&!L;Z}63!J?e0*{`P-kw#n#<z11!LW?;$%O!)
zeXB7bBVOkx>(|A`N|aOV-#oMWzQ%q|Q;pLmnZHy>Nt^<R4HLec=+is#vj-ZPLw@UB
za&#dM3Wn2wBhVv>sIoY+Jd?y>1XE6|>e0K~eCtRQ(Kw==VJAtfuafpim}%;D{ln2D
zr$RZ9v-z@jvZr$S5K+;Z?q+*3bJ}AyhbB%u28@ggbcZ4Zw6LFx11a-oOm*KddS0~o
zFDukl^qw^l(rSF7^x||R_(?+1-+=panw8sa-SCKpMg3ktS>L;G|5s?x@(+P}ps8W^
zP~9quOYEyz^!d|G{NELMAi>0j#3AQ#qs^5XDDej8dVjoYhLU|p!_*YHiL{^^e5o@l
zYJJ_h?0|v>+wc-soc+{`wfXpd+|)G;3Liu68ICq5EKl`G%-1==ecE_2a&;3Mg}ZM*
zhbzr}n18U;xbaqIng^qL;<-2wA?p`nwzYzC23y6Mwp>n-U;dys#W~;?Y}qKxF4^c>
z=D~y^p>%|t@cA`*s0@JnwR}2SG39@;hOnZW3BMp{qTND|3ubcNmWwHN?h4StmaGwQ
ze+qdd$L6+^j1!2*A^zj}rpYCb-su@U)bi^gP34kuNMIv{w!EV?^BBe#JbkYebK;AE
zL@l@w|IAA0qIhRjxF}CwD*?amph+&yU`qbjbw8am9N+9wO}i;7k-BMU5$RA0BD!iN
z!9QGS9H&l^((;x7e{u4Y%XeLUFWt*EOhGR9M|o<C19)Y(FlzF*t)tib2nK*WMWXio
z27mXwm$9-lP*Rgj@MgNoeI~dxrTAsMn=ljXA8gRnF6nTewp(tsZN%l$f{WUi+&=(x
zhZudn&wzWMf>@mI*>OK(yJz`6(goLE-gx3E2X_4g|M;(v;@RPJW$u1-1b0K9$x@J)
z?8BqB8K83yN!91O=`GR-KKwD2`)K3_s5)UwdtU&%`7c5Pd-RN2V)oX+%>-|AyiAQe
z#<sSr<uh1Srox(R)B?3Sov%u{jnC$UL2oO+wvN;8f~-0-FgBGrQrY6ci$rd7FV#;e
zFw;XKL-sO?c*(lZZIUzPP=yAAg~0JL(!SSxc5(r0U3PH&1)OM|hD;6o(oGz)bhL>J
zeCyos`<s8$CzO8^{wd03$Q5Q=ShvDWFDWMoceoO&@=hihQ|Z#ZeZ>S>HC_VVJ7;wl
zaz?j-O?jB$Seg}kuoYsa`L`{&l4VpHmT4>E%c*ps80*%tlX$6ld8B!J%c9_H3HpIv
z2FifF`yRbsJ{k_x+#mHNu_iYhvkOEeDo~~>JMfr69vr(pjT)PW<soaT|JF}%@KYk(
zQW@0Sp1(p0O7W$i4mzOkEEq)Pza}Qn+(;g>cQ{q3UwUl1bW^I&3s0R!y_~O5?jRJ%
zYXwKJ)7q9O?ih0BU5iyq=^t>w)B|x!0+A8_{yHH(vs-xbChd0C541#9{{fk9FVW{_
z@oQWAx^<D?a5kDWu<OO+;a0bOl@~HpIp`>L?Ocm0Gg#i+?G0O0yO@!Jqmb`LX)A5p
z$93O|v;HFQ&H&Cp3tLf_9mUyS(Q(vnyES_RGg~7tgt1d;m^$JcnEU;%+MZREN@V&u
zZ%Cd10001c-4XBr000000001E-$xh5007=Tr1#qY%P~2y+`!#<2gk4IG~^WBo0x7-
zCEVw1$COn;#3En@joRVt@RWoU%7m3-eAn@EjdbW+DG0-#Sa@?!&H{*HawcE`8=aD^
zHJGd{3IllQ4w|_vv%=E>P@}plDw!*zWm?Cj(PTN(PXG=N_GoG83K_{{y$ERDaNG{|
z?^75z+Dd1&$Na?auuY($&=1Qr@h{4mT?0#%GksPbR+IKFC^l3=!|L+PD3cziX!!K}
z!$PcVk*#%$Qkx5XhG;_REk&>&Wgs3#w&OpArKPV;C1xQqx5`X!2XH0#&)fqYSz&ne
zNDdn$KO3~Fxbm*ZAcw4+V2@UkX4MnIrX?9UIFq#mJ$s#~Wf{+BzmQ<ucK{NkcNB=;
zcnCLh^<wMc-PeoIYqpMYHXU%UO8mA+XvZM0MGniCs^_@9aa-~iRzuX?43O#bw`>a7
zj~Lu8=Obz<A0Pi#_k!m*^S(9t563*iR-f9$!INXL-=5f&J)+EH7cQ)D#WjQtXhm4O
zNVrS5KsD6Sp>{JwOMu^tvEcQ1kjZ&5{$5!eE*^eTL%?HB3N8!!)lEfdVi6(v1C48K
zM)%1F{G+RX;1Typwfl>4)zmBV<Q4ovyJI4;eab>t9~acchg8<0rp+g0c+XvvWZsV2
z`$LGyPIE-lDPvFJ&scJ1!rBaaKp0@a0Fvbdom5J4dB@bH^wYMp0mQq+X6cDQel`9D
z8Ps8xT*_md0wBFAenQR-Kqb~s%3n`ZdC=j0Mx~Y8@H+=uD#GfyUtvC96p52t&KgIY
zYMSR^MZF^2N!<|Mx%@E&@pb3w!6rV39@<F<k%An8$Mv%SkM0!w%8rn`6PSa)`NkfS
zV@DEI+OM_=w1|=Jo}LyU<`z*Axp+jL@9JEP8P64tX}j~`aPoC{Uf`1pU#aGRa4n=?
zAsigt1!CMbZF%!uwVGji>eY?)fZZgnE7II!_}y7<@DxJ7ZK<+J_c>{w8?pSy((a(=
zI^U`S^N^7s2#xtUdQ!XZ)IE8Pt`XV*R)}y(wlj)yCV4bgFa-)aLp@D7iyr}ra(PXX
z_w6~g+^_5BHS8mWu?~Hvj{~)|(aOtWyig#xF-hK{K>H}oydv*Z1+@tMWa5=hsGus3
zI@vy-hEZk~Ri3P3&09Y=FqzJI&}y=LB?Fm(=bV0X7Sahuw%$Ha(9mJ|g~^1$){ieq
zpIkJ-1Mn?@j<nym7Oh=;dfZkqHUxT8tNTUu7CeFC8fL-bw}p8a`pgin0q8v}eHIp8
zM4VVR{FvJ9G1hQHJ%&t;4qDj>a$LH?$E?$-0E017{hcfv1Tu45+91tQQE;J}uoR<~
z5OY$g8UQTy{nzG%3_Ulw#nOitsbh$wY$0HG>3m;7a6&`}T`id}iMVJnXcBMevVU$=
zn-M<osYj~OGd55487(ZN_YB7=g3gP>WsgOU$5KBebKKj7FhLm+8sA}+=3C;I0s9S$
zdBoX83VU?pvrEb`gwH~SsgQ)Y>DNh22$KJF5%LWQ_~{xRf#U5a^9u~}-E4JYG$+Y$
zSWbg-_GL(VG#o?m&Q=w>c3Gds*KC)^T=&4`vHt@kH_H9yCHqqs=2G7}ar;ccf8~)Y
zi(NM~ER&s*#dvn$TDx(pc+pu$ySUcK4iH2nfqp3Q8uv0hHSr`?;qRSp6cZcz{8#f?
z7!CTy-jle*t=CZ`m8hyXfW?env#j)2GOMg8rmVT=$<$>7p4$sBJl>)EoMD9Q?A91{
zik&Ds4&W(v4$jJ7rv%8iphGp54(eU7Fa0vWSH$rH8_OzjKR%Pzs@cs|Iq-GpI4|d*
z2mLG!KNuJ>@BtZJ7+qa`vCJh7t|m?+(IrOX&GDb@LS3iSTRb^E#$(aOS4bW=bmAwk
zYGmdTqqP=McE4W*!MzOvIYEfVC};x7e-ZO#OJOh*XuQmBt=J)xWP4O0LQy%qOMaLH
zELo&k$7yZth!YE(WB`^AZ`@6X1V4EShU#W#b!`%SWn3c61$N7SHAytZ3rkSgt21bh
z&8fQotjJAiZ}4R{Md^ua1#nDi(RS~Y4U@`-hmC^0ETO&Mkb|tlXuA|HAQo4tb#xLZ
zj8+<!tQw~T55)hi<}z4I><bnK&QnY5Jb-)<uVL|jA_XpQclRY~v0`c7!WG_aIE;l?
zcB^0=jpUw2ZTaE6#a5bpyL*hi<N3Z)Mk(<@?l)ix&jQp3(xBQr)Q5MBlPOMnq9u;_
zzQOhNMl4T`xgeitl4Dt(2j(Z(`UOFMVu!dTY3mfs|9tcx?lh#>nrzApVo})Ynp!a?
zdvzjbqr#;O^nlAC#l-njxeV@z<{b!|XqQEWQ&)P#Q{RJes?>*Fl+TrjK0f|*i<!h4
zPbRDiR+20TmfAgPng8jv&kCsXMF58y<jW=1ZP(J>g36FYl8ocXidAy6HIi}N)xOI{
z117)s+1DfB997N$hUl@19aM<6;^qJ$x-=mJ<FDgrh=S6%;6#&8-We%YCJo1Q1bpS4
z{8ct?CsJjEJaFe?Z<iUfriyPws+_3#>DR-AY#(X3NoIH_ix*OOyQ7c}Hjnfw_k9qA
z9QP?Ei;9v2<a*b`zWp1O6*f%=4iw_OwyM^2zoF6ymT$d+=6FM2!bbX=c(t#r_F%j6
z_gGf`_Vu+O`=Ie<Ou82>qF=;Sje^eA#f|u|Bjyv@9e@A%T<&o&GOTnKu1_b=o%9Bs
zs~(a5d}TrIR#kktU8y=rj^sgA{?IcfPO{ppz#pNyx$X^qug8k-g2oC^ne`btd`Wii
z64Ac|RCJ7afF<!F_We&7{28LxOg|Y7U!{C(DBmuMT?@&-9qOD}k`vsR7dSj{7KnsY
z!4H1$5ipJvdNu(P2wZAam1TWbgb~ql*6ZNC%}CfKD$!%?M=8@HTsrsFi8O83h>jr|
z^^m_}?=;g6ALp&$-p~KUNnk!?OozuZ|0_}pw4L2@6fEFoDmkI8FP3LSBLdYUxp=1_
zu)Ao2%^{eLDkrmslS2wE)6uX!EDk&kAx?iG<E9mBE@Dy9?CV(m8(F&#k9I^G$ReNs
z0xP2CSmb<j{q-_{L!MZOKT`xNI+{e35#mnQPAfm2c|Oacc#X<a1X<HYU$3ExSy5ZA
zzcb1(!2(!{5r!jsBS&?JY-mc-tZMouCb7JFv8aq?^rJ6I(!?j3ewN}et%-1Rn2Fg7
zaQl{68VOz;MG`zySpKov32ZU$505Y8!3rfdfC)H8WHXNP`yMl@ddzwdS~$IYTfH=V
z+cJpD%ZQjhP<1E`Y|zoS1u`fDLW?+n@g#4Wvl37GOW{<P)jJ<OV==u@GI5Om-efZF
zzD8q>2q<zDfCMWU%L!>rb9j7S&N-aWOe9ebBJmE<Fbg<1+4jB@b#oKc$K+{L0AdqW
zolMc5lo1V+Di`Suv%qh7cwu#_>78jOzQs`Sh?7-m=f1%T4ivda<vy8WsvJN>25uWM
z%}m|=zVV#E`=A5D!^HgqgujM5wJxmU|1|t9(Onxj2}V!dp?Q^R*+Jb2kWU8X(V7G)
z$Q*dH?fn2Th(BJB#F>DCN?u+p+5!LKAyh`xhDu}5qu>|Q9RG%;BKZO}Rc0!$%_~O@
zs-?dhEJhXp`irapd_iqL;O5vg86MD|#;%WZ_+t_8K)lJg1juk?<&NQ7mHs)xH;L9m
z(HXcoFi*343)(ur!6YY+?R4dfPH>fcl7C+F10rl~X`dr<{-915aFIKRNntz_172z|
z%%A{Fu4c5gy{Y%bc(h%uSbW%mlk}P==C%o*%XhK_$FN;c#rhzG&6U-6m@!!Ee_)-U
zV$^4{2-P{*uF=`v>12LlRAX>`pTUVFQ~Iu^Ol|x>^Jnl<U6r@g^h|4x2jioq&u5hH
z4hJ+y959v9M?w&|P-cj`Svg&9t)*al->i~FHq~c@KPffM`UEVl!64@GmCxgPdrCfz
z*`Z2F2I$e6Xr*TN&61bLfuys7fs9DrY?x@^o3^6D$WpAxi9#CplDUx)({p|V*8uzA
z!2VSjG?ewu6v_~g>{GjpP+J*>?NhF|obgD;YIOs$5Jt(6-`4d&usK)2oaPfSDGRsE
z4pWk1)Mh}$WhJo|3$h~$*)R-+CPX|`J%77xew!AEH>#UIj`XDcquofFuLLD>KFLw>
zqj%<!B1DXj(n~~JEf4<=ZvOd49G*GI2c#2n;1|WOP-Xw>Sw|{!**Cpfv6ZI-3EWSL
zZl1k<8f=Z6bT)zguWdd!^J-}s?=<bZU?EaC<D()_RC%+>lJ=H|G-Yuma}=6kuAAa|
ztgPgsT`m`xX~asAZK@`E;6H0sSGKrER*!;|*k$YwcFk-*bQZaCG@&^9BaBb9!PjTR
zP_?DU`4ojU=iJ$58qVDD)N;)7DqBsnr~0*Ms_~*YG%DRIlX{@9=E#h*Xl?oRI-ha<
zs4=d5D<WfQP>@`DxKaz3S#kY2)Z<qk`GR4a8u(@G+wp^1CL3|t1m3l2)*b+)IIVc#
zCvuV%!gVUs8?$+-l3ERelWalv$+?h#Vs*(P&-DP`-SWHzL=Gdt76u;(7^NnN_VNKr
z!YO;?^M%w2YWHnEbe2nJ@j>Z`N;L+WCZr)MiM4p%g9zG!vk6P6oJ|v^3PNTN`yF-=
zG}JCkf+~N!#2lei!%qdmb35Lc=5yde88M6M^TVGuqFN7khF3+X>x@Ol$X5PKl>s9>
z@iSVD?YtH<ql$`0(LS4R_aQ!T++DxbicR#~wvh;-0*T#1A_}0h1Y)`g1LK|7q8RDD
zgug@S1LLeQB9EQXXxA(N005)s9smG0A^_z0tvcf@w`5ux^L%_!+O!nNw6)95J~}eU
zUnm=+!nb@r_FU~AnQRwW-9l>cML1R;)*ta{-u7EItXbH~^l$xktWY}1MA&D_&&ZNg
zJddf$ga|^-%+I$=u5$<`GyEU(7AFaZi+F%;6k1m}3=yJxj8xLZSBkGVW6}TLQ<sjI
zYNt#{@v=Xs!S+ApFj<fv{_RlngpSP!xe5lENLl(MZBmM2_eUfWor^3DNYr8Wep<&&
zi?abST@72E4+Y{+#E@qeA2Ou2f>~of{tN^2(^l%5TuNZ*;S*cPT}6ffLu4vYpQEFs
zyAJiC(>>CYA~z%p5-0n3o{h+QHMRD>{hKk26#Y4KtKV{Ux9)C2*MG^}HEYEuM>|I>
zEoEP1=cxMy+O#dk^M#;2J$Xb{IBax4m+k(iKTXef1Y~><@TMr!(WxQUNcoI^XcX+^
zUMl^hf>D*<!Wc_D<(s7uJ=5ohv33##@`;yH;R6U4mINC3`0`MLkYBrqdZFD5wN7@C
z=tSXjMd6;7t^Qc=3jCYEn$93ZL%y3D&Cu=goj297{DiaxQ*5mz&LZmt@M*U3yn=`w
zPwp|+KHqY<XcZPuzs_V%fblZuycB?wduN{Pdu44`Hu>rIVH4aQgp5f2rX`z1cjcLP
zoD20N+o4{fM%#wclvr@WCl`V=uJ!PXsJ%VdVDAI;Z}3rTd>!fwy;szhV!3g-j3^Ux
zf~q%lK3IsKham%hkvyN103H!^*QM-a=3>QAhm1s6SgfX+eW}L{j&L$&8Lcv5$O(0;
zSAA*#r0hk#aveOdgEZ>11Yz^v98u4qlg9Qs3lCKxWGeIS0|opj*1MaoJgSEP&M~do
zl&Kn7FQsRY(U02zl_VizTI}B5_iK0#D7mp0*g3Wfmtv1eUt4-O&y^(E_w3_bvVI~Y
z{b{O|yRkfoV;j6Tv`2OnH|v6ylVm|B>AAOxLBmIqiMIJS>K491yw4}elZ4$P$pBk`
zwo+~YxSgj!bwV$KaaLx|-2%;uL^0Uw@rr1(bq5v5M;QAjw#(70D6e-204+rm88L^|
zLo5(c8?aE~iMX%z@4<BOMKsDT$&X<`Eknk-^!~N{4gogYr7?q=LqCMs)O?eCChb)#
zx10k3bG*$*y;UKDUF*?$o~MP4;Rd<6fs$PtG9w5X@a08q!e#LZ^y0MxxN!X|YKEI6
z#Z%RW84sf#$nT%gPC^rZ$%soyigaz8FcFBd{Q!|x6!&iQg@R2V%(kNQLSDXQ1nk}c
zzTNL{LfmV!Bp38(;fZM_#y=V)9)bB;VJkPa*y9;#hNYv@(2%ar4*Ru~Yc(maPdc-`
z7B{mO2zLev{>%R>h5Qx*195g5mVL~LwWoD#HgZKkJ2S3`!~9gH-Irrt4v?w=?Us~r
z{j11CMpbW8GafT|Qf;;fNv1+aloYn+wTb)av04K<X{9ODsAj#UDpq!-9Usa%<<t1D
z;{Qdv-;}TPT%0u-Yj^ZeSHKX;yjWn0YK1E{xEkdiBdcQ!N$?z~Lo~-6H>DrEd9XF}
z@{ts;+za;mrjzeenU>Q)o{a<9WX>cw$)E0Kudl||%7Pt<U73$h!qT+N*DnFgNyxMG
z=|M!w=^K1ZOk|6-8U<__QJ#xU%#f5~#Y(Y~Jl|I6(`#uqBy^Q`3L$|^&51w;)<@xF
ze7U$xMgdz^!qKhGu+l)FCTDxnPtAs(#N1>rKwB1q+?(jJzWbiC^_Bjf{mJX8NgX1D
zoZc73^PrOWmN0Zr)P_DFRUdZ2Xr{iw&T;`Porlq;Ia>Xal4`X#(!!2_rj8hX9#o03
z{NIb=ynG;lx0!n6#){mrKdL4<@AI?k_N(l|If{PSj!W-y38>#omCpEK&(F0HZb^&I
z=AHGz6%d9}2VwFWx017r_btCk*k0k1QHeK)WhdzFV7%IsVBzkFNNYSS53Dnat9NXm
z{`T^UT$%B_5#ftO>u!7KQA=-l-~n813-&%#lYWTqoRg?rpQj0XH$;{=Fc=bz)ATdE
z)Wwyu9jo*;V$ld2E};i%?^59@g+#vZ-_Iqth*F6ehKiyhLN3E%Y}VfvJa)HvJ08am
zHCP;x8T=7Ynn&ajUnhwT`LjR;$0Z?4y{QpMSqOynve{Rr4|QK#4F%>B!V7<Cb|nmR
zbg(8IUp-m8t4V^)C>{y0qPHfIGr-k|KwZ5d;fW!<%J>YEO5E%8y97)W`~zT5mq7M;
z>K84!B%%M;>1u-2JQ}}u0-sQV8U7b<v;JA}m2@iajCgaiGpNl1Ruau-+FN!<veAi%
zTAL*<677J4vQ!ttb&x59q%q#0cSl`(_QR@_CF|iAMY8g^ctd<vPrpm6Z#Hoa8S=a1
zEn1Gg*g%AoaAxD#&a!I-(CxqYkJsLQTKxI{90VETTUGxy(&YM7)#YUJ5|R}koX{yj
zDw&|tWN`qfNW(;+`ot<g|L0$8P8z3W2p+!9RoKP+4jv~v>w-o34;G)SOO>YjET9KZ
z@+TzWMp3zDR7?D20`KYZ%Kb7BO7eMz+zFgcrls>_qPX|);`d)fE1LHqXS3C3e|LHG
z;%^3g_3O#iNrB$g@g?J=cJfn<lw{qK<yr2?E<7ZQ1e}VHDt&uSG|L8ms8(nf6Zm`v
zi-QhUPe*%%K;IVg&ODs;GFSJOae!cOF%V&}I+>PQ|7$DjoCfB5AWpmIdRxad<))eF
zl|o|kYY)sAmqC<yzdudYVMM;nmkfcXxxN?#R;yh?4LM{7zohJ-M2~@bhlyH8xAnFZ
zJ)5@`BEpXwfZSr0>CC*(STsGUquR&d#M9ZSd?$PanXGDgzP0!(H2P@0_Y(6iTALcY
zyZNLjiHz}TqZ}|H@@`SghbkkU`ao@A)+zh!N`(!!?{|CdZMt-VhIvaRve)3^LmEG;
zgm{bynjnebuHH#0tAeY8EKp+*W8ypRduhK+F{Z<20m~&1(OLLq7TYsPQZD$p6dIB5
z$d`bIWG9tD7nVkeB|T&E5dyrKUk>^ea9nJEq7QFc1GY*1;=Z~hmiIJcku)5`u-nVQ
zOYqs55J<}6=PEE2p5Rp&z9v&$>kQ)_B5kINp4asy);cOW&1OKoGEDOrx!C996ArQD
z`@Z4OLc&^$>}r3Q?L9B!z4rbVCV)YXG~FE~#<p$@2s#c%_wZITG`N{m1O0ghPyl8(
zk#dYv7TEj}<hmTyO3i`P4aJ(~s6ri94*g$+;hlOkL92&Npi*_-M(S3YY!Q@il1Je9
zDx2ZiZ|8GFVW-gO2MD1{P;bBJv|A#WB5DcvhW7%B&+ijV(h_;8KAd|k(7e(T6-JZp
zUZ1iu&*COeGBU_tg=9Y>=kmu(@lqd*DEG5ue5{FWNS=MA(Hi*a+OSL3+L~!fXngD0
zFZpLN_CL4u{orq_dlbvD?=Q^;-<IPBB>`~ybRYLQ{N50-3=tz{7<%sTDNNaVbA;RJ
zt&+afm{m0b@*`LssG~vW2p9EY7rs^0#OX-9!7P+Ur-PFC-`D{K2Gxu{`HuBe*N+H-
zb-I2#Ytl7dr28{N7pF`dxhpfhDg=~y#e|}!?t%!fAPao@KJF}iz8^p{s^fQr26A81
zt;DcpAofeTUg(l}$V${osluPoxUkUQt7K7I2+@tZ?2&BbY8WYq1~@&iIfG(AcrwKB
zouo@J7dq%M8A~Vw@GKKu-M(qnvl;^uchvMPmGJdFW@OPo1)cCGBa|ruBP~A^*q6zH
zw?oL=Y%iSDf>Q%F@hnZ?*%j6*DtJI_*Bn2oGv%?!wV_<45=e8Pc&;9~X5jiyBC`B7
z+zUVq0ittCO3|-%N?6-rYCh=d-c;V8hW?>mSc*NJsq=U>>?h*qseD9&yT8)ug?gOV
zkZeuuvP8IR8v90sV{zyHBn<mW1*k9Cr%|*=@>~!PH(*`C#v%U>Qy2Ftv%|Nv42IIl
zE01C`HR=l)@%)Zbx%pT8(*=e0=lrW?8I%vJqH6B-6FOpk1Ulp1wlP4!C!Gkg+IM&c
zQl(=&hs*mkKewTChtB>*{r>X(oJL|k&P!vcbM1vrb1v2EoHTlbMiqdjI^zlTVZBS(
zm{wrkYdl%~4A&h?@Z0~kIHq`n4j&;we|O{W9&4psrTj={55H0^*W4f0x$F966MPso
z)fJe3vQ~nnn;}m$Wn~GwWAx<E`c_4Y#YUY>s+wYc$P7kl;>}O^*sV-HF%p8V+;{qr
z{Cct{qo~_1Q}ZW(t(3m+(}6rV=wL9p^Q4{>YwT#jT1Yysnhxw;^l0fjf+|nhR4ORx
z279f~)N<!5$B*CNrA#=mzNR-3q)t+6xoudl>=WN<7Ck4|dRN(IXrRWKczjo@yH2Yd
z&nS!XD@9oMB{P&RvSwrw_x<COZTRe{Rc-oPX;EimIyQ=9u1c*M9yxE=-0F$bu8I`W
zK1_ZUz2z^4uDUsL46?;;`>%ba!Q2uIKpbRXx0ujb&5%C&_K-7J-rh!n0rDrKA165-
z0{{kE6A1$2YpjQ*Ca|t$=NE-BjWe+gd|xDdzpv$W!8cD+sY%-_gUk@!pmQd8<M*-)
z>Yh?(Chr>UC^?@lXWa1@qJcC7r^O)DcEl;Bp23M(Dv$>jP?@?YS$I+cXu8>000kmo
zHS_=mLXH3c00000003Y#-Zl(K0R@Jc0TCrfqP|c*i7C}Qx7Y!_2*0Qh0$L1t5MWd}
zNnA>(@~vn9R{x;;O|V=r!T@+{MM=-Ks&Z*ml8yW0B>lGPv3n)_a|XiL6C7*Wjfmq2
z?Jx;EhgR38cyM2Kbmx5ar_AFTUk~!uKjtGA?E?~3`Eai2-X9Q7j#HHUBu}JL_O2gr
zS&O1%X6!~n&jZT?@c&8m6u}kr%dB=ELilF7m!7~hz29!FaRzgU(3SfAPnhs~7?OSV
zPERp4iv#c3+DOTv#S5BK^Z|_Dv2D)?G$Gy~gVd{lZGmBQ;XYviL}o&WhPs=Q86|4E
z;xSQ*VQa`ycnGc~;p4SKDqn4P<xW^9D*^xDe2SKS0A@g$zZzEUiXeExZVc`~tQk+1
ztwe;sLYS^Te$T&X25X{Znc95M!<8^+vif~1phueMi0aT8y3j=}(&<HE>P}IQGQz0H
zDT83~w4sltZ23iK1c?xw8Z`i`k)jr6UbpvrJgMXZ&#c!bpxj{@hWwUgkKHeWgy`8t
zymgqs55?axkj{H2<Wb;kW;PvA+`WqpqFv<`TJ!K9fx|%A%_f_F8wxG9)z`Y=OW=eo
zkN*1o3UkE?W`OP8Wwz;>15@rZzZ;vxe2>Lj!(7(XqBJ8SWu`kkLuV?fTFR3L&UmgG
z5W%n;G5ta8s7oit`YChYa#&;gL70sA8kd52o<wE7Zv(Q2<bkE47HTNzV_Mp6Bl^ea
zsG8@)Hk&iPBWQJfZq9Oy?$O)#KC?wzD%Refy&CN{DqPVA8|+P5-)wupG9^#5x@Q|(
zN`!tiDycWQg-Oz1A7<UITFNN8D>f637se6{%?=a>Z3s9#n{B=@U8#l4X0FZ>RFZJ5
zyk4zN*lAh@8Pj)|hOQ);#TRw2?<WO5#Z|eLim|Wk=~6Jg=pcm*ck?v)Ik&G2M{y&h
zOB)<|PYpfxxt%9Qt(wRaS?HGEWKXE)6()0A_J|afy0$C!u-r2MrTOI6v724=C>0w^
zSB8lU6)S2Wz2qS<<-UBy_};1*+lpzZIY}BX9I=x*qaHn3aOkL=6;-ax|2#WM4|I=(
z*y$pHGIW#KhbJdme(Gmi0{~5+gPSkoW>uM|T9P!V05Njz^eAPDzq%y{(W_#ZR60Fe
z@{aB2Js2b=$|hN`{QQA1KsPc{`P&p3e9tvF&#PdQE4xrv0EqBGP)|YuVwbuN7arKR
zdits1rI=LggbUcY@Nh)){?P+*PK}id3uMVuo;E4c;!vPFcuf||wP#c$EaC8Ok|Ni{
zePWnxIgu`eW1bQYkWlv}N?>5-U%V(M$j<hEFTAqm9k!}1-<h=7+#{bH9b=!9-rVq)
z=mC+Hpyzp7t1}_uevV>5(G<`;DUsMWlCR02lk2}XX#4Dle=9j$k^R(9)!azuzZ<p*
zur;8&Mip7xE2U33L?^z;C9j+`zgGmjQOSDtgKgTXCUPspS!|kXIQ&w>d<lnEtdFb~
zFaH+HK7>s90^FN4#1U~1XlCo6!1o(BSG6_~_7%*lX5z1$#9Sru;KaW=7#z^cr8QAC
z%n(<vU}9nYR)kS}<#Kp{GCo2A2|sZ{^5F$u<ua8u_qEVlE2)SL-NqK$(j-BBX9)^+
zuF<Yjr}U3!B2e|~MGQdilP>WS|APohRSVXV+kz*DwSA$hXr=1mt<bFLfpVXqWICEF
zFIm=s6Xpc}GFGDP$smtw{CBc+RCDuT=)Y)(LxMMWKTv#B^hT~dNEcSiH5YD3pb(80
zNgnIc&^T6BrM5w`PgBvzoB#_@zAV5HZ}~UDr-KreMPcOQ=w?7`C)}WG3KSF4!|N!f
z`D8V_Jlb^PY-Iz~iXas)MAtmKtD^<&GTYq+Ls43Ihg-Z=B~k67%Rr%HO8xcaZ3_Xg
z_Nt7jHNulygNa$=EJ+(O9x-BX4FurGEqs(Z`NkJIyDLG7z;#qqBhFcJeTI)y(`)S~
z;ym$h`<T<ut8%D)C}-rgu*+y`ZkwX(eH=S)GVI9+0hgdn@UI<i1Hd<EVr0S;dV&PA
z6jAILOGxa}yv(TR0{f{6@YEq)H7(u0ul-O6o4>*I4NM%$&2J<(qy73QRVt>$UI0WR
ztS4!<<dhBv)ZWz*w9PyhO0f+9l}H#vF2{yppr@(sCoi8%N=R*`8pCgoN_FwvPvHkF
z>s;S&z=mq5c|z~hw9X4!5k&4lV0o$v7!v6*A6m#wLOsPlk#KwqOf<HwqHWDe+-H|A
z6L-S{PlauCdH@F)=ZHi@%?+cc!uwF_NDG(Vr)-F|t@ax9k&MH73AdjTgbGea58|?y
zFku~0>T*s}4Sq#8lO4RBuYn*~2Ui3Sk<&u<Ga`@6h;!Tv_NKLBB2^7TJ_Q9vu2)~m
zU{L63Ks=8l<@<2<M@khkvp_35EO|{cPHWgeT=>!IeIN_6YkIuf{fHqc*oNaJD~uer
zxd=^(Bu{z?H@<&8{#;?Xjm~3%dO&e-%6<)@*zqF}lC*p)q<$zjccUXns1S+WRI)v6
zaI072zB>rB9?WhV2Ds8bbG(`>8rs4bB~1*8*;jF(MhWEWtkRsDW`SI>C5M(-0rW&$
z55VUOyPRAwmX?S3&#rh52NxXjtqR{K^=HY)Z)7PQ_L4k?Z9^$5$0%8Lr~#XmelBxa
zTVL!jt*}tZXlS#B+q<gYsp&v-qV%tPkKFn>mAtTfie+2sgDi`Q7fmyu3K){%eLvHa
zU^RjMODG<zPI;)l`%IPWCG?Ki$Z4?FV{-eUdQYCc<i6PR32K}N3kW9oco<JcNuQ4=
zAShv;?1txI&t3`O;t<M;psn(IT=HrDDdy*7$zwZ*Mn3D#p9W!_HJYQfzDC8PshmXZ
z06qnBF=?d&{s$%{U<nl?c&XmoPQ3KtcM6W1PaIjkixOu?2R;3<iWexX&xfLCmZ(m!
zaaw)WM~@N9xqqR<uslG>`-rc(E37U}Y&Zu>1fQgGfQqF5oi=}*Y9(7AsU=>lK1QOL
zLjmzDuwf}k2TtAYPhs@osoAppq&i9Ek{fz)l;S5fYrh-F>xHQ9p(zC{DUZ%l8S%Zf
z+A-)4AN!kUY@P!TySrG>)FMp@F4KS{)c17X-y{g^^vu^n_s5_UHzC)MJ$SdKNXR<g
zXwueV6(cW=7wfvVUE63c9-F&1lK6A)7=BkKxl9ECR6;xqZtUc6f$8j2Q<7>Fw2g8!
zA}ISkEQ0f*f6fR+-y5KQ%olf<u{_%C2KD-MS?Api?CIJZ@syZHQ&2&{-Dp?6^cO4X
zfdUfNcdf{E%%(LBx_hbClgvB8@Q~>D_9lor;q}OxOw;17_Uoj&4SzNZ&of7lcFkjr
zGTItrS(Yuo$KMMwMCLCiB}@PhD5QM20KTHb^*y*W8;a*-@vSt@tE%eGoPbmL%6e}R
zq<&;YE1q}})}DdapEhZzhff^V>k?#!qOq5{s*hP<o$@A<^9pI1IX%VHK1RT}YRH^s
zN2xP<+tSr7yh@3`IaSDo!8MOs=VL>0`APX{=%_tCb*)G28U!{vG;CH`u2Z{HQ@QCE
zE4gjJ0*ZtDo%fVUt^11r)2^&NPm;_u2Ivy(*O{u-#F}OH@Mr!<O)!NIUsdOmnx|T#
z{7Yfa)cSPk3`#2T^Ir@}Lzn&gNksfhx!aLgz~zZpp3OleWY1Yw^wB$%a73`~SrRnp
z3V|+Bv~4NkE9>|;0uo3-<C}Yzywc5%3``sh!WrWF@+4CyGqK+?d=K9DPR1UHb0@zg
zF(B^jA}f62#BR=@GD`*=0rAH-0l!ulYKlf&sa=55ot1@Fc>ln=7K(erCoF)UE%iHC
zS1e+CD&xGhsxbTkT7Ar-gJ55NXVN;u5A%{E>=*iJu&tgwT8ruBcS}AZo0qK~uGwm$
zgM1Op_+dNCEY3>R(Bjja;`J8Rn{gi<n5+FtPD`<Tu4Mtg{b(0VM6(WX(?TVJbu7|r
zF&a5A&=h}3wd{Q>uOI=!h--}ZIKlvGhVrv=stu0Ba?>8&k`aohUocN@tm3n`vTW!D
zC%~J2aD~J{sZCA2b~uyP)CeADxnUa(o95jN!xaTFS&EMc$e`ht`<AaPq}{k>%}b?u
zTalt;l+Bd)g?!+jEd3*LqL~-B8vXE<NKXvJcwBswrld@y*$Ai+kh%(ky^Rvakr}sR
z`nMKZs{YV(A%8`#BMCR@tzSQs#P%EYAPwXOdBGhXTGRzQ4&8w}^)LadLpuowXRHbE
zIWu8Ou*fa|l6Z^nAv8EvXOtd2h6z<+yWs%=L9|0?@Z$9)5>uX?VF+Yh`ui;L-U);V
ztL4qXbLc(5P#KPi#*$j&Hkds5?fenF`!Xh-{;+@t;!#Un2wn2_WmU3dNK43B$l@-b
znr}Mi&<&YrwNU~$pAF-kaBZn54z(QINz=oO9JpQ@Z2-$4PYRXtdI~zoaaYrDtp=qt
zSUOn+Se|0IBdxFE4HihBzlXS1zY>{6Wh9J&uf&3T2xPf$UB&$cW40oDB<gy16k>|8
zvrS`Enh&9<fo96S&s@ei+>R>%Y?}<N3C0+{t%H*cR>ides7{2oGad>?xxfGrSV{bI
zEr9JN93TuFaP2TKe}Di003|?cKmY&$0005L6@UX}yjT7sIgELSBY0+I)4WrS_WaNL
zq?ab5@p)vg7ZGxQAjDS4GC&S`K4;k3o{aNXD2HZ<X#YDcnr-YmhG_Gyp|(*9{K3Mb
zPliw^l*Ri4=LO<mR`NO-PVyC{XH*7Q(7m*|HyS1q`yYE3u8UEKl>o0ZtTmg<t;rhH
z%l7ajuwW-oJI}=l4~{yxn2x9C;N3TOY{QgX4m)upp!`YY*5i~L{>Oq~*J6#P?&-(q
z+~!8#>`M<)G4}~ro8OR^7o6u!^#UyS>GRLHAum047t!mW67D(Fr*%%9CcjWHel1q=
z?IRmvJQne|C+3^wKp%A<t3&c&&+^MSqWuG--u7pmS-(eY$EPHlUkXo5M5S=V5Wvxd
z0n5(H95t>!;vgbTk)&(d4;++XG<aBcuvOTW4x~npjXj$H<LT}T-342f6eLS&WtmN6
zRn*$8q++B1KiodrL(v+_$7obSHjJPqw#K5p^T(xJ7le2B@)A31W)xQJjZ=HDF-P@G
zoj(9sJr`fQg^_?<B32c4MoIXmy{o`KD@ro9`NLssY{5ShnWc?#o}DNBCzMwctEM{@
z(&;`+(8>F{Od@5LzfHuBnb<U12qJ31<EkXi9Nig(y`<>d!E`s7#?|_wDr=rH68b+*
zpH>80SM-lLB6V0)=VQjY;)C(c<Tw-TzxOC$uJ3g=SfG~|?TrlbBS}<HXAc4MSZ_D!
zs5y%>c{MlOrYw`})z7zYFlDFD;U#Sbhh@I!tR*eLi5;ykW1jc%hNMrMOJ<FPW%+TT
zYl^V-F$^Esx}#KblO`fy$Mv8`EaS=JcNo=ptN{xG%RhbzZyWP&Y*{+TkNQvwY`OV)
zM+pm5Q%%-lgBfq+>DD_jHc?8spB<9{^P5I_K5_mY^JJw99^pNA3@E=qTNaW%_A8nb
z7_dq(J^)QeB8mUtmS?Z*2C0`;S|AOa<~UH0yb(@*s994w2X+l_lIc?grj~|t{#K{+
z2kUpfs-VTiny}5r8KGcyvi@Y08)p{*s2FPC+d%h$vQk|s#>?$3d-lHazsw^q$nDkB
zPeaI@=?t%VognpGNX8%(M%^W1X<#t2jR5P`7YL5H!;V~rSX6)q;fPHUjaW%_tn2jr
zz*w!x&33VCNU)^QwvK-G(@z`-xRn>6jzeiC{@zYEQXoKU5KnNHd*t&V79=*yuWO+U
zj{<Wq3_)5#a@43(-SxBDDIxskX2Ft&W6Vql-K7_eS&16^2OAl*>W<<8VeBToM^8&V
z-r<?IG$Vvi(`->7s_|`$?w5ZQ62$TjDWKdWSZFcI34kIvr76P{FfCEJ`>+pD^adAq
zH0t40K<bf2;aa4ddFTIiT>5wKL$85i%v`rp)sgcZC8L+R?Mx{1gWn}5DkU0aQZGc;
zMio&Ej~`R>dpmP&2ye0k!}0{yf>`I2YRVyAF9vk$%^J@RMD#y{wqs;2#&)0;p2Jkp
zyEiMj-u4+O-i~LQ8Ahw>?YU1a>>Y*R_Y;nlkBm*cI?Gt8N4b=KT}C<zy5|KQR{1#@
z3zqWVj+O_cDD0NEk`BNddO?~*cU}ajCl>e$WF#&Ruf)cPuc3H&GVb+M?a^%RlB%TZ
zb`OZj{$-eW>d~dgf22pTs(bRW(<AUW;up>UpR;k1S%n&WKhz0&Z$d{!yceYS1+#SV
z2>CDOCHV!=)yFKaAPru-ez|({mT7`G0_*4G!+V1$eVMho%UPeFqGOs7(SPK>rzWzu
zA*gEQ=4VK*uI$6%yk_NQhL^aqC)-bBMUe4PMQW-J<v=nLeVlp4K$4(Gl4X9-e?SLq
zeu43rF1IPX-p`!g_+Rm9jkM8ow3>$9%slxPZ54JXR)(XW5#K4QAaZRylh?fn#@n;3
z>r7ckyL$R(X{R%z&?DpKgvrD^_VVybs`K@0{}Z+WzS){2GhOR%yV)DdINv)@cyv7=
z&B-!Y@#TU^1uxqhvS{1l9kVq4V?*_h7c)szka|BXRss`#m;5*bv}RQ{<>>vUbL_&<
z=Yc*8Imo<Bm!!nRc_mfB>Y0-XtKFE?a|Y}=p5%o37tA+k>3EO2n-d**9jnmINQHZ5
zX*GYBec0ypi~?hv-ttVs-@gTCv)N?bkdR9k6H#q}pDU%Tvru1;ozTF4Ve?M`Rh6Le
zQh8FFND%UTsMX})M(O*4p%c*#SZXGX&EofbO#c5@JlR-g(;GiF91wvHZ=>NGT9r5J
zFaaZnD6veHQGtG}DcZB-qZ1_xx8#iY=dKsClH|Gh{4y9tAU0o!NC|aDsi#sF)U@rk
z6$Zr#7s_haDGwrtQQwta66;z-d%|!*3}=2b9I7@&T8NnL&I;lE`~{+yqrY|~1B%li
z)#>r*u1D|N&+?%bFHQ(kr&rDf6tDobt<;KMZz=tw7!Pfm>(SvL9!QU2ODMef`3fN(
zy*Mh131O;Jc?Fik=N)I64JVZ7HB+M{N(7F9{RR;E9Vx8}DQ`TS*Byvb#^uKQy=Hh{
zJZp~M|Gh*nb3A!jGJ05Fjv=7^<EU0;kPrX5K><{_O`w@l-~^z6cUKI36i!d(qw{H#
zms_B9xWfu+D$duCtKAx+^>K0j<%1S9c=DSpIM<N>kZbv_06x|zHppriv*M3XD`o}N
zX0w}`WE>NV+#%Af*}Z(^+p$ykxfWts<T@n>P}KZR|0V#)3JSV}R4g9fiZOrc9c2p=
z>D||2;#@xApYvm3P+0xs=?(}hnV;e&U*MEhX#b<sUNU-3!50tiYiQ=5#!08DciTJc
zK#`PV#TpurVfO&#rvr~zzmGxFzY&e!y=>diUeHqvtIgg4GkOObi&Hr%l70PLAnHCL
z(mq)oiVL*@bTIb2AQ__@OX8DAOSK6QZDzo?EQ+-G79`o5#QO=f{aDW#oLeHs<dD!I
zfX8`Fr+9>MoR|Rmns6sD;5L!>^2maD(1m>Uv)U{H)xyu`)551nB!Y-VeV8s_$N>xx
z-44BXrw2hm|4rLze~Dc13dKsW$FFpX9yHTj>`N~eKG#!=L;qoJ$&*AM3I<Jv<y_r5
zn+!g&?FlUxfHYBTtRB_M+SdY3$okB;bYa7hZ1ins4Y!Zz!xT(DzNT=vb?b*cS;OH{
z&Uy#d^-DFpXOd%^l&MQ0L&6p4LYIHT5!Dzx;y1p>UH+PHc-M2en$+NO$Ikh14a|dU
zzCc}Cq^ZaLtmZ$R$mtI8hhw}%_6zPLd483_Jad~>jVRkfJ8=2VE*moa3r%2Mpm*2F
zxeZ(1+BPP?bFERt(yJZ0EbYUGkLuigEzeJ~YRt7K(Y>vrlD19h>;Q}U&ldj58}(o!
zou8BZPES}Qq)RpaVrZW(2_l=*m}eVlAPXP_JweHEe(ED4%K4BGJaZK?589VYu4z&K
zd8Zw9Z%Rh8&;<2XW#gi@JTPDGRGknhq4DN%KfZYG9*7E7Q`FtDt35A4K6Z|E`hS`-
z3gos<WS(xYs*^Rat4vrU;ofN>4lqcZoYfSW^Y@xgPigZHeHJCbbH%=-QtBY^RQvq>
zas^2RH5AWtL6@Ne1LglXw4&~k%k9A$*u+ZOlFm9)m_oypitpqWP_7OC^UlORIXtCw
z+!m|^u~?87Q@pHB215h=q9=7hQOhAK1yws(bcsk^aY_sGqq*?n!qQ}w2D@rkakhTo
z<k%1&hb=SqBYp2`bw`>`&SpB8WIS!n*9C357T|t9LFZSx3)-KQyv5kIo5e@bt%nb9
zoYfzBnnO(r2UMFW`R!~O0SSgTofp0<O>~Q&c01wZdQW<ame*gZzxCS>aP4nTV-U1*
zj0R&&bGozv%Mxgfwxuwk4ofvoX~J?5Lg3o+Ox-|iV;)&%N;Cb8Q2E3fNq;ou)0?Cp
zuTVOU`7hRKuP9u3vSSKuQ$Fhmn6t4>Jgkl+I{)23%M2WQzzk6EiS6_kUp>KD+WMMX
zHk6=$VtyecE%2I8eT-w?>nHndL<*)uvp&*+xcM%s9jVC6A8S}|aVYaOFrdv}!C@*r
zCCC-qV1LAEjqy~6uBhD0h3*W3EknF!z&<17`>3Jl^5}>j2{5;PKDPF7-)6Gfe9d-s
z8yzLd4F0M1b_8$uie1WJKD`-<$oz*Of1E9wQ&g3BdHXERn*EBuYcMS@>B6SVTVz6(
zaRj01Dm(O3nN`!opQ<GX$dojjBw+}U|8$F*e4=@*ASGP*_1<Jc{<tlB$2Wv(>h_RO
zmQ@uP3Xq|y6H&L^Q2QX45I^|q&%pJh5QzmH9DK~m8Hl22AfGX$;h1S*r~Pj0B9~$;
z7garQxvxu8^OHp=hg^7a^8WzYAFI_6q(lFKa{vor+D`ukw$mVCH7ZoEz8$3%I}TB^
zUDUlzR>2{-;E;d-00A9<000Vn0002|f@DEc000H^QuP1;0aYg*k6s)-2`A3w%U_Hh
zXK=l!CWmVHdsEAHLA4jgcR-#WufxG0N>~*5OFY#D>Ugqg?O(#6#kIu5GOgSn4atJr
z*|Q?tC_;b0ev=@fG``du+(e0R;DF(mQzFv$nu-bH>9u!>){1FL$U=~zxs6!MXC}*P
zDBEV6yW#zeY*%DMun^Gt;T}mkHo(Y91#KyLlCn>Zr4;m_G)F8}D>xK>Qt3u==18gA
z7bG^(3Cd5BD?F8@#BFP}@=x&ntydv?p5*>Bxyqb(OAt@4r|ktx|043J#a;FRHS*NG
zfGRN8WLIUKgr&vj0b!Hl8mTk1ZZirmkqBC&?65*;WDztK=g{j}{7uz6(SQZV<?%gV
zQmH^*rrg|Y%tkuS#hLs7%MY|?>4C%@S088MZ&?r|+g<G(^l^0#iJj+Rk7k=S>!~$%
ze*^qDdWy|cHsce8R>G!F2c$N8uOHkxQj_s_(S4---?OYPWlG?<b>SukRbO7=7%S7Q
zkP$N#%Pf-I<+8BTfqcJF`zs*^0cpq!#@#__(G2P!!ETAg?KIvlit;{gIiDQ3+5F+9
zGatO|r{<^b%+Q>Myf)QUqB7ePpHL-z#i^q-$Pi)bMh^g{!dz^~jUm9zRWaNOC?4oB
zKg^aB28e~*yef=G>4LnPfUk&2SX8t*(-(QK(fABB)n<})MgY9e0`pxAP_n_wGpqB|
zm|~k43v*GM)2O@=8qYqKeIX(*A5PKZf3(AtW!*#yEM**#o$HjUebfj>i7-GeZa=s<
zb(;8#7g~tm=+Xr%&GRA_+IH>Ib~yaj2*oZ2f7!0<7nVGHa5Dh-PT&S2JE4E2!CWSp
zx+P(5UyMpxt+cp>qX>>uK<?SCm`_&MlXO5E>)sEo;9_0zem{qVlB&xA*1K75v9tXd
z|Ei-2&iqfXhtoTO<5={fS%v`Y<3vY3TaNS8F(p?A+FeY#@v_+}kt1%Gp;CX)>{aZn
z$}VeX2(S3rw^L9T_b*cAGXpDK|8KZR&xb2^UF~WDZ@c8FU&?)sOY0t^cC9W}OWOr~
zUTmgrW??`vYE{%$&{@ESs@H2xB;~pAaGMp32FxWPR=BD6OfpCbVZ@-$Nz|c&0wX3O
z^X0KlP$IV=(82f}^BX#`Dt=-_+I;=<=!e6|`IaGOL;pZ}2hrO3YHoBLeTa>}nwz9B
z5=&-_&=HE85>G)1xnEMyXBBd-64H<wH%63*&%7!(@9nMfy!M?jz2<IFliI3Ok<Nk*
z31+ez2Jqg8eio~+H_IChDWasC{3C6JsDk1gu5y-yO*NyfC2w%KV>tIE`0vuN-B4Rl
z^Jpj?7sgm^%WSNt3wyBh)0A#kk*E1ZP7_QiVeXNpzg_m{(*rZYcHW>{Prx{2mZnOX
zSO~H;AQ(-G7aROg>@{FMUU<xJcx^uJ*K}ei6%XNClhu5m^N!xI(p>!z8Vs}*j;pR<
zkZ{qpsNOFjahZl9SU1OsQNAsJ(WyhGW@2fB^Z$RFn53i#PsEM+IXQcyAN+Bor&Yy%
zGS#7gtn2<ak`?#{(^En8NfqinP|$9h#&k>%r<JgnN2aDZcX?ln$`0z>smwKbg9+<u
zsALLSVze1mr_ePrT$u-`Ft=@fer-S91y4qzI<=PLkTxM)>WfGYoI_b^JyA??k;{Bh
zy2U&x8!2k$AQ#yr0nz(VW)upBZOE`7{Ry7$zfA<CWGc?NbyAR!Es@6<9eO+a05df2
zf0#Ezp4x<u1tD}`#`l}wtc-paE?6#r1#9N<rtrd5afHW5l$l~AaPv4YM9&SxLE^9_
zSmfzdzDA9mlnwzMawFQT8kUhtqr6k+{Q!2d8frF#TAM2cB(3*?kkg_xwrxT5j-2{T
zIEjcdOuO{<Def|C=J<ZLMD-U>i+DXi9NKE^6Spq5*NjK58cAR_C4w2K&kQpwnrG{@
z8#ea={>*sZ?VnkEn>x(=l?32ZSjLTow$InR3QRlK+MC;}Fe?zyPX`{~cEXI$Y~gEV
zfnj-9H``8)se!j{i%5USLp-M8tq^}f7PH*THUwDR#eV~zkIJEL!Lo%RiL3<O)1!Y^
z`PSS*jYolZC%nHBl8t!(z!w2-LZ<~4kMS93ZBub@LvC?SBb-;n)zJS+ghI76$}*9_
zP?yA{{hw){qdlGq=S0vDep_KGGg-{#yNPiXd5>aH>dUubub*YvKr(@KMt$aKYQ1_W
zTaCt?c+<P1aWFusqUuoB0AK?h&E&v^M1XtxUz{K~6fnR6VE_^nL4_3nD+n#tqQh6m
z!O;h*WPYugcq7hqvBO41Yyp62>^a@_DJPM)_Fgp#+Z6VT?ogS?4zLI%cnqvDUHC-r
zW?M4Qi);m~eUj}P=YgTEc;U9|v|BGW-K3M+&(Z(<Zl-X98O3-W1lsVt8F<K}sEAg}
zl-iZa$yIbw6`3RM_xDFKh!)l7Lv*1ikldXl6Xv0~V$vZA3^PbGbAeV$M!Wc??3+yN
zfbRh#>yAosVJz`Y6k+CZ=&<_rDbiH5XFyclL_BlCeBbP*0b8=GwO=}_ZFMn$t369{
zY6*-j4OMN3<I*ZuuB){oG)KT7skp8)#2wM`d$NU9UPwb2MTCbB)#6ZfoyO`*JWrb+
zO(MXKZwhngHm>$FjQFuz`2V1Xymmfb!qMx1X@x$fZw`>Ihn@~(@<xY7az()8tkZD=
zVwNvHmJE`hC<?^O^)p?m4=VZuuctvNIeJo6{ALM88`kMcSMe|7Q_9ZVpJVD-QE)Z&
zU4&1VNj#9Jd%{S4*7{zO?FK`T)y>t^k}`dDa)WT*Q>o;5b<<^(LA_){U?F8xliJRP
zMk;p`L7?VQ#V}JPUD8D?Siwl(?l7Q6G?n?)A@qIdx3Y6DYU6sGs`XhC|H2Y>h#ug-
z9k}b;#-(v~O|-{p7M-IZsl*0`=q(Jh6LhETxJ%cH(cCzF6jRu~kKC23hU~L~5G#+(
zpHQAR&xstI|GEX6=s@P^o%$XyzfUm%8;ZYl`m7UYUVj!H@#3x0JCVG*1!5J1cg3Ru
zHTkF+l|7qpK{r|cb%-Ivd0_>>{Wls%+(z}Q2){z59J_xVIo=J?>c(n5uCgtbw2)6|
z9r}~Wf!$i7YQ>{k;p(|80nrGL%Au!zorGse#NHf7AA>gi<#H;@KjMJ<29Y1{BVh<x
z&J6uCGp2C_EgB4=aq#=<yFV!Q4yEw0gh&lK0rCi*u?w`WNiNl!#ZN+@rgI-(cZbuw
zu@Qi8;@00ZcFp<(xp2emm(9L7=5Sck(3GGS?(S~juUZww8D>U8u3(3*0O5T^sWMG%
zRWqpXbiyOBG&b1Pbfyl+h|KR0K*L8L8OB}=9yk$3bv91y^Xz{fy_o#{bc|gg>T8Og
z#2_6V75z~S?O7}l)n1Ci;^k~CO2;P+fn`#2BAtqgfUJ0A!hQ?iw&Eer=C&a#;YOm2
z#Kw!f5;Uy`2wwU*1aV!Q(;!#_kdnSgm4MLtx4=LuugCoOw<=dTp~@XbibfDG%ZHG5
zT$MQn$$+P8e-G}9P=J^}gzdz_E8i^~)36EP_r?wJSD!j$C&dK9q6`Ei!xAfhhE-WQ
z=BPJj^pkyezE?s$q82x$d<877Qhp$Mk!ti=_YsIm;|q5&QnEzr;lc!EOI)@{p}j=0
zA~cF6pZnN@e1VK3*RojbYq|$zG8tsW2_ddZ__@|)Sl|2ohh%@!=mrq7j#3tP<yOVP
z2B69n!LaODZzzdvVyK?3mGeU9Fvgzbz@(1;<GW{KL|TIcO_H33c5@*Na~hs8&U;>0
z!hg~4&n3wX5zO@mA;NWDNJ}P=eClLw=^Th=Gwj+HPCVbW*55nXIv2<Ggz0lZAEs_n
z>zz$_WnYEnB6zB03zoPGtGVDrcpN<vzeW+gI+(t-=5xZ<d#1fEXrY@*gro)N`3%q7
zF*fN*5vEEo{KSbf@fm`_wEI_q@N}$H<5yi6%8tE6c}Ndf4~%3t-xnJ94u~RJB$skI
zn3|Q^fdmPl4!2BR{~DIVVaEMgZo}XL6u4}*McM!;>e#IH7p%Lv+iPkYghO^h9a%F}
zM^J<=BMB#vzubl%116<6G&e)km_Ue3F98uPCb(&tYvF}%lvvr}12r9;OUxrXz8Q{G
z0hf1g^$J5cdP(DfdEXO!424<q{>r**89mA*`r$|6lZ#b>2ABX3vlDP~JzI?+00000
z0U)AbX8-^qPD^f!U8>OlU+2HnvQgra(xkA(95tY(SzGt6#*DDCS)^9R$Yg|jYb-hT
z55&0+^myAbUrY2L0jtp1{uU6RhMi8}5!j+Do@tp7=b_JDzvdk_4rAf31c=6nELdq&
zH^jl#)@%8mo0xeJPq9@1or_@ueCd0FEWvBJ7P;sWEa87hJ}IGsS>9KO07)>oACFe0
zFG$M&fReiA<WS|)M~%&92Vjuj`CklP@)ownz-tvuhtLu?3gKp+5gR|c@upqT;M~~T
zV+2830kdyMZ(f5%RAwxV^M1w72j;7M#F=kx6FYOZ&LX$Qv}un<ZAJ_BARs&VZ(DgF
z<D_E+%H3%TrSVX5;o`F_{}&2l=n6QY=;6*o9-Y*6t@$u*$iE~~gd}v#PV$9*ZW*c8
zrO^0K8V7Nub~4!Kb?>H}jmoQJ*l0^tkm_2R;`xCh@2WI1Eh}8zq}c(;kY=9==6+;i
zJNBIh*w!Q82dqAgPO8)^Pe|G-;R|Uj8b_w%B@R*y1sS{Z_l<dO&EsHo8V~2ELdXK3
z_uIwRj?_(LP973tbE*i{Tw}1z4II4w%Q4imy$#h!5|dX?tAEoq-acx}15Jf=YWkK#
z=_!8-48_X;Xh|nVmavheXOI-PHnsK3OnG`IVij4$pfxzylHPe!vJ+X3G^s57d<(54
ztb^qf-xrXF&R;zN=#nJ9<g>N{>d+$SfW|k#@H~neVWc-~;>J{Vc`CDz6e$XXXc0ro
zUnANJ4_eSfysSh?Bl(uN;h>{nHS~a?S1cCw3Ju~k11|ZR{&^Uu#W4ITX>9XE5x#Q#
z;`@bQZ}uL$jwqzIL{46G=c-+?>1K*NShLJlrqw%uWqG8d3QE!UJ#(m^Y;=Oh0~_x9
zPJmXo`Iusx%1g9WWXWuw8!lAKyMLT5aCg6_m<zR@Ds3C7x#>UH2)W_*!la=cH_h6N
zsdn$A;#*q4D;Z$_2(F}hBVh^K?!FzsQ4oP=p7lo#U&&i``qx#Y%6A2yzDfO2$1Cb)
z0+yRnnt_?PxiH`fQF^16ua)!IL<Mu+Z)@EZBwt0}Y~MbPmfMMrIw|;T0RyP6@7nNE
zscsB=36D~2Xi>S}!19DHP2@|46uq%cM*1!2U!$LZ|3NBtWToS#BjArHxR1x58X$<K
zRB`vI8~4Mbt5GoyW#dzM?3fnvjR~O$;Dx{cN4j9KbGASN#xu%oQJtR5SPN}YH2&!2
zUg9DLpqJaB$q$bg&8^pFw!5#`rq1}_e)99WtRhGwtIt6c4I((MhxckSN5sROr1jvH
zP@9gec^OL*=Gn=bU&2-#h?^Wo9emhM#5tu$3r*3DmeDZm#obDxm8}-N8aE)gc{qim
z5cUDfKiWicU=c>b*9|$w@ea~k9Tt4T@5$X87=WW<E(H98FEedR<e8XbEv_!6hUflO
zY<!6p5wM49S0i+`ZlouMlRqAW@S6|RI%KlPbMk9wgEAwxgfxXHg(%y^bB`qqQcPmN
z$o0PwAl%($A-^sf0LCT@?@nwE_w|f1(mI%k>R8Gm5wP=ppd<d)u^CJRPg>}z$v;*M
zK$}sqG0iV8s)J7glWLhlCGq9!balb(`;e;STMF<4m(ri-D`W@82bLu}C$>(e!j6+E
z_~=$P8vi7Gia6NJ)TDSxeaXJvDA_hAeaE6xKwTMqer?)*NGO?L#8aB?N?bzt2<058
zySr|CpLMQEan|fy^4vTz74$04@unF7Ra+=e!S~BCGwV{vXQ4m-SW#Potr|oGuj_}J
zF^SY}4bxIuhj?H2Szyj*s(S>puiN2@SyTs7nm-86>uihU^42@nsuf3f-LNfN|6OL$
z<W<&_0m{s9r~)%!&L%#P@WDYCKiV-5m!i47I<iUF(@NS5QV&E~ergbEP`b@_JI)nW
z<)2{?vf?6xyW5f7izNV;UoNf^FahLt38Gj9TX?ew^;1upHbYvvhS&&wJBDJxA}T8d
z4X<TcIyC!z(R`Yi*Kr3Qmf|HXJZmsFgORo^lc6}1aj#Ov^(}6-6q(uEXV=hz<xt8B
zflBfQ!i7gkY6i@{&K`|JKATeJy_Q$BVl&Y*oN%WDfnxL!{ww@bP&1X_-_NFhTRl<o
zkRL}}KCdF4aM4O~AJFo-b;0UFygtj(^%q~+Kz#R}?m}kzzm*Jf5XFT^nf?uwF0_bD
zgT9(j?fj)&FTs{;WiK+p0X`n>4tXaxwZ728%})yjay`)!;mI<O+_pf)c)OpVlz%Xr
zal%k+vC&eJ5?1VFASo*y?2-G1?5f)UtfiqvLH|*=e9o>f8F)>ZoLH404hWOK)jB)z
zR3KRhV)Y<2;3zH7IlVSor~C1`TGUHQH{Ajq+h%i0X!$kDbi(*;2l;C0!7*-gmGve~
z<x~F#8_g}+!So*Lk$mmg?H^J~Sx9EE&U?l$X}R-y2n_CIZ}o?(FP2^M-g|%=|B++q
zy~(}`*DS0xm(2y83>|sQasF0V#~w3QXJ;*oF1P1~#ogUN$f{Rech)^B>>wavtK%~$
zj{MD|`*%$LCaxA`={LRN*+j}z*YKZO@YY;5#mErVVpYoxfw#!Tw#(M1oVpWBPw;{E
zKaA-hm>7Sklf4^iQnXU^5V@P0k$C;$?PeuKQOd>HiK{C^TGB+NGA6e~#JjEc>eh_%
z4(||PY#YJO#U}$DmM2Nk1}4oK0GYAIWqJ^m3f~|f-Q}FNp<&mxcL)2tFopW*GjerI
zyYBZLebV9#p?^A)h!$n`=*2()0UfN!9&Z-$583O!V=mQ`5R&#)RX_Tuj4v}j7+MRo
zm>v<@;Es*SXJJF>Qre<dkFtZr_f2uCyLr;y=q-&71SMrZo|%oQ510hEq@l3$tfY&3
zD5vTR91w*f+@(dxze5_FTP!GB<YC7Me9L9nA0sq}r;d^t4`gwaxkhM;9_f)J<RJuF
zQ2LDXTCYnoRtOQwaTm;l#xEVgmXgX>yCkSNAGLZAufrMgkYxPi9g8@lO;F2laQY;Z
zx2wv#^igv9t|fr;>N2=Q<L({{Z4~y0EQ(++RLT5*imIpQCEDx@#|o(!;wYaIjm{SL
zY8---ybct{W9w9$$dss;v_?4~OQ{{fRO!oo1R2zR<IH1eq)FVxMF|Y(__3Py%3b)a
zYd>XYW*Ve1pEr0}cyZl4UFC09grFnl90GO)_4j>8%^iTgIMd=8PRt48d=MHx1z|C_
zkGaK4Gypu_b#(PL4C+l0x@}n~5qQvrb?n+VhkpGG`?Xf+*rD_|pk;C7q(72G18?3b
z*EMnlX=y*UKDIs>%&8fJH-jWMm3@v>74-pVY{YbP-t<xk%o;Unl<7#e)(V+EHmFwb
zlXTi-L$oZ}74cDmekMrUR0;mxN?!N}e3Z_SVyvyd=~EnZDAIld$g%g<cCo6z%HM;W
z*@&U1eq5J<S+|i~uW;I0&h8XyGi7R2K%0#OSv&OY@7H(Vz>;`fX;~`TYr~K!9vpj*
zVvjMDgZaExUT~&dwHnf);Ru&}Z;MgX6Q#|F+gTA?Vw&fK&vpL?1V&&BWF}!w1h0>S
z<SEq^COjv3{|Xy_y3O7}<r7=r#0twpQ&!D7PcB^RfLNO}NUcsdm;KuY<J!F?YVvp}
zN$(>tDL11gg8Yl<t8NNGmkA1FOXzLMR%p%D_M$kctcfeL#vDsMsvaku$QR{w4*!8z
zJnTbR8~LJTLn!Bec!stFy35Z!dqOSFfq_!$q;Xr$?_Of;Gl+7F(i}__T9N7z5n@#q
zjtl8NtY;nicv}$}1D3V>B!6U~*|xsou>6^v2_4fn4acO|I-q9=6j$#K>tHJ+?=4lj
z@<K`8#cuJSMrk9_W*ETRW#CNKs@9fy1|vs2dv41&jDDEsJ`EW&4sNw-u;~kl*~I~2
zUoH=ut#22M?5Ms}R6vs|0a`>Wh(7{2=>X{OHGEvt9XLxj;X6m5Dhy4Y1LP1qUV)|>
zyh3zBr=?yW{FQ*Z>j#u$iEG8xBBct^7|DxdCH6SZ%F*?p_<+a#Uri^>`KdB3jO1Dc
zJ+DW*8mX48UNccZvSUQ}dAom>VsS8MA^V=0F9!U%R9cy%_IZYureOtp=!Bd)ER5ul
z12V`PY)G)6=>Xk7kOjHkCUmgf*|UEy9g~33N?na~Vl|04F{)4ImrM?a^*{}c003dv
z0048|<PnU381Mi90000001l|UiVIP^@-od?Dj>QV$^3kf#3pT8JAGwxwuu6}upIVl
zO)JbJGufL@-pKO|K3<<8{JUZU-emy0wPOG*5nk*EXSqIZDyparsN25k!``XIBoW=2
zB#0Jqpr@Hf0ZcL}bkKjgZo)bqRVQoI5_WFx&xoJwlW?Q34&N?f^rzrX;>!dniK44}
zO=2DD!r}2LSvuuai>Fr*^aljK)0M*z)ETtn>Hf-9gmdWOSG!^)q_^>F@9Mhfq^qp*
z*5A`8dY6eBeA_@Y$Xef8YEo%m`u&97*MyZ#_6J?Cw_+a5RE!X2uA-l86|Mc-AzPai
zBxQ>?6VS`eduG5|6E{i>fgI}K5FYs}HDt&y`paNZGi@*rt>n&{fHvo{MchFDzXm6?
z-(k)%MP!Gy4y~hAwky!nvr9_(g{k2ny`@gE^k}V7tK&itkHN2F$?sWQz@=}_7;u-%
zVR~sQ;rTW#RPs1+>U#P+nE|tt9qejs<L6TG9C_Wc*)Xhq_2wV!u&~Qu%0#2Ww(1YT
zV@~>LrBcycYk(|X?M%xKFZzFCN!)i^f4<vA97KZjVuim4^j!y2K!xFew!M<oQ8%wU
zPZAo^dLcn>yNMm;Pf1doxJgzw^__G$xQ6I<3GV1}W2v3Y3tilyUXOcbE)uLqFRX*~
zpbB>eQ#?qfis09}!oBuD^qem!JIJ5wC6Oklo@-wwguz@m#lzH9G#Y_R4fi+3yhi}K
zq4iTIjCT4A`36a5)~y-;R1Nd@rOyoGy7G-*BmA$aJXh2n4TLfyr-`;7>e5fq3a|6Q
z747touZJwk=^<T`Z=h24fvjo+z#o61%iyA%NO2UiMMgF?jB#|mC!7DEzoY9yH61Jd
z2;e(*J^R^<XD&Qj)zYf`b`}lV@D`Y!+IPXy5yN7kl9G%i^dZRN<|IPjS<YrAFdtOC
zdF|T`3z)cEx%DG*8H9@$MD%DnO@x81C3Nkrq2TXfphi^692`D#o8N%Ge~i1p;`_Dg
z%JXD3w3Ct;4E!sz@dxdXEJLuhVv95RE!2Wl7V54B_4u8Ax}iK#;6^HB<;P>9kRToq
zB(7~srN#<3rGfNJ+`?KY3tLkG1KM=(`rU{g5#oFEdZut&gUh2bhoDue_`ggX)r^9y
zcv$5$$EsA?+lIs%vVTg*4i}Ms!I8a_Px6e>12lYt<Tb4TQWCdmibug%GjN$hd@4ld
zVI>&YbH`v~cnL4s)7Ix&WXc}jn@s{Hv}d99FLV_N;z^&Fj_`#{s5hLC<Cwo)kli08
zN`bwhV#~XZHJ%zqQvzX?F&tOZ*%zqTj6&(roe3`67o5`nMLA#t1v@?2M#_>o*&w8Q
z3=4P{SP@$`Pz}9AyCd>@B9RO5pMNPw&gnq1`=uA=sBeUV&XXOl%tGq<t`Jw{$HZV0
zv7Mvrgk_D<jeJOK$!>sn1xYE*v1vrxTHXzi1#RI7vQ*~}qHlwizv!532pVb$F-x2r
z(CMStDwFl=8K89?`hDZq@`-0;ZQKU~3R}F8<a{|Ga*xmg>|nN`EE_&))wZfvO;wG$
zEC5Tv$VpM4x#GH}Mykb&9=3Il<!E!J%%3r;KUr=<QdW0IgHo*?pB9P!^YNhvupu0O
z^!7r3D53Us=x;qBJMTpE+X%;XvwRq`u8YkvbJPYwR1<G1t6*R}8UdaepnUt3ukJa{
zW7^mVFiP$AYErY4rZ*TZEOP(h3J}p>;2y?DU%1QffCSTKi`WD>GgK^D{`Lm>p`gHF
z<9r+riDj{upQ>g1*J0p}mHrhGL~M{v2jG1_?*0tQ>EC7dh}JU<sq@#!RXu=Tg)H{_
zShy&p`3pq1DaB~Rc2$lSed&CKH|Bj>UJgkBv~3VXnZyp2#Bs58|FZ!OrNbBga396Z
zQifzdME#8)cMs-*)msmzij)(lrX9B9O;M~?CMl-<6CtcVXo|8Ae_;r|7#-4YA~n#m
z?hzqg^#zd-VTd^rF?uf1%B4bXUnC<c!k`5oIXBev&xW3NViB*fi?q!D8G{A9gnK$d
z+}s9t@71050o8!i=zQ|Gjm{`tCI$0;uXp*g#YyTo=ZHICe&I0S#<izX{K5_TLOJ2#
z5B=-GpN0RW@g5Hnj!F0-oyZG1YBNUokZ5^9ca`7ATS#tUy0!5=>rwG#m8a>QB^yVG
z{`Q*YW--rXsEce~TljZfBk=*##Yy)89OEQv&Htd;#i0ihnRnx}jP1{k9Fvm40$sGB
zB5ZA??OP5|rUEweIkHHL*%LygT5(_I|IB6MxSRiP%9MMX1U#i{0l@z8&p0RH`$?;^
zDT?nXkWI;X9Xt&$PUwfe!10{(gc?YDbCKhJ^tBWpkI9FDAk_A1Xli1}gsnpUzUToK
zXPe+-%~b>pqYQ0~_>e4gvvaU@__;&v(h7}=wtj4jC1`Q(SXR1TS8@%IwX%suVretY
zxr=-EQ+}k+8{?FsBNU^w6Rjg=6m4NPV2S$RLIX-J=C;Eib(@UZ>AfzU+BMG#;$Q<r
z*ScU+Pl2>6mAX~0$Q)gwgsjc-*vV84OsXYM=JkGowPx)l0(^~`t4LOkkJmuhP*K*1
z%VyNxpr%d?`ubzeDi#X^?yN1vG3HTflt_N=sS;5p9>e=BWg@}3xa3IK{W@j`)5dAH
zd~gRC#esl>pSBMJ-y(3Uf;I@VC5Iw2m7x0k*kkOVXw=ZCV)Q}-oW;4fMhGm_9C7nS
z8q8#y)JdwWHUu!<8GgmEUam9i{>cBpo|ZPORp{$V5P(6Xq0T|P_eAV9lp7V#i7qTZ
zZ(8@+)a8)p{qI>=^KF1zK|Ayr<{cB886WWN<DAh;a}6i^kh$`y5Bi?HoDEe^7ow5>
z$%2IUe-m>#49If9BVR;gxpvOH1iOPYk7v>dYDaZh2!Sg8AM<5N`XmtsaT$P+a)te{
zBMcO$YU=+5hOCYTjC7%q^^rm1!}xYY)}0Eahe2KL(B*S9t!iO0B}tw*ZG21z+2)9b
z=g5d@M~?~|OgV@)HHO20)OgfB&7TIZLX7N9r_hLV5Du+)4V0Oq=e3vVgwDBYFNQ4y
z(X_)2X~8JGlgG$Qxo!wTD9Cdu8pel$ivC2*BnQ+z5Z*RFq+6(u)BBn$RcZ(_o=Sac
zl^qEnmp^bi=^CvRjtaQr|0HRNg%{4C;B3<9`JHxtKW{Z&fV4Pu;dI@G=2ytem2=~(
zcqgZ-Q~H**NkxDoK`(#&8Q7f+sg|jN>Bw5#I{<k)HdJ&4WcNpeO}Z&SHY!l&S71%T
zy*r>muq!SAu60!A(bq6cYa3Hd!Af@yWal+BDc`R0$Xph2=*);@jboxI(hsvZkY7Y+
zWU#A3Ym9LdpT9TV%)B!UUL6BUr%mm~aLHmP53#tUg?UrV8bw+Q;b8VeVb9P1N`UWu
zFvi9n5<79zsm=DELXa!bJM|D{rpk&@=tJZg78F}QZPdKX)znpwKWXe~<09OgZ&I#v
z6BCk;c1oxhP&r13)SbC}pGo$)0cMPglK=wZhE==hKbdJX&y{fGqBZZ)nk{2?OlLe_
z&4Vi9;GcD#@wFAnK5PZpZ@=pR(*3x*MlYeaT42+*-K?ABOg2OcqM%L38Hqr1t4f$l
zUIGYC5V*6Igcn2>GDc+|%2IHV@E)bE&qAI6fHJ|v!|)Z-xLcFP7b#phVQ>2wdXmDs
zj=|MKOx}K-eJGVwAjcr@kdWZgyuzL(RWM#+KX>S3^X7A^x_uW(dy}NQOgE)|df4#!
z6cjUTgFa2HrZIA-Uck<5n6(yJDz^t64d8zkPXbtnEC<tFoR!XnJWB$Z{J=|U5<80J
zafoRA->Xs*izHS%9U-Q5wSUaVIi#Y|kAS{Db7vm^0_<5k$pI&QH2B@byBIZn!QnUs
z%P7}vr-Yc1;=F_9OmX9pugn0{<k;2~uIuHOB+s>_$!2<@pY#N-1t2Z_Q2cGV6g4hi
zfBCD=!w2Abfp=^+d*e@smmrhCt^t&DDS0-$14EDmoS^p$^iGppLyPj$4|{k;z5qpu
zmj*e4eT1v(U+#_u#%;J-{|i3Rjl#m)WaKlfT8kWM3C6e~FYv4tP%DT<8JiOY>4=VP
zgni07KJaKRJ+h$Ch5?Mi;zSyhFfb~Znl+-vVF>-1TGyqGwDf{caS;MDvi7>GqSX>$
zF2?|rpZGW+qem9LLR*A(VfbD}mqQB?DY3+XoOZVImy}yZ4m_1@C&lpQ2jH@<1W6X@
zB?XcI000;Wpb;?uApzwwf9Qn4hz4v7YzsgGz5u@f1}1TPnJ@RBln$(VZ>DPAsV|4t
zr52#KIxjb$Iw61|g|pYrp)>{XSscJT%rRW5#2qECwos{eQUbs4xu>Kp|7||$KuZ{B
z*S58&^WTC7YZfQAtNWbw45F`;_?A2$fj*>nKy?MPliR`?b8G~E!<4`t?c?h!bEmBN
z2TYwqR6u!lKQ9`Fpy8k;vj5b93!R%gj#~6FEDsQ$f`kycj$%zBl{z$a?M;)+moVIQ
z@~sGrigwKl43@z=)kLwGC3j>6$bNKdOP_8vvQ#iQb6OMu>D<3zQH^Pwt=an-6D3AG
ztzeNZ%Et?GXRy)?rTvzxe(3ey3YF*XW@2629{SNBa@`d(E-K<g4V4rW!gNHoU)^da
z*)_>m4&DER8+@kHG_`zllzL8rpZ|Rm=epKKfT6~;GA75MtFtcvF+k40A-Pf7Y0{0;
zMi9BBoDO~W34Z*h0}~#K5;3M#$+|ieU(SjC10sqRbE;4;E+T=g|M=V!eY)l9UH4I(
zf-a!`qBF$x#*FE+SLOgmzLKz5eYgxS*n6JVennAtg{H$-ks~U9YSg>!y1v)3UspOY
zqM^&%{P5o8&d^+iX7XLV-8p%IoRq(|W+Q!Tr9gf&@|MVa(16HAS78yxbQqZ?z}Kds
zNZTRL-Ug}Oxr^T7jg}GP5=4Sf)(aTlsTeeG*0$6XB$-MS=TF@e+!jy1-y{u(vs`-P
zz?9bd0tOn)Y+W@#uOo^iklp0?A}#GV+854)ajTDd7%)T(*Mb*6i~2u<4_8$3pgWfY
zsX*EDXILbjc^A&1Z~@7m)fN>8W({|0N!w8I4(sLSzwpXAV?lltXvf*Y_qp-R-eA?i
z)5-rbc&@9@s5p)U!KwLD=@R<*f!?hHg~PzyST9}2HLP;gLCmtMJFO=kTlnk+qThl7
zE9I8n>uA_y2_SQN@y${m`Kl$|l1x8QeO94JFC#rcr{{UD<DJF}2?SnBuW4Zqv#lq2
z*@Lk!tx~yc!rd;gyAuXND0bT0gx7dzZZ7}~JQ96WZ3tr_miLRfK~){twopC3Ddsv$
zdQt}qi<TdL77new@kr};N~J*Co<c)su2vF6VC^Whou_7%p&`89gnZ?8^z|npoD3h8
zB-pd>LzZR%LbK$5;mdtlWOCqp-X?^Hm{a?1D#B4?Zz1$KL*#H9Nke}J<Fp=(f?Q$u
z3-8y0im#aAnie<QE?QOU>_VbrP!T{U0=gJp<-l3D>z1`r?>5BdX!8qKoKfN0>JjOn
z!4*Gj3aWo2E|=E171u0UA#Wdt5m&9NSU*Wx6`0sg`r_Y_VGTl{m*W_nZKfT!6T25G
z-he{qqCIA?nIDGEWhVnNA>AE|6|KP!U)eL8Sp{;Va?r1A9fZ@V`E*7P<xOe30Sess
z>>vdh+N0z+WWf9Q?nx<K5Kqo#5Z?BqNdWzII803qvZtFt_<)wI)P+YiQlE>`FAruI
zUArOXauF3<wlR`PX^j%}kXN#7&R$?x8wqcR#R;(!OOryvrcse-=IyaL^Z=rS<9mxK
z=~15}=%fMb#f}05EDwm?-lK@=6D-(QU+8#T%fDpHaL5SkG(Iewb(F%12k2f9pB>US
z-%QEldPN$q0KtCyINtJwZjjJv2?HG~IQFLY<JW)~s!f1gh1am`v5)RAwhl3kThLl-
zAUI(tx!ovikx!PHgU`X465_4<#r}YRgl9{JbdpHD;GRnaC;=VCOc4c0YceSq#ChH_
z+3ef3fT{iu)Jqs4|2tMRg%0x*KrH4wJ3PK%oqdN%!va*198I_3g+vJRE<Ht>1@{>P
z*a*xT9feF=-WLGg!Vio18s+J`P6;p|d^A3FkCi!cqxNg3oO3~a2{6$rAH}g|a)x9?
z4TiKS%XX4^;s>cdV_91*oE~#>m2VvhA=9*le$$ucj=Vr(05jY-C;Q|?_oL_}^MhLo
zr3ttKmY<~N96l`}v8QY>jN?}fu=D6=_lVtU$rf-LdTN&Ph4)~B72W9qklA0{Y&L@A
zS_=Pa^87B;kYnq5ycdwM8Lv1uF?0}-x_YWr^D6Uxwc5r_j5F)R)VZSQN&JH=7bz}>
zJ@U@-jiR?xfmx73RPtz+2(|>9U!{->4~7D47EQ!OasPMIBlEeBNhkRY;!{|`=AzTh
zdC68!_0$?`smT9@`F5l4tX=lTv;~F`b+<)BEzT$VqX14;jEZsRJ{ffb77odCve8e0
z`1GVljrrv50n@9j0U07lacOL2KP*Z&rhHad{RxUi8NIb>j7_PcAbBKWs&aZ^3bcqW
zk#LweNv69(xq7JX#KougNo;>R6_C0V0$yHK9@tzpOWM#UFus`snLelT-im7Gk^<m?
z5~-a|j6$fD30nUC9+%IDZLh0HzXuoK&g)vUmsIlG)T_ueHeHYWsru`0cYF!$^k4Ic
z-ANxVT<+(Ye!JD7AFRj9rFvi{8s)R&Zl2Ka*tfBb<dqLO&_Li!_NN@>m`&1^Ke|bU
zlmoBfYnlz$HQcn8S5S*y?>Xmn2~WN6cN8{ODz2?nahyJ*KM7I($dck99^2N!5yNr<
zlITt@y0t*@CayS9^AFA}416TH;r^t?@Dje;%y$e7lQ2hfQr32KsEsW>^fLChJ=cJ!
zG#icrdDzvItDv)t+0`(!99x7xdzFP@(!4<RLF){7Z*kl9;HN)zMwCl<==aJ;&g&1l
z4MYd>ht~Usd-bmyYzx!inHgqlb*X-qbnyoL_5z>q9?Kl?huc5{(`|!{$eja8Ixs&t
zVxTnsi+DJxq27gN=$XR|ugGa9|8=I^>5Mrp^$&f=*jg?3qvxZo@KcxT*;ur5ZhuU?
zP<=Uv`1RNg6(zrXy@y>YT0L;Kwtlc<^bqFIHjD=a54^*YEze2!@*KGoNsc2)6-sVB
z7zug8QOuT;B#1FCZ+?<%FYsmGfNv-Nc8r)We%I}CbP3i9o>Nd-?@M6tLUV#vkuYz$
z0tkt%EIJdCdpd7U)Q}?bwDIIT=|SWh&hAVVQ~1AussL%m(Ny48_6Cm2J6q~$vy^QR
zX{WY0@P^uMg~qy=z9?MW_tyP(CH8EN017&>n>3Oz%khateq4mhfBHw<Q_YPg6;Qj0
zcvM2%@jw`^ofKehpjB#^CM)o2rxE_7m5t^MoLO>8Wb<*`!c<`ZU6wO631R_2Is-R`
zw$coIhcec&21c`Tf3=zS7uGFe+GZHK+Nv>1RN+lpL;PMRN~mb!wh<_=bw{#dG_R{^
zJkC>^;ENbnVLlj;6_d}rMonEAM#b<YK8Rcd6;5S?q+0KIM%XT)mgTh<g>gka3>)C!
z7`bvpE@8HmR{<#PNm$UyHLzW|fVfEq;Ht3Em6n6vaRmWE7B?U8CkIF=L#kgg8MJas
z8o@s3*=OJf4;TO`OHH~r+i)G3L~1RdBqgbtFdD453Ghe-L0Dhg4U-wC1F6G@hLc&i
z+IrXGA)O&@l3l10H-*0cU0`7F&0;<zn+{7*I(GvJ)9ayHZ4)uM^m3Rh6LGM0)_9FC
zyg!Ye;VXl@%r|)n;4!5UPr#6KVSdlV+Dhh;ejNZAc5Xqid!Fpt$$RL`Jb~R(a9G(?
z`QRZjHFPQ_K7leZ>BBsFR^Bu2&q6xQ^yI5u7n{848!gG{INAV4X(kyrZH&Zeq>A~)
zV%57)-jVsjeEN39_0ai8>VXYisq=7DF+I+t5|I3iq#i#WokwcFwVW){Pm<OW!JUEl
z?PWs;HMgY8obh`KM{Kq;E|9u#19ay6@i#j`04C7&z`iWm?!TWjNP1=95Bh?h(4rJM
zwPm(TbZ3JLCgaLay6BxcOfKXF#!2DTcu91ZoOyY5iC9$pW26k{VdZ9)7-yI5D;764
zlB_7cl6LG9D#atg9<l{@o7;=G6Spumv-mrZA(YLr>5%39Y=RpnMHujviUIu|j$+T|
zURpsp!ki(jn0C@!?@)Afi~miTEHtwNlO=(W!=8&<i*VbUNc^CL8!qN{Q6+v9KX!G+
zfy9!ntR#;KU=hAGHXL;(5JMC|mQjhXFxRjkZNaT}FM}VF87La^OX(>%Q<n+!#`3wz
zD{A{2PCu$yl580KC?LQSDq~;(?PLG}If4P;Nt(cH`d6eml?7$d@BoRva8hMR0000Y
z6@#7QmgDd?nOP2!rf+^*=eGL+J~u=XKwRRC_`0#jqbZ5z`m>WYIIiRaGS|hN-k(B5
zA~=7N72V$F*z==yIWxLQblf}4trF!2W4)i>FhLO1=>+PxP%lFYr}j)@{U!X*;-hQz
zP9IQ-`p67^`f+)sxQWPJJ^EF5jr#IdzUxl(zm$+M;i&5EyT|WQg2IdgWQ*#L)G%1&
zDsdCA3h9ixz@spwMs)`ezjcU0!P^V_&DZUXg1NkQ(VzQz6PE{l#k~C@jf-gB-jry~
znPMmbj?zYGA;X^H=7hri8eT#n1Wdk0evwk*vb3MYmuf2GZyLb+JR?BUkFS*A5k{hx
z@24oR6HXm}Gu<|5RZWi{RKZOl+~8hG(xEuLbqqAdJqn@86G;)p+tM3>SW0w0!AbTw
zMK+oU0pNi$QrMVhFnfO43Ur=<%5;;pv)y36VKMB32j1W{Ht+aT%=}#Kzdr_+?1ql>
zN7Jx4REO)m6_8Va5$doR`AJE}mCcT_xdtAXLtFCwdcpT5iHuHv+%!|60#z!E@ZoYZ
zhLh_ZdI^^fR)s!}C$*K(`$7g(iog2Otj<VQHIA<X$eL%iS7enuPV?JO<Dbr*sA<Cc
zO6?pqz$24uwLEvXkhg;QuE|{q4xkmB?L0$>(iqrDVu$oI<CuSY+Xq+04YIOW-Q@Q=
z5sh$<tvxCP)YN>RJikV00s|}ag)D`9T&!oap5segWCA8Yx9zG_m|2+|ph6f?)OA)f
zA91n`J7@ie$2J2$eYX)U`;2Stnaf6C7F>?FQ%MS*mDVw?-XVHsuXY19ERRvrxM?E2
zrcv`nTtsNJw3^N0FTkMvA4t;EoT;u<=c~*9rI!1&JsPy@qQnM(4U%cwr_hI?<(1xr
zCP2gG;07`UD}IOkG8^$*UHdIzC7<(M(2l;=TXQZ1n>&M*XU{2OpjOAcvNeW0#f6+G
zfl3Y2U&hH!`|Z+SpcCyY^;&!JNU9n<<WcH+Z|<z_$htb_I;ZT`IDx`3EEH%36}DK7
zN+TyS-WbtD&}nhgkoRAd>Dr_^ts{C>Qi!YCl>7y!&?fVb9guF^gfP}A<pI(wtyQ`S
zcB%XI${+H`>9UKimB^JXhEMcyP0hrzyFPKt2qRry8ZB_1mF8n&Ui+B@+K7`<EjdAf
zkH={<KunyO?Z9Z1G!`O(q=J7{$sY;vmKHWm6KE}#TgVVF&J2SWw{H>i!eu8!&kRiA
zuoYMcKo8xZYQf*?KtGecH1xy_C(cGT@%XufB~`vH3vYLVc`bfGzSkF%ue4CQ25IO#
zr25Ied<P@=uKl?7G_=HBA3!CJxV1$-xr*4L<Ajnq^9DV&{1qnyS>+RvKPV|R)JXLL
z`BME9K=m9%V!K-+DMjvv@fL#s16(u9AtN+&jWg0E6fp|IYhsb3T*qWo>belx$qPXA
zM)^&thjeek`|~8`xi2c?|Db$hx8Rvlwn)>lpOl36*ib<@O)mRoa^sZ~j?>QQ6Okpv
zFu&*?5C*kmrZ13xv)y*MsJp<?5P)`732>eeXO42N+m49AB;OUC$2M7^O~=xPg1csg
zsMeT0Q%RsIFqp0-5l1IbV}x8%Nb}8;pe_t91Ty2ss4d5bcza~QFR@*^IBiXKwaZqw
z$x@-9u;Ku%b5^%+DCqb<a%eyuceXW?y11rHQS%X!)<uUj&kyqw5q{lkINnl3uJ3Sj
zuKG=lGf~a&E>x%nQ_&aKYJm;moNb{g%@b+{m$0%Prk>Mlzv|GC?~;@0)yBh+qKDXB
zFFy<udu+4BY7%|J)%@ntC-=amMu0zSk(u_by!PTo@5#N(Adv2cRg8)w_wO_|hrz2n
z))2cUfVt)K&2|~V_M!33wy;QCJcQcEGAwn4!Ah(y6`dfJKUVgqqw?SIPeVT$^YE?x
z_Kt^d>srnj24}p|{r)O`X0)~xg7+O`PE{N$FE=;r_#PtR5|m^l5)v9O5P~oR<{V7)
zz^<0vw~!EgbZ#Ge93`P9ckl~h(>KoIv3^0QHhZ6+X5BPaWJTmQ0zeohd*(mZdtMd-
zFAxoUOiaDsIp$o$j`j<&4B53c8&?B|oXZuTNb9Vdf?+LL)zTEEF|yI0#r$&TJ8bN+
z&z27GcM*@VuFa9op~8EpB=fmDWew++Z4nVDj}-{KG|EL-{AAK)fCBqng+j984w7J_
zN4Ku;Vf1fKtm=b;4+vnV06;T0-Tl;l8!)7ImiF-@uZHBbNl0Hn6lw4`{HP@!$1vKu
zl$&=fV*$|e*rZv~9<?t~z;AJ8X-I?*9QbGZrHx!YQ|v+u4nk))L>XTPHcjZRC<8hk
z0Mllc<^+GW!+uYA8xL_Z5R5_w4W=;KFHJ@U>J7a_H^@e^=hwsGk3S;p)2Q%VYA|vN
z-Z0>om_T_Elr^0t`8iDVeb}+k5@f24=V@y?BWw$*7-!apyVmPJxs`87`CXv9Crzgz
zqEnOJXR2gqht%E=_Te*jhP}XwBYBi5ni34E&rUN>=xTAvNJ2iuwe=HHXl-yr;SuW^
zSf<>cEsI&yJa|y(;-O7+(q@K_Tn#H#dt}mF6^6NQ(BBDfV`yh#QJC~09jsHkRj<;V
z6G62}Xm*q>m#XqA?mG=ng$xEJ##H76CNZko=^$6F<SfvZjtT$FKD}e36GS4v`HUVu
z2Kwfs>!>z`^u~}ds21QtKhYPoil8eKpvxd~v$*xJ4HS6<N=Q$`NvL+(A?F?W;UMof
z;1;u^RXnFAte}=xxk4*kdgghJ{i3KMM-Y@+XngNEQJXh-;V5#t7Ihh(<Kt0#>4UIo
zio0qKCErO=9gk?8oBd;(t^*!sn&y{}@rmUHqOtRZfnkXy+SB8U89ho#-8Qa1uQ>o?
zzE)(^vj8Q<&{G%^V(3i(&J>xlO=^GpRCpqpE+wA7y7G}T|Cc^c6D%PT3el}Ct-@&Z
zJLV5?o2NK~Wc!}2X=B5bu<e<O$7WMMSC0HFPbkO}Q=r3%>Q7}_bi!p63CC_oPIoZw
zs}IdOSNDfyF?hMEBJ|Zsq?&WgXp-Ap2AH^$PPIr=l8u|Rx}=(IobFhI5^4a1;+@7a
zeT3{Ll=MG?OVk|3rbtZ;FnAkY(^nTC;^aLA&h`Sm<{{~nOwhkh3%!*-s21zau}o*d
zu6M~@Ohd|o`n<5Wu9@hjhTZxe%^;xj((>VChM<R;3Xbi$w`dxEi*hD6x1v1-N@paa
zdKlq+0QL3YG=O$uKXZ_M2@c_VY_IR5(87o??VhYq7Wn8s^o+_*9|)2PwJlPTo+P+v
zzC6Qlw0cQWBB)aoSizo0omcp>gsXt%>bS@nY5!W3v7MOVmw`NK?y-LZgHc+BpcuSq
zMER)K5(#t0&(9G3yD)(koOKTtC1aMY@7V3*v3jq`7NhT5{9W!yoVXH2l&cRn`GVF0
z){vCuw0(XNT`xzQ;Fx$>q&rHYD4fPcXkFLD#vRy_7C1lxL0b}%r0|>fylabOE_T@f
zuxj(eueu~aOP}^xOLr7vLHe<W=SN)>cev2PDOCRVmA(RG#CiZj0zyyz{XD_sK_zX&
zG)!y<J#gBML9&}xVV|3ljdsPPZeApnHcsnBaSjWI5)iWu0Pm;AajgbB2&-7GMwolp
zLJ#zwX}I^2ez$)&N9^F}#dnG=omy8AZ*?13z)S9?LbZXalfVE(4N$VJg2!6X{xPyM
zSfvUJi2*7``Ag!}%2APc-KngPcglJ#L*#~AzwRp4P<|2=o^pD?Wgc`%AjD(iw%a8F
z3Rw*%nNsAJE*g)H2^I;f#LwGo1rpm2R}x~YUw1S6Bw2gswqA}oue(C-UEvaxk$ZRA
zYY}!bwT>|elSMPBCw*}RM(%0uMG<+(c?6VndFVu#Hhe;&gjUK#d(wdEtMwkJ*g+(3
z5!__wfN&L6(MY+&Ge7x=p18+Wps^h89m`tGz^gFSIGo>W4v9Ay_LlZ{2$~ZLjE~4L
zsZN-s%UtGb>w8#2bN31o{G8@UNK_FJt@lS!BD?A5;?=*)M(??)L2l@-5!C<>s#O;K
z9VhU(!=y)@9(W|gsUV%yjYOE(fIRktdcRaW(_VXK|81Dy4nFi?Ry~JO$%U!F5aq_l
z1x8|>eUND{{}*<jstiP)q1wHADMMo<HGNL38=Z?zLV##RD8i7QTy}HDpbM8rL&fr@
z?HF?3&U;gg2K(}-33fFLzb(O$HtSqO4B$^=hnY1qGdiF6;24-tx2$#AMnh<-K~G`2
z><GY66e;;Z28kOLA--}=)E|U!2+QGL*C@#1NW5e``m}yQ6dvSM%D>jN7awSdCkxjq
z1OTTlk$uo3@mS`xJ!A{i=~tD&06~xd0000036{VB0VXX?8o3&!3>$J4>IPTw#Q+s?
zsJZ=^->|1lf05OzDJe>9&yXqVq5I!KIezQ)(R;@QdtOD=>n>h0s|C5%VurUug2~zn
zv+gXtNIr5Dnhn%9Bi9^h3x7yerH#jNE(vvdx1F>P;-{nbBn-SLaM_hJ45x?{=Ff2w
zuwm)4epC_?(n9}y67#V;-(CVRFoxHSNg-vG(!^Z8l5~{eSDIzAu;;J`4;;W}4~+%k
zy+Bpyr2$@BB(0kV32#&_4$NVEf~g0i3|32k%XnvSqK$A$=qo=tcVDZk;2R!Tbc~O%
z>P?u|r6V&vkt|nc&Y2jxD%Q2I2CD_uc6frOSJd36f>+1+*`w5Cho~U7^eh>POn+y>
zPLmO=EHoW1gOXC=Ivm=3QTcl$PcKhwVbR6EgM6W@8i1qXrRN5$<Q>Il#?Y{u%W%U7
z0wd|B)i7Gyku0RBr<dfw;@$TWuWjG*yyhDmPZ_*$e3;A?|F?nt(CS~Ye14~IBsnyn
zO`o?-&-KoL*>f>FM&W2Dazf)?)%(A-H5?!SYpWupyhPu;_xEX&c*!T9G><B(Kq8xy
zX?5BL#%LRdYfUBLf>}z^=}2&U#YP2g$glgKdxgWQkM~6>!q=e<L0(&~Dw|RY9Gbqm
zev%|bj^!)<UlO+%5KuRf5#Etv??C?njA=rJ*!87YwY?pJ7xP?Yy6kAqz}OOFtv(mz
z(lRA_8<+4oI9a~WbVnzPF{q&^Qd{?0oeP9Wg+#C%cMTAxXz-FfN${zxS$`Q}&`*q2
zpdjO~t37wyS=U<bnkb3K1mtN}s{&VD9p;zW5f-R;!nM|HXGJH2rrcs3#5=eBiIo2C
zo*OpenP};zE!Tbw6z0N2>s2Qpyc=SkM45+&C<`VE&&E!T_^I2v{bnoNck>^-nHXB)
zN|N6sEg(R5eF;h@-ey;o`N2OWelMXRZiVvAOX|!;j}=WTQ?$oNrc*ADNnD*tCE%$3
z#>>#^C}p`?heVd6*8+u+TD4ILG8n1&fN{arwgv;k#9Tu1tk)28i(CSeMf{229LQsQ
zVqQmvlL2)iftWPx@R2K`mjuq1xtQ{9lg@D8PE1n(WTHUaf9&03*}3E;xdf!o^>5HT
z!lXwfEXi>Ff=W>OsTpI_8V-uVTFxHXto=--VX28O_c-;l9#d2lTa*mW5K6{w^}qX!
zUC8UZ^NQ7g+6uZZ^;8eAgt#^y>$eB|VxTTE$nVsz5MD_~b>38)%DQVE_6AWCAOW?-
zt#cxf757S2vE6=RlKU&6yVX28M4r7}s@JK=Md4R|Tg~2^pl`Bbs8Bg0E3vz?1{E;r
zt2R+Zq7!s*E{wo&YVSbW+QeZLC}afs^p)p@7Y2ZSC|Wn#+dkLD4-mN10Ylof^N(5(
zKn_FFd4$8#O`EOW-+%+s^|luIi72>=T$~|8C*eSEbUBr_TynUAQ#?#)4ji?t@xbXV
z)q+?Q{XWS5pu%DyK6{|*@G-CYcVk^9?|>6O;H7aGlJmDs<gW0a7W-Oi;X48cAg%cn
z44xEJ;lC<&!9tzjbydjTY3HP8{xY-vK;W|ZEdYvYWdKB{m#VJzfv4Leiq2;i`#co~
zK<1JCFS`wxWfX9<e9Tnh6|rF%?tj9Ppo7{oX@uP9wzsTL(=u`SlH%(#tJs|yN?#Ec
zHrCgw=r*z=GXDZ;p~Dd2cqXLBf*?lQM;o4SPTpZH+MYkWGAtdW?H7M9E{0|20nwL=
z#ss7LeOWh}<&s?hSz4`M<7=O|PwzDrOCWZOlEr82Z7vs#O!PZ2*UPM@#@@g2Q>8TM
zIq)Xt1LU`!l1~#~kDg9GsX>ZA;Rm4R-(^p9nm<Xs(G5V|6ioB5d%Ag}<>ao<yAJP0
z_!b2a95EZnh*IT5A_!!N>LCB#aC4MtS5W~j$|jLB$9UpFG@wjhe)$$cN*k}U=2bo~
zm)XutX@U6DAEXT7Z(cbP&Ws&Sx}LkO$x=1Q7$}%jya@Qwf9TObw03aUJ*`J>Xyykj
zm6T8xN!R;Vv=|yNntS7$@*v8DUPE1t&MNB31>Y*{;!W13JtwKH*VZhU5H+$SVKxZf
z^D0@>06dd(6YXJREzVF_sIzo~xl{~R_;<N0Ui752{Gl7RI^n<dCQWumZda8%>;S#6
zsG$@y9^?|zPHVl?wC}c7JXOyw8L(OcJ~oka*;N^<y4O@8F}yElWIJX5vG(`YMip*Y
zcR{GK{+da7_!4g^h*!pD)Zw4^uiVU`-Q#3fkxwnlYLuxkur4F6u+NGcN(A(t$<=z=
zoT633AO|;wV((J>@F<}2N;XewwOi5l_kuFP4(g3?pB`Ow-bbLGK<H3}lC)`P3Dhvi
z0<ODG`B$BEAtV{~d}Ib`5DxLWg=2w3$TvR7kNz)h695D0Uu6HRrs|OcPh}d2y7T)e
za~T|SRV8yL|1M~y6lvRJgyE4(mC!FCe!JOJs$;7EgIU#a?Uof8Jzb9t35O;<!-eUy
zRZEYry87MT%gF;VA?%UajPOAK@Mh-InAU{>vm`zJ*~!_1>T-qz5mo2)7oG2UnugS>
z?xrfh=5p3pZar42oMl!owhIx<2O2Xigce~!UPIe{NbC?+<&uM&7KT&Fx<gx!u_=};
zX!$(4tNNtX+DW{+ux#SeD0)ZvGH$sHe8D3l1N(AIJ$y_!v=X6P%k_D!;;oD-5q8gM
zF6}MGaEc%JZYFrOxAg|oVD#>{d*a%rn3#bdE$TZ$L}8!pG{72ioSZ}AU)ufIiT-cE
zdxDuX%m=}hDA)o7(t*Z*HCuAhrw=lf;CI}D0}S$^9(1z0JEXEM_=k*xC*plzRNiA|
zU_+wO!qL}f8tzwZ(o}=yptcuf|3;i)4wcW^e$V*CM-*w%J>H2qgTEtw+me=09Zt>?
zV&b~OKM--ommlPu>vDXw;P<h6;c2qG7FTNw4LC|fo)mw!pPhZ2g0rA5bkxk5Xjv%D
z+Yf`!3327H2M7!3DDGF|LCHn?3L40^pbt0JXUb@k1t#N#2f;!Qqjf4rx_Uac28_<f
zct|c4I(vdbRCNkm?Di_X5=?=pL}U6SUG|?lZ`q5^DU?{PrQ7fK6-Ra#Yim(cY9j@f
z4oeHy+NcY4KHFifgPl{>z_JS0s`m=e60>GFx7H%R$oaET14Q{yG;h=WHRGHH{cydK
zun^y^ZS);RAKF6v4}y$lx0MVfn|mZMkxWkZ-(U7o9-|mppAk^fmJr|9nqQ)nMbAIi
zb2sC(wksKXLgf_Eg-^2#JQ829Tw|y_0;L}4(?KV+D)*P;!YtcnfJPl!D#0*dp(5V+
zKT;>VY-5q@2u|(q>f(JWsvZT7L~5iwsEzwz$Sqw0qz>AFL_Dc4^NU=m@*0Lm*pO4V
zR8j2DmxSSjS|q#u6EpnIUcoSW{KPgMv%?@aBplIx-+G-$kQ8mPPQDQhBogosTB9-J
z@rC2Ka>ZbB6+^N$*bz&TCoqOK`{%`zk?>@>347y02dqgcL%jX|dG>oi$XE`=8;HAI
z&H<$Z4k^|$Ods)rHJ#KyVmD6MyX0YH(Q$Y{YYDxr-ijuyU_}W9rQ-yyFd<n!IPiU`
zjDgAG8y*v_^uFi+0q~<el%E{7tn!@4|K|MRs{?3dn_O(|ro#`ow$PEv8UpNpv5nY_
z`EExGX{8~OPa6oLMBM88Bf(K)^xc<Uf9{vfqno$N$=r#76VmgS4aKZg5V%tfeuiP!
ziL%>14@MU66_)?I(ejw<M@|@~c^LKfdx-RiXxLZ}mdOS!gU4)@jq=mvoF&j8xR-dz
zi#KwquA!lRDb<0?d<N0}0ZEJ|u3nVO^{QWKA1DdnTp!RvyEoTaUM(Bf;Xh7(gTo-w
zaG=Xt>uPM(^UZ1-W0t76u{$FxQ^KxK%l}7<1E8(KP=V-kLs0b=$;dtkJ9N?}Uy4-m
z?)Q$c!PRm^@m-^`X<SYI)XEQ%?LHAI`XUsQN#&v3O9eEKEZgPCQ-(`S|3NP^Mrc&c
z%@nRaiMWja=>h{T40UdR(C>}+wy2uKOYtwC-GST&qK57vf9Jn>&zDIo7gDt;X{k|e
zf1_yrnHQ7hh|Mv>G`}U>9v<r_3}lnW3NX|omMd==eR6a<!OuoNpT@p-cf{+=VdclX
zjdl1qZkgwsXK}xSA|hYi^ODCf?V|$7AI*lFS@hlD_NtmJ^9~hH0Xm-p66K<3j~>>>
zW5h|J2oSV_>;S76)<(XEiCSWgr_a4`A`kU9qz#WgD><~=s{sg7+CB-IY02Q8AtUlQ
zD9JK_&VuldI7=!eOU{wnzw!1;0wFus_J9MX0E6%vJoEx`0*?RyD!?IePyi$o3!w?d
zC(-O0<Xhcb)2~RsuAnbC-rCN{pO^qU{%k*Lnmsb7Sxb{soza_x64)-hrB0b9i6lx3
zsKEF`Ir}L9e?BNrAGy)vN_j3TrVc)<tpWe?j+YHADfFv|WlHgW+cj?MiI-~8K40+8
zoYC&iacgz>aRw<sADv>k3)Wfy5P(47y^IlgoSp_PH6}((^!%DJH4VO51>uLQXhX?8
z5&jKPqc@J8Dg~({L9CyKwK`wv^C#fC>J(=5*d_fMS+}zUGAu|q3<I>%zb6qix^pYi
zc){0AQfSW%{-UU#Q993p=ZGM9L0EE&*r24ij(pvtzS4>wcrM;g$rDyd9m{AT4H6S~
z(g9%GnAX_(60<#RYn<BgmR-b0h5HwZK&dFJ{9^6Q(if@56Mz^Do2a+xGk}8v+fF`p
zDXTMLg7#=ZY%}Rw0BlGxITd}qekp0z`QDdsOlhH2OEDXeh1`_oW@YMu!+*Yiii6L|
zu*;;bsd;dYSO;mzC%|}^Ru#fZFF%(>yU5pd$Mg{&R5mUNwCzF~BFrJ3niR2AY!?!v
zn6@ZI?1goC=f}|b+@^L^g2rjIw>yF<u0@}GFmH|td(nnDza#}gaXUuRc;rzuZw};T
z&9ARky-xAlmVHv(W1gH>%#b%yvAPv;Mty_M*R|dv>}>i>V1kLJD1SnZs4^Yzdmt%q
zmT>e&p0vwX?&3}?Ey2Toq>}8xT929(n^rQV=o~IS32@vuOosJX)1(;V_?MGk8%yY^
zQXy4kPlTiXVVj5)4Sbfq8HU8W?7yDwR!U|R7v7-Gx~rOSUkYe&O!pl}l%Kf;!(}t2
zBd|!>N4*H5=Gs5y9%~(aXN*hsh{ta$OyTaDq$4I?*;l?;&EC)pG9QcIuBkmE-?hfv
zwtpl$KueuhTr41i4)8|c)Jx-BDT{wDRKnbfnYWA%L=}`ZbcqU1A%*K23F+WJ%d76K
zCZpdP`WlhTXvI+d%&ynA-YVr1z{)h8jd#5yPU-;O$BoZ5f1*n!Qy->BHrU(-odH31
z0QFuud4XXl%vPv!K@dycU^xd=8Yo7M>Pm7Trq5c$hfT(l8crTgPea2IV>+}OW+%ti
z_b0wtqDLUpU{z#|K-374nQ(jZL&&@&BGiii7+8Kw<FPxhlWhg58N?4RkLbm@sH8fQ
ztq22iNNz9GIWD){p$6GO!&}~)bZRGbMD{e{&4QY@-qK+1D{CSsVyN@lUhtT~*QK(W
zkmSkJg6;WWoiX6dQq3rVEJS3M-RTVagL9J~c^oW+w>XSLOU-n88-}Ri6ba11KEBZw
zXNA6?VDaH-d%&RT;;q$5xH^l&`U7bQh$i@y>&spg4)hzBkDnx+?U3!PbGeo2iIV(_
z2eNL6-o+9o74ovyB^pZJaYxb0Hj<`uz$^ep8~X*KZPRoYc!A2SIxT1~%*!cJ!UV(N
zsue^%tsE8q3u)L^wsbpok>*qjaQJV)&zu=LNN6{fYb(PF>m9#(5J)OAe<0M>R0z3X
zVD0pEzQZZZOMQOA>60UKY7GG(Oo*!`9|qocW*YikL2#=gS~)p3{#3;KeAP}5ZMVgd
zymJLH_v5U?a}Rp>XwV>w$I>~$DyI$zT`Tl^TOO6j5eLm2D2Xl2ul4?M0ddu%?-Ai7
z^7daQ3JDoh75XN-vL8tPi(E1~ixH<W$yYgXO(Vzme99m;MgvAMga$8dRz_Cqx{g@5
zLRofs<)07l(C$9JM(ged{l3r0kP=cm{UKE)d}|c~Wp-RGben;d;;7fZc)K~t`H7fQ
z=J^q#5*X^uQ`2+_>Q!ZbXwyJG8~F^bik4WoD0^!v4%Wmj0@1xbQFZmo`(H<m8)X1I
zmwH?r#ghXRH+&1imDqJ~^h<4!FhCeqX!Y}OTnFY1-m)Ir!+5taC|2u#B<p4rV()|w
z`~F22&_Z76G&YUKz$NDYjncsCOX4juDc+rQC*tjkNcG}GJ)n<{%;FB3+X@2A$kqY{
zRLngSi+|W|hyozQOBYysjMyTSK4|nh)e!(6oyI<FY&*t?<DI2CM<G=a+_i9Q>K+|0
z^$749!91w+8mIjp>RD1w=uI63jQ&RrrG&X~CS640ML}JPv~1v=soO#n5}ob#k$Y&p
zrq76;{7kEA%o6W_57O(DDP{)ng)yt#qS+ZYumxB$wLxR!<~o&c|3!HPYrc2A_&9Q)
zb{RBU$4yn=Yf4?FN}(3hWe<cP@Ccg*6TEN#fw+^vngyUeoJ<ia35uh+#2V5Ef$NbZ
zY=sDn>rh~7#OM*q6Q!#?ka3YSP9+fG)eB)JqW9L9@{)M;oI{FQ+zDe8As@i#MiB_5
zPe=xE*okLco=CwY*kgGc?x0JLO;ED0??ai`LhOx+n-uR5DtWJCmApH@@hsR*xfzRH
zEzXSRJgk}G4M>83?cZTM`laUcK8^>0J3b=az+$1N&v`tsQR33d#}rT+P*I(f?c|uF
ziQ=U29<v~4Um3}hjFS7zRqRqWlG{148gBgcxU~KmH0)({^KohuW>mTFrTVNZobC0V
z%wtE$Ek17>LPib<!rS&&dC@lM%3ep685g<`l|&X`K%r45GSshedqukf?TVd!wy*su
zeu9-n3`w*Z!JIu)(FL4U^dp0(KY+X78y)hGh;W=)pf%8^9$XZHo+sN72l^`#hd{em
z2;Oq%ckh7%!(zK^sO%YX#G<UA>{f=->8cYAA46&~jHRkSA|2EaG&#CERq$7k9D|{4
z56&I$7Jh6ciwde{o$<`bxsjU&=>Fe_FvBPo;3a*iBXx&Q==j)pEKsayG%64I6KDVN
zZ@W)iA5=3)Owg0C&yeBbBrK(nP%Gnju)MB*#I2(4eIW3}P)1%g7n&u7pNwwzU}Zm!
z<^bbN_5C_0wvO>%D|I{OJBZ;210j%bZL&8F56nHr@r1u{U5$lB;~LrDA7vEp)wQH&
zz7zLT`o@za{YX!ypT}lF$Jp4Bma}Bq5Kbg%$JOC1BV~>v))z`Zrz8>0&=Z(oydbYA
zGQ-3j6$A6l!m`zrVHi|n<;aBl&@_@XsiU_@#Ybp_VkZFT&BeO$H0QR0C<xokj`Eu=
zC)1ai%p%Wt>0!Ks6WN%L#Ch`#M9TJjt%Z6oiV6!p1^%HsQjh-hzB_tR6p*-<=;Txq
z5Y?PkmuD^XK`+MYF$kjB)K9=h(NCljVw<~RXAB_r8cc+A0TTaGV*A1&KZ+Nu%+Y3p
zmYst&i}_ZnMC73ZUK1-^q7xO?*=@4@44%-?ow;Gr^NWVCZJt_z*&~hjAl9af2?S$@
zwVdEvWn*~Z6C~sea8EC{m1JH27K-r1xQ7&cV}v{lL=Yvi&s*94TsQ`7g=77I=CdRc
zj}T);0EHBzr$a*n%F5lnY1>SMCPxHK8hrV(C1$~U?X(9*5^hE>2OTv$57dDF8<L0s
z0KU0oPIi>YfCE`xA!~ubbz&Hn!*EziRKR(P&kWgVzUsz!wx5-F4Omy#`O((flv>`#
z6BL5#+P@#vR<Qz`?4oan($Kl^$U*1fcdpVKj#xqA<HUWra9OpdYySR4rojTkin?8z
z3-%G9t#Bxppt^~#VQcQ|K0mn`+xltmtE@(tk#y2Pg4UsGQMC794!dY_*DgNOs8<v0
zqr=of21rxaGG*x4obj~C+RiiDh)i(jt9@SQA*pZQ<U`-I{1r$v-v>U)C@}6wvanvD
zp<(5J{Mmxkb_YHcCv%q#b!fTW50zw=qd;KTm%od%pPkKG{a5WvaQlj5>Tcvpoc8rb
zT4l$&41Zeu-GAl@CwCGKOrGFgbYXl<o_i_5*<Zm~P}AeA>k9W@3m}Q8;w9;xxpb-(
z_4ijvwfaXCA?>zy6%?;;wVGL?5<$2$nPm48{A@K1%dM9O1V7y4ygH)GMF^+bTXuF!
zs+{{hc#Ba7DmK`lP%<HPIBRhQO~+MXXC;CjoauC-6Wl5}%y%DYEKx{4LvY*`_Z~Xi
zNGcO+YCo(&EjXootezYb0&p+-vhh{6ozMOut*8o$DhN7TSMOMP+$${m_YMM*z%+&h
zY!46Exm88(_^m({Xo<`Nj`ok;GI2V-75w_p?#-tw+v#A0T`m~|biCYr5ofQ$(sB|e
z^3kFLJy)$HIqI|m#^2Fi&07*LQ2>B>Fkpb1z?A?3BR+sAqHWY;8XfivmIbKbPTRIP
z{!q6$H;a*He^=fJ1%AK^ded7{)6Ux3h}G9UOwwG8&uDo*j?BwT#20NrEEB6FtC(rZ
z1WyyRW?SMzq?zScud#Ts#2%B4t4GOzuhn&Kgeh>V)GC9+uWiB^whO~E`X+Xa$kZnT
zw_B(xC6;O{p^cjc4NV+B?Y(etJ&i!9?9)fcqLx%+YPyl;uYBU3n!zzKG*nf*4#Y26
z__qyGtlR6eDw6_}7RRg&x(7P~MYQ7B5p){Ym&Dy0(<p75hgQPS#nGHHeBdhtha`~>
zqw(y3bPVzt5LhEnlGM{uq>BW##iE3N;@i8Y98RT*Wv1We(+cXGNuXLEkabm`!|6H4
zLR8r#_^><<ca(RvNP+SQs?;?@2V&)xz^WS0lMaEvKBGAr%ySKfdcJD344w;kBDVX9
zDY|J4TJ_fRKC7)_Z3NN9X`LKqndAI>yE>lUm~W3n6iNDwCBv4-WtSOuD1s<bu~^*h
z!;`SW69l>8)KaT8vYA@9EX*H_2;QA7RG6=dsb!|YH#CZt(CslWMJ`Jdz;s|+EEjMP
zhZ8Qw=5KcjZA=A=8q=cf$T<vCoV*dL<wvI-*flCmqDlCDPXmGv^vE&rBABTdsoSZA
ztH$7<bM4fmg9*G$AwK&6%Qc@NB4Hj(Ym58<UzQeJ)9`^Z5LYoPNc3Pv0sq$t;6~pe
zJD{wrarY@=6Zw2>vc%aZm~c{e^v4CvGS&@C!k7V0rKr^Nio-v4<^E{NWN;}jw69~Y
z4$Z@<1%bO4@0$xWff2REKfBC;5}owjuARN-SS9lMa<kFyv?(=GuL^)L+@Fr)RE(tO
z7UJZDE<U@pt@c`b5Z8ruZC*|zQFYNpJ?Pdx&MF&}YU%HVL1}s}Wvnovriis@rpr-N
z!f@WUv%6wA`%!x{mO85$y0O$Va`Eqc%+maXM$Fvy7nP(T1;i1qeM#h@`ts^Gm%lcQ
zJ3=E96Z~*e?*6JQc|sOK@4aOo(3Pu-Ehpa7z8V-bap(Nzas4{fRWKo782!}Rrj77I
zI;;EC8o2D3?t6y*B+T@UX+K;oU0_OUy#J?*LK{NCK}NgZD2MIR*N9yJd`Yi5U!ED~
z1r*H!U+N!Q!rkAR2yo)aeC!=3v%I?#m(Dn14T`09n_p%VMvuZxEp|3%Woeb#f@f}=
zvvW(F#{dX6stS3DyuOK_7r%@{)^F)k<L)NS`0vfM(|pr3TO<4_MyvwK#L2m~-riGP
z$kgKli=EShECd+L!57VP#srfwoL)HhqFSwMWPXP%BTM=9;7P31s@ARyG+iO;(ihs&
z43`aczO#gjKO@mheftlLmti_!@@ZBb5P{PFArsh?<Zx#*l~{N|^P|gqQOBsQc!r`F
z%ScrA8*A+cvDGXiWcJW6v0mVA)(6OSZfGBdQ!};pPqRDPS2Xm54vVbV$PFNEg&qun
zR%5hxc~&I>CAbzcAU-X}%kkWB^q=+~_t%T~VFUINdI=>V|N7RPd5gURHzl!~njZtb
zh>k4C+odx|bz3j1fgc`J(3IU2Q0WJTOxJ}?-;jvKy35fbI>$~~<yIrf!*kR`>0B};
z&}i7D1}Q3DU9r!~+D^63jg_&j9srf4z%HqdvgMRM{t)nYh19r$xSeqNwioEjp!1fE
zjZ6@31L8#-D>)`vUkWgf%aBJ@o8P<0n>qEaa^X2dQ}+iWZY_Hm?0A}r*(+qC%>UCF
z8~nL%kiN_DZ4~^7M79vQPk*R7X3ZfDQAB~(*b1h>g0$u*avzC(D#{PAZ7(OAPPJ}8
zn^-43tZ6G;<bxo6$zS&H@UtzFeBZKn2`Q@^j1tB$ppb+j7{e;)NWDoL>>!YMVxd1w
z$Ks<^mafeSh42D(oU{uu_jBz?on|>4ohcXlbMndV36P&i>qHHvtiA3qCB`mp;yn2j
z=V6qEx8JJL$y2d0Q~nY?20dHy^0Pns%!WvoOP0$?#&p1wA(8>HYQ_hEP;zz)kX6O#
zG<>m(JRE`R?qAh|Ws|C5YUv@^;;izPDetKMxck2@ZxGE|dq<m0h+xgmr$~b-y@$px
z*ef+f<`1)OdW-&#$uZ<Hnq!oE3w_3QQGBPw7|sN;(<2ToTbbg8dhoCHyl<U;vP|xP
zgza88aSL$gnP|8;QwB3%*NTYYK}Xy7Ire*n34K|^>Uef@SeIzi_ujaGqCz;;UI)Q%
zoxbR94<5?GDs9McvNd=$Tdk}dYsfVj_JS2Iq72k!az&wORXkFOh*A?4hd_v%z{w7z
zG^ZE(lU$9ftl>3`Zl51dOE{c1@sZjq0$|_tX9~k0&en*2(qdl9O(AZ}d2f8xUClXN
zOoA20x5V(x#8-xew|F4upx&!*mRQRc8%b5^C5P1}iv3`so-%7v0jiz^v}eQPqx=iY
z==px(d5QP!i$3g!xZ6Q=-_d8V1NndE!uox;%e@Pjdf?v@Z>OeN=gGiJ$HpV^`A<6}
z1@~lt<#62LTZ_Y`*xC(+?XE<_!U>o`moiiE@}?^GHyc(80)h>FfFz&ch959%Z;qdX
zMoR-a<PnFM@&@;I2iKH>n?6=1X>$xa1$CLx59!795v_&ucRt(1z~2qO&*M~g-GUw5
z{7d7`A(OKO+JW4H_n}t-<YR{ye}fYkUL=^5{VRG;O!}Adjva3@4M><Q(i)XkN`;;^
zs1W3tr%@MLMPvpniS72Tu`yGYIdnePe)mXePa`^WA}zv<bKk!6Hlb|{@Mk;!!^+l1
zXEbt@SExdpzqmipVG4W)B<A{Iy0GjEdz&dKe;H9B%%<#x7n%Ihk|Mx2ZD=9wkWJ;q
zNt@c_2GzS<5$KOyXzwtf^idY|^fdy=b^6k?3h!}NXj*)40cJY6YhH8mjpC#=oIXoM
zHq2@mj|8j?vh%t+=KwW%`r{^1)+9fXar#jIULYJ>)Vo{W4Di|04$SjA`~~q-*NBFm
zejfr@@PdGx+aYeMiS~sOj<_1L$m@_ib5yv*zd}Xr_`k;@C-<sW1x2wO3uqciPO{$=
z3E@1Dd9B#OR&G%&NtR+jV;Xv7vZOV)n{>qj*_Wrx4JG8TO%ZY8YA0!?kh#kcSiJNm
zu7Ppb^#l6Mo$C?p=&JOU$|HE3^*1c_W4uTkAL!X~(oZb6S{XtM-p|(Z`-u&&ijNX3
zHb1m24HXy`lWQehs;Dkj=<AsSHclm7qI76yV2rd{`L!FsM}K;|1<NvRRk5=&J2a|q
z#97uarFP>16`J8;+l8Hs_>#3QQmOMt#VbJc_&;OS+mSNeh$4c9?xF-b#0c}}n`?XQ
z_-&70sVpO@WvVA14*eVd*`P+HY3K1oV|%>OI>X=Dc}8A^J<F$vbA1H@vctMKgES4*
znMJQJ*G0Pq!bi^>l0qU%Le=n3cO!){TWgNkr2H|?iSfv+3oSQ-Lxv%}CDG$?d49y~
zEdU)X8@HCs)z@2z*)%|TKkb~gRF0Kl(o?*8Pwmt{OhS$NIS-uX9BGTUx0HFTVXYj!
zRGt=z^qYuu4Zk?{S6r-vZFTysa%OF9JDalnU}-EBBtx=`p5QTCP}dt{^=$w0?yEtQ
z>?AarFW(bX1?CpM4)@_J$AI;zE?8RR+Y;k*R|)5i!_iA9r>}$wDmz#%tT;I({i?;N
zxr4B0E(lDld3U?<#!`<}0mrAJHYOyHZu7OCqf@Z8iZDA|RSD8_a?e2o<W00V9qQv&
zABqjwOqi`O0`<@>(yH}5kkOgik2~e(l5+w?dfk>ZSrQ6p!v$TB<}bu!Oyx7Rp>6v)
zwMaL?;RmzmPgs9mey`0p@)qx?JtHh?ArcDoS))@adFM<)2w~R{j`xyApZ~JgmUU_X
zL6o3F_A%DkZadlk*Vz+KszFqu+F>4F-vn4#&>yC)e9P+{Ry-OW9q+NkOz=$}9lBL~
zD6r^Z>IhIq&i~eC5!_5J@+Tv{sk-m2O>8x?<oxS#vMfHvRXl+B<qJnDl5(8dSY_Ao
zEABa3Q;Ccu$&1YACn4Eb9wgqivmy{ir|z15c+*^WZCG`@b0xIKYRq@3t#-OHD5q;j
zM}z>TR}?d`Ig^{wugy`wJ9I`S{4MNw2_{nT+O0|M4%(3<a}G~e8eO|>VYWg{%t(AF
zdD5NQRq41kgb4zBTp@vmQxQ~0p07;kEEq`h8Byabw6G%Ehry!N#r}TwiJL~d+1Qea
zf)O*@H{v@(G~;d*jVO4AXc=>(wY;gHc1qjS>fq7jOLwZG%46VOJOIv7TQ{~vFrIqJ
z5rHE-U_mArh!Q(N8P_Ww1Z!_U<u0j(8AMfAPXr$igY#ljbYly*yJ-gsTo8i>`F&_w
zAQFD@-E5!8SP~A4v|^OYwhT{AVCKfw6vUWYOPgnFy{uUE)GBqzQe%pFhRWzDD*dw+
zKFGx9Pt~a(XcuqcrkE-$qoqULg2cSL0(Qti8=3&8<X`{+Hh=&DmmmNDA3z56-~a|n
zw_74@usiV?#>GvL4NdI~nTUO5W#i3xP8_Aw4%&jGKj^r?0czY-m-gA?sKu<r(0}L3
zABLFk;0lh7G$b!=lwfCU5DC9pp!)}E#9E*KqY-;$NSwvrSfQjr(=9DfeLG2i4}0?I
ztr}i+nG12LR@9rv0Ldf{-WM?bT12QS5oixTZz^`bhw_f*PxLWKu?uP5r@Wx`Vk$t#
zt|QTnvx&3q3O3n}at%LJWZ1R$;r|EF`)3lHz%FcDSxO*w+Q2QCYIKo#3_*ex(4V=L
z=0xktbj;J!V!SX+tCDMPSXEjJ1B$6=Bv0=zqnqOFtUdY9nZ?HSR14tk(ODljDFfNk
znB^oOj%$AMp4Q6CtS|)uK{Js}vOVuP4+~$IH6#zH%BzaK2%B>@cr|8DmW=lWxEv6n
z3zCHOi!;X`;-Xz*-)jE32H`BK_dXSQ#;oGJ5}1Wt_ZMPd<m8clkrqBBl4C4HC~O&!
zPCG5JMskw+172qB!@jw`iarjBZ@(j_>K5yG@el(wPOWwAs2Y#jG4NW7b>)v{#7J5v
z(DOPj5YXJKG@(Kqv6^B&^Bj9w=?=*l`iDBn<MJgmTY85W65k?0he-`*002@zt-qNS
zIk?i6cU?z-{!EI=yqp0?SB$56iOdMavdJ)VU}{auNhEGVI};=7p(P43Iml5MlQv(#
ziP-cpHy7y9#$iPg-?=k>;G)z;#E#V1$gt#zghNk5`3ZU(OB6wRvdOnJ;i}1uq8HA@
zIA)AXo^@&4)nb{!k*i^B3C2#JbE)`N*n904`H3;V6OiKw6`@w8Ipx8$rLX1kD^J>*
z+iWpV5>-XEgvMQXN>IW3_&h+fIs{M=G-1d@(}HThs(%oR!4#Sa@(gxM8joTjbuWCz
zH82NW4BQpHExGH6<uNv)WoW=xqF$Hr-?ZnA&5WAr&_w0_mog+vIC1CsG?DJeSo)P<
zQ%4)mBOWyoJyyUQRnXFB@Syfugz(KA5Og^~s42ED*<mx-xX>J%todm+^$HO00hoZx
z^G=|8Xl6wd?UFlujbtkOpC}!dlfShYZASBPHhOR=u`0bc9$Qsd-%D{c_tEzTW@7$d
zwvWM%pHOwtaT1Nx7s><>7=95Nf9o+kRHaW7;!?}e@wef!14pTKzEDdy7-$3nQp4VB
zM6?i{V^X+F4G~C!JA=ft==N>|mvdUcV4ks6?6|tD3ndC~j@eOxqm+JVcn%N1&RSZC
z)b>lWXk5E>4-P$dmvZ%MqwD*7a}nPz`dJl#*`O#lKI+HM(r;>zFt4UJ30WfPtevu~
zV;R{xEg#Zw#KP%~;Nin5I{ai&r4;(e+anaMzjNtxW%M2K9OI@~L#;0E=|i>YH1|Po
z*-&|pEA!VpEX9eFy;764ZxmU<^e5Dk2-niD#|X>XJTSFbkjE<O`+bmuDY1Wt=#qee
zreh(S-!yyd_`}%z=dp|q=8}}7!uS9Hcx88-Ubjb2hea2_+jp#Piv1<uV{GJ^^+RK*
z1)~x1W$HCus*g*x`F;{hzn5LIK5<#i<sdfT6r4m7TESHQiG*oF<;hOK3U5_3rw#rl
zHHH<U>Vog_$9-CnsV;6K&bAQ{6*o9jlgJpD=IKQw-2Qu>`Ov=)OBrybbg5=m*g*+~
zihCg%%W2~YS7_#*apb~qg4_jJBQ-6$+^vpuUAd8x46-JxCZdvy=X8xr>$hm%`8;E%
zt#7R{+q31AFD4bJ_Qy`d=`GxWBp_8@qY7_U^3_h1!KK91w^M4brfu%WOd|GKg(ccb
zQ>RKVLI+hhb<<iGgAz4_Ptf%kpQ(H`F<Qo>N<wvUOG3bCwW7rfco_+4*$g)QR4jLl
zZRl9JX&}W)`)E-e1=`=uB2zdVA5DQLAZhxHrqBf;@Cta&J2D^_Pt$Fw0fiP;c|_i5
z$dl_)0HO}<%glcrv&!y1N3^HuZf`f=@YfUI^iwhv4KXK1@sZZXv>ZG(JxJ|*7zd0I
z{l0<Ou#E9ePZE2i(e#aZcd^*o^OVM>ymGTxr1pfa8`h9`?AQ*(iGS>P+YQKOT|HhC
zCLY&&y{awtmJzE6-VWAmV#HLVM>`tuV#^&x^&hGrNgz?7h_f1$jfnFd%W=k`<pn%@
z%8cx5`Y(ejtQ87)8T@mV;Na|v9>U9yh%+aL58}oh0aJvA;Io^bz$_F@-*GFyDZ$xa
z`;35EtZPWtl;-0Y-66V9=7P%p=rY41?jIv1mvc^suq!Kq*<J!$Dt*33HN^}f*ZfD!
zJc<#1xR%eC3=3$9F|?+{sGNNvSP)eKYhvA$w=kL7grq}v<X@Sh`e5%yl?*f2-cZh%
z2%3nM3U@a!;977d`N>}7KHqeOi@VuGi-Cv)wkSf$3AICtR99kmY+qke!KBL$fJ>@b
zH6^Lfrmo2k_;m{e`l&%L<RBHX2cUlfrq0Z`WOjtN5%id>;hiTIwyJCC%K6x*J}H$<
zY|j*qTze61YJnPvm_MT44DFt85GvUpwH-5B3(4Ao#q*4v&s_nH59DUEabLn`(<zj-
z4QKEB0jDIsh-IMg#g5Fu%H!KhsO842+=rjhy{C|4JgWa@5NPxR$j`V(mik2oFLgr%
z@GE`Io{Xu9_!kjX%7Mfai*YaDI;w+9Zc29T^ffHv1Y8HeMkAeJQ7ZKd!cJQ!Dd5Y%
zys3uJX0t+r&gk^`SzNvIyswRltpVpe_j=fKSDv;P*%@1N-Sh`-PD{^FDCCa-l(kcA
zw?ebC|M}j7DBMqIl98O%i*y0!ZD&#pir5X_Cb=moFePILaKIc(7OWOAaex<zT1f$y
zi6Y?}r4%D(rNO2)DrCQGWB2(oSdWgS?;+v*Q|tU7u}w6k_4~GlJ*mcyDcm7oo9g}!
zMWn|TRePPE6&GgfhViEwo6+)Gw#P&|GBo@;VvU^wacl%&ALbc+W83cA3|=Owg{WdU
zT%!fGiYg+{;rzwF@Gm8_-uhCGDae%NVH;O4-f-nOZAu_fYS6r2s1!&gSlyMvQ{H$9
zbD8K4v`8cAi5GU$3|x;Eva;o>yWQPuE<~(<3Oh>RSgM_wXaaY~FKEzpC5idLdOJw`
z9aiSWI5Wu;P31-l6W3OuFk)PK(%AgZ+WA9NJcW|)twh7ZI~=VBYdB^{jKQJ|7C~4P
zR)nIB3JyX&9INETx(df33T6AcM--ym)gd#rm+IhhTAtlG&!!iJ08IeF4`)}#mkM$%
zG^^=0B!5bxFHKh+_!=3a57w$NF<9AM%`LHtHT}EbCy=~|z0%Yqt)hLBd<Q1WE=z_+
zEZZg>(9hh!$(_GD4&*X6w=}OIPscGnCL8z;RU|$y<c)3sv(q!ilZ)AcKG7#sJK*nz
z5Ci(edyW4lR&<*7;a@rzF9VZnw+Qk~6oB_lP;VJnv%d%TUolM&^XH(o&y5iEa6L{h
zZR&TwjmO*K0<^oarEB+XM_E+Ao_|gGc!&)vY}iURtJ`RD47}_4(~pHpK}z!It7#&p
z-#o%LGt|0~Z>PYgPo)pbV|osZ5YUWV3=Ytg*o+ZuL{N)hLyv5GCWqsJ`Djxqk{E|?
zou4b7=8$3}hjW~pLYDX{po!RrZ&3<?f!8<YDm_yX?*X*Q?3eU2D5?XIvV~)kG$T*S
zk;Qx-^mEZ_(K~y8KB+8<+X%Ns`8P``zS<xgr*)CtTwX3Xrn4j2cyfFGh{&*qrD4Ms
z=L;UIiT!U|c4Q!1tq+la|G<)4__T>XEYnXYUor^KmjQ<nub6-W`N@z%!ePAF?9<Nz
zvJ|B*6wryi9I*;WU@AKMW$RbmE^%WEcxzx!7W3Wb(@HW7DCU^v&%L<PM3mzfLlnPe
zk}U%)-h8UZfv*1Xub0^^X7NT*VhdeQd;VAzzi`!Rd#!yo3wl=H9PHz9X&%j^g=G!r
zb5aC&C(GZe*Ld*&gdrkAzt7!6@kX?-4i=Gg3DapcBg<0`ic?o-YIfB|+sM;T3T_(p
zBUK!J1JNU9X)qBE%JV6w)Wrk`5o|ZnDx#VhlVMM$_sp|{`iN=mMYTEe7nUAAFU#${
zV^@vjDG};A>3oGg?ySg?k%HC8H*uGyNO1L!fH)~PL9(CT7&~k_Ns?HS&X9APP<c+e
z2PVJe{-b|#+<W7qe8V*Xrrb~9G3lf(MQ`x(ktji&bmSEvwx1GvL8wrg;&Hng3_{cI
zQAtlB%*7zwMdqck`ryK1PQ-_nGE+ZL4{b$)8i6(~jnJiZ?5B|YIm+Z2H26#TQ4b-j
zNsQw&a}!B(@9z#c^QuLOjH*neH!<99;dr~PbW?d+Aw8OM>-=4>5E-<kspA`t|G>|X
z<5s6gp{xp5IMO1JNZR&4BAbyY2fkqAw8<gmpVj&S;qsRg1uS}Y^Q+y$l;!8Wc~%PQ
z&9fkshNZ6^y3m(EigI~w(nIw2CEE4eF=Rs`-tzkOaaI84<)D)ECN2)snmdlMZ>`%x
z9^E3#75cFU+2I-O3I%2Mk$?hJ%z{0t2Orr=M<%QdO*HiDvEKjy00u7D00Khnh9it}
z@B}6U49tq>J!6^q`031N<GESF_k|_uPTT+UKJL_usU1PJAIwvIRtMlJni_URit#hk
z42<QoVVO(?3j>Vu3&PAD+2D5hY(>nIfeTx<gLdX!C9xBYZKZcm%h^%3y>Hm|`AVQi
zqkH!eS!f9;q5e17nbI{y4)o^Ty(aYrhJxk5?Cg{!yU-cw^28H!^w}rTe*n(56!J7z
zZ+*C)NivgSBaJSF^;0QlV-xEX4TN}eJLCqDPTU>3jRT6!bNZ`w8vFG4OqSs-%qT3~
zXul<1{9Z6tV8x=fXcvt$4}w+EY}Al)9ky#_i3+?IPM{1EKxtP0cPzeJ9bhzCmS~ZI
z`ncdnJDO_37vaC(nK~|;%h#JJa2B;cm^hB|h1YuL>})l0WX@PcL5PK-!$!-^Z=EN6
z0c41=9_9S#;;&M15MJx>GZJyuC+>beDJ6TGR&+KRCuR;*X!e`Q(+AMvKsC}Msa{D~
z*?;I(q+^R6&uph4f+Ze~HXKatzRV{S0~}0mo&9Z$y>Jfg44#x~YDzi1j89~~lzR)5
z>U`*$z~HJ^R8JE>_g9A$Vn-g%ty4)DnwW$DHi_c2;9dWTu6w4?$loNF{oKC-vM|=M
z&Sy5Unczt9dU1mKLq&0u`><=2hfZWo-;)Ia*fQ_OQlC8gplRBfvwUH06RRRUBb{rf
zR>)+i<|-FUcjc1ij8M04tyuOkG@yiwA_X&EO)sWY-=E#liv-xYEL7;yb(0`=!!}GZ
zpaltWnF3kG<HYDX6{KgsS0rzjSb=X0lOu{hRhbR&t0%@_K@Yz=JYU&6g`QI<2CGF>
zb5{vwQ!UvAxUc0r`KW0C_^}-Lk>Q5E^`-;aPG&a5=eaF1(=;$ubN=jaCcMYDI2`0K
zcNeS@hJQOn*?pFFY^j1OB*PCstg`fhJxOWD8q!JQ_C3sH1CX4!e8{}Epj?J>p9=S8
z$Jf_n+QeWZ*50k#)cHawcUOdFgB_@7UD|Y~wum5t9~VAYUoX?{Lh6%X>!R*ls+<_}
z@n7dXN7BGT3kfAo3u@opjlS8#_<^IEO^(4`3!0YhOSVW)EnA8Ty2(jbYpBtA62wjJ
zIVJO((#UX*6VtUj$#fvH9!A*ovt{d{mh<!!`RlV*yTU4)BD|1ood8A0$83HTQyU-@
z!2H#@5`$&Si<T||$SK-frON1bw);D2k%`8JS`ya<_5<@;;tw2p9~zV-86+tOYg|CK
zMH?Qz`D?@tg{K@o|1K<&XH&2`l_r}{0K8s(>=~ER#4;z9DX&EqhcMN4qB*EA7p0Fv
zrZcFzZhy>gjuOH5n<+G<+S{SM=hC*D4LS1tCuCthK2QD@Oh5;QX&!tpYnQqX^N}mJ
zW~z`dq0dv%;tTBz0WhR=wRInAb!{!=<om*}+f7D0b+FBW;~mF3_rZC21b^=`)q9GD
zBwgP9l+~OfrY+?e7Jz^OWBWtK&3}5FEbEtf_q<^yQKVa(+y)M>CYz5~_Q1@dtynn~
zVF0c8vLxI7#9qmEHR}!=C#45LtVXw9GG?**Ny<|)Vh(c0X$>lRG;srpiCa0!BK1aX
zzq|Y?@3iH3I_SPvj(%?Jyc&j2$d?z3vl}u>i-0RDv8Tx2d+$$DdZ|vP!k>v5SFz=!
zhPe1l_j&B+lk@?ZA!*&5q`Tmi;MJy*<1_Y?#o(cD4(g3vB6y(~Mbi0Pg19_KH<0|3
zst&h#ucCq1G)zJXwH*KbjNiu_pf^o8;+-LFZuhr0TD<gk^byG}9YDb&TAfBWEXnhC
z+G3AzTCpm!oYt+fA7z6n*RZSVe<-H5azg?)!7BL%n^lYcU_<bAQ~p2>A_W8=hXaOf
zFWSzS`&!Asi6qeBL`pF7S)yKT$V%Nck_nG53RDaTQo_KAp;WcR(NjBnb;qx*9f&-V
zj{Z=x#qha+z9{57DS(Pl;>fsP&O5o<sX{6BVp(&`daywJ1#xp_mnqMvrq&CTP-y)H
zox56~%yB0RM6L?-=vY@$MOgCT9I52BoCm1St0EPT{R)_Lrl3<JV4EGU;?l!9bFO3=
zJtE@_$*&$~gy;<Br=YZ9E;hU%k#{*lfq<;gQ7JArV*kY-vqeIdUhNR|O#bhNxG4#<
zq9)CG;(mwc=h~vFmq}Forh+Q?;aMJ47DL^Bqo6MSS2F8>(bD!x=pE_0lh*OG!lbJS
zB*;=AZj|V9Uksuq_oF80jG}AWF0!`evWraQA37mCP~c@H#7uluf%#~0i7|Coy0iN+
z;P!hKNFBU>wmvmgKI4w$k-xdD{8Jyq@u5;?cUB;o<LzjV0?HBV{ga$>(%Dk+5;z@P
ziOtXT9ujNVpKc1aDvJ@Wta8<*<yG!l+RkO&QFU0+8<{_xdoVFp2-i@lBxp>Nl2!_j
zws=xE6OzXqCxz5jKAHh4YBnh>lhVOs4ZN9k-#Gs)4GPs)WxQ%UYlcPv6Tf62z6CGN
zhaTM`SxzFbpLQdzPQ{MhgwUE|V@S;!>nP2~w=}n_EFp_RI4-DqcyF!$Lnju|Mx<w1
z2F{%{F2^#{Z=+qjlP8s`lC;Ubu;p$-<kA)z{I~ivKE0>itDWKV5S~0jwFYvLvOrl)
zUHW;*_zqYXY?mAnaR5og+<T4VRM?pt)MMm1_dEFWOUNMR(bI}?D*|PIsp*%A0ZwnQ
zEO}Kn4E?ZZh${q>q;YCGZ&>XWrG%~k&T`f(g)eYk+*QnXocmD8=k#N+7hytF*Z_DN
zAionuzbs$K83Zlai;iX{-Gd98wpSdYRNx#}eT822!VL-lU<lW&Rngk8UNd8M%v^qs
z+Q1$xl063z9i&ns=V=tnE^fMKNUVQHo&6R|I^BV4q_GOhdZcO}_iTPXa{0Mx{3Sma
z0iXrH9<ICi`~~mUKjaz@<-=^+S$eBpvPA9xi~~>Xo9Aw5{C5_GITmoU0qOBd*+3l!
zJ$+ve>@iH4?ow7vTuuOrViX-jJj-huY1s*i1s;a*NwO?uXp4QUK;=pw>PT;^egx9H
zJ7VJBp9^Rj2(#*d7)nhOUN)az%`17oz-8NLinA_cO^=|visgk~C1Y?t`-CiarEu!#
z6kZ(Uf&v@^oNJ@3dyI?9qgK7aZg@a-T}!49ZyD44&IGP#t=|4lK`H4ii7d+L*8o2h
z?`nkgk<oXU&hE##-XCRjUVRoW<Cw?aDFTJ)J9thP%SYlSB;lz?WAmYg_<5p+0Dj0w
zePty3ZLoGIf~#I)H6;2^&1pkVqZd3}$=`g+kWQt(RyjEQNy#+D&8Fg7R3mN!d<HW@
zWOLTfynM(9Z#=BaH?A}3E&?I1C`Pr9WYSy2p*TRJ!H&@vicrFWXjzz-8Ram1=O3#5
z%%N<jkF*XQq+x~GLed*3WNB(kl+`i}sKS{^mVH1839uFA+bwy(^!ZCBIA4-X_)1fA
z32vuWD+xx{j7pPgqSBO=y*8pKfAvG+8>uI;It9togMl?FIKZRK?_jR9U~8Y}&llqB
zz2u>isB%==!!Ss)=bUH{>U&+0?;YBd7&N_&$^L~N55nZv^XH5%`EA1+6}0L}PF8!0
zLGIjK62=M^zj^Wxr(R;6NdKFky{d}`vcXaCbmX?>d%UD%sjhD-&<{fqCh`M@;ZRDk
z=GQA<C6~>DMC}nkS#=nJ;MzGpB{ty<$!%mZVoZ&<(<kLfK?BEOY@WD#)L1QHYazUV
z6HbcUH_VWWNh2nPp=kVNQ^^+eV~$7BEY!qW&<dF);kTy5{D13pG5@LacCWlP0AI&d
zCV5BQ$Cskmdj#GbtXsBsrn9Ke4b)c;bh%P_`59k2Bt7r=-e3OooPGCG9UsB;Toyb|
zaIFR{aCD}iYoUVn(o&D-_v^9SHun9KtxR^knF_?B@khE{cLJ)?_k@~WIozNIPOTx{
zp-dijm;HCK5lj^zAP#K7W-o9!BJN{?B?M*H6HdmG9q$bY$5*F0u8v){jy%J5i$&nO
zzE4bbe0Qh|BB-zxeEq{IEAPQNOKo&SsBX5c_a}-kOgG0j>c{vf7;qA|AFER?+Klh$
zq2=+vw&&K%!bYj;zTUP-HH{*zPjXo**{)iJ$!<sj)WGv4yO6hns89cm6nONn2_}=!
z=Aw0@{mB<jkX}dSI^Gh?!|QcO<B)5zxS*_(!c+2SV!P9;47d&WH^|5~(Ul6WZdyk=
zA`NeH=2YVfI?-gHe0|V^6x2OWqs=?58aQ0_x&7z@+R9<Q*t-=g&}gb;K-5?L`*gD(
z%h+E6K#!LJDriv{_HA6!dAwVlOxb0#aeENsDG84^XD;Py7+-;r|6NjoOrhVbR%nW$
zY)yNh8I+WQW~pkYin*w=l~>(nyLt1~2+79(Jt~@C7lLhxO9_Z6i44oN`!sT03Y%aE
z!`|H7+uy3mhjhj--3k_+YFp@8E`AKjq`G1!tOLm+3dijErxJjg9$vBKu>I5c=Xb7!
zq?vGZ>U06;!0Pi;Yi+2rm1&|k5=zX~Go=A`0l^424@WcDUa)rBiOFD)$=GDBP1Z50
zbv)zHO4(Ye9>+|D^R9bD8+HQNB(zyRuJdsmbDreQZLKtL-Q#vN8BvxOypQRvLz3S8
zB-qf=I&yZ$^6yR$K4!|k?xurSC0LsMU;*`@Msil6E#>+E33q|MN_xQZPg3R$U;qFB
z0004S(V2cdUH6DPeD<RenhfB{vN}r{Qx*NDa7f3<6sx#M2cDW{t!;`BP0z216qhjc
z{-Z>7%|ho?qVb9}jsRW-|DagOFjQlZVG=Vn)7V&2_A&1G=#n!$4qv=qergYZY1n#S
zB_vY+?64=_b@9?u?0Hg|KFt2p(CpBzt;(Q5Bd(VClC+XL_2>m#ZcEwXF_Q<>i1S%p
z<I72pOHIA@%DPTXxI$6&>Z^EKbiZ#p!f!r8Hx6Ld9!54B-*A&to|q{tN#s>uO@e=f
zme05uN?3p+*kK88APJ}d#`(M1OlnI-2?J#Vu=I&c#N#jfFa1RD322IBAQ|{evg`$_
zO>Zc|C;uP-^Cd5YHxM2;JfKPZ<JVxwN~<R&b*X-|*vmb-$W~BfCE6nzX0G@MFvbmN
z6=M~FDCl^qRDmi}nz!`RoEf{(Y~f9s*4giQpwmZY*m{2CB295q2ou58EE@is00uoN
z3I*n-pWS#JkE8mFNsJuj9z>%($=;)_p!Vz&Q5r}M?IAiDI7Tal-E{+hcwFq0ONnJ2
zb5qU}jOmg0n$e~h+$Hi3U}dm<stN)~l#4>0y8bV{+B9*BLY-7}MT!`U?Pd!!&x9IF
zb-1jbPtL*iT7ZuBPmTja<p^Bkq3EDCWT>iT2are_9_@q3s3A#g{u`%B*|lyAv4VJ@
z*Y(eT0`gi~ch+Vs3uqE#pf>Z#kOf=9M?S?-#!7NmYm{@z)b*|NGa65Pov#YRt7C5+
zfh!_kWm}=IVR~WNhh*R}HOo|^zIz@1s7F(ECr;+oN~=zF?0}Tq+@w$<WM*G!;m_3a
zXU@O~?6LFGPRJx`wVf6T%pOE`dCfBd;E}Z)puJyD6Z&kB4U?{~KX+-BRHwa99196K
zaMsnaMv)${?Q}0Ie7GfsO@2B~*(Meb25w2h24u7Z&%%Y_qIy`{!-E~%deBxS*LFw#
zuK@-^KcXnk1m$nDj{19(z%48<0e%;TyD^hA(6|}kWCX-4xZUNDv8ALTB~4gE5mN#f
z3eO}eZrb<^xM>A%?FzJQwD&;Z3)?xpdoejFh}e>Q^)GM+)WbXT8@{#4(Uj=gb1_47
zx>F3l``XW3ZH6{SzdEa(_0-1q$g^8B5_X4EACzG=Q>xT5rvn~7GKII8d1B;+6^>t-
zj{)jIa5ad7ZxvB;cHT+1Zp!BH7ggS`CqbD(FSv6OK3kr|BB5ofv)Yd21A_Pa4OL}x
zAC`|D$K)4~rGX|{E3!&E8M86ImbQq0YU#iF84jq)3B3x?(fVA!!CH<HZ?8gSViHj@
z?qt6&8(-qMlN%r2(z|uhat64P+Ax=T?RkLe2o->#0kkaQ2l_K_G#;rDtmC%|3&8W-
zWbzkbGw#LVQio(iB#)3D9)TSjc3cG}z0N?8sr>;#>}M%RK=6B<4-7;fjvayR0?q)I
zDgk(>ar4d$FzJJxvS_;L02?;5(QF~r;{`7s9b4aNi04;&(}9<eYVJ$)TbCzEQl<J^
z<0zzG;<+oOH;cB>dEbJ@GRd-8?xKF=4_`+fCJB}l(Ujp*qy@<%BIL~{m#0=0V&^Gn
zI!-k|yZ75<+9I)nXoEL`yk5F<9A$-rDT}=DyDh@A9j=}{TOXM9mIx~VN@%3<0YO@N
z_=4Tn>)ochjW)ZRAa@Nxt3Xy(KwQObTOI~X*tmBZJU~*~$%e4iVRb`2k&1u%Fs|Sw
zoFF`{&5l%EX1)GLB|cmIBbPZ?Mvp9rDAgP_U%<-H=iLxxCvs^A?0(nrEtLa{tpb1+
z@-HkbsHr=sFW7o<zW7A~<GDuQqvwh0^d01!Rx9T92Jx2RE*6HFW`{=thP*0>yrtLd
zN>4vGM(!q1X8$tt_CA3oW1{63O`69va>%0kH`&XXcvoLh+#)Wl6J<TdCZ6n^heuCt
za608*>Gd4ouoM_Zu}vN0oQ73<3YO8f4WYc*O(HNZ+a)m9eZIP}%qM;2p*|#s+?w=N
z&~1`-JADpNy-XE`*JWS2SEQ9UeIRrPn1*QJg<ZLpu3t$@b-I_}8JC<AK&p56ghx?t
zzC@ol?MOva?#DZRDaj4S;XRQ3UV%<PX+@UC>jfzbSt0%`)o<6K6(?CRxioT&2<B8m
zcJ1Va@6B?&oHa%NcR~u+Z#f^VjB<DN4d|@bV*gZvME|YBMWd}|v}co%Zb09$d9fK%
znAPt4$?j~?NSiGZNv=nv6|h!!!|?zC$y%toIymOJfST~qE<?06(6ya28Jlw|2c!BG
z!$k$1*_??nv9FZ;Iqtv^B^2+QcH1q%1LvceB&LE+5IhEYH12|}lOWvgIG+1L{V@6K
z0?-i{8`^4K9s<fg;vtqFAVY@&@HYTN;)^(mrSka6-#OKz3b-B<y_6?T2k^#@J+-gu
z7ao}aa8`V$4-Su3Bn(4;#6XaTuU{5vI~y2FK-v^PTJOP;8w<jF=4G7bkVaj2aQQdw
zdcin|M^FT<j|3_k9Zi10s;WVo5ds!|K4ZPT7KJ7?5xCvbJUMJhcG90c22&^h2*T%)
z{i>YZ{W(X4I=3Zh_9}Uf65<CxA5GUjGf^Y&uK>?UvSBLy3u|r6yvwAljX~2&Y|Cs(
z1OrRUa>_f&nK}QHF@(euVaAl_cj0+!hozCJnYBJtQoj}Kk%)h@?4?oa7_2gg(83b~
zU}Hm&uH^=_CPG1&X*t0N!>8EXhnP#m7VtXz*2*k(<b)RiZ?uIn=tNz^-E5NUu$C37
zS}f9($AOnB5dVMpF<U}d8*FK2FE#nr(nFxa18cE!q2Y&3hU^%c7|_#@Fr_|W*aNHv
zQx99@pBwXn?+JArMd}(caib@QM9h{|`{+3}shT1?e+Pp)`?&YLc{U@O)SA4;W@8H2
z-O8uWs@b5Dg=5&t;~Y;KhN>vwaD5!7jH1l0o9Siv1~z@M`*g;X&zJvL+c3WQd;N+s
z_L-+l)IjaWGANUv553a?zru5kBo$`ktsfWe2v_ASYVG!ALt}YV3c`Zo3wq0sblq8s
z$lH<0i5S;MLO?~T3ua<4=~3<CcyyUVwR;1p6vMt_Gd|dc^#mKJ_tNEa3SCQKz|u3j
zoyt92ujdbaDOJDa!a~H>l>RxeH^C6aABp|LK_+*$5{>Mn4&g7hdC7;E5bv#qL;96H
zSGuj$CC6jc^w?YfnE8Xy$WOXZl$KHX12zv_?P(~|OV~2aoJAciMYiVDuun9bzK_}3
zOKY_6%E!YbS)Tsorx2J1z{Wh}JB>j~Q8OWHQDgLO;u<q3-(YB5PFNgm6z)KGw~`wV
zMwPPOq|l(&^vWlxD^8GQf5(($m&h<O8WWMXDfG4mG6P2v_)?wBLWT>}1~769JIyec
z(NTMg^+Ntm^cG^SpgYo%%d&O#!EOUL7nrVG`W-79;}A$76nN-o97UuAT;90hRmXSU
zmpgd1vHb3_MaHcsstr5THlUsESw{=9AOP*`Owg35#owK3BP1>I1whvo1Gd3QE5oH@
z`*gN=sXRSqcV>Qef5-Y&Gi9H%Or4#SM-ny`%2hHu&V-(vZy_z_&t;2N+X*gWCH8!J
zPVBHp^`V~l39QD>SXWRki0n6L_a^d-3hs?fU9heBM6~jLxmZ#ufJeSb<_SGdQ#tQy
zb}TPUOhsvoy!wnj*yv3@0YA7_x$DxJte@_V5+@X885bg`i?9i%5%%MOnRh@NzP8W&
z^g(ZtyvXf>ns-n%H#vChD+k>;6vmB(psl3;XAI#jT@KI}$$QF@GrxaDY06$2857Jb
zx2HFZt85OS33_JRWh@94N~Q7rUs2&(?e%=3z_@1oyvsaOV9uDUg)ZBxKZfdnzEG94
z;{hlB`TvofT3CGg^7=$J-B`JnC@@ioHAMt$$1|jVjc~ohcqwt%&j~+YzUyNU(Bl26
zmc2Cy${XZd^le`pyhwxdehUo8{O$+dH=(@9#9UOei3ZyCd4>PF@yFHvA13Zj(jO%|
z2rP*##l|;fKjgIk#HOy4JW3d7-6Mwxz5eLw5gRWFFSMNJWgF+^;ds!MQHCC~|Mr_#
zySJ0SH>$#Oj>6E#nTgpsV)yCtH{B$3E5n%suU$Lw9W_boD!)1A#z`9_%~bdMh)~Md
zgSzkIAU(1ZM0YQ6nlDe+Iv0%AA4J(^9sXdL0^CkOq<Gg21uN?YPaxVJ#4J3$%#9Jx
z`L^!=d#ZN)LHnLEAPVq@BeNUe8v+Ebw1IT`^7u}rZR@_u8#2i!oZ|smdS)!gL%p^H
zKNOvW5mvKAMV@_ywfj)xCRRKclyH8*lzkiwK{7I`w&LlOQAz<-xVW{3L{&{vDC?XY
z2GA4~Gq|knEdFxRakF<`x_l+)=tMjBz5hz}7_6K5vMxT(^_PTs36_UFrp8yj9>P0z
zK6ym{Ys=OkRbUYM(!1x9gv0>GTgr!!SZ16qGbmee#|BF}H4CcM_*#qgejPuC2&wC}
zd8t@zJ(=0b7z~ha!A&+E-^0XXs6hptQw~F4spa|X#gYBx!z<3cGpY=N`{1~iw?r1g
zZ(8!oL4I9har^yVkWgnCO0e6^v_38j|M$czHWLyvAO&&Q8SBZO@gG#57^!iS?tPPc
z*~(qE*g0I3>(fXwi+B}%CEO}@=nr(JI4G}$m)?;aKEBDxLT<t7Sz`_>$89Oh_w@_j
zw)R<%&o2;yJ0#N<W&oFDW09u=-#w=UmzhAS_UdZ9TMO|~uL_z$k)0?IJ_Z0)DVU$s
zN@G{%Vfhp}ByGx`6?5&;Roebn&C_oS2kGx18KA32JfJgq=b;MB_5t(mXJa}SQVTW!
z1EibnKqdfqzyJUS9loIUizBjt11~@aiCdT?eNdVYyAozG$&ZU&qsDN$zthnm&><pi
zqlsr@aJ5k_25}F@D{>C2(TTlBC#HUmCFem%P5ZY;w<M@*-+uYWZNIe^acx5a<GJ6R
zDN%<#nvStL{Tn2LWC7HbiN~t%fb4#JzgRu()PmyXMuO(#b}NL6f6z(8h*5ipx}7$v
z>xfmdQ9!w`kc9YZ2?do(T3Pp+<$}#ynqNwi&(|~0PI8Sm_9Pk4p~Z1GTghC6=d^*k
zM`4wdag_x78)wZp-+HeVUj5%_C<?4V(nG*3DJ21a3XK%wZ`ynJc+`oy7o^6-78>w*
zFS*HxH-7OLzyn9->P`SI^@Z@P+UPo!&Vrw1#DfR}t57G)thZ!*ddesWaY^FcEIEOx
z$Q;mZ5PGjQ+w^927(42kC<h2^#AdE#jeFdo@Um!wK_zDI!s|*&5P78zo#>NBryDnJ
z26Z@HkBr1K)_G9tJ`sKPKeU;hxL<U~@}mG=YH3LW%~e}C29}}slBx9im9-?53-eXB
z<?g~v*JRIsZ@Ks8VhYfVUU0aZ^57iFvBt;mENSW3X%$o2?vV)xWlfWC9=8BSt~VMF
z-~j1Z&hJ!eiPQTQRK<$huj$Q%1(!Ihguh7!E)e0w&zyiydL-|wIk0bDD6oz%>8oo;
zP7i~~pQp%pI^c>@y-Dh#TPwcjBFzjBdnsj%*6-7=143veH;jg+Y{0dk$KItH>=sD_
zK1NzL=(GOqqB+Ng`Vem_Fd}h4$M82ug9xfMlaCRexw}kDAx>J78k&niCULkq8Sbv9
zKi+Y1l<|;x<%MJXKgE-1SBbv`b!ehbcLh@ubE1VEAVH%`q12mg<qcl5)%zeL*{qD%
z0E9$xVixyMx%ltl6t28=+CoOTmzy-t9aPcbYG=<?7F)KceY@h4&$2rHdkzi22ds7Y
z0n;dF-yL&Q@MFSXAXfU)gV*h2;SNUBgp^PE`c|zUAj#>lm;wHdvRyVyi>DO9P3&C`
znb^39ulk&It($<a%508}64~Nf#xNk<$Y=&%m$xmfR8u7><0xL+zf;rir@uhWUv-T3
z(YM{boS8Si+EL+d;PTs^NxK?`JR0u@j3>%U!96C~Cvg@q5t_X^aK1eA8p@oeOx%=f
zQR?6e%Y6o}p2psIpZ$<kRI`8X{s$BJv9{+X;iaAo0OlZUI#-W}o3&=h2;}#@0TOk^
zxu1n~LfJ<=se)sXfB$0pl09`M8WrpFZrQ41#Vk{)9klkwe|w{q7g(qhKgv170RxI-
zyLBpQhTMrYbhDZ)_{OJnCTY9lEgo8;J&;@4^XHa@6!SDk5+0n%lax%=0!F#dC@LdA
zcP^HKX1@0Cbby0cc~gUXX-m!->@;Xw?q&YO1-`DC6bi9kZeGS7F&wZEuf3da1BYpS
zGIdm&p~kEYfWWb+jei%zIOIxP(|+F{mu{k;%7egG$=6_gs)a2DPzS|%NL}ncAg~v4
z%36BBVB!x0F*6x>Wgqv=N<MJwOz<n$W2l0*x;d%t)g<sURQOToZ<pl$eZ;5efZOs<
z?-3~B3>grunlB^^$AossslkYlP)ig5@SDbu;o8=m`8@GDnt%Sx#PtE*BWvS#inTLW
zrMG80CGL*&xuDyulrniEzG0yECA9=&0({Whi1=n{=!coN_<s;Cs>T+k6V9aK>#P?o
zzvn0L*O^Gnjo8uFao=kJ&U%H$Ewe1mBuri_^CxfF=TbD$;-n5&A7naWC}{ua>oXp9
zNT1|=DPL#XWMOe~tlc4+=EBfd2orAjEI&*XsG|-a#FTwa?f@kz3x(R4Cg|oKu!IHQ
z#K?U)J#9<KuTI_VS;%WdOfiF|?;|o;i$=#(FBd!fE?q}QLAXk;JY$(YGo>7PuRvt5
z49Z_!ErN~46($@1Cm}XQupxQ>^Q9-KSNsK#Rrja@#WqV{nMTo&hiINq-1Z8f|Ic(r
zuFk9c(a=UcVoa{BCWEbGG{lcAOi|RqWwxgLo;3`~b*I>+e3FpBt}+GytkfbqQWL2O
z11%I$BbOVu9-%i4n{oL2$4=!XgmE)$S%PwFdlDPZ_!?ti8v-(t!3x=CCP8?c!4ND~
zTSw$FPhMS3$nXNno`M1GArG-aA--CNzh3CUQ3$z9xv=#0fs(Qp#Y;6tb(4#tQdrS3
zjS4PsO!Vqz6k8O>@_iZLZc7DuO8oV?PKwYV&RL&Nm>2!Q{8Ndpg(H=cUh&x(0B_QU
zvJ~zHtFVH65K%tmof~}57-yHdj;sJbHXbwk{r?Oz=8Jt<Uu~lvY0fV-1z-=x4<;@m
zzlC%gDgl#i_%W=#@9n73A<{<Vj~$wV;G5^OqIGCcE2v+eksNzo?ZYyQG$Wu3z~pQ)
zCBIdnxKBuXZUk+@=$fQ$a1$MT={vd5DEYZMc`+ml0IcL@XlFc3zQMX+ESm{^-zmm@
z{&s!w7&%<`ts~Or@pBcR1{y34^suaiKE-QuMoun=CMsVAhDX5;e?$*ott?#@L!*ch
zrft+ijVN3{*?trt9XX9#&lA$I_UQT^E?t(Hs*+KDTGv&ltF&727$r@o&K^#FkNTkG
z=F|~4Q=(YbK!g3x3@X{-9-K9qgXm>Y-1e}mx&&{f_P{&nO!TOsjxiy2(wOrQseXxq
z2@=1Bisch#%*#av;ZigL3dnBQn*25VE02_^D5DRR5<`DF#w<Si1l}8^-f$;Ose&^a
z+hzz889Q7@oPd+zU_1qlflU(*x!<gJm51lFSAM(Gxl3q)r>n-u?Rc)*H@Ww^27z))
zZnL<|p^T?UK5g()!>!S3aPY1H{1`>zHb)YRx8bOg2D^?IfZgWXSP?v!o>>Z4_uc@z
z3*L!NYv*Ju>$_~Rn+D9?G=}_ly71T*1QKmPB?&7Kgzu^~E@ha>L10q{C=e$jUm+hb
zCHZdL$zn)0$mRB)4?kW3`mW8K_JklIXls{u594WqGMGRug4R{~69Jms^IK07rog)z
z5^!=P6J4-~8>Q)^bv{&pCtnGnE0Ei(uqPQ8S#5h0_}k1$RZo#DWW^p_zQ;`ji}F$g
z+e30!Se4;|uT|*JYKR&w>we?15lcFI&a*=}jJY=s6I+sn(KVUw(qagzgVKf}b&%b*
zhj{WMqxPlLm_Q_;`~yNT+5Vu?%(p_nV08&9SNrj&_zu7>O*GMxuu>b_Ng<cC0awzT
z_Kwlp9#9gdUFYEdTy`7Ci^<A!IN1qKSsg`ZGKw=#oa+h32o<ZH1ajQ4%;iPG!|^QK
zPPQF6A>HOQG;zzYGU+;#W}K>2i|>w4gcUEi>(CCz@5|22?04+OIkncT#jn6iNIqGz
z`EK(KSq;S0H)=R3rvG_?=#uy3=6)%2*8A<iEX`^KxFh}siK3w*VLkUL<D?5T?wi38
zxFXe$Qz#b=sbuBC(tCp~tgHdgoz+hJ#8N3W?X52FX6$F<5h`Po)12~UG6<SC=EKru
zoB_GTA+$1-75go{y<ksp%H;T1&{-yM^1qfDcPa)<IgfHG^+N8yO!RK;!{T`Z1<oO4
zN4ZjFV?LyUil9{uBuqRf=sF7S%5sT=erv#;ks=`wB_==;nHXB0&ln-3KvJJ&@gg2t
z7>Y@Q#R|Nsa^ANtxjS0st)Pu3I|a?#nA}9~rcH_aWZy7vY6iFxv!TCRPYAdfP0TX}
z08!T?^04-HLvF%RFfybwbY>&$l?_9?<|Xbrlauw4Z4U@if=6@IuABZ-t9!4pp3!rx
z<{&7#ZBq^5Wq<QqG>~0@I7pFCo2SRHI6AJY3nBch*AS4{e)oat5AjcTOzVC7&07bv
z$T#+0mROz3Y^~M=>hiTAv#Hgw!fBI~thDWFh#?jvd_KvZ2SlVK>IWkp=lA(jlZ4gx
z$+hu_I|72kDVb12bNYaH>~h9Y5BXR$J?0tjn9JS-VTn_G?Ig&G*%$XT9e-09@iQnE
zP?S+rUNN|1V;db?G%<sFbIVN(odgbYGIbgI6q$b&!(P(J9%utbfkoPae1n~%rxy~5
zs#1I>Gwx;9W({H${)kSKVgvAsbc9cfVN_nuj|3OXI#Gb>@&-qSTfJhH%sEPEbsD=v
zN{l!mpKmx0tr+x|l9^SCBIovm$j)-)`PwZ~gvhZzwa7%E2Sb*_4ZyEPsuS+23_FD0
zioHVce>k(+>*ZM1b?M0@EHK=P3%)Dcov3fVE)eCFZrYCQA%(SXdv~%gwHCd^+TDsZ
zy0m&Iu?!9zDNzfr{X=1<FxD`aVCYTdvUxX4+tN&wS#}5+bB<E(K*8!d)^mvyRL;ou
z0}C6Ft>ba@>3(H8l6(83;}`FSuoI&K`znZ11|8p04=*6A!6?96etzgUWZ)sm(5GjM
z@}5uOIBo|Z9ge>!P=FVU2uw!HN9rV1V;l%~ZVuatu1%R3ARo#-qlv9+tE<jaTNSw7
zo4cMiq#z7;w=a|;QDkFafchp?DX(M#)eydxtcE=A9#F7)ZUYEUr;D7c!JBTzsdziC
z;8&FNcFo{CYCs(71vkhE*<j$*zkBfr$<lzdq|wjMf3`|Y&5(Ss1e)305`Ta4e0SP`
zJWf&r9|YMWbteQ0@@Z?5RS;`#%L-fAQ9rsa?TTu#7BVq0#DnU~+0>}EV36Bzd8fd)
z#s1l(43{C+?6-iX+}{X_FS?kWmudOS&EHc#d$o!imz`sB@C$dusY!ba;@*sYOqDsS
z4Q4(TFEX{OFC3rNpX(Fs{Ljy?b`Kx%I8RY?SF;Z%weF2Mj5GyTDSRtl1QCBY-C`j4
z$5IqWzEGGk$!T+cV494Epg6$@at3SSN<Z3HZ~y`1Kmc;oz<`u=00TfBxc~qFQZ?hJ
z$&Y}CEL0-2oXS7c5>l-91uj9!Bf}^pza*CSJ#?Co|AmVCca62Mc8*>o7b)l8DMfz1
zXv+0E*N%ccIz~gf!)-*|cfOt#Es;aj+>XZaAwt=qu|+(iP$w$S=Cu#&$Y1(~rki=!
zy`wz##$iahtiKgW^Q${^_N5y<jdD((tV^&qP;zEj0v=U5&3SLgR{MyYx)rQR0~Oy{
z#&NEKZIMOPOQg!1Z@nX&2fKyJZP}8lviT+2jTYM0Gp#73E|2HF7Nnivi)xV4-Wpr}
zgO2W>2s|FD{G7w%D4Zu%b!&#0=XDuUMasO(GJ~dU;2=ti_io*Gl*PW}{(nf99E-kr
zKHfJJI5wg0FZqv_eT*h<S?|E)^2fa<Ffu6tR&{!k?&o8@6v@asZT;vzrS)G66qdVc
zY5f<}<0x{k1x>j^Yf*pi)Uk!NfagrMS$rkPwXJ|*ES%ihFW7jrJ#h902_+oC3)s??
z<VLE#_qa<Otfs^3Et;j&sY-r$Kz34gBBq-MYnm|p>5)y-V^;($m+3ZDTBgO3oLO-w
z8=D!rl=oi^WeS``xUcb*KOL(e3-QWV+bxy&a)@y=b>u#48h3-}Zdu=rreh&fV}X*f
z^_1Z2uZ^V@_B293PB{=0MZ+&b@r~OG=y>#kn>5lXwY|c-SrN=dg^$dm(d#^|F%sk_
z2Rvec=pNZ9S<GD`7s6#)^b=K-dn|Sz4VNKbfBBJQy?yEYqo7IAgb?fgD8VfUM%AhD
z^i$y%*#o(1(fkz!mJ^BY_((#^wOq2nfcg$|Ff&A3!AhpLmlnc)+t&O4^Tf4l)w-{z
zR*+cRHvKvxr!{(Rtz?I>rv;d;gU_kF*r~~KgEW>*N;ho(NNT(HbO^t%KeeOO6kIos
zh>lp#C97S?aW~^dB6*W&-jWP$b9R5*{h16ASUTse0@4qV2e+}fjD$pYv0>$68ei7C
zz1poE<~O?}O}XWuc%)2x5?U(k!>JH?^H3y1RxGQA&3d!KiDxOP=B_=^&_i54*!CnE
zuld7h)6Z4^dXs9x91RSRLgi^vK_d0QEV!K>g~`2gkh@h{WW~<9B{^i9h34zSBNJ+g
zSUTIG!iUZ!##yk{4~l;U!%}QIgfoHDVksIzjPHnIp#beWtUca#h}k}CFb7vt>s{1;
zP!}Er=<yI^5<io7B@uN5f*N8rJBquV4!y&U(Ex?sd{k$NHCSZOZ@X}EY;dRip^fX9
zT1o8=aFHKUWRz^dzpDuRlZUTrUB=dB-yRNqzmQrm|98eUhiwj+7B#mQu#3Vm?#WKp
z6l^IVSGJMCbTw_s#{;T}OlG>Bbv0+(ffP13NSt!h_E37_q=0ie2RN1#+I<?F1uvU)
zDV&6x2|x^WU;{+`<RdSB<FQle!eH)BIRUOPlhjhPH|8o+v8`>eitJ+R4(9tg=zskC
z<HzYH*C9mNRErx$3cQ$<2a=*UO9dpaVE6kx{K+Kv?&HH}|LOOcmmw(p5yVeXk80Df
zw>6}^m|}kmnZi?fe+i9ce($Ya-3uI(iS^e6kK0)QM`mYo(^okv0|j|LkDtmff)lo@
z)7XS%Cfu0Tzqq2aT&HF)dOB>?as<YN$$;w0p%*=dr5<uDdz4c4U?8tRj*l#q0&keA
zQX^x#A(gx+PE96pNXak$kC=*2#6(>eCv|d%N~Au_!F72WISt;3t)nVH0tOnxl*=;p
z`%XDvnO?oA>r!>_T?F->B+~{AzIjK7(ULr%oOv_(ajDR^aR}%ATchOj6oQK4fw;NX
z8#PtJT5s}s;fS1CLn?iz9McLRcDtM*gz9&^8zOjkKRW6Sy7CuV%V_H=Kt~+W@XLaz
zmx`yy$PSQxIr-|41+;+Lv_WURU(%kYbIxl%xN_(PZUn~{jb<?>ls7%x8I~_6L$S)E
zK2$X+CtS&02!Lc#S$`P#!)(~xPd&2MRbi*aFS#s#j-vjhG*_Gm5Umuil)E6S&7Ah1
zwI{J!{Y+l{uA3|u#+=!UyD!<}w714`H*78)qJU?Cmdm=*49D<+7>o$M^dxWP{WIDe
zc17YgRn~*~gNy7yBTBwpMj)0E>B6#EtMDmFJsn&`blP}6q_|k9B~^X+%y2{7QCK%M
z`;N}1iC#Y2<@3pkMpI)PcrJ-Jpx{5$s7^J)e~)-A(d|Np!}Yh3Fx*@Qdrtbt1q~L)
z0@~fPj$pW>ZItB0iPK9t<WYvYKA4HxVq`6RARb$-k1btc`dGgW>Pg-X6A_3nqHa`-
z7nb%J)kzBk7lBguG2Tx`Ums8g&<V9x3O<*bYrN4U3*d8AaU`FlA$-_F_n9Ekz`xHO
z%RYy)>$g~os2b6?^QhM$zw<&IViwaGrGCI|J#+$Ur;!kVJM>}3aYE{&q#+X%GH1l=
z-Tq-1Wp3BEP@IU{#Zag5=dirkGq8%8;h&&|5C9K5p5(L10e#TmSeJnGkae1khdW^n
zt2(a*;YYURVJc<IeFrbo!3!AADVYKOzg9*1nY%mdB7D@ezprqWj!<n9GXaTD_83%+
z|DWU!kyxmIhO#8E`@lu@lnDYI>82}jN^8>5+k(en&%KLTJDB;Rj)79%6&BUX^QS6~
zTOTO3p$|E?2IS6tMJ1Uqph_)DDy*@Z4@^mDFl!cf5Y$!Mt*oz=*=0#QconZ*27vzN
zwkV;0KnY+X74jy#CRKI&wJo!nhwa)lIr)y!?-ZIEM3RyHVFx={goZK-P_aMAPar*)
zD)F8{|JFcqLj9*0e3p>uH19(b6=W=T-%kH~AvQ)FMh$9<h&;+LfWZcvhU0HI1Mh&y
z&6P>2cdb*5n~m4C(c5<s9O+gQcpH5gyUnsdu9$9~u55YV@6iq?DYrHzq4}j=w+=B3
z!Ve@lw4`8l7G~r%4cY4E?E&)>pH-x&t;Uz4Y3CK}{D2uPuo?OB{VSM7SV-r-lUF1Z
zhk$LbX)`G6AF+#&_7jpEY-nJe0r(RG4rn9vcU2$acMZsit<qMF!u=u*#Yuy0_~M13
z=0T=)F*SKI5Q01%OjA@^8{TcQ(I0;rSRz+ZBmj&j2_@3o+LyWjH80PxzmX_C)g@oj
zf#h$w!;P|r%i$mS$e~xd%q8nDnUVP{8ONfxD~!@5z)PJC+l<Z8$8<*a*bHo^EM2#3
ze>ZK3?K=uS)l+xY;#HXG*F(oA0#?*s<U?s<Gfz@whIf>Nd_s}QN)|N_fHFA#m@(BO
zwhI(x?G7c@<3aeDwu_H-d|N;8zfQ)J%>I`KYA)vC;OsN4F1G<Iig_~iX@|X;iSVHS
zExd;AsiFTpk0dMcH(Li5^kNb?C~>I*>r_Is6LLalCWB@HsE;N-kD0C`-Z<QY;;9wv
z7}kXuiPrvE3x&_|q((j0%Mj118!9~u5siq{ckFP>OtpxyL>QV~6cpe8>mYL-bDLAt
zMJxmBsD14lLm_&;Wc@zZzw0O`^#bce{i^qO>NdjQ06{>$zlJyqe77g3XfK&8`g*A=
zmV#QXXs@?ZHU>S{OU+6I{S-sXpdmxkd%8DlDa$k{ZIA{%+(Ow5^OG_t#^T%eg+w||
zN2}N+<h>^xj)@UCwM&&A7J@EWpN1cBf38M3Vb4*vstBhHUgHYSS8|wvvX9Ir?Clg9
z0ZEN2IgIme`{?1m4n(Xv0;mlArc5D&-RvDJkpfmyk4w$G7c90iR)=POkU}%V=XKx5
z8Sf)KYkRZ^3s8_@6DNNetsLn(>GVCPT1G(N6o&hh_GIZ=G7Bc6PV|a>#aR@KOF-Gj
zf=yM0m(fnK=X^m<NRegl7s0}zX{5f))}O!6mTLUDwQl%8+h2>aXF(H}czT7IOg?fH
zqhsT~eqQvhAL=!I7fzuB6)JUWFKN3wV+ZaE)*cG$)Nnb0{1IYPTnPvI!T&}cDsC#i
z9+-ZKDZuKqB4Pd(R-$0m2^fQKAxoV)4HLuO)5nX{v^<B8;H!9D$#`<_E;8l|BQ%GD
zRk<dZg6xJyB}lx=GqFYM054JB#_xx(Dmm$7P7D6OHP^-zTnN}JpR$YFy|0f<sZri$
zhZW-#U!|6j!9wfA4l|Xai$e34Y@gcu9gnYCBuZBDz^`unFxE(Fzb?roA4-Z^4v?M;
z?P>4fE8{E?1;wqQ&}390Ec5u(!{8|4)pM^2Zh>_~!$3Dr01e~;G6VKNUfi62!Cc|u
zX3>@b|9kwG!Jv&+$^!QL{W+=F-ME3|_}T1<I7yT1&tA@|bim&q`%;>4I~RcKZ`+}J
zPrYN1iJ!-6vfw~(7nR9+j2GIUoo&|bSC!HB_(gjKS)|jPe3jv;-gKwbGa*0|G2O_P
zr<ROf`O=$zgMa%ILTs<_5BUTt)^PaR(Q_;^Exa%a0t#+Ws%shrMrY$@9LAah41?vR
zh2V!GTUh5xrLn|xRcUu&3Oq0Q5m>Q&xE~O!nVW7^%I&Z5D7a=>Azzwy<uQ_LW^(8Y
zOa?C-xU@lvzo&OJ54$SOw}BKOI&+1`yqm_encFsAw_gzBW1TFY2whG(1DM-gopA`7
zJg%A-hEu_!K3qoTHa*Ec!_mW&B>pAeGE+}*GCd2oFvT=0_u`$TTD`UBd{BE#>rd#=
z{kC7c^s7+1s6CiP0UmK8$-+%H%NW;8Piz%ownJ@T<7K4EK?_2^GO$?wK<>9U7^wTR
z|9M{+Wsg{jKnkxC1XlV9%G4XvGT_W6AJb?S-?-%s9k60Nz_%y>qZwM7>*Km8G+pm%
zSBD@&SO5S301uFW004l~C<FVQ^~ibTy%1{{1S;jE%cT*Uv$<v>R{B!YYw&zCgqY0k
zMr|(!M>i(#z>N+s@Wx&~)c0gBo1c!SZ%;Gegf~RfE|`w8oV^ee+#gHS+xb}PF)xf{
zWb>%|k*OT&u9a7VV$-RP*GJC^9=T-xDc{SX!uU<)midGN{HWq4XEdyqYmg|+UyKAz
zX027BoAj@_?)G^5XjvsCTwaHMP@{bWK@0nS{I92OaW1a7hdM#U&@>V^TJUEl+XfY{
zV+V{<h@S7fX}52p^_E?qQu78(NB!1YngXf(cIxQ^p%u7=me;saBJx&yH_`qqjH<1`
z=x_zR=`j71pzBs~LUb57Z<7=EAn`-)?PLO@uHkXWcKkvb17|&$Jbz%uAmc1Y!+r$p
zXtMnkX~l#8y&+Qx8ay?4iPO1U13+7YvJ))$)v!j!oR<hc4aci=NMo8~uu&_B=xB}*
zvkSk*jy?i9Ro9xc0)Hj&{p`T7Z&S_Fv}t<j5`t{I-c3It!-KT)E6HvTCf(>WPMN5;
z*$>VH7^^w?CH+KbkDr`awVHaczOK*(Kv(Vu7%4qbuUR9~#k9153}IU3q724=bh?_g
zXZcJ%8m$$s_3He>k|kG3I?HOs@oh~fOnRF^QGen?StDVGB2X`vNzE!jC|~X2HBLm@
z*7)MV7DRMMz}!0dwT}z}-TAYSHHTbum-|fxZdhtq-d`}`sob(C&#8zp+ba*|sWS@b
zKku+&69ZXw^w6ouK*oLyMp|?hm#8jVoTpU^A~dexUQ7(t_}&PKQx0uHP)OdeXZyZ1
z(!SS!3SyKgC1uWWg}8L|)trqKZI5`Yz<o|t*xGOKelmRv>Jjp&X%Z$wzcN{#*~=cd
z`cU|3t4UOnD@L<)f5<-~aY~@AaQFss#B^olrWi-Kg(shnUqjG%OacK$f`!WZ4SIR`
z8IJ0_u}%lf59U{QZ!AtidZdxTzm2MoO7zUA|AZ_<l{9d|LQZLSY?MVlcgdOrZHEOV
z$&EP{MZr3&#B8*yO6Nz3XXAqjw0L@_;{7PVdsvgu+lb20`8OR|xZL4mrk^Owy>jI_
zLx9jq{hsqiO&=_q)xcwo(AlNqF90?rb(+0^5CyHcZ$37l`db5PRxMR48ND)a%76yS
zgl}u-yCg<b;AZH10}1)98~;N<)HNNm6X;c$7E`IXlKA({BQl+nz($^^HCkEB$JqMO
zGL{*XKVnvy?XL}{p`5PdBo$w<{AnJ7y-UL6DvfreM@<HXkFPFzth@1IFJLsN$g@1%
z&N;edPrNW(4n&1tcW2F(I$6*Oi}rd8{Fk4q-0$|hz=rwc#}@JsO#<?9;=@ydpboTN
z<O@^#?#5P2EvM8n&xI4`u+=QO3tgoIE_x1o<de3Gn{0=fbli{V_49WJ)`*V{r)-Za
zvjB<DsqM|ht(5l-(Kw^H($mi`_?rbxS@ma010RmD`YUE@khMm~OFqES|IS+SYDDIZ
zkP^Xi&iIU{Z6nQFaWVNt>uef>4g+pUJ(m~XLIisj54ID(DQ-h0Kn6qTjcCAnRYl*m
zB2J&k+Vtcp{N)P#-bq<M9^<qJ*HdcU<V=KB*8tJd9@lNBG*aRKj-cLToDs$X0F<Nw
z@X>z~_-e%t7EU4>kAvQEThJ<~B5&Z$d>8m+{72WG1*6mL(wr<Q<;j?p_FoB_zKVHs
z_6W#ikWp1Ar)*_9z(gXeM2tBT^j^Ge9@d9Vg|SJ_ZG@^Ca;=cTOEw)>g(125KV1Hf
z<v2?Q`j^%v{_LgZgp-F9t17W980sO8%i7Gnej^+(CJ&ChAs{2`z=~XBl)Gwt1w0v=
zF?#!(v1N6|^J&flP?o)curpc@c0nUj6rUxBR1p{nRG7dZ1i#SGVW{LUcpzgTb0jfr
zj#ma$9i}oIO@%y$fx7aA-KzfB5ot4pBKb=K4m4$)+rGOfb|S_<E}*FF!|~@5#<*Yj
z=u^=4NTApZR3bqoMnaLs>9H+DHPBGVB&p9!UCRA)OZOJm_Q{3mSYj3Pkgy1mf)-&b
z4RMgb6m|HWQ<Y5q`xgTUK2nY6uTNi7i1!O)*)y>qc}+-vTc}cR(1;3pp(EAQRwmcf
z%b-|0ZIs7!nX18e(+?n|k?2f%w5fmeRmZ0%oG|7%$LDmGbp<ew1ZX{UXEZgMrNa(@
z%Mzl293lE-6!S-S_L+a72doR*_iEm^#(aaE<QVlaIR?lOp3bj_VVGV~zev$JT`0I9
zw;mq=Q@dSeuOEjT{jD&fHdk=(Lc4%TA{{~W-rgp&Ky}yU-XS#l+~w6^f^k~2g&td<
z)tbqwn=`9WbSBaf_=13{&7+OC=*NncjHvoGo5U3YdYy*(1{|L*IQyFj-3ggow#k+r
zaT#2D#K)u`*W*X2zp`vJkfqZDr$MUrzHftrU{DF_U(X_|6ujx^d+`)Hxw!^Nmx^A9
zc%0@SX^3(T3rLh%bhKBjhc{*HrU$3&&grekyl=Z*SWY7Sq}XF(9WKUb5RLq_6+G7x
z;nF|3ddze*@Fx7d!uzbsx`EN&9sy;OXRh6dlQjviRfXX1#ZjHCYBV@yoIPMnMi&y!
z+Y+LeIDdFFUFX<;D8Aq2aWO(!N{U+E9_v^hy(mK}mAtITQ;6rsD#4%V)fGVmf>>D1
z@()o_C)za^y#i7ETH~{72auWG4u-b+aSPJxSXPy>bP%%yY5l)a5@zu@_kPioIQhT<
z<GTVZJeXOVpfcKZ1MA@x4*8bxMM)MDXEx6a>OU6)SO5F`>%tZLuaYQ=5?^=+(5Al4
zLuWBwJ0z&abAccpu9fm3i{L}yoaxj26gPRILccL;0Z+2_kWztNQOxJtSF(VKnZBoi
zuk)bO#VBXsisyTiG+(2L%aSxMR%Gea(qJ83txh{gD&`S-%1L7gm~u0P>B2L`Gtac)
z=x^oI#Yi}h5Ns(alx9dXLv!S~p14YLtZPbi@w!~=HmB4P?i|8j>4%3wA&eJFoj1D=
zdd8`J4eVV1Hq+gIr1Wx+N>-fW&6KAqPd{fM+3(*NL7~+N17K#tW=IxwTkqlI>SadI
z?Q`opyD`MmThPYIgR$kJ87{B=uAGr1W!cHN1tv%=Kulh)LK=0rMQ#2fLZq9kt7EiC
z3D!Xy_^XdsaT`{9Oe-MVbiY{Lo^7lMZKnZkgY6^67=;&8t_x0Ox`B;DgrnZ?CmL73
zRSr~cn!(wNAgNyj`g{{(!1?cDJ}rmwp7&;%Ia<B0Td<}ETzR)$_;r@#@2@1=Kk;Vf
zUPi3_x%=Sh5k_o&)4pCU)E!A;Hw-Bh)%FvcTz_5`^KqYj7S8Wg{(UUjG4P0t!BmiA
zOfTJU-hzfZv&5Ht0y+$#()Fu&t{%+E<h@x0tGf{Hw)}V+sDh(l<>m~A_(SB4_g6@f
zsuG9WTm<alNQnY3df*`bz?U^pyXI)9LFyzb{$<{hg#&<IC1rNHH?q4fYb?mM7A8rd
zu#E!Pk%TKbwIvJRe-2n10I7SV#ferrk_dm2kX4yY0;PMHZ0eceW^O{yQDrApK!_$I
z38+t~)H}>&AldZl3Z}tf@iSFR|J;V|+16wN9=mQ-#!@vnoLJX`mf|V&06i6$(21Za
zY#YxcxdqtPLM%_Plyaw>b(5|w1JtJdQdS9hy?+H?z%{v}+tWHpEi5Go<+OU={@&tg
z;`i3$dBW{J874+l`@ka_pznK~R4+OC9lwUWHP(Q`?96kdx&`b7H0PnXz|FPMnF2WE
zVOWey;9xHlBMzDZ?<~{bKsa#l)D|p|Cwp7bYj*ZSy<3^%_~y@m$78AHsvT+OC+UvU
zQ)agn4O?ewem1LHG|G<a1?82|=S8Q<@xjYHW1eD`i!e8FOOiTE)dxJv39S+jHwqda
z8tXcthIL4i4nbGge)sIL<Erd0b0VQda}_X@G{2$vSfSPn8Qrw(=bAMaKWTqL<|Cvl
z2>do=N`m><YSEMF-O@nVGVa;(CfYTN*}!Z(Ug0_q#LA=#l?W%E<i)pcmdHI#;};jo
zxTLE?mKqlQu(v>aikI(!<JQVh6wK^Ve*YY>HQRriNQuNXfG<^#g`8rv{Y%gYBzm(*
zUdz!Flv#rvm~<77tjl8tCo@kmPj>&-jO=evzV#)=Y@`ta^teOd;q6^5w(6ELV0SAd
zP_RMGvXASTs_S%Ft^TM_3M>i3x)bhtMdbf7k(a+vgX94YIJ`iu5J?m#^h+t-9+V`g
zc(;``_KifUgmySDurx#yKxf0-pl3KxMZ0X7OU5OQ@&{}8d${F>qIlms4&+vEOjKbc
zw1E%&?I^kP@|BP+`PeLuuiNm0BQNq7hXFE$%|7uQ#Hk+Sd?51P%PJyh%T(x*sXcn)
zY8YK7HJ^?|njy-|E}lOeNE<+h5DHe-hA?T0E^=>nQ4QbZWOylre@^`^oWrh~gmQ?l
z%2u;9TP&8ZBK!-LNhkn4+FS#uFzS3vbw{)2&-2#9zL<jGVa|0U>;r2!La{z?7$+V)
zS9UKyh{yp8YFb|)HG}V>5<AhL$ToZ{Zk_xai7<H_B~Xw%?Aulp=zu&(VC4ZF9aG9M
z!)O3CiGTnA000000SchOIppVe6UIjr@czDowX~hwH)pq)GdO^be^bo!>TV-&gd$&!
z1eshsl=*X^%C|wGvC+Y<)+#ZkKbH?*a{u9kyK*F@NDVwk2|zH-LyNG*%O9zpq0!fW
zKE(JXvMb1xUE%na;w-v*D4lvTXql)AZVGrmm}E5y>(_qWlLA>!$DTs-B`p&=${YV7
zSekpGy%FT+C@euuw9qp2O=4#t2H@gP#D_Z~gc#b?RCe7c!=>@hF3sx^!tbP*NL30V
zO>B91+fbS@p=Q^?sbu6}T(m&5&IumJ)@bs5*S49e;kgXcb;Bt5Sc965B2<yDL5QN)
zxmO9C?W8RfiFe9R)*mxvU-@*n)i34@`vk%p5rD5psc}o%x(lAiZfIZYM@TNsugW=?
zGqq+e@FwyYVbtz5jp%YfDw1QwQTa2k$NBjV*Q5fq6A9wTjko*J#ebJ1mdz<JyYZg_
z^b^M~+l`A8LMJ*$RIMnr-!@v_zh@*HG-cVOj-S{|rA98UOXhTViEfj;)kFGXRcw+4
zg*v@qy$00&6zkS<OW7RQv27Z-+$i6iyt|#5VNlWltfQ86%lwgtyVyyL@HdW?4sb9F
zHYnTI^tkT~i>Tz?T%6=P{#qpYs}O^k8C}xq>FRENHX!pC8fUh87S#Jze@wB_&JTGh
zZ-hB{*U}t3E<n=N%-NVN0RwRht*px7oK{p>M0dU66krEmLzC*T?g;e9oOhc)>k6F7
zpEmajJ+GzuWZn3ijZhNf&n0XO#$>axFHI|l7{1e7o3Ut4_&VsSrR3~N)x`k4)D=5%
zcB3v%JSv(xxE3r%$@KgJIl}_;Sqr$csm%;+p?ApxGFp<$F~`Z@ttzAgY#8vt1kS0U
zO9S8zPwat&rZZ3^(l<Wj+=tZVWQz-?dKKIjW}`hba^RPA0c&XEFw2v?@dEhr<K`8J
zBlbh1W?GTT(!sEQ>^%rYmJ*eIHe#EDc%6(#xH1ILSH+eYvn-Wqr>Y|3S?sL(ki6no
zzkSbDrEh7~2Bjyi8lIFl9NW6s5-_ekIs#As1fmh)b>3sy3bsw+tM~;3I>sRs!UzT4
z{<Nk-l64t3Kls)(X{4W-xcf}o@#15Iv^Xep!hMGf@6%&qk4PnL$LNK%xOd88vSjPs
zy7r@7FV+4SAF0ROotDE0t~>GA9#&ou+-^R=+Z_$-&!ZLNI@P1`pK*%wGwav@K^kol
z`!)qM<!YB~svFf2)LGAM!a`jexvF^>Q)b+YCX&uqeS7=^WBcfbTN1DL1Z~5GHAzNs
zIzV#;%HqKr<CZ_+bUQj@r88hIMY11I5#6OPLK}S}`C6Xk9`H=bqWToX-5_!r26>FU
z+XKE6E;ixTa-dCC&CBxoZf9|vx@Q8%zYE5ri?6`56FpZBJA*4s6KQ@l6oXu_U~mhG
zCvdnd*1jk57!}-Z9XYYYcy$x^3=7hL2R2PM51o1|hQL=tJCWLInOF`7TYZnpJ<&ak
zotgLZULIm-uDq)5Ox77w#GS$-iOI+}p~Mo8HC+Q$T+f1hPl1r|6p)e!zYqTzgt{k_
zg7_``g?E71*!D?A(&{K_K1tqLDBtw&HC@?JAA-q`z-xGSVIa<7@*iOB0bY@nJVF|o
zIgZi_{gAe_cKMooGB%SHS5WjzT}`fQhC=7eFT)N!wp8`*XD0s-VhX8JJWe;20{wqy
z|A1QmdH6v~`9g1qJ$f~^sg3%vJe!2165ut6c$_Pa9;7{y7~OPcF;T%+)ZBIOJ-Atz
z#kqX%Cb9n?1I(T|k3rn@gxxVi+@LAibrPdEj}Dd~s*lGQIv@FsQHhW$0#37Bz&hg0
z6vQdF!{8gtffCe_J9b3n#VErZ*y-j!idyQ2O!rtBITA#DmzFns@(y)CM#ELS@R@mf
zj<}Y1wKelxNV<bZV2Y2Vn|DlHrTQnVfBBf}Tnf|C#eka#KrL~SK2GQ;N(I+dM(+q7
zNol~tL=*|*$wSsf9y&1U<34p1T|)=24@{IfL{cryw;N>)U%K~24+!e%HpOuM52r~m
z<Lw~n=a8P@B`WNExGi=cexfJv-{XTE^0&j)W;{-A<J)1K7=3;U2*nSw0Q1h^n41T@
z%RS1Q?0H*v7z8@|1Tlv>E!(5(zTYwp;JC-7f4(t<3hy~Z-!xOw8yS>DmFjRyjO#7!
zafezb&1`8gN+{jOHE(}d&P%kuqT0JkK~`e#4H$!iYxnqJOw4ODzHAV`uha7eWu9P`
zWdDY5DV|^<l?-l%jY_*9qD8cN@W?>)!_lgKgQjJ2V3f7c^)r$E5l-@I59J8uv8yfD
zW2Mz&<4C%|YA3xshy_vf{fT5SuW<0_rQ~(%&lyJuY7LMyp$23JoOUILm>#(v2+PWv
z4nI4;Z$^H=^ZwUg0C{p&UwuTo5+z3FLlPud(;S%C-DgoK1tve9uQJ;=4_b}XI8p+q
zNoy;0EWL&V+ZcAS<Uj+(4-$_mx2VfTAzn+uI;G#S!TiqCGAHNk)7&R8@br7F`nFwQ
zBMWGoCMu*CpGP7zYs_SA15xJ0_o~^n$%Ofl#%|2RK=1mEK6UFJqXAE7s231egy)H2
zFD++~UR~(==lWP?U;?b=FjT(E97ohzT4$|{^;eCt&~q~5Ak^wh!h%(uNZpWA4FIm=
zt1ec?^#dl^j@Np0n)x9iTl!S}e3ksZp}Ki<<fu;WH;G!c+>7Q`dD(Mjz&xUGC(}-U
zE|0PSGQ`^Jd-njR#Vcn->y_7wxddaUn9n4r_x?=_-Y<$GEK-|eV3n0~<$#%=p94o<
zSS%Qd{gU1M0{H(^!<>%^E~kI>e8h$?&5Wf@f@jCus)*l#wL&85lnlnCqJ-Fdn)*6u
z|2E73CDzpT0R<FZhOL8tACbbovjE>^kLl3_LW4puBziOjO`(0hk$qk+xgx!pkLl$a
zEuZ_4N2$NAu0RL39S2?YcH{jdBV^?VM$~frNPBr{0qf+*90PgjEDm5=ix3@?S$TR`
z=$d>gcl3TqMF`E}d?aIaOm4^tTgQpo=&}mB9_|CjjSu`h$~tn;`<*8JMf~V-ZWVh3
z4|^)10&MQCfF}|b14X9OJ{7d+Q0tV5@IDkCo^c_5B*xch9v1Q0a;^LZc)*8^T#^e@
zHSXO<Tm^V?p9mL}8k{L-JYs9>z(~^?#$f`YPP7&VQeVhM2Qj!lyLm&Ymvh4wR~@L8
zo3trHxp9x=2=}uKQsdn<dLtKN>kH}3h*-c1a!?i;(@WQYG@@slv0b`eRKLJG|IaxM
zml}hso<lCxFptIa`;<}I4NB6Omw9@{;P?%#)4y+8*bwn?_a>@Ea|=zWuH?6PXN(D^
zOKwdq%t>9HsP|CzSEN=45g{{p!}ep*5+Y3>eqLKDzE$@}#ZVIk7KOso$Qb#*o!F{U
za>W)|{38Mv*Gj@u;JIEGGdqo0<=6h;@WFMtju5+_8)xIgMMhx3kHjTyR%%F3Ub>@y
zO>T~s`dw~l^j<}Nx0Zz>L6tDvaQY5u)$8_bI*v(7!9ek`dt8A(jUM&gdgE818c0U_
z>xTLpmEB^m{2I{j{7ng8dx2%1^dadwP@Grq{MxNQPaIGf|J?_gj^t`M;!@Ou=L^{X
zR+T`lhQ*-N?_J(jI88~9b!0}%LH{M=|2jNvO<3(hs9OQCWW_#3RGQphcloJ$$0>qp
zd+j!0f2bZhEGUBvyw%udI`93-pHVIH&B@IxhfWdS-JY#LyV%Khi_8SF+AoBcQ6@QR
zEtx9M{UymV5ywg3ZE0L+WB2xgn&k3(eBkq`QF;w!ztj0f*-<ZL`VH(7v@m?(@MMz1
zZnP9isJ}4UyxSqfRUlibwoR&Hr$3};-tzUE42p&A0hTi@fj(F)SSygo-!eqhZaoA*
zsY_Hp?@^SP?*x%o1X!jP2a`Vn)i=06=X#y+cf(tOw}!Sb)NSN6@dQ$XM5pXWz-GgJ
z#b$^}%MRS8A!2PHgBn+YuqA?8d!BlH@f2)D6P8Qj!@jaXCAsEiD{tJq-R7s+c*rlj
z%1}3ABa>R>t#V#;@pPw7PMNtbm=wwD+jsMcmM~Nlmj}EC=hY{X<JVoEhhzq6rH67(
zR{qE(^3gj{VRQ}m+vUhdZ3yK^-)Bp0_>*5)p25b2Xs4BTCn!8BPe`Cqf5u#8WGs~D
zRuz3^gtqt)^cJTM?yQw|N7P#H{dR+O#vklSmfnSC#2)b6LypNc$iqkZUubTpGk9Y7
zXWvaF7cMdna!KuiJ;i>p9tM16L-J;Q`Uf2`ZgxyeXr^mNt(ve=c<~UL8$S3f$Rijj
z`VX)z(smQMN2+wV_(`8h1@jtWM6!Fi2!k=g1-p^Y8+RkcTZeLiU1D%<ld+YjfG605
z0!t=QmI;y@N^%IkB6&EZb|{%!b_ael3#)prdinMWD~mLlNA7)DMqL4Vm18ri&%Nz^
zh_XSKMJ*6|zGA&?z%D-}?d2xhc0EaF7bQUIArJJ0$n0B1fY}5*j({|g;lxHG%%#*Q
zNOwq(0VeJXEcrLl)pF5KYkKuJg4px}L_Sg@HV_|<Sw$ofJ9KIjK_eI=Fcd&U$N-3|
zfbVKg0dWpFH~<250C(?hlPm?2G?d&6J3n9t<iyG>OJb2`fMUt`(LaCMZ0yCPcYCr4
zWyO^%YGi8GMS@Jz!%30(KDb`+TV-~=ya2;0b<Mg$IF=!^4Pfi2#^m;Yr)VuVPk&97
z@q)Tuqn^x;ZFYjLSo6pg6Ld`NI1eI%7t=dCdzu+x5^D78NhjWbHzd<nHm<6MnfKg|
zUD-q(RR=`@Nn=I3Zs%QF{Sr!N3z2f0I&-gVMNUA`<ryP$?1&w{T#^rI8VLdu%i=z5
zJF(idV=-QTP~anOX=sM!-jbRdqJ`7(j4br)#bj>?p2q%e_StPBddT8^8Qfwj-X)B@
zBCWH^aMC^w-d2dNYvxFp;9PsZ!gK-|-IuW%VumE7<8%1E9}%k3$|W{!jtKd!yWXce
z!|@6O5-<`SP<@#1Y!_SQ-p#$-JD6}-6w&J~7Vg|!(?^XrsTt3RO!K}KZzcrm;4ahw
zOEq0M0egk5UNU6*sws41jh=VhZXkj3URXOLIb!I!%H8$mEQkUmqE3E{oKlcjB+_2+
z7G?k?jm&#}&D@E(T!&I`&+53{nt{nvWwzz}G+raA0j)Cbt$?NEE!2N3x%jMB=!sO$
z@R*og!cSQRiX3Rewh6ivv)^nw#*GvUz!?Jy?&(nrG765evB6Yu%Eo?~v5#0xX8&!a
z-CCm?PV({|Fcj$%=9{Yf6vlC4+w5niAi){*-pvi@X7#Wzn*JxXpe#eJpU@vDSbYPp
zpeNmq>p*(p6rwk>$$ZahssqrH-)Z2+S@LzAH2N-4n15E2+H9`im0j!ksiV7xM6Vdm
z1_184J$C-C%R#uhvDMYmWRS?_Eay$<kJ5^s@2*mLOB+}fMp#mDx(>}HY0O$L&I2Y8
zp#=JxPO7JOka}8eVL6p9{VDA0tGfrE``snG@~Wto&{&HF5Ba(d{*ZQEVcTwO6=3@I
zozegg`!R}K5=!^DYJaCl7=AT%<#_!DSl>pCIh}Q&QYdaO@O!zjtDm7)z>nH6I`xGe
z*B#1azY9eY-$1yhvpKsp$Lf#5IjdWonl@F_SFJ@J6)-X2#<0DvQXJot$Kq8`XM~GZ
zIsPR9S<3mtW9lUx<q1(N$Rp9vy0R}$Rusbmi>z(+5j>00dmbU+W)%br@|GSL-MBjR
z$WylF{L5oo$+9r%E1**NaY3^=qs?U9258@l3|d+y1Qr_wk6G~%|72S)b!_aahA~Lu
zvhAc}Y*X-I`D%}GE)I7{%$ExpB)#)NEGJ1F;_+Ea<1V9>=fIl95UK6Bx9)+Q)hP?a
zm`6j{S9<kIsnOT_6tXNqO;j1x38^_qvzJeN7`0woT<r(%%zL;h+bv$rNbcW9`i1x%
zfBJiKGC7mC?Zu;|mV+t;F-BiDhWUG+Kh*O*Vf1U2Psmu?Z6<i1B@6cS&9^MZNoT^Y
z9}Q8m2gpHlzuI$#!H5>}C(?y_PUt&ls}Z$V>ySGwF-&q<!JN%h)PoUxFf|g4dY4zP
z>bC0Yy<vMgwX*U`5|dHdC5hSD&@{(tvHBh#_p|JAgNryFqlmRh?`Isf<UvH4IOP-x
zEzI|~SUfmZ?DCAC>?Ek)3W@PqJijkPF}{kPFJzlq3ZjvcFZ&6m5-rT{8fP=G0}YR?
zA3TYUl#Tbjm(kn)GMlz^yOfFE{C|KNlYrfAq%eWa(vH%lycv6ZDL=p`Q8y*)hrE-K
zmBHjP0l0B)cT~hrA8V8#SO1}jX;z+@1Prf&dP-Q9y0*fcp%0t4p_L*e+Jn;)`U=2V
z0zHsYMR;NnvE$mOV*v&J4Yr%|o$#BGuAe6+r1VgD3*KR^hzLIpfHAR<DXD!F3bq-r
z*lbb6Z88b|%YD}N1yz($5ldlOnGD}2=mjm<BRK0XY%{@t1@b08s$x(UlBuFu<0=`N
zg^4Wxkp{95lXCmi^9cvUspQjI2IUNiGUhDkCEPu?ix_xO;fZacucmI*Jm5n9@nOoh
z`s#b7uKv5*O*|T(vz;D!SC4qJD#KD+h>w38B)0D!+^g6^s62$)2n<50uO^ogT&nIl
zHqB9#q$^9OhS&O~k<i$rLqccc*1>^QW4iq!YuZWCP?zBRV^3|w_^H;^5@Ld<3$_HV
zon$!O(n`1s6?=cGaHY@PRgR5mcgCv^b^hLa3l4AJ33w-bzrda@)ZA)It+FvL@JC@t
zZS*)zds~1+lbUJ7iLE+kOAAY<*XJ7w5)uCz#vX$FH=PV1#}zA6b^6ymh?7Y8$ES(*
zb~Px|c*4h{IIg_aJV&V#h#7qt6)FsGFC=s{q*+5#RShe#_n%zXqpY<?B(CV^ltB0b
z&Cyi!9O=)Lw*9<@FY*!~7wt4=c`7??19ZJ!+<h8@DEv`<rGWTvUzM_6FY-we3c-7y
zf2d^c{lxEME3~?9=+&3)HA&GO+W&A|B0>Y60~)CV*H7SYmHNH{icTK|P>MGfQ67Y#
zNWvu=Npg~5MW9&dT**0f2*y?TEtE>!sD#7D7l0V%?kSXCl`auV*maw;6q;oDOc3N<
zU;#Gzw9F5x-gIY(9HmJjt&Wh_ZKqr59d2#Clfl51DMX^HcXpNjYvEfySO#**_^a^*
zc~e|0c&yff(2Xadv@s}xrj8f5$?4<l@b6z(*D9oDcSI#P<><+5$8v!+gY*_$v)WX=
z+(K9Hq#dvkR4LekXmLcwzGN-mf5HPUvnB}YMy?JwrGd8e&Qn|8bB#3`B{EB~@YdYu
z90nFPw@#?VF&<F9U=P)oI04JjOCz`}_b2bTdmEcq)166Q(o8v$zI!!_mzKAojJlVc
z2#dO~*aNks9*fth7K7y@(IN3bgVXEZEw5jyz!vNCsu6^G{(=YBa|D0wH!OeH>IPbW
zDeoN9o^tBproi&p_<IrXGW+lTF;~U?iBTj5#f@|Z75&OEZtyw!1eetzx6aidNEnl0
zuOM_Q))&_$a)6aSW4K528>EUz_WB9({$Rm4?(}Tpy`ML)4Qe=z+5FuS8-WzFewB18
z@W*nZpaUH3{SC;KDCjBnrA6;=7&QWcQ9Bm>iX3hp?$rg@4|dMiFQouC_Bq_O{LnY(
zyHcYHZ&T$auDLqMpZexyb(VL5YWTCE#N@lW%?4zx`l54E{5)G6V^`TwlIH5xrMgA4
z{Z(=^YjjHrgH)dNew#X{q?@Dy{?itQfArP{64luG?%e<XRFt}q1*C=ttW7%id~1Ai
zyr*+iM0{O2@;X6mS4I?YB5|%d$Wi}IVt)rueE_dwVm9rHik(G7UWv%w4KNO~@H$-?
zAjajR!&Wl+CZ7N$PVe#g^Iu^NM!yxa@_$5xb9t*f4CbWS2BL+xhOq4RVY##vaY>)>
zoQ4LNjcamU6Iml~7xZa&Ilq+GlVQE?mfy-4H2hXa3}|Iz9gg22!ArRU%sXw>wJO*S
zkhWW|g7nN+ahY)??-8)(e1)!QQ;rVg6z_DPUcn_%mW%gTFu?`W(j}nMId?P>Nh$QK
zQcOOu;^t6~(=9e#dHJ|*i;g>q*uJH}j&+XK3%ceqe!1*oS01aH@y}QMe%6lpk%zzp
z$#(Is;?~kClBADTb0+*2*q>Kfac)m%u!T%a{k1=H8d34@=q6l`nbITT502dWqfxrk
zPI}g5ye4$7KJcPDhS>6f8V-!Gv;eM^?HWt-E7>ej;9R!1BFIl70bkr#%y3!umr7oW
zl5F^qaZ1S?;H0`Gda!*G(IGL8IWWK!wx@<+V%1YxvPO--%mtdVncc+-{VXMynJup-
z5m+SWUt5MztQL|MdER-8?MFuetG`#&u#m4Ovy`wXJJcM_RMduT`c7R@ppY<d98c+)
zsdmU?I1vo%K;=I-lU}<iVHc)0X%olk!P9Rk)Ce+Ey|WXQ3EtL>B<`CJOnrd0v>{aU
zj)L4nMcfx(jpGWXYg3pP?A8)WXWh3sa7AgKq)jquvwGvcn(`ynGJvYa&XqF~l`0TG
z{eq+IE?rF7%zCEQ1r0(KWiC~Ap1peHwggW!-R>5XZ>C(o>^VLadBT2Df(<RaNk|N=
ze_o-zl4&fd#9WonefUI4$93&1j<B822m@i5uQY##ru`}W0vUPR<Yf}HEz}6ztcOnY
z&}tF@lMgH9{nsH%?;>Gkz#XnUtl_FmGVP_H#6d3Hi-U8Ycwa<pl#c?Zqc6_4LgIY-
zi{V7AeKEhTJsv0Xs*5@V@YA-I=JMDRfTjc>m8qrI79_~|vD0{Xe7Z9hw_n<~IInj4
zId@hs{ygy0D*owxeTW6S6f0l;1tyU1^gXljTK^*s+`nQORhyjtFU?rker2jOeS1~y
zGPeI}k}1xcx{qGA1s-LB?^S8*Ecb*vz8Dy=B$#8d8&yTHrK=?((?QlWEh54o60jRZ
z5}cc|7L!f7HDJhOxiDrYczZtqY-qmGxqiDYrunHWW(BKLhuY5J3U)VO?3TNB@+_Zu
z6%L_fW-AF;6mwM;atiUCD;fDs;s+<fTG%=^ewc3ZgXQ_gAY-@ss8{ioDGF2apnhP{
zYP$+CH8@JgPi$4q@G=xD(sJ+U7N7OX2R(I+UO76#)>}x>5d7&fm?tWVuro{JsAc7(
zyKw+8k4(<Dn`e>7f{rsuLdA=H&fZ6EkmwuW*5o=2(*l}!v}ZBOA;}kPRT`8VJokjE
zoDZBtvc~}t!#SB7emYDyp7*Ym&90kpZ7pS-XSMG{P=g4h<9%Y9c=ZnrjX|bpQ`YkA
zNDT&{R3yN^@)YGb&z>FMDE?Hxf)CL#L2>z}&n@bTm~ah$SekTL{KZ~wrP<~J3aAEp
zrKWkcfR?3J@Rh!`kuB@Y|MLMsqCo%vVc6O!=YRxeu6L^dIG&ezxS!hb)!D`d`!Kt$
zsj`o7mYDzzQfKg0I1A9D6Wr0PX@`-+io8&wh&@|Gp<w8AtoGnNK{O`H2SEkmNRwpH
zr%h@^7bY=fa}Eu$l5)7O938Db;)nc%W?Ig5cSQ_=l?y+Y#9*cgPY@NWA}9>XYb4@|
zq!J_`WJ(mXDfyQ|)t|4$fLlktu_u%JuB$X#xiM@TWupm;tu!MZGQf$mAA0j|`d_H(
zK!2UR(6R{zwTAI($usLyw`)HU3dQ21U<nv_HKARX5)3I`#@b@1#g~~&0`ymA?XFV_
zms)l_OYAWDM(U3-8wezY4Bh)p0_En3+8AC89z?zNhlznEgcBS%ZXmD&4y`sqhR85H
zt6)%#;C?%_9~U*^9O(Qd!V2K*r;X_vI!(=*x{jT*-17N01)yFM`ujNZanq!e;M0Lf
zdb|5K8uB8$k)!|?xk||d+WEzyk(rtUi0gKvPaHiE`ap1CA2;^?{iKBA(PtEQ%jTiN
zD;%PaLq5{5Gm@z{uRr3Xg?@borqqQ_O^UO|>eWJHvgImdG)5O@T|&NOv%EFe4+lGt
zjxt2(p`2x4P4+B4*oH)j;8)|(k;%@<POk(EvRM|+tUmM0(1I>*;g0)1YJy4JH5hWw
zcv#y)f)pO5H3M?SbDxoJK4ii!z(8~4o9BW`Wvv1{G;%&*niA{!7md>lPkm+^B>M{9
zLh#e>8F<`W9#k2Czq`H@_pR2c8eG)lxrZ8md~5lnVq%Qz&0b($&qYZ^YSkT^mwQN&
z6gNBddxMokHV1A`1(rIldtf_4h-a4fLk$^Nue3n+TcQua-+FOch>+bJ(ejw^CsTjW
zvj(cVv0)E=aO;x+b04WHQ}1OjLJx7to^5lURsR|1$nnC^e#Vku(sn)k|FK^C_^*QK
zqsYXU{C>j3dhCob09Gi9eRVcruH{wvCK}0JahPg4z6AtZ&W^-UfRvwBUPm&OmVdEA
z)M&)<@o*bBhh85S?b*3@zmX{`S|{8d#_M;To$;<MCSezf0WETVx9^Mv<gY)p1f^zA
zg0Lvqx50hFd)rxI`}Zl?v{GtHcdR8uG?T_k&u@2Hk@hM#G{9Oph56;2^4KY?5%cX|
zlbfV}4uw}Ba~B5L#7C>{!r()<gn-y~%Vk%uu6*amm_5F&jkTwuju!{T9ynm$pO>-z
z^m!W+URYn$vEjVMk9PpB{75=Q1DXO1_^RkY`_3)ur*Ab;`;))3{B#QH)af<{;Q<6c
zNYt+-997D8YB2{MZMjZSyIoPP+9YX%pH$yYJ^f`FrG4@vnfonT2e*t-<_sY+0EaAI
z3}WTR;!p5UyqQa3CvKxLvY^%PV3n(!GG*7s>Z{bvBFh~s+Mc#=&K<F1g2H)Vd|;R3
z+~CId3*9zHuzL%Z@97N(NVk!W<0yCNi%lA7y->(sL|C4F0@C*qTGaPCrAebGfbHPm
zxpaRoTP(2tA&-T_TTUa@@A{ddVx#SrJOn(GneVFU)S=>)M;Sd(3q8T+51IDjoY9r!
zO9jf?eP?Ue3Jq2!-Rim0?gn0Mlui44Ca-u%)k)UnMY=7h9i53k@~rsB^Bll5C4_bv
z@aZNCi>JeSQUhHqMG}SE`qsd|p0?I2AVLp?C?jh?`a}t*w3`mA@H-0NCX!xsHik2f
zMPlCbO|P~N)n`b8ol1qch0xLU#d$UK5*qN7S}Aq(0|yzC6Q|A{h9HgZgzdL-z}W|m
z=h6WGoR0E{5G4=wL<=i(oLn0Km?Ijy9Q=MVAmN0Y(nBmu)z#79@$-xTce3#+x(zTB
z+}4V;$cu=|$TewLJA{G#Qsln&%OEL`>!S3e>F`xbNNjr7`3#8Lm}Vj9CqZ%v(#?=w
z`bv*_i<W*Gu9x2H2|z$g8kzgo-(_WGd`BsB30OSyShylE0A<1N+SfraKfL0xx)PHT
z?-|unA1IkP!wT_+jc$A4te8J4F@nz3t-`Q5*>&UU*jK9*xumS=mIX?y5IP|YU8bqr
z+BJFj#pPTK!JV{O^by*5&S*U@g7}iHrF?P;0w&@BdRT=Lf6>onfz`DW0PQ*^j|Voz
ztxeWCNw_bWzi;vzAKLNbAd^%D&Tt=~{<Kcy-1_+yYnlZD$u#Um9N$NsR4*ADvjg8c
z)FwRPo>yCZ4cpdq9`UQ@0y%}owd>X{^VZj^P8R}5;o<)ubmCGhNP_T-sR^Qh)-h}z
zARcyvjj2DZSAZ!~92~k+c*pd<H`|3|7JZqkN-P?dexXKt`kapF9qJ(3>k0YhX}T6J
z1_nU_%%7{RqQK{#!^%EG73TU_6slwA&kc%(Mp7zXcTiu1s<;4rS%54b1`qx9(eI}k
zd{UYkTnOZo{)uH+ZQyYvwx>=|)q?GTJmdC6@~y3~2(nRB>y}Z?{Zhl?Bzs#*TNM6`
z|03jK!^1U+CLbOc^ny_O*ncYxSWR9Uy4AQu=21oY$wq>fUn5jMCE&+(Q7ovTrHx=f
zPYt3XKr54t<WTIzI!dhzTCtMrVR;1`y-)zuOX(%elKM;NsgJw4ltmY>qPGgzvo<cb
z=AtoKP2P>1RNMy4;0|O#KHfx>TY>fy=;iTX^6r{ui?w5$4wULOY&e6}af^JHIdfI>
ziSmY$q&mTRk!d|#UED@nT#ztOJ0pnDMxq`;d)sAm6G8O++j<1_nb#aMdsQmwW+ug7
zO?n2BB?r{P_2IG91`-lFRVLTXExF9?ELFaJJ1QAKG<MgD|1Ud?DjPa63V+|IO;9ZT
zyvTiS(fgt#wVHbM{i653@>vT7+Y|TG>O9JJ`P*wm>JGrs^}SmHq54Bf_mwnsxqfDl
z1leoOdpI%jgI&gZWEYOM&*6A7VFr+7@5(;W$S@<YLl7KAfaugi$-#d#GO5>)L`4gF
z*>d>f_ai01bYSip`T_^-IK7Sl<C<kFqRK6qJ3x=*7<BDVdZwWCRq6O+pl$5tP~uVB
zaWzIyQsY%C|CsC*X$C(Fh<^{u1`3-hWuyIh5zL`!<I0Sl5T5IM4V2xD^!zw@{*L>+
zXwXl)s3H%AU^5+*`Ns~yv`#fk2ARcm^BI?KzlT6}6K2^?U#DvKPuf0|C_rbQDFOZZ
zsetQfXoWM#5ib1B_n5=^h;#p}H++@c1DFoR2)B{zlf<w7TDiB`5Hu~7tHQbnbyKqS
z+HYLD1_yWMvBAm-V?_`i)ob$Wm&IBRHl@}nf?J~FjOy|lKBS7Dxd^O0lrLuBT0z2r
zx~8|p`!T_JS6Gwu)uiD`ZU6YX2?Bn(A?Z<lU{m+>lX=`kK1A?HosRB~i81H_z67Vt
zqaU!pg`9)B37;XxNnrXmq(cor<XK9`qh~Cp^UHN(&7u%)DmgH8iUg8`ZLJ&Jx8ppo
zAX#b@29a;a5gwZHf`;J7A!S;z)GUgJsk4F|K9WwjQX$7Pa-PO^O$Pn~LzO$Y+HTYM
z15W7@5t@VkffNsCx+<<ol3z7(05oMV-G%FD*52q*>Ae#T@;Plk!Y*7g1d2j*J?Jjn
zo#cD6EnJYEK5S6%P?*o6Mk(QDV`^S@14$~Z`_@iC<JJas(yiC_=-_>bS}Y&UwBqki
z(ruP}6+e=*tBaNw6kx@U2S(VR@ZZ6EdOEn5O>`A!>$zJLa2VLpH<-b&lBsB=bDo`u
z$HavvddBm-?ld0>O9erQ>mj2V;)|JHn=9Rt9zPBMfcosb5Suw<(Z6Y`fbqvpi&n#6
z9TD1S6mFy5Z4li;j#^#DV#?!kC&1*fVZad37?X5R5@dwYIjo*1oAse8+xfd+JawAm
zMi<QJddY%$do^uSal|nDB|S5olQokd9<U8xa}c{zNeW~jQfueui3T|@8Ti3K^<hu{
zpgRRLsP_)-m~MSPKkB&*E7K997Yi6oH;Sz6s5cMP&SC;aH3roCerGvq4gV{a3`+s~
zCP4}yZS0fW5V<k%y^|Zzr#+A`h>DUWgKyoq-vHAooU`4kIf8cW^VsSn<G|fE?j>(_
zB%(zmda5j>cMlP)^s&|U9c?Bg!({H2FV_Htnn;pvx-9Bmj|=D+fBU$}41W!8P^BT<
z2n_d@O_4)OhBDZw+bEL<iau2g?^B(Vk?wR*sb1LJ4NQyo;K!4lbNCacIfsF8s-7~K
zAeA>xK0O+a^7Dg(eSx!Wm+NjX`siAQhihTo<nz`iD)A~+CEL%-ZqRGZ&dcii#fDoU
zj{o9ZZlO#5t}UhGLXyhm<zBK<SSW47Vj9N0;HkS@JQb0+|6y0{U+aBXpgmL6aqh^u
zM;^{bFx8nOtq}mpT(Mfkn*H=H%LvA-c<!MN*{5afV|2bv+WcUSs9of+q^aJ(f5on^
zrK6`a$G&*ND!zYxsc8XkgQZaKo{%6^k-?_muQ6@zGp|l54tyDy&xr~ML~DAb>Z~k8
zE-7zfu5OQVU;TW~8|Z2z2&dx1Uhlb=&{Z!)gxXqtRu{Q%Q9_D>VSWg(^RD^ZGiCpw
zN3t%pgbX%qk;G*|<{;4|yt-tK4okOfb+<tlqzQ4u$+eRb;UIy77rLGaP=O9s2RLD)
zN~t9&%6_-PF+=TlXmTz*?Kpb6w_2GvM?g5P((3JoK%VPQezw!(+Y+y=*0?(dN%IT_
zIZj&T9^%Xw8Twl1+Oaq#(M$sq2976%3WLGrDB^*@{zuLMEn%tw{5iPyN~SSYB={R*
zh+IHkw|wt+Z#EcrS@vQq(LY?~Eb}a5cb_l)mHfwtdl*;LMC`++BP{%RXPA<cQYBTg
z9AFb&PcCrDf*42uz9+942s*Qc5}h}N>RD-z2yDHQZy5$MgH%8esRleMBcG|Q4>UE(
zQdGbkk2G)ja@sEpk0834j54`~mH-HSod3iDLMr&c-idHl>Mn_$Am9k%+@v_KIV&ij
zm(s#(x8;Vnw?$nT-D@-ataV*x5tk%Ck#{%5gyRKAhp*&5YVC4l8p^QmY8k)_UqJpp
zV(oQxl?H4N?4zg8?6L;Hl}%1KfmL?^WLogV{PT%cF{}HDwhIp68LI9{93W|^<H%-z
zP){M|fsZMfJuSXr8s~JI25#>%M$#IOhdopZ8wJ#g=I<V12bk!Pp(`?9XfBF8gq$}s
zq{`!(&GPlS+WzXQ#j_EEnT{8V1wX1IqM#SC;gt(ae@e8-eJa};_Lb}UtCF0|o9(ro
zsPhlr_p$>-{LL3R)7IE)%E7w8=OolSiEJ|`ym?*wl0zm|raWyWlA#v){u|Rz@N{n-
z!b;5Wy7S&g3@_3A1p6o9WUpp4FUW8ta~p{u$0Z4$hl+eOS=5vc<-tcyF^k1e@WIV*
z=KVV7uU>A<O4O@l23$u|&6Xg#kgx)J2v}W7soeza!rS+4VSgMb&#Y|z%A%kw|Ic@n
zmymJkJWW}+ftb84%AOQx|3ZRcX3{{mY*nVzxR+4}A>y$;`~;aO-nzi+>@4d&VN$EN
zudud%1(I|id9ARKXQnt0p2u}u&KJG*U}@qzt#n~m{4FgYygP{>uLcD%w;Vq4eFO||
z1e~<PdU<K(c(x9-Lfj-6s^9Z9pd4Kn+8WJQ1Bi`h9VK*>J~k$3M5;!tAt8=y)p|L0
zeR1JQF=mJJNGG&wR?@`9*C+Z0d%VRdCicZ#kqT-&agx5L)-Z~L&5j;sgE>-z6S>?+
zXgom3gq$UNw~}2s<AeBiALQ4%2cp8p&Em5<BSWM1-xj}W3xR22qUe1nU1OK><3l|9
zat>p*%x#MxXec4m+q-B~@ZO_OLCacbSBsabBL|NzE<J3docr4~6Ph_V44U{Yo`C#-
zQG0;X>US)+gA?w;XJlM-`tNz+NI_Ca2*Nj<3h^(ZM)Jei{8e@;x_WDp$v)N8X2hI$
z<q8z|#nsYUd+c$lSnMT+5bEE_b%OutO1|8YdD@H>u+EQDU))WgN6tUOnovJ*wg!$l
z+p8d|KjgLnkH)FlwlW|4X$s(jKIh8o-JQn0yM}M7w5C(o^Cni?Kaha)a|FU>C<G0}
zRjKlAczqyH1qN6wU>nD5=cs2i`$ZxH7B*pJyU;Dz7e`}|Iw=inEZLx#cW8^Jeajx^
zk--REq_E3;V;Jnwck$Cn*10X4x}H4CK$R|__A1V*Qqr)VqfO=hdR4z(M4!i&UouR)
zu8(H!X%V{*1Loq5IXaLvya1Xs*1#-i_Vf}(!Su46?z4Lk4`Lk1cbgL{|9v?s%thc2
z_9CDoP7R=zV(G^YYi#arJ48DpT;LHDT~x`;-X@1dIXr~6Mse3Dif{tVZ`-mIZo2M^
zY@p<3x+_y>=AG>i{Iz&>`r>gHiNR=LH<_W`cm|%pGB4#S=}5^|ec;L+G%9X5u7PJo
z9S0^9mOoowO|&nqWFa@IOBLh^AYz0bO^z2Q^{6NE@5mLsa_k;#<Gm+IB#k|fW%uTc
zDlGs@K(xQkeX{=z9p3|jD}kNUi+Z&>YR~j4$IW+HkhESxuMQ_NZcsxRFkAe7Pty$+
zfI;mnAGB|vQRr^qc`)7S+S9vkPo^BUFQR<L$DLbymsmyNQfya>dZYE7mS9zuT3mmk
zF~?zL0DOZTL(6F7jDX061}kM7jpNzzn8)ZVM2^ABNc1XC<B>hb$1%<?!ARj%?ANsI
z{2VAsajD~`s^0GWc*L!rM9SYQMJ|M3aE$o=7&*3?+ucbFiScApNrvle$kDsFt1`c2
z{*605*d|GrT`$|9L9<P;PYxTmZM=D{@4-1QMT>|dl+WR4Fot7#YFp9&Z8XUajog&5
zajqqPmjA(CdUdPcErJXeC`-W4LYVU&-5|z7G3LZ#4;k3mZ8ZR)@=xmOw{y7lCxl-`
zoe%R;EjBUbDWk&%BmDszLWx|)$KZ-eDvLMvFPo;hKQ{)Y)Z=D2s{IR)<x&)WNU#Dd
zlW6JF9+Re+Lee<dB^q~wl=Xe4kWK%69n=v4!ER8(_Z_P}B=6qi7~VHW-BKo=gtl*G
z`F^Xi8{jyvUiUY>)|NpUlao7HO3RQ&3^4g5%(u(SJD24VjMfvm-b+-ySakfk1STvz
zQ?y}sG2sW06ffOH1u62~G7@VNq;LYkSoNymm3nSqbO3c@Z=GFYGqC}Qx57kvlBs)a
zF-(ju>Zjk`CA)<VYsnz&a3`(tB)!?LPPM8J5HJhhC2J$_$YgNxZtU}Xu`NREPTEL*
zeKu`%CmW^X_$7{qcvBar=@jKL#=xRQ<L-b4GZR_wJRSHxWP{BW)BKg3{C&zY-8-&f
z@P^r!NtzU_SF<R1h>-eL?<Wy^Am;j^6I*UiYYr^;Rqq-qpUnY}A(PU)uIb7T6tgxL
z*#&oxGaaZT*!xQew^0m7j)*(-&g!etzP+f|OwHnR(r9Y`g9z?R5SAY7fT{jC%U2%R
zJ9=<Ir2U!I8qB%MLlrMdCG3RS0V*U&a*Z^_w*3mFVGdDwGR#!#7-mkm42PgD^aV_O
zM0YFS><({p>I>xpsQtZDZzscOyxS5RtOKUi`ho|+)a}`4prs~C(j9b3FQGvxU;;Tg
z{;VF)23Gu|5Oij|RvfYx55i9_@;T=Y1Q^qg8`chJqF^TQpeZ7+k}prS>asATyvILa
z0@)S7xhw_c3O`ep!tr(SJ$|%_w+SIh-%xT~qdym%%6Ul#TSQfM4BTGu;H2*UCbdua
z!3oL`EkOO5`3(ap4`D~9VH%V+-2L0NK3gNKKZ`Jm&Xq_U^sfD+H)dm)O1MjV+EgiD
z0hG(tDuf80^hr{o8LUUhizBjxmL$~EiD%<(lBQ~S-_L#NCJcd*n1$Wiq(N@nU!YKP
z1_Pt2fju_vP0`C@G|{%5hts)?Ps`LvmpH*JOHlAnuHT5BP>O{xHhnMPq}y^XdIQAv
z#c@JsE>M_XN#xxA1JW?CeTl?VU*1OWB1^tdZBp-_<#S9-c=4|oEDavV9{d(;{1;(|
zH-<{MU+#+nAoj=1wfvQQm9)-qX{xiY6#D!O&nL*o7F5%&<0OIN<D{-WZ-Fh1fAi*X
z7l^SfJ~<%)d@QeEJY<dxiOHbfR){MTPwaAiSSe@~Zx(Tzv`|L#_;C2ur(Y$LJ*m;&
z7_^m|UbT+b+Bla9rZ56eX^c`xS)Nm?JNdpLv)8pLdMF>Z^rlNfatdHj08Rf0-W=)6
zICR>UWz|CoCWw*P$lJ6&G#Pr7zK|q&UdeB(q&Ejd7)gHBl^hs0D{;xR^q~aK1Z5-O
zq>goZ7npy*ib04~O%jGi8b)@(i@GWbb_qf7$*CHpg;9yq+@A)9`ad5QYSM1+|JcRp
z-~ba(BP9d&a5{zLWv|(ewA#`9A83`87RK609YF?PUa!W=aP;&VyM>nlv!}_#h$Fqq
ze#!mI@H_-hQ}6=XovALbx^kN^D@4<J7x&?)q=ZWXe9J$Lv<iobBfGv@RMwFg6pV<o
zdqfV|{Ph~<O~QcsP;#Ym`V78EEFNrS6<QKD7kHhua-uaOtnOO_FD7UlNYP)^P=m{B
z8_4-oxHV25tz@LXcsaXY*^dvPtZC&6$ulg#<Aoe;gsD~2M%dg3Iz*1y+F^uZ%ug;_
zkH-T8%PWtT1jSP0z#R`y?=}(b_lsrHZqqx(EIo+qc%j@L3PLGM9Ctnq>&`Q9yZq&Y
z|D3ROo;&%jO3YF+QScwAN(l#j3mnWGn3rwkQPL9ZTBYLg#tbf8sNKO=O8u8Xe`lvd
z)g7BeKG`MJ$g*gD_@sIW5d_rP!F~;8?Y1oks=aHNrKn((KY37X{yNXQYz;K^Y^6dX
zbHjO?ib+FmH^}r@6D-okZ7WpdKWMXdO&KOW@eL{+0#CTTIH#E6jSOaDJpMIEZSUL4
zCG`QOu3*-Z3l)hVQ}c@_KNkmGIAnaNyG(Z<OD8=&2t?>pa3A}KkOWb;hQ87|Vv?qL
z1I(WKs=OHwvjuT-wXxrDO6Hf-@81M3fLAv1p!(J*Zl3q?Dz1FC-<=hE?vrnh;ir!2
zK|CHT{G-j=xbiak<?#7n!#u!~WWw^KS-{Cni))ItSA6(ht=Bo_%>_YG8)+kYcaRbo
zP6Ok~s5^oDz?fwiOOG3zpB2T};SC${Qz*?YCID$l9bTC(1RDd5%^s?~qEo$u&Ne}c
zcqYL#xlF*Yk0gF1_D@b^3->GdJfg-#w+>`L?1L(2aP)i@xprE_PiFsg!*&{hdQEzb
z22N2Y(VQoLogj32*a+juzeZpO4=J{A4MDy<KXKPSSAzwsUqYBK4EOc%=*v>D0D2qC
z_EMHG-uZ8Nspp(Upk*515HnFv+T8vs^Fg~Q;WUKZ${pWmL~ulrC3B4(d+d)(UZn*7
zaw$=!8I~=EU%^KOq*fFljG}zgGNBb!JFEMDvSPV2so02$i!`J8`{iyIpyV)^{D_@(
z=Ht-(apg(n{#SAFEC?UYaew+tab_w2t?M1?{ET?(J`?Q1y`SWj4b1<Jh2P(|oMy_}
z8!a|iDDf07CO2twjKGs=x<Kj1oSrx@-?KV{|2(M&vV{}}Yl$nm?>+K(L*6?XjT8zd
z#GOA&VejX0<KOyLUbh!CI_i?9r5espcZ8QXSimAZvt}p0jxZv)J{a3w3IFEaqjYA5
z6NfC1;j#14wn}+9XJYG=_CnMF?%{k5<ftqx`N?*N^-Qx5TF$ZttB;>q>&fJ>(MPLh
z$QC-Zqq;{Dnc+Mg7n{bFbG{r4-8EdAnl8>@PxGQNsg))VV$Iz;-oblbc@-c03F@?1
zTl=$Lh+uRmBexGy#p2P){nNNzWm}+YtWbOrC@tc!qa4gDprp8{gk>Q9W1j9x=-DCp
z{dSJBIaS>|iW8VVfhQWc=#BF~yvZ09u>&>%$TU`V{L;y>xiu?wyZq`0<g4Om>d|k2
zMfvT>7k$|=NH^-5Bn`=V6SPXa0+!?X1KNT6PanXn#_73_9&I7r^ypc>%s*P|8q;Ux
z^W?hTT0S(aPwtgbrEMZ=I}lR!#km=Gtj~U#04WMvrJ_%`0pI`tSonS%cF-?F#s`f<
zMiZ!3kdn9n=rght@qr3bquty!pHn|TBWuYJS<y<Kr%5IN?3f`RP4>3xdWcO{eW<Xy
zP-1dQc>R~(+Q)J=e~{sj!ES8cww(5p0_y?b8NP<=3KRN)=R!(+cj`3fFpxunanoQ!
z!g;ymXnm}&qy!f*&g;eUA==a1!OSZ3s@=o4bpr>Z-C<IDgvr&Puy#m%FKc&86b_M8
zHK6S}wTdh_8(_Gt(}rd*HFk;i=Azy7@gX(sl!k(8AFkZ!bJqnj=t1sC%dlU-|DjG7
zdcF++Q?!&j>$-9UnS!Hh52+JjZL*kJ!4np3C!9_K0e64y6azf#HSA1*WlC|M<m8in
zI1b$w!d-V`1Ye+9=E+j;Mgb1o9LA~^X#Z)_%gOX<Se>HqzyY%IecIwp*BqHc^8mJs
z_JF3ol>i_UksZ)Si_dG;41;KKCt3=(ViwR{Ws3_u3dOU|@qZsZ4KPUSL^NrE>mET#
zq}b!dc1ca!iP7O3@NZSW3y$_63zk)l*;Y03+)v+@OKa(VF-ou*JbN(&z1h+qd5@_a
z@(UO4>EyumQSyP0m-?jI6yBYP;jW}H!En6|HGW5AT8fO#mhi~XEdvb<0zY_k3|188
zN0m&H6RRNbmV@16N~yvMx?!mgw=?fb&_Y|$U;sTzt4rLuO@8+b7pZ{x<ICE>UP|wm
z9*aWLvf>UyI99VJGm=l>6R5*#YX@})?ES}gYE8UxJZjYQyjm|cv{}LB(Jw_p-7^#V
zZvKTC$o}q`pJ-XkovKjZV#kE#L3Rq`);hli<_N>7XmshD`!*mfSBRAzPQji!aUIC;
z|Ga2oA<=|iH@MK(Lg#V9)l&YMbx5D(3otCCV{Y7^S9YwigF)H|<@FzfpNImv*lIHP
zk*Tawo`9G?HstcBoH@t(17=uia<tn`z(D}2=_a^WRmoITEMrmL!uHBLW<X56-~}h=
z8rShTYv^o|jXGRSAYn1vJi}6vSiNnQc6wP))Wtn6$*j=rCpR-Jt1kI{Z3oZR?%8G(
zxr{oYquXVz3~vJQj8A@`MwbV(XdVrmC@zX7&Iufy<D%#P!q?2$d14&k9*cG(GFZ(S
zm=`;S23}nk!}qU_4V}Dj5}|UD@nj(3PjD!`DJkra;~~5ljPI5EfiuN~v}!7D2$I+>
zoybC~UjPwqosg+J2GoK+4L14r1aja^CoK<@+v5Q0EAg=B^&P~T5KJF%HU|AV53#VX
zkBf1r8rK&6gGs`Xx}@i>F|edPvownXQ~6stV6DKuaE>Xm&gQ#L4v?4K>TYmdsd-_r
z6$*tClyO6ck<S&lud?K&Znp<qNGB?p#s`FPp=b`p7FK=p=-Y8Ir5O_~ujwTx4k)(y
z`Ecx-=y$iDhKh#ifDH4uA)@N@c=v!t@^{sNkA6=jD$GRjm3&>3P!6V7LUM4cj%@Oj
zy;DuJ9|c*tVlE5Hxzz{IfoxOzZA6yalz+Z;2zs|)0N%oErXu+$IIU~fbuqcDpm~-_
z?l4q`*JVBThy9wMvSVWcSFdcQ`Wla#E>PR*B`rM*`@yFdPsDT1Jl_nXb@tw@DUp}K
z_cDGJpJE36B!(DuIWyp>c#J-Vtv*7?J<HRCcl+2I-U4j?c4x!RV_v)N;P9YGUIHqy
z4a_}e$0q${H!9CH5zo6rvz<&&(VOC)LzqyY7>>~vJto%+&by#~dXCp@*$<K^yf_V&
zJ>3mvj7MXF2TTZPZ07mnXK(uE`u<;lrApoOoHj*B=k!8AT*$l=^<FH+N9{PtmBW@A
z>;fj(tlR1S#qUH0WiT4LI<6?TC*o@D@VBEhXYZJdN%X7%S1aY6)Bq9Uj5l4$E;?}y
z+ZDX8z0vG2I`U!ouC3uf1~qjox~)C`XdJ8}Tju5-Z!_FK*Oz{DKLfLh)4I+Wh^^R*
z*l!K+9N|Rs>Ve7hEkC{szO=;rph{^bI0hE1Tr+KS4AJFaG5c&I6__lKQw>NMLlP~(
zqRD33&L}V90<rriYJ$R6suBImFt-L^T-P5@cilwb$2eOs<D^7`^+}Gb#uzq4DV|xq
zCpHfeMqgbnvM=*)E!Qtm<_Br^ARMB8fn`s;d3t#KYz;=>beBJ{yL;Q;gY=_hz^lVS
z-V4Qrbp}Vk{XKzBL!a3}yj!mnD6m|Wh8K&sA9#y{=|CyN(0MNxwzcHe4wI(=*r}AP
zzjt@?;_}kkUow4lN@Z+3bmj>4RB8MTHvlcHaz3<@tsT;Xw<GChb+|8rJr4>!Jse~<
zpof(LVMi+6Y5rhKWjA=&PHrpMp$=>y)lIdHbAjw8&1h=TOk&;X3qg<~&AJI+yVaf{
zM0Kc9lfO*vJE!>(QA+N72B5wUL8g66F$-S6hQ-Qs%%CZgDV-?`&a9C_^3H5h^r25~
zg7}LD(D({Nn=BKR_RYi}Hf}$PS@*{!!YCC^88;a2Z~@2MfitMmxG20A{E}APlHO9m
z+%&yXLURQdie<G2U<LsG8yNHupDC~=r&M&%a19LCXrFaySOr-Ya&=<aE9wn<w3IXs
zOY>h>9UtU~7dY;o8<-E|J};j0&dj{VD9GM&k+7{Pe|{w}O&XRQte;((FQR5fQo3?N
z1zxpq@2ahDV}c<j%g+18aE+K~TDE7pxu%p%HP`CVtQ`C5z1j}(0%XUp^UXZ$ksN{(
zvKt|cGy%CkeVt0Gg7$!&R$HU@sOKkI6oNcxfN#H(A69(yB(PC^)w|bDNWNn~Icr59
zLY_CnhvH=!;0t}k7)Z>hQ{xD7+MPqw>zLGM|4MVY+X7k{JupF2ryV*%MrQ47<Jm=-
z2~yK9pqAXf+2?`1q|me$2-eiN4%CIQue~(`Q63N-nRFkol^KSo7e8D<amS|fx|_Sw
zGl(pI$@V%sMKv7k!0^f$J-V><vFWNXRD+!TFBXs40-N^L_o-?C!!BiPSCo5Tg#R89
z^zj_aIzxs>eL)wd2tLlkikkOOal6pt4=U1;0tU_6u&V9IgAKrWn1;}Cfb;Hbzy4V7
zdL+<y-x&1f6fy^(8{wlo=x~8ua6@3|+_ZwfP;1Zb3_;sD^)i+2?GNsnRY^eMmZ!p-
z7702zhBTiylkJuk!fK42HAZUPJzlH!YMZC6wEHxv;8GMfOHN%b9k1kKE6^gAnQnqL
z3rG?l$_Kgywc_laEPaRsTZL5v#F^d*ScuC4Ck=W@ko=E#{fP|q19SF@w=6TmZAzQj
zAW**4JC&QVPo`Zido+2>&6knwkNBIIWMv#Dj+0pli+JlU!8&v&d5F%=hP({<S%?IQ
zm{Wezmy+Um%uASX1Ep<o6q0@+PflW~m%Ut*RoML{+@9J;bsqdCb)8)Rza5|MPu$95
zRCbUdk>MygdBsUDDH^_E9=5Y|k<w^JIlbj1o^ku|^)hn}{*g43ls<6FS(?M^6*A_}
zrHm_r#lD)KQdwdRa}bm#PvYg30#f+~Sfsiw*sztW>NY&|6iC`}Y$31rvIdE}+}pR}
z?s2?k<CTs>xXGPgPh|J3NeL5m<+z>TkpFh=AA<q4QAznxsdtc-2*m_-i3<cpu#zfo
z^4BaZga0ig9Y?D0C>bCmq0}*PXEDXyj4EF5*H)}(&VstYO1GDB*<RoeQ;%4uGd+r&
zWkF0{N})8LQ3)A3W4W10(2geP^MGggTfJDJ;N?26c~z)1%2*dgAcJ#C)?NN3<L}?G
zObrkqAzPIeKdrbDp@-xojteL)c}L0t!r|Ra)~g%11D!6?6^EoVCz(^UHpVwV;>SJC
z(WpXADAD}eFzGXe@uS_l+sq8#UA+P~K1^*3220x*Jiqg;C9d_meNLLdV+7oyZd?|%
z^X%mE+*~*Np1nH5V+IU^2F?eICG0h5?M5gC)2!WdWf}u&#u4a-e$;&uOrCGC&bEt7
zMWe;tX_%C{OMe{uDh0s*oUuPl=Yy<aV%<UhL?(Nr3gAh4_=E?Zxk7Gb>oQnSCeaiJ
zdX&vu81#?d?&{Jn^(Fq2lGGNuzo=aAMZO`X@M1SfuTT;>r^WtjMt}|xR5j=yH9U1|
zvPv+2*VL2BqoosoVc_I>e!w^RpR)oA!+!)trb3i{M_5`#&(LI#HlI}#cXwc$qYS;U
z#9bhl8n7da+k>C~t(bxU#6eb3i!Us-8~BAilFq;9NkF0jKn2X$SCnJh50$I>H8_!4
zJ238bhf#-bIygp!4w?xtRdIVXOlxQ>Cn=`8)*oa~Vwve<ga3g67mHXgnjqaezD1$s
z8;gO}EW%w<##qALc4}!!{U^m;P>U<YlJ@L@KCRu=;sZA|mRW>gq~FI_x9qmqPD!&G
zhHU`dyWU6+)+!Hw?D<IJL1M0H>3s1l24DQt&T`lan>(=qs(u)mw5=Hymt~O&VAyS9
zg2Dz9J`>#_aOeku=I>t;TTtgS;TSez^MYNWB_n>XpsR@r)viSJ)j2w-d73ef0FBXh
zF^Uc5C8}zk!d$K&mj8X4*dgY{05xPMO0=;EuiF#cGspbx*h2q;W3KCxV=&J3?=z>~
zVTt3ReI;%X^-PsJYOvyopXuOw`d@$|(CuDpJ$>V=7f-d1_}@`a>+N?!tP|J3#vH!+
zuIKcv)KO}X51h-9bfaMl-9z_AN?4ag%{?{irO2@c8%DulLPvGZRaWFh!)v!5)q!A8
z0Lt5-5$J55q&<QX;1FOUdW{&OD+mp4w;5$T30+{CA?B|qyJh<1jy~WGs%;#Dlsz^x
z`}zhzblDP6kimuzZFFqz=R!eBQegO$0j-_|au$Em<<<Z*8P>UVwx3a>pIGbVmh~ve
zZ|Q<u)zEyYR5J~IshnhuI|O6t^_`DS%}N^VBq|4`@7rh@S4-hZv-dU<x@5pen6M|N
zLASfj*vRQGcR>)cZU{1e-h)@?8(MUreW&Gobh|c&=>6|Ot}&$2@(}`-X1LQl(RbOq
zSFvtO&!p_GUMaGj>%0G<VLVX`$oTb+#gBN<%=<>|#)`02)21z^e6{(Uhl$p*Pp4p{
zb~%`N&uhfZ!L5DEl%NU4QqpSh3uA{AQKE#DBiC-`<ihvIxu<EGZ%?Y|izJ_1zIy@b
z{VFxxmpojBQ+Fz$lc!T$zDK>X7jY+}leM@2aEqz|mDIVLzyup&M*+y1;e#fV!YT{%
zFQEnJBP4e=E*eR4ym)$-M44vQ{e$!<2L<hY!RE`nM?h)jv_o{E;S5>yTiN)6R-g3t
zH|*fi6e!)Zyh0xuG>#oNxwBIS3^qxy`nKVpHY$+YqGf?(vuPCw%?0m{2{f&0MWKjQ
z9#Ly5Q?T>6R{ubv3b-(sufGH^_g&|9z_k*I|A$SR2TiVMPh3fzzR*XJgPxXTvCOA&
z#E10FhLh~?k=p+$Oa$1kNX;O$FpAmdrNaCQM4u3c#x}4eV$pd+z}YtzIw*;(zdNp3
z69qF&(pW(X(;l+Q;y4p_t+Z@ien{p9)-kd0N6QN=dc<C!VbfrH-jT?P`d_jlH55-R
z`8fnW9V44(o?2b6buls^-wmS!;R2`QAtR?;Bb^Nhb33C7y-sY$@%P^+;3C<k%h7z|
zwC+Ai%Sbtufx6?i>y~0x77X8?x=R*6nU@^8-(TGyTcw*TI5+ZG%bdPK7TNW{Rc5ZM
z4F`>UaYGqCf51iW2=WFUrpPWR8f%*^((P5@Z^*9ZedHPW%H;?F@jGW{<^h7gORot_
zH+m{njJlHGn>DH2#H#Ycu?e>3G^$_Q#c(RiVsUsN^e2XkHQCRXcHln<&z~S4&`{AE
zOlQiXJW}VBOge&>AL!57)nGP3km7mAYl~HU1Z9nOh#J)|l6)~F>Mb@(y{O6K>)2xH
zc#}CFV1^!Eyqavy<$F^dGw{<Kv41L{L1P(Jp&qc!H^)PO`23pOs}`+Mj{}%|9Y*hU
zW`97b3xq?5!xdbE?<S7tG+mi0uw8{cNNT&@3Zk{~KOD!KJdO6L-zNc1O4CJ;IbTBC
zxU(8gTYH(GS7<c|7n}k9*@A{dHbc8sl_kcj(2AI4%l*JFx7Hn6i;QW~_ZBpocXKFz
z7*7kCQ(56c#iv9E*_H!l%Cq%8TwJt=iN<n3rJqHPHTp*<M>&O&tYaGQ1{sj*1lv$4
z*k)aN?JQBQOwrV&0Tcd4=N^B>r$ciw%=%3!XP);>X)d{Eqr){i&_KwprM$%Y&pD5>
zbQpf=f2~L-wl*HgroFF$e5@f#1v%FswQ1Bhc+MO_ZG5qy`r+7|+jRydU*!XGlvmUe
z6wDK6lnK|K)-1<`XCE{kuFmcEUjax8`KYFUfMk<DDhaJL@;iihP3zttRO-8(q&nKR
z`!%q6+Kll`6Wmw3#IRP$YiRfM^{p3Whk&>p4J_+q2}T2HnzMo5V94YOKOqNBwcu`~
z`RGL@F=^6i?ko+iSdV?JuvQ6nGtETD2t;PV2rctSCz$fVE&YEF+>#sJo;VX>bq?R<
zKe$)aV{@G~Ac{t8E<8emw-Dp*hwDxVy!O$eV?0<^1w*yOkGRG<vqe&D7m)!uFtBmp
zsx+uMD|1?nElI0flKkeVwEr{$T9_g>vLSZ%NX*%>Bn*&J(F>Tnh4k$U1>Ro>hUBPb
zu?!|!LH9W?L)#t_MiIR<KO?B@<pdAX8m{SZB=`~P0+C^VtD|?D<!|Gg5QjHb7t5d$
zYlx((r6p(*FT&WQA|C;zdQ_a2{V!L=3^c34J;dIYg6ND&I{4=br~(#FzVnOcO|PuE
zT;DO#M}^Wp_+U|W8>(+g={hkt25`OFP4B?kHfo}I@DWuD1i~g*2Zmji{V3tBC`4(6
zPj_Ynn&OeBR-MFQ*)&=I)z(t$`PO2{&6whWdyp<alotBt#YCwk#6JbA&+-pgQrZgt
zoVkA@Uiu|Pj9&7t?1=OAvg7_!UJhx(k)V&uZQ2>p#Uww?i1D=P=ds1wPt8RHD)1~-
zYS#|r;;u}==U+{GYcmfosrI~&9YEXPiH?wZMhl-$y?L`t`;H<>f)tn9l;J9A{MxJ*
z8%O{zSDI<bS=Y=(QYLJq6H~ahkM{;%T+4a5X<(E5#iGN7Nx?Bkf=9%I@o2xOYnhk}
zI%8pTLxquSnv(M;XBO_e-Y|T@;Uar^?5$xjXyqYpJViZF26yA&x+3-{b1b9@JUL&u
zIhW)}Lq{Si2G`*WB82{WYIG81#&^cH7S{)@kdHyzcInE7(Yiz1Ypt&QyC#z`ct*f0
zP_u)m=uwRS9ndAAZ?o>*cC3L;GSx-FAR@m|CK=}rL;7)br|TmzhAzgj)blo^W&;^E
z@Ma1w?+k_AZy6|dc`&k<oSDF@ErDv3Wxyu+w1=X2EDe?1UQ3u?@07T9-4Kek(8O&v
z4M2sIPui}78jzuDR&@Kmr}=9(D<a!6QrT|9Vs<ya0)JEV3J^uYm>0NofKA)RnX0>x
z-vP-Y=Uydh_k9tI=fM+`(7*L{J75o9HwS<0wZ6SXrrM(T-DMvK2u@2XX)XwP|Er`u
zsD5~I&(<YEOK`24y42}ZcN@_D0;xK2(;fLRF$h*z%m(A#CEn1+`$#52C&mHuh&b_K
zsm@cA71&S8zb?M&sFR;f9H`stB%lnwEmt4)1%JRciJwc`cyi=TXJ&+m{oBinp5wX1
z{m%lXW@KB>GAOP^Lx}W*wsLJt3xfhaD`Vj_n`u351v0*KPuA(m`o>o&j+jZ$qTLeD
z+TaZcUy39Q<Yj&Q?8hbZfQ3tNm51wBfSYH&m;9G~!bNla<}Wq*gAhc(s1A#PS^6`g
zY**y_!?&A!&ord6O(7!p7I=fU`)45}(#fNK)^Y23Vv}9z3I^E5C`fqD<X1IzuD`7t
zNLQ;F?I%lTyvbu&NBZ9_A`T;kK6JRKpT%eeF|TaQ_!gIT!MxDL{wtiHob}<fUCbFp
zL^wU+Lg32PW4@t?AxMIGOTV?$^7)|@&(AQ(#pwhbPKjjxDe*?Ko_svGhb6G`_W~$x
zKIb555$TEmId)R4!v4iO_N$=_+By;?VQCTXkb(_35fD5=QWmY>aWpzQ<rFiW5pJ&8
zM<dx(;iNUfEXm(ZlG`S^U6@gmbWTeN)p<w~kZ=Rl*^uS7q%a^`Z-=QqAJ>{;F(;(k
z_0Je-51KwvzelaoYG7WjVc*(Vp9E8i!yv!zWUQmSjB$Gvr7E*|-AHxtTpru6T=RE3
z?fJd=%Y*yPrzFk#fR$r4*VUwd4sd#g@LDEx)eSO8(gWTn^RUaZO;qoGAKdZ{0&t44
z)a|46gS4oJ4>tQ7U#q)*Vcf_S#GMGHVO*svw?j%P@Tq;)2v0562QZT&&##)2;6j4L
z1`c`p9cut<+3cUOqIf2x6~GqJeA(=UAo`F!1_Yj$iL2az35i%A{|uvbCV7y`gxdv5
zp$MgckjVpPLp~9stkFn_RX)@}CH1rp#*D?bDBwt|B;Wa{)UCdFBO{EDUYKDOYRp6F
z7e@T&IHb3TrEi_F^aFvYIa0!lP`1C>$H@}3;~KQbeKo9=7#6ox!_Lg8(;Pri@`&}D
zDB>fprm(A@yT!jmM`V|HcYw!Q!v2w=Jk?gsfJ4s)agWrdR1ec_yI#m|Zwy&Wi@=W-
z$<T73G0Z_4*Qdw%phwVf2&7Yu&}T8*hBJPNpHqt_?w*&Ms#~i7BdD<!rPR&Bn&MTg
zG3voF*G$KDF)itDf}*nSFq-?~*=m2qBOK4mMQ2w)tJbEgub6cqhdW3sW}ptOcy1rU
zd$9};j^u?6g>nX!0;?y0oB72~`WC;ggZox+;Ke54_yDrvB2zedWSYx%73DTDm@r*g
zu`2h)q(%%yV3fAwfBaA4J7wDtsY=0ongv=4YGV+8qa2a1`uE(0;U=DMrTmim2ogem
zWKTRxXR38$RaVSsM7CiZre*S8vX4Dzy&*#J*8VxeF863KAAPn87F^1y0Uw91<+CSd
zzu+G{`rPB`{6L+tc(Y0(1WYg)H^udLr$p3vxo^aF1;ti9y9eb8JEaM3;ichqR?gbv
z;~Kzl;cyK89@1M(%Lfm*s(A$X_|8SwN%NV|_hAd#T=}^3Av2DeXQUs(i$F$iR#PVg
z69+N-rqj?EvZ0GfU~XTqPkq?nxYouW2A;fNR)$!1RmnbKkzndY_*{UBxlDcu*qj{w
zciaRbs3D<v;YlV@OvnI7z3CU$W1Yxg9wo@JKi6S&J@Ep>t8*kpn%@=j?EI44t#Ez~
z+>Kjtcv~3#lSU8uYi<tbc;r7z%Yl8*=O-y=Vl`ttyqNawY*4%r>VqEp&Ka<W9Bf5%
z1CZl+6W@pFgVB6JTlcgiGgKQ*ijWd2r+*qQJv)e3WgN(K>6&*9r>wz}C@F~99z%>@
zn?_Kz-fa6-CA&C^WEsVq5Up3=-zqkRW&Qp}5o+^@xWCRX4B|0Y^eE0qJzyWW=fBII
zF)qp|j5X|_IWa_>MC0*}<KT8pAAz^HjZgA3tfmnMZj%(S&3HERcX;n}W*Kr{F|X9|
zu{qS|zjw7x<c-tsnIrL6Xu7Yg4%0Pn_aJ?*khn~3$&7vs4J#B%e}vWDxDvD_{<Yud
zj5u|(@No{BWG<xo>6UvC@HKo95f|z&%?uR^y!Stk+%E`=8&rlOLnnR*OxO+0Zl@Ac
zYdlhUQef*59}wrhy)@P<qODw2b!MC&tgPuTQ5S^KGK>kD^(p^&#lOm`O2=L9B;dv%
zD{nEK%o)^}!PJ0|hWd$mrr~XHu!6>iAy`kZ)0`^K38Oq&BtSQK#cMj*Z-?`VW56_d
zj?WIru)UE!JLu#<j#;ZCH|yxh%p=%@*vm?@3Ew!G^o0risC(sIrR*q2R8^V=8|l_K
zGd|*)16+wnro%)4Pxk*(?nVP^;dYA;aF7<~5Q={)^Thl&=zEn(FI5^m0a|zyKtPeC
zc6qJuG_scz!qpDu&O=HI!<9wYIZK2;q~fW9#Xk4_%a<#&AiH@aP*21Hc2}UYs08U5
zm#i@9<S<;e1GSuwIto-7U!!LnmT+v8=hI_K90|l3n}6Q+3ywJe0Rx5SBRhAZD7wrT
z%ojB<UX_u1%W*;|cdWS#T_;7Zyd?+#xg4?Me|GCOxpHYk|0kkI`*O-N68WNk6D?!w
zGGjtxlrvT{!&s;z_AV%Up#rY4LV|2r3(VPAB|_GB)%I-i2&U^Ca;V#n09^)RR8fUX
zVD1N!=*}zBI5vy4gej3*1m9me=RZvy?o3!<n=2Z8IIefPp$!+a_BIwJF-k&5BWE+8
zULrdt1<Zd{k-X4ws011~c|{MAbIv-`9l%zY{3ESRO^tpAqtOTw;1`NqL5|L+&5m2U
zNrK0xfmm{o*-3TrUXD0z^Dt%a3plW{+@c#@rz*pN8Z9~j0yfSt99!^UZ}E&a1*px>
z$1s6nX=#|bP>Bf$5;!CtTNe*oe7Z{0Ls&SNy#jbc{n<CRn2H=Sc!EDQQtV2iFin64
z))-|f+?YhUq%7to43rMaRqM>t*}*<uWWE_PrW@<&Up7!JM%4miKqAzNnPLe!Xq(@l
z8jx%2Hrt;fEo&Fho?Fsk4`A|5KO>u_-CM&Lt?YhggI@DP)1FoE?7ve96ZAP-JK+w^
z+~;n_pH?FL6KP4H--WhJh27-k7c)c~iklpCA#~pcO6aOG7Y5AyphBu?s@%$aX0MnX
z`&)J&tX39SOMx$EG1n<I!)!!T*U{|eKh9FobG*}H*?_yj(FfzPd4ao@gv4#4&yj~E
zQtn+*O{ARlBrsIsOfaU-)2+_EBC^k}1~&gE`y_>OLb8`BnWzQ|u+KGNfp?b=de<vy
z=%g7xHON&41*&cW#;r&KgFFm|Lx<#>by<vfM17FCbDgDZj`(zVH~CNLLT;NgCQRwy
z7Br2K|KDS1)ouf}a2+P~tv`Lz$50A5YB_-6HR$Xt&tL(K;12Z@_W;btYc~eh`dVG{
zTup~Fu@Sro?sI*Lf+ut=&O_oMGq^v=!U09RRnwRI!geh`q-0GG4EFo>CkrV}QXB90
z_NSK5s%-NwA9egzO{Fbl*zSgl!+jRgo_Xf-zr}+OZf&6QE;4!Cw@%a!>p3Fwol0c3
zZFe>)DWz{Fn*Mi4!6H0HC*~4JM{UM6o+pKC8ip6UMx}<-$Sl^cc_`cg6lAC1qZ>X$
zx^W4=D-vYkzF5Y~&#cfij<fhPD(+ihZncz=k~LvNtETn|ElLpkH%ME9oLcrmZR4>Z
z%WdLB1QK5P;jrrj)zPoSz2t2vN%!!<ROVI$T6m&UypN!72KIImq|5lzCXZk(qx@3-
zkSc_;NoHy*<6on!;0KT8)ll(GIvM$up+gJ;V0;?l?5#h-!c6f)r0Ev6I6R%5Pu%67
zJ=#hU=ZO8dsX04uvd)%v0u#sWv`klqeP$EpSIc70uOhAF5@};2WbUV&FG{S2(nEv1
z9UUn9liy3K)^gxzg$2U-?_bk5;X%&6?zwv?JX#cy`$OqJNF-gCYM6V*1yButi0$g5
zASbxToyQL_XSlT7Ad3<`zP7j~;aD~IxGj0IHlZT+wKzfe7|EZg_O?x@dA4Y5L3$Xb
zxN%cLT)uv++`I4GR<RjWTc+jtYwoAq!<E4(i3JafX?~sxU%8oOaO3dNH|pfYRDQAx
zJhKM5cJ%?Te*BEWTCNEUewJ=dcjdvq??MQ;2_G!Q&Cpjgkx(U0`=Kp#7gq)?76$O^
zA>I&SqYn6#C3*^T)VIw<t4t)~>&cR6hopVg8S0PIVPigJBlgrx^`JPcsV{9>K@Xa`
zu?mmt*z-`}k^M6xijO_dLQ~D%W1*hn2wy;*?fP)~2dT*X{mg`uEiEX+FE7vaEQKl=
z8C6`fN2A4ee4v|Q?<vsgOe%M1%QS1US1BWy=g%K85@d5Zxnbw^Ph^SMJ$1qy7%AcV
zI+=qJi*7U8`EHf!TbQe+NnKbm@Q@H#LIqWyy=02~Rz(T|YkxnqczCM3`8xAoz5Qgk
z?TA9Pg+k$ybg}0~IC~0)J~NiYNEPX~x9v>jd!)ZgpPkjgDO_vp&3^qW9BfS!DjRI1
zOD3RbqZDJ@3e+nbm(SNYAE8p5O|ozTP9#*RhKHCK(Pe>|_g?;*InJ@~SOhYDR`H=?
zkoei<PGSR|S{JQKhS5g1jE(j6k{qc&_lf7LNf$sCrtu0{<wrT8f`k1P=9c<V4Q1p?
z(MDUqdOrneUc_$mm*=&yc}LlY=>@Ca;5NBDZN_>0=zDNENRT@Yy_Az{nO@+)!V&qT
z3jHg;PZ*xI%?V_OKjgN60$Kq2<rp^epwpJD2`WtLzi_~+q|7@$=3dsAM=T0WiQBQW
zZq?@xw!W0xTx{un!7vNKVW0+T0qW3A<{hz*fdSFCv3ZXC(t}Q#6ZCyKqzEH=kd)YS
zem(&0Y--Xd1Xyu~d3$?yUf&|ypH>?YJFloV_Xc*@9^J>~T_T0^1;nj(kTZ^2yZr&_
zdm*yb>gDV{S+p^b)KFM5fx%@Oh4KZFAh?IbF&~?J%Lai*@|AAOjHND(k`F|-l9*CQ
z@(t=f+StkZ%iCsITT}DLA%a^Ixo<8!5_;rr(I<27f4YLRV099R)shA|aPjuHk)Py2
zD+?)|10U#~+N}N&yitKGoMunD$X8ZBYEPb>zM!bi*OLMr^~lapU-|rlHXH?1znFWH
zHgtv+(Z-TDE<iqBb`a1yZ1cqJIs7E@Gc*GeX$er(8J2XJ+ZxVU+SV7ETu<%%7*AQ;
z-TjyUEa0v?VFu>JP9Xy(t~1`)Y@V8r<{U3T;5iMZz8H8fg><+uRS_Fp>R~#`7-f)b
z{E-TGHV5<Bv<#mE^WX0OI?O1$Y9iyL<ooTHWrA3_8VK3NhK7o)Q@pHPmWMC3mT`O%
zu`dVXIPFeCWcr*r_EYcUkia2Hmc4bSqLfe?kyYwmc06unW83IQX^myEiMz-r`Z&t|
zvX>tLQuji0jt%b0xn0+)rCgGExx(Qkz~ZG6E1@Om;6$r-gs-gcrxPi-Q`U-?3DvsU
z4g$oI+R1P$&Q#q*qlmbl%FgZX*4l{J@-KM#Q;@(+gZ8l5PF8FN)nLlumWKMX#=X#U
z(j3?*io~n&8Ny|W+i8W-(JR<!eBR#T_L@#^&L3fn<OwP`!XT>OiEzYCgn9egZ!z$e
zHymw3SyL0IzSIkx#0$yQLwJ#WQbrx)Ki8sH8%(0ot3!>$()`Q9wpBwEQZhl3=SylS
zEN>HNbzj{)FfR(LEx^wsVea=A6!CcYu#x-a9X<_t;Z3iB=E(eW^5CA)=48l~olJ;N
z)2)jC0PfXP{ShWmn7C|I&)F64Ox+Dx?)ABN=t+)_LI0-Ry&XCEh_{4jYZkb=4|1F_
zanxansOB;ipi!&eEU(->;5qmYig)gEtTUr*eui7yHk8>Q=LWCI&o8va{3afZcL&X-
zD3T~GzT<%~f-|oX`)q0sFc*{U2902@Fl#G3+7TbJ@~ppA<Hcr$^D=#BKh6`5d(l=e
z&h5vnxrJidoa-<@^KEz&OS|vbN^-tXA?j{d7W(}FI1|TH;$4fub13EccWmay6N+x*
zMk6N22Kbml?F#Wad?|31%jq*BQ^&ElvHdFluU@4Xjip{WcJ<F@UkTJr%W4t0$({f9
z`7!dF7P#>WGUPQFvlPoQIZ^7_#Bj>ocoTQ?Rknn9#-*VkfuLyWMWO>4Xk1)DC8L~X
zWI`-wqIe$ErI`c#%5j5}uqm8Po67#%?=NrX`RZ*#uEQXR&p1DZ71aQ{UUJ7jW0*yk
zb<{2(fjgSt9ORqr;&CW=utrbIfOb*OT;9C7PMY8)ZP!(*&^pN1Be6FgI}%FGXoX!`
z6rJyoIcQQ1$UOQP-S55dP0ry|i;_Bu0HUMUJ1ehkL_2HJ^`-|uTTIe0x$PrCE4asz
z7?4cI?jNUZ?|pdV(hH9t38N8Y2<zK(-(6H!3g#TqEb6i|He)feRl~&!#FIfJLOUdn
zMU1=eZ-%A<Al^&hh{gf^&?-CD?r(xlaj9m%h~TLu6k}U^&hp0aIK<pi2+Y#2PQ_pT
zv%8M2G1`A6KxJZ$S0!x|T8P|wX%voS`#gI8%A6G>+R2<(j7vFU)nK|iCFq7zMvtZt
zIVFIW+DH~KF{#Gdad2)a^cX(cFteQz_s<Oh^9E(DfWUX}oIR!b$#tH1GYKs1&_R#>
z*49Of+gnpMz~d+@0179gZK&!sWnx*e$Lx4%1%#ps4W=|`+>gI{SoUk0{<Qm&>9;e=
zLr{}P^&$gIScDvl#lXRc?GEuvyEsRbsfMJ{HA&)(|MG+W2N?Sc8Lp`3vKo>nVda57
zN!sWFch(-(4(LD+xK=mr2+A_G2HDCi5)z)9QD}{pQrF&G@Xe9+;2ht2NthUb=bzhL
z6SD_x>0>>lT<dzz5upsMN%n2n`nqj(WOB9ogf4|nT%_*34!M%1<x4`@dt=En2b?F+
zp2b=WRBlOf^yBPgQnwZW<fk|QP+VjMpP=W<L&})Ek)vi+?+E6ST0EhW8oyo#22d+}
zR5Vt1HqD2}J<rzTMGTe;E%#*0GwDFZ>;mjEi-W>^NAvqw#>*xd^m3;PGw*>ERZ1#)
z=@vd|z5tH8?zxmUdfEITL-zdGfRM8Uywy4iC@gL3w5bJiUVCv#TD4f}dN$D_Va+#B
z&pDEup#0xnQ3t%q%BLQC$<FYg;a%}$83vW{@pn8Lu`|M<6COzN9fzTa0Lqv~q)=n8
zhEh0hW~V45Z15ALVI?)QL;BpnEpH6LiRbuyY9P??YSd24+W?9?mz5XmJA)NTd~dc(
z(8a|Updo}1%=^gfm;io>#YCw}3le#QXBi8~4Eisr*C#ro6lqta)deMirk*u`sUSl^
zaU0c=LE)uoMtsB7^k2vQLZ7M%ew|rrlyJAmiI+~D_x2jd)6kz7(ERpxM`eXKP4E(8
z;|=YlaGZN=%r11F#Yy<Z8{j+IO~8^PU|a*guEX>ka(+%D(dt4JL&y<pHeC9#Mnd?#
zaLn=n*$1R$%xg~>w)A0X?CgdVx<!~SQSJxu`;M0jnIj{G?q+OotP^AXV`Cl3zo!-Y
zFVs}eyz_U#{g8qqU(U=I%g1O+^IO4m_o4pE1YWb2Zcqk7H+8O$-b#H1-_CX)MF>6B
zb_}mAzt4OSv-g8CY-pk2m?>IFoH-o2%-WwI?2>L2w5gmgo2*L>*5jaA+X%Yq-3=oX
zz}e$f_+)s<z7|X}WiL&fN^oVnx>r_wDP<r4D2vMPj@($_+Pl!;8s3=iXtvIW<iEfr
zgSdKkk_n^ky<O2L9CM(q!S<S|w2O7;nS9j0-F7X2NMOED-WJ67f{!5gU>4B!{9cx8
zA$pszHn8Jkh2V+QG~9rT_GDf9vJ3D{>yB3kV*pqCW?Nc2c!-_)ko`xig#d0jayvwW
zd%)kCL393nevhrC3F~B7?GoqNkV$8s84H@b%c^>}UduBb>FmC&!wVr4qHj1=2Z|S9
zO|Daxx|H%IEfAZkXFSbpl-pCvrqafK)abaS#l3Ni+~WLwlw>4#EsM<IavBCNTxIc2
znu1v5(P`KhsKP-b@hEC#lk}1`Aaer&f>!Gas~rMQFL#`K!vD(s4t9Bv5B{j8w~1eQ
z2xX$>D^1FHoo~OdD1-yLbtfOpGa2t1H2z^KOidIR=*=<QhRRdb4qi%v2UOC|;Yc&n
z#Kw<A5Df!Q`<XYT^E6$_tzzIz>RWS(qf)%`u2z>LUDclM%BB@dr^+@#o+-+*=F62e
zf2j6)J}gNJ!I+^!)bAl9`5lo*xIk6i6E&(#Qo&CrE9+Sml(LC5kT5HGJ^1~S;mX~l
z7;6ryJkkCev<<)Tewq?hQmWJ(&Um0_4uD9sM3#ItY*c)_L}9zkj+X{Yub$D{F)*&m
zHI2g~_b=m9I?%aHdhn_|;u%2?{Pf#MWzAq16b~9wWJ^fYiWUhh^x61dIA>f2U>R03
zQYFNNBXnkB3%L$F9J0Z4CM@dkNb*ZClu)C6^mJFUiF1~@p-h`HEs48c`1U_dCD{a0
z+H@4{&~F<<>RYtvjD+yrx$b9If74mc9I%T9BlZ|yQ$X-@l`P>%6-I1`nM%u+gWXFq
zVxu<76g(n8sQ(A<ztlReyGsi89eXb*K@J(7es|2$MTqX%iML%aqs*_9ae<3r=k}m|
zkS&=PM6H>zJ{iP9QuiD|1M=b~!OG#O3m>2aCGT4E7V4{fpagUL`K5z($pwjFN@V+2
z8lj;VPyYH0*AnkcTpa0sID12o#d}XJI^s6zW009Yfg+SC_q&*aGh%>bq~gryZax*~
zrhnyd7?k4&`*c8@6|(()DvJKT(kGocIb%@$llQx8U-Q;TV?bWM@E1*GZT9sFTUXJX
zj@%J4PNX1FdJ}X&UMw`luPL>vMnWI+QZuhU3;(t>{@VKuu8a|SvN*<d=VtOtl<1b&
ztw}6x5+v!G;d5Uf;{V&hV00Hg^B=PXlp!tsC8#)GML&(VHpx20ZtvzP3rh^S_6Fqe
zRNibF3E5kd`D<XDi&6mayv$wc;lae&@Q_F1KtwH+LamY4M>joBkHo2z%Gc|B%rs?S
zMEv(q_wfH!KJ9wrNE~FYqUX0FCQFyGdjB{e+Z^v8@1GpUY;nZU*E6L8>l}Ta$i#$%
z(q6E)P)1ZA4dVFfIod3g(d|<S#=|-m=^T{8lU-2Q7ZcQSB3k>xw2wzaX5R>}caXR#
z&p%x%j9C=a?2U*|)rkWMKaGscBx2ZhZ5;a6E%aS-79*769DfpD4muI%QI56rmzuD_
zr|W|YX?Wk<mmSnYBldXu@ccJhBhqa6DrD)@eSUYGi{E&`14X2l{J{3^u22*&J|;d#
zV1Xw5erK>9M~iU0xRo*4Fv>n~D!A7zgMm5n_xp`_5=UqB^?T$V@wsqw_*vwMcv_UW
z=`tR;^RD4OQ1+xH+-z-@4*?cM2>gVwMkmaw)&Ud}!-1pb9fj+<exh(UexQKVzfq=f
zujxB&h@Ch7s_&WQL+*k=*k&;o?wYCH`$Oq>cSoQua(dxQ0g0)r5TddJP2!L{Bifzo
z!mDU%`GR+B-ljYe%8D7&L1u<x2TGtvC;B<c?HYdR_nL#0HRuYM+p{;vw9Gk%C?}e_
zQJcfaGu!Q6-F#DT_seHgR4Xg#F#n+g`};22=-Nf0=bLfUaTwU^a=j!3X*YV%9TT}Y
zi1WJBtTZX%`+!n_UA<WhuAZZ4256jxIQT4s@NQS0@@7-^G?VlmWLEds>5iAo#&;$(
z-&6?ADkM=Q$_V{r!-YZlMg(Z6HI*2Hg9H8LokOT=2%!7VOq$NJwy&QgC`;)X|3A8j
zAkUGFT{!u13>=|F2EhHq4GM4{_CVdnv9}bsKAYR-j}^LD$}lveGbVOd-Z~{bqzu)A
z=y7ZkBChIuLkFW@&fh|v3RB*bAHS{|l2g}9nIO{J+wU;@ZSPw9alu%N)mK?OS$-4C
zdL{go&k0ZjKp4Xr9?x3bSuQT9i<suRjlxKJ5Io59?SS9^Wc->dO}6!0^AM(FvB3qT
z=78gS-cx?S*7jXO!J7phg{E8Z7BR@EBzon(c8Td~H*4bHjL?G>3}H7hMSDd?s5y&g
zG4^ArrsoIc`p;>w6W8k`RMV$@iT%gm2bWPodHoYtRF{n9HN6)W&s^Rji`7A%EM4QJ
zo_J<oe_wAq(K(ogEy!1fI>;1?5dD7kxNX|thNO^=RXPVSfw}0j_6Qg{0SM+l?38jG
zLk1&ToJ2M0ZuU7qPit3u%%!j8bc=5$>GYb9Myt!txTLEikgD#$L7Yt>{SmoxLWO&!
z&ChXivmMx-1`_*MIFLwjvRy1A?UFKEF!e>w%h7c0X#~x3%&;-`899@T(11@a@{yK#
zu;iyvpDoS)&N>SyS6<6;t`$;Dhxoq(ez=B$`aDt?H+e<TFwIC3vV>)xhv!qT%qGsp
zTn+BPAjAP#0AxLu2*+V5B4S)U8gy6uX<qh^I6Su-P;<(~1)w6zu~6Vz?G;pDkk7~4
z&RA8zVwsflasb}UuE~!i(#hcmG}d4AsdgGia&2w+;Yue(oAscyLx6kytf6+=G0R2q
z0>%*O!+Pe+ijcSUtoCXCP}N=g{ZMC?QdT0uR`b2SlFdzF`g+VyG9?=P1SlIpZ8L+z
zHWSNRc7O^>aJ3j(@RP`wvjk+xi+uvfT+Sbg+w;6hF+2b*K+?Z<0js^Wd=cGgOh|V+
zyS)|_i7o=94&ls$FBDI<^HhD)ECGS-$~50tL*&bZq>;aKcXyu6mG*#di^^&ef!Nar
z+9!(#ue`goTFRE5X$pw*k=rLz^HTWMdSU+NOz?82NIEH2KrdO%D~2X$38yEUok<6K
zoxzWz&1A=E?-0SZd7;Rmh{dre7Zx!yFUXh}hENqm#3N99+y5qE`nHfv?P7}O+zIt2
z>$^5GnCn%Duek9C{00z<yq3s@3T=|pp$F&ggwq~duLKgNF7HEq{cTk5y5z?BCW_n~
z2D_G`)a7qeHJF?~;|R2ek*MjKQrL_h%&HE4Ncb|tmK2GO|4pi^Deab89_|g9K_9*C
zX=k1}l~*roAa6mO0G5;YR1~Lq7S4TkL>?<rtcQunK_Ql$4uX;>Wt}AR=ZH($pSrM1
z(9Uk6c88_EuhN81V@Ne=Y#emU7P)zB`dl2}r!!l~MLPOXBCTvdi;oDImT!Y8!M{pv
zehyCdpbn7s>JZC$eIl8$v-g#w`RSzX)ze&9#Ei?y$-og>{%gi#4^H#pal_cWVj6MM
zu=cl9*NC?^&~k9YJY<B-dRN06nld<b!9!p7Az9;C4`l(`A147QBykluYH6v-uXRJO
z^U7i>GVO0h5h}MhJ~x@Z#ITMM+g10wCu$U&(Cz9#cf#Adq;DLAo!uM0_hq>3Ci~rl
zH((xd)vvIztk1;9d<-7GQabsEC%En$jVr=9yF<7}PuuIhY(}T-bELX*+sI8q<Wk$d
zEyT}u&|W#Rb_6iv@+d$S-Itv)j>F6vU$U1bJihM)eZXea8DMo9ch`bGgtiq5$cDQi
zTdXkC7D)961od=QV9pC$Tj`0c(9|tG#k}b@7FxxN>h1X|Y6KvwYoeB}D4Q6^np0HN
zp&v)_iK~&W{hlw*w1EG6(v{?91%cKf&fxALETU#;G;ZChz>kb2Mr$7=b^8Q2Ua0sO
zA2;+twMrO-^^GimsT0BfDRYPUl6FY&P?ZMzJhe;#=RJpg!8Hj~hvWLUaUvz3FUSVo
zn8uQEkm>;LBDs9a;Fqmi6+*7`8wcCbN1L9`Z1UvM^nOEAqU3jeg{^(&m=xsM7IemV
z(+|%AXx_a-Q~zD#Wkg&`IHYE!f=xVEne<k#C}s*#z4su<s&zkV$wF8?CnzBE|8$qe
zq!u0P*^&W<&WBb%WhbUPMdQ?fj{(|@I^1pqAT(}<(Fe6Vst2TNB5{a6MF%%mCD9@1
zZGDYLtHqa8epfs`bdN<aUlLDc5j79lDx?qVx>(fUX|Hq$7va>VM)zDE+=sDa*VT^q
zoWOwT?>d!Vf70iw*e9Fx!G$v)Jq8wK!oh#ua~Oygr++BMADe62W^bXHmPqvP+_I=x
z$V<K7cj9dbgEf~t1HCwyCgYVqqy&l#SOO!5<_uY^q`VKB^f6B=UUwd9_c0~7ZMNfI
zqL=q14LexIl-cxUO;G8YB@LE{)R|JO2RbWm{h2(n49!!KnHRCJ6*<~M+NWB=jOb=A
zX|q&2hR(`9uFaBI#NL(I*xJKohsN967(&eic%xC|*j$G-`rvPRVLJ3e4=w~{Ok8cG
zci;oCe>_h01hk1lr&mJen(hvoHzU*6MiQlwk-dpoaU8IKWb0U`$Lhb?P6RBBylXJ}
zo@RQ1273v@?b}8an>h<>1Dz#0gIyr1&Yc2GdJA?1F7l0HHpZCJOxMnxc?xdFiFRip
zeknUqVW!OCFG{7E9Nd%^%1$kK;#^uAqJe$R2YxUDUGUnWB_|WzS;y*?sXc5uV20*S
zxtTR30agD5n&jrJ%v3o5CS;2)=06i54sJ1ohzGO%v+*S~B-KF`B@m|5t05P_0Yo5=
z9n%0PrrqPqAYyPg^%`{>t#quY-xDW=;g-bJeRG$dTCvNW(XooQ4nTb4162{>BTyuT
z(iN(LilFUGDl)~6aMnco8#HQAF0yaQ_@wBNjbSRj3vsY$ETZop63p^=dK0wtCG^|_
zIUjr<`*K>Xlj{f%0Xm3BO{J!#kDmdMq>dx!+!>&z`?0qm)%9Lr6dDh?UV0IZr*~R<
z^@~LLiGY12sS)AtqA2>yXYxiw>VgtZP;bump!w(WussrgSy`DZk>Lima?!i1yzYmr
zhK0S(@kYJ3V+ZU^qW-3<LC!^!z&kO~PCf|c<DzR^!5MR^<vA6_Pm0`Ja1~Y;_^N*x
zz9;DV55#oDFrR^AUIGVsesbJhCS9|*=18^E2j44EzH9L~t4kas<rC-7`p0<0+573V
zXntsit<3ASc*NJnrU#l4tZxmGWv%`Iu_O1bLhr(EdGMsAS_OD<-7Ji+OH#TZ0;S$I
ziE_DRPgPr!9<y21!B>WNy<{;y_M3cyO#~dy<PQnpgO`+59U_7Gt)UgSCN7I;t1m-C
zt+09&xyLiNpmjG0VqFgS<b*)e9eodu>-nvNgdEfuw_FGVDmKiE8c{{AT(25#z?6)}
zB1t@NA}zN{Rars*6By{TAXLd1u3Srtt62=DTppzbTqgSBTCR_J4mda04+KMFVRkUY
zssAv}?;PY`Rv#@|OTHZz&4HbxuG}C_4S~aGT?@3y6;S`{5P}+*`uixDf~D}7{VcDE
zY}!0`$@lpvPNkly3j37<m^WilR=xE}!xeB<0JJ-%GiuRWwD7PRR>DNuZT~_4KI9HY
zS;Sk+HeFL%zXm95(deNO+ucA|BZc?`JdNj+cm8?~5XwW@kvQx~%?Fx>QxScAn0Qbi
zen@+CN7cwY45fO7OOzMIsSg50*#sO{sRRIIo*de1ffot|8BPYVEs3FOHfBF)%ecoJ
z1)RV2r-pZl5y%OZ57x&c=G@0y0t5IVqZdN~XFY4_vLkK;oF4Mc7JkrL9ZDlkl(M`O
z-AGZOT92w)ieRQHBZoNL9HXWs>kRKz42#3jtHq4=JqRkm@T9zI1XQtd+^nZkqf==Z
zA8uSwx|U(Y=2CI8N3Z>Nf+kwO4Unl;A#3L54Q6`(x234NOmd8jfQ2AUR%(y&A6JWI
z1;C+?@t2N*Gnht+Q~k@uNh(^g!``T2hAI}5TsT@S=ysOO-EbR#FN8?1DD9bn4g6y?
zWNTFWiIcCX=H$G%^Dg}rH56NqFOcB1_X4rT<X71QIh3u)47tjjx`SOBo91zItyS_z
zPc5N(7VQ2Tez<ZNuJ9+g;W<yWYn`*I&1l7JFxVKr@+h(igoSHF$?w-JF>SR=rkBz)
z(Vh83z$#vaG>oqc7-P-LP!$&|M<JiObI)*8!B>(fDd)qlGUWJ4ZI`Q@vtmtYWptIU
zMa_T`wq|RwJszHpHH0mmCQx+gxc=h9!GEuTQoDEt+58|O8x=T43V`CdI34|lYi@re
z5xajvrapuRke3=4U<9_!?z<q<RI}%`UN~c@zH$l+Qm<DT%tX*0a2YwfxLvf|oLcNB
zyVNX%r`7v9>l7)xk_#Ylk><6Q@uyX7_+1RX6{TG>!Cnz)<^o6BP;uf{%^azp`G%>+
zsN(7*@Ys<(Huqw=%+PS8z}Z=)$BDzH%xQQ+nUuB~zHA%q<7Cc}7HJi?k=x3LK~I~m
z7lcAo8)3B7pHSJG*&71{+yzT<b<jWf`<{8rz_+Z!XjT9UZA#Lq71Z)lf-VO3^|Rn}
z2}%r#tHh1Rq+L>Vc*m-|HE&#T4!MN{5QA>GKkA`m`k%(B1y`^dCbL^`b%3A+^YHhk
zMZPr42{wO|9O4Fpox|Vm`mIibx<b~Ol|sg+o?g8Aa@_!K7#mrTpI)<ibun=(i#k4H
zsFY9$KC)c-{sljL0aH-NyOMr_@yfFMZGn^&WcpS_W#n^ZO`p56=Vc4M!LxTnu5tBA
zSNO!$vZU1ad0+#_c??Nir~9?XTSpQ!SY#i78F{rha>9@ae`;*j%=wS)>4yxK(opxD
z0G?qOfB*TT+M)b9l1d+qgQD}Jv+c5tq*X2wBeYqqWOa5yPoBw0+DKZ|;LcpY*&Fz%
zG3km%xy)CDdR`3sv8087pBzSA##hA^v6TtLVkh3QgpEdk>rq?6z!}ICzehHofGU!u
zeBB%=7fKJgLgIvJRt^N2=iP|{xrW!u9@i+PQtP^D1f;bWD%J{G7Lk4pkSr_J%xvCl
zV1)-bkwD=zLT+#I$J>HhHPnJn6k$5CWyNE$1XvS1P^XJkhIfEVZ}Z(nO1iX{H-L$}
z@d@dZO*~5czvl1Oj#5>thc6@*(Gs`d{c#^4Ex>nye2u*Bh%>IO*9nqAi6xST7nQfT
zO*#3>4a=5^u;+L<2?P+N+N5d$f=cGbJwv0<OGK;r6KX|%_kU~#&uRC{RTf?#w>JtC
zq&MvnX`uc8bVrhM01akDd{6-gE^)BT`EmaJ=7R<ufl0b5fgaewgGgg-%5J>|>xcwG
zg-RHdy6x?~_eKxA5tKtv!rfVa&}Vo|QX~l?Y<S1%-2g%#qoSbPNDgSda2=Wd#4VjK
zkgS+&{|*#lW&1`GP4?m~lfBv{huf5wV_4V4==k^N+o^g~dJ9=H))h>%Dh3UyU{D#l
zZwS+F{rZ@VcH!V8$e=UmDabq#qM5ZLe=jC#KyC)r<?@|`L*F*B85ENYB(#59&SBqe
zFD&&#+*jngnuNA3kIz;Q@pQHuZMpI<a`RuwZ=jXW@rMqpi^GWfY>rO8I=zxWFop37
z?M_U41J>+7Z!j5yfjwJf7M|oFA}5@-%HZKM*%!-j<8<U+W=-es8L}6vKOIf|+J)}j
z*a4-cPxB=($4ry^$G^&{WG!|I8m|*hR-3ZA6*s#F#)X=6Gc#j#+jzBT9lOZQ3vigz
zog-w$2u@X5cy+3x2iW&A*px;PeE`)N0njMK%OvSdu|gYIa~MYJf^JP>`eLpsqK^_S
z^tZBU>rVQk=hx_agQeo~D;;Uxln8iwxhYc4wg2S~a#Z6ZAG1mZHur>GEbfGLb~6!_
zfIG6JWlofW_9M?-2pa=`<7w;mlka|uBEG2E-2($1RV{$aalqvXPl6RDoD<8^A{@Kf
zd!%8yz$(ehdvEJ|zM=rhxVy;6XGa<Y>CZtJg4blWIqMgXL6%~ArL{QYiLCRheS4f5
zBcc~sl?!v@aHYYFv!54oY`vv@Zrff@O^hjH&Al~M->3o>v;lTfGEDmP3$P$bTwBmN
z+n{rH>4xm&LN+aQ(QyF(oDcC8(8wp@EgMANMIxrzNLvxTpwWzN_HH}iOzA-^D7@*E
zHD&URI-@=7mocSOFb7q6V7?3KOTcQ97H7iAcWnpjCk`NF>FOx%7z+IRfW?1=<emoe
zRvmd*Vf?!pQ3|bdBF{8=EMg`~<(rp5Wp4B_@wdm9USFbk*sMs~@X(iH?`JGu7==JW
z0eh9|HUJCZp$1FddbPQAmhJi7_x%>6NIEY3DVES#sxs9DH=<cOM=HLVIX1<Z`gz3b
z30?g8>-_;wOEfi0l|i3=F{jE+gRp=8=A!nI5mil`N)L3B@^IPa;^bFdESGcEn8ty7
zIvnhAI(qIMe_T2O!e1`N+=}tc9_mEMn0%AumS->*Eq;2sAAkjrnzzVcP}CeFy7oNP
z5xUo3(6)|#ghKw025+v;wsolv*Q&W)ldrd02XrN7*7vR(<lg1lL~k$3BS>747Bza^
zmO7=;TFhs!lPHE|E)m!z_1QD%5}=I&iX^5hyOlKU0-xA0nj_zA?e&~uMf;d*t}~21
zwY$rqV*3%)x~zPRnCGY9zV~?+^ky_amC<4K&NTt<C#>_M#k81RyA(J&bcRYWJRHnz
zgxikO*(Tb@@_Ore*_$&lbY9Q#tLW^jYksgumg~gy9w|He&z89wpxT?Dh1D*)(KW9d
z64$=eSiyBA#LT}tilJlj;aHN+RS%x)#l90bG_Euyuy?Kft}oPC|MTk0<nzQ$=*nsY
z%U%j&FZ_13z_E9I<EB)YSjnq2Rq`oGz@X~|wNgBU2RV1?;pj6vI||lTJBxsu?n5Ol
zCN+Tasg~?kb<pumD134<kkPIl(FMEBOvoG=k85s;1%nL+u)?)_R<`gykIkb^dI#mK
z6PtG|yZEc;(v1dJH4m@MsW~|Z7hDODmM8z2xNPs}WH(c&!(KE>?^Ecme&D|9GtoD7
zSe~-VGVC7+gdqZqBK2>izawW;uec~m0jU1PYFUG2$nS-q(+*tsRDfXHr1gXN#EO^A
zi#}v*$54^@p=_d*M+5tzq+rrzeqIZrXPi-5^R{sH7WBI|KluQJ`_5zd<6oI44>>bf
z)Y091Tsi=r4R=Sv1a1^}&F2(5SbKJ1N*m4vHk!G~!MWQJJxcq_$3pf#C3O&`zSR5Y
zp8PelV99ptU%svNmkgX<vUB~f(2AAe2@kdwVMPNvt6Ztxo8g?<{1|urtp=X%*p+-Y
zAfxmg;Hc^Jo6_)Fs22@rP8=z7-U!Qc>be0bL3Y>pzgs*7<EUIsJ~A2j*Hu)vp7gO3
zSqQVw;isnmY$-TE9i8BvD$|{j3Zf?F%)Su)r}G8g@ZDRWUZ{pS6dYDT<Bc2zwDSm9
z;TU&lk1$m>7!el<e6RiM0o&_j=M<&qMZPtnhb(m(t7~Z}rM|ISpA*RkI32&OS?IhB
zjmkZ5vD^!qkyZ&>(c6rqcr-hlvE04^hc|3afNYJTBzUjzicDg~Wf&l(8vwpzQJaEx
z=ZMebi!otc&th*{%V>nb6bLHps!2ObZ^bydj}aRRsZ*p~|Mcy$DChX=#yT#$GUSnB
zk)QVw@orh{i@IGHoShq-#i7U2)ZEq6E+Ul(HS2{(5p0+y!>r4uuBoP0-tOLSouhmF
z_%&?_@R<!4($1q!o%!U4fL6Rpi^&zHUi-S&bf)RMi-uZ<9IHGKvAvndH_B7i0p=>`
z>-LyVg7q(>kyNMlvyJT@Qui=#B)0o(cKQKkG_MH3mws~@f*X8y=?il5r*k6XV#rP2
zfX1Bvn?W;<(Ny5@Ffe+^w@3&Dz49ZRoCg5tS$`nL00cLZK`-5h?)g_jhGxjfFJtek
zep^R6OMkVJ@!K0tJtjie@?A+*iMsjl(g4A64-eDG=)cFHk<x_uNccvAv7WeA>!mKH
zz`lOe!s)Oi<L*2boXumNR5VJ@tq^tmP%wdD<+mem>~YKqTX^aa-8XqgEZY}U!3O~3
z$I=Dd;>Mb7QT^gA->cp-t_30Q#N8&+L$n_&jPpy}0*XB@h;7of>ahj%*alxmF^g<W
z#~|`7fL*(<NF1H5PyRrAFVb=_M^7c|h2rrP_hE2yV{0>e>vzI0kW|t?sg(?@Qs-EO
zX=u@?EC#X|^7@h4N?d&i;@MgcWNagquh_L)f9rCi2lsNfBtH_w@}G;+?9;+8Cjteq
zz_b`K*!;7oRe!s2?)5AVFsmkUo0WLznX+=zF1LSGnkqqiZ8b0B>T@Fy^=mtlI?6xc
znoGL4em*t`Y$UMEPv<T67O>o{yM>^DQ5ZL_ALO%x`@kal(5ynz&)y9;{M_c?V@wqX
z1@VW6ff!OHOcDY%ho$lb#)boajk-M4k`kAkV(?EhKK(MdZJIiRJ*A1&QgTV%I@<(S
zud9GGA3gE_1$wOa;qclL+mTMA5%>XYF+52?`(Ev$<XhVCi===~Xb&XrN$AL?5P*@^
zBzSFOg>N~V>>a75<7ut+#ykt63-i>Ii$v4mFzh_#FKJy_CTGA59FcPYgOYKpcn)f(
zuSqaXzmG*FvgTfJ2BGv2k+cARZC!2UDC*9ZeIDq*{$UY}i|34h(T!QSx;4?aWiyD0
zt3cAs;UQ1R!pSmZ=lUj6iip<(<^mkfr;|0mcOp`J_v#CcflJJmuJL;_kfvxKi~=hR
z%_UtYNd{IWaX2qatI|vpqt_RtBUQtIg9vL5^04X*lkX1tRxS5wQ7#`%ZHKB31Qs?Y
z!vvVUaYK9}MkLi7z^?0<VW@OKN=O<86LshX_?2{h-*ou4Hu!3T#wb9u>Hew3A66=>
z?vF-hV@`hs-}ra&=z2N-kfJnZ)>V4VtC_43w{4H8#0}NDCkt&7fC79s62?Vpy5~6P
zG<HoEi_|<9)AOByj2t;a5&Vv4vBx3*^7a?2-IDmLAWX8mfMKOmUD!$kd53;9H2Y}b
z)oLJf6*vW#JX4=>dT2H3S=dpBW5(y+)};Cl^Dkm&PU}T1d)zA8SCtg=uA+i+`N6lM
ziHB?#bK=mrK**9R%U-s~)LxW@N{YD=f!!ih;Yjpot|xX4^QeTs&c_t(rQAuylt|q+
z^jJf@#txpWR6Ohq+d8?&W|^`I2;4~vflD^4WdU-OWSX#xAbXz9jKI`22J8fVsxkzp
zJ_y4!?cOFcIwj+5@Sq7W>GJDTxq{MF!ODmEUS9!UEz48GeoiQCi-3H4OxMpfy|q=v
z%feh!VQZ(z{MjAULhzZtr;G-7zp^F976UvbzMp9Y43=gcS#gzf30j)pydwhGU$YQM
z4p9jJ<83BLT=0u%7UfZLvuH2sJzd;`U?iR+H_y4}#S#+96Ld)9_+x^kyR;II=>%-N
zJe^5dZmLHA(E&bSSZd%_OZ@0}r6e@lq#g@)NS}RgfE_;Q$LYTzN({CFiskhts=1Eu
zwX&aPq>-XQ%|RMZNt@D=2?yh1yJ$#r5rEVTja$Rxh~y8p&JW@rG}acV;n2gH?#Emb
zT_Zf;I0qg1t3nl!g(nno7?Ri*9-xElAxgmdJl+~$(lY}(8C2-`6^Nx=@JdVZ%BDwz
zwWFnj3VJM#H{1|piv~YWwSit3FXvP3(p!9I25V>M22Un<C*7MsQ%wmEEzygn5k%)f
zZ?a^UdMfS6*@dV%smX$Ypqzz|zNeKL6Qw-z%-AAc>bW*r(=>=7<W-|DFHL4AbbH`#
zh2Sz5VGyT%M0t=k{9za=KF%zJmLJ|-Z`JnVbq_l=0zbSkNIk3dmlryF2vZ4ui`F=4
z?b9?Fsvo}5US=DTFxj=)EE+MMlG$0I3f=xmytew~+&Tic>yJm_f$wkL^lol2*ADls
zCMrk^J*-A2&d`{SWDE5X_t9zGAD4vD+*HF7v|?$X;pja>=+WWjpEsA$kJLvx>CbDk
zEiNbMf|eKLXze2%DmA^Fi*0GUiSqW}y>p3`O*W>6md!)cvS8!FS7D9pa_1>JG0(`>
zVSy=$vY(KUzsQVFs9I!-y<~PVq^-VItp-KNFOKxg=rp6<LmRY|(FyosJ%kx8XT3Vh
z{;<da0s^tjZE3fF!Scagxh5Ase282p_RJF&x#E!)!;Pbo7dX3ngxiHXj7^=IH_9GX
zooi*+82sh4HG!;b6tW2FDTci0ZK)5n*5m6e14JQH@7-xt8$=LvU9t2?&b7k7@_MUk
zf;O3!c*ym6`wCa|hD?`%<-uoDPh}5gUO$ZVR4^@kv`pS=)G4_J!3p+V`j4Y#LnBRm
z%_v&%j>#+Qkyk%hJ0KxPKTqbUi!=3=C*RHus-;de=gS_;^{`+cYm3Fs1MF8?|1?i?
z=~-qd{^WN?TQ=I!P@h3%Rq)6R;i1kmco>q!n2l8X-AfaJ(7REYW|Eq}go#kR+(SDz
z-M<OomM)srjd4bhT0v?01CZyYO&hYvn!6#oSI+XN$Uv7Up|8cbySo81%srAA%Hu})
z@aJUS)b*R;<>|b*o8}SWjQN%iMcrK*cF}2poxP8HA}FQ(ziggG{NB5i2RSAR``g)7
zoU<TYGB^2m_3g}VZZ#<NoZu|`!eiTWZOci?qSCUp;<RAcu(pur9BtR7>nF*Pxy?YC
zgQZxHs!Y6G%cHTN7v?$7i{@wRN-R_@C#8W-9XB}^sUNWxf#uz>0fv3XL12x3VoaaU
z*5fF_tnlmYFVx#$`_q;K)5Ukl{S#5mH+N5nY0)vu<Ij*`k1+#tf;iv(dskN&6M4-}
zhEdp_wK8rQZBpf(e52SVM}S>ljBd)e+7a*Q`zMc?jo-qPJ?p+ztSu8%xhO}af<JYM
zOZgqNTJM@oOQjqTtaNYU*pK!LL&+AcNkT@ji+6uHv++{iTwd!(|6A0wt*X(cI!Y?O
z1EVsG|4+L8ma~sOV$>-0_2f9g(4qZnHYFj+>^nV@_UV>3p0pw4*$byD<uEI!7)bcD
z>z2;5#aF_E)6m8m15Tp#ak>B;0+m?z&s`i+=e2ia3>F+_QaUID8}Jw=1PlQFzyt6n
zSX~JnB0GBH)<`S*{-^)%l8dK}@Y!|Nx0pceu)IYhjAwv+CG@=Tj^q$m59ABbZUeJF
ze)qTN0>I~H@w`l|-#J+LxX3u!#Ce{dNPfUmatkcQ)=dTUfg0+f{&2os1ApWYLv@Y8
zo`d0L=aDQxNNimkkNifA$G^DG_BC`#JrY&`jVLv$LVMJgGagIe*(l=iA<9rY8H+5R
zgTHy{T`hI&h}0MA{Dq?jk9ad#RM+|e)BGgQvicyhz!kZW+);_BT6?K^f!{}OUvsbl
zzP8el)d}bzF{Rbghh4!+8~Zp7X}-)n*?>C^KAwB-Eiar0WsmX?xzw!#2uezhF#9T7
zHJv;=YafDzA%-gp)^63jUi}`gz{IPoaMY)*`F(+&j*qjm_l88q@H8I_5UYRty&F){
zq!)ZL70hm0lU%3l56xO<6w`;}@wS*P7o88g{q`re8(ylEe+Lu3NZf@yf+4;d+!v#_
z%I~rO2g_&(BxRW}x3JEnG><?|Q$-#xpuoJi(Dy?ED}yIa2EA_>UR29wf;hL5k>^7+
z*LrmZkwV;irIh7(xLH8=<L=@V;Qa14=8f9idHE6G88Nxx*{u&W&ORl!c?ilr&P;z%
zx>e^OD{j;LWiv}bd|3^+_n=wOEMq<8<$Jw0ghcJ5V$*chUaIH?kT-i0om*7`-df2d
zF*E!U4NpMnV9S&91B9`tnp<6BI53X{Nebh>kaZC$smjP$GKhn9gVn257C3s^zJ*7A
z2`XI`V4OC#J9vL6%)FK#AKDQ?U|#1Q`JM#^2$F)>EyBaz5$7w7WDtg}<-R&Xje^|g
z7!wdTFy^=5=DM7Zj7d9<?xLN?ZTwSre+8guStyM*TdOFs9uzJYtP$7TcSy>x!rg)b
z@+Fh>1gP-NJk4rW5`GC8XA@5*J@zK-Qb_AZ+QiE?JjJ2>8<_tODfYI??3OHU2M>|O
zmO1`SrLCQ@r@p~lryp$w(0#p9eveQ1Bqoo`K(9mK`j|i*w3qY^c-!b*A<e#E<}|rL
zt=@cbIC*k{W^YkB=x6yNvJ%iF@(%PmwyKhwc0#J6JM(IG=+hOAiR})2SX*9rFauA}
zsoTaPHc$Xrw(`8v)|wB>iZGO(=&th`D`s?#PK{q{LqL7mYzJSV_5pZZpVkYN&Ws+=
zPjDBrSQlYsD-o#pm6`!yi~;~SuP(k^&L{AqCI(@*`@#Z(fh}=G5!55Ea-#b1xjM+{
zo2pC7s9;jzdg)SFON$+Ug1^~5;sQjuL^4^ay;ohHg(}^*!Qa+j6K1AQY$K<5lw<DS
ze$@A7a9jz`3RTuBP@RdZ=0yH|JPWs~-%}zyINv?mk8xRHqQs+*`fx<E#HSI2{V}*7
z_XmlpvVC9V==;<;WWULG`@SIXFE*8Zc^JJF3y#S6*#wOV<y+4%qNPbB6!#D$phWS}
zh1<2@Ik;1GS#z=MG|I+8ExB~+aQNtI0|^I}vGWKqvGpzI+a*!n_rf_#{{Qh6YM}Lh
zu4xLy4dWZ?(+z*t*(P(y!1KAEE-}}MvWFo4?jA3m&5F;;(n4_e%L~&jBcyqieNNOX
zj+N7IgwAqqSnuvPRcVf%&`%ZyXAyqTQ{UHM;5}0X4n?XBbzfv>^R_ZtE|n+obTlj2
z9Hx4E7%7dyzYQ@iiR9LoWHk*<Iv#wR?W`)B_<f53fmq4tafsC$w-Zgq*PNDdVkpzw
zGF~r1$u_N8<Zz8ZBY~dX#|$0}>w8V}CEnd{sh`C(EOZv-XO*cv^ZJ;CQO<UL7rZ<h
zD?OvB-qb?-K#pHSk|>&|?bid4x0K*I?}4sf-H(dZ2dThiYvLMTI9&a&j^u=?@N&s+
zB!7_ZO+UZ)t^&bOewC8gBPK1~cusv^!=#0)WQnRzDVq`4W$qLqF-ukrgREHnx*mMd
zW`{SpOK+Y_SiV2DvyGzeu4e@t|4H9xdv^?{ML#(N{QBJp`Dq;|pnIr{(dfqOQs$hU
z#1^8W2j?5(wQ9W|s2a{g$#NsENmz7OueIvOt2ndN<@H%-7B<|uXP%bplk-=;ElYov
zR|)dkTI(5gFAz36AA6wmO{MRCi-;wJi<1fqQ&(<-B_=<+h6Ywh)sztZVU)4j3)H<-
zsX?fMA379Vxj|&1WWJzQfGbrg?B(H8P|TYFXfJva+#v|-0O4G=smN!CCh+cp?oY7U
zFJfMj9=xj~!z#TAHJ--<!8KDD@?bjz6)XRhZtWeO_3Q$)b&q7Wrhv${ory7I$R#SU
z7tRcGlLW?BRc#0PhTKoZHJ<o(6o>G7_VOr1QaZHeAM`J}^%AyLXCH0tG3ihK4Quye
zaK+0exp+?V%%SzOgm|W4v*jdND{6xYHH)Uq`KK45JNY=k2bKe&mgrN*{lnH-(HPXR
zW$k+0pmi4yvA#;zN;_P!`an#aCAIIbQQqan_ZyE4y}D)Y@|?RdYw>Fm=zvgur{(}w
z@Tq~7PZ<}r1?0@_vY2j<1Xuc!)WVX4d@Txq*QgL!EkYA7K<Rz>G)}ib^)MVte1CvD
zHaZtf_cvLk#4=j+9PKFgW^GZEg&GZHT^R}t4~DqP@SULiXY3^FY%#ii!&WpJJrI@n
zXq$S(5G;&vcWo7{A2PUdVO#uyk9_k-`oL*15`ak$QuhleE~Tmwo(E(?Tu~On#PFq-
zkv2%DM}6?nad^su_Xu+e<gVeHRU%DuEwij)S4WBl99M$A%iwhyQl&ozw}ExK>-BRY
zEraj5?lu3;a1bzeQdI+PAVu>UD6Q*$yoa$IP{g+TX8*j3w9-Y@9s(r?f|7)whpvn0
z?lVdW&`7>YURpfip=f^9y8AB4D~+H>w^X?56LKCh?xNc6>~R1jn`yKfa@n_m>dWaE
zTd6@C0ruP{PYy>XiWsqX9Ab8{2tP_&hy;{;YJ7fh>>3`Z+L69^ovXz8!e@OWolg`g
zW?yLx<Je&>%rSsM`_uT3iB~TCi}g!%D9cLMvCr%xFDN={L}9w7o~g(rrVf-X$h3#-
z*q^v+b~BcNKk1T|T+Z8mAtgx#d^yyO5L9(`Bhx`i7sMYM?Niz4wrgXm=Zq!eGqyG+
z&m@I`5c5JkgHCO9fDS5U9yP$<R|S+h#ldg@E0#OZ9`Gun*%CAUAnj8EAxuO<2sh^B
z{shS*;fw8@RZ%ceBoIZTdj>#wE+Y9!JJV-^)Qk4ycvr;^VnH)5`8NPYBMMBzuoy^K
z7C$0jN>dBQsm{#B3Z?}1DJ|>+<iZR?(BxTDjAK#^=<sP=Quz5y@g1Qh2d*HlbpC0v
zW_i}cLUVMaNFMB3@O+R7{bIxJf(W4&_HG(O+6a)=Xp)7AXerNz#Pm2$0YDJv)U4+a
zI%nfSrF`;}Tk&fl9gMCBxyWKF;`-)^DReTC)ffdGN7j>K8OJ^<Bq!1Q7rQc-yHsLg
zWHrj^;1>rAl5gNh_e=qTp4k8!ZtIy^Q^$3GIi~LtS~vsORvV3|>9W$;Z({shH-|=~
zY>Px{t-S65S&z(>ox|*AT17|uC76DAUYTc;AlK+9WY|Jc00Z`uun1jGdULo4)W>(w
z*Vv{9S`hmC<h?3aO9Hp(d&QJCc&wptnr~%NJJJ5d13=DV^6<F>MUt-+T<I8$sM)?8
z%m$RZbJiW<VC{I14)mevTE9fhlU=vyq8z7t3D-=UzvFUri`_F_dLSVDf4DQ{DE>n{
z14gtu%mbpc>EU<+N3}MAC;6V9bE;mi*(ImqwHmN6L1Mbk<MLj&BG{Kh9%nIcraYc*
zr^xid97><7XFUKd3d!zL>veH%LYIXIyiiN5Q-4m#y>EeATQsrF7D?93vDk#Vm31!^
zBW+S8rr!iaJ8=7jvP%-gQgUk?Wt(px1Iv1n69DCS&Oa_IOf^Ja>f9PId@lJkGWkYR
zhR9o=x0qZ=l*e9B$OOU#yitvd<Id>St1t!)y412B=>GeFrC<4FTm3$9x6(zHQuW1U
z`SYU-^5e4ROk$BGHu{uw3>c(f710+-K#KhdmXR$YcSbp1y<Wn3j{1y!B1$TmSxvLV
zY$%*8Bf{4+77j5J+R`)orTIcu*r#fTkl#-J3E67@5tYb7&q^wz>=mGbWTlU;eLd4>
z5et00@+uI0%5hV$H`2EH7A%G22=&qo;W6ue_<xFD6@p{b!rR_&=z4^m#Azl5=6TRP
zUtDC2p~V>;2ss6M;8bEhzRmcU-BM2i{Xi+J4N;d1;ztqCR*TSXPe+j^D$-RZXfzxa
z{a>KxGQedMJ~n_b=0kdp$K0&w7oRpGb7pEHDXA7f18Jxx<+(_7JtsWNl45L9@8oFx
zMa9?-+^*1Q=s11@w{#*reFrkpCkObUNr5z+Xjn{2M(Qw^i}9WnDT<Rx>4$lsb7VNq
zs!B;??gu?_HGT%6vp;69X_QGwXaGN{G#AIG9cJaleQSYK&A;Yshjrk&BiL+fEF{9i
z7acX@+FyfIO34SB4ES`*#I)t{`4cQJy-yfiW7Z#^omO7^d~YmlqRfhOV`0IQe4Sap
zMpUT1es-FX%i#o(AuUK32$b1E2a$l_kGS3KhDEyA_1@6@3cho0R)Hk`MWv-kOaA!y
zY!8BV<|?9Uk@+bld2`;btKLd~*eU8C-IUV6_i9}!aAn2vinx&uM~>YJ)K*k#=f|&P
z>w(JhWP~8iNkev65hc-Yd^XU;hT+j=c*Kfsbx)O$k<OCX=7#s}r5!?SRn*qS!OgLk
z+!8v?7ab<p_+>7p-wl1EndZ4^b=x-II@nLSCZIu#bt^T*89wzF77!3qM`+o6FjZ&N
zB0*L!RqB^shZyX0avk=H{qY<hgnuFI@K<&1_b+8ndfn76YxeSeW7H&b#U^Ap{s}PD
zq^dpj)uS(}Mxr5a6`S(i6)qCF;hNX9qrF4+C?*kq?*jH)TwLa836m_~dNTr%eQCX#
z*ch;Ly=Ew@z84EUm>(=Xl!H{I%xI-F`4YVK4onvuzwFDKDM?H$kq(~8kQH(UMS$ja
z?+^_(;0Zag9CaQo#IZ^+o~ys-O9X4U7`4*TjgYabN2D>VJ=*1!-yc{|MM(n}kDiby
zh`F1^%rGRz#F-<4t8}!hk<)o@6neTg^W;SjHciNsKAw;C^Ep_eNos4NFqY>v#*V}z
z^{X2j9Q(sOZqeZ40HcItrW(nr=&P%!axZYgls#nFI|f*hVF7Mr7j1VO#rRBi;5);K
zhTyZpU;1(TppS?Jv~K|fRwu(rs$eAGBT^`#+9STF?s7t5hBj2H-)l9l?I#wM+nb9*
z2tV<(LR7B_t4Bu)O~T2sk8h8tLR07ZvtJDa#xdU9eABKW8#<&CA2l7POPU|42mRmf
z_00|oVzk}a)sh-6Xk%d(zibb=ZdCvK($~FLtoy^CZ9I-uC39DW!a*o`d7QlMSH}^%
z>@C-3vIedF*jenw=eJ%hW`aBGnIx`pPDkmq8VgXFNY?v~iJI;&i+$RSAQ(s71|qw9
z|9z*&Um0VlU<DSukM6zMg+P34(Z8h2jtQzu%pB{IGviS>oFVBfIr$%(?Y2x74SB!u
zh<HBi@BoGrPl+Wh{9a;eBxp0VTh@Ti<ySeM5#qy^eX^+sE?u519?e`dp^`b7Y3`wq
z`JFLiw3jKf8`34d37>X&B&#-9MH3}bLuK9rpFx?E8e5)o_VYVUX`)Sk?LI8r8WVu;
z=efMLy}AO_{NkK<o2@6Z%nS{=Gn08aT&f?@q27Td0@@y=ox8y=a=JrJs?Keu5jX*Z
zda*LjH8s9?*jmvl?0gUw)A_qhGh|3k+uQLNlqPK(?vUW$CKhOZ<VL4=$T2upws`}L
z46o}X`R|0h`bjAwu5#-t;?0^R3hT3Q*T(N@qR@~5@Aqx(|Ce~Y904HF+8I+T$TvEn
z;mN2WCwEux$xjCr;EmvjMsJ)kPi?e#L-@P!w<xjyS-aL0!Xt>Yb(zlr;$w?Gr*6v7
z-<IHeN)MtmBVHZ!Vcpy>^Z{ZKZQ}PYy!3W0&r&k_j>Wq%b}An(lkK&YuXQ0GQ%1hn
ze(R5!0-6^a=pxwl)XAV<7}9`D?S?H4aCkcsuR)D9ZI&PaV)vr8Oi+nhCV}UZ6TtH@
zxv@S-O~BS1OH3iy7Q^`0uLtcd%Tq$PM2|5w9p~%*GEV0)n*$i`tVx!%&=zS0!-lVT
zicn$1`M7(#LIL`C*P99G_bKXk-@zyiKf1Hi3Nn2bOQhYeIS09Jk-N9vwoK3^<;yJP
z4uDK1m}hr0Gb~l}1wFEQJPx2Qn_TR^KCB&mYfxg3WqO@de&JvJ9#bf)`Ex;k%s}7*
z4r5Nj^=SGZ4cbpbI4rw61rh8j_YgP-H!|+UX#!oI*ERJM3W9HRWiLWe5BQ{mR?1u=
zC0ZroOo8|ZMo-=7UfJ}%ZrXC8lL)<)zF>eyan+gEA7Q|x>p(R$siU(mCL|LZFLiCP
zRt`j%;RZ^}=`ONu96}z+l<VeSGuSi?#v2bR;nN8|u&lin*nevpNQU#<d`7l&H<~H>
z_bvLgM8-j9Yd40Km`3;ulaUb@6a`2lr#y>O8h?)I=o5-BUcb5}bEV`0;oR`4bJtZ#
zdhsuSqO=<m)J~<=)8)d)V8|>ivJroyHK<<+lWLmkEv3pM`*ZWL>>Vv@*VWoT6-of5
z-3&}~%)R%|7F2$hi#q+qa(eexAigF!lojy$p?bp~KzAq4gtiHrEko8Y)Q>s<wbFX=
zy0&;vn7C$hHy>X3aqVk*{khVYp%2<cv<UW*_;-IllR+Wz$g~^b3tOK=%q$naJjgdX
zOW>iir20n<#E4xedaiMFO<na1tu0ilF*VsQz*?is-s`%oo7QE#E#c<K^!*tZ_R8dN
zB5gF3=Q&i$LNyVNf_@hax}}TPp5D)62K*0<ci+9IKOm&y+`U(U-b5O%$O^M?MGoJ%
z<4jy#=w{8SMbwgkA;zD@#EhU&&enJFwvKFA-Ahe@UUxK7-Lpgrio1;L&-(f-M`kL?
zc^?_(nQ!`95id~m4(*kC+thHPoGbh5k;$NEn|Y0Y@sFSGaWS!oIi$%6U_hN=v021;
z0z{>?t$bY%do!kYD`8MVutBEQ(G0Q~HF{&5CHX1~(vhnL#*|{|NAZbg7VCsPU0*{#
z{sc$i<@L%-V0i9YAXBj0^gA2TP?&fYq+n6taFv``zTHOH(g{1${s$KU?5?ISepvp`
zHf<F^!p6WiM_Y%w?V@h><n^7>6cVFXOleQgmHu0NJzo!DHOUm<s6QcRPFs!fy76Dc
zNGp_Ip)!HBl1#D5U;$1>`RY|=8g+E80AK+o1YkGFX^H^5sCfcmWAj+c$8Al*<fZPU
z`_^>k6upyFcjF+RiF0qA6`jl<?=Isv_R;_mH)i8~c9HC(*OV`L*xJMP?3x}vF$e?f
zD=(9gcqp}tUz{>?o7G5_ojk%+Ej?>@wdI7V;6GCsNM6pPcNz0X24%%LSH7HJriPXX
z(AAqR^2wav1zE~yS7@oaNjAwO`BBi@C>s=O>#M!?`Eqy1vT@$`eV0;eiF4ZsrM7@X
z{BQQg8oZCrk52@9FCjaqfX8_hJ!)zP32JHlbUBLab)7E3uO*u87fn7m@UVrAj1y{t
z*6|%U2Ej??C^0j>4IXRl8}tE#A{&XsKglbd_3U{2df_%2)1(B)CyabpLFS>FfL?Q+
zEYa3wa09SYh#!e=v}YQ<30)ZEW^xSCeFQrRg2eso5ymvI7swP8`+~hIF+A6a*Y;>q
z@IR*H&LFN>+cJinnl$C7KsHL!8q<h4x?3Y!em%sNJP=NmTe4x+g9mawy*pua&u$lc
zr2&b?9EeM|gQ3^!p_Na8GpBd;EsZixwc{c$IDSI9$i|DMFGh5^Y2q?E-X-=~<}?~J
zhDit_NxvAjm#Wt*erkH|pgo*Q8P-)~bxx5qP@YsM#0}{j7xLLF!zGG<8~Gpdsbiwa
zk;~hTW(PRDJ8cv~w`N$^78Jd73pqrr`FwvW&vOS6S3BNmca~qt*Kp$}0TDrC3l-Zh
zrbSbv6s-D}vc{1ur1-rNhw~<HsByx-g8X9tq2_ovs~ag*^!L-%DdLKMpb4ye?USg4
zFkT;0Q{<qX(_U)7>Q{Y|4GNHSN@I>#zCx;;+Vu2IBOFfgJqz{v?qBgm?5M9V@wp05
z6})THXeN>+cn)lJvU%f0PNFJQ*rQ|M4*or7?5|chIDF&Q*x1i6iI&Nm#Lrt5Bcx1U
zbz%WkOiP|01No{iqv`cc>40}nZWn=Nq}|c|OqT!;pA*KHda_#3b=?@#5#A^);TcWz
zP1PssNLEw7%afhnsfOo)&7ZVS8MtHwhO%SP(`Tbd3A79TwP<=mk0a^Ao6&&6Nsv?o
z+pECY4VQJq+9aulXC-()U7;IoKcobBv>d(ogo^oF60Dk8o5RJaMmU^Vjpefk0$gfz
zBXbN_OKT1!PItYR%79oX>te1J-bTK5neTd1IV{NU@+a53Q;P24Kt`8-SCj*agF=KS
z1I#z6gzOq>@qmgOt>yEFw6yo>7s}RPyB@%=W3ABNRjMSnQ!?toYi$|62uRE%(x4>Q
zVKUH)de)FT>V^5;u1GYYo$l5`LflbQ_e3ruZsx85%mGl?5R~d$g$GLP3qTrAl$()Z
zSRCStZ6y3bwAi*%sHHNKKExNaYfsKP_qM|DZPq6w<&>YTkPk=2Ltsf)ov$)=6N$J*
zb+pp6Ye{<$vQyq`rOiEQric6G&aqb>E@>%{DDs8OYHnVy??pCKivgkqi2i179NPgm
zqvD-j#ClJ~>;0oLYCtyTS}f!D%e5;Prxd&~LR4O%xL>Ry^8&x@8>FHam6y#t-mx<U
z0LVQDI40$Q!19YkA^oR|s&W=RkizK}>$EFCD?-(V5+!8_W?M$pXN0HXOrKbesgm+p
z20yOo?eg%usScPYW^7)N6KSzg{Wrbd!e%A~B{YM4)>!kd^4)K*-5JeWiw2jsI(d9)
zdJ37s+bdmKW_w61V@=>wI1+$GRST0K?A=h@)juD@|7jHR@16cw0d9p7b7HsH>@oC|
ztH!NmiieegqzXi(O*Q7bdjH_N!F{Ff-G<PU107Mw;s~{7jHCsb)fBedZo1qUUUDJ<
zw)FtYE5994G_Ts+)}bX((I3`OtwPL~KL!HbG$SM+^MQvzO6nqHKWQsWL-_4#Py0_w
zlo>J=*@d~BuFKh9VzNz>(ySxH0~WqMx7Y|f<^Q_9#GdL0h83K_(hag&z0{u&HS36W
z1lDX_bc|sQINLH&xHtbRT7#E|#7z-I!ofT1&Qmk!hA7(95yQ&E9=PE;2_8k=*um#)
zGu>qs8k_lrJ2dD07K3x$3F`pOxFI_wP}RsV(jH`V8J4y;TC+}QO6ASVJdCoXf`FmR
zeTgK4wj3XTT+%3+XQdteiCAl2Bub2_hlbBDM{17M1^^rYu$$3be(p@BVHjKQT3_hm
zB6`&-<p25C;!b~?$`tEQ<`;*bZzew1R)T4QGW*MUv8?w^JLvKLecw0rh+>OVAxY^e
z4=<ZRC6!KXniQvPbOr8HOJXGIN8R6>U*Jmcr@V<S2G}!=>{`q+kp=vy0Pp{>oQ)~W
zF~^3Sy)8Y_$uC^5-{&qkZHdvM_7pyfeZeF&5Jt{7Q>^VPag8_UlgjnG5AO}`<1Z@x
zq8|&kHpFDq(E=un>9BfFS%Ek1U7q_DGluMwPPUCbl^;DoLZIvsy^@}p=->K9cUO%4
zcNI{=1_bnG$WNNJ$IYT2Y@7#!DM1=-M}7DscDe=A(({&`K?bWg{&8D@42Lq97I189
z4wzWY1`?=&<9$tN{lbFb`wQtWDC0MK+!B^V6VC+_BiWt{gkvQ1S3BZA;i4P^NT4FQ
zqiFrQlL?dmI3?uzQp&;WTxnPbPx?^*FNPZbFfa4Xt-*6D@B#VlP#;mr>BdsdW9&`#
zk;2$w$%+;=+c#L6UL)2Wt;4}LiMA7|Fs{ZziX)~oihk<{jW*kpmNP$}wk9mV*l;5T
zxbOiwP<M=RZAe;hp&!L)F7b=0)~8sm<*rfTOag>x6xSc&AuyK4|4;=~7yyRCoax=&
zq*%#3VkiRSSwxhhrLlaKKodJJK3=gX@}0d$=WsyQqyd9z#j|xq@9}JXH5}0!E0EVe
z&r1#iV^TWk_D_~JdC=MnIwEHAnL87E0%nq=8;wnpV!#B)+f)$Le2?j7%K6O}gUx7K
ze0R?nPyGal;f9mCaA7_))pZA8K3_+J5$D|B$iLG(&IM4p4rN2Z%e-ObWWnF}s!dk4
zVxNm$<Kt$TYk!09!Hk$lZFn6mZjAPZ>Uk0^=@I%astIg8<}dUhXT8%g$vPsmqHy9}
zS3`QOeS(#cAWNRpf?&jVx9y+$M$NH@>$b@|Q4(}L$r0&Xzy*R%Mr-5gCUqE46Z#gb
zu;EO`Xc<G*Ku4|5{>-LXV9T9H!B3}J1W8^)*AZE;%Du91ZY(XMp`1|9*%{M&zgF~D
zN)yA6Q*TSCjyPU{OUsb+p@s8X*vKddtDPOz1a8yU>}T;YLVk<2HeU7BV~PqhV$2JT
zv>&_CPu^lrab#07*mxx9NqAb&KB{Q-4n{Lfl;7@to6^@}CuS!&%5<dd!%{a!;H-4d
zkiUt@Q|zTlWZ!qH*bu?KK{1?QHvP))6+OjIkZLK*<ng2QY{Bo5lUT-3sIBr;4>QEx
zW371lVp>@9-!+PXwvcX0(Cn1aP|fGW-?}*`Zami%w#e|iSX@nDmKTM8APq6D3i$}*
zhN<`OG4TuLaur9cWh1#n0C-bd%GK~>^;TgD3YslSKJ%g<dv7fE?&;*i=pqRe>OY08
z;KjLN7-R@Tv~K33v-RrZJgr`s<tY9{?CI4&(=C^Rx@CA0k$_tZ<upk&uMGA3dKlJj
z?Pgd&W65Oh2u9AbZuE(ntouarN8Q-}ID6&1(eV;iTqr2tc|hbvOwDtl6o@~PKV)Rf
zZjtg2_og+4Ae{3pMiX7M;kA;No70c@jcxi;ulJ5Hi*S(`*J$(4Y;O-b{B*Oy<F;%r
zDki0i87b&W(PFjI5(3*8Q*Nl{b#dDn?D#u~w^FNMcq8Nku0Dizf1;<~gqU`?PQt9C
zWkLAY6s8C4ilRX-ScYHIEnr!AjT>3YUnk$6juR2Hv2&I1Nd4ZJ+qb(Ca?Fz3W;FS+
zwkWqD(`3Av2@^UlnDH~rH|~=4oH?C+?>EPpttNlB^ty#P*)JC;m^Uk=xESr8;C|q`
zUf8LONiQeAEH>_F3!+nt@f1aq>-e)jiGy}U`2jgP+xMZ*n;+h*;)^f;4~e@W<WI32
z(-H4CzT+2o?o2#>5oLvp2?)s6v-UligBN2aP}V~WcD+F!^894kz~`4K!K$I{X_ZQN
zzd^E_0>391|5prKWJ@hkI#PcQKDCcfr0Z^V&Q}{&|GKcJbV2z}n@F0^*^23I{?6)F
zoZ+R%smKp>^qduYjIn8QnS0M_r3y~@j4=1MsU+bNyQ2p@?R|w?Ra@8ZT69T=f`oK;
zhajbNmvlF5x*G)P5Cj1UDV6SSk&;vpln@X}X=%6%&Vh5D@4nyt2kyIg)}FsT<``p+
z`I}>oJ$arD>&dGaSqHz&O6M<o@39ScEG6-kjDERHJqy=c&njDsCYMn9C{jJ}hKz!r
z^{zU}!G_s+LC)|J)vRh?kec8f1i`2EE&dr|Y?nBSBlmIoh22o4YUN175(~e!-l4!E
zIkCi#-VbHxoA&a?7t~nfjyszgMLqU-%CBXinW+KGXDM^!xX+jSX@rDD6*Z15q<cy~
zou?(54Kvo@<*$^sEoyo#^y0C&6a6~pMAhAqO=E^`MaPdC1W$SzaCiDjSR3qoZR+WA
zaCj!0?yD2*e5jkOI(u`-3yPhedbr?dzS7(eY-s*LwM<j6@_2n)v$TsYi{tb@2AA9R
z(cI$;>Qk2X$1UW+wK0puqG_zrdE34_X*=@$ALJ`Fn*_8|%r1j)2I?AQE_E!$^SqnK
zdxhn-U-LrzA&4U0OUY|At5koN7)}|k!|-Up-^s>9lLdvzhx}<l=mpM658D<gCpMuL
z!pEA`>Ql|lipO^+NDDY0=9KDaQFyK_p3)uGv)gDt8$aNX>cxstTwvcfcNDg|le0Z%
z;#N+tb8w<IzOo=(v!c@!N+Y=~!a6%{|0;wJp18xuy<--hHHa$vYYwltzy0^Tx!+x-
z<vPa3LMUvmtNUuZVWkgLG^2-tQ&X`b1108-sVKO|8c1X}6A+bi4*t*&8EFqH?mNQQ
zDzeFKRa{m)vwvm(UZ|s^v1ux_{)L@td6C)s%pV;YjzAp!mv3Ij=J4))6$=aYTx~~N
z-!mLKf6Jw=DXY!NxYdkW9~YmCmn$;e<Ez&SUi@OPAg>SJU-XOcDC<^;%81`GOj6ci
zh~xn>?Tu#m=g0FGeL_H$B<bR$OO)qMKkM5o@`GrnmEPy_*2TB#b=7n)<S~+Um(?K(
z2M1J?5dA7ap2EzZIk`6wZcVs`E%y1P=aIsUqg75x_4n9k@;*UlonG%J&+rp;H+Jot
zVbjbNEK*)+Xvbvr9vj0+pH9>XPn)-E&A0IPyc6;VBB=UA!_yk{kDMQ8=VXJad?g^d
zsxDhPvxB1es;nlBWqO#}5c8Pmw-W$GC5!pXt4IeAEGb)JAB(q$YuRP|jR~Ka4-~z3
z5jqPItshLDbaJ#@aAM6pT8h;#GDe{(e-lM6Xl)nZUND`q&ssH>f4oM(8N!g==rox%
z@a)Nf?s%RmP;l7b*`RE4H)YF)KF2eF^|QP|%n2N=nO{n|f9TJ$*QWzIM^Q_I0;GM%
z+8qHuB2n}E_4D3K?0~_f(c#G`q940AEZPzS_JY~$Y={ZfY9t=dNLSRw$JvOsQ=5_E
z8?nwc{TXxWZyz~|tER`@7x>MEm2^gtOB=HFsf~Ef6~pr-%Yx5EGrOR?#0c!f7YS33
z!cxlVk%42|ui9gux#X?W`VCAptOxB!zV~yN&F<oNt@X_<Gv#|YkeB(gtoXNSv2fZi
z@|y2*#-`?ol<*tdWAPr#)$6FhNxUc!!dF1+%9U1jH*?>&`#4?3o%WLHg7k29A$p$0
zVN$xh<n@53wCx9uUj`di2aAnMqOO}#>x9V(tcrO49G`8N9xCn^H&mPFZj3rZ|D<q{
zS@>7#(_Oxdc7k$`!2zBR3pkv(C>a?%LT{#Y1%xA=&;#*3kL>+1x(eRi8-C~_V#r@I
zncKV)NFRoT2RA@0+f(_>gl&3HF&gRT;hHSRGzo5bVX`0c0B%3~lTV+};_&Q1Z7T&N
zKJSU(!ngoRY>!{L^^rS$W6Yl;x!67Y=?UrlYJ>(dPAk97sH6l=H2Rewpm`Ml=Lg6>
zS&6~@9LR@4wN&3XM0YWP0@CcEk3zosJF&DEJq6`G;*Fc@2JW3BfivTKzyZky>+ZJ!
zo+C@H4x-rMzJj>jqr<kc`jU=G+PumjZRGt-gOIZ1qPYMf?co()Qxmeo1ejXH*D*%f
z(N6)rt)06bE0ga{zt4>(k=Jc@TJ(Oa+jLwEC`Fy|@bqk5LmA4k8+;IOU+933pxxor
zp?~fL${9sA;xJ8sYcXaSt&grYGSSw4a>84ly<c52y)VsQyW&)4kc*j(o4AFw1Y5ku
zmgv0a?!0l|>k*TOENypM<LU$}iQq-_$D~jff+QoVgD%f`=l3n^F{!74`?4RVGrdk>
zU2!DxXaZubR+K+L(GJDc#3^Bo0meF%Gg0WDpYM(FoUr-6U4E#Y>C)dMT*5dzQG*{o
zxj>yN*v{^fgq5D+Q2kj?Wg3w-lp@w)j92}Vx7zu{ScxZ$#;e!Pd8Z?AyXT1O>u+s-
z#)=oA!sCc9=ShW)Vw7O%kv>~%c%Coo4(5>~!g$XR+r?*<XPdoJ69f!caR{*;(-mx*
z0{49BL@W(H0c%^^#}C~WAI~Zs$Pp6WFOA%rOtWBGCgib6*dlvEp1Yba$|v*`Pu1i%
z>-TRzwG|o_8WXjNcerv?M*~dy3<Hik9>t_sk@|S}#~b>rKVBDN*#DNZ<;CXe;6+K`
z^}sG4Rq46qa$Jc#Hw>B48>@%@7nVK9*AAzbR_e1yAcH>ZvX!^9uY0&voI+{pp(`Ml
z^o{Eq_G^j+WB7M=g^DAvqZoIAquzo!SF&nDzUnRddWJPudHjz#t&IhAmXi?~Q%bFR
zeg?7oD_XV3AypA!(&WQ$k_=ZU1}Wr@(MI-@9{4J?6CaR@-6bnHm9l$VX?mK`!B<8w
zv7Kf^EEi0r_?>3Hc3AGXV#@WAi&Jz4>sHUET(zRw;``CCg+1GGvKJKZCu={QD=hNS
zv<<`NFxBl6nuGp)KzsI@Y_Rw#V<fY=%|jpV9prFP*q2(BRcbAjr~?#qLu8`49&${d
zeQp%RR<E#{WSIpo)`yaG=jSv*!zYJa&~pNgMS9$E%!ZOrS}^=o;0g;p&49k1RA<`n
zu@oYXuKn3Y6K~79PrZ0P+J8%BAhi)&&fNIZcgjEEaCpD7tw)i<^QT^^F2L9xVlmW0
z>QA@%`Q&lYIS<S5q~f%D%PYTEi=?Nf_M$N!G<<19TyzW$8KtjF{An{@hRDj1*Otn)
zX{2V84r#%a5NyzqxHz^OZ<*<>k}}6^*?lwgl=b4O4-}Q)wL&j8JVzXl{1p)4V{e%<
zh(6&N{YA&h6s{C$BuQzM`da{lRFBygsRWpW<xK3UR%=t-*;!Eu{`*W^K5Fj9G0io`
zKlF4tSd9-e9F&w*AMMm8ReyCB#lXbr@NoG#`-onyMIizs_km<C71k!7&76d#Gt0v{
z*}SI0!4bX;`d_~v$MYWj{+im3`nd8!_aIq_Z2d6&rJ~WQ?$YWnyNa{=6l32)3<N`t
zp#Y-CKW6KSl63CD4%~S8F`2NpUKniZG%*jw8VEByk00tEnIE_#=&#t0s>nl|%cQ!_
zVHD@EiyShcM<~zssv!mE_eOe$yLW!<<5f4`1|MB&Wa0DPHlde?^6x87-k^T$c!9>X
zi=QKtR>^Scg!*}(pFB!}|A%2{!1@BR?Xu^QoJ@eT`X9L<1TQS%pM^8Yc3%mRGp2aM
zwaxNbpV^!oa8gnjsswWwCB7;9kY)LeethzSmL)eqPwRH+eEI{d6@i~iXx@&3a?il2
z{ImgnRosQl6he-bS)E$2OhLEDh%NpL3H`kFXNk(k+g|P%t<^vsdB1q9BVYRTGJ><I
zz9*ra0X(3<PrFXnU=;LYz6Ryo(KBXWAn3R0LbWM1C5aIZaE^>ar02a^goBG2{2;)U
zi(Ke}{B92wdw<c({-<7gtbp%Ui~&^{x}*F%4tge(6r550`okb+<RF|z{EVkuO_tqv
znsfUNLa@23&0T{64MX(kncNO`aigMmb?~g8;|D&{V~imntLy(+=r3DoNg(^aZpj4W
zUB@Go4+Z&YNenRQ;^T=}(U{rIa=)b7!L<--cKfW<UZ4sG^VyDT@Ihk8osUDP!uOAj
zwT+Hk-4HMcfPe}j{mmu!0q}Wl>s!*294V=UDp!XUEm<|N*!dedQ$_D@4_iaM<QL2+
zPaVppc1k=KR75e~ez&(+(XaAX!&flc_3^>&#>-YksNqg*1Q1n<v<{dhmRG_OQZuOX
z<6J^JJkDc(ty&^9k`*r<n||N(XIR}rlim^5$IGNEN;!;fnS6lsL}cM$?=W}cF(Go`
z>;8lBxMmW$mQ;2-2ZSMhM)v04V!1V74{E?bPqxh#zrdmK)9FR#gPE6-{)w)%OQp;1
zB5t|wJ01_~+WKR;377{LBwi-bHdI~wblmo6Nw<?hk1)5e&n}yj>3*{whY%hexVfRj
zr&Cd+4KG$xf{;NJcVW)iwT10wfrR?ozwe70#o6&)2}!DWbLO1*bh!1RN?Ibx%lfAF
zxzXput1$yq2wxmxnnkE<&4^voMULaz*`BpimlvgmV!dUhjG)0&*;SfGNxf?&tid#S
zKk3J1H18LCLev;I_47Vq@jW{dG5mDw2lJQ`yo-n9rrp^u_hXb*-v&;n9L8+$MXWb@
zzY>kK#DT||?r+!jCUWXO^Dcd^Je=n`X0vm5wPb`?A&Lf}<Md3=1VM>+{db<-2M+S%
zSL!oy#vaH$13s71cWG5Z8J)nKccda41Bi&2%GrNh=2uuK!a2xsZI$0<HXKM{#?2|H
zJmwE-6@2<8iscS*FqWp1Y(U?`p~oFlDLv()fb&*E|FCiQ$2@!fx2JniXp4DZ9|95$
zd*k-_CYj~VGc&3QT^Z_Zdx863a9vW-C#ra>Ys6D^pQuQU{t~Y{Q>fVHl#guT#pNjF
zr%&w1DQOy;n6!E+Cas^{)Ey`PVmj$muQ%Z0)N@9$fNG)pbx4fz!w^)>1e1vb`><pk
zNdrRSA+<qq*rvGR$T4>Tp}~Vci#SJQpLQe)vQ#a1?et8#H1Gai{isPsuJej!wg&Hx
zw}qni64vsgi5F~99bA<u1m5#uo%GhE1kor|DhhOA+cob!dPf|%lBWiLMRSn1`da19
zDf6Jbm-*$xuzT_}f5WERsX<cnk7f5!6khxTBtt3$lZ#2iQ&exNymSh7bPQYe=<4xt
z`WCV2mJ+J_lF%3YqsTSgrzZfPGh;RA8I{eW+aAcre8%r;;Fn-DjMI}m>cFT#!$DGB
zC_If)uedM8FRMprR*qikJBv&HjK^B)iN3$L)JjA*U_qwvtqq&%l|*kIY}l~UBTnwR
zY76zY;>u3T%F&>%+aps8rDL0_9QK~|(mq#`C92uOObcqN+X+aL<doJJyDXa~9vp14
zapucT^J<zS;hh9(8vRva7QMStAYznrCejo3vQ)-I3#9h?=GZSG<bDsH6+R^|dWj+{
zFT_Vw9xmZMkH*w|ncX<}#?-m48=z${WP4GM-g!xHXy+VIZdYRaIb~t$S!7n2pE6A$
zuFTFLx=Rxtjc3yQXLHqx4`o)&BgM<W!Xv>yXtl}SUX?~(WF@INc_Dd7-gk(`Er!(t
znHA9FHAN8ii-^})YGpPqi)0D5Ho!-(`>L_N8!+PUsrRL!;&+%|QjW6vKG>RNO2O`~
zqStr0!2jee#`GmnyKkc#srxv@$9D`9&U}lP`&;)I5p~i<m5j%RC*dP}&GRplBgzk?
z*IjmtKY3>&#c#7!<~^6NFRJ;mJJcuh5pl1r%IIWZfuKC8DRFKRT+H)L*PBkG<Igvp
ze7mg9Fn%71<E$}fl`kXm*r-(lHqNZex%iV<8Q&bnsgS-@*=Oduw)jHr(WvzU$$5U}
z=D?iuuD+osLpt+0P6_DG=;Dbunuw$sQNHq**%3a0Cx1}dYHN#vRZl{#D?O7&g^YY8
zgmL889RE!b{v%(}Q%RYNQV)@)CE0ky&@6HV^QhNdy_@!@Euu8s#dtNe`NOB)gXm7^
zl-%9!7H`QgU*mOnbj}(6S@>qQp!!FpPx<G|nCNBCpD4&4(^{AMs0&3t6Z<Nf#<G-k
zT%n;JOV#B(TgA4B!1R5sSOKok)7~TeMB11~Ta{ky(FaYW;K<Q>L5x^5DgJkrtalts
zdbBS*6F6aZK9f7bvHABGs53Mwo0%fMi5+%*XSjsEKW9d!H^$+y?k>2|E@X7rhiou-
zsb;Ws=g$v0oH}HUkko*ocI_-D-DmH9xV-S+nWkUlanch*y^mwJZk_vDxcQsw>y9j~
zo-?ag#aX&5ZIuyctG<i~<t^32Y`uzfS$8DC$WnMoTk=6VQtfB~9?eh>0auaP^H6Rp
z&3hEB=G5<B_w9Fir#2j~3Gg#+H(grl%n`+P5Daa^Yl&`rtgKJP7pIL57(uU77j<$h
z)fSujLThcf0t+XoD7SC*hH0%_M7%L*_2)5ID8nq5TQ<`qNPp=YT^hKaU4@K=q5be8
zf>th)hh)^to-Dd5`F?6yd{I17a+cWeGUC~;vCRCtr>BW~a`~`wr|O+Q(L1Zz9Pafq
zzG13pg<tWD1IvHCT!qtV$oaKB>(9parE}fWuW6}0A&9%{okEO3M=*=8Cb>m(5CRMK
znau>u>0R7dL-SPN+mR@pivp4AV;mBxmz1HM%dV8^8ZI(uycG*QhhH6rdfaT6nFIrX
zdiQ}R$<4m7Ccnaa{^yhIcml<i*n7wy`xLkQeSb=6cWSJTH1XB*^kH>mo(h?Vd9YB{
zN}-s(x{Muh3H)WDm-zO)tIAm~rad^nR%PC`x$Sr-^1ce&tZ+&Z*5;5d;zKX;Q9!r7
zD-z@B*pYN@Tw2;A&|FWcc6-~TzbmKGaEJ9EW66BCA>~if9HpmYkSe1qQ;lmf+*!#%
zvRcibM`V_yTyBaiVQWO9Z*a*UZu*aDCWy8@#(c@}n56tY*YmKFv6_~C7TPUO^TMxN
zpHZ+Zp2%!w+GVy_8e@`nO9gYx04Er1?Y8W{eMNRPI!PU2c1?)|J-A-3`W?0&ADz?t
z@_kGANlxF>YttRTO)MUW=huCC9w=rYL7gN_&{26n=DIWJaZgD0K+<lp(g3yjD?1&q
z##1a<N^0l(szzI=F_vC<oKI^Y%2YSQIe6WDZM&ghe6njY`)Bsy^NlsZKR|cTOX{*8
zGdSdGx?i?-Mi?&jHZy<l%Yfb=G-8Mj7Kkio2Y6=`g;<uNX>n6i@x*x_@=3Fn=J`KI
z8_47*k3&ybO8YG@a_Eb(`K)k`;aSst8Q{)qy7UZ@FMHLWdX>u_R^y+~>Nuq=Z=gM2
zLX&cH85YM7>We}wloK^WpP5k@UFtG=Dz~QfGVAWXJQeFjzw7*w8eDj8*DJmigr32f
z-8*L_3+mV<nZ1K<(Uw)?{k!1`1oG#-rChWoQRku;Vna_R$LDaJ%Ll>`7cmXXU*=`J
zGT^FZj{DP9Mx`_yZUM_+su29m!q{zep%NAol+T+6ql<Iozuz`BB<#29^8o|R*?m?W
z4>$OETQ70V*;K!LN#CPsmrAaz&%J%DSaZV&49D=iO@)rzxX6RYy`pn_Y5Nm}U;UD-
zF9p2tV#2yk5)X?e682c!V#Bi@8)3XDrlyL@T=m@b(dfHKoi7UDO#0-si(P17=Q(-j
z5+k$EyR+_HwBApWav?<Vx4(?@J71D0Q?M$bolnEB>s6M0I^>-ti9&TS|I?Kbqx}4Q
z<E(vhsWQy}0&kK>()4SmN(JuvT~Edw{=p*meWy0NLBgz>lqy_wVGQ%=yDV>v4Ywl#
z%{T-LKMOp5O_`+pS*7A0-RDy+nAl>A%}PxJ9oGdF{l5FpPo*65HYd)V$|qqe9lvF$
z2%m2zV+zH_Nl`Q~rd2JTglpQK3w+$rWRt0)l;n%)LBpo23m<AcmwJ1^F?5%mT;MtM
zEV9j7rZ=UUz9epN2G+eItjTJM%^q2k#mjHO11sPC&s0C?lz)&EU``!>e=Cqx9bL$M
zwjuqwB~xgBk4gBVXdq8p3E37?GvA!mJ|Q8ANK17u<j0(Y1oPCB>R2~XU-Fvs$4fQ_
zS(6*k*Zx=JJcXx&KNVFr5?x?p5*zu6Y*)NVC1UHWN)A<h<bJ8O^3;7ItKa3VZ@Nsn
zB8`n7wE@S%e2jt#n0ANkVd2A{c2FWqf~QHPb|<qj>1Am-{f*51J&Ph%9zPs2>}gty
zJYtgT;<FzHe;xA4WC%5lt^H8)Voz)+Fyv^+et!|w7SA3j;r=YV7E>#;QeOOInL)u4
z!OkQfo05P!+Iyu3{bg`}UiY%w+7-$$@D~gZ1vs**!PtXImTW_V1+*{1R_}Ks54UI)
zv6yJ0%}FeD8Vm8)!<#9&hyPIOkNXff2-LxuDyCg-Oda=*s?qxC3jR!B6&7*r=9Jcd
z`t_5nBtNeu`{)BnOooPyToE_wu2NrI`Q7d5?A9H#6;q)uVSE-JbeiQ>wg5a1xv}1i
z$&RED`3gb5J)exu>Vluh8w*`#ewzh7U&BtTBNymn$<5wEPrT({1Xh>KOYv(_xvKQK
zi(<KQ*2u_JyE8oe=3IU%fBlJdXKwWM9}NyeWpqv?HF&GZSIkRa52<1{r}KxCBoD^)
zXZ-Gs4l>vxxQ1HTHYleAaa$M_R_(VwH4-~y;LxNi<iKm?ij;mlY<%w$DJZnEQ`l!Y
z%rn=&WOOsFOcV=AGiKkcncy;4WBML}{)+S0ke4powy6*KekFbpeixAO(B#LPh1kXr
z*$)F<=}8ak0QVidgv_{pzp@c~G@lojR>A(g_Vq=xkyX@X8=2CRe=wgMWWt=SQlq8m
zBK1kw?;pjs3r5@8!xrz|PmX?Ga(IY4k$4AJ(0TRKYFxb^_5C*0^GN#A*!Rb_CJ!TO
z7O9<Ff41TK8`?WN)V_tCJIo%8Kb_S)QLK>9rlnS|U}e}ORYX@}P5tzy-2hcxjBRge
zCoVpaVjdWcvwGq;I9Ye5xn}hq6ig|L-<6RVQg}DFyD@?Qj7Dv>GcvgDql~21>||hd
zbik3hJS!LStWH=-_WHPbtp9oIb=tw5Mbl!Z>bkH%w9Kf_d&*CU67*J1DaI_z{5xZ~
zf?*$9@8PU;rcfAn@GgfKea>LTGI$y43nJmH{Yic{5F?^mz4cwcBq`htZV`!?a&M-k
zYhpirNoy2y-I%hHW3MxlX5icFlOP15N}bM0l?3@TC%b3!>L*h(Ok9(47OywL<_xz2
zikL33Xr4rn%|_Qw*|9(D71hvcaVGQ}q;`s=$dJ)52#(aZZX^~Nd~n7+22(?~G|r+l
zj14z_A*xJ`nbhSX6BmMnnvWzx;66niDTZvx=7!qFen?GA5sYbMI*ZaTy|nTHbN369
z!AXPvioM1?Ig%GuIF9%{ZxpL5^J?MkuqXdiq(m~`jhpA}`$=*7O6CGrq|U-X%0MlL
z@NLY7Duo~+edzcv93o9Dj``UqKh#YOXrU*8eVlP+EwN^%oTm}OY5Gpu1NZdU2f-Ws
zUNE~&c!sLcSK`B|ml<v!((+q_Q$&}Fy_U-TXRhDfC;aw&X*)j%Dmt*A#5|Yh_>E^j
za)&~VlzHLXDmAMmM&S0Ic>OxF7?Fs<c%#k-o-Z9AI#~G7reZxSIMs4DcnOi7*wIT@
zIul_=5aT1L^;L3{!K~Vdsx8*<;_oMrx6Qbo3Y_CD=5CYymO`wm{U*9oB^bDi^YQz+
z)(@hAK8e89PimnH(mA=7czg>qOtw<LBC>E3c0)0-bB0jI7(4mUE5EB=nv+%z>jiPW
zbK-YIj6+cy2*lb@H+_oc95}v5cTYB<<JIR4>3Pr7R@Qqc7`79YDpL<v=R#muo?8JX
ze>O_h9-v@jiT=z%SQkaH17H}>K7vN(cIWThICr(;5m-wuHXkqXhRmHz#aPa~RUSVp
zG>cFrirT`K_idzPxmf(F$WrtD4bs4#Y=vM*GTf9>Rxhq&xDfs1SXe?ZT9!wfw3l0F
zX@8JORn?rZ$F5tpN!gauZ<s?brgw{QF{u?r*4iMlfSjExY$H=RVf@V~@jHtH8tWR~
z$Yg(H2H9ru9q%EGDvA|ZMo>G;9$kMX>E6@oB^TZMm)wO)$(Rz4GqUYKj(e)wTo;W~
zr(PF@MR}5m@A-|V2dUMbp|hXc+IJ~dzM91L-3ugZb+wOxX($p)%1Twvcz!$0!#EX<
zlsCAix*I7OCf+-qaMAk?%TG!fYvZHe;jC#bKfk=;gZ3b=__<!Z)IvoV_p=4Nx~hXm
z8Fe#Qd)AH1jl^n9#E80Uo(9z4!WfwZ=NZY6OK|<SE*MDie%IaeJkJw?AJx&W>`kF_
z{8^{bY413pxq5ztE`aFiK^1XQZrE#%(fisiX%ayEZ9=nGpTc5Bi&*;R4x&$a%%YtS
zw)XenZyHM!ET8FkQVH}YbG}DwXrjQ7mTjaMWCp)}V$LJ%9rl<scJ#A*(l5RiG%hP)
z^x^BViks!T<{?`w*(3GwJnJ%xW~QuFYVjJvrF_1jLItP6=pW6NlpN2&h^JHOkq?jO
zd&BTYR_yet;fv^GgP!*dS|AQQm+3Wmo~Tc1^v5r=sG_SNmH5jF<CA5_W;{mmH@R8r
z9SxG{zm3hchegb^c8T<<6F;S}M`bFEy%VeH#!c#r$m1ZCw)MvC`{Yj=QXgI!<?dBj
z5_&RCu&Rtei|Rj_&dHw<-o}U`5&TMZfZF6|b{t|-_4^$$2ixT%PlD<ev0$#&?>*xw
zs5I*d^FPR0H(eNIIlET!bTgdJQa->3zi)1=X=7l!<56m_?cG>5FOyQ^*uXodv-X@R
z@W(3g<u^)6c0^movd!kl?6D!l)p`_IpW|^>p0i-dtq1t=H7KA09aI7o#jq+xrA^VQ
z#752K`U0m%rk9;Vch~+D|8Z0Imx<4F^iR<SS4?K{&CU<8t=_@Arl32`EY8g}?ku=`
zqlw%8twb&0>qy`eH@c?!M<D&Q+LbN#K+f1RSg2HcTwAyc2{Vv==kQ!yATMOKidjz+
zC06Yt!|VJP9hEKNV)A3&q2+2i?qYzHwv4nLIshmr0E_?tpa6G3EC3EdNYMQb#J<Lu
z5H1IC0eGkdp&tMw1`w|?0JMT6x3~wS|62$00CHU0B13vZAm=s4hwua_eCu-!6bBIg
z@&gBe693?E>l+LlMbO+}G+sy-cm#vlnFH3!R*nwl6dYU>%Fd2g;wR7zMfO+A!OzOY
z$_W6R?3_G;>|BBz+!P$_f;?P;T-^WD@<H&coA}`(gEMb&Vg%(sbBUn)8~Xu3JOEtH
z34xuHi!&bnW?pcw;t_6fY5ZTjL3(hV@i^D=E8HKCdyB^sK>+QqnBk@q;cmxWNQA$Y
zuO%Yf;@w2#zhi)yPelD2V?!A2*7hV3|5^@l3J;g)dle_rR|umeCR~q;z|O%7BqsiY
zv%$aoTwVe|Hrx%*Snb*HHyC{+m+0@Ypf!C1Ue6u8B03N5Z}}C5{})F58xuov&g<Bq
zcu*JexUR>A@(K+ukNX<4Ko}*@=pX-(tE=nEy%}_0<s008TEqV&V`AqJWM>C}|Jed?
zxT64|v;+Wl9sr<M3jjw(03crn`M$cY#u9*TH01Ay3n*_9*{<`8!dgiU>VtNLAf$o%
zx8BvxxLQZ(E!-d!9fScZC=~`Fwr+GlXvR0V7}`ZQ_&ub3gF$GYU9CMdKSXW-;~GOw
z5#@n9w>ozL%v%fq*tZx2@NY31Km_$%&jC>nxOXdu1Bh?9Ml=J+Z{+|$aV@8T#<Bq(
z+~gKw96)uga}~o&faca`7C?Jz3lGrU>K6j^w{j3*y7gHGu-wS8c>&fN3^B-di(vr!
zt)I^T*Nq&S2KNny*yOpz@Br@(hC>ASZZM?7e~ZbW6};gVfL81uEc7ode2WnPkz0%p
zh~8ol5W8MeWr&CGz@u9^0Eqt!OZ*E<{tHX}3rqhCKe@%kfXpp617vS89H4N+2@*4)
zcpZZmw0F4yrEAOt;SxagU;1jd7z8wKF#u@aVC1X41NZ>-KpOBI5QY|s2}%S`h;VL*
zTrOx4v;Y~XL_YwgfdFV2Zh#UXg=i52B(8r%0b(#8WP}zJA4~=cAbll(9drVm0dv3*
zFoCuwD@YHOetIAZB!)`2IA8%<gDJoppbmHjL;#_{djJdM0!V;yz!i!h2^a*o!F8Ym
zXas}+c_0~R1B#*a!hzD39$K<uU>P(6Wk6TZ6x@Vjh6fvfuK?NK{mQ@!@CA$j10g$A
zPzz)QWx)}k71|2;P^wcy^YaHo;2wd_&^QCY4saJ_27dsl(40A;)T4)H-UH^t4Ffhn
z2v7zL0vnK4GlcX33rJ=F*aK8>L!b#XH+LWihy!AQm%vBh6EF-+0F@9wCg2gc0+DM5
zSOYqMEi}U(00hy&`_TL(AT};QYq(UXUl&?bX}|%pZvmD7RFE9F3yon1+=YXIoKSQs
zP*PDs2^R&l1K6N4WKRj%zyK-`1O>rWAQ)oe4m2lS00q<r4L~JmV`>9lKn|o&4K{)a
zkbi8b-xi<&EkGMk6k0z%D83Is4dgEhE*+$W%EmiT2;$HlbOKFacGfPg?ChUGICum^
zBxDo~3p-;=7Y%n~J2!J3S8IE7=ueUD%r(qmj;2=FARYiP`Xc$(@!|@->W2nG!6720
zV`1YLxymJ|%v{yVtLtii{reJy^7B1_NSAtfIc5(4yl*cr2cep)`xH`w@)!t&>Lpa`
z|1uX>rU0DyIeA<FehEHlPAPT?7IA(K9u{s+P97G1aXu*)UJfY^2`PRac1dwQ$Xe|f
z08ES^Kn4{F4ye7lVgZoJ3Hl^v;o{=s;OFC(V&UXu=ZBm~bFhd@aB{P7iHmb^N<prq
z9$l4p_zd8V@a6x-hYFVphYF_(J2pIJ8>B^f<r*7A!NDUSx<^6*)yb>tf1NiS0Fs?R
zhbEyLzhhTCUwOoa{+I%73?dv=jgyrFx;d%DWN^0vA#YS-zrPznEdX_+V^Ce8tBXoZ
zJn$Nz+`+=ZBP1cGV&)N)xR(4Az@5L|-@eM<3=FN+|4_YIs~cT303rSWfLn=!1UL2Z
zszyLHA4(ah;Qfbl6@`hhsV#-8vo&<$qA)eKH+MFs;9=#nx2LdR<6z~1tgxU(z48F3
z2)#fEI-6X5s-bN|uh(*^D>=fA932HhSCRciDblqZdXG*4)w#cI(dnU2#A{o*E89D_
zI$}^pUdz?5<T$tTC(x(hKk~b`a%HHXUCE)-ExI;T0<QdDjdgXhxVqS(`zjXhzgqZ2
zsJ-gDvbmBI{MCXsP-_N&n(NR+LLq#^-qrlC^d4Ndh!aNu^5riesS}b10yphHClyEw
zCAJIzFz#t9C{z4~ya<bW!XSdpT`5e=Ev+3yD7Tv0C@HMXL@2d*6xbDD66RLcPrRMY
z)w~teO}%YR1<WW#A5sW=3VPbZ?9E+`DLn1%99#rFMJSEU98JsxA$%ofqolZ2akUkp
zyc$Zv(b=4WmzABBof5KkHnR{^m6ZP57J4T_Y31q)6J%ra@bF;u;9_-jwq)ZF5D;Kv
z=VasLWPvnTT)Z4yjXhZ$T&Qk5NJ51JN()zOM+b^4kH#jBZmuGf(8zy<WDmP_>)^tA
z9UiNxqdl9aF$~Ha_Nx%D6=7D6u8uBNj{l4LZTGDaOi;qv+}PDz61qhwuh?Z_=VIaD
zR=+vlUwQsp$<bNe(a}zX@~__p{_0S0G_$tw`hQs84k>u0^w(g}iu|XM*dRLD{^s)v
r-Y(2TivM2!W#GRI{Fj0MGVosp{>#Ase+>L{v@>^rP7fZ?!R`M5fvu09

literal 87888
zcmbTe1zc5I*FL&Ix;v!>73mV`4nexRq@-J<yHliFQo0*9jfix2DBYd=u8rrs=lt*Y
ze)rzr#ouO6*Is+Ax#k@4j4_^plC*?`lsXJZU0g&#O@Uhj1q1@U0A9nWpmt1<w5X^8
z5iIau5G;|Qot+gNFtWCBa!`^Kq14dSqD1@+f&u<L{umlN+6gNt$U^_~_xqnu{{DS2
z_2=AiM(DNn?sKEK10}nxYg*;q=ZKj9KI?yZM=^QtXbgOI2fSE}?HrsyAQ%Q<tl;Wo
z2OWC=V>}07QouL{IyU<={t6u%{TVkro};293Y_x;7*iUX8=3&)Jz&gW^snP){~B9c
zIYaLY{eeCy+It&SW#AnTcs&J)fh<6dAUlv1$Pn}qL<v#=vHvgUb3C3e3bF;x{s?ja
zzGnt92RQ-X5eAMxukaoiOM`4c#vmpT12AR-u>dbN=sE-61%56j|5`tWe~$StgFyW4
z5D29CpJQ*^L7>XlAP`F9KgV8hgFx7*AW(m!ouPx_<K><JzhO;HL7<ZY5C~lp1i~Ew
zzN77E%Fg!qISiTz2n4?bft=ETK#1`m(0vR9a+?Ez+~<NoPZmI+4jVvXD8t^ufUrt&
z(_!dGP&+UML%U~81>4(Ob7GU{k64i{Y#^>54#|hZ?>|03Al55a+BD0@7==9E3y{rG
z3Yy)%i?%TL&6@*sa-n{G;mwD84v1<<JLFJ#d1Sq9Rq%F#0D06E+|COrj$%zbgs^B)
zJQaT+hV((E@8#_%2q4~&>APiF2*raW#OntI<e>e?`~K|P9po-;6mq($pYhZD@ZlV5
z!5eZDbPX8`s??7hh19}q2tv+(U0#)3G1aNCVd1pL=v%XF?R!(U%^8l)JqUZ&bmi9G
z`Q2IsOMbY9zZl1enm$3@&nF`*-yocq<>A%uXRb?fa`_)$)0h<R^qO=!h260tt3&m(
zM-b6(wW=2TFK7P$xWPQg;>3I^=0QGyJZ;W=D~ZSdsJeAug#X!}NlQ`|Hq9#Z3%&jC
z(<h!+#)z6>uZ}sdDhV63_z66pe;wGlDm%s};m!}jKXFA5T?<U~=<4@^cd~>;+_Lz;
zYQBmLAb<m`ioEom@<1=HWD_Jp!}Z@D{m%paxlVm7Sn=;G-&$JzXUUe0{~UKS@}W;o
zkya%@<>8D!4=gcfZ*D^^O+X8P`+r$q;3f@Ie|G0Sm5iKj%Y>5FpD&TLUT&s^7ZF~P
z9NEGN?wV!izOWC=S?ZJJ)RED*4psZGju%f)t$KywS;qP}pu1)Z!T4+6f6o2&FmEQH
zA82^b{SSFq1D+XHgT3leOoE|{MA6OTEPxUo>Qcd$cKEV|Ett9HmNJwk9lM7nb6)8g
zujT(IA&NBl&%yw6SmyXk<U&ND5_V#Y_RdI0DYB)?=KSCm-hK^t8uWQ)G)GxEthdFX
zgBO<y=G9-4dDaduKJ^`#qxv5itu*?#s6H;pzeL-+)&V&24fHG7Qh*dYdX!kx;2Jbn
z*%ZZ&rj5`u^CVc7HYnm}_#o_P|94Rzr}`g?@~=%!3gEBlxx**arYA;1epD1kYf~wi
z>+~imDMHdHVR7Ty{+N9`qC`*uHW?;Vr?$ONqWDZ6Pi^<h*?lki*R!SnqkK^5jfG9y
z`M2gZWIjH(3=N>7XPpzPPA!M+pA7EHi&nc_Bz`{C>iX7BJ*nYSes4-f)?0-!4?mkU
zZx3u+X_DaosqTp@|7cDv*W=RsXEiAh|51FIk>c_hu#al=>dzGNqEw98D~u+WxqdW#
z67mL5d0^)DZq5xYk9zWdS3<P?qVPur<Fe${AG;$6{<pLnb^k{Y!gS!-5yI{SE~m?i
z<?+#zmSl5X{DmAkQi0Vep#>}wbfKGE{x?;*`uoXfVpNQK{|`z2Nyd{&2;GsUD(nJ;
zR;!OAox&>`1%}*uAgOeW22^uO)t#JOlR~b1a#J3|+`7a^Lo!MA|6mTOF#j0M_IaXz
ztR(_wE;(DSLz`DI8plO#Isbe%_yBX^w_F>x&e3}0?>M#!Kp2_mgGA3g2`g7>_^rVI
z)y}Su0QVP_@BNQdm;ajCGO6MMbo4JvJ+&ApQc!~9d)fAi>Uy1K(n03juenN}vqD~#
z*xK*WY%?6YeIf@oJV7MJv?<A{|KDbNlhYp%FN6<8fQi4+|Bu*FAS*@_n}%#BX$Xx2
z#!8KHgcFurp9K?%bgBDFE0(y@)Sv<(RN>w8+u0*O3T=AcwWzy%u>V%mtRl^<`5$=)
z%>B@#3_tyIS-C&1M9NoI{~x;u;h)yg0nC>-W%GH3E1&FuymycT-)Aqm#4m4SDW4y9
z&|E(~5TlkWQow6;H6k&byj8{ut^+gxQ0PZ1DMJ2lU)50jsBP@JvegObDSx}G3bV&M
zw9VV|iH-@dM}`=Ioh){*)Ga@*VX?EtQesn`z2!_%^Txut$dAS+I!+QFA`$@B3k%6*
z=Fu}U!~b_jrTH&=1D%a+C7?r_#oxFgl7SuGmDOLpLJNvx19#e+R_8^WLCD>-_Tzc-
ze!0kJP}2aMybk``d_C$HRL$-#9rFHGeN6VJv2!ZIHGpfIyq!}4RA*20Z)4=lfb$B{
zVQy<@JjMR$sb!9G>4Js=%M`3@Tr>FKsdS+UxgT_P9!X9icu;@wk7FEh1^jlp@t*}+
zD|}p=A?J7Q<S<Zgb<dbj#tsWLs<{pHOeLZWFAtw`XQKUNSJRD9oZs(?{j|kXaRZAY
zBmeA!$aAp1Zv~)Yz!Vqf82$wY@<txf1UuY+=Ii7^(a&7(v`^2Y`)KRJOMCgDMh-#z
z_H^$kfE7RHauJ;q=3#$i<$h1I$}h~U;rMghF1d68s~i>yArxvjdrhsiqW^JGfCq{x
zF@PVt@U((HLEeZt>fajxcxZ1_s6bz%4>)MPd{h)FQgm5%Nr|NS^zIr4eDlUog<Z>-
zgbb?7mCs-)*@7VXTKnFy>==LQ2Vp>px0x{-cK}H;uz>1)D!FcH(qASSL4wH~kRz!5
z1jOTy63PlgF@sYR)G9Z<IZqm2X>xX<VZ?HMO^Q+-;@5b<@Rn1MW^G9Wa_#O+lPjSO
z2qzg+GCGsb7pQp={mW6N3Qhe5sxHceWC%ITFw&Kf9|6QYQxPV+)-%97@|8oeO3eX^
zWscU~J~Kjwyxj=ohZ?HGVpfMoqG=~n*ykCx!=WOKdT>oQ6%?w~G{I`=0!|XqI*8QA
zS?b>yY$pb=K~(9rz=HOKm^lst#yC(~+(_87xv_^65VM4LOksY{SXKNj-u?Q#vcH?&
z5gF8T;2iLoUB=SpGmBx-y6+1HCzr7;K;K#72}=iK&uaqTr~MJAwz=#yOJE8ASaktR
zU~?WN7dWvQ3yLHUw_i7b9<8&9au5oyW~F1LiqqkzRC?XKG_8!^b9`0)D4LZ*dfIR7
zUT%E}aa>f-1|Fw^V{0EOTjzY=LlHidc3;u6*{k@e=voz8O{PUWBB$$v=2qZ9G2SC^
zwbJn8cl}YBE13u{zK{mm@LUaW^jY>a)L6Qhfpd*qMp*kmUOvj8*~Hk&AZLEl*Nxc?
z>?5xg)Ny;U{jn|cR{YjfIy<~4hNBA~{sPB3s%U{cGnMcUpUMtZ-)8{^tZmNd0VOo#
zr}|tvMJSVf4ZiJt<w(B>QMsOj_D}#>Wp61AaW;COS4kWK&Rm%8ZuKKBI9*ggg?fKr
zeE^3Bh}34&qeG8MlnwlsOCZuKW&%$EH`$;AFnG(GcsDj&z-8R@%a>BzM~eCrsd%sE
zlmD27P|(dKn^aAAg0k)k;<iUCD16rDtP-Ktg^HkQ*%-LQP&CutyVb7JFDOxe8^}r{
zv}t9GWK@U}6zf|v0a!Q?hle*(Kg+N|-<r#ZW)C5jD^TdbzqTE7`df@_bN7x`9!*<C
z$BHt;rmxBM^Xj@kce$?&YySiLyq?}CJ*s?NIvLp9eY4O+P{txywxdlrWyi4)DtE(x
z(zy1juQYAOZ<_pYHdW7{<dF(7w_>d;#i2l8>HRSsM>lHN{wcZFT;jPyekx?&8_`GG
zi=mA%f57(}U<<)uMW{;{J*9r~qwkq=P*hW))r9k;D3!eYrShsqiv|Z^asXEVz(^;r
zXKlisQwai%IrMsqd~8=pUdV_vzen9<AxDL#RB}1s**?VUPQlyyz}%Bp2LbbIjZ=9z
z?6K0kEIx^~;ll%6UxK88S(E!g4XR7~Idk0t0Cf(!IlA)2VkdTuerIN|;nOg05O)>u
z=^?Af6jhLsIc)69;XB6;xQ9?kZM3antQB2q<{NSJG>aQgp)#|d%Sxwc6@ZoWg}?Zk
zhq(_Gj!q^EFvJ6(hE(M79(0P0G=N|MC;{sJ(WbMx+GD|ZL64hOzyrLYt>q%Ez?h7(
zUFOY#(^?d)<_=FKaCh-_4U?EjYS;xdL&ofAI9iZWjlQxn5)c)XPN9J~44w<N4OH^P
z!c$4Ff{0`yVRl5*No~ih@4vdy6bFf*!~37<Tl4Vxjg!6H*YOw9XL>2N7l(P4?yNB2
zpg2I57nu7ZIk?YG)cs1$C%=n7k4DDI;9KT1^Bb#M!Cz!z7wo_^W3Grv-_`W#wYbw&
zQr+;=w8*xl=gq^Kjr761+7I?6;Fpx8NWf~37RK(;Ut>3iO2S{^C#yHS_$(zKKA{h5
zWf*U?4IsBHfHrFeDfIcN`leR<H(K&)i@8X6h`kH7f!WN4IN63ED9avgea4lyMYW9j
zJidgN^80Hb@~B~DXvOZWy6bxD!pf||Y~kqlvEz{V_r$`_aA|7dZ{er;#bDWc8?)U8
z9wQs|!!7gC?*UWBJ&n9ZJ^i(RdD@%Ad0G8ppYaHWv>l$cqjys8&{2|y7}hdyiP32B
z`V4%*42mcYlf)2;vSZWl?6zi-%F6^KN9DCUL-yUnQ{Tgd08{jtTV|lTKJy-!#lc7N
zUa)Ffg{mKQO`}qFTu<Z|f|o}XI)|w0gJIAh6jJ0_cl&}?e41a<^8kO33lx{itD%;r
zQQ?;7fc?EweY=WO)hl#GG(oHT8WkK3&QE+J-q2f6XC7_+X37+z+D6gkrQhmO9jv^x
zQpyZ3KKa!~kvq%?3l$F5h);t9D!N^X+AQHX<?}PF>-2xarN1Fr2M{*bt$E<HEIcU|
z{VL?j30}CJi-G|g8~>s!WFFmMR>nHqX4)`ylaM<;YBa19R_%^m)=(B?WZU(A5|hb%
zOI-u+sW3RVUrxK9Pd>QXQ}dTQn2yBAmK}NpU>G(eS_y(fe+Z<r(tXyT$QwQ%$8Ma3
zIYxi8IRTgt+M}!ZGap+>qh_#9U3^VU$?n6rzo|6IloIheopNhXwHJj*`4`Hu$(>Ai
z38yyw*2UkOlzOMkeyP~dNZuXr-RMMTi-EXTS%nt*Mr7NHM|l&waXjcS9?&TNW_SbV
zqVx*^QzNdE2_+q8j2@dSNk8-HBB0cp*Tds9f_32Gr$Sby$Iq|VvoMvH8k7m6rI7HI
zWQc!%##E_+hFnp1+A~ahhKFjt2yvN6i3?wR02qG^qyHE>cX57gTfzjb5Mq-~4Wi;5
zGc+^jB8=Tyj4nKegeb9(CYdJW5kZ7w{f*|6XrC~L8%hwN@=*4Z#MQ*VqRFEnX0dg*
zM|z=TQak3>xFuw7z<_KJfA+dWAlQ`~yL2f4JS_iv_oEt+nUEvy0(`j7&g_bbM4Z@L
z;w@WXd!xN2t%FGX&~*0yY&PB7MIc}~>FycvBefT(Wdb0NZqg!vmM&N2-V(qnyuJJo
zXlH>K9;7IG@-$U=O-9~C8ZN`3QQ3*5`vDv{$4PpsfWlM6+>x$~iyw0{_I!SzV!-Pm
zD0U2*LAkXEBkbp6-;z(CUM~WW*MWco*XRSbY{<oGdMf~ZpZ7-o6Se(81$^Z*TG>xx
z^48$D^gDNW&?>EekP6l<F8%QTk>pB-*Kn{`66gb{QV3a8V8h*;g_n76GUl(>DEIGv
z=H~G58vPFMl>>a@ek&mHg+>LQMZrp|r!yJ_V8uQ^V{0A(%m)X$6&~Jb@5S|CTxg7|
zIPo*41jt^sXXn;_8h)}eCd#CnH`17eoKzNmErdG&j+<h-JQw>-onzNNutV({P6d+7
z|Lq*O{|(_?PCers`T^>JloIdT|3t@Zgn;qb_f98g)C1lqp-{NqC7h|I=m-i-0CWm$
zuydaCUr|rzF=aA+6E`~l$K(tJiWv<si)Gjz;kPI*`70xk^l&B1x@0zIFoy!uCp;^c
zz1%dIQj-PC9jO@$yKZck1U~fq5t9|ouM)|%k9g|u44j)pyL(|%tvg0NwKa)(`#k9l
zbvw9*vHMC*vi_sc<L;xxg~NkA%O#~AF?e6?8FgS!o{7&Di;Or3f7xLnl}LIH{?%LK
zKK|!5HJOU#up+%-Q}CpMemVPAJ!l-;%6_}|(&GO23q+U~oCLlatyTqStH8d%G1pxI
zDXqY$H;anPs{$n5g!9S<L$0JqO!>^ag4ex(Sxb6MSLGY%Q??H~PrVuhOn!;a8`QUT
zGE2QdOZ}1f)>QWPdkiA0BVu>r>&rRD5=InZ`nG#^D!ML7KIQxLOyB+7YY=Z~xvy5e
zDYw%fCT1alK%nv%N!)xH$A}hfYL-S)(iElb^B}D9(=z>P9jz~Ub3{?lF~urrd3o=*
zn*rcvR53mv<Ny(@jOT|=*D++}zOE?5I-6aw&~^f`<eNlzb?n_afzdX|QEn2cIC~j0
z!gvjERq19CIG@)<-Es>bwND<_vTP?kh9f|Rrz^LP!IYCA7~!mtXY1X<jwyZGju=S{
za01{s<ebUMf6YeDd`!Bdd`u2Niqga%rm<t~w);OEHpzi<iVWFemzaD{MpLKBI=>f}
z)^vTob&uNaIKIvAiTc)y#RcXf7M1vv&WauM0AHCvc6n^*QbDx030n!n;C%^A$N^~N
zw+42HRh!pucw@L5!`~kQ!M_IHzSWEj%zdf>je@LnMm=lH615o^lvj#^K7R{UYZW{N
znU7$?MEagaQY-JF$>gGPq@fjejT32QQw%SFoUUXO2+-0yEKUcN+@!!+4@#vp5-`eT
zYxy5F36Da59cu!?A*MBDiAV(`gadxmgmUC953Kq_KEF2riFOYFAPk`7opii@qu<H%
z%DI(#YB-QhQd9{f89+%_^7G*Xm&fN#z|pVzMT^dTf}|bTY1rvzl@{fvSEf?<GYQbC
zDF8&kWvQZqk^^2rmN)(x-Jws}!9}`wte<h*71h8*;lk>RUgL<*g?B*m17U(cZsM!c
z+jMag1ouO{cHK2$&q?YBRMGC9@4SbuQ_#Ta&A7{RBzo9IR{Cb@gWG(clMEHz<W&)I
zObfRRYI`Y86L}RfRDr5>cOZB?LM_|*j<NcNGslR~LV03*O#MP^_wpz#ZBJWDjm(mt
z=1_Od%$7q+bRp)eD}}CWVm}ME=zQl?<KE|)blHw+eqik{p0(+y5k$ATp$27bMMeAB
zy_RKCg)9(k+Z|shSY&cC#<dleSKx}>X>3_8ubxrP7LK$$GvrCW$R{D~760_m8vUVY
zQ*zICO|vx)2YeWg0mxBMja#stOz^ZwY60xI(sR9GV}+DU-Jikpp;YW4^^~;5x?r_m
zlHj|b%m}4MdjL_HqdwUG<$iafLe%8ft3<p}7=p>Vy9SuU6%PCg>1OSfHat4~Id)p_
z(J7Gn#o1n<TN0lp2`+rz`1V4<_k(uG$<NqwXhhHj^YH4j4SZv5iu#zet3d1zGWRgm
zB|ry~1y2LtW4s82e3S1TN)B_I^8`|8?<GByDH5HpSQqG$q%dvj7u%_obL8^gC}P;5
zh#h_B%xNyfrja4QM(sEvVnY=^HRFl8-JM#}nT^iUD6m3^A^b*>>0a0xvra{Uy5Vqg
zoxZVt=2{#+v(}0t{+{L63X;XKA-;6ymzS3_f(n|BXbG=ZP6L%$IEUEli!dBzr$~LQ
z8@|ec?PRQA*(5LonUBJqr~E~o*=>7`-_tCaU>ai(FHCB13T1Z1y__{j0Kz?7yH8EG
zN$1f9E9@MJn_bChtSd%%#TS#WfvE2|B^aif%O<p{buub!!RL$M_6-kBffArzPJl_R
z*^IT@h3w#`QB!&En6`~Iw^n#}0!Aqr^>Srbzw^RB`I*Tnt^1+6J6+K(+Nh}628Vfn
z(n&Ckq?Ja97RF3d$KmyWu<UWoA>q<%eED`|uyVL%YO8*0>M+N*#S1L6T=<&mY-L=H
z7=5=Q+|sYFFxhpO(3v^VgcFd)xpvGCP(y^_IJOQ@Wt}=Z5|4ks$*##7N5YzR!Gz~R
z&t46o&C(pKASrKkTd+qg>`Aju6V_d-aQncxW-_<V*d)yyk#4)Bgu2x>kLl~t6i^k!
zf2^Mt@5&P$-W}v}kswCq^t_@_f+)9PEI{luvbRc$qU@d)@GIRlFDEI#gbX1SZ6<0<
zcO`}GnSKw*GY=K?R!4d&X-<)5`f{&hiv_hq((gG#ryqiWP!fjIT|Fe&hbo_Ix5Yih
zHkR5nh|_B_njyb?hxe0Gc1&#|D}WM$g3m)x($#ZnF;;Z>KLz^V-c+zMcY>$T(QQ;d
z6Ao6BR>KLv@MuTaS-@7u{9MXV=zFU=-2zKl79QPkC(Boifk0bTwA!xO$?U|C@bgZT
zWX;>PDxUY-#4ZcToRK2WX}QGv8@ZYHL}L53W|3LywMu*h8weGYwxJbXk*~*#^-A%D
z%y#R9={924f4a1p)<o8b5g4P0GSJ{wWF?|!4Aqq}iBlwmy6~+L)FroR?B0Ah{vEm2
zO%w-7$G?qg+Sf0yMX8JRLrRcp;6dWA+JND&ey^$qWI5SM;;;%h4oQVnzr_)D+U&;o
zfBMPY;obbPUoGHunX1vkr;oARaejl9m7%R4*giPCIxXMnt)lpfd9GB223w%(yu!?D
zIfFbqA128mf2VzR63%w6W*kl7`Jxc_=g)lvk|496QW4#yS?dTSPw5Nl0IUV`#?ZX4
zo0$h=*Z0csfMA~hqe(hgf8O7PXb64POww9x9`o`e7w3^p?*m;Ge=IlImuDU3L(a{1
z8+Ss&Yz@@5f^}cl5SLKjCvT-zY(6vYR{n~Eolh2CZg^9v_|@jy5r~cX`B1+KTcs3S
zUIk4!Tud$$n2g;YYa-YdU(zsDomxtja!C;l33`!^9l>#Q&CL_iu)jTBh<6ne+apBM
z`RtX#v0O~YV?^d%+h{l);XptHXI-EyFGN#tBB@CQI)5pjC{sG+AN|Y1P_R9prsj)m
zsFvZ25>Y(K(>uOQSswO_0EXT6<(sD?#cwcXL|xoq%URsg-6p2D`H5Go`SD!(?uom)
z#D#TIqc7tx<e%}cKKV3R9cm-Lw2C&FmekogMAP8yg@lLo?Q**Iqki{{U}aHd`I_vz
z7t=>>4LEcN6SOPl6M76MPIU$uJ|&$2_vt9SvC^21<+}Rz?#>AZ=F5ZQa?E6dJQIYA
zU-)T&m`8<7MSjaLn5X~<L@=!aKT1AxNyu*vW!;{aeCBO2qY<wo(yNid<yol`nhI&|
ze|BwfFUWV8^wyZFZPWmBnXIKxRaMRv-yi*sp5Gx@I~;88k#DM86})uHwiwjS;X-?;
z+|K`i!ayz($E7##d2^0?qHl66OL<28c3=CV&Tu^0n<-sPYn!J1;Kb^~(e>f>VTa|+
zIM;djy*15{q9%z~8MzuIhx`&5!dkH}YiNnbMrx}!j;Xc^W(x<u!JtL3hV_wy_?EcH
zG6?}Q8<&dwnel4{QniHN;mxQbb&AzFy0$#!zh0VT4N{C%d$MfD-{(onE#O}eU1lpF
za@<R3n!J=>(MZD%Wf0h~BefjkHI);(um9@6xe;2U@!@D>nT~1#%}q^mphn^9LSOZ4
z#{;j3eQhzPE$L@3a(iBgq{|29^FjwbuuXV?rVU!83!5_oJxSaLs`OUA3k3a01v{nZ
zSykC-Aq>;5D_6CH*KorW!Nk<`vGt)~%)ynHvX|SGCdQEFfqt^)T?+mg1NmXg5sCuv
z7^=<ol}`n-?l|Gm$Wny0^4D~Ufj&bST&zKy5qHD!*))+ul0n%K?(sG!343ZD+035|
zXDw{7nSzUVmUzFsa>;`=agOOteFfB|=2ES7vZbW4P0MfUTM9I;dvn`58DQ18U*)q?
z)@5I|u@aq7D6eW}Bx*~kmpiX8J(b4YCjAzCk<GI3QzD98by41u#AF`6_}=lm+aATi
zB8^_!=;0QS;+v^-(NNt-thDmgUB;YA8KE(i(p_%A4yG>R{LJ~}XUn(27rzpFBDBJ*
z&VT$g@|g1k?Y-Woze=E|x#GsaplwaWhnpjuA5_d#-h>IQ#nrYU-cYG_NH*u);2*iQ
z_?gc2+As=@MCrFWEVA37S$&#FEO&WhL3!40^-%5iZXk%;y-J1ujUhL4ugo3s`k3|v
z<MQ{!rf#L8OiZ_Ay?EDKJ7FoNf%#8bG&6GJoLf^`u$5FoGZj4Y=NS<>L>w69A%6MF
z3qKa(e;;vq+`a1^eP_dX9x`52L}AGr85H??rcsQ|On{dE*9k=iH+rpIb2VK@wnrdc
zgJ~)TOj2azjFT6bC!Y@daPX7tJCLWWB@c&XoM_u%6`U*T3mP<65%$0kDzBpTxp%ap
z{S=^2jf7E8%f)$c)9Wj}(pi5q%dwYZl|=rNtaS#-tSxcI&$I2Ysx>LObTidt8Oz!t
z45qxUlt%nA08!Ej@s=dpth@b;UOzwn!)|(20y2))D2Wjbn&LbG&EX5W^>8hQ*N2X;
zOEV~?UIue@+J!P!C2kRcr3CEZR7*2<-dDt;xiN7^e6oFq`aZV_d;Qh6zdibpPd;et
zlk%W=<_{qL@fRk$7r;ooVxq`!MG9-bfWM>yl4LoOF0pfJgI%JIZ7yXE0~LH)6L}g7
zPb@OedsJQ`TKgUB<2N#|A)BiSzg$f2B)o?7U((WY8Anlgz<o6<JvW{jpTNGJ51Z5B
zd;fhEq31lsD_|kd0z5n!O=aU)-Fkp(v%(SC+R7)TeyjavDiSRHy*>0D72k?+zUyqf
zi{CX+jSa2>s2?9MLil;57L&Pmg#^&In1Lc;d7H4;(?2u{2<Iao!7=PBO)sB`F52(A
z(*cY@g*D=xRL8Be2siPstYVwY!9V#go_3iVysCdwrX=QGBWC~cU8dsF;Ye{>p+>Zj
z^TT}q=rhQC@)S6ArxB<|xX5ZvP*Q+hIyixNav=Pu;$4N_Z`bC~$AH<W9&U+yjvex4
z2MBxuJg_ZGXVRG&MSA9Dy>?=Kn)!T)E5*FG$s^ELENEe8%^f4+pOTiS(i<$jf2RaH
zem15lN7%W)sQ80UX|$+DDMC#PNtxa8r8$Y700e&8pKXL~J_A(wLnaxA)8oMHb4<hU
z=<nUZZ4+Hzvwna2lOti>Rb>^qPV>+nboTzSJK!^83k0G-BoEwkhDG1BlplrIL9a?E
ztTVmNJV(rG7Vqn8V+6Hl+)D3iZ&D4xJ|>Abj_a(0*kqP>T+jQg&syiM11S#(mSCr+
z_e)l1x=W8nIWfgjNtMC|Z)S+dxgVrU`eyHw3V$bTpGv4E(6tuF8iJl^e9BNQ7w)Ns
z5#!jIjfnuNP8iD2^vYw%f2p%FtEGqiyaeytWpP?x{5!G=b1K2m22Q#I0>%Pd>5tS=
z1y20??_F+Rkk&=_Jo!euAg2(x<H&WCbvt;$!v`BnW{Amk=EX_IFBIka5fqYSbgB9J
zM@MeN%PjHVlo&Qr4v3u}S7CZk!+R$oG#sIkNJ-SUiA8Ve`xM4B>A%LgrZ8Vr1>x#%
z+OCoqyA^UYK4v<++3Q8$#8|;c2fzn2bq%U6aw&KFQ{~Sk%!Tj^KGaQTZwG${T{Kp#
z<js1LCARK<G?7Sha;p_@8;`p=uj0we8-~*<Ky#3Ljb#{SIr+>r0+iBat<d{5bOd1*
zXBLe+<vd(W(|z*SN4NOoQfssPr{V&XoJ_7?QbM&NrAcg)dERR#+utU<X(y_MK~`lF
z2HOVi<5r-*avtIjcIV98owUaD;#j>I{4&Hqu(99Xk=)6`Agk8U<zM|X_7(ux7Osf|
z6f1?nhILmg$l!MMoIRx?TlfooFaZ!3V(<Y)P1&!$vOv)psP#m+jApZ{+)QU5eSqb{
zRN9+y+5e$oz=;_|9dtUAJG~*ck~8(Ho-6HXTlg5WNEJbspon$)rk9!xS<=8ge3Ng1
zl-E`8TaQC#^=6C$WY;`Fk6&y_j@f~sQ5TNP!f4jx!-n*fn03NzQN5v7W<Lxr;m-rw
zhb)qYB!2~~;&**sW!?g3k*u9*L5Oabr$Z$sp7uLc;#1oG;4pv8^%?wpq(OP<X-MP)
zK}ye^NKTG0RgK`5T*&-;+fpL&!hulv&jQaTrnuIu7fY-c&|NKylCWxEh+SQ~1QL$Z
z75aX3de9%%+7IB+bTW6LI14HJRN&&|zG1P-_4bDnR2WarPBfSd>-j8ShmMJ<cf)%=
z%_i4OWd45QtNB(pkxoqWxX-L&yxbK5TD3SR!bodXON7z^#9#^M#qK;48MrI%B!tlL
z-HGjzK|R~l7%bWTCn<DnLxlnTccZjK?Rsdr2Kjf$6Uv&-Rm%2GTn)N~&MH#}DBah_
zm1*xh@e9JFqroE{KjyO9BoQ?&Ve-8@O%Wnt{cxewhZatf&c14MGUCg$cffkVFy87K
z)fCUJ*0$is-)CN^TZum<(g||$WqzzqayVpjCTc%}pmxIfMV#zbXESqG-_X(8>sOvV
zi`o1Atbw!D@LjY=GHPWwrRMXam?LTd_|~w1v@rJtcH#;<;x%7Vv;@)cYiuDb|LQXF
zTSK^jwzN-lrExn`6Nk)bG3C?;l$CH&+tSM)4}PuU$>WgUs>}e&yoh+Jnk6_hRqpBW
z65PN(3V$KO|L`8B5%JfEhEC4=f0Jo|3RZL14GC{<qx35mAP)D3ux~iR;sgw^I+?|f
zbFbl&x<6&xz<b6#!=^*Dz_Qo>oa#rmCED2y-IvbNL!mLt%nh%dy$3EB%$WgitG1Lm
zbDb+%P#hDtPZA0W@9hrz{3$$()vJXl**HD__YRezYl+$7!#)mjM|=jT6x?er5K&1h
z@6njB=NGiO*mO6}_;`d6QCdii-g*8~ZXK33G%2c4zBTrTzI1u&xN9H%saZTo$4$zQ
zE_S`IZpSE#Om_4~a*a&))%<t)!w;j$XZ!r0ZPBpcNL+hPl-3I)rzOGnXz`U(j!G!+
z3^3DP&2s6+di<uH=e&P<JNPn@U-^3c%Mz8mqf%)82-=ISklaSe*(N%3i5K)a)%9G+
z<%=1IVd@Xhm)vModaM3T0@Lp|vzFzrwQJz0AdG(`Gqwoh62k5$J7^m#7VNzw1Hns$
zzx3s*zO*ay_#N}Eire;D4q0zUVq32N9b`+e<5u}o{e6*-Q#L%U<vL$#tI{~xbT>k;
zDt5zrJ{cQP$Se9ae;cxij4jeDN$%D;H-pJSy8$bw+p<F^!O|?X%mX`QPtPF1v(@5q
z3fs-raG==w$k4%jbzz*x2(5IP;EWUiwaZp0ALux~*1&YvTAn26<C}Kbb6f$(#E+&f
z5Z^ej8=g6YpC8Y*^tXOYtsTQ!Q_pc`d8LeP^5(Lf95OG_A_h(21P0ad;AO5Fo>LqR
zo8<30C|!2!%1$Y+M0L=He;2{}Qu#Sr(mCdEZ(*OuD33s!1#Pw4Debqo$c)e3J9mz-
zQHX?J3nhFq1J>w3$dhGNFbwAfUiiFA^0Won(jT_uZ7IE{Ys3uwo6%YzM>4JCZP$=v
z=r3xRh}GQ7`gHH?qlKa)ug=f@7Covhq=mpRlMlq>1wY1S4-t#Q?WpZXB^_<vik_X3
zb=e}n?uV5VImoSf!6K@n*7XhTh{wT~b6rreDyLsx4W|&JZZx9v{jK$7XT9bNVe)aO
zFqFvIR?*)Eq@^jcM5}v}Hyy=bv?6BJL{t2?MM&J*1{x#vT9+yvDdw3a9OZ1TMw~&U
z=aNSRbsrgT?gaV{a*C5bhQD|$qCN^pZxv7g$FzPL_qhDYtv1ZqkF_y%pD53K9|^LK
z`Q1zs)tLvJA=a^#lZe`Jj_AP&CGJJhc&C&H6V@IY@f<A}g`8ivGe-3F4E^i1T?NJh
z+Lrlc-Tg#mL5L^VDBM`wH0ezjtqf~HPTuToCOJ<GDlVC=mMzfdKF2Kwuvp{ywO*F#
zzG{AwSym+*aq}xCJ=!+XD1$6)`AZ$4+553?dht|?zu*C~)!#KcAj*acG*ANBtOU}0
ztZ}}V_`m91QcRWb;VI-foh-3vJ;bGk<kn%8R14}$Ug`w&5C0Uu322NM+u4KD)LcXJ
zOnPIJo;|*4;$0P@CWSG?M7(}AIpe7lb3<}~i|#*oPwb=iMM2jH4K<z*mEyU5!a~x1
zEY<{DbODEA(D;w#1+}smwI<qZxxT4b?!+R>#UCW4F98hq!NCP!sM%}-r7%s>Na}ux
z+qY4PJX|UqRYsc@{@3WjBf~A!unOz^ec|*jXv0J&v!gTR?dPEe)!rr-99fZDv~R+}
z8HS;?&+W6gU-(|a!gJ|b8JB_m%Bpvto29^?U+O;xv9maF(yov49PTj{tYzgMFSla|
zNTc?ot+|P8;%Kz}e9dbJpbT`2k0O>AGFl%`X^X_9`qc-Y+~IxBfHKtToeI#Qyo*I8
zXoY#E%V!cT02y7%X@`Lj$ZtPQCm_8nj_?i!i_31mGlJ8iwQ?_L*<$x97om18-_Z8l
zvs&9-z6yfPC#RrPL&`f+er6v-FXav<dD4jMYw!!^7`|`dhtaAa9&-vtS6@Y?FSfIU
zVzb!$9@3=zB>r@npVyxTp5K(dbLan}s`xtM@LE$t79F~!0JT5~SsA^D6Eb4cM3Ur~
zoBf!9q)M*?))QbE>HV%iAb_=QtZBDzvHE<-;@{;Jmb@uWc{n_ojRcf9h<052nE1QZ
zET~^q6<C#)hGe>c3?meC>6Ax+@;*$7DaX=&1clsrs>*kM=Ir&I&4N3BI)flBA2YWz
zeRp9^vLiiWWGMB!VR|yX^&Q!?55(A@N)XrJp13TZjO2}J$VoeVukpy}TnkgMzIxwK
z_cyd!b+zOTmNP^*bL#ruwJ*sPVH~i$dr8P1m&-v#&I%pNdFiaaEE-0~1IKt>G*;R@
z$-=lU0UekUaI_pBSiy<=DPeWHmQGJzc3tT<9SaUoQ_i6&WOYd>2so(bLa5eksF)Xu
zKdTHT5C+u?$l~$=M4x*tFQ=9v^O*6|w)>r2a*ja9BA_h8vC@V2!ywBTtgIG?@OozU
zfkYuF^zih<q#r$HzY&gACv3$SmGL&M)8=oal}qePGi+6P(kXI=q_OG}2e9JkvCsM#
z0t@j(2Z=u}LKuHgm4I-3`r8I#^b~v67O+2#u2npFi|;6k?QfH+?B7;qFRi*6#EX8R
z0NVyF9*>+?<>rkZy8-k}fK^pNLwQD^!seP_9y39P9sOjO_Eb6Yx>s|K^OOqCp3Vu$
znryh5+?LF&$?HR&=%yPHg+ptOlgT(q+trU;3kR5^pK;E=ng&%|d)_3~Ob_@<1$~Xo
z4z%csXDCC1lv(&alws}eEW0fjn$T5j?(U6Bo4`j|+D*hReF)FcK+VP_e?H*jUjnze
z4n7f@t?LtTTYDoMNA!T&jI9!!0OkDC$)GDf#K8jVXa{kP*PlHH_<ztUuHpgj>UH(@
z4d(?ze4Uu3d7f<mZWerid_YkcAJq{E7lD>b>-)-4kb5`SM<@`ol@QjPDCLj&`>J0D
z_f}(}hSI&1inW_+wxHk~q)_Q)7gnZ77P<+SdrT)>smF!Su=f0@8?mX}tNpAkLU733
z;g^_LS0T+AM{%VSjT_UoZZww5nj3MjQHZ%OCLcIa>dQ;X)lE*cF`C<LnM2wqE?s+!
z$lI~IqznXaK!w*I%#;MgA!}=Woh63r^nsM^bB!?BCBmNdT^Dp<JAG?_A|MWwWLaf9
zT4&W$7t=uMG=&#U%nE8!CH=VCL~On%+T5;HOK|04JH8X`?auF~W={6hs498%Ha7O!
zbuOIfxjOG@7Ux{H{Q1cOKHZM~@)ng$miy4$10z>wLW%EY{oUXDyOB?0(Y^HZ29*I8
zPx7|1PhNM79|^90h&}}S&3vr7&AH+zXuY>nw2s_(`O@0;_+(lw+PaE-q&}I^>XpiY
z11qKG_xjRA)YcK+htG~;Pn&WJJ6GNx@c4TV=;AZxldE@XY9&_&Q!XdTjo|~ZVXF#C
zH{wKuc2zVrC`TKJz9<%d<eTG?cJL@dL<4ysTRgo*adu{j*nNcsWI$HEq$1KrcqmZT
zpsoVq^4hRrC(bE4wYNeM|EVbgt{ta-ECLBz*o#i|es~u9{*=Umkqs6zM#<PQ&U-1?
z&xv}oH%QB`n^mz{JXHnnGA+v?%C8}Ohci~J)-sd^&nO8bhJ4oUu%d$$pJg1q8mpFx
zXn(P|KyJ#ElG}#pfZWOaG<)h;Ny7{K(DfID`H2Dlmn~ncH!pTVFNkBP9F)Ml@$(<v
z+$t04ae%V}QQ9A1dFkdpI#+d$M(aI!5X0sx2Iyiyg}<LRr_1ZO^X-<Jir~}+MM+)>
z0xOz?$yUTG9MsE?FE(PSNhbxQzP?9Z55}gzQ=?MM^Ab3c4s#8#lRIwwY;CQ5w?U3{
z{pN)}VV%d&3(<lj&4m$(((-JQUqtf^F*p>(+|Efvo5m8^6i4mRzspMd^U2{>0?<(f
zjF1a(uyxHS+1?1ly&p_$;kZdLY11FJu+Z=S${?}2Vd^DRA-em7-Yxf(xdcOA<CjST
zqcom!_d;mo77sj!RWkaH)lVE}dYqml_`IojgLGZ+;st}(7~k`R;Z#3#c)#_;M8Nn1
zC1?G94??*npjsQQSO>avTMU+cGEg482>M($`T-8a1dzkpBC{AVU06XXr1}Gd+R_e#
zTGu8DIGc{wb9Qr%Fv~4n`6od{SALp{YzH1rLbV5x#t1YoY7?Xo5HCOSZpp=mWO3fb
zJfp4>ufS)rJPyceaxg^}knY*K;z}nQsK2W`So<Y?=QlN{bGM_>%kh4WwdUTr+X@3a
zhIqPqCu~lsRJqRh*AKkTSq8B&wLQD9a$Vl}W}G$Th?;n@PE*xw#cVt_oH4SwRyvm-
zxp!jO*}}f^@ETwmEA%Uu`CK^>b2H##fOMFTU<=5R^#|+v;AQq#<voo#VG-Dpu&ONk
z^GkIP-u7j^TU{E>;(2ZhZ?>my$gAMrj%^-;ST<|D(vabP)?e9n=OiN>sXy{;)-B(R
zLwL(hlZ(2uSmcJ}{oA(cv%VGHK`pYQpE77n1eJ%5GuE7FQC~LX#@Lf)sc%%k>LeR4
z3JLV8jET4to>C5wZID@g=bpkzHRv(gb{ck2kRGP=nW?3mF1u?wgLkAv!dG$KFsm2?
z%6d^VPsA_gp}8u@iAUO+9=Tsy3oi=en05~;-7}s?-Yt|ar`pp$D_kW(Y&4C?g}%TI
zj_1Rx@r}gxPb~;-CJufX;bKbzcUQu-<1*mtcta?Cbi)-;zO{y#gQxvnd^@LC8vM<F
z4xP0{yu+@}h@q4fodY%5SRdhy0)6JDy{4Oo0@HYdjYWQxfDr!Zs&~@BTN`a^btHK(
zKar6T=J>5Lsl=-?$L9(+por#v;qG{VPcX2jz8|HNGC%q>w&$3f;;c)U#qB6TmW0uD
z7%8dVp>0zd*<88kNXxKC7T}4sP`(*5$b2PrZ4KqmC`X?)CNStr-lKUtS``_0xb^oz
z9NsOG$B2@u3`)syyS9ch_idYK$rM?B){&z4wEz5xQlS8%jsbH`J8{UhZzc?;`GafW
zHh;f|3)YJdW(^uyiDwu-25#TY#HYMvf^L$XM}9crp>BPa8jHGDR*qr%#vmV(Q0uDI
zm+|ehn+!Vz&?x11jDi!B1oLv&@{{$GD0`8gkfkSYyH?c+Ex?TY{Rh49KJ2<=V$Wfm
zY{r7iRmbr=Yd^m-jcO^1jTnvbfA)dg53YS-&sBHq!V5m9%Ns`@s3sH|cbuV{t+3bI
z?b^0BHIynhV3!FRxJf|ShXQh~Sf-cDvGpm7*`M3t!@8q!GHdMx-l*a<C<rR(k+yjt
z*eu!4i$@`~tV=bVs_JG4e60EEe|m`lnK7M$%^#hDGp-%uTc6<m;cm(%4AZfVDjeL;
zuD^;+iGY-QsA%D|B?9Tsz7IynJz(r<a|&5-eD!VOThdEJtlDDtXP9@tx&ijWqJ_#6
zdQqUaq?xXfe)Wb0C0*&c!9C$*Gbcq?#_oq88xl&P)JpZ)E^FnsI|gC%(*B6K_xZhh
zd_xu_E(MWXULUS|S+rOuUum4bAbj;Yxq<6zB-Oq#_qS#AvU^3?R5T{a);gXHIpdeV
zUpH!U*xu_DhZd2QQ(r6ix;m1<xkMjdsjXCu88-O)jtS7vZNoMi&8+@-BH@TsdEJ()
zi0H$Flo#CO>2k~){8SmOZN2wh*s80MoUY42)i=}J704#ZAEwkUGL$53k4{-Dj1Xw@
ziH$2?XY~O!hC3Jb8tnk?o}BK;;!E<X`5=ycMvufc_T{hCWFC~OOxRcReHXs{z2>~j
z=J*9$`L%OVO-;G9X~Y#m+SiB7sY_j#VcP@mn_PaM_HGWn=t|w$Mo5)hLU5jN$@D(t
zri=AzATYu5oC(XIKt~!JX|uT|5dSG>;#fw@9d~zc$oS>MJL)?gCqYZCU)l6uHmt)l
z_DA~FFiBZQ5bP-=N}I{ZjwPa0xKY@084Z#!F_C&lb3y*!l~b@QxbAW__v3h#VYi=9
z!34p!@}hhcMlX3ak9c{+wd^(4lj&}+YC9nJyz{w%>wP`HWr@$&TF-AW*Lp><SE*E<
zywvv}H>g?AxlO2se}x2}Z(D_PH_b52F(@HqW<Hsrp7Isb0|lk+8J~N&<l;Ct`Vwfu
zhJ%JvX;BEPvXfu>aps~MD>J*FR#F2Xhh<ZW=ZNCq#QskQqw8{ys2&c$Kr2ypz&$3Z
z@_mrl3-s_0%`LbX%YoT*ViQ<@zysRe(gi$VIe<#X&fRh7@Tw?=N3us#kMyrNc*++w
zZxl%zUJioa6N>$amX1SQ5%%A3W$uoV@P1#jjuPGGg~dnVHaV0h{Y720d3KFnjjETY
zmvb!7ZTa{KTCli<@`{fR{=4|K=DzS}<R4QoZ<_L$hd<%D6b7L(kuZY#`W<pny8XEw
z;2(p<dj>+?%4UqH&Cth2(>0#>!<a}?iJQh}TPALKUvIw*5#+z7dA`gqE4kh%s;B|S
z9@6D?u5{~qQaS+e5LoI%?F&y!^op|iBG!4^vI4vaKepfDef(H9k`C*&4OY!Xg*!d0
z@0zJ__(rq~WFXaH$Qe-;jh);Jo|8JfD_VM1W^#$d7ASFBMP}e=s#u%EL>F}SnNN7;
zv(%GLg82-|Ut_^esrr3pEaK)3<%2KUSc7P)I(r0K5N})3e52vHXx?5KHszc!UzDjt
z0JR;5EckZ`_&C^C)7N}LnG{IiJQAgW=Mw8Io8%k>sE;M`e&(+7x?(GZI~{9*i&mOy
zne6&H%G4@%MBbi#WE%t2t;a<F%A#^bd5pYFNX*#RS5)g-!cSc{T6r5i@7fb(qHxhe
z$I7(Arb*o(xSpAA+FaAK8V)k%9vFkqU5M5PsaS6!ngGuWL?;)$56{}gUO}^7s+sU&
zV@2x>ou5vATTP{Fcs?;@h)BDqR#+-pQ1j8JrbOgf=kaGe-dMHA)jcks;FOLzE(uNY
zTYnbQg(Bo30*w;LbgS$i$sZzIw`Yo1S^a<vokoiBl@vYi#}_4XuGkWm#C4+w`c*!W
zMl8SI;{n|i(~6dferi+}pb1=%r@q`T?G7Kp7XPA%2y)RE>{y~gw?9^`m_-fjX{5VV
zXT)~CMR^J^Ca4PeQ9PiWS*mCH^+4qaix2Ev%=8P_Ep=-1<b5pT8g*}vS5(jX2UNVP
zdzcSRF8pk?ulI2967wUgKXXT_JS%>ntoQ}xv_t!b5>dIY^ixssE?p|zzptM}3KDe+
z2AMWN`~wJrOhh%&-?A`&d6&N3>hhLD=n{5PD%rc7a%f}wbku^j_=O71)J&2Ticr1(
z_g?Yx4DavZksj~B2km$Q7tD!OghdN7=gPss1eLg0al6x?fE8h_T*dDTk>wk>FXjmz
z+eYRI`D0PK1|0}HbOefhE*d;mUFal>@@Fo{I1H$kU%%}9SQNmtJI6Mc3V*4Nt3O!P
zS@DN!n2sIXg2lt4EX<@!o>`~8Su@N|mek+V@>aZ?iu-JvWniHA!WU>8yD=QBq|e-r
z^iD&;NQO^2AMI_~rlxHfqBDB4q6^=Ngl@|s0XHm6=7=6R<|G(exdWe5|Gis7TM0{4
z&s*&+h6Wp_Y3ySNc+&|DX_t$jgjtoB@BrR9Ut#JZ<X2|n8WnY=9;peS`5_}iK2aLY
z)eHmeQp$^ap&eaxnYzG<n6;-(PqJh0Sr|uJG&;=6bT8Vb#DeOeqrLh}CUrDW@}BV5
za=A6h{1?8E1+1DHXiHN}nKz=}oLK%Mx5ZcZY^x7NW5`s+&9=R8t{axE-_)(LOx1Py
zEz#N9uxTC&_9X|L_QRoE=K#3AdZ@if7x#Z?p6B}0pp3i02HHu3Tg^gI?GJoh_bs>@
zwGDV58Kz#YF=U_=(kn0A!h(jgp>Rsm6-jLqHZ51A`D;}5MKYT%N6)CC(E%#E`y$`l
zn&=D_tK6r!<!L)6K#5>(;F?<Nmx;7eTl(595$>XG^NtTpba1A{T#2qrKe@-RH|?jO
zlsL~4(;Fsf)Qcu8m})c6@7q8cOmj>S=-;VRiOJ|O&9y@Rn{1zO*HlBH?_Yx4+ZsnE
z0tr-6UHen90cx*`%XlvB$&rtpfN-*;7kwYXN@$)OGZn3~t57<aZ`Ju=Z8Pk$^Bps)
z5m^9Dwf0tHTh?X45!%$fZm^M$&Cf)g&n8q#<HWxhn7k12d>3-4yK2`vM;mz{KcRdK
z#_M+evR>B3wJG!FNW~OmctK~Z{wK*}`_}Vel`A!7ZRrM#s5xD^hRZVpk_Bj6AYmL2
zJ8^^Ulz)7kfaU4Wz-eAD>LNmD&9*}7t_H4rdBit$F-%#jWiVO&<^sGe{P~@ZA9~yy
zB{nK-KDuY$Q&2xN@^t&lsC1QC(%27+^Z(X^QE5RGu>pF%Ulb|DM$Tx5Ab)M!>A+lc
z6M|4q-II2}e!(H3XcRhJx+NJ)*Ck@!<}Ew8=E+^Q?Qkf)e==hXG_9eh07Nx^&S6Oz
z?r+-@$9mc}?`24%f$ch@&3qE`hWuzWO2rkkbBWF*wPHJ_J<<4)kDR?G0~CE^hPD^w
zrY9@8V>7q0v+0AYq}<!k-ii)*@KLINeq*y<g9~$E8X82$Yo{NB@MeuDp%t9o)n%Vd
zwi2{@-9|y=Q?AX9IgC6+MuCb>o#Ep6#%CWzohv=1`lE(f3?sE`TnOpim#ejw;xEiE
zNnpQ95**s!CmF-nJJIn6KlXVI2v&577tTElC0?dN@TL6$TFQCO(kCZMXHkrte9REq
zY}2<A`p_;EfWZ!Q!vHDkDL81yCfTr!zdSi)1vfk}Wp6a)$u&Ys;)ky9NQC#-<eT6k
zO8aILHrX`<sj#tv&LCZF`C9a4Dws-wO%Zjct}=-jE8V2h4F7HwHG->XEqk&wA$pi#
zyrpG3Ri+`e6yhmEzUABx-q*)L0!bYzHL?cNif1i4{LLq`F<)EGr(Vq^v5DoQrH<Rc
z`2!7|#4wXp*__F6(6+vr_voxXgtl!*Dl(RO(co@wx_I7qOi^2y`#d3Vp8W&%%ka=9
z{jcx;^tRbgxt>6V!E!x!->Y+Lew?Cxi^(omnKrxk21`^=x^5-T{1y+*a5Q<|#SU#D
zJ5Va?$(kIyxvqR0aQjS6w%f{dXc9yYkGwQ4nu0U7lfsA&dvah<wkbZ$7`%V$wh+xk
zy!UoNEngw7iGwZtWt#u=^;O<kp^%f4u%mIw5vAUx>Q*O$KnkFnZ`U1LURLr2*8#QC
zNvhEmyb(ksIMI!Czt^<(@rZ8l1+K$>yA~)tcLYh>GR06h4)A0m%jo82qPt03>ql@L
zH~2PcLL6UGkM4c?$~BU+sg4>See!y$VsO_!rYvfu$iwZ#5#FaPNayaEb?$^Q)-`6A
zCCOe{vu+1Ty@Gr5MhCVG@(1P@&6%Sp1)nYLs>H7vu=HLfLf{M`hy*jAn0q18k{0x=
z^0la<RM-!p8GyB`1dLz0q}60Fz%Y_D;#HY3IbZg&BD}`x?xm~ZB}o<Cvn1st8^!?u
z9~Lgq-~x2$dQc2Ts7+z;+BuZI73*i_Sr3o1RmD$tM>Y${2^6h#W@N=A_l#gxr!+#c
zzMM}f==vrk;5X<ORDwVIJr$jVQt(69L&HVgg*v2>HXY!-g?5P8ik6r5>)`N*L#V?u
z<=fxBf?Pi(QFAdI`gp8^w)W_<XGi*d&_B5XZ5sJcw`NU4PJc`QN`L2%867c8vrETb
zV=`%VslDfi0+DN&(or*qwkDF_!681@$L9B3!*E}ZLv(v|5KK#W?S`=P36%-2bPx`3
zY#4DN!}*90>H$&{Mxu2&0Vkx+i_7k=tLojj$C}^2I)p`{sJOJp_S178V?tYY?~Y@9
zvN)if88*xq4YBPB`Gb)N_7W%JM4Hx$qiH<OQfX>BmLkD!$*q7K@Vxl**HE^$Z#$oS
zza#WT4nt5c*72rSQ%!Z(8_+hV{NCvM%3hB@h*h$W|00BFGOL&v37vr==hpf{K}H;!
z-GH`rB~5{{^f${al-JgIm5U{@`YMIg`E0BEOKrt6B_??2V@@i5NqSz<KK=y@wAlSk
zx5ZBak4<rX%~jv~om}~3s=xvlr*cvgTiav>p^<^=hbfW-#ZupxW=CM*US6N)F3!eB
zxiBVRz{b6=z=2E_BD*oNbl2oM)>1P5UfHtS*U~Xr3?tm^hARSxZqT4lQtccwRK|s|
zROlHij<-FV`Wv9c*=!x0Ttn&OI6WcEP5CaSZ;GS0)ADg4Gqc107f<IHA7>kF{fTWm
z6WeKHH@4Z>Y}{~S+cp~8wrw<Qn#O6|=$$<0ocG)O=HuLZ_PwvQ*ZN;Jo}g5l5i5eP
z@)Z2o2nX{WU2f)VA+<Wj9o9sKllA2}>E$z0aokED$>Z8z!^-P%sWm(Of!`oa(C?QY
ze$U$Ox=TzWTZH~HW874X{khvH(Hmm&F;9Y00r%V_JSHDa*|CA>w8MB280BV}<W*w~
z6p<+(V)36Rt5XdH=A=z4L#K27$h5iaf?bxLNYO>v8m%-v?_b}fXIe_YX&A@YyS=bR
z*_2G0N1QdB$91}R`P@?c{ezfr9&^zJ(>^2RqND?kMR2vWc}ffGNb<<}p9tu895wR0
z#(4eTMh!gsZ2qA8+{PKEENr4+Li)TkzwL?4?j0OS2cSmlRDb9nUm+zVnW@zgc{NZg
z_En)#`n|JYtu1U#v#s%l7z_vddrfAXP>EM_>FdFd;gnqiQmwtvU4B#Vz#>kqa(|WF
zwVgoqL0LU{0d|drb61jgh!r7&{I$1IvG?6$^BAI)iDJu-rQUzJV&nO%sNAs-uQ#d{
zphTScm6>~nGLf$}iYn7XvB%HkGTXcu8SLH{@-ULo8SyTK%KmXwSuX-=!4#W9EF<39
z9`nKoM8<W#oFu*T+KwgmQ?TK<t_plAcsT&;an<1LRthBYjvB`7g;3d$yt9=@I^P>?
ztHHoEeC`8`I8d=|btyx#Bk37>7O1Lh2rN4Q!a939f#Z7hU&Y_mi82;J3jTES(VJ!R
zG=z*Ognjc-OqO<%<Sa!07Ui4^9Dg^d#53MH>0}GEMA`hf{2shxPmkQ3mCVNWu^hqu
z3Htz>jc;mxPx?{sSdbP<o?wg9W&pYNF08=K`^K8oN!n)Tm()cx#w+pMe$FuwId6|m
z3~2QET(Biep&yJJ;hHh%CC_LL(^HdHjQDOA#*mYB7~Fz?gwfkXAgc=<-272sAIZw5
zuC2ZPnRS-O=+wi9as6X|aPH52^bMRL-ju751V40ee=Ix8&;qxqZO@38I}MVVJ@fvk
z<x<>Bl}m8D50fgwXZ<hM<w|n~-n$MFI)MYqnPliKq$7{Dz;9ymCY`09M%Du&Tv1Tn
zjHqpYZMNhR9C&rbGvr3o@`&bF$&aNZ;oB>gb#YHtwse7hX=<C~lOtwdK+=uMdTY`D
z)E52%9%o}$pZ<%lf0(^SK#wQvKq9r92gW0Faf?!MJi(tl%l`ogki-7`2RFD$%=Z7B
zJ=Gv~cC&cH<@)`#%#W?NTOk*?7RsPEfrB$@XUs0B_xWnu_r&T&-u<RE_{F_$!`)>>
z@MqcH3p)}N_4b3wH2olt+gxeW-G7M(F!mr$f&SkI>`3cACFBNP_SLRVEl@Um39Re>
zmsa$9CHybk24C_&9){J+;`$(Po*T+*=W4$Bx~MD#9x9l*n?Z0D&4Hli$fnqK2BH2M
zjI-d-x%u7kTCL;eykh%A$^QvQZkJyms}f~N0o*iZ(f)jfDFC}iSV#RcLmw58xH|RN
zE*9tt(Tti6tKI}*z92op+JV;s1&u2IpHLN=e;b{j!l4=s%Ss45<3QP*iYCVhX-B-<
zGelGJJk#x^ruT(83(~%2pWHxRD;sH_Oy`d9J7H7)&Wk_`U!pMI8sYL%A^sZ9AvY-g
zy3!L>oocNjWqVW>F{XP1Z#vVavpRh|8eRU!bu7jVi#4T}1XZn<_<|?$k!8CBEC{C^
zZir-&Ep|!M-mDn&M;6<HsS*E2b@*7Mwl=G||A&*=w3alG_{Dix&GrC2-koXiTxXnA
zaJIm`V{e7$`alTEn|FYOe$RNnS+&{@@(9>|f3@J(y9%l!^WM3RoF0FZ&zGa*oc;=_
zwF=Lq$^JL|&qKA1gg@Iw79X0rfZ1Z{Lp7z=+|18XaPaJ)DqeY#*=u}d>#T-jFGrF*
zbnAZuh=FAKLX~qXaGA#QMJe#L8gT9lGsm*4e+fnu{|{Dl3!!Z9Z!!AuU>|^=NjInC
zAzZur;gBD!vR5vDAfMd9YVXUKb=;6MM9@DAD$qj(&xUntys!BWPTj0^>x@pUO&<|x
zY%@uZj^_fA@>6P0W?+8iWdG9swo%+)_-$&ap;WlmfMrOc0?u;O0*BneeJ3Ll?OUI~
zr(Sz;I<QTbFcE95mIW3@*_QgQ#VxV)yUBAm1O5+m*^7^4d~za=w~hJs$H$La97*om
z&6a0SEBbJx{Vz{t!vKQ$MqV&&R&~==Kd2=XmoR%=r?lfXPn-?9vYUp)fWEy#i?cE`
zK(m>%Rs>pT31CezmVoy@(mhHI_|Da{bC2$C%&(JRBL8P&dO<*#6-CG+MJou|InC7)
zdk?hpCkol1i`-=Yi@<}$rfJxBK#K~{<u+`$wd2`W9b@*3zwAkO7tNW#l(TdKCYJ7d
zKn6X|^1q;wE?D!sAO*17{X^0itNmfm`Q}mo0T}_;NrotX<8xgPC@~HE9FW}7{vz+K
zF`$Kf%uJ;CLF63YS@;i}i%6JeQK*@pmYKM8>{WH5(_vXkUq3m)LQJs#n4ZfRI&#og
zubw5Wc)(E6A5@tey!i2t-Prx^gd2(3^}3`hHW6}<3!yVeBt_fB=A1BY;D)AI7=1ea
zl#Qt2IXHRSkA77bPEGO^h(U!qc_G<v_oF3A*IDLyjgb@O;MHjnY67GF%Q#ZYtmYu>
ze_X5yu3_W}Lc2_r|JpZZ@1IrY$X=j&uRYkNf{AGA&<HLe^^@0Y<03_5c5p$#f`f!@
zvCid}^yw}fUBUFVKk{dOpyfev`iY_psx<%E4^+hSW<O|rYDsfsimRbbBK*cf;1XjD
z6jiq+Vs0YTQO|m?!LLs6j7#u-eMlHG`J^$xHlzFL05@)sp`!h-Wc5Lzv<LA!MIL!c
zBk-G5w-lX=O!d7beNs;J5QAIC+ijRjvaCV77{$li)hC_<9p@D+oPg^FY(#bMjcvFv
zd3GxH6utw4BkX@VI*LLtzN_)Ly+KKQP%&afRpO*z*daR2YU4QQM;-)ru}x;B%}s2|
zjpJxI#~lBSLl%|NP939*j->$3p^g_a41B<6#uJCLO3G*E@d6)>SO90aP@7gm*S%lV
zp1GzuXlUl5+MR0PYgZC}<}32OyIzGa&#%Gf5`w+qr_01aSwY9h^8bZtsg%+g0wuts
z@%7J9DL;9(j+EmT8zELqA^9F~yZJi%L3o<k*zpDX$AYTf#BIxUX|AN$_QUZyW!6_-
zcvh64i$S{yh@Zqc&2Y1>XlrB>tQ<@tOnj%|dP8aujADb^c*L#O1#mmu>`k<b0#Z0f
z5uOmkp?4q*Jo@8myo7FLtBa2_giHTSu${skI=rt3;J|$QDXw&lDeIC%lY8NU6m~D;
zmS0ICg%!&1Z{a_m5^Fm`3xT-S&$mz)FnwT$s{^>-BsJwBt#OXHdY+f{h3JdelFFmu
ziJ|QfXyxpL8ME@f5=NC`IOWf8Ij&T?RP<wX{&f%cuw{nn?FeEozIp?ji}wmel4b@N
zKkxIFqA)0pWR=+@o{e1u#{g;3Gu6dXP*8Gfey{k*UlAG}!ZL?kZS}*;9=E({=)Ud+
zoJ#uSz1FMgsA8<YT>8E86l%IFSvFfk0poh3V>^|~-=;o!nxJUu9fJ_I#zU&0b&1i{
z|C=6OiWKslv&pH!(~_%Qx&Oo#?1gTRLuzSY|CL26C75FL-+{Kd8S{S(hv49)-I8C0
zOUr_BDXN{63jIW5(A`T&`6*&Q9N;PTZ8~({l@b4u?Q_uFjq`E4!V4s={xDPg;_^0M
z!{47ZQG10fLdBxFzYFou5Q*8VHRl=jIe|sOt)&4|JPGi%yIi>RuSLhf9fWH_Z}BXR
z1Dm>j6~wfzE$AmSyD-$^Jk}Pz=bQ*!z+0ZPWdpY3Q!v>B-uJ_yjnJacJ#%3Dpib4L
z^3aP<crdEN5B`UK7!koUzX0S1(xj-_$i{e)T8?<H9+&C}qcg8`97z$t1HEW-q<_9k
zG$JctGl#8J!0oJ4O9F3wz-w0M68J3$WR&}!kLu&us`nm_XLylmUu1_S3iGTpOp8HA
zBj=$h$G}^6E&$iIFT=CO5*-^<%VMTQ@>Qfy@QX)+Gxf1b4Z28xLB=}2v-9=A&4E9c
zdr#EI-x5}k%e~frwVnX(%^2F_U;X=2qtL5U9sAS;S~}4!$50bY<unK0U--Mby#MC6
zlMfD*Jl_}k-A7qZD@Vq2qs%wa&)$dQ0?6?5yU@mxJ;j9RH0EY1PzV-p1<zh&?bw=t
zYzg&RWS2_9tntsvqtMm}%{v(C7|A-Wb*)s9YeUkTGNj6rhOf2A5-tasx+X!vvyVtp
zqGZ0__^Ka|dqc|lgE;xRjA;1Y3U~R3$tTA!YXctmbc`v-QT7FKvc`vOYGfJ<S;l`B
zyv_gbr=~eT@~FTwTWnjhgo3g$iNQ&Cbu-&T&C|%l@8T)PQlcb{y;vNXJUPrua3}tU
z5_3d*E5oxJkoy)&PY|t4fkL~{Z@nu9<bW7&5rm3@%{;x|rS2bHu0uh2xA)gEuS(i%
z_0ESlMNG}^-IZRo%^1HiNu~Qs-nJbY3`ZVk_yMqRyilip#LRo&p7yJ$e~a=oBPJp8
z;60?;wyBa7LqTj^hj8DI*N9rR%=u8@Z7n`1MO-geI5%hIx;SOCN&=*<PyQq}j6Qrh
zJEK20hCT2H@i|8qv>a!s{$j%_$7<7&uP7`=6x}qzA9z((e`&9v@rX8ucx~C^9Dd;F
z-40C9Fx0^&B+{TB3-mDMVePyCgEz&9aqyt}kD0>V8nWgo{<*1`z9YvTGe`$__;b}X
z0{f{kLbr;hg2zpJ5IoCHztX$!qY+p{gq(n#R|SbjjKOcA**_(u(QPPJDP=F)UNxSl
z+0gk0)A_V1Q{WrSmL+6jzk^_*JIN&k9{ju4Ze#LIOjjbchtG5BERPLvP!rV2ak=b1
z7c~>jvY+>JE&O35GY)1VPCMbmn_l~vH{_&}l6&VId+d^lGmYtu_^<E0ZCQP_7Gl~d
zn}HVnzBRwRQsDlz&rBlW3t*3NpIqFjMOiEVr+ZcV`2UecB0FCJx<daju$}q=wfhCZ
zVPW&JOJre>V&do%zar!&YRm@36<O8SiYAD*X3vw`Umo=A^i)XKu~0(4Eft+t=A4V2
ze~%zzWnuqFAijUKD{W$!{2$mU2TWYvo5COr=y5rPJ7XlA3#yr<ij4aZlqz|)pf@+Y
zOxluI^T@uC@5de8YHhUN)pDm4NcX9g#Ptd3MW-ZC0=qpN+dwz94hl=Zbc?xFo*I4^
zV`YYm>6y8vR~}l=bO-trV|41>d>?1eiF%0WaIM9qp_b=NV%6H0iSFPyS0Xl?K?<f%
z>;6@5+FmoWFuB2XLB{gqXursBW1a=f=9H@>KThYr>yU#pen9}R_Nspc%i_)L{G~c=
z=-LH*#lM_Fy~yZ>&o8T_eef(Et<L7l!N91G5xV)gOKGwX0`CbHt%R!1Wa#KBB(;Vv
ztu*&tq9Dr&2={oTjo$QcB=H+Axv)<z^e^$h68=`6pwp4zsozmu<{Gq>CzR@fsoP$$
z799TP;iWK1Xot$=A&^0gguhR!2Lzf5(CJphcWlhF!ROpAhhh3xzW2xb+LqMK(d}1l
zoT?{nUbF7rJ~0Y48*Z^OweHqn1Q>8z<??<%k)>!L^y5IsSe9Nb7AgCD1Rve!XZQ&w
zG07Nmd#R<?Ts#oP!gq>n)InrhDD|iS{dY;eC3TP?UweCf%oy#d5NgLv=gdz}PD*<(
z!$dg36)s<4{4XFyw%;?gw+F$P`voJHgw>}kE6IvWdMVe3PN3*P6!InGzC8bDX{ES#
z&dRigHdry#h-+@1E7|@(S{ydA&<IQaw!P6r!7+;(gX|*4$N#h>=&yQmV2fYB%>#_Y
z*N~rt=?fIOj?5vH-kbzZEL*9nwMprKW$?7=p~E6xEs*6n9$}xxMAyzLvF}3Or61Oz
zKD?ct5_N`)LiuA*+H}!V``=A66R4sp;T=l(smK<+!?oyoE25Ny0t%V|(d+#zRJeHI
z#Z-(~Y6KTz<iYsjsLx@KM)#UlwR8)*a#>|rO725MeHTHa)>(j^f1W(V`-x6x2-czW
z`{?fhxAv!Bpxuz+y>Ni{+G_l2i=;6eFyKiI_KQCMx9Wr`l&?n@_>eA#=l&{tO{JK(
zQ?R62tC`K><Qy>&hL+J!w2_|!D;+_0f;+1CSV}Rw-zB<udY0F{-eJsNytQ`wAhz!)
zO^LulB5Dq<g*aD03D{LK;BQlnWFwhCAmSt)3LXc0q=~q}?-rzsrXN7o7I1Zh+Ydd2
zph|Wol3?`*(cyzb)TK)%HFrU=9kqJ&!&Ii?Myo~U7ikrxgA~-X^LgbzsJJb@d!cal
zj4*{CdNuOH-%s-@981LdILSx|Xh$ONBd6MHnqo5I#w33JXE?g(_D*@X{gtEpglPBS
zPwgABWc?AZN%5!n3?a<$ap_YS?UQv9HNwf5&)_|ceBw!!AQt+X9$`S8K~P}f7iGGW
z39|S=f$GE>1bIK^6*FNNI6F|4OP?uUiIJoj>|%6FgML6tnWe6XRKd^i-%3U^yZ)+t
zzT5M;-cW&SG-}4!s%Lb*AtHH%e}uje2pKBl-$qSwJL+MQe8y*Hp`Crrb*va<q?zV@
zp{n)-v*%pkngd2ZFHf*wW$zl<tC{{lr&*&<RYBHnYpToTxek&VU|yOb;YY%Ot_5>q
zLdBqvVN9AP+y){O{e)G1^gBTg3L@MHO{*@H@vYMkEEE#ySwcGhSk2K0kiQG(`K<bl
z?S*Zjp#ADx^+4O7D4~RX_Pdg}dw14r2R5YTrc+6gc(bN8XQ8%g!#Oy|NK8n?W|-q#
zIQGhPP#MecQCqwzE0bLEY-JzOqe6D>go~e6X;->R_EAe_5xi~<g^>I%2({EshPQZ?
zqg7q`KJJ-`Ew_@pgjdxw%^FDuBc1*xZ?CL?02Fh|@+t)ioO8`(jju_#kJ1ili<F)}
zv3qfX0y4?x%GRUD<Vq*gVeLNGm<5ffMf^JLGTy@dO`<5f+n~cOTK7i-e8OYEajPER
zcwdTBtaoncg;}-CR9D$}|J~&<SSt2rkO7@#IL6hTkS(UKEw3@+DAn|N2tzG0x%};3
zq(hPPSukCiVoKfZ$WBFC4Z~kT16lk?*dTOkDlau`A35q>>vt?<T-4oudqj>0_iJ^r
z%^ta<OHz3C7~R<gxwhc8$=AWfif0sQd;@t-4!rB1N1tZw%vJ;Q#g{nUU9RO}m4FZg
zAyq65QhES)JX{Z{Ni#R2DD+p%VF{AeKm0F~WI^4raZpG0@b!F=p19Vhj6EF=^o$Eb
zXc|+ZS=16q!O(TCfN8+PcM{;XpeJXaC{tu`bW8HhXVw9j^VW6oD-zY`VJL<(rp`k1
zd@%MjAZS;J!%<BOxRK8ho~&<AKa3gksmnB!6%w9NTnGi<kP`>tpq!4GeQ6KkmjxQj
zE4raQm~>p!E6_%w{+P1OcKi&l=U9I#3>E;`{h^g2j?mW_mNaowhoR)%=^Kad=CD$#
zG(K&9C4$BI-kZ4=;gVe(7=R-acOKH;rshN^yFj*kb~~X~ZNSoj6}D4va!Z>(Ri{>8
zf>ama0j0T!TDzl_tv%@Hb7ex5`}5D0fsWr&`#9!El`q8kvv`gch<?5_;}ae!vKrWm
ze$d(6J5D<9TO@IEZ=!?xgPRO%=Yi1H?ui_X#=-j%nd}Lcai@*sp7p!D8nC%pQkou>
z@**}%vfAu8S$~N@IQN~wOJqER20dIwSV@xlbL}JUI5??+VKXF8JxkqS-iN(Dt~wF3
zG8xQr`rvdZzjC>j$TZzmal4#%+U&1u=pbS8h{~%zO6ikagfsC#Y!2k0MoLUv0RpH~
zX!&A#g8o*;vvMNCrCdU?%Q!cwK<N}AsvjpdIaC+H%<F?|SJN2a^btXHu8{t0@XJMf
zyHVzMJWgDeyG@IFW+JYNTorU?M&Re#YJL5y2?43p4FYlSIx?42d7&p*(J^hEmqju>
z0Q`+%I|G&?JMA)kX3LH|v=5++iT9Iz&Pq}V!=|ThP0b@JgU*ZC0S;-46c&HyP?11n
zLfTsxuD0jQ-dz+^t=r0jP(hOq(?T)(-XIKEk<I@f@!R`Ne2MK2&Dp>ja?<RY=gA8v
z*KuY=7;}imJq_QxoZe0V^N>UFWS+PR3e0|lVA5`@Vv*34z-QH#Gazf^boxl{8joqc
z{GizVhX!8v!rDLq;D#;RP2`?{pKq+a)ycu8vbnC!z@+2|h{xom0cml5i;c4ZNDVjO
z)dwFH>$ysXWX&30`LR!*(6J1RQ3_^ibv-NMe&3%SCB{sALK(28Xks~MU`_-8%^xga
zdi|%Y4_>=3rUsV=qLn9c3r8UIalfYEF!77d*UI_v1q}t#_cLwtx&-%LHY<cP-O=xL
zH630Atv-I3@BbOCByl6bcWn+eTB+gVqYjHefCT!sMPHJJ?H&tF)sCliXZK;pCQj`!
zQmD)$0cl~-O4kMZAm`E>uY5-t%fDx?qD?7bH6G{|Ju`14u9)Mh)TG;unYaO7jG}jD
zg*MI3uYwzE=PdUFJbHP9pUfe*C5mSCd8f8iIL1QrK}l`BjpgzIpX|vF*$l0JpHr5!
zYGB-*yb{XjLJU)<fxRGWH1}oU6fm_vP_#s1h|_ri_&v05mGPkHUPYv_z2!>8FE+bJ
z4OsQK0T8I-@Fs@_ri0apX8S6#8&HZSIgb;m9^bSCO=Dg}*(+}^^wt;H`v=%7^9BKC
z>?#Vv64qH-RbX6oC`2gz+%1iq%;H}X=-WH#5K+cH(uR0tCFGuQ8rXMx1idS3X#7~_
zaJT;U(?yHg*c|Z;s4V^>VyJ5mdR>{lN5f~9fw7&aP|m<~ecbQxz{W9AJT>}$egpig
z20h^2ZP@T%IsV>%A=Q?TM?|Qnnc7i7H9orYt<Q>Y<y3A|v;aVQBldKV8ik;yH9`EG
z836#<tpFy8F<=iPN0o%*il&ca<}_T>?C8A1-Qh-W!keb<K`sB$b0U;(QfdYEtS@!t
zH+ru9kdLqzB-T|FJFk9w)8+!q#)h2sC1dvWfK^?cMy9Ru%VQlj?vn2q$^-)&qwXNu
zwevbU@jdYc4Hhbw;D8Y5Ukzik<h8v~oT(N{;*^Vec2<p+AvD$$pW3ERcFYsn)6`^%
zKMxMiPDo&Qf+frb+pI^=x!H#D{<QbxgIptA5Z1$z3q95djG~WqqC^f7c8RN5xj{_j
z3N}v7G>>|m!)@((0JzCUAPol+TjgTnFjP2ad}eQ&oW7BU02JYKQ@_T-mjzvL-4c&E
zurS$Nj94mrRJZectBpAy_DNRC#A$^G*WILBGog(}fl|>MFh!Rb@Ii+xc|5BeC}861
zr-r*dtMThI<J8$~+u|ycv2w^@QW$1E4*^}=#|<0SCad2@P*iAQ?xt^&Xd_YUQ7&-V
z=-{(Sh*`{_2ljbvs2FmzcEdipJj59$s(P`?dMPvg04GU1VVWzOa}uE?KOGf}*VjFw
zw)4WS7~)fj(@e=JJqBjf=sZ^v^wxxT4mVAw3&QY&D66b}ng>raiWdBz1MZ%-pOr-w
zUcyonBX=ix&jq@1b=jRh1<jjtlPO-MyUQcXp?X2e$1W5Qofv>$LI6dX#93n98T$rY
zn+B2K%3|MB;n;h@j3Vs@9m4dPfDowuosz*%CoHXy+cZ+OqEJ&))^9^*FA+6S_gE@4
zKV%rR`S;4Uo_EjIMe^gD!%H36smQI&axV<Mm!$1h8ne|dtB=<sjJAV+R>MR5P$>c-
zi->R!3rX{$OZvr|4nS)41jC$_qxhgZ?jyu}ZMdu@mcQ6|WP!^*OBmJtSkrvvUcCLK
zksjL(9+5%L9DL}S3TxTW^HT{S%H(E@-SQeVXzVV3xyR;pYIG)X`LO#YXY}j|)3%B0
ztDCIxP`B!ExTfDXH%AR`v^s}hq!}~Sl0>|G^s17Aa=-D-^L=iEZN=B3b1{}Wx;EhK
zzFhftNAhr~feG*Z1$vf1KF!Qc(%7v846H_7(0i)QCQSdHeuU4-s<Sk$ARU{nOvyIQ
z&_yV5Cq~-4vDWD`^E&LuZ8v<y<^-&4zwdK0&Ug=^5#b#cUN!BZa*5h*rIA9YIBE0d
zVZZl_w^}&6u{sGt1l(s+J9V!u=5)M5t~Fwf=zmX@!0ZtXA9}s8{Q^wEr{I7U-E$b6
z6#V^Wd2`M3FRm6{8pgs<&f4qynwjp2@nSh^MvUlRdCw|NYY!eEVTC+eC%JuitsNDn
z6$t06Q20=O)9*I$OeX7O{+DHioxq7o7iTyHJ~keYs1K<-P-yr0nnBErB;uQG!`H6y
zW0qNFgMpn{bG4AHSSuEQoh#3rECUOj9dACRG+r;iBVfy`#yo1L2b>?z&II#{+wwqW
z1n}Z8Jx!Ux-Jd}ZD`+gC-}R#<XwC#PC}L9(vo8f=hBWQhR%`KFv123;Y5q2omEh*H
z{`thG*A7sw`)ZtTL&$HOV$ex_e~i{(>Zd~`RGY%8h=Li7Ye02S55nC}>#<nSHWpYb
zTt>UwtD3c??*3DR>~8;3E{X{ix|eyha_Cro1e+}ee}Buo>UcG<tPLe4DmZCXXrYt2
zLVULB?NB&T)FPx1$Ig^MeJv3kit*d3+dYSZSWOK56Gsc(SMZyAcVP1y4jl$m?yQ=_
zc47b8Rc-*6Jm~_o!E9IsqS*H`&h5+Jf8qmIvk8(FEA5Jc4%)u|RgHGQFpY?@K7k(3
z7vYe?HVAcAwz2Imj@hnCqKEStIL3j$mWX&hdDg4h*+2^5#8fh0jitm-D}0-g1&Gz2
zyq|z?E-(wmTj4b>g>iafihPP_p(fN=J*~^qr!WhF^<QMWtvTZ8f4dQwWBT<iWvRZ<
zH&S)L&o{W42Hr9QA8^Q%SzbT<L?OwfiUJl3ZxfS?hOU@*vbE{H{OKpNMCd&Q{$Yu*
zFMJk_ZEChsBf?d1_@D+(@x|5TQ-Wp42lc`WgraVupZh6!#-{~Ps>9)&28v!$g8D0w
zrSQ|Np9})`D9p-Si$vDZe||@oI?m9Wb0jJl+ET+>AQ8W3K=@Y$jEt!O7AR5`8&=Ed
zT#Wq9<qR}~D3fetrcwJHQvY?Uw$`o@B>TC^ts*x=P4=~l7Xc_puR1okF*d4$lY9O$
zTfqOhve&v6E{jjJ9zWiUAcz#5zd^8#^#=z7`BE_PyJrq*8(C}<gQ2~&CDv{`oRhGs
zk!3lm2wjmknW#TKuyzh))5JKPLv?Mp3h(>HJH3_}uyw<t>xQ5UFppubx($B)cBxtI
zHOhVKnvzcs!NB#lvN<J!<`Ra+kGLH2%`(AnAM>w|=L%I)U`oH0qKXVn^J({e0zu;;
zJ%kgvdk(N!k>3I<bdWmCr`HxTm*I@fI&Jc<pGsCyqtqWXj{NJvmI@sB8$*DY=TjL@
z?jwujzVwwIUH{2zOs^g`9D+rUgG2Z8hpjdEXKZ3;58g54g56NkpVY`5#!Jvo$95J@
zG5!}7vasgFKwz4Odrh`u#R4yMz?%?~mgP-q+du;xl7_O+B^5thlrOfrtNonN&50;_
zc85GlO34iAecJ&;D^bcfm@pO*$~1dIO}I64q8?F!V05xoJETy^=2EXGcDvgj-ap<p
zN_Q`vlMPz!PGpSIJP^Ob7OiVPTPG2&Mz%zqvqaK{QWtHYiJJPL@fVdW(9-x|%2}u~
zk*g0xfhvKvq_h~{IH|1h?eO$}b=A|1K`Y1Z&yrXm_dshjkygX}(F~hdwW?bdqW>Dh
z!7u4@lSmhhzAyueVn+igOi3D6Cl_qb4d#Yc)RELv^1ekOy=y`panF|mp0($!gs}@4
z#T<?BjKwfK{CI2PQ~#+^ws$*d&Cdka(=pmD9uG~Iy4Dz<jv2qfraNRw5QJ=Sg%kSx
z&20B*|GRWF@mwmpOK0gz4b&!z;LG{yjwrjFZ8b^~v>T6!pGc6nPr6~kRY^<2CyYRI
z+*QRs*1nF4n0uQ7d?ziu4d?^>i|KHzu^Li8GgM`>1@LyaKRkmqJ1#fXH?3Kceu54)
zHz{oUQ3s(^eR1hEoBkK__Lpp*B^?S{CNrp}LWoi!roYC*vv!WGD!QmU@`)toRCje#
zP{x6%89=4MA5>&2?g8Z(5Ta_5bJ|xLIngqKJ^ze_h7<r*^I7^jC5k~NZUPxq+sYf*
zBI2Z2rHkSGojMk4ykXvn2CX$=mi0*vY!YQyr(J>;1pOJzgA<j0o>GT%1wnxM<mO|C
z!9|mAM71}u>pnrOPb=+*@Up+9!by$*f3^FFqYZxl3E94#F=88_5RP^RDs?XiF!}%B
z)n|L8R&QskKy~sCO0T}{S?(>b*D7c0Ge{*&l0!U}rqNC%KK=b1xV#y7n2(xVtm_KC
z&&)eBpW!%e0ioWg-}+A}6Sprjm$0nsn9&!^;nEi}2}hUdXTVaYcyGdTrhsxRR2xP7
ztv49j8O(mLphmwB({5r?q%WU}S~_AQK4M@-SN1P+fX(Jbno~JE8}~_`JPL$=7Od3j
zp-UC~Y(U|skH^=M=P1O|uG}-mC~=Y4Kt0~zzIU`e@~kV!*say<%oFZR<zril;xMNk
zF>pFB!s`Cluo>q#z0p$wlIEc7Vhjz_A3KzeI`9<{o19jn-V`YS-%1!HDsn!K*G~~;
z^ebo-e(3wiIfVwCSniO!%^b_ac8%X|e`O0<X_Z#^KH?)QwIM4ur%0KHyC9Ee%qP_w
z5oh%5aFafI#{sl(K0d?N39Mp4RCTP8ta{PH`gjgsUL0-b0G@_<73e9ld)O6`;S#NE
zESH8-vxXQekS7-ynx|!#MmNvy;o@lmgf}`tbLZ{K*HIn%7E@q|f|yrUjWU!Cg<_Es
zHB|T8ZV=BFgS?oAy#Jmn9si+b7f?TD%?8U-O{GaQ{CQo-p2p*5XAlX~b?pY<AiRG9
z+);=1fzXbUeT`y?KIPG@AO?D8a%kfd2TSeowVo@q#l3W6FUE_jLh(v=6ijQop0kHg
zG1K*s?C+y#)eI`cq)e8X%ah?F%Jz|bil5kd8Ua6ctK5Q3Dbg`_X#BQ(m_lKraonPG
zn0s%KG@j6nqkmmajFrffGlwJkA^Z_>9*w++WJBpCtjNDgxTJ(@kJ5MC3$%4S=BFJ-
zXf60o6`0A>VDv0!+0y)A%UTir3HZs`FgB7w<1kNcFQeNPqmJ<(v$P1MraE^t4;eon
zjCi0Mg|$T5lB`aEMnxaAmRsR~Ua(=E?608B;(jmqeOS3j7Wj+T-d+KLQ+&1yP-G;4
zcFT_;7BUv~2SsAg_7hUCmPd1BK+aXcErLk#V!XO>-ZPG2ax6U*QhH(EA3S>RKZ*bn
z9lDf_ZPRg}t4-57y&5tIW-XfJb`^kU;@YI|L<W?~LvK8ZPo&Guo;uqOYl%5rb+Teh
zGf3&}Vt^TC>_SyYZ-M^AXt)7T!}e#Tti>pUkoBu`D0PYAN%9)oj!nd%s*y8$tAkV!
zK;r!(he%Imy|fb~LsUfBY~7Y;(x7Tv;ThD~m|dv)h@|IDix?`lq66P0vl81l<1CND
z%eyjU+C4>T#MXswJe>8OIG7UYJk-xz`jZE{l6{;_uW9#!tRhN}wAq<~SiTKA(|taP
zf$X<M_5fX)Yz*otdw{4SZ;6vYZoy??cA>CNOKa$!Vj!jPp4I!kudIW)G8lmne}TX+
zomdul???Q$lX9g$%>j!c#BS%>$4DBw#U9a4)A(LYH0X78uYbGD>!lt#>L{sPjX_OV
ze#`@p%r~erKw~}*yFBLoWzYd=&xFepR8+J<A;Nz4&*z6GKxTYSas@gUxA2BeOPNIL
zS2(nXqCAX++(?Rjx^!TE>^H{sNarKP^~+!qOBo*L2AbBqe1z(wHnk@dJXy+<R``D$
z4kbY?Tm-OG1ZY2Tp{^x@a+<(stXa(~Sepd}J}ay`@1s{R$pk%KBkAu-ZAPc)6=oYs
zNuzF%`?|W-Hu#FgsPI2%*_}5u9ZF$!GXjvpS4>~sv=`)wDMXI(hs9bN95L~M2GTh~
zlOxok$}Qn<nhj5ZrGzHL>UQy##REsdVyaPR_{uGxs6;j4rXcfGcT`w8xLYg(<hE4z
z`-6QM=VNuHMOZ0m6_JM$?>ICWXSVb54>SXdPD|YPD%ge>*#`gGRa=R2ZnGKlb}{Gb
z?>1)N%SQE~){Z&+&HTc?*3GxlHo%VwG%T$ziqw%-^L=QO=L+c<V~*m`Gt%39IIQXn
zW3&$6AeL-z^>gEDW#mW1S4|%0l6Fg03b9bEEw5HI%R@sk&HAO9C3qATq)c*)I}$E8
z1XU4Tv<5pPH1s&@f5{zgtRb3%1sxF3x-rL4VHs#rxX}OkX{;{#vsNKvh_>t3Q(9%R
z2beV>P;wEvmaU1ziwe(x`fLA)B%Ae7#VHU@AVOsjkV-F8w1xz8g5(L}vXu99Zq8nL
zqunLx$%Dm}6hUVcd*mGBTlM*L6B>lZm^_-mS@f&azn=am2P2qFV?^Cg@fRZE-1>5q
zSt86Z>23_81^fOr8tF!(A`C@9b$;`ylkwke8LK(ZcbG9Qa-)u&&p~U_2&iKP@BXng
zwzrf6EM71BGV>%s3{f&^l;k3?xDHU^f*U6(NvP^C`xcRyNVO6%1dseCTq+Q+>Deu?
z5qIfq#<mMBEpXB(Gl#Av@~Jf1XbL2dD#W{jigny?Kk4e2MTsvsv3KM5$3t<fY;HH+
zqZp1dM9jK<<km)&W8``J)}NBOjdD-%a?meHhP=kSs|5)OkOpH<Y{bKwcTIMhZdy<z
z$0OU9|D3#6BB(J(QGpl_L7=fG1{ZwO3Q7uko?s19$F#&<^PR*qp1P~`l*BggEeMCj
ze&%tPA3#9>UaP1vh)4=5PxKfOT9?x%$S6T=^?l#9i|!2w&4(AGqiIIID5dVdwT7+{
zA&6+lg7SCECM|#3Ii=$5m-5J(Zl#wMMWsf)<RFB^Uli9)OIc+BeT*S2fVf*-cwnd)
zfMK;yhKkeJF7pVJvB=Gur=%j6Ct#Acs!Tq#u4rk5vm8R%hw}iw9ld<aL$S3>|I+xM
z#NT49=g;Yi5_Qyxc9d*hzeN+cC7&O(dinz3IbHyr_V5(<UU7vq36-sy$L_LHim}|~
zZXGgkGR<)`C7~iXxYs)5h_k5?Mr?~FW7={?<bI}nuCILpb`bv8fi!_=vV@lqP<%jT
z1jyrWW(tho=G=uMid>z72(2dIY(Yc$Cfa5wj@hw5dZ&R(yN8|yD7(~NdN<8a2s;*+
zel&CcIH3hgCbtq58`xy1ekAcWk%(Ovl}F{DQlF8WsZAaZwiN_m*t#>9QH2>lhd;xG
z%c$o=nuxk-L(cQj3Ux@oGFKfE5p(A+^JQG2Iyp1!UhogfPWnq?ONphM;Sq#`s^-l4
zM_99@*c^%Nr2CSoMCP2Bz8KoT)~%TaH3UFR8kbU0kfK9Eo+f^aJ}x4qw;2X+7fYoE
zr}>$>PU-+74E?O5;z)2Uw2w$M%IifJQg@jWm<tY{uf{}YHssN81~B8pQZ1GF3Ut+x
zSo@r+vHInnN@41`6QZlBf{C@cte}{bdX$*}m5bOvUSy6WPNtRPvx_2=RNo4rX*Doq
z=2}l!VX`N@OpB#MS%Kk|8lNtVU_5pM6ENH0(8mVQUTk(v`uYZ$2a{i^`g)Dkwz|c_
zuHaF6UtCPF<c(Yx1ZLD(+{%BU2X+4yV?QbraeiQH_FRk`!qHhv(bK3e#e!i=+oL>m
zNGTQG5{UnO?b--djRSI?xT+$meN?m2?jAhDxgeP_TGIj#{`%!5@a~7Iq#<WhcqK>w
zUNZ|Ql1Lw!fdeFpo|a@>|1*){??UY(LdW77X=0CBh5=OZ^y4DQT|({Tz#bBYlYur{
z|GiRsU&k_CV{l1M;`78uuyn_({|Z@ypiway?fFHj^Gc2ES8mZXb`3!di6~6OZb|);
zhLxK;LW_o^m7MmPMiNeuzQlLQbGbDfrRm2;jOfbEK#AbjVNx(NUU^2fGB5<-S9*aT
zz77Y4(DbkS_Q%_}L_^~($86VH^<rUsnQG{Z>RO;H?_8L6M;*K}#|-ie{U^bA<j-Kg
z)Z@x>m>c5c**|vL2+ge#QuR;tNOzwWTV2OaYZoSCWJZIgLl#TXC}`rgBkjFkj`#47
z@C8zyGUZ~U@BmgS@oq)V77N**huFjzzXMv)%{EiX#R`u*VjNr_Tr7P1A<U@}sk9wH
zMH~Kfsh)-%hqiN_Y-v1u4CsZ+^m|zh<!S`qJo%^;uEbTom=*d~c)2rV-IYs#{YEd9
zU?(DV$3N2&GXkIi$qY`Kh1>KaRR%Zo-#IV0%X|5d?06zjbhF4NxvQr`Nxy?zN<`T7
zC{$#~*k^c3#q=ACQi+S@Ad|?KX#^OWmeuvQ-%PFq3;D-t%8k21oG1X1?5CgN@P?GW
zvv;ueb8~y^j*sCfhc~5>AQa5){s2I12kLfjC6qhW@c?!ozR3nlMo@v79T2^ihDa=8
zt8|B$yo1-(E%|1x5gJ>ac2Q~@bGeOunOSppV12)Va6286A)zKA4SE^0z&V7YM<l~?
zuxrfa_uT?UefR~tolc!xm+SF2smTMDMHzX<4I*Mh^5AVmYx8D+)RC2_tz8UMfkIw(
z46pglU~v5};4n;=5%5O?Y%&~altiLTXH;Fv#{8aJ0&}tMxd1@<0`^%{c>ghY*we#?
z-!8jWj9i4)gv+F`B4|R|Gx1H1ba&X{>2|`YuS)ri4M)$v`1kb=vW<FP_mu7i)^&d8
zF1F|iuhnz_)Bbpf$G4nJ8G_+-G`Pk}c8wVx@<urOw8o#a2#-6xEJr%%S~GZAq(;`6
z)sw0?smlYg^Y)nPw&U0CgtlpdWnF)1XbuKBuS8H6oTkf}5sE0+SAVCTH)>hge8muf
z&+p!cA<BH95Rt&rBJQ}O9$}*Hmqj!6C_f`61>aD8Mcjb`F-d+_hZKscyF3(p%M?&l
zh0lwCC>H5tho-<DWu|D<A72^<?*`C^%J`%b0F8cMk2%-|KUn;nqf7IW?DWf~gXoi>
zjK>~@fx$&7A4|(a93%?@8#gfNy^p0OlD5PP$U!hRq*iLPLR`BQ(abU6StT}Eebj|;
zY3NOb8;q-5ctuROsbGybx4)p&YVWCgsb4*_c0nQbyd^>~<_i)_J4t-R{+jd<M$f?p
z#U}y?aDbpfSlT5I0bO`p-TVbe+>%nhSur5*S)D|S8?s+25Wn&7xNZ+-%M)P9Q+YC&
zq$KUq(CWm;6$qeTp}81|d@=q8_%j>dz`hF*=aXc4q=)s&ta^4)Os@#Tl`kg6=#XER
zAtwlgJ4Jr}StkIPUr%sQgR3A{vPj<!FB{|QT!5t3|B^0oGGZYC0!YtZWKVNhDUXR=
zZj^%1u@V7=q)x~h+2{4(8^YDcGozF^W9>7=;h`j`v`vj6AA}$Z)j7uK6|D1pL43hL
z@^_>-IBaCdKiG&E8W8kCc-hG^C`kwm)K0_0@x6>1HTq(1Uiokx$SeXPQ~}Tm_Wd&A
zKQAY>Ju2|$);SVHEJVLN`EHgmF`)BES)khR#3SE2x>MTNlqi^fV`h>DCpExwpeKk#
zrE-}hkDajA$$p{(^J+aSFeJ==g?E}K6G1L<`|zJ(op>HpBNqnrPFlN>M<@ow0#UNF
zWD9>2;yEV6Z7@-hm@_<o2+dgT6^t<(#1evUzXW9UoNOPXl+hkirAagNusSElcZZrh
zX;Nb*^01ER{)K>z!5oZC=PC+>3K$ijYS6I3u7*}5n{gdPZJ|I@Gc61;J;PWNvgQg?
z^!>n>vq8LI9C30sHObW!%0LS$zHCpJzN<1%3$6Z2d5Yw3W<5XFqveoSgP0re%mzEO
zq#;XUWA2#dz6^0vYD_`Z^kDkvWvk1N+zTz7dlPXrGTi_M;17f}3($pls(Z)CT74m>
zT4_g+b`4ET>EmhqSRsV@L*@M%;{i}>DZ!JCN-!XRm6LD<2k^lM_mNv_0^S<|;Z(x3
zy12y?7h=p@6?Z5We+GgL{00cTXsA00MmAPM5tv8Pc--G~5hbeXKsB;a^bkZoK4UYq
z8dLnagbmvRFVIirZYIik_u~TVKqYlCmWDu@$9&(Z=neWSqkhYQ&R;bsBx}-*(gRpE
zj=+oZuLlOjVWSm(d0kRW3Py)zE~{IU$5#v{ks<m?lOn?POEZlmZKr20!hn_z;UIcI
zO(7AePvJ7JBbA*G5IsCYAp&F52fe%dmq|Y3S3j+DU{K7zIOA2n5TqVFhVN7;K~-3)
zjtn6Rfc=$j83AtDMu~X{E{rqv$%6eNB2jEjtGCmAGkB2(8Hh8F_G3nB6)e5}y^by!
zbW_DEQoF6>z<jY@bcJ6M2EOj=l8^4nEY0fTu~$)DZLIK$e-%SNn+=|i8Jwugigc?o
zDvpiX$t-1&lcEgXyua_0l%zov>BS-QmNIGvULO?ne`dxoE-#C93YAtP{)>|^IzWT)
z+5M<Qi&@t?Rt3V3&3S-}Nre|}7lu$LU5W`AMeRxv7a2u-km-vye0uK%E^HTqDT8pk
z0|YcySBH@gpFGO47A;@uynio6gdQyWZq}2K-~snoycHZTg=N=wkd!|oDpQ6uAM_vE
zU@JM4g|odOkP;eS6<T~kn80AM^26J$neO<%1Mme-{RqbM!C!stH0G7&WYe-tVWSUN
zn;?Vu{;fsTJ}xUK$#`}~vu3JGTJ-_ea)M(J+GQxpQL2Bbp>=BN%dzVzA^9CoGpa~o
zf#4vth2H_t!Dp26hooVu5+h2N5GszCWx$FyB2l&Q!40iPQLLUn7^}v)2p}FYYYXI9
zX3eqC<Piu--|*cC{pOt&efdJax5Y#ZeBMb}ji*h)3(s7hXi}I@cpH%BqvjnHA(Z_D
zAx(pmuo)h!S7!@?Rn)+@QH$NKH0AZcQ@Fuy37~3XvrL=cuU>S+84pvf5+$GJuUpiK
zmN4{4_<Y6!>gGpr8IvcIF)jQZbq{`ssFPCwcuc9`28cd-(J_Aj0w|a=<58@xHU@fx
zKJXW#Spd|L>BiMr-~JD8{}!b-xl*?K9Gmnpa?nB_Au)*{WxfEjEQN^ph|GMj6Pl}c
z@QM^&LpZvs4PwWjdXOFnT|)GYC|+|z+!nQ5(P15SEgF9S^?Qc$hE={NdPc!NgKROA
znTy;%A)K2c!}^_Q!}>f}aL4$h9iIdpURtsPOUlldCX%>mlzr{<@*at!;rDebp>j;D
zC^|Q(Nk|2HQaF#NP1me~`A$j6SA;_JN^_RRNrF1mnGmSEM)7%l(W`CgoXA96<49zT
zNGaVsT8#61F!9Ai#RI@C3M!B{Hr<3+=9(TQE2mFgWLFuoyWS<vGk-%0U(9}83fJ~j
zNVJ^kb2!*=(K#quAU9&M<nCn%M$xCXe}$8AF9HPXBuLQ!e|O51R&@VdEO-v=Rp6{}
zRjP)ZI1r!c47`Y^Z&K)x84}K<lI?OUcz#b#U{PM>BhrVYkC7PW<=m)m63a*Y9B*<D
zDn|zm(SDNiGREiDBz%UF$p;UC_4vGNMNXy_Z%40?uDW~VLke8{6a4GeB~%IyweXy4
zScZ|%g*;LLA{(-95q!5cspWJ!A-WF(7g>t_;DTS)_WYdcoQfj#jcIbmX&2YgcB<yJ
z$$k%s_(xl1h5;<BL75iqOcs4csfd&w^4pXF()1-Hc`{{Qu$?c|E;1=|4!LqRJ4OgU
zLsnp04&{(tT8&mT+V?%eWjt6cT?d%;fpJN!Y+Gl58M&nf4q3dMSAAi?Em{xNAGuFd
zV7Vfmvkmh*WaQ_5WRBbK<78f-^|r&7#T*`Yo1r4W{V6hq^5Oni_Q9`QNX}yIp(0{@
zsi2X@Kw9t3DlWX9f$%S99%*NbCILVUsc(;1CgrhgJtJf4Obu>IMBzaNKz;7;6)1->
z{#$lyHTGYSQw{I?4@8HTbfNh6wdfpJtZH5t2)CDYvwK{lX!?nR5N-6QVsJitVM;LK
zdcM1TPjt|`1$_WMW)6XPY+N`dj(sMpE=a<21zxpcPUtSgO@pr}#>1T#ag2%e!7;7`
zFv=HAx5Sy3(Bfm?f`g^v@Hw`o2#2AXdz<i335&V%X*fw#F7C5A7yDym$a)a%Bt?%#
z_n)v}ZX~`j$iCAyt!r-C+;qEEawruKLEkcF&gzF|c{s68#%OlCeuYDO-$Fjb>U}NR
zR%|BC8vmVmRsN`f>N5>+2Z;bk-rq`vzumzr4+6Z`FbYK*G#b8d7lsbyxCNx^BYU31
zE#5Pr$VjiqbXOV98;!|->$ZBF>}NwL*y^tjGsnH0AC9M>HSiGa!=mpF^}0bw>rCwy
z5|j^t#OkF<Rlzl5a-TBHzHgTf4BpA1>QKQq##jI`%Kz)|Eh1@(rLJz0R8Ra|Kc7Ni
z&vR}&s9xU}5a*14e=nfrI56Ois=Ij_sa&iCSsh_dA8wlAiUzS1TF4pv1E%B;j>gHu
zy`1_x4Td`6bo4~sgq#FxAI7cGxHOkVi(nc_WlDj_i`$ELKkn^2;&qQ4)m9&w(9Ofy
zCQBp)q0v6hm{h-;>oe%Diusp=FXFY#c4|p*sNWG%Qm})JLE+4q<dLe*)6eNaq<~--
zBc`-ig+56()0_Zk6Hm#|RocgB2wrC_xe%>JU@fFc<*z;ojto%@tgy$4<Ak8ROH5eQ
zudg>~|90;nvDz9`fp~h9@r=L_u;YUrMaq))n&<JF=nBLYrMWfnZ+P=XlnBeTagHxS
z-gmGE%8c%c6qwp3VdFP35GSKYsD)|MEXr8nImMPMr)0+rF^*Ywx7f=O4w^R+6U(6L
zS}oxeA)zQ45Qr$#3b*`+d|QS7CHc(qxIcoTVo)}}UmgJ}Mzn`j4|24qQXi!H5Iw?U
zHD?gH4X?8IHeF}<1Z4lp)?;c4?de~$Xu=_o2z7R)PfkNQ_S;O+YLrH|C7rUe(KvAk
zCBmF5SURug=o0je?Nw!G9{;3entwTkBjeEBQMAj&ny-=xHp029iRWu)YtC?RRS6AV
zW^N>CX67qR2P#D$D{3+!fwCrZx1P8n-(ZdML2!%R+H*PbRhe(c?A_P8`*{E>(y&oH
z3^Ll|32gMx{V?0^fswySO&M(Udb#Y3h(Y*|@zwNiNJZksGV`GsaP}SPfZqh5l2l_`
zD%RQ4aIxjC;r=MxjX^eKyffq*#-FB_>c+%FvM6D!o=B{&IBfO1l|`uryK@=4=tA-H
zZCDbS<x6Sd=l;`G#$OyW(lm^{aOgH_N_WX!$vg;h#FWUHG9dQJ70@ZF8Um=Y?9e$F
z*DAGN<WeO~UZ$NoC+d{D=874iA^{~a@v(7AE)dk0r@*yxJibT*J?FEgaJnAO+RPJm
z+aT!<$v}3VnFd2&xgPMom;?>zLYs2aU>KHsz7lu%&&-$M{7d^HccIlWdZj{M{;ncK
zvk`%Sp8Idti+Ak5;gDs!koW@3cIl;)u})TuLitevXWV8$g#f0b?7hGm9H9YNScaBu
z;&1j?e=s6oxpog=9DX?*kHb7|dW!reMW#Z|=lWZ2IB-ou<t(8n+r9#IV13S?Ub-77
ziu44Ibq=kf^`*4EUtXpMq8MG@5MIdL9Om5A?Eb>B`#BmZq7r!iM0ir?*V|Gv(8Yk_
zo0Y4m_(<AdtX(7954yS_L14nSY(`5q+;_=pG(BLxRFo^wUQ1v@Yk)*Trdkw!)H4}(
z^HJx+6$>Z<)}fwKUz*HyDzR&*3GsKMi%yKitEwH*&x{A8vgN`B`iddiB;TZ0`d9->
z5@7yZAP0TcvyI|9LQRPhIuu7Dbjgc>=?m&HG}?XjM}nfE7b3{&Gv*;S01h=cA#6B6
z5geL!?UL}sc}(DX<<WkZ{sfpi{BzpW_i`$g$?`Qg&9~61bTO=d2OOb~JK==7iVa-}
zMy-|3I=6y)Yp%5ARXof@LKJAW$YE`8M?p8AJMgBhH`KsX3PrWz8Iwmwi8ctXABCMu
zBj;ZLTTO5yiM|ZO1Wit0hB<FR)1X8fLO2XN2|iL*Rp5E{W9d0*(lyE?gOl%%=}Ydu
z!o8C1X@TOg?o8y3={O9wQPj622HK{n94k;DJ~6TU-;O9iLTLDoy}+lQ2FkJ^CHyTV
zL`}&38c2P}kj`kNIGqR$<@pdDx7*F_sc&Zce=t}IC!w{kFULNCW@P^#OV=2l+3&Q^
zQ`@#}Y;AMPt*x!yZnw6vwQU<)yWQHh?cKU>fB);vhjX0|nPieol1XMJw|jGu$J$d9
z67?@S)%-)4H=QF8l(i;2ctvjvVxlFthhXDRD*t+g%EDK`xdf+8-rYC3^>GJw{#JbS
zV<zIISkULfT!B`(b}T)RfKCj2@*HrH3So5)^*QWiX=G!{t);A#Sy<~&W~%KCo1NYB
zX_G_bkP_7yHyRyGS1W|4!!1uZ>5(36>BBlj321sC&kv_*c)?Co*Rp-)MD#Vnq&Mj;
zbJz?mfWPLruNyesJ?>Yhz^gDfF+wrbvpo#wKp^U4Rm<c?>g_kC!_&dPLRXPyuFB*3
zU~FEDjqS^y33mGK_pPrcrnXmxg#{>OL8lS;r^F$rLyltZ{7kL?pIBrqaA|-OO)z<M
z_E2$@Au0fU5(I7bho7$}vbhhQ)n={^HA6`7amNy&BK-D;B{~^`H^D%6zH~WKgfx%)
zy!k||AAQ_(>#1VRieMdm#kYYLPVp0lKsCkB@Q@%<AyCcw#o9vJB7s67e>xnku4>)X
zv}2R#Pu6IhIEqQpK?_eb8eaEasy|atMM0U5vo~l$jyM0pdt=A%lR`10IBUlN42>1b
z_yd@$oJb*pe3c2TkmFem2uA7V7;M@}a4<-M=D08t2*gT@AN>tZzz!Uh%}ez@ZC+7*
zF;sYlvUk<)#|4TwFXci&yn!qax~=(5^_~K`0^wCtxY`B8Xw2g^Z8YzT?2P(t$mr4f
zB-QZ<bzT7cwxS<B97<N;xtqyTAbUbmve`5cem07_|7K~Yd8sMlCek$1Z175UNxrql
zK`6%)WO>bI*%Q0omOHwAy6FGVL@GU`W!W5u9Gq|TL)Jh|8s0F0l^zltQ`)_Zpm8Rl
zyp>%XUG7`c<|uk9pNQ@vD-`#aWem?SmnsI*2OqAR)kUtqNVYxCVkV{O2oV95U&`U}
z1I{H~#J)-KAwwMI@rp^EH&3JTan;9}m>x6~!gv1j`sGhp`K2oAMRz;x;eFD74LPEl
zqmD){>^yG$jE;eU|NBm>TFc_dfeCVF4-L5I-mstiO|fnqxW>uMUx?y)$4@U@o6K?;
zN-8A{6MT6vv9@A39M%)=166(iU<$<&4y84k9JDJH3BDTbY%Kat^<aK_VYMsW03dLF
zBjAb7X1T6%Q$esSU|F3ski<4g1)G!q`(;y4o4{cYmJrpSQO_tazjgErVM2m&=fRs%
zNqW=5mWEaU(<pl_|Ly*#`&pe(zhHT|Cu$XO74;=Em~*u|s2FXQwyMR`*Yv9V#LbQ7
zH>);ePEXTtcRcH%NaZi&6(c+4L=}SZbHus3TM$v{l;OwmW>G-60My@D;h-NkAVDZm
z6yjJ8K`4Q9Es~vUmLJK-p}0MWCQ&#dNG7=C?OOi7d7+mw<2dtqE4oE+pnm;|byWTY
zo-gKygXVAzF@<VTRkzPgY-K|AFHZV$v>TT>?dAU$rKTHL6wud&=A%+c%e3Q5VG=jR
z{psqOo1X02-sI}*qUE!{?MYet%}24iB4l52GvnUtG{QUr#+=qr;+sRt;|%A|v(sbg
zI;nZNyxZ3Z(eK6ItaU_ommBf6P+kpjLP>#O`mSev<O`SHKg<7$Ra0hydpIs@?~P3n
zbT>i5I^$Fg>B0tC^(P2HUlB@%kX%jMH%<JC8?*T>(RmtS6k`l=P*^B&&O1O(S@ht2
z%e)v&kD?4SmQ^s!YPm`+e|@h<hPhnRCqTqhCI-;K%>*V82HVm{YpGid+tnW@!Rd+D
z@ZVjoc`y8AtKO`<FbDtP1_B3H?hhxb^WZ;j^}Ky!q=-6;j4dbfD1}?Zd;Qs2-LN<{
z)qnoQjZ&?y+CX*d2s*35qwOC!tY2TAj0g8&NX7epbbW94EN_V8)kp$N5fW6bE`Gz)
zth)ZX7q-bNn=ly_w~8g+lS~;-(KDPXkCRuR>0GFvN#F$LM!j8c6_EZ&WGJ0EQ*mOs
zE|15$y0G#6EFCSfewSwF8+1X1r=8`P!RRx&!!5lm6`a+G+8Gj&5?@n<k%1MCRyzX0
zUaXf83~9Q_$~r}PZ`Ma*LjxM%M<aW-Z(lS(l$5Esbj>mP-L5sl<~L>WfXs%dbwI!H
z4W$7W#J@6~FwO1dWQ_imsLG}c@CWUxZW~0{6hmIDC9UL4AZ_7%Ay@Cx0?AGMcrsw0
zTAv-+%wd>3+#c1)(ew{W@D-^hZ3s<mHU?Z(fMIBF4lYJLD+C5N(VD$8D}fgO<KuNm
zkr$gt8$9?QMOo6kT-iuRY^ypY#oXPJLM+XuH4&Ck=sk8CCDj(IFC(*@q?K^=FAo|J
zNKa1;l5dcqG<wHSlwt}BkN4ylMXg2nJ#*BZ)&Bk{mu9tGwmIv|9uy482D_xPn^t6M
zNBaj`_K%IcIH;SXF;l}xo+~yT4gm=2nvQ5^q;rB#z63KdJZ~Q6jT75hJMGkrx-@a`
zB&*bkp^9t{nJ9wV6AOq~y$}Kq?jf+m!aqX7hVxE+5h6m5XC=T##QWxzPOkM!jY#b=
z81fR7LkK8Dt3iz|-7mY|i2lfzaI2)&#XuOl8z|4-!cLQ)^sf*??O3xm`H(?ytR&=+
z0C<yZLnr}j9zJO|IU%ZnK+8&BXuAH#Yo4ev0*qh3^HEh7*sCOv0GIZ&^f21U^4cM2
zpQe1#g>l3d*s&yHyj4g;pML3BLBME|Q*S=O<~4UXvXmh~L|3z?U=fej4vAD?`;J;f
zI>@uaTmZ&$MmT^;Mp1eO-UCjk!DtA!4ZYRqB7XX(a>x5&GNf?*C~>xlR3L-~qG+Q@
z07t(G<vpuV69a76#+<o>MmzPphI-F+sph?){}=*J%;C6ehy~U5%Xt{eG(1Tf!b_I#
zIWyXHHZ}rtiw!}P*FQ|L7ZbW5{4x`q?`zMA6t}Xl!||TpY~(B(6aGDd__XK-VKChi
z_$J;i&{E}V0vQ1t;D=Q7YE3#=J9$L7jJE2nOlW956g(yHw|!i#rm$xGV`Q)fBm;(4
z&#$j8)t&6Wyg$t}r(ymph9dn`E-Yi^HA83-TyWeuGcY-SsHmd8$%{n;cBkjH$O6=H
zE9fe4hhXe6^>bMpOiMgJI76|-rvS5dwdN*>aZ6!-3gW^dn{$(Vr|<Pcky$yhe)VQl
z#?tXYN481@c@bPQ9eB`I1&s)}V2m!a1ueY<<UIv$(LHFr9|2C!=mL@5;SRc*yEZzE
zXhRF8;U$^7u_nHTXmfJ~o=xBt+qARUndxhBPBa_%pr$YjWM=owsyZ3!TOE=Yhpt6f
zU`3or9zNZ4@AL+xK1`@3(8f#~=nMS2CgH>&dQhZ;QK_$!^DGuYpoLDVciqO;;7=fX
z|BD2Z*wMuWW12-l+Ocv`QJ*4WcXiP}serLh6&?hGFTa&kcSSoK(oiA3krXNqfuiuO
zXZs{j?VTJ<o08%yAp!#nD^W~RmyE@bJ~dQR|Ke*HikyE5<*viq$BG*L_~-;-qAj8D
zD@^(-iaf98NJsb%GaY8w&66#Ylw#Nsv#y?G$v-&*Xd}z$AZfA119E%?h_-0EN$@W!
z1s$c!pQ{)yX&16>VJQxpf`v+8na-N79VNB4s|#K|RVji`qSxbW_&++|Oa-&0QZ-Qx
z+nGYxB9tB7Isc{A3Pl96$19(}OV3WpdYMEHQ;zd-9UFqm6wTgv<B_s(>11-S3f)d-
zJR~I(J%+qUz3&Nxjkv`qroCV8ogDCHxDJ*PC1%7gq+AGLdvyIR?B2cRz^jsA2=h4m
zP}-_<Z*#G~o?!YR>-dBOhV1ec*+~@7H`0v2f%;QQpbp5IfBqw6Z8$^0iqFD;-RZR^
ztbM*mzKA4UovDgyMONc>9M@-IzrC0ro|gs1rE>gzSBwEc-JwLG{$=<4U1@&-B~FeQ
zu}a4QGn)$6(^uER$;YX*V#AcqGu5SB97B*1n4r=?os-*vhsS381<AvJG`vyriAp#~
z6wh)<Fuu9>t!bR}k3*_m6~rd;>%up*efH>8Y-LGKZdqjs?~x#^(Q0;2RLTOq$(5^$
z4r!X{*Jx}%#;L_1N>22lp@Rs|RYmQTLQULD>OhJb(4H3h0l_VyF}I7OTYvS4Mh!@C
z1YAYzabAs}&RXw$Xo^%msVWlIj}x7wIxI^c(K<IJ0EL3q1`9>(#&Nndxg|Q4=ftFn
z!$o#S3HtLX<7ftPV9^DVfP{l*vM1M4v>K|`ghVh48Z1!MC|}yG+f`wYQi%MlzY*$X
z>F03@hiIlogF|Xj&aj$w50O1`h${)1ivv6J8xvnngWXNfPFo1$!Fv^QtS`nVV5>w6
zN$_x5zI`Y3J^OOQ4?eeoCsf~WxGU)VeTF#yPLN|EeOY!U2W<^u$r?m?VVbiP6S>;!
z6TkKTpofx~4I5uy+0s+3V1H@NpQ9WZzow758Zq|yw^1o5IS@su>P@9tRH1$Fb&S;?
zN5c4i++`F4`GbrN`L$>F*r`BwpM?%)+cR)cvN)%}yUJ^34VtP04CEqX+(f(&mw?ji
z<xj-mpD~cJy4uAYp8&qQNwE3}wX#PNySZTyNd~+BQ2Q&QkbA4q|6~%`(uRY|%X7Y~
zYc;{_bvmglM$F+wj;5j~*PUg27s5{g7fsU7NLtsHXMKeT#s~^8EP^NS4`NLK(znXY
z_ARqqkuUkaS+ikHEL4e6Nn1|b(MKwp&>L#C+$b&<?`xByj4dN%t48Db;1K@NZ5(1O
z4X%WaH1UCtf%k|Dk{w{EnV{@IxxYQZy&VlEMqWK5{UG~lBf?IX?VW56`eQ@a_hE<&
zbM+wIuo?r)@1|*0I}+k)36l(ze%^2uo+}}J5|u(m$~Dqj5M9JJ<hNRN!7N3Jswl@l
zZD#ehd*eTSD}GW@XrKr~1I#j}XtCz)0CN?RkBBtGV^qu>ODHYfC!zx@hIH?isQqS0
zQ+dq@T4|IJ$n@Se(fzdox)xjE?q8Nxm%3Otl|}L?S!{8+jV;Q9d)mp}m>>)%{1!h`
zJH@RWYvy-dnnk6e@2{ZY#*YqM+$1ifs0}=EL6t2V9f^lNq4q8vqug2Ev7q|_BC}_W
z(Pw@0iL1UI@)R}3igq*PXtq3(f6lSHEH8do7UfUfME|teOHnS;N6FeDBa0vj1{S+_
zI-C0rHgg*q)9+xxc+E3hV@W>o4h2~ZNKK7`qrbKH^7ZF(iw`H)vZ(rjsDZ&gkGn?8
zE7QNq;mR~L4(US87eU8T%R4hc@c!fkjjEaWD0hr7Oy$x?;$*^u5s8syN!qF7Piw#)
zN;U;ij?}oHZkQmNNIknX3P?`5X@$D)G_iodAA1-*rAJga)|S21ZqryL=D{sF{1=|-
zhl^`wMP6hV9NQv)9dDtjJIv$c7v-WQ>af&4duk~Mc8)JWjmSZ2=!#l9Dd7by*W#GC
zA_N4lDwvlQ%<^Zfi#(-YZ3r$>cML2&=q&IxiPp0dIUr=kO4-HNn<5afVxHE;Ob8}Y
z!#ICX=x$AHUB1aqtV%mH!G_zJu${qYnW0aVvfUG_!aN6O!X=3aJV38qK&58l?oN?B
ze(65u2Z5DnK>ob^>5KINKS7>_4~twYy}C2GV%5XzM2(LjUqBSt#kIn*fzH%I+W+gm
z;A?MVZtrH`s$~zueDxu6|GEqXBK#nT#)e+;yrU-@sRjm}tGbX~qUsm%=#3){MV&0E
z!od9(&mCwj>LoZ>=Au1y#%98MGWM}BryD@+hocHrxN@A0nYGb$!3f?FX$*XaWvUqZ
zPw)Z(h3mf_XgdxZ+uiQl9Q#o6bnnJ-;Mz&qv}rOsLSjF*KX0hdL<gX^!=@utQ`+23
zkovuwulK!GUgPVg)cQwj(<JO=#w>mM({!PmDoyi)tv#v7HX1e$k(tihALWq$;&?9(
zY(6NvR{YU8TDko0J3u2$@+X4HWxLlG<rhm1$}z@d8jo;ao*y5d5`r!sjC1|x;SdC%
zL|9OjACN*wNj#||Ko>{5zvM#Blvi{MGq6UU`26Hf7jo_<1sxX4l80_KEXOd1JUAJ9
zY=^la!JS)i-`q?X{bTaeMB09D-o#6m-fSp^*_ER+cmN0U7-)mXD09}RxetPs_m&+G
zz+YT@3p*07?6Nr7h{T!iN3HLP@RPToT{NdOQ2>t%cQu3s*KwAblaj<(?%UoMvE&g)
zT&{sMhNn6S{ls>5E32X>Wi~$I(xS9v*K|e0Wg%!NwLav>f_YmoH}f-bXPiN0_h;&F
zESrpm^}C?bpcnmh)&AX?)=S@V%)*5Di<e)*=+*v6@Bvp%+uJ@l-%)x1)gylq+F}_|
z$_1;mHxCU&%scUtWEf{(6e%cQb%P{xNz7D!P{v=RHO1!mN*HN67+{j4saf!2Bep{c
z%QdQP)OYuSDR^*Ca92i)r7?)xQ{UdsFkcL=(`!E=Fxn_=!63UZwUSNAmitY`x0kKG
z2KWaJFp67fjTe7x!3JXOBkkYAT?Z2#&W2o~mqXR5Y|(M~gfpi;2Ecf7Nj?#3c{U=F
zQNiaO3xc4|zMY!Yb!)O1ej`-mZ?n01gTj5yf)J5#`y==S6&}TWUH)n3zy7jaluK+a
zv8-UyN;Xh!R98Jz?1mJcIZwphB19LryO2tYnfmdLv8B4hIr6<4@Vdgedg_5S022tH
zU>@S7<Ibydpn^|yzIo=`g9|@husswzKa=~}d<dxf?A#&<TzbVAfU3|C30@?D(i-R_
zvB7g()N2eh*YwYD>0(m1WL(X$Mk&ov=7Ja`+MZOJeHuOADaa~o2h=E>N@pUsu?hs}
zT%@LGXlkNTHz$Ac_iJZSQzI}A9z#Q?iSDFf;Z$YRF@&SdQcL~UA6zqjN>2m^vLft^
zJ;(W)IEXmTDu16@mf{tHYxSo3ld8KALVlQIJE#<P<kr>jx7#YQGPN<j>srx{$MXc=
zqA)RCbP6sVR<dUB3VgjK*y5(2i0#Ft2%ZMsuM_On+w#?ld7Ren6_~HZN&ax%O8=fs
z@sov9&5&QiQn<nX(w!|xzF`=gTVUdW6rE6whib|e?I#omS2`tAB;k<8`K!4Cd#jVR
ziazRM@XiToe}!rNO24%t^OwwQ^#Y`rG#p*4h$Tg+W>J5b{Qj1!iVN`n3C_<CA{x_V
z-^P=V++^Qf9dXO4L2zPU^KXy2*H)R4I*CJ@p<1{-nRNBJ8Gh%<_x~ru*#7SabVYe0
z=o6z2g;Z}6SIH;A*qQkApD0jp-$ENtVlSe-`TM_I5K06fau9_eO2^XO`zk6c0E`Wz
zK-E1Gza5sFjazB=t0REBB$fOiLs46A@yEu5sh#>$`yU}-v2WxOT?R9!?vU$HTnjkF
zt}))(r%gZ-X2~$BfE$U;nhHP?2Gj6-D`|48OIG@igvCGb6actLzLtWRVQNa|!dT;Y
z`g6!uPVe}=?W+@b^+j8LuyODAWGHs2A|taT#QjGE00e%}#$-TpZhk$_?b$E5hIMbb
zZ0jGRNk-LR4#Dv?nwfnsn6$pUO2It=Pym4V*$t@I0F=Ky3jko~0Eh<#t|{}}o@<s?
z(6YuXvfz-Dy8+fTuKe+G_uj%$rbd{iZvU&s1>A2QhkjsNm=kJ%=pPc!AvDs;B<f9S
zLF-uT5%@c?%9X-GP5$4__KfgcB4LQ2{}F*q?s<#Z5B{)k+`tw&FOap+tiePPEzBPw
zqLnWpW(D^enx>2W%=Zk1z*v8?0gsTRm<Egnu}T5XT&Qm0&mv}K9YBMV!yV@Wzk{~f
z2=d86H@Ce7uk>AlPVML;Ms={0ei4y%;N_6hpP8|Ke-+k&g7|C~{rL~+HXM%c2`P?~
zhw|Y8xd-rgzUL6L*rOb1^MIW;B>z5!I&2Q-HURSj0RPE81G_HN*jJ_A3W+t@f-n^n
z*c$sFrk?WaO;9Mep;ItTY52tcas`QYkc9SAS>R_`fB~Q(z~carIl2S(FIc82jJq6B
zP_w5(1mR~GKD4)}T-B2r+e+LN$JJY<O&HLk(wSQz!R*ER$)&{28?8JEAoK_T^kfil
zegy+@@?U>$*KqB5ggt~`l|rWn!Rz3Bhh<_il#=x`+}^A-ln}lQ{R7bLKp>HQ_G^S6
zZ+-xirw|cJwh6k$HccGOs5u?G7o~CN?4poo`=nBPE?7Wmd2$N{aCWdl>m~{XfZPjE
zV*zn)G0#^B+5Nwb4)IEMPK5+z)uBUo)x5^POsdE(X4|!d^MWOeUnx!B8rHKaNCu0T
zxA`dgz*|3=27Hllz7Tq^G#&KhKuk1PY8%|#&4>nXmXB{UIcAwvq7v3i;?pDu`_`VN
zI>teljWhNDh?@TqekKTK#DayM*Qwjmbw`!(gE#AS*sGuPy;DWf&A)a++~YvM!0>(o
z%<_H!9>IV4adOQHG$wF^S4<|VX)0ktw#WXF=oss^<rp^7i+OdWA%AScrlTNEMD<u4
z%+MAC0NGA|x)*2^k;}7smhSjISYEWM+x(U>2feS$BQ<8TYsTpQ_{p;HcM(L1S8P?p
zbQ$dj(J%un4uF)~noIm&m3(>kLB_MZBDI)})+M}`mw#EtIn`1etDIXOZ%vmskYi^R
z>)y-?p96E{KI7I<e(Cl<fETcks#9SD0F;{~04!aMa*R`K>6mnxWvPaZZ;h^#{`FT{
z28Z~FC!6|2=DFHJt(&+<-0T7G^h2G7O(rj?3-SA}W_pP{v+S>03Z?lP>jW$1RhT{;
z9iT}+$(S|N21SGj=E{M1l?XEq0Ki5CgU0FaDMXri5=Earhm3`I1aERuO?NJZWiFQG
zNKN`yIq|DOT9kC!I5r0AF&XZ~v{5&v@qO5}?uS?p0O8h*#`Kr09(djcL&`<uuZ!+!
zYN*fGC~6T#jwqwId!hHGfjZp0mx4|hI;s|NFr_AElXu-#1+caSIRgIU6hz4^3{yZN
zl@%@Q`K`<fN0-ZaKKPRJ?z;X-kQ7gMg_DWC!CYT+1aafP+`gdC53L_ustAp?P<sbb
zY#Isqn8Ko1PFi+fA35!_vM01q-O_}7S*Z;eRDAU44lkhkIfdi#=;izUK1sWc;`^Gq
z@!~PCxk?im!`vp9>AYrAH5KTarM&ZJoj9n!FQ(no7A{!~O4UL{?Xe_=qSy$7yZ%pD
ziQ_hIElCN<4yEV=r`Qx2W`@)Lg^HW>&sgh4rO^{o704X8nq^_SxJXavOsre&T7v1U
zu<9Vd0HhR+K<+lkqzAw)<EH$(8I-Ren6;HnyQOsQo@Ch8CO!uOJVds$K^}0zKB)(B
zMWYf*hoxQS*%|!UXxPTrfNL$E9{~Pe1Hh&rV?8TUPBmJLzv8<pWOYOC_Qd}Y>Fu|B
z+1FA{8r}TftBb{gibD#W8V8eCaf3$!aE|QCIl2H{0Ix9Ee=7w5oJtLc8G4T0LwLk2
z=N?dP+y=plKU#2@WAZ+((Poz@^64?yMD`;pJplCV3|3(<z%8M(AppRg001Nl(mC&J
z4$FB5;(<c54%eciw!0W~3Xzy@`t97<uR^ZS2N5woKkeK1WrL7AG)`=)hB~glW(aRO
z9`Z{gR{-<$r&I#~5^o%U?oKiO`Ktj1@iDZs$Q*CZUf}VEnLUWq>u1({b<x7UA}Yy9
zar{Gz2YQCLL%?Q^BLqjV(xVuouDc6ZpFE??U6QBMjm;mpV=)G4Z2%DO`7Eul6b3a8
z07U&m_+)6kuLh8j=x}<`?kdI<?W$JurRGU?;%yKZRC3goG5ic6Gb<Ukmt0tgYRnaO
z9cVh=G)eFH9-lqh(gu+io+Orjp#YG-x=2rnvCFvWVEr(A0Hnsuzuwo>xeC`%Lgul(
z3|F*Cyq35LzC?+7FjH9{-!n?#-qt!E86zItrB{)`eiF)hugz0$C{pH-;9p*xKkI8}
z?HTh@4&-|r?YBijcj&2Z>2E=CNecRkt)`-R`e(p1$w19F(m`6zp*&Dj0t6@uTo|8A
zUDRjOfIblBMRF;n8eFwrcO;+L)0~+oNR(j5@-KQc125w#_K?p?R2<X4;(wuD@jK3#
z7())8izM`y>qW+~2RKnKzPTc^Ki>cCE6rKIog5f5IFwAVz|61qdm8mT=OP??oqRC$
zfJs8mZjuPYJ4BBl+TpGLsfEY%T<rFhpYo$sc$w5i+*zGSXX|5C6hU6^^DAdi^qdzZ
zVYWXh{GCs8&SA&Tx}Ud^J?O4Se^cCnpx5g<B4w_c?-R<G{4>4n-<t4rCYIkq5VHp}
zB11a!Iwl9#qzz23R^g3uBf9l!E!c@kk{!?%kdaGA0rp>e1-Jnpel-$6p#1m2uiw%o
zU(FP$ugGeUo=Vu5OhREhTN1^z@^)Hh#4OfVql~^cte1!3@x`_O#L0X2W<dY*6f0S&
z&>2FKo31w2y%qbLvrD7aF0???;-9L*)p+0{g>pW&KFdR5*@H?gs{AT_s$7=k$ttwS
zQ)`kPJuw%WQ{)MTqeH@@w0;?&hTb#)fIEE(F12v(r>L2R=a;Wb`>v5C&V?+`efnPZ
zMA`y5xQT6hidRR!tnAm?u!Q*3s-O|Xm(U-R2%WPeYXlirI_@UBK~>={Y@B~YeRkx1
zvTYaQoA8$;F~kXEymEyD2p-0{k~s~lx<d1qgj)gC8l)b8OV|(qU|NwjvP%e(wH-EB
zN&Jhb&3U|7LSLv_c@|v(n)kYv%pD!mR}%^rp(oN;+g2~(gby$Al*j^f37$0Lm`fOv
z+4IWHvmL0iYxJe+v35`KNomu7jP2+fTQV6f&M#^&X5iaqvJibvI4B%1Z3FaBhTv%<
zK&Id47y!Vy-Zk6M-?PDnFXGKfI>LQ!T!8}gPK1po7t8dCQ6=E|%$mCCEX|%l^v$+O
zP6S67Ka)Jj(~8vCXLOHz!Ml|TPzK$GxOi>Cr?5Th1a8)IkJTvk)#pY}Q`~y@ZIvhN
z1#uBYBU$(0hrv+d+rJK!-PGlpo*q)GYC4qOG=fuN`qr5KZj;B{;{FXl34?4tSpv7z
z0e~_;0QNH4Bd8x0x7l_>>B;_Qov}gu*w<*3T6~u3Wa`(PrZLw$da=rBY8`Hu4XExs
z<iL}Uq$_%VwB*3*`sP2eA0Ir~o7v~Jo-6$mLU8+UaKdff*wMfRyF#CBK7?>+p*8y=
zR&E1T-W|yyAVbnY1fV*Ah)cpB0g$|`q!+-*hS^V>K)HeaYRYg~0^21uQPQOj1)Xuc
z<9Ai3mqSs%r(~ZYr;~)|HBvpSvG=sDgGocdSl)`aZ$q0u!`BM6%qm*5*DY<g2MZQL
z>pQf!5c@ZY=9y6LidyB`=1>d22Vi|+f&5Mk20(i6ce1K`g1L~ISs;>nsSSEbr7?0I
z2-&*_$?5J9usXVo`a81LGvax@GkQM>4EdAJ55(l(ZN`8@EvaK0Ol?wu?N!2LShQs|
zQGl?UUgh!_R-k8^IxW*Dq@7k`-e)EW$a5WQ0G@mj8DU@_N+yyHfG0?F>o1~p?SeK;
zXB(>XDjd{;fSR5cH}-JRjuV*L^1_9`ctHE2y2brE3RfXby^*dFy{XZxdt2Wr22Pzf
zfbpjYkM|MF>IMn>Di2J<Rx`TD2|i2dnEBV~h6~{n4H<!2eh+m07FhNN{lhT_0s<}!
z&2(5wy-MHZ_oXi9HhYy0M8_bNPXG#mP^HgNPf4n|{@j4DBVcrjy4_?Ha!O4YSfHP9
z)zX=6FenYsg>YfM%74Ul&F;W~OGOcIap_uWzq_w}hn$7=h`{c5YA~1kws>NNUu<7M
zr27mhT!tSJtDb&9-k+5$w9?8)ruT&=#O%PyQ_K*3U2ABMbiNpk1Rhxz0P9heFJRb(
zAqLj}TH(Qds>%>^(KlA1ynFRVxXhz(eyl~21RlGG_8o)NBy;@+txUBI1ey<~cKMy8
z*1vA~G<%!82W&PO<dOy{4@6Js5VodXMcj~(X$*Dkf^J-}#A=BD$SAeb8l^PR2(Kk-
zI|Vt!*+}^tz&mjGUw#U^-m9$G=e`YAl2dMCN1cGPgyB7SL)GVA6gvW;6}zRH_j+t6
zUX4r{HgX`^^;$H$fwrz78M=kI=BTD1+JT473YtISp%|3ibzPip4UJ|-{u4q)F$<xB
zzBh0!r<@h`N+hvV)mA1kA{1H6Qo~LdChF~@g~evi^a{oW6`7Qf-fGpi6+`{xw<#1z
zspOaKH{}P;3&7W2!uN}hNqprZ!zrKh(r#h3jcCyWh5M`JFcGq#>b8svIubpvNem3u
z2ZXqx-jvznTZ}F)D(BA16c<py+9y4^WaNGIt7GrDE&V7FWlNzRxKnO>Dssu4AbDx}
zfV?;)VJ-=j(KoCJB2RZ>S3iclS(g?$GMS*tnhf=a=^FV|hhVgKNrV9~;;jfQ*vF87
zy>2p_jTZ|YN>_bdnX@lRhFR+%TIBt|-MNT#Ni}A9$-1jn8#R_~g%r@}it0}$f6^5)
zHl=~!Oxt3bJ8_dfavx@8x$@=UH|j7_L^Bbe$ZFlopfd;zemUpqx|@otl+wWj7#Vc)
zd>9!aP~hh0p#mbjb?9@0BGPXP%v^`<8R9;29vchi6%(Zg3trelO<!qdo%=h(mxIx;
z?!xg63!J9wiP1~&j`*%32vup=I9i9lH95HI6JF{TCgwtu3E6P85Z3xTIUXyT1?(~4
za92jJnu>TWmgDCpChh{1d<ui&hL7hkwm~twpPy32*tdB&It-aOl|jg&v<Ax8XC3g{
z3A+VC&u}*lZ(P$hny*XVnODM8H^zSA0Z=-8!>g6Yt{U4>+wbbG0%zvcdnu4Vs$%#e
zFSP{MYk$!)9QH!42Xoo9YO|kK3y?Fe@s08yQy%#IFeAZ4W!KR|9)HBG{ZwKBko7|o
zCl8c%c;U{UG#JU(#mFDOg>QaUO37|ge3gYTDL(+M;D0l?ll;2#4)sk`biTyKb^X-a
zS&$MjYfNW&;p|X9o19AaE#t0-C(13oQTM5cn5I2AQr$~npFStSpGM*S_ZrIIOr*+&
zJfBf7;^!^eLKXc`^zF}80061E<>2_iOD;4OORF7SxLEvY&5rI_W0sm>6B;Y5BtmtM
zyjF8<UsrMD|It@8-4p_cIoAB~RT>=wx!>Np0DqP1%RG^4Ml7k`&AY#3?g@?({}NW5
z|5<_8>T^oH!<Zq!zMSDQkx4ZS^Nk~4J#~#9d9^i|7yuVkfI22c{^a1RzZ?_&Of>|c
z0^`V+akizw=ef*_OZAdR5TYvsMi(Y&4Y?05I5>zsnPT>GDsj_J^h@ROE&KqNVPq%B
z2%YbHC7Zv~<eXm;t)K|EQxGfna+KN^>$PGNse2ve4cyVM#(SFqLAF8&k=;Ojeo&`f
zND-`LC`TAoc~}tg5v4J^OzCvLPI{n1;`4)w))lUdFbc23n9pa|aBh`zt%}vc2<VPi
z^IJ4%)uPcEbvqm&+rB%qy#P$Zme<28?F1@@F<La~SB;nBpoLQ9lZ&WK<!YId{(X*}
z-=k*vsD6gC^iGR%tfzdgD#R}=vmMK!iB}qshEnp|uT)-Ov=n(_l|p(<ea47k(*P{W
za61GJ4++8SmfPhv3dGD^N>~YL9V*hd=+Qf;a|<tO2vi#phr%ak@?&YCcamx82SeZr
zq+j#I|K{(Kn*A0=Vm)@KQexditdlH<hlr)<F{*J$&LfwcdXcl`e|2rQi2RpxcQTsu
ziVIHiE|+QI9GXS9oG%Aw=qDn+Tmsay8ZV`g+x`!Y^*Vn6Kj>viSVT?C6tbv@CAXp_
zG&nV*ar+3*5pp(Rj(9lF=7-UsI}<$hk;Jc_hq+^mW;f4uI_%23%DTUInl4v3JL!4B
z>xVNZ9)DZW6zuNbe2i-wxKVmsp(&>NJ58A|O}Q$`YoLu)tOWj{TJ;qVTSaZd`kmtz
zO0#Sb7}VV_toP$EAIA#G5KwjikaoyPoG2ITcd0>Tsk2uw*T%ZKkkUoo_u*pHo5M@b
zEFVt)1mGZ$=68t;@=UV$A83?!G+N!H$7YZ5MzYqv>Q7@6rrf?}N8h;cjvL#6FV&*J
zjPcU7#6PK+G8X=33{%~aJUd?;N0iR$KZ}xrgCHXnC*U&67}qdMK}=j{(F<MPdvdM3
z_Dp=`J#2>DJ#x>V4V$z>tp$l<pPm|ps=6rw#5=_gEhQ|4SJ2Q??np9&=apqCXkpD}
z9%g=nWwybC4nkt8)z0GfXppbcc$rA*PNK7ycD*0O6q=;&Je1|*{8ccSy*ytUiU!Gj
zULtwlV9&1^Ypp`k-}s&VcoHi;vwj8r;UGvc%^JiDD78h4IWU1EOdG@+=sEvsm@^^X
z{!Ek_2DUtX@-Gjle-I$)xI*-l^O~*RJ<9pZ<OO?jj4+mY<M^@%J&VHd(DD$Y)%2@^
ze;T{_>VmbeKpEauQNGWv|4w>q4?26$IuYM7lmW6y0XyS6L;O@=%kI@LZMRz&vVRm_
z5H!+-)*RnPax<fqS`;bR-B7+-ET~mm!JhiXL;n3V>c>K!H#5P_GH;7j>6GKcW)!hU
zf4;N)SmP-2eO=}ILGT{?EdYD%TT|nWE(00t=l{WleA2ZbfOr|STkwSoX8cb6ikHp8
z%l@6yssCg^H<S(nE;alSynw=RrS!nc5?^*#JNEJ30IyKyIFKLYB;(zhmAXPBUxgdI
zZMORq%9>#JJ3KE}riaH$Wq=Sl%!oynf5H9YQk9P35h9I-1510{ccq%rT`lSBsWKdC
zIJKc!BSWl48o+G^ET3Ss$Z)Uj*dw89WAU{f{_{ZssSPf>?{lKn4e}<;Kh|)Sz&YVW
zuhKz0ov6hN9QDzDO)fjzOl#Xl_G3ntAsy2i6Y(Cyp;eZqzB)fGs%S=+9n4HMnX?IC
zOp1wH*5LFv9Y23~jcEyCups!lQs*F{T%jUK>ZHKy-(B-)d(O8}0L54JV0K*GuX4FL
zx+3YZocdtD_f1@@+fYVKhr_KWCrwImu}Kumz``VFgi$tD>e+dPe18PcqFo6gffpvr
z4g)_DY;q9<%cBz;>S=0CPFA^N(7JOCX)(7HB+M+!RvZp#)SX05e+ZxCy^MATS;F?+
zxHEZ0PqY|e_--zP>YqC>e(l<Cx13@M%$^a;niT93_y1f2nt#O^z-A8nS=2)47ZJ}q
znAiSBO(xP@W44dD#4%8_)mY$MIk{`_%YvgH^v>4S4m>15!Vkdh9HrnY<u>gPc!lCL
zd`P1%|3WWTUJ3o_nRE25zofs}Rk>-}p|jkfCU}}K!fKGwuQ2pr9`?pGLDQ^vE~Nj5
zGak<{;w%}&LjDB!^za!CrlROoMd;AW@9&M@|5g}hX)|Hu5{#Heb)H<YXf^8mSuoi^
z7FFfAghBs=#*``g?NVut)t;KS9O8X!Xt5WUbcIxfHJPV8kTX+KgX51Av8jH_c(IQR
zPKoPQBi8rx3XY{{Erx}$GSxwuvFEp!_0Y@Zl$dJGNoyY=3!HDO`*%JhLK-2dOD>ZA
zGXlRsCkg6YnTj{n+_kbO<8=3`uj3zK+rjSOg}@&Z``eTbRu$gEPItY+Y<gi>nfj*I
z`EO?0K7{Wsa^4SQQSbvyXvDHUy!ovb#g)m~)Df`Vu=f=|hjXqK97yom9x#`*I$Uym
z9(=Jk)S+sd8sPgozzm0yI*YV_xk%M9J>YrNGI}X0X*gGzNZ7-Jo9UfP=T5IJOr$KQ
z*Kt21j=?Xu6t-pKbt#hcnMLhQ@9>nt)~rj)BaQo4lU8xJ|A}{BT+wXz{dc}t!6NIn
zWfkGGhH1ry501d<gZBOR%yiLLlh;}Yr={w)_-%rqs_QgD9~Zrg9ciMbW0feaPehOv
zEBtQ!agU~I)^vqBm}1@J=i)Ye(MmMW%ifRrNH?K;Y!UfaZhj(7Z{rygeN13_*iE!}
zEM+-Frbc5{J|$o*-S8)}1)9}3gsF+*-7}0T0))(&UDBZ?1la>tm_N^@XWgBO>fcUq
znFw?te>_vhGh?jyin#^RW^~t7{b&(8-&_;bsG4-PV+Wj(H>Z+i9D{3Abh%TOyh6xq
zyn8bjv^t&1aR))9(*2jU3l=pSJRMfiDPDCk;H9JWxztImvmG;-Z2qe9SdACaxOXcf
zTF-<m`)15R@MwNt2ilKItK(IN;m%zC(PgV<7R#NCZgKr;X+BVg1s_<>{DwR2AqsLa
z+q)4h>P@!E+PC+6Xd!28&P!?<yPtboDF9>}&L1Ef2TG(*T?COhbV_B8EM)wIY1DSK
znI1P!7%7Rvkx_}mn&(XUMWID$dd9=!-YymdLoT)=70yK5>U^G|VOPlegRx>~5TRS`
z!K7Z>eqRb4j|@-YbUw#zfwj>!zR5Jh_aLSqhJi_+1o<uTusgBFWjmajm*?BT<f0JF
zIT&tcFy(e_1XOw_OjW>4JZ+gAhm^Y$sH<lxJ3nw9#I&J#a;|i?OEX=2(A8~1nj&*!
zwxP4dB4uxUsqI1D+Iz%tKK>gbugE%sXow@hnDFNo%UGiNmg7Azf~}3Wae*XlxELqQ
zBQb8s;UCvqLhE_y>kwuzO|m%m{s1riR}va|0(FYh-`mWtHJMyb-&AQtz6<rHtUQ(u
zp-b<pfedM%S?tRBgpEBI%8O6Sr=En`c7^9UpDV@5^Xfn&v1b1k6X;y5xo%&m#N|Ns
zMf`BRni8{At1q=AQ79U9?V0O7Y77ZKi8hfjqESgcs8K<GFzHIX1Nss@htFsw^UfNO
z(`hZK*Q2P>>90jknCV?a3}+e#<WELh;*oCE6%WRioCdq)FK=zl#YOygd|PhD<?UeT
z>B{S>vvK_h0)X%q30jfAY1MCCKL)|>`&jjFN(F7-+qx4wNPv2;mN_Z+pq_8sRW!V;
zRa6&1cs_qE-MR)r!_8vX%~jG|BvF*2ZJ5{aj@|vbXg@Z@6#W}U0f)KzPXQTUwe+aO
zZ+L=0hM%P}5tt0|`7Y_DX37$vs3zus%W<&UX%?;sk@iS0F^ZinmXd^mm2BK<Liyf$
z>cmyK9fDc$7(x0rqaOcI?fzri`jDO(2COv-Jegpu4$p599P9gtGCLYRK=5iVTn|S)
z5dPRgQpR$W41kSXfa5%b3=1^VDqpn?+=o5ec1^=+_;#I2zPdGpS@p7KySu<O9Nn>{
zV}4=bQoFoWa6RVAk)CzLkbU^w%GAbA$+++BAdOIaqA%Lzj(cJ1ag@^)fZ|Ik4dRg_
z?Ye@7(ZsXH>9=+#om)PvwV@4tI(x(d*KL~<p->BQ+G-?l2v?vS{7p@EvV_8;icbVK
zNmP){s^-87)t_(pM|U(JGV6YR0uttOhv7_@8ofJ~D|J45n;H|F&P(>BBl0=hYlk~(
zV}tMn$?8i|wvy<etm!X2!ut=j0LMf@<T6b9tKN<iu~(LEPLL89ug=F5Df|`1nzEjV
zUgS(s402}<M8hYFF<0|3(jAYclqO^ht0)^}JWfLhl&AApu3FtiQVFhOYPK6%&(u#c
z5PN>bUmxQkUePI8(ogG+JX^>5i9i>L_)I^)%;sD`V>D^9SWb-e_S*istFSwzrKr=a
zm1RUBT&iQ(Jt&Z0@1bm!B&$wmNWLE9A7`B5q0a_QkyrMN3pSb!9m31sRf_pcj&CI<
z!C;K^uRW2ZT-EiS{&aX_=TDTQUrm_a^u2T(7=}TdEuq7lsiH?Md#;ic>Z%k=tKg6O
zRn+LzdO|HDTtx2Rn&ook6+VV`OZ;a_q6%~-IRuI2W}~fLhLE9s@rfxe5>)@N9HV)N
zv{5IQvQ8mneCIURzm(`)HLTN4n;Bsvt%AR|NKejq)f@h%xrq{)>E>UxKvRB(=55cM
z?>+oFd)-MZ^n0yhFfydoF~z*zHcT5f24j<x?eKB<k6RoxsO9@D<Gw0pfqHr>57H`A
zx5dgm#h2br)`_z#U*vAA?%rzv+)C6HXI4-njo*qE-dXlbTFgJa^7l=puY35!fzwes
z^A=KUUlcEGjIeU^pcHUxo3~6z7i8O~utW<uY8;l#nLV9dGj6ws9J@}Vvz&Uh2!3?%
z#<J!L1fi$_KUBXW;LNs?of_{t%oG^$^9p+C&3xmNnvh^Pfp#A^-iEeW5WDQS@b||f
z;@-=qA*v?0+FW(84BHR7n%fvI-z;bW$0PG>WZ3uh6$#8m$8MG?`nH3d7XEz)soJE7
z+(d$|&(y&C=0}m~To59qF#D4{1ollMhi#7H9dnG<)!pyu@J+C}djc{@4H5|Np}&9H
zVGI@LLaM~}yA*iM#Ph-n_sJkMK3JYn4c9RLjqhVzgR{v{g9pB0qI8j{Fqa7~IOf*6
z-^JK%@{CvKh-%05U|e`@Xl{CjfB>l#+1FKeQikrm?NG^g0^=i%ZX4shr0RsOpJ&~y
z`a(1%H2L4^3vz$g^2O!Tn8oGwIwszuCbIT1vMf5H@W*$&G(6CX>g%;wGh1&}?fK8T
z9LY!gEtkFtc=X0E^R`BBylyi+d?NRl>;m9B_dTMlG2wngMDZ$jcolFQz9Y~0gbI#R
zhLzqbZx`e8da~l78*da67oVc{<F{P|H{g4^RJFCSyp&{wC<)UF3xi-`TeFo7)h0bi
znY}T7u5RcPebMP7f=<ht);s^wB)mB20*fxCRu(}wDm$Wah7)r5rJ)H&wCsYk>B{LQ
z(YB7Qin>u9v4KnM#7m-umHOY6)|PfUicWn%;yFNGqw?c93UPnWDKQD}H&bdZOd~Y{
zUg%6Lh;1qshY7>3eWonIAZW7KLQNe(8x#@aj@OI1N4~h@LKx-Sn|w<G!2t-OLYC)t
zU1@9D?a5F^ZAJ|ozf!|JE0KcFs&k=c5yar82(DqR_+Fhmi>JGLc5Df9q30ixtA~n_
zI*#eYwo8vjC6yq|3BWe|-W@@3pmoK`7zHVNKP~@^DXFKedps?*nW^2pX)n6JPH%g8
zjY<u0S)ON`7&l|MPX0RLN97kg!}%`V|C`wSIG^Os^u=sIa0E`Wyn~i6?m~D6t-|`E
z#o_n@=K)9bN+6b6O%&;77$HhI_U&G5unpS}K)Y@JoJw&<5rv(+rx#6A4BYZCjvTL*
z_HD|l$j6S&$2fH{2Scx7OXM9wKl$}$wo9<6=JL82F3nL~$ky(X6%iH|{>cXu$n8M2
z|AB&QRywm{&V6}$MssfT<MIbDZ#mGHt+FyDE0Ut;5TcYmgq&g}nXTWgl1lm+ac>nC
zC?MxMn&xzp&pN@QL-1@?oww9#`q8VqBU|D#yqv~>U1VvQk;w1ybNaE*9uc?s`hhIX
zx*$C;h3%l7+g7{M{bc?35^AuxFVcsfFG7`01*A)h_q8BJR;uzfpd<>*T(jMo!e`he
zC=ooP&Xm(VkG#`#^skR+`<mQD1S>+FN6L*a-04iz-dtUHvfi0Xgc?$HFj7|AslV0Y
zpNHMZn%?I1$uO}OO_2|g6$MI)iG$|U)x`=_gt{!VygjZ0t%241Pw$cu3AvQ48zr{a
z(qv_WSr0#ORF3GklDhbxhcz5s*pU9`imHFw1F17y#luyZyHEo3uWkY@U~D)kFJ<UF
z{w!6)7kb=o1+X8*5}};v_(0>im^oeOZ{TSy2ZJa(!^(CH?a$?f$WE^e!jVFZkgX@6
zg*hZXEvW#gfny22e17hXce7tcl+|#KWm>s-OYiSevvxZbD^C38K~0{!u$81Qm~F%)
z1!YEN74-=j8a-|X_lKIMqLz8k5B(5CgZc1Q5-~Q)C^sHMb<&)$$O|y2gt`cf`!Y`&
z4OWM*YLN0Wts#;Te61$Y(FKSznIVXGAHyI<*s>8#_p4-c>IlXLaoOT#vg=JDJ;pOR
zxCm`3aW$$?VFf_xPqkqU<caB3o#B&!N>*lucXVi@^8g;Vah4l%BuD_NMQjfFU1O(E
z<R4+l5Dpp7f~|gI%B;+w2h+lA%;M!8)D5lpTDI+nL0h}J+!t&!hpsE9clhb~x*E~*
zw0@?fF}GSpLOGXly-=h`yOaF{0%v4jZxmVmyx)rr>&!2!7FC;#KRjcHnL**nO<)`8
zUk+J?s5XsgJ}*}%{y<S-mvH!hhKeIuNH!W#HU{NCeJ~f-y!=G;Vf?p&^E<c4Cc5!E
z8<)vWjGl7%S5F-d*3HI)-+p_YjPoyk2#?yxFt(&PD7ch^BJQ~HF~tLMMq4hd5#nM=
zFUF2gZU=0{X&q)}=4MA1k3vL0qX#XjYE-RmXT`*NuCL|=L-6A7L<gCb4!)pg*%8oS
z$x^5Pu^%3HU)mI;GQUKECy<8w3V|66)$AB-1vlrSG?zub7b&xq8{C(kCdP`6dil?h
z6G7$YKsGi7nZRHB(YVzkg#*i$j*baS!!#N6!b;^~RVX3H&g1=iS)-L-0;>)WqS{^f
z%|tH=NNCprh7=X&_AT`Tp{h)!0qC!WNT$d2(a<UkKJ2xl`kG|g-%}k!LDSsMGuvne
zK=vRjH;L$~n%G=inP3ggw!#Z9#dP*rS95QIG|ZpbRu!!M+}!sZ7;v)&I$K*0xltZH
zXH=Gu0h`KfMol#gZ5skz^zjSiM!VkI6yHeuvxcuvU(0)FD7T%563wbG_+t7=I5Q2p
z`nU_RoZsx;*JEZC$}Cj%WAe0v_RKm@?<UEV13T~i1N(F6BdoJRk-Kn2juDo#*hfSj
za079kgS(bQyex+(VDYCMT>LHgmEJ)m_B()`nY{ns5`@sb7}L{{FJ4XHoos6-s_69<
z^*J0-+6+6n9!EkZR!dFaO~2oN&LvGSZPFlYnDNPr6dJRq=M`(hq70SK(4(obTzolI
z%t|ey*HgY`+LmL&=~C-Ve@y);S=&N%{2<u2LFDqM-<Xv*=5t8t=XCbGlV^`I!#~@b
zCe%w=$NKT*n;qLS_tm7j{WcY-*HOsp!iC!wL!eT0JI#hcs9!WjcVhSobkmSKC9@M~
zZyi=5Pqdkn)oz_fmuBKj=*;J(qdFAP4wHUO2QbZ#$8OcZTs_hZJU7SbNwnxT+hDc*
zg$mUJh^^m2iz|MMO?KQo5Es%D?Q1j!!0}H*Hyt}vs2!qWSkPiRIw?WsrqSmU`1$hG
zIJg3eVD&G-IvOZ#5_RnokwXX!vH7mMc9flZPJUit)jniHOgh^rNNYD)@%H<^$}|WR
zNY@7;!!b}9x1(T(7dX*fO9yBCq4|<9V3WpZu2)eCBc4c5+!s&8SBR;<j2-zk$r;7K
zy-2*lYY3pO0W{@7|Ic1-Z>Nc>#PW?ZpIEz)UtE#Rq2)EOL^A#(P>Gip=C4Tbqsa^R
zwoFGU!T`F+=ja9{nIBWBS{%hX9EJ~m${x1ZZ#E#FBjm{qm*rp3g=ZEbs+ivG8|2xA
z(9ItfKz-tecI)cS2k-uc8+0C{6dzkHFD9W{3-_`QFd8J{OzOvefHic}e*JCna6jGT
z9Jc+1EkYtgq};#%!kdFQq_~WyK95annJUb4r<0VjeQ&s9V~%ANPo^d;dh}(}>ITxI
zuQZ?cDr34fl!!>W`@_5`osec}eGRvNs@gq?0&R-qrE`_x^juaVv(S-rpm(68>r#gE
z*72(itLK$2cS<r}^fmyrBoIqWTq|L$V~y~B|KmGaP$yO3dDIc^fO3$e?*maDKU+7s
zp+0w85=fQ$Z3fN`I8dq99dZL|<yW<W3X&Y0K#o85gGNGAk>I@K8@QOrzTP+bpDBD5
zmvAGipFK?o?ZWCm@Cy+_+N5qOL43-B=}q~56@2(%Px57VwXq9;NS5C+2l(hoIZ%JU
z11QWSPHTi0eiC|o<VRNNFF)o^7=wv?zU}D@3PO3akaoFL6Uh!gFL4LA*<wUpVw;5P
z3g97j9<yP?lZBDl<KtcF#d@`)T|YGERKPdlou1e|>1#KVeskUD?+Qg!OXffrsL_=K
zK=5A}mC^Nvx-T~U^=Gi4DpR2@)==f|*N;WO@Bq?n6qGJQn2aSPj3KD!)%pJec|eB0
zJ;f1yy`8v^@S_oUv`>xE>6I^71Z=CRlFxiu6sGq__$bdly1B)GgbPTLK@rjmfC!V1
z74iI}{}hjWh^dGWDHeEp!M+IpCfr%nBDPBML_P4aEo$a=^z!w~dGIowj$i=ZgO}^V
z=r1||{@;rOatLVPfCkI>4?tK!|Mi7xVb77S?twTyh38zE=f5PGFPqC~lw2)r>_sGw
z#-BeD%yRI7CE%E&oXsUjL3jxll*1TM=AU@%`C|kgbLBLg532r=qbP1?@0(WIp-m)y
zJTZ;=o<sz)TAae##h4#is@SV*QF@MkS!m<i_;Ic^P5!rj@-c%-j|^c6QSa)z0g3hl
zxhXroSct!-Yx#^eVn6Ghk`sdP1jIAZU;t8ycmft3i=`gJ_h~>M{W~K!Q+9i1>8HVX
zJr8#~=Ux64QV`zO{F+s-8l{}~P&h<-=cK2fNRXft&_=m=EFsfI9ENqF=<FmlFwh-8
zqqBT9r@EUn7QU&Q!zIxO0ir5rw+80bBp4f7TF(}*6w7vmXc!-2dVWZ4nEQwZ!<=s@
z_L?;Bf{AUJqKJM!+OmWQ-n}_`oWJO%x4I(^s2~&HjCPD_X+h6MbQZz)dqo;^;8b0<
z?WJSNpu6jM9SHIIrZJaBx@jLKCT&;V)<-Ldb+6EQ)Z{uH%_we0)hKzT8n(3tYJ)Q8
z#1~>NYybuE*vODk5Vst53`EiyY#zGLPUX)m7;^^Imt1*Kg+SLe2W{zpG-+&jxBCE;
zfEJ{&atZU~YETlPGY)!tG!t)+H1Mb6^OZ}1Z#A#7#j;z;y@wxx0T{Wte<KCK_-Mc1
zoVvEcAlzx?r`iA3ewAJO+==C5u65*cfYBDsJ9y%MvX;FDINd0acglca9OJ&_;{ZVK
z4#GbUw{AFD-TSA4eL>txd%u`B-@4*Em!A*Y3^uLZ?c7a6><nmM!v&C3!r=r>(C6aX
zDe4io4~gamdfJmQt|ctA>HVLkqOM}za*_BNXaGa(woKn6_Jjjv7?8eET~tJtbm~0<
z{XjlXP<3#mYvHCg%GSb!4xpdnU$)c1?6lmLr`~`Bkom0)-VOlJ-R-;p0H#6UScC;i
z7yuWopbnOo@B$E8rE%~TQ}U1^fB&q;T^7vq#)+`DvaR9Y;X&aws7x8Si~h_$kjG{S
z>XV>Bwy8|vOQk4U8yXnD;FA6CNTY>)I_w{13U_vq=;L2_*iZT5*()D^Fxj6T&ntGL
z(ho<<pGG&M!|zA|Jyq{#N{>?>Vm^LFiTb0`p4&KoIrshh5ackK$;GX8A;p!ZjV0z9
zo-Tz%_KWc$Kbq}uM0Y|_h>s;3w2~t4HMfRM?4Fj6majd&>$F7u<xTH|{oP#UK$tAZ
zqqZsd^uM+a1}fGDogjz!|L-{#dxIJ*+v(fom<|+qE+&DxxB>?0p%J~6p8>aaWqKXh
zlqO<eKwtpDe+>!)wq*xcC&2V+2mlRrkOY^Bcm>%cst;go6Tl$`YJzS8gqn$vC--OS
zC>Aw$%Y^`ZB_IVX290I;p(y(~{^0q&TkO0p4ZU{Ig8_`6kLm^vsP}^Xr;R;{2tkRg
z07}3q*e#EPFopwG8!e~%ozv(KPxhhO6SEaFu)-3SucbY<JJe!WFHM%`hCZ{CJ)0(H
zdKUq!ucQud8WIoYkw2o9;du)pcz5k9%ocQ6q^qN!**Jh#Wc914%;v>KL!P^z@$Ei%
zUtZK^y|nA-AYMm-BA?b@`%S8VvF4T$yk!h4@xAL1UB5_)2);~4_y25~eHZ|perOB}
z-IvWpk%o2&WGJm(mw*E@SFh2ZkHM)4GASU8Ls8|NRR0T7)IGdh*@stKB>yt-0`@$8
zVrK<)e;}{;8vK<q?tOS~)dXHSHH8sTA(sYG`R?3CjO##n3&*Z1!|OLGZp-I$fjBD_
z>FOE!ZCVXFKj+sH15!w5Jc}qC4v_9?Oj>R<6Wx6x?wK6KZFl21kI{-P??r@2XIXS7
z??doseTN%2`(58~Sz(btwlJeLJmyS{o?t$&Eu9xHU>+9F&(~TsZ2x2<6)?|F$lFvN
z^$<#|iO<LnFu;KGb*wB=*qwW8fiqZ9e((v|OElX!U51fB$~QSKL!Zj~mzTgfi!cBH
z0kWkSOt``vppUuDsFVTr+7kdbLF&+7xF0kf24FOOcRgq*zg9PiAK;7=X2+H#N)t7c
zZLT(2=+4WcV=)???`V)#H&>M|&2PaUO~qpFo4W}6h<{?}Y}n>=V&6w6txar_vd$3A
z7xa1@fegH^;uje(m^L03TYbC<X>$yQvHp+<xd~81q@|m2i$I9c=o^+F2Op8Nxfz~v
z$R1OQI}S0nzD0J&K>LHlQkzt|jQM^Nfu8SlWZ8g$0OB){NHGx}9TgG&l}vpQM6Ezu
z<KiCHYj}j&rFWl@ZdjCwb$LM7QO<D6Kps~<^bd{bSA3FvCh*WtRd*{DQ7ibBh2oJ^
zxRY=ihht3~%JpIJ+p8gTIbl-hp#1!vsavH{${M1C`VQHuJk~pH^D5c<x0WNGV|9+%
zIXhBCLL(FleIwh5VT!zM$T>%;kOGtyOq(R!947jR0>=LvKE-i81<G4GBy0C2t)Y~0
z1yWOXl>|`R<PY}hr{}u}46F@==(7Pi5McRG6qRld)^j8$YrsiDdx#`^iOE>UVzD<P
zb7j>0-lf7I!F^xcuGCEod4c}e@VU<k=0%;nV6NHMWDh+vMBL?M+x&vU$Qr&|f}epF
zE5pGteCp}R-b*vm12toC4a~X@Wx{*5)tbG$86|*GUqM`Z*eo^r53Sb&RUld@%L|e}
zB3wh#_h1?xoB#l=j2a@A&$*b0&`Ue6h~lRJ%#4568fbUouJB9ww|zLrL=7zGwsu#l
z8LnwrFgqda@a;2yWhuHmT-_Nd!4RmbRQxw^2ygt!vJf8>;Y$3w9^auHcF93?zP4I%
z$W4$ygwZiuNVuv+k`X@xGrU+;mTznC%)vBCS_O=)`uAhc&rn_r+ZM;CjjdB-=oYB&
z4`empCTd%kyNqJeO(g3-r4KI3V9zrFp5TgPaj&^#m6okc#wJX{v0l)6z>p!aT^%w_
zHOYI83dA|-!M;bGINV=A9vlE>!(5fH1BOca8EKdZPohj|`S<_=oVWDC*tAKY<?ou#
z-#4vB3oGI+PdnULrwTCi{i{<7lU6_aVhRAY7<@ru`%Li&E-e^qDZi{(r5R3}1!9or
z3-;UeQAT1-%WpD2I8?yR%;fXlw~?+7E$sKdC|{WrX+JDmpn`}C^u_4_uwrEfv!Fcy
zrWx!@@B(R%iOPUjgauK0a51{wi@jE8dP*Or2DWy{&%$OlK$ZZBG;s~{ewUK?E>f+A
z&M@U&x+9&(9*_?wsK@;Cw&4P!k#5T4e;hbmBXjOFZK4X5Rh@Ys8A?Q)Q#40ncIqhn
z6$px-@1pq2AU=xXdcc6aBLG%UcY?Fl@&3kzdQbA9OlULIB=CMGYE47Tg-+O6jkE*^
zd>?>H22G;{E5HC8RuOPof|g637-g>%kH%+&*i6I~z9|J#@H$qD0FyDKsX#~{wrdga
z(8s-H8x3TySKW~aZ*0=2K#L&AcL{qQL)H(E{f#j0L9UCj%9!8prjni$ZE5w-iW1qe
zXtYCwe<gNwYGD5Z$k^I-y--`!aM_u{0j;!Fto<l5z+oF!G3ZcUQ6@`t9$?wBMs($l
zlhphcD1!z70000BPG?y^pGP$GtzI~+OM<`MmG~YOkY9JlfB|jT{-A(?Kb~|k$M*|G
z42Z1n6dih!6k_SQf6UZU9ijMqbDEQlgVKtoD3V+5ry5x2Jpjk73{4$MS9r;5YR^kV
z^rH3#uDk&tB%f-BuK)w^E}{AN>C2z?yzU?CfrCdw__<_IPUt04Hfmci4SeN10WC0{
zolJW(@u}Nz7m~|l^w7mqIk*A==mCk?CRO=I1E<<%6Oc9pES(}${ytXGJJ80nItJJP
zaHI(U6=#Xk>9{+}o0ztbyi(9ZLb^v+7=c=vqWBjh$)K~vHG!yIWfaNWmw?Y9C-n@y
zYgf?*95Y+H@Ov!US_Ie)<|yi8Z|AT5^fGfja`&P#p$->-+I96hncbV%srcUtbJDAu
z&jiLD-SjkU`|AaAgDbT?S0-^F3b!k*OBnzB+0t-_I8==68WEQvouy~TfB<3#MZnyX
zW%Ek$??Qg!O85EIGE}cKLnKN~cfnLij=;2~l1vl)Z!|QNhflV5Z4nad-%{;PrU#7-
z%LV5FAHtD6w*>mvG4*nOmMnk^B&h^~dm(#nNnKs3LT=%?#S?6)52-KmM1~f~c{oO2
z?ZoJr_qFGxAK&A|L!(SaPL-L#m~w4Ub#&E*zPh4DO4Zy=ng#%6e@fpN^`P2F6rfb0
zXY{~JGnEbnswHuV;+uwP)qo16_e@m61t^sUyC06HiOX}SxK55@K_R){A77$Kd&*<a
zG6GZ$;5Gr=^HY*5r2s<ZWM-)SOr`(@bpXa!c`_CBNBqIwZ_Cr8V*Jgp=KB5hi}gu7
zLO_fcVPY}1;p||Wq%#^0foXo=`8zK=m6-XuQbV<ZlFw|Zo`40ALr*5jS>ZZ>AkrWp
zMxdUws!}L|3~qr(-NvL^%k&ejrF^O#%W3CF%k|sQAXL#k8HAD^#be*l2sYoIXqYv(
zju#Q9_K<&j44x$=u0PQ6FrvSwVch^2;5RTIS|cL!2tC*$;%(q@&Eqb`Sau45xn4uy
z0ChS*pRexWk%P)|6yTi`)81&D<=A4g_l9V1$3zr)^$|-^1)u=xJ=4>U^0Q6dYgax&
ziwVj)O{Z?p)VyWnTLB;hs#iqj^duXC;C=cH)%2ni{&`7SmPYQ=WH^}B0n4-obWdz1
z{yR<C5BfIvn11^4M6jz)dFfUCwLHhPdc*ML{^-|3m0gWRr){}G2OwWSl`>4wH&JLn
z;qbU_>`)HabU*tacj5As)ll}Y8mfr7<SgF0CwQEL^4zcB2IL4-W|x5bM*UMsis!a$
zGUC`Z#(o%L?otJ<rS5ApfbbjgOR9VFo#_$A^aDS|xJN4p_Tj#xvC#;ykPYAfoCVGA
z0EjKS+y0hmyfLPGp_nH=8&4B1YX5Lao;q(Jmuh{blC;kYBRe!>v_uP@=fkuW5=GzV
zqNBBHr$S}OzS#ZgTLO&0@H@RPe$(5MtWjX0;TViOgy7Jv0`x2~ub!cd4Wp0ADxxV*
z1M-NMdA|-i9|#E~1EvO!t!TPQs!<j1JR5yRq6{nSq2|6)_WWs*5!ff{VvF+Db{xFr
zzSwyprjD>ltP)<cr8+5*i>3>h-19FRq6nVE160{1=%v#S{@<u|i~cBS=Y;*1jt~i4
zznl(cgPln3a?qT6Jca%OQgKHMUYL(G(QwA_7wg6zXr!9@PU1Cf2xtRSt^f@Hs40ML
z-dU@zM_?XXe1cO<<r#%P&NHsS#4IG$-;O7))sH8M{?{%Ngqo&i5P?qxG87y!6SQR7
z3<nk}3PREQXTRn8zyJkc0AV2D_c4+)h1g`8lvU4f{C~RX(VMzY!vK=5T4KXu7*S{f
z)raYqeWr**(7y12toWCmhGkm#K%o*$?S71}1)UaOPSTssjh$kI1;#;Xo%k+;8Zb35
zpF_9+;&V$CZAif)*2xUW0s<lfW#R(mB;D|hfY+7+P>`lJmU&?W^x}Pvi}41xkdBgy
zEnjVXa$fAUt;PQoU=AMiNB{&!$@sZVvM(Z(0HywZlL#v-Z!WBDPwaI9l09Vc)@}G_
z|4piV5B*-c2`lQ#?jO3Z6k~)*`Otb+2na%EP$?fbl(?4t->VP-!O6GCmG>75<+C97
zi&LTWjW64KWwSxWo2#o^!ls>VAIH(nuL4RJC_n(&nF}TZtNmMie^~T(2HAh{M6gUq
zy5Mx*3*Ik`fm{?Ix?rB_cbcW&jAhr~_0<CSb;i3UVW8nFcg(#9>8%$Sx}?rq5L7^0
zcI-dVlmvm8%VSH2bx2i3!@SEA0Hgx$D3-HirQNK!0n;=$Y9SEf@GluuS@^4h$O$h4
zZ8K;OTZcQDILYJ!W_K9)M3;~N09-92MPE%+7~9n>6=M|WV9AI#^YY_I5JK7$(Pe+1
zO`!>z3B5&}`Zye_17iIQ=E!o*h0)5ursvQ`v1jw#8JZ`YYbb*r($qskJ6Dz2WmB5K
zGziN>M&?{AT-kNn&UzFfj0V0UPi01AJ2oCP<xa2%lZq#O)Wu)<R0OZS`2`T`NIw7v
zcg)P5!rBfTz!o3&z#o7UhrrLm+WI=6yFgQKfh-#?|E^tK|JLp|S(@I1nl?ZR#vDd{
zOsg0{vLxuqYTDsXY_`<e4}(nS#*iC^RbxA23VNc-KZ~-|q@|AEV#A{0NGDTPH)&Jb
z$=MUfHYOumZpe+DB_r-h^WQ`Qk;kCyWJIvsK1#&+QoGO_5KnOY!X4ItTyO+@JuDVn
za8Fh~DT*R~VF&4713m!7RWp?x0Ksgo6+EN*KSor%#z2;Z<##o?-QEB^*LCFpfLlWk
zex8lJ%weF)!!o2UmPXt*RK=>*r5!fNi-!WSR~-Q0P4zCf4bv=juA+G|wpTfsSm}z~
zZaYG_hK$yNU#ocWTs06LHr=atKsqX@IhhbpaEX8b2^;w{>#yo7j}mI=26P$<gd3I2
z3Pj2zt#u3=bF5<iRPMc^o8a!;B%#f@5#O;jMg*wBFCswv1%{jP)K4^FH5Qu#3<Ttl
zn;HQIPc}z$h`9b7FF(Y6^6Ghqnj7_iKUo!2e0NeL4HQ?o&`1<P=*`wDZWyk342kO(
zGgc1%D6NQqFgjperO*H+rfq_m!wvv3>!Qr>*sF?w0%_VOC{5O20DdAIIa9LxkfJ3T
za{_i<v0-JgEdLGuy4<6P6}A|y5t&CP-7JX(2>XjzsT3zZRzJvovt)rb-gJU)4%I>O
zC$;yXz9=>Prs3rdB5=$S+}8qJTjPE7`peaB><$irscccQSuh|F@qE{S>GEDVjtVWX
zRgtKOKv{gU>G~b*wAPLy1w5AWp9R`6a|%zXKmaa8EHVH|hEt0div6#VE#Dd%ho&<h
zS-j8L@_r0aXKuSaA%FlQ*5dPoLO3em0I=XJ`ny}+m!K_x0009z0GZfN1YX^xU{Fu!
zNW$rXlhXscrZ@RYulQ9T+<j{D^{`(>)=7e)645@uOx@TXtVb{bEVs^;2|pUcZhwp<
z#EK&5C*|OR`>+521w0de952cnUQgRkU2iR#S%~zO-ehJCo!F3s$JpzdIR5FQ(7Foo
zUs>f<+b4}q4K)1h9!tWA1&vyjqrQ)oX@rFYNTgYM^e}A0_$V1lUng_)HW|y<fd)#%
zGpA8+xD{_#Um@hVN;k2yJAB=Ly2%iD=S00;Saf1n)7FP;(SeP~015oua6tmqz2crU
z4Ae;l2D9Fcj1CxL?5}tSGh<?mN9r$j^{v-Xz;kI@bVwp3`A$9BF-|@qegQcr*(EfP
z)4<EZ$f?*&9{zvOBCJNk!k~EDaClO~#+a0^58z{XD<IlWR3F*R%fhhJl=*{a8IK$i
z6FxplcprjTSH(q4gph21N>c~`06GWIoL**^!q}reH4Ej+@<`QSUAL<;tm?FYbO@D$
z3Y0d3ddR9j)6)N=<L0`%V)~Gq`*2h|^+vrphJBlnZ5epYkjDGEJp+XAN@>j^tReF7
z<{8DgNwrQ*zyJiagYf&}f7IU+M=ab9?hTc|r2%@!Q2#P)AD6>Xh_YILld?{hy&#2c
ztCo|0DD2wQY2x;#<r(s1S%D>*gROu~s1?%y05^FYI5<E67N7tE5s{Me$%g>Py_g~n
zMP0C(0f%9|x169o%a-JbL$yGB3_kh!-T22DL5Dc8xHDogjXLZfmu%}!zyMB#GlADO
z^NjO&=ugf-2eWE-mWOclFPPH3PopEJYT1};dV|w|6SFqO_?d~NjIU@vF!;30`_jYz
z#;^TtUp@C6v0lCC4#%)j@R|lAyNNZErxT!y|9E)~!mNwN_5cEwO0U0L5l%-C98jq%
zKoT%ff7xBQyNV_v0000#_yX7DEmIOeF3`-V7^R;)n5g==LV$29=0}LJJd6Upu&t*X
z2b3bYp%6{zaCm)F#7BfMWxuXX53IldK|laCy3_#%G<|v*0EGo}t$^ksD}$*SHTKZm
zE}T`6UyFW}OUzucb_NO4xYODEC{z`nP}%5VDi8oOLgW^?dDvA<_!BXP$#@~In!5e~
zVB`P*7XxrAw}h=6UM{;Dn8eCb=xD*Zx*(5t+jskfjlP*TFb^X+q9&Z`By&f@uD{d$
z<?11iYYWqOzfKA7ckPy2p=d!F^Lon65|Aw7Xm~bq&sIhcizizE1*98Q<uL^h41Hv}
zR+)#9&V&PH57mzc;JtTo3y>$l0+>P<udG3V@FXU77z1mtEf<_D<Wj#xJ*|Y)Zb9Z9
zy9QHIvNT4wqT)#X&l9!LI=5beqW1l}qGoPMAJM6r+vibrAE#IsSiBFkVYt&^Pd@cR
zQRK-@nh%{zuswK@?Kt1#reOG${LRiB6K)FjspaFv^9T?uIyaM(=ltxS`LHtQ!55z{
z3Aq}#aZh+s1+E_38p>OJgF|bmWn8E_Z9qu&U;xEN@23`HPxt@=X4+IF^a8n(8*h?z
z|7x6@1>;Je{Xr<nOSp?R4&CM_Xlj3D<oX*cMJd!qwTHJT_BgTcPB}z*H)F%Wb&Dmc
z?KRv<EAs{Le4=Y&9WpJ&Yp4LVbba<`D^mxjLZ0$-d2^yotE3I7%?r#&@iXHpdG);t
zxvSkY@zP4dnca)-@bzzgh${c-Pzc(vW(6i@w;?s243z&bagn6OOr@NQueqhAaByEC
z0stc@gJ-5qE1ds`c>r-R*}&f50001TO|(%m@Bjb-TmaULHC>T#Ga#7D+e3~$x{I^D
zZ!R;P1^f=Q*51d{;g8$&{a_FKky+HeVhn*H0dU@zB<9EsAHXc0OuW=HWsPrK%Z5Hh
zuUT3#t|~*@%fpW?$r2G~0Bk{{6x*is0!adycRBuo^F1WZKoqKX<t<(gL&LEPs|xY~
zo|wpKTGKx5Xv_V;v?st+fxUAaaJ;W!!v}x>6mDw(6s!OM1B4Vf<sSnOLqH680LZ2X
zVuRLrg$tW(GCD`H*<XMS?FSp!h9GuFG$5(A$|jaO9>nyR|5qSJH>~%fKUEB@r-QxR
zOwC$AWC*uyG6>$+Q}3<r8@r>ELf7;88CP$gqJ;-sh^tl`e&k~U3?W45DF6m_zcXIn
zC>{oR2QBD*I-w%OmP4>D*L242fS=~(<U>P%+(gI#o`474*1!NA0u2=NO5mh~03-Ck
zo=Un7;BEjqUcI`U@t#+W<d7)gvS$`#lMQTi)H4kM{X*~#2IOXUAv#nHs<opq1R%&R
zl{cDNFS@KoBN2lja&&1q<$6aj+gn2??lA{fBzGxCnKNpLmm;AIMwMJrLXiVtEb_U$
zi++2N8I4A~&@j;{;y+E$=;D$D3;Fg+gv!)QVT=@aST{Hdq8L{5cNe+B^d~-ODemxf
zBmg`kxWpvyi@*Q?o`3)V3oiQZ46$$o@<>$R>^%ZRJ!KuLbXw%RvewW}`sYPjUU?^O
zrw~*m!Y&-3cd~1N56uIrb)RdQeXh5W!yYwcd~x${Vnr;3p9(ZztpDc=HElX11P47S
zy88C)X{HvkyZsyY4A>cZlgoXFO7LF`k5%egoc?}kH>>h?w(4FiRBoN9l6b@c-F-`~
zKBlZ0&@4?rl*{u&zC`bLOb%_-#$?;2xB!M7Ei>YMp8zYE!2kdWyGPJDD>}KnPXMcW
z+XPMxvIYG2R~2kS{zW9Runz}Azq*T6j(}%Viei^aT7P``Jdg>Q#<1^mZS5!ot?FV0
zptaTx`yDchHD{=4)z1=2-F4BvXIZhE+q_a3Xh0@sFTF^iQZfs+p=Y;sMxZr`F!(%n
zQ!%6inDcJu_T2c@{F5_m3pHr}!!K)6Sp>vAIZL^uTxNlV+DJ{$RhSvmzyJV$4!eXI
zjk({gBb1UWG(7SE0fPVouzrIEK8HX!0c0?8tazi;Bp`Ze1)1=6q%y<aZvXowil4^%
z2=v>h1cFno<se!74aby@;wM)#icTy(fXhzdaWHjRyoAu2m|K;)zOe_%rh-0jGnTG4
zVKtInKr*JpfZLz`IeHqZO`?-1ySr}&ZpBp58Q7_DnE^>L7#0Da-7Bqb`RINpM#+)B
ziZyE&=_SgAWB>pF00aBb7e;o3RZ8RWM}m{5fgt1p0EdV(bP<qR;0fK>{=JNv#JNLv
zO^dyO{ssmt13c$Q!CwbE!FV_wI9tA&EXRPE8Xr-m3XBPSdP!W<OHvdQ5#cPV-$;pY
zJO-_dq#4k7SK70UnP>kNe$yWEXb2(<h<-{}aK&*%bj;z?l9S6irkwUB{94h^q4aXT
zEeiSaevVD)36>UJ%#&mJ+r(1EK<>zyO2bY-Gl2c5tThi&yy1o0gunm*3BZ0kqycUY
zqV2<$1E)l1fG<M)M+TjCG!It63izg0h5(m`6_=&?q@<vLNDwg+k7;0;+cPT(W0i?`
zekIEpMdlNQB7Rw$E6dmC+=OmxG5J{*Oq7(8bx;s1DUUOzlpwv%rpl#V!}{!5sXoKt
zN}GR(4GG$E0*8{>j<--Uos)Sq`PB+R21SojHzJ}`C>C`j#5E@33Asuv;F=|Qx|Uv0
zNUOkoEE;EK7*(fwW*6!PoI3@1P9(O7S&2m7cfgZbF0laH@Y|&aOZ4?4hyVZp0Xb!F
z!w$kATn#+Smnx?P^Jp$IinTDmN8s5#3yLQ*<U$5CRd)d>0B+3%@T&>db6@}oK&*(9
z@awEwj79iv_`i6dS+R}OufseCPnp$A*fdNKno|-ds8jPL!p8rRf$(76&naX9^u`67
zxvA$O4xPBWtYoSP)+|pxhPQ~DGW)WPGljAV@2^q7DmSqeoHD-bJ+CLK{G|BdcGF6d
zB98vO*TES%?F}4lc`MqIV%h3$`z;gs38M;4bb`n=RvDIxz}<tmpa1{>0M@cCu$E7b
zk!ky;YhMq!%*h_tC!aXf=zL4k(1pM%z;iE{-*I3I<MI((I=TFHLJ45!g6oas9{+75
zutEAEK*OW*`PVj{R)tGuvqp8R&PEg{iCW401sDjN<@2_Lq~T?#>#MW_Xtj|5FOUV_
z0g`sd$XL)El=;(XIww6ItaQ%e`3Q!+AJ=FVU+pKcakH|BiD(BJk=5!ffDCR>!D*`0
zENpsi4pO}Yd1qh&H>Wvj=@|e>s>mm1vNndbN;n{UFGO6BF~^cilygqWXadwvWMBXT
zV}LeE^)>y5x>luYjmbfG5}$jLeaq>qF*jcC@JMCJFF6kzpOdGRc@VU>I^VdK58O)R
z`5p<BQG7qewWEF}dDHUWZO8c^7TSp#FPt6P-(oV6clY-EUK~+k6X^SIHZ@HXGKKth
zd!!_7US)|QHu~JKCP#>)A14=wd@)*hWM2RP08Pn)QsGU_^mij|K;||=u%y$t0eGJ4
ziTmnP@;m{bow_{>y>A*=#D-u11_!7Rq=yf?$>BB(zziYAySbYt$Cyw`ImJBj&#8E_
zz2)FN*Ej1v+9=`WVY$&~|03%q>LtA=h5Tms1CB7SgR~7M%v!1CJqktQt_BvI{OZk8
zG1GsB_)Os;kH0tH*z9FgI@0xluYNj#1V8|7-X*;&;W1Mx90`bIZZFXN^%L@^*LRem
zJZIJ<LJaH<%o!PA19srxDOW^?wl0RJ2?PQWo-+jF-h$Vw+Up8UC&cEo#h(?cU=V;>
zWo3ipyH@%c`YOr7UW8zt4U+0@uEdn3SI*qlkHL>#5vD-O0X0XIvEja;3@sRGQtidn
zKJ^e%s9f%}EoAO%d(<$e3}=9YX~<w){pV$Nmh_sEOZJ0&0e_!50t-2#2@_1IQosNO
zAnq^oUil(nkI+4UTTx~m-jjPR7!ng3M#4wmjXz=7m&aCC`n?5uv;x3Pfi7UjRiWzW
zYGz<fsQ~!$qjqCl1LU!XGoMd$Op+WU+5~7r;l_{P4^t>PB3Uu>DBQ{jigb9n)RX^c
z*__v?E#=%qUIW-Bl4oMU`s`@~_D?e18+0kgSQQg@-OIbAJ|bw8FZ!G=W+f^nqW+QD
zZ!V~jJO3*<A3zM60P*;V$l`R7APax-fYX{Fahyqcu@{tGX5eEuZA*_p&!DH|D&}N+
zfsi2b&gG;na|jlTTk9rldj}7I;z}~{qMRTkz*|8OI>&Cwu>wZ$bZT1`i-z65ik;wH
z9Dv3Rs7GSX`SuP@H^1Q<HaXNZ5zcR1#vZQdObmgCh$HU>^BIa+{$|2;MKkB#lko(b
z)yg|5FsA7YCS>dL1v2s=^fAhrF75NCY$wd3NA%8;=AXStOF$X6iK*~7oX^AGBNHE5
z2WS067C;ZhbKwDwMkIpEhqR*FJBMls&v+Q*c)tWr39vX$s9_s<J@I0hhW^!Uz(~KK
zfRmV<I4>|ATEGD6vg-6K7VNIqXv*t5v4`e4^1Y&30;Cowz@@HNz2qS+TG_3jDJ_mr
ztox;$J}I}aWYWo7_I1VPCdr4AH?OSh@>DqXjaP)8BaAU;_zQa886P$~w6ZUKwb78^
zsd3PXi9V0l#as<0VVRU>WU0+Ih5wdlVMrX!9Ar(|@t+uEiBPS9c&1<xyR-s}!7_A2
z+_!H|Geyesl(1_LNYg;HbIkK^De#oE><A=r{@+ZPq^K9S#a3d4Kezw@1k9ieZ;eeW
zQN~qIo59$n@Stf4b^ml<5Fv<gMTmQ>QBvhBTn15lRe{Tplzjkc&dNvNa537Upc-dj
zl@(a~-P)!>JzT%Mc}##$poaHzhHlmmQ_zEvOzpDgDNI3_#&~|&mUIZQ(13>Ek8lm!
zLZhx?c}WHyXa*uu6@#EsXx^=s<5Y*qfKeb+gQ8}Omg7{3QZtUu=?ZiW8aA~46zsfS
z7q32uaxMe0G{C&AWRRr*6yk}``u+d`6(H_l1D_<-hE@MMSud4L?HV&os*825x6?p<
zWH56J9(O;)@Pux$AR9H+rLVRZ{mQuZ5=3}xNt)+~?54qVZ<egKd0<WgKp1shEe`&R
zYqy|vDtoZO0e$1Kp?c(5MM`1e0F3lfqtgW}f@gxNa}Wxt*;tUH!*M}5!HC6LqlP&e
zst)Wh7EpUM3;3HTZ}a409H^Kz;B~Ym4D6q45u1@ss`;^{OF(dyh#|I{MM!f4B4P%M
zRR`2JK6$uP4o6e_XGf2{SSb_DNvfOtB69v+H`Ugw+5K#gu<E^0Gp0YoWN=t-Sd&s6
zt-ObDGFs?@5IE2ffB@{s&zLhMa5dbTq{ACm0nWes_Uty)ZtVcp8KykB?hVbZzdR0t
z+*bHL#0!r5c_>ci>Q^&I-&e^Fgelae_x9_WUl}CVD3Dt(K?T+U&>zUYTW{7K!!OtK
zLtNJbZA-ut3XlyY2NA0B00m5C5_t^qUE`_v6&qGqNLrRl&l%}uTTaFVE#{2gq{<Fe
zo!<Fcqf_wTJY+#b0Ar{(f}8z_-jG}okz)9yinJ}R(9x6MVDHiAPF(QNs0ZjfKY9z}
zPX*d4)D8gKjVT^xcwXk!GkFwag`NkXK+6t5d8myIS?jU%IO!{Pwg|yF0mQ^p*l65t
zfxPihg1`V4$@>FT*80t<-8*XEv8(MU2%Rq}#|JbU9mul>5AwmpdG9y`zRW}W4)X#;
z9hz3Z6S>{H=EPo#9|>>pfOD8@q8jJ1lW@*h$JqbDQ+@*1&7&eA8)9L{59&gmp7V(b
zW}JgSi3>RcaM`A-`i^)$ApxEYQ$Oyz4l)rKW4f}PdthMc!ctXq&5qUT2B0FKXa7Fb
z#I_fxfr;+`PIE8$B!dV7S~K9uJqQbE#Ar}JLUT=MT>!oYN=sEx$xEdF7;&KwmE}pj
zquDh6nJ~n!YRo?hA|FByOtFc9!o1zqw#N!4PY0WJP0o(wp>%+cnJUrgso>^p8G{4U
zOYIGEHeg1jj?Dcy9z91Kkd*VboMxFzBh2NFlV=)L9x#2D9lh~pW33>-CJBd@mp}zN
zIs@yoFwg)3$_`c5QrP+Vjvj=IY(-cUHSW&SW&mv&;_@%|Z#*8@k)HKG17Aoe6Mm>O
z{fT`<BGfmMiCiGZiKSY<v?B+O?o|yRLV;`S_Y@{x<?P2B%RcxdY`uv>uczG1bRrR;
zKqh%>aRyo#5^SA9;GF~ZcDTS5m;fTVMEgr4xHN?-HTN)>)5PaY#p@ZcEOr#O7zsVk
z6!W`b0jdUqK6;`k>nH+J6jl0JqjH+^<(Hw6H`ShcPAUi$_3xk3i6m<=r2tMEFSM%5
z52`UG<4}Y6HnYyls&%{_FQm~TvhDl|;yiepV6&*EL8;@^LpGFFN)j1+iYFA)zUmXW
z<U9BS_<FA|UNC{+*P3l1Yzw!s8E}cGHi_Tr_d;{zGN1-Pe^zcQwte}Mr7Rfjv>Maf
zsMCd(Md@gQ`mPQjCpuB&4ts%0swXf*bLyeoIY*T6@7pI=LmqtHCT{u}D96J?V_!UA
z?me%y^z0a1UvG_wK#=e|ksQNl4GiI3Q)vL!q&V;C$3#?UNKT72)CtId*n-UvqFlZR
zys7-Rj|K1;YNjEt^g|rhl4z%b1fbG3kHbC|ABX$^USZdxhc&(G$OkQa>GJ$b?6i1`
zOemmJ><{eKjR~(_AkI0GVnQ|EFcW6Ulo@1w$>8`A0Gk%4<8$<2{l#)rm=kL4*Xs^>
zKvT0?C$feXE>MA;2f#ak1@>A1nlpm+!>&soHD#(tUha7<SQd2r&T-BBP!&r}MG-|}
zAZdrHz2egSxSrR-4$JQ3Rgq?x@;~cgWpX6Z^CxOLqo-mcje!7ceh+x+2evES=lrMT
z-QauNBtjr!ro<<JVE(p(Qq(TWMTtrF;8H6Y-=?i@GX@#KT{n1WKn@qbH=;+t3>@QA
zfP^ogt>YGmRINV(QrEhEL4Lw?_ADA1TgI*FdzAH=TJz3;+XMh~xT>?7)$8I(`8l%$
z?Dg&NauYjd=HshC<{)KTT{bY^i5~-Gqoq8#L72@1dVOl#6+H%!?{2z8FLuTWxwp{)
z=<>t=Q$w1a2`kYtN*~t3Bn`+p8iIOUx(kXB%aqJk_A}r$gbJqgN4esd4gh38VHwBp
zx~1*AujSSf%+zOpqaZO5LpVEIOLy-+&+*#6peCTsDoEwL)F~%>A%H|mGOz#xXPlU7
zu)2Qays293A`>$u!UL#bjT_y7?x3`1#6e-n;ct7UCwBi@>*|iC8~~v%BdjnP?RH@y
z?hg#}XdnRJG-#?jAOW8@hev&RgVw2lxNf}fE}~2t4eZm5mP;`SWoJ!&B!H*L#|_3k
zKNqe}ij1${f_u`mxVKs{&`rz}b;hx1a-SqrgLUaJBeN1i;EFhS8bkuLI!pdO4n+^R
zF+<aki~iI?RC-FDVqFQ7`a5IAIH_uTVElgB-5&?EmU$(illI+cu-<@ydE`G@l8UJ&
z=O@XbdH{GYlzWM$1`_1V0002u93uq0`Q!&dtla1~Sye0}4$4r->hrMmo2U`f$)BaN
zy{76LgRmtq%Zhf?l%ZJ*DYT&Hlopm?H7M`88IMbF<qztnQ~{CVrIqt6+$V|WtD;aZ
z^;hSvwaiqCP)Lw;z)^u!uh^*#+99!4L(geM+P9bj?4X4TK!?(ZgpJ_#mYr;JR1`f`
zk**hqcEejZosGI+6)g<<BhydkiE=89yDWt|6CO}A_X7+naF(y#`~}acwm=b5tc<pB
zIlMGmY!o4*>&A2f_+Ae5&rH&y$?<Dvdu{K##xxF2R|31RB|`5U^b_p;JXLYM`s%_)
z0!cl2=bmlWdE|CeByhC-tF1;$4*79b*%0p3kdCFIJ#(}{VpE_!i-!2wU#So3rbpUy
zYit)E^FU|LEg^7T0l%*{uQ%6#cujnj>)B~00Lo|ltH$2HG+u&tb+qyEm@HU@7hUFh
zbotvnK0>)mjSp`dikoAc$)(I(W^}F}c+R*2jDN}1Lfu^k1y<2iXm!4T0o|uGU=mX{
z0+q97Sdh*^E63B_&w}3SmQf(RpTf3ozq6mOHd|U!<V6(`dE)g}Hm!YK2^LN%&n8`s
zs6D$`+}U;3>wDe?xF`Nixf{^}zlC#_3a{iFhC84-qV#zxN@Cv7;8N3!9ZxaT3xJr>
zyJ@(B=OP>DcBKdYs6H%kf1dewO6$%YEWUp{ovqzH*>F0Sq%!vc1!>{T62cuYygvj)
zkqyWAYtrXH0UtqLeuAuCi{Dq+;*z8Xn)Z5?zQl+|cAZF~X9oBl!kG|X7K`N8{M)}Z
z84w82GvOo(WQVSR0)5~B8QJIqZd1oHdYb<s8aP9CyG3pDb@=j94}8Mr*d<z_mM$+2
z3^Iu$=@U##uU&;yf=pRE0|?G)h*AJ8ps!?=bw4s5RfM92cDUN!SnVNTfn>V?;$Q8Y
zO%Ehqg|nt_c+%mL1S6pwh2h%28;M-h^N#)yGo|GA^Z&{5m`qR45qQ)8Y2HA7Mi;$d
z)*d%x9*Lj~f=ZD;&yZYl9tGYa3JiJGQ4j#1A6A@^wQgLA>=Ym%_{LUBYYj(q`Nagb
z)OeVEhN&KVEM<!uoqic!h%238l#Uz4ErqOzO27GmH|ln^N5mjO)E!qrusMF6@Tg#e
zD`s;fA|EZOfZ3$bcJ&y77dbbTLSz{tTUBm=0x&SU{FjJA01@yJ>o^{9JLh%<(AIJQ
zxaaVr?eY1aO4{|tUX_#W5__lx9rZMt)cV<B9N=$a$k$+)h;GW)erTq&64RA@a_f+5
zeVm6tqPk*_oEmgkJ|O5MCV)Ey8kZz)dICv}jgqUQjY)*5*2oX19nHwt=LV$y+qY@Q
zv&o{H{a~p3XCX*w^GY2b=K^5(R!hkv000015K+Tv9S;>8aaPFzTHrc`?$ePhl+Y~)
zob9$%wdQ6{!@#67wbdpN22XXlQfzs{NoD|}F&as{UW}zUu4Ik#>e<$;;KXdn%#}~m
za029Ycw3Hu%R~yDcCqA)I(h&?qJYLZdw>|40|Q82MdJ4On~?2b04_rmQw-m_J$dc@
zf^>yY#rsI!&Pg?3ikrza#d4xn2w;lA8TpP<L!epB%9{mCPJ);Vq6%-r;T9mN_6U=I
z-Gj;nG@zz$A=J#LOGwj1bEef$H#r)`ku=l$#ZS-IF~6SvW0!~m1~qMp?8y<&zY7Y%
z1-14gUIG-q-2^#MCg5Sk8Kk9~ly$=_cGH*^al8PMgL+1$>|zo||Gd#p^~H&20j#9u
zD4tThVBhgApKJg;uk3-uMvUZJxc-SwTz+AUkl}6u=bRlnQeBKJCW9j;%|%h6sRtoK
z)fpDKUjrBb8ylMXIWGkMe7W%cFTDUao8Z;T<kByn-ycsggzn7KNhU)b%UO07WIX~R
z0Ea3CnwG<RVZee$8~HW*@5LopMGAF8)fI~LKZ~@?jfzGuM^aaL1YjFi$i+{*sz|>h
zqYxEvJr8BK4*&$SO)J|{Ir$fJeMuw=H2cK_Ansl6_6B<=%p}C>GnT@vr@sUCOt>H{
z9R*R`*0nN*ojD{jF1}$f^CG&j8=nFq0SM%}G5|zdMv{o7BeB>9szdfVg6%S^rosWT
zN#t9i`Sc<@08|df7s)v5?roH?o*lX(XJG>F!XA{#d;+5=FjQm-hynR&$6t6ka%3f!
zmFZU4-g(xi&WvjOkfdp~=w=7m=PX0@No^q)ykCS+g)cfUQSHJT4qmL9tuT)~CjRj9
z*Qdrh#UQotM-)kn6wbi{L8_1bj4sJKyy=Rt>sAEofK~+z-pOh`Mkx6F41fS@Ne@tN
zEEKbdy}svtl~libO2k5TT3S*%l9X_i8FY@RWgi8zJPX!8#Xa?`bE})rbW0`}LbA4L
zJN0$s@1pCWW4TNt|EtJf@v{@>eUl4*8oj}AnuNmG(l0|1zQ4&X>B}Ceta3!Ra;oTI
z-#^4ez5zMe13s4(`Q=vagv{0g0Jj3NF}bf02?#(;K+xRLW&6%2z$Td9+wx9rbf3w8
z$yX^RlwE5p>cw5zJBcYdK{wU0C|uLODBUG(&qVpenQ31h$n_fx<5{NwS9qn%m>8?x
z<SM;0jXBK83Stp6$da^9MqShXL>m9Cjiuw1%9(d&MU?BfD0uF>#u(@!jEp&I25z7*
zHvHa(AO#D+PJeI$Gh~8zdqzMlI_X0L{&*MzkNS>|f&yq6d4;8l$PuLn05nr(QPUs<
z4n!^kxtaiDy(RpCR*vVdj~$AM|MZZjP~1%DN<`m38ab|Cpe$teqjE9Xl4X}(2)Wr#
z`n2rz-M%rK$BhMMeexE=azL>~18?+X#~{Kczg(S2CrBmsLvA9J5RpTLzd(Cn>Egwm
zp!6bk$H7c^S9h}EGN?Dc4OEI02+3R&&SX~@{tZOGRW;dRXL=;dpNUyM?;soz;Gc=$
z)Bs5M0Mbl{h|YJO-$!5?U}fg%$^8ZuIg~J{2Yvz+==(o|hQMtEhKe#Xa+p{af`!{8
zXcyDA($j2Zq}8H!lOJq6WFg6f0vjB$b*=m*@L`P9ecqZlf=fZ&!*E1eFe6^p+FeRe
zrN~fu^KE2P<<EF7-Ru_<J1bz;)Xi=II$ztZ_ut2hK9rV*LhD#Kd#R9nu}@Bs@Gc+|
zcBP?7>@;}M8|3_HDg?}HU`fyqL_Ua9A!YHY3312(47Sqp-3IK0;RU4uehDMMcDM;c
z$|WThqyX71nqD!J>ydd<I+gWN<t2cAgs70(E;pML$NPbB7bVBwR$W2(b#X$%%Lg4u
z<B^qXC&W%jVj8V#hnKWxOqHe!S0|?mVgit{`Jl`ep`T=LJo(2Gh7GjumHpT}R4<<;
zBh-J7&v{NvL|lUwY6*m5Wd(=h1J#L*1C>&!Yu0tN481epirFR@Dx}2l5jRbtHUpG_
z;Vya8yH3lCa5&u9auX22hL{}mTsCMGq;VrSR-7`apMg2)1y;W+kQ=b&_^pF<)q(@r
zsQk8j%ae%GyCQG)27Cft;0`LY3W$MFp;9$_$adR&?eZArHDi~o$QxR$VYgm~02*RU
zRl!vViKkG5&$b77x!B|ERWCSr_HC6?dGTD~xy{^O(uUr%_u_@)w{*P4PNxfSc^h2=
zT0}xUohl*fH|+`4+$ELyv{P#(h@K^#R|}HF1h~T|+GI>hP1$UhzN;4>VIw<veQG+V
z>?6GbAXz5Ky-%ny%DSrODYyNAx`hD=mRX@|)5;H0Kki~z$1e^2(XvO}M`}gW8DGFZ
zJ+0ebSrN@azA7Ypx&V8~;8)l^%KEJm@RwL|^ku~Qqm?giW*RbW2RSd$aAReU%)k#2
zPj;3ZTF_n0BAQYiy&=K`lh5SwE`2=b2(Tsa=eCHifL(g$-cS3by0{+B`C_AAnc{bM
zh<Ynn1mJaHW_Qtj=D!cM&*Odk!IU9OA9Qr<WuyEr_zau=|Gq^%oMWOc5~revl;V4R
zUKo8cylD;$GLu)~sqRT4SG8w^6t7xd;v08P3+t3|;)xXBB*dw`yL-F4P^<KaGoiS{
zfK#rmuu;uudap)s`jU^l|F>I6GERPGQBb#1HGv7je)*{Deqlp~{5sXC*0D~H-s(Gw
z^`Yz&C60#g6IlNNu+T+pin85rz$>r{eOlb!Ac?#>HEdXQvAe0y&j_<tr{Bs&xJ?8|
zsybX^Bmn?-WbQpP9NnIXF3D)*e+it=-Ijm|%1sB?w2Y!KYcpDWI`-z<rj2!<8B3ul
zT(i33B8|(DNZEBvO*L%?-ZRRciUnmX+_sqQNtK=fs69PbtbFf|6*U=F>&e~alaV&#
zyV7hqf3L7%?9e+b&l4t7lJALYV#c;9C5IH)jFc^J3sYf!f-4B0=c!TcZl0sa*(Kt8
z`fc>{cj31rYW-UTPM6{0CAAE$C;Q}_myX*E(qDTYE`j(S*ERTCJgdtq8QKRn;=wsB
z1<xpXBRsW3uL@+u)<2DQF*Me#{|eXcT3D1&32<aAejl<ocD0zEE7f)Z6W<(S<B$S$
z>p>d$Y*;VLK^uk^JE&pvOd_3|0b>Z9ZF7^VnmGViPJtlVgjoS`R?I8U`HR|uIP4)2
zTA;5JGg>ti+(qI09Gsm}N;xlkAF{4__5sMt64LvX6j3_zayAN(t>^%^2eM9^n=!6N
z$b7jtAPo+Grnx<mVD{;EU3A&}2qYQp>SLS|r{AC><Ox)-Ue5D{#1CSd5K$3__9P_$
zEkJ9yPWC`jvDraMS|UdrA>xfks%z_EhDO0{^2;RlOO>-;+0T0CQNObTWLO0SGzMhx
z(i48DKIf>Bg(7GcfTfvh;1-1>P6(L-W_G5W8Sv@y?;+&*-nbhbja|S!nL@?nJr>og
zBheEy`%=<SjJ1PZlE%$xi`+vD3aZ^&YmIMG@2^i2{)<Y%<kNW}rMWa_+GaEqcvir(
zN#uAbi19KC8YURoBRNZ7Y2ipImk2#bGs*iBAc{80Y2zBP84yq}Tgjs%2$AT`8F4-r
zLLrhvXAX8#lA`A$;8Y{-ew|ZjwGy(v0wI}%)v)a?Q=;4Tc<#%rhXPjukCM@2*?UdH
zY9cn<+={OM-@+))xGk4tKA!+V+{R>@sUSn}-f&6Kan-m4$aJ0wlT2PnwS2+<HHxY1
zy&8^LOMM=sUb`tbYpLqJulYnSPZP-4|JNC^lxn=}Y4QGf19PrSaRI0mTo{kDmMz5{
z1^&?NnJ4zV_-6bIDDGqM$vd7y$CFXRY5-Z&wCeK@*t@WyFC|YzE3~lws~dlIy6^;_
zQe@g4{ExoIl5@~uWRsn+NU#BGa7vny3^$&~Ko#!5@6@iduL+r7@NTW`Ih?D@#LBzO
zJfA7~S<QC<svr*|!R`8@sEH&o^&}e0EZOCrRGRBv?0R2XYD3_&gG9}!S*|F!mFn+X
zZXdsS!f1m2c3=ME5jWZJc?;@HPdxXSkal4S#z7Jk=N^6e`aJy9iG}*oR|q0+;P?F=
zrM(sStHn?llI{35ZTT6m8aAHIeA9cAg_2TdE4QMLc^a`}#<K=xw%=bDay3YJj12|d
zu_t$ln>-m3cQu)X;t<as8mkN=LWv@goQ^b0|LnBJ`-4*jeb{x>Di`HjI@0W(u$-LG
z5h%RS`L&6Uc<ZiGRjO>!3N5mk6Uz?gr=Ai4;SUpcOnewW_XK_S!Z_4AzX%+J;(I)~
zT(?i9v}!`RU|5Rh)T&tcBe4zDH&szgv|_2WohL5=^E_#X$4a8dr)^0orDIP|J53L$
zAFvzlS`EtHDV_!SOvZKN2iv81>E+<Rz!>1tCy2_fzD!Dh@7Y0$l^(QIDmmX2AL*WP
zyMS0V7@l&+r-CsZsQJqcG4SH&_T%z!=J}#%oBvf^ddWXaI?#km2p-{K>xT}wtCuYt
z+QpUhPdq*Qocb)#jV!nU0$xcRL`uQ~&LS+&4m}{Z@sM-Qu?k>;jo~2qXtw{{O6%;(
zPJy~9T_R1|Cbvw{O5Q2np?HiDpa45+X$ridQoz&lQN-u^o1j%L`*5)NVjx8qlOU6%
zrwJAlTo)U|*k%;4FOySo5K3+NeA0hEZ5pHO5cSzbQ9@g*I^TcD<cjKU-o4C|%Uc$w
z*3`#@aJdy$0GY}c$cF&LYsd8B^Yf^*+4e<SPOascn$K&_R5DFV_Fp1*;gdB@O|PO9
z<gZFhzzt+O(K7U4D+fACkH~l(U}qMk!yyiB*kWHqo*Gc<+2p9}ze{%ba#Y7z-7^wd
zIK;R!BiOpYBqVQ8e`g75TwI<AI{;xop1(;wd|qW<;x~+^MekhOpM5nhk7M<6?td!N
z$$U&6ex3V&+A>a3o)Ln|O<a&qPd|9o#4Jtb>ik&r%=PD<fn!QZv?QI{u1x-uv!`Kh
z$A@A92P&80`910;APTLuAsAIbt@F2FdX|lRg>3SbU@w8$a17Q3U8s{XOLd=3=CMoQ
zBYibYQ@%w2o9%uM-I5hR!1<jutJP0kp6(bn>%VFJ3SAi1q#V2yK}C~@KK|JYf1@5C
z=Tigi;eta39U9c&sTpE+i=Dm=L)Z%urR+o+*jG8$=!onsZfPeDVeyH)6MAXV$g}GB
z$Lc*R`ujb)jZ{#}-iELI!hK5Mv9C}i{t322D?M-Wev<j#z8}gmCW1OpKSAMKawPE}
zrh~-~cw4NG6C>9IcbTlGbweHM$~~O#b#{g~b$_}vKEajEEbl+<ek*n#BE*NCCXn*&
z)f0p^Z9ETF1elFswf9M07i%BAxWbl#Xu#tiVXYz}<wV%hX<|Wet9~3=<b|w8y=_iQ
zeafGuJzIogiQ6a%0uxao{ca@ZOj`oCQNVNxGXU1FG5`lCbCRH+-&A>9{v6`Y6|YGE
z^wj>5t>PX4w~MtPv1vr{4g?#ZKmsJ-C?T&J>X~q$JvB(I8&JaMm}MY9{5TA|(QIgk
zbqeur&UW3$->$doUX@;F8FvAu@z(#mSnel@m54^2XbvYYMKCAAgrWF8Y7w^aI|f1+
zEzecFuMg@=nh(QC`}bzPh32I8;S>_|w`I3P3CScD2m?e*`^X1&F_2o{`EAR1c&I+U
zz+Vc=dPO}|mn4_$C|~aMX}`h{u^=XO(rfNZM_~URCSZ+-F_KV{Ep66C*FuVUT7%j#
zM)P>y7my6umQ$M;83(Mb=R)~vY1}NCkY5|H{Q!EAb$54cE-VUc+nSvr@Nb+DB}AO0
zs2W&3t+dp(IvDoclD$G(RExtMr*u9b0kOd@AHa999V1vM-fM(slW^|?#uj|9E2^|N
zh@c+ZK~nr%=~aU3vlZ=Ug3!y?Qm!wHS#L!e)S8<t^gxc`03||d%$NU>Uc={s8;RnQ
ze<dyvDNol7u;(M7I%fNhh@S00-=%(oRk8w>V^7jxmC5OAAIhRz!B>v-_)&f$xIR&M
zZawpwdqtm9l<_+~3M))SyJB9V6qn4fuF{#!`9+#F0D`r;)3-l3la22g%a_>i=#2Lg
zB@esd67IxOULjV%VD9HA2Ucm6$4f)&BG&f)8Z2_jScp0=SBq9@|A{EN&J#SRICgZI
zAj3M9Y}5(F)7`Roy)fCL4>AdF+J%u$z;kAfQmp8DeFX$heQ<)y=0DY2I)F-X)MX6d
zV0M^a5B+$B8z%h${$Cb{CauV|gf)O8U-iSb!*&#o1{A%M$2It--cPh)%mAnrYHo#1
z(5o<xaiOtT0b<Y9A03761T~J}r0|p}L&i>L+%IW%UKU#ELq(3|RND2bzK#5Ykhoiz
z=XUVi3M!hWb~D%ixqqAdh#LaagYQT4$;j?6m)N$<iU!~pHwGMSQc1qDcJ@~qDC!A%
zJ{rgSmB@hP8l`cqx_@4ERKw8TLGRzotkw8}2(mgEJ;k1<c$nYDs{Y1lb1xVP$DKAP
z{XHiAz#v^_L>wO(GIcDS8J9Nzx)bDUy67r%20PuEz;3b*<t{>d!Hiknt;S=s`yb*B
zp8lQ+?OrMv!Wsr-qH_3Iz<V!iohC=J^@D<Wyk&A8f78^j*V?WDeC?&MZF!r&)NN-n
zS3eg5&RfxIChmErYe!MQxlbzlM@|TObW%Ng7sTsF01p_dS?NVVHz#~f6(9fs2Kd=k
z%lZZYQX4aecHD4X%^)gET1F{L6nN5<rLOQp%-Pij_|_)q@q$(#xp?sh$};HG8a~)p
z_XXsm;B>T*TIpbu_X8uIA;?gPf{*N1t6<4WZt!?L!UDP-Zu^ZtvXW)<R&A7&PTWep
z54`lhm+>;F#5P3Aaf_yCyu-h19{=~wwRQk<7OeJj#pL8Plo8%)36YxhDR!04i%@{y
zYyxdLlV+_Qo4MTAvz%-mFzJ@p9$PuC0+0y_6Y{ZIe=P8z2XFx1J;Xi&Sk>R5NwLpK
zZu7)0p(KMJCVYbtFPEH_t!1?QpF)uw56V+ElJeKZq9YgD-vRuf003M-9{T-01QT^2
zqiMI?E<vhgy`}OcBB`jTv-z7#$17>Smv(#jm^$!9FY{t54>&a$XKX<3kVGz+0#nIu
z(6Nd$S^NwikfLQ{M!x!~UExdqz?YnFH7}bj10okXjqB-nE=K8D#LBpt&Emf6N*^OM
zzlZN3s^lv~3vCj&uNJIsO^`;C4*D!nM-oOAL26r;07smhUd|^1ECEjqp@d=eC_?HZ
zt~|wnz&KNU1;b6q-*{MbV34SFen_aOdrZiUOiypo0B_@IaI5V$9bGy;+A;QUs4u0b
zg4*74gTsTCEnd5-F&NsD5bAFPZ4!1To+oFzP7W&j#cFcoeMeGTk=^#ETSGG<Bdm6@
z3CPwo;@UT{8f#fG<e}Slrx+0j9CJH!c<d1H6WtmPaT;k9oIKx<73gHLj-0EBWCOO2
z@zNDX>+yWfEXaB?GKAI*XkLR--9F?1r7N)<3RxSinZk)A!w$G6B%8zmVEo>a{w&(B
zHtHJkU<>_daq|NRqMyLkSl7CIZ&b8SyP8(%O0^g&rK$3cVc#7${jUMQW6Yv5l58`P
z|65XQ5WT8vb#$$zGY*`|ud*f`{2)*B+w}gslTry_du~<psD#ttju~1E$QsfRJf1nX
zuOMXD`L8t06?qV^u4!DXWez33a(}WTQe3WyxZ{%h=%)yO>{WjZW>~j^*5LiL_Pfmz
z^Sp9N3owJCwtD8LW_->Bu0eCfaN<ub{)szp$M|cZQ=NF;;M20s#`@9<Y2nG(w)*D>
z@3aRbg5j~(P#a7&XbnQt2Z6YC4ZxG^^ZF11r7lS!i7|78wk^{#dj*7SJWF^<Z|>X4
z5wadI?;vMIDluB|?L0(2<RIa73~g*PIV%W`RstgusKXGzli^URU9RIC2MZ{|Y}*|q
z2}z*-np`!qdk)V|C<x{Qosq=Dgg5Mh4;}f(!y?GLI8~N*xRwe>9%$8gNc?_o9q4cC
zE08FkK%WKV+Yu_u{JojbXhl`p?U#iSDi(zKuqkcvA}3oS-CrzL$}!K>PgoS*xiHdR
z7FBa9cE+@JB&w($mRDF&Hf`s8e&!)Hi%JJ)PgEq<m>&(dm*F6hYiUiI0K<{vebEzb
zZ7W5?R1t`K5CGXEXHK1%jX0OSOVZ0Rnp-(p`8XBF%rqg^gm#C+hqnH?Y$SY4!>nc+
z%FA#?mFa{}fl77s?XTD`S(n6-Gdk{Z<o>@_Ci}H0ottEhufz16^bz6Ef)ab|9-usQ
zSPcEZ77FYI5<Y%{Ijbu{xkYeg8K0aAO*5-9Sl9{D@+Xsy>k(p_$IH0*p_8(wvY^rG
zy+E4N=0@sTDMLnEn2B5WvfRql<w?0gx3d)JTYf{)o7yrB(dIv!XtmRG*GI%M8aWvn
z;&#|F^)1a)0#}}L&D4JA$<GDiKP;E*aPSdRd?gqYfrA6-J8$5myv+q95YW*}o{$pY
z>8i@tu_wZmQ{^1OGnipj9Vy-xg?WTNY?YmTpf2VC>+9&zx0^Ip94m4EbTlF)fB|&u
zcF5ud>1_s1{uQ;@c?dMd+aq8Ef-e5wAPFtKcWQ`(A#KM6-Wn=Kb~P%~!$H~I$s{_b
zk9hZPT*QO?*?l`03|s#TfXAl8Bi{{Hwr8^CWa)BTllz#24LP!6o{=K9x~wzM>U!N2
zFu(zr+iyiv0(*f0+Z4u^kcBU`Z!)e6HaR(+;g-Bzi%JOD!*#eH8^v;7cbM(0RC5$+
zK{5t8HhFJBNILj@10SKH1mIr=3=s39^gj*6|5VYB;z3>y%MYr+FvH<7(HGTEGx$sv
zIjNjQM0KLcb158F<APnOHiU4zn7}Euz3AikAY{sC5?<sHJOBXoIw916?w22nrg<}f
zH^oZNfMm*Dh09{&<30N~-2N*EO4%EtwLGG#swqpZLIty(tKxcZp26gYVm)vi>Ws_G
z_CD?}9%<LAVw*#qVUlbJGGwNIa`Lk9{qIRxGl(^$?r8})ObILp8Zn{!QkB~Y;P}}V
z4f)NLwXZ+^+xGU1ds5BY94h>DKA!@e4V3_{G%^H(pXdkxmBvsJOTyG%t-xLYX>1d4
zec@2@Jg8$02q{C3u64vWFwl()lLoKj3e>+4)-YjSZdT?G3N~<HUzkG8_}`9nX-cj$
zz-{=c!%SCu4xk-liyRy?QCJv<*IXxVpq2a>YjH^JWj(`k09kZnc!IelErUznQUw=g
zgyJ$I1`rr{br|9PQK0|j#XPm+2Qoo;{k=oV=<_OA_V=c;*Es7R(1}fj8ppSdcvS^o
zp%SN7r={4Nh=wil@$+YOY+OGh?5je^Ums(!`5S`CDWCpRxaJKOFw0z^sUJK?@{!>h
zm@?gubhx2eUe#r@P<nV77ZG2xuLw{0!+UrBmx6er!dWB8$VI;~#5YqIb5>81GAexz
zj6jMhC><K5wJ3=4o3#EkU;|q0Xk9?MD43Ki{PY6(iQES{Y)p^T6r?wK7GbHtmpz&`
zem|C}_h!qQr`6}HAe|^9$xrjPp<(Psom~k<FadVeH*h`p8^M<g^YN|(ZKIHzfjB)f
z8Ou3({+Idd9X=S;2#62Qfp9p%Tl`Vy6c8OBer~=15HtadsdJ$fZ}4LAesFt4ZDt)i
zIN~Xxa!~B39F-K^N=v+cShHPj2Y+Eb|A1gm@g8Oe+&mpzub7b!Oy?hp@)&<#&-sOF
z%wMd?O(SRq{CP8Vbu#gE!SRG9h;T=_1&6arhn0YmJYOHKalFvwya+F<WfyECLye+c
zwT9o74fJ#%Cda#&Z^0yHUoB@$?y=!@QC3R!%Ov(EwFe8K7EcRxu8solLst~T)Q3yg
zD0ectiEj8$=lX6ER22}BoyrqMZ)c!x{gk9>a5)T!%m?6f;8pU@jBNoU>hv`tg*t1D
zV^$Gn>nd<(-U;S#1Nv}p1MJ<8k?=CN)dDnkBs->@-*Cn~_1C3Rrw*@i;eic;o=J+s
z{Yww6OOeLSPk;zP$N&Xag24mGV|2UwJz$!D&(OFR!XGE~ZF=t4ji+ID!AjBdvu2E+
z^hCIRJA}Bnp?fa<+`a)oH+A}VDX4+njeCo}9j4|%E>3UN6*vs~((cuGsfQPgKf87Z
zJ#y!*?h}xGq88G)l&_D6et6(FwLA3`l+<iW4ZYkXAEM3U6`Fc)vb<j?r3~iQ3Ku}_
zSQK?0X6xHlGWi1Z*gA+)M8;atZ*xYLs2rwMlD7i9!giKO;?+H%WqnbutQl!#2C^mq
zYw(PSq)&s{CLQ<iT1nL_>`GhF$>LHV+`6_pU{f6_tKM_iuC*?tMjuu~f{j>!s}0u3
z>I25>_T15j=^P|N=zyxUzE$1k+ck`EnFw(~dqh?OKB3$Vji}QEhjzc*6tA$Ql$m-K
z%KOLZ%P+vG&~-Z-2RrW(kfVv|zSs*PLJ$j}@zoZud#CsitpY1%QeUBCCAqdORG-K;
zg3_&&i)=;QI9}AAsn*S%X#c`EfsSr)g*6_o@<l0g>e5Zd&$9}A;N|LkkHdk5E%o)R
z^{c`Ig$HlvMh5mrYcJ#ORtq=WO%%d>#>rD@$k7Q6e0ltQ6Ydgg(jAb<>d53*62n}4
zG|r|GSL~ai6U1-^(YgeGMF?cO&6&k+n5ed?uvI8CiEq=C11IZGSL>)`EK9b@s5w9(
zoWueT<iIj;Dcs*IT^mJlS3Wr(gtH3qM_G!y3`}D(pNuNJhT89bVc8e<XDLAzL7TZw
z@y#dGY$_I~393=s15t+iDc}rnEdVw_XGzBi)g(0L0z!lEA6(S+&(q=~pqt<-Tx~)3
zdm0n-zm&XA-AOa~n;7%&SJLr|cx?8bqDJNH`5Te1jY^i4X+2Uu)rC?gaGaDvRI{GX
zj6~fMixLOYuOD)v%~~JsqzSkMj}<1L1u4BsGP_)=2|xH`Hf)maJRLXRQIBPtD*S^p
zRLfs;nZ@ay-V!g5{apxSYY;_@+h6LQL_+z&xZCn)pyN6V-XG2f$YRySc~<>g^k$@w
z9qp=66b}-XDjVS+Orf$`uBZ^nYHSC_(&syixmoqL;5H^%(DnHD^LFxP%`>%6JHvJ-
z%E;~Zp$(E`Rvm<^?b?vFvbRh$ZuF#`p)*_%9}(|Y(SKn}+T9)6Y-y{#vdBUQ<Lg-#
zYT^~mb|A}&M#-YrfJzC-76C4$`Co`cfB-z20Ib)|2tL)hhjik{8abIfua~!Hy9`V>
z*0PA-a!Rw^NuHyAuVQCw6HgyDtcWP--n}i2F;I^E60ZpiNiYY}YlCp&b8=L?xlAu#
z-f9UmDjOrjhYEI}3^2(B#RJSiE5K1qe@j4Jr!pqL?}J=Fg#F(Cg)(XaF#)6yCE`l$
zVoY$61s>MMk2%2#x$|F^#6UWCC8XG_-Rv=q)tR;NI7dHvQN+Z?inbT1_gFY^)}CQ0
z#+|=FSEI~bIVBc&mMu-+Q#L`fgbA+Ua)tje(Es3w$>N!<grla#au*Lj`#EeRS)1Q~
z8$w%zaxH6IR*_wMZA|#(7t(&#aiSHXisc}|WEQ(^695Dpj4Q6Rzvh#m+%;h*s`%(W
zlehT1&syAQeFo)fp^l~zFGQsLI}@IG{p6+V%_>az`HZV*IJ74Fa7K#F%rX-+ZCqy?
zO2<)Z&kuuKeXQ-Ek0}OuJo~b6vRVGm=L_g#)@6q87y7mQB1TChUKWnZ2h5jzQ$PPF
zIs1SQ#=$P8I_^%8pQuZaAC@x@GbeNkd2Op{cy0gX9M>^68RdtoJcUL~N2#`vmNR~_
z;4x!?-C6K)qYdfv{VZSdJ_{rU9Y?m=6V>~`%+OpL$e6Y$k<XDpB*8ZMQs1yi$t#J(
zRb#b5T#cecx*<Qq+5ufDQHjd+RtWqMs<ug3tdDE=@Jwz0W=T4Kwk=gZjenEJ%ss-n
zcA*Nki?|B<3qa%2_`|H8VwD(aFBw<#Jt!w%g!;FFU<z>$8Jjj4?L3b-r*P`);BZVd
zk?WZ(iX`)tGRM~gf`DCKoiD-pwcCPg@MU3-mB=jS+{okaoP0|vB@t?yK%2$4j><-M
z+BXB6k!AKzhEs&(4;Eg{Dq}-NV@}M@@F==&ICoXLHz@Zdq*D7x<pZ;f{xvZUUEVck
zN=*F;Iyg(>nnzx4Am2?~^RwVW+0gl>zFLqS5KiGpI<=qSTcGk{-Pyl)O`TWdwnB^7
zpVUl(I-d%*ZBg4W6A_&30}})eS!V2pm#0^OepS?LqUo9{bENtp)D;KvWuf|H4C*~g
z(K~cKM)>-J|CI0&$pps8E72CWX+#vBVmjtbS8l^iu_qV0PqH*LX~p#iC#NXjqSwhZ
zx(ZBdjJA)b-@LzXuLF%CB}~*twVU`Q&ZL*X3NaZ@z)*F|xQ8ZR+jGK>?4b<2mJp(v
zPIHmXzJ2;0ZUan#opP&skCU5$I0QazPBjWLQ5l8zE;#HJ{VH|`GpxB^fK2q~jKPdP
zNf9FcdOXo<ym;>6M+-!ryF}rK0V1(C$QP|kVCTxdoaGRyO}q8GzO55TGi;^ye0^e#
zi8%2&Fvti?wByMJ*PZnl?4Y$rG}xuv@#{o)qBHzc71Bi<&(qE2M>xN@FSQkkd{?6{
zEYr!;vwD-U;D7dzo}s8=<`Z8!BdWkzcNVRx@FkF-(@?QvmmA>b5_!-nMfhEw@31#d
z)x6nscLrai5xXol$c>*&dh}2+8~qBLq!cJdSb-U*Nu&)*3hFihcLs$%TFneOPW9W>
zjL~vv%*9QbxN~a)2|y_L<;#0nT*KWe7|+U+aJ|zQ?sBq~m3Zlf6M)Mcv&K2(Lfr5T
zf4*G;o$l}e6MaUM1o<QCki!!)5hrk}mh?nE&VFl;!zhD&Em^Rcj2}#h&S-KwG)lzL
zDBbTYN~KP_+o4p^WwC8&qF2n~Ul^?2Sr44e72rQ(N*rAZsEcHrbuOYu@&04r0s{xc
zu>vep^fx!OLG1<eDLBMbwQ$%yF#nIf@?QWHON<Pha%r@>fdcV&GpV#tXt^w1VQR66
zv#iZMJ8Wb|{lG>@wga<D0d9y0RJ{z+O&ejlnhKk8dr8Lel0y}!_bIp)P0+P)li2d}
zY%(;6C`lZA7~0Ueau(eiM!89(R^AhMqv+anbHp--8VbJ%WCh#BDpvaPalni74C+wj
zw^u*j?>fy-i8o#bz)vdINprU#7PFblY+)VY#c;Q0B_n}KfO-TM85^yM<FC82upFLO
z9eXVcpk#{$a;7nbQ2?e?<dh_GLL}ze&fdo!X}H@HH%!QxVB#z&P&Y*D@?lv#0C}4|
zwV?2U%08e0^tXPEsrz*3^GU@Ok(4C<rb(-YDt0<?e0H?)&oHtXJn4zP*7$%sRRfD*
zirMd^V4XmzDmjZJiTr%)UoMn49yk%)1kbfqT9N^uUfSbQ#KuXCkd6I(gd+I0me~3o
zx9dwNlDjbZ`Cf1zDjFGr$keJ5_{yQvF2Nz^fzk=Q00T8pQG-%VKAbPx(yVbnhtg>J
z2cA%xXNet2p{gv;$<({pGY1LZ!K=t33E17)WSvppH3DmZy~Tr3Gbw8q^q+6e>>iHE
z;ubA!Nbr4<$!)KB5WWN+857}tzlAyZum{C5gExOOimnN0{hB_pl%nE2zD%b&mT1&k
zlwei0EH1XH1sS`+R%D*ftRW0_`0UnM^dZ>k=Xaa}P-Bv0Ux!ENP$6ug&9v17i$L8?
zOh^}n*ktM1<HWC~QY`H8F?<Q!rzk$S=RN#<)xE{iEu6t+40d~A<6&z=MeRP>GnUM6
zI7FBjSO9161&<D&Jq2_8ciI{qPOsj*Ht<4g6Q<*tKx=^H_e{RDB_i`e8%$!A^aOun
z0+KUvmtUawsvgE|E&GJ>9RgzS#(P-wu_0mF)Cjf;L8%8iyp}Yd_;L%}eZe>7I|q6L
znS{yJ>P5yUj}zzu!Js{o{DJ$QWD*xA2qU?t>GWj=kWDJ%vz>9G87?*%Y>4Sjx%KK3
z^5uOmyz<IFtT`#*-vwQ3amLkQgwwn)-PV_9!~}$vwrN8-nO=t*j2iu(HjenUYBMP-
z(OHcdV+F8d#+2fa(`VNE(`2xDZ7l)ZUi?n$LWN1vy;O=TuMD|mVs0Y?%k*^_o@uzi
zfi0{PekUd`9!psZVkLUMf6Gx3Y!D(Ym8LrnbMD$CqJ=Gw(4wnR4hv5rWiAo3fK&pf
z9+Dpyhj<hcvl_Ao<G#B#YZUZUR$+xd8gT_EXhlHX#ykm1G9C&!kG?w|StAmK4(@IL
z$?+PJf&vvj0OTP0g!aEQF@dtha8O^S_YwV+`<0Fmm}GdRN$%X+BpjDA!r)wEjpdJZ
z8gI_YX1buO7TftyR#O!Sg>~U1v8+#6B@453O!a1R$4P`^Mc{ddcMXYSKxu>XQ&%V0
z>bM76nzu1Mqct~lbVS?qeOqKURKsPET)ob*e?}((Xm=+fSIk3@o)$PWGL##9Wmzz8
z<A0ekH=BFe-*$Goi3-{SG^nvTD8d{!;*9-PJ+m0*vxdE&ET6bol?fO$XGyLT6%c}X
z1mw`m1$zMs&ZY39Es%1Mt?BJNwIxSSGLp<I_3<GCu1k#o8!RJNuSLIec9FK^*8}op
z1%@-FMrj?ldq5iIF|z!QB$kj`&PO*F_B5eEQ^B@&+maR4D?Udg2fNn&gTP91{#g}j
zK{Y+YS3DWoRrt>5D951_B;5oNA<Cu2#O<1d=oi$m&(3g4w~_)>%J?}2#Zw*L4o5;s
zbCI(fz)TRde5U@cx7_8v2iOouD%a-L1KbuV(XI^_v3B&Qt#K{p6^W>*g%%<7Zjpof
zjs3Z0tcsC~4)+*-m11-&WbKEDGTiDY8g&KWADM3vmtye-)qKhF<+#VQ%(0R^q?LMJ
z+&em6aSh&|Nfyg?!}+v6VSk5Rd4y~4*xIu`+;uSnH(XzZR87ttqCzgbVvinPF?-B$
zFIOUYO+7x2XSsipLAD?h?9MXM6L$42#O;)sS4!Ni+(l4S_ez{i_<*qGBv;b?g%UdB
z);{{S$(D+=BfERw098)ODx5MMTcAZ@<*hq=Xm#)DV|8Y`ZP&1c`z-V|?Nc*&do=UT
zXV$)5rVzD}0zEt=z~M?BxTf(Rs=;RIfzYNtq`;T7aY2S--`z!9tci{<j0F2+(&2I^
zndovu<aMS56><DDMPGppY&;~HvMTRZNw!FH`!WnMf;TCxgX}(9_S|ymB5!@^&Q=bg
z=JhHoevoJGu?Kn~s_w#uzVvH)-Pp^SLxRP4r&7bL+r>THpX*xoQX!Swrq|s<ZFO|l
z-t@q}MtkgqK>v#mlBM{iUJJeNu$!m7;%=LKZ1Oa2Fn~UK&mJBp=s+~v6d1M9&mo9#
zs<(+eD5!~~3dTZ+1*uAS8cZKW-@YvnF~A4DQE@`Ce%zu1>MJ5-u&`cC3=>~L=<!6R
zPNTO3f2;T_`(V#9bqyuX2XJ>3mD{O>^I{g!Jidk7^&Qp*-Rl<D7v~N*HpPpjM5}+Y
z>F<*mg$}Y1D*ymU$P|y7!jy_HyYrm@6}#A_Y8pfo8hAM)au0i7J{i;1hbz?{zNa&t
z%0kkm{3e_hgmi(!z9KV2@STXsRn@5g@fMDsY_1o}rm1t6q7tzFrO=mWFO1CvkU1u)
z-YBW&`uB_}faun<m=c8x-HTh9bk?BK0*vjeD(udX(0Xd(?AMan-Y-^2QMv0IMXI1X
zB7w&z1A`>T5QYwLc^&qdanpqMdPovjnb;+-Ca5;CU_0Cv2dFcp#oVRKkCX<!I{cBu
z8Xs;=_4AlT{5`r|n+h0o?-}jjubwwD(Z%;H=+HM6IP!8AnE{7Gqi-geGtP%D`DSIQ
zuD3r3OpzmTMA}gS!&%o(rI6X>5OmAXrn8nQM&ZDIoc(e*S=%D{6A90m*vz4u@?ROv
z(Gzkl>j4A&k7GZ7cw1Za9Vyzz>Qj=@+enU5K76E%Z$XI5X(>9d$D-w4Qogw(T9j%1
z!3~o2fF(~ix|sN4YJwxxkCYVT<>bUOs2ky9=;Ozj=upc#8y;au(Pp>~@J9Q4o^O_*
zZw1Y^E!Y9M4&!xH_L7V4wadLO@OkM-CfqCF#}_{Ryj60LLL?%I^X@XBBLVh{+1n44
z<{WD$uI9FlAmX81`MHa%wqaV9wu8#lAbMR+=Z)$6K*9G>@u9!o#xA;aIm5B`q@o3>
zBD`oiRxx&=!H+fG)92+0=L+=V-QV0$XwvWFUT#2S7F;W~B`s(~MDk>;9_n(wN?MU%
ze@RO@)Cd9?>oqdv=bZcwfoN;EpN!BX$1wxY;%sA}(s|o<5(B}#S0YX6LoD>x{H_Dv
zng^U4E-u<qgTUe0rlX(i(9TZVFNoziJ-JTx;;&@{W|A#>l5?y9L!8?XX<d!f%tu-k
z|2z2c_&?sP?dC2vcPLE^s=_%GT_;6$KN$7k&Ntqkto};Bgwd4B+XKFGon4$^Tkwlr
z#$0euSQ`3`9;K3G3aahjjzv(5FG1~)04ub#pl0p%^wR`G0%ka?0v)SO&DyoP4j9qU
z*CBK`Q77^XVW}5&f%=`Sp2$DLMn_cV4cb7@;DZzUzEuY)|4c!Rww4bC!M-?N99_uj
z$Q=;K)sRt>jR29C5jc_k<W6I(`*E|C{Bq&1U-E>qLf~Hwfx|p*{SFpY$rr3$14G+{
zCPDuPQLv~Ta@pFSlpGV;%if}6Z1pIOD%$P1PdOqy5(>J?Ch*rC=u<{h>Tn98)ESaq
zjs(pI;mEX!%R|kw^&vvbt;Bwraw{=8d>rw=>5`ssVqg4|KJ8B^k(5EU4BZn~C3Uw0
zGIMl*hQe5vJF{Hj-O{mHV&s=$tVPqU_X2^PXApE4VM@Z0M)%hD`?9&x@9cSWnk`k3
z(&><*Px?oUCGgh90nI-O2BBheN*;uV*2~U3J>fNHM&J>5K;mP0f+s*1aI;_Gh+r6s
zE-#fZ-@p2B#*L<%#%keaUY3H?4@AsD)d(i1`{z8KT>zb_{MjXpd<!Z&zAHej-dVm3
z)SfwqjmbN3lPamBXd=t@>y28Bl03`gMdrV5_-WvRh*}VT+gzq4_nRA|Q`(*;`6^JU
znq~2NyJEllc~@h_WrCS`B)`quS?}mh!W%a><cF8}X?Q~D;IbCo_?y?xaT~R=Loo8y
ztlprJy(#R*5v+AWFcdlTjshQ2L~^elaEgCCa`?C~WU?y7G$$)rtzu;m&RquO7p@LS
zX?d(Zo|{hAtKWfLwr3b<AWg_F{l!aqQ8dA~;rUI=_`wManN|?@uR=DJ%t%5a9n&ho
zlZ^{Ma$|x8hL?fm+jpdPVJ~oDGLi#QxcU^r13?Vql{P@5%#W^+yeuI4Wz^R~J9=Yw
zoJRlvIqAGW%#QnChH|iJNgWrJzC<x4Z|r&DcQn;2&0q$Hq%C$nO$qi98zS1twZP1^
z;zAiD005+#Md!eXx|X-Tp{vDe>3{uF)Tv9$$q|B~L<nJk#vp07muqSt>MZebD`sY?
za{JU{ry<q7ya*Z4i*tq9<7WOR36%}AI#L_A+71{i3ZgNtoja%%eBADev8;oX(QKwI
zeXn$&s-DL!ggnpeY3%Whfm-c$RI*p24G<?~3OJ<su^5~ilCNGCEBS0ugto9EMjui1
zIHj1a$Aaj?cZe`JDFuz!_AKsm(-vpr3o8104q$QgBHxggJH&clt^l<vr`oHnii#m^
zWS$&2V@-Tjo>c7$9bci_2Y%UgYi;F@`_KQWd8UX64t@{&E5z|6CV=1g98w~Az&+BC
z8ua;FI+!ylP+fcsj^iRUjnc~$m03S+d|Fs&1EasH!hULR-681W_6mZC7UR46#8KFe
zCquG}XTx-Fv7*_G@)Z23s~noKvbiVaRR1EvzXmzN_d|am_^#>IIg6`rTP}`%jV|)D
z@`-NXShe+bQw|tRk9eS*I@iEP_Xdg9KuzII6L`@}+WsZGSIa_u|F3)lWGc9<q%s6N
zvMKPez3%BWbtd<h-%9$3Lcp`0&39N)x3J1X&A571wF*T)nY=yXs+24Zo(Il~t7jNw
z$Rw_g?3h<z532r4bNKJ@=Adk<WF*;`@ENU`G^<o!oFbeG@ol`o2Fsm?yv#;^gpy`S
z5R1cP082J}j+)NXE`ep%VoF%p!a%xelRPZiq*HYt8ys9Y8_+lv9CviKv*t1Yf#c)y
z`c+XDmd72>s%t$$Yr1br4|&)r`gF2!S5&2YE-!5JgWd)Fa;HqXx50BAMN_lEN(BRO
zYfP4nK%_MADb``>TU@3_-<IyQUdbe#ytmm2HUl-SGu7&K7-sequ@`Mq>(MbaLN9!<
z)#;X9ZExhx1bUM(<~g^(_KuGj&2fh-NY(rdFsEYGykq_}yi1J$AeO=%Gt}u+z)Gjy
z3Bd(@?J<j}?h5#aM^heOHl@_T<$_Iv3ta$P7n9W4(DOOu;Y5oZhu7LD-XdUAIn@P$
zo7rayh95V^HdBitq&y5WW~QY)QJkOQ=|13S&rOI)RNoa_O8{NI7FX>5-}73jgL1g|
zSHeeB2qq27htb<>qX@%`|E|dN{PjcIAPCXGBOzerLMh=hqKI`9_*kH)cJ6*5Pa?ab
zY$8E00!L_Y8xtiF^#IWKPsvw!enoCB<X<9A;gP}H^EgHN4Z28G{kMPj<9?O_3MYc2
z(@cQ<8m_Q$r);0#Pc-rHJ?UQ{3$Q|%q@KQsI*U&ycED+HtD8><1YMmE#(vCxTwrj{
z*hY2wx>6q6*N8FA^PXBZmXN~~K#a>HM}~?qru)!G_v7MXMnpN@lN5DrTkDXAr|A<-
z-yD3X7S?ZiOtg-@&Gjb1cA7Y{@8A?ag+VQ!OcQ>+g#JnMh8yMewo1I5AO_w#PU-jr
z$ZibYNq8i7>Tf++k-&MFAFQWfd0zV?N(Lw;LhffEBhE0XzL1j6ig4FzEl=&EfF;u~
zAkE~w$c<NT0tICwm<_7&va9jDr4H<<#Dm^kWnj^%r)|zcQWfJlyFBdi(}F}}7(V41
z#}5lZ$<Hq!>v*)81h<r8zJC_zNIg4enofU18TUN>J_I_h01QIoQRwg^s2|IBJFP1|
zHa^WatL|YDRAI&!<+b)=KXwq>p`j!)SN~%XvEvEhe)`o9HhaEeE0h-FARn9Pjn+_|
z{C7RVJbJB;`IaM52lqR*8^Jy}u?y+qcD%LTyg;77o0Etmc5SC_yUiY^dnU}*CF)t2
zePFEa>>hbih&|!EZ?d5+u9Q2C<4*nbivo?6PI0&gwoCbDvJ?$sy|PQgAQ)M;5{1Ai
z>ZG7vRWP&ge@fYSlU$7tWUF+!i-dO^!S(BtMs=ED`pY4>uAgbOJF9li+h6t&z3@F9
zbojgBiF~oST3vibjHp;YJ)bi|W}Dz3lDf@Tz8j#!)T|wJH#97dsSdgUSV>?Xs_K~`
z-b$I2(YrRC@X0RP)1dP}d!0e0V-k@f!&#LN!D$qVAiNV!xUrN%wc!`9Eda0S&9#q4
z)>RZx$DL$1Ugu<wptVCMJmGZ<Z&2<IhM@J-Id7+bbSJb8%POB!PskjXE9{8MpOqiZ
zx#_$PT3U}mZeZ71ldYr(>m@33dQz9P<680N%m)Kf6#;!DFT`Ux1sl4%*!}=Ci@1Pm
zG&ps*gYN|mXZ@xEoRO6`IA9`s&4<Au_t4V+x$2`|ET12)vWuMa5+f+VQmfk`pM(N@
zZR3;uJ-~EDhrrbnyD;|rQAQ}X%2EOqrEVKRk;jxI7LcFK-GbIB-&@D+X!Dg5zffWj
z<b~RqYgGpZ=AOnu>*#1<xRuSE2$3s(vZFKD_B9J}D00OLnIm@#6>(MWR)rM5g`rU8
zt5LD*UC<j4rebo{L42jP7O-!obL?v#QXGgjNQpX)ReVGOjB3~)a%eU3hnc=CCsx27
z^h6-^d_hjGgMD7*7<WfAI9GXfv`OOpwzDz&d9f7_aNkrkCw_NaD&U1b8I*;{D>%j|
zm|JbiyAnZgWm}D|OYPO6{0<D2FO1(5wW!s=M$2gQ?VKM=wAiOr`JPu%g*m7rs-fM%
za3;L51A#O6rGRGmQNFv>HM(th1%)dFi*vH=iO7#?nEZ>)hIDg&R4L$R2t?K3kAWX2
zJ&Wi>7KCec3!QKKz3)#&yDJ+1@Z<w?<Z#A|a6BmR9aL)-PC2%5Ut!M>2ey8p?QVMJ
zZTz|~9EY?tk|bH10$V3UideF+351~p;4Hn&v4$$C>Kl`L1}`0)m}^isNke*&H(wY&
zTEUQJmFqjL=*Xs6NHYvr_^**tyK-=iW~zDvE;P0G($6!=+)+6~lQqFY1d&&H0e)px
z`Ylj2qoE&1bQe27JxA&{<YIBZ&*Ik_1s-PNKM%mIK^nzmqO_G%nMz9PdD(b?823b+
z=ouR`+#$b8=C<<a#Vkt(Je^-har!ko-bNcL55*~cGv<nBVEW#Jpsj}c5*C7Or;L|(
zG44stWOB&@@f1d(%dzMF(|sT%IQdNLMp`x)RgW(HLSvyFWVoC$3nT$YPE-Q}b6i}H
zm6R?T9g~Gd)J}SI$~<9!M811p3WSL^(IiP3dJ|?!6d|r)ZsF;<)A$P_038Zw4y4~?
zcKuOMJ)Yx}-OR0HA1c^=+#0LWG9D8@ak{LB=2R{aqRqAbh8dG)4F*5eC``&+ILnX?
zMmDWmqU~fWON!YTFSyUVi?jF&ACt!{wxR}}BDfLndF+0u+xSJ!4eQr)HvXtS7uuB0
z8d&Wp5HJ4q2!}W`+`kQj2rX8q{cUnzU=3@oauc;vzeAxo*$il?Mdl`M(zhP*)nNtt
zio~b1fzd{4Z`b>|QrX+45vmuDjsMI0Z`6Ak&IVFjF*!?zFpIx{uJjtDG`feON>V^S
z)n8<F^j$h<UHW=;MK?&F;n$sXt$#{P2o9KT2mnAN7`rvBY&z0;#K1oie1kEWL?n}E
zruRGt>^MV*Rn*zLsX-IY=9C#mR~Z4*3-3YU#h=zfc#@tqG<MrPEEcbcGg_vUj{jDN
zNjMke*#o;2T1u?Y2W5Z02WAvWb}M1c16EBVSq!K$56rFqstfXnXs2Q=H<$w4e70u>
zNAqH~gU0qxAc>WbHM?+_1L*3fplicwaWlzNKO=OvWWPx&p^6*Z3iVJ7+(ga2-XQhs
zRYI)9jX%3*a+%Qagyv%?^m2LV{p^B@h!BZo3EE#@qxnqSB~%e9U%fe|*wUFX84T;q
zpQ5e3xH@u05%UM+b~p>NHnU=T>vX)&s5=BaCp+uQMwom#KB=3WQ57QOYM|vRr;+b~
z#Zu57MU0&{Ah|bIUWIYS794g%|MW$O{SH7#%s^v6K?`T^6o6d2u$Wwa%r;}&UXUHh
zTAfUD_MJ7h38+H#5;^c=A<G2~+gA4I!bhKR)-;QI>Px(@jj<za0EQZ_kyQW|J?h+I
z7UwKc1g$Wvbnus1^{YF0yZ84T&-J7~3Fdb{Gq`K6RPFlQa`DPU62>a<<re9s+JGj5
zvZm{llH>aziH=t0ST@l5u{IG^JV91rjA+n)8>?As=#0`+3E%OAWZ1Bv_=c2hn{@v5
zU$6RM(*r-OK5~!D90-;wCTAIUr&7)EuW<2TAdVz93Sb$hnJVKskhPYz!8*l0ao}9=
zeyJS*_Vvvty&(Z~{P-U|(!bgrKGDRTi_LA%93=SDvVt1ub(de(u;Y85<bR)sVeZ%9
zLXg^2)0P}Xa>;C%X1}oix<~CIQNLPk5L*;$gm4W$sEJ7#QM4_~=>L4Jva}?@GxPBL
zNEDIkF1-Qt-TJMaIiN(ty}(Ru9Phm(Ersag_x{u!tBloM_74tW8YV^M;Slk>=cgmQ
zexE_ZMJCx*yU$ZXp=_c*MM<&#_GZ;qerNRhPSCE)42|`D9A*60C%0Lie<auRdvB!(
z_f$^YgQiTxiI{oiW_|%~9dj4$QPz{LTAjDBi?G3Dv<p&w^%@Eq<?YlGxh7}o!a+hC
zIVtu@a-<4@qW+m|S4!1Iuo5(4fq$F`cEEV5lDar@|L5T}qJW>R&&G=EJ3%Q*zU*h2
zdE32tuRKx+Kjg{wU;Y~7AW3q~v6H<%OMd@M!9s*?AR6ZM{|hZ+;`8SB^MgP<z<!CC
zJOWzcq=c4$RP`HGn;pWRtVAE*g0LSW6hPVtC9Nj)RTrQfycODV<5#jsLML;C%6u;|
z%D@>bl+|WWQ4#=<dQF~~NKGR>u2+eGk-<W%itfBWZjH$q5$?Mx-h5=~43-9BzVVMp
zfKstZ7vsnVIaWpJu4UV9IfH9B<wAZ*OZi)+Gmio}80cF2E?Brg6s7DRW~N20(AX!M
zD=k*p7^n?wB15L~Q!2@x!1Yq**}12+1d9XXp#n+^PnkhZ6&36OeR*j<qrMkU<bz3M
z)^q>k<)!UUIGX=LPx>$|WEZV?X@JM`|7NRevdE#G`x@mpX~+UsXu%}AM(f|HlsZPY
z49H9ZPcRXKf(*{pAl`6V4724k3oP|vi;6Y_P^@E);uGZtg&$bOJV6ZV6(+=NHH5cK
zm!V{NS^+-pC)GOm#%x0=O6a*kdbQ@JkEP;=DbE$l!pO9oa+`2AxK&A%b^$%{jll!>
z#!hC^;<*uSH)DOF(`~^U;L`QtsL(7+ODJBUwWdOg?oQ?ch9s$clMTsCC-#FpDv)Mn
z<r2mgKlTm0T-Xo_IOZY9-6Zl3^=meO6iPXyE0&oZ9;gU)|FvppKOW3`RTS9zC>mej
zWu9R61h)+F!?XH`-wXN(pP#8fe2r#)w8d7GY4QAVhcdACE%@!8-|yMrKM<HnXJD-$
z-}A%&=Q93GA2b_JkWDOVZ^JeZ@=Y%gK2o&;Ae(rl=Ioy&=2exKFRW2jxaG_Fm9B%4
zk}Qw4`M*9zu1+T^=a+Da)iEme{xrsB5vF?5rAHY^yTO|{h+#2Bh4Q72Rn=3i2nW?G
zZ>Uz}+a!3)^8m)gW2?YPr9lsrt;{tkdaP_-?WDzthNbt4U6w5FRpI9H!O}}R_;Nl@
z92Vncc3jXUyZ$+X)Qs}a`<)qp=cdI`UQc+jbB{(`B^5&@Vz!JV&KHN-KDg+RBGG`g
zQ1NFqVsGYt_QE(>lCS0Ts$xi~dTcHkV_cECq2DT-l@oPCn`S5O<nA6lFPBcz!EB9}
zL;=K^I;)F&f!kIhc78i{dvJa?X?-63sr79Ud#FHj8#gK1@rz=el=`VcCA&%UrDE6_
zXPzhE>{Coj{khx~@$bxMG<L5y1`ay397bR&^~MHuJP@0k+vEwJ(kc^oVcbZ9B+>X+
zTAuALY&9C-<qSqhYLo?b@tL%T5LW4>oyT(RT4b9fsSS{;Fd%+$)^*N{B3?Z6RWb^a
z8$oHI<`c@|t7iXbtIkcc_y4S~NP@6Kj+qkLVpFPV#m(1Zh}RiL{|x^G$VaFZSop~8
zl)P39eEgG?N0FN}iv2?BPf{mcha%vUbF)R#nLznRqMse0MH$KVplHc{A#P(p^$q&9
z1=a?UD^(AD$O6x{j~X<cMX})=KY?3G=)5tWmb!+Gm}rtPng=a6<LcY?(CL}xk*W~=
zQb;`6Ym4{oC@)L&hF{Q|l@3m|j0D&(Blrm5y~DNsbPeupyNlOe#X2jwFDF(L?twjr
zC)%qF0Q9wpXn<9Rb^fQQZGj>z*EFr43{eZD-p}!V5*x+g39hwEf}o>^Ik8D7!so4O
zlx^k>#}C5k8x-N=vQ~q-YJ3#|x;Q<w8SbCH9zg|Wk~w38Do^Oh!dkA}#fqo4kR53^
z!Ay5K^#7h3Bh94)f|_TAdOby;IifUSDQ%|#8e7sAh#=*aaOL?%Z~gjbvNZ3TvA)D8
zvl48yFJwm78F*-1=mQ;*TKwb9&Fh)g9f_o%nhlS-1v|}5)|F#}xE2Jr&M@95f~2YD
zv<>^eO2=DapT3)Zp#uG(6PNH@NAGO8zltZ3!D}(qi#p7BU)m>8&f=Ob_t-$$<DM}T
z)k^q@g~)r<L@<TP<(iw~UYaaNJrgE;tkW){#;W|w-4(*lc*p9uDFOveUoW~eu%L2d
zN7nr=fiSpU#}_C}u}w~ci?yn3iS12_!s$f`#i&)jQzjqUTNqtU*w!pw;+Xt1DhmU4
zJ3z(b3SGfOxw&e0fv4qJ4xdm@WhqHkQ@lXBCfgc;DIZDS4gS@NtD1dW3iz9+B2g5W
z7;gl_ir+VLOUZWc@|HDX6T+&T0yS+eQ||G8#49Sq9kVC-*n<cf`SbAURKQB$5k7xw
zMKmw#uWrwRK+wjINYFAGI%?O-A-JT+W`su$^1tf|*MdoP4!r$tB2JG}*7!o=V2qwY
zw8{PbvcvZ%R=FC>PI3;EA%!C7vG^S}YklFqulb+m{t126NqHY^%^L~oga*EfPZXYD
z_TeHVx%f#<{WdN;>tTN|yXlajUa9V7fPpr(<5B^^gkgR@x!DEh2ZI=j&%G&G0qJez
zQ3St}MkA_3iQ@&O#Q0e1S1oga#^UzH+|AxbUTS!=jvsIux^MS3J>2qmFC=`loOM%=
zyybb=yZPr{RzM8z(1{J&H$A{l^4Sj5*B{YYl7mo_DaUf5zW7QGd_hTuD+EduuU#Wb
zh+E?xK=6qABBRPT^EF8$@Hy_3Du?&a&vY!jItoy&r=>HSR;jTPHdEp53D-S(*@Q<8
zn#yVkRY+w2VA{aNj!1C}it7@8av>0DhAZB@h;w+Jx4DeO?sUpQ>P`@05Jc>#W<j42
zD^E4u?a8Tx;m?arJWX{q08gZ}6!-dRR-Vs0l;a5#&cGa*k4{>`h@J(jY@~?5q8Xix
zldZ#M{R8J9E+Ot-$>^*v&SWv)z$$d#wLgvqWydoD^-Aw^Wh!4@xdGY=iK5OCG<!Vq
z_9`$};#E>n?OmfC&Jm9#Nxf`pkdKFdyw}3)9xcG6hnMdt)2d(*XD*7NjW)!&?5lo_
z2q%oDefihGkeE(586w@gZxPWbnK{S|JQGV4tkOO-W=OC04;2FVJ<{)c2KF3^iIDN_
zSF%kq)?}Gv_+IbR^b}L=B>lpGhskO8_g5@?sl<MDjz586aL`i>80o*B8?I{Zc29ea
zw91jG3{FXH+6r*1gj9t9k7R%O&(D6vsjv=pZF<SyDMi<v*ng8)PwWfb)(f6mY~E&^
z@QioOjzOE+R;&xY2+vpp&y{ms%AL7O48TR;ep)97lL8BBaCH$kOQtr_bx*ZM#R{7S
z$AS@i46Jb9?wj;tJ4m1GRx5in(X*WV@BC^4><^gv+E!9Rj1s&t2ievI^yIu85QQ>x
ziEr_1D~H;BUM|}8s?@xtnS^s{m!F)V`sfW^nk|35KE_`{+w`i|-Ym<}rI`6s_e|uY
zX-p{~rPJggRDy4*uL)X>k8iRefaFpIaeallpZODe)diyW^rifqUKmW_V2u~+bD$<0
zN20=QWSwKllqB_yZmt%RsWoQ~LT$9yJO%<$amsAjU4!SnCDY(fKF4@3Evl>j7hhWc
zdf0Co*Libag95Ly(&%}d5c+P5D!E^$2(Uk$UJV$g^!H3&m2QJgQ5^$ty^XRE{q4rW
zW`Tb`6jG4i!{b@(!|g3GodkWSipJwoZK|>|H5k3i#>-A5yvI>fz`URJ2CmNohFd*x
zI3tRRFeyata4`&;QKc~YZ`o8-vOV~A(Y35)GNx0j&#;R>(uSciHU8^ntW3mVjuL8l
z*5genC_SKfB!ttFs#Hk9M&VN6r(W4M)vNH!%Bh;Z8B{bU8^bf2+!-{_O%CKKTJj+u
z${GGY`77wX_gsxZpmydA#V@9%K(-iosOV$WFFcdg%xs3WbztSDCX@rpuPvJ(eY|DO
z1ww9aYx8h5FH_jFeJCl}B5V_B8b)(7P18rRLKIw-t0)NtdP(@^jm-sZsk)6q)Lb_e
zY9=wQZx9(Fe$hP_7h<sK>Rzd)4)wEBmWV<CI}b1neMmE-tjbO~Lje%Tpew6_A8uh<
zeybllyirqjZP8X8^Wa5xc_Z0I{9hAI=L;fP#Wqn&&VU#QIYS06`9sHtwIVJhOH?%N
zoNb7i-7A4rkh_PGfpWk9dB4NS7da)OZs4W3c}-k^uL{RHck|ls@5q-P7QxRe&Z7bD
z5BhO-uElax*r6cLb|8d=#Ft!bJ4x}fLwViApKmakg+d|@<UoIHL#HeR{~aplkf;Vr
z`1f~867ZHB8ZW_nun0CtDg1)<)}DeL%yweZ!Lk5s#V513K0sEYkK<$e{E=U`)LE}f
z-*Fk%1;~;47^8)@CgI*JjaU0($02ZgI^{WE`Lh&p6w}T>@oe7LB=C0_SQGo2*=I@k
z+O<5<k0wFqrv`Hy&R|Z025#}yPNPy__d~3ycGjft<;|_65G1TAiS=K49U=9TfeNx_
zWC^1~j%3TVc7(~F?dr6s9w57=_o{0H`%Qs1UI^i{`sznra=X2hi*WEij%zHxs8u7@
zTk1vzyEiF3SH){lrv^}ta^*r6z$gCD_X$!3c%;BPrFd8sY))Oa^1RuqH$hLXUuG$W
z(Edg~KP6#STq?TnKJ({|m`5PDFjk&t*H-QLvhkKb+J@9)Ti=`JmaruzIP?kt{}v#1
z<deqQGxqk-FgROYhgMuOh>Y86_QmCGP9pP$T07VP07Y0yMtBMU08LE*DgXcg2mlKK
z4*&uH000I6005E!5C8%I000UA005Y6U3+X(WfcFN+jj4{2ZO<$)$vl+aeLdY?GRxd
ztEfDNuqX-9lx;v^g9-Q+g7{#H%52mG2noTN7>JJ`8byN!@edHx5EF$Uf)R;=k(lsE
zG}hnuwfC|ZZ*%YY^?c{`opXBb{iDg1a=1u^A4nBE8Uwqe+QGZ|-h+$`Er?(1=2C92
zSQ=Ll@0VL0n_q28!kxAA{lGXI=f}uHYkz-l50V|rR;}#u`Ypwp$&=nQ)E{nYZt??`
zX$4#SW{VZ@`hzWjXp3nM*Sc}zHak9J`Nka%UOjNr^;iccWbry+5Ku9@O)Fpxy6m`(
z#|GUFerYh17s?sC2Fo;G;oXDf4&Iv*sJt;=V}HtU{2olX9R87%+rh_Ex!D+)*;IZO
zml78^x+hZ=n$MgWKc${fapq9k_$~Fa_Ukso0i;sb@lMIuNvDCGhMnJ%&vv?OT=>nd
z%B(Ne>~+z57nS58Bg<FVH4J;QxQcvB$HsW_E)4~=U-nIY=}=JPM&eOJd?SO-gX*fx
zq0Fm-=JE9WU;X}%H_5bAY4KkQ{BjtWcn*lH0&d;`%m@KB6Em)Kzl>CVa!+_p=k4^Y
z(0%1i&YjQNu<IKsk<WD%(+!MT)sfH`%czO5jIA)1*|KGXJGSws{FT`FGfLZ7xHDCI
z?%VwWiZrHC_YhwUYRlBpn~i}|2MaR&G>-E7P~q^4P)R8rr~3rP*nF>nDjhKM?mmlp
zn@>rv<|{kraiiU5o+3188OGzOz&P8crv~F4T^A-e@?$Z{w&Q7p&z31(hb9{{cat5w
z0H&im4*{Fc!Ub*242B%+Mzf9O2ZU|RjJFKKQydK3>R>lo9Sq#*U<0$A7#3oVuH&QJ
zZvt~Q=0CVRCvo>M`S}i3eZT>;9?xMZ(s)Nw@`!XuD<ZfF9f%={12~Os*o-8uV4u7u
zk4w4Shgx}nDKBGVS7DqS#H;AT&-g&L%6d71<5(gqXk{9=UW1MD4|d~Gp6|&PStq-3
z4wpG%&yZ7zIIhY(IfWOogyZ#3(l7B5^|s0d>7<Vac#Jp2l8^B;I%JW22e<IW6F4Vt
zbI{hK4!OobStW(C7j<%3W)fY)F(f6yMyN$K+xv{%FQy!ZUoOdLiDNqV=cDC1u2$iS
zoR@xSWjt?6K#noZ&G2I)eb;bx3@*wkc}wc$EOLy^*o50y+)1>pR@M3mIVuOFQqJLk
z<jQhPVOAz&Z7chSWIy#2;*vv@xt(RdMMqXc3+nT}?2#R^RvP79S<BcaV=UvU&92sA
zNVdynxkrMGVJ@b!<pLPN)r>?PUg7E^;*)3OL$*Q-TjowSdNqAiX{iC$WQB~EFk}3Y
z5_8Z=-7#DnsjrLsdy{L{n&!7+xZIwc+`P^uy@{o3Iv+~(KG?HxZL+UtO;@6~r?aPj
zRoAjo8G)R1?aUiKf1`ZLwj*?uS5{d&!8bWFRrL~ovbv`T)bD-xF)f`=UW4nxQ|a`R
zoLkS|oKFAx2{83{3Pm#`32nq1W&}f#KwC883$&R5U$8wI^hKjq+-J7NLlG+!h{esA
zHXQ5l;(@4Xu7ueZ4YviXHlOK_H2Z?FNX!=vTYg_W6mF0C&2W3z3Q*<VEkHkKC%hak
z4cZ1uUxE>72TGm|1*~YmAB_7V?V&bbFcfO{wZ@{YJ}Vw-w#-)3Z-(@ZS?LLKuI}L=
z-eV{4xJuqU|2(Tyc6kbpGmH82ttLNDt6};b#j7_^sbTsb7tfG_%Y{W*|B4+}Ox_`i
zOUg!!s;+Nn47I3C@NlwOocZotXW5QffDF?SwF_X&ayXAZ`UOhTf03i_4y5{SL|Vkt
z^Pi^=@8U$)3UBv=iC*u+$?hI+SE8?Hb;28LvikbGOD6l9nwc)9fKwI59A1b#yt-KQ
zzj@Vsrj*0j<`+~DslYP9<!C-}K_h2WR<|I?XteHKO1IdNnZ+*C`~`|%=I|GAd|c;`
zcKD0f-ilvH``sK7%D(c|uhe;PJnJ}u8EVWX?dGX;RD9~mjkIJ2X*XQ+w=;n+5UX6N
k_3;^6slHRs#V3N<Uo)dm@(HEfrq}Q4N_q>QNvdc33y4S==Kufz


From f0505e81ccbf9cb856be6616b395211a3421cff3 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Fri, 14 Mar 2025 22:00:09 +0100
Subject: [PATCH 035/171] Move common Feetech/Dxl code into MotorsBus base
 class

---
 lerobot/common/motors/dynamixel/dynamixel.py  | 299 +-----
 .../common/motors/dynamixel/dynamixel_old.py  | 895 ++++++++++++++++++
 lerobot/common/motors/feetech/feetech.py      | 288 +-----
 lerobot/common/motors/motors_bus.py           | 340 ++++++-
 4 files changed, 1268 insertions(+), 554 deletions(-)
 create mode 100644 lerobot/common/motors/dynamixel/dynamixel_old.py

diff --git a/lerobot/common/motors/dynamixel/dynamixel.py b/lerobot/common/motors/dynamixel/dynamixel.py
index a09b1847..bced8775 100644
--- a/lerobot/common/motors/dynamixel/dynamixel.py
+++ b/lerobot/common/motors/dynamixel/dynamixel.py
@@ -12,18 +12,21 @@
 # See the License for the specific language governing permissions and
 # limitations under the License.
 
-import enum
 import logging
 import math
-import time
-import traceback
 from copy import deepcopy
 
+import dynamixel_sdk as dxl
 import numpy as np
-import tqdm
 
-from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError
-from lerobot.common.utils.utils import capture_timestamp_utc
+from ..motors_bus import (
+    CalibrationMode,
+    JointOutOfRangeError,
+    MotorsBus,
+    TorqueMode,
+    assert_same_address,
+    get_group_sync_key,
+)
 
 PROTOCOL_VERSION = 2.0
 BAUDRATE = 1_000_000
@@ -38,6 +41,7 @@ MAX_ID_RANGE = 252
 # 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
@@ -200,72 +204,7 @@ def convert_to_bytes(value, bytes, mock=False):
     return data
 
 
-def get_group_sync_key(data_name, motor_names):
-    group_key = f"{data_name}_" + "_".join(motor_names)
-    return group_key
-
-
-def get_result_name(fn_name, data_name, motor_names):
-    group_key = get_group_sync_key(data_name, motor_names)
-    rslt_name = f"{fn_name}_{group_key}"
-    return rslt_name
-
-
-def get_queue_name(fn_name, data_name, motor_names):
-    group_key = get_group_sync_key(data_name, motor_names)
-    queue_name = f"{fn_name}_{group_key}"
-    return queue_name
-
-
-def get_log_name(var_name, fn_name, data_name, motor_names):
-    group_key = get_group_sync_key(data_name, motor_names)
-    log_name = f"{var_name}_{fn_name}_{group_key}"
-    return log_name
-
-
-def assert_same_address(model_ctrl_table, motor_models, data_name):
-    all_addr = []
-    all_bytes = []
-    for model in motor_models:
-        addr, bytes = model_ctrl_table[model][data_name]
-        all_addr.append(addr)
-        all_bytes.append(bytes)
-
-    if len(set(all_addr)) != 1:
-        raise NotImplementedError(
-            f"At least two motor models use a different address for `data_name`='{data_name}' ({list(zip(motor_models, all_addr, strict=False))}). Contact a LeRobot maintainer."
-        )
-
-    if len(set(all_bytes)) != 1:
-        raise NotImplementedError(
-            f"At least two motor models use a different bytes representation for `data_name`='{data_name}' ({list(zip(motor_models, all_bytes, strict=False))}). Contact a LeRobot maintainer."
-        )
-
-
-class TorqueMode(enum.Enum):
-    ENABLED = 1
-    DISABLED = 0
-
-
-class DriveMode(enum.Enum):
-    NON_INVERTED = 0
-    INVERTED = 1
-
-
-class CalibrationMode(enum.Enum):
-    # Joints with rotational motions are expressed in degrees in nominal range of [-180, 180]
-    DEGREE = 0
-    # Joints with linear motions (like gripper of Aloha) are expressed in nominal range of [0, 100]
-    LINEAR = 1
-
-
-class JointOutOfRangeError(Exception):
-    def __init__(self, message="Joint is out of range"):
-        self.message = message
-        super().__init__(self.message)
-
-
-class DynamixelMotorsBus:
+class DynamixelMotorsBus(MotorsBus):
     """
     The DynamixelMotorsBus class allows to efficiently read and write to the attached motors. It relies on
     the python dynamixel sdk to communicate with the motors. For more info, see the [Dynamixel SDK Documentation](https://emanual.robotis.com/docs/en/software/dynamixel/dynamixel_sdk/sample_code/python_read_write_protocol_2_0/#python-read-write-protocol-20).
@@ -304,124 +243,24 @@ class DynamixelMotorsBus:
     ```
     """
 
+    model_ctrl_table = deepcopy(MODEL_CONTROL_TABLE)
+    model_resolution = deepcopy(MODEL_RESOLUTION)
+
     def __init__(
         self,
         port: str,
         motors: dict[str, tuple[int, str]],
-        mock: bool = False,
     ):
-        self.port = port
-        self.motors = motors
-        self.mock = mock
-
-        self.model_ctrl_table = deepcopy(MODEL_CONTROL_TABLE)
-        self.model_resolution = deepcopy(MODEL_RESOLUTION)
-
-        self.port_handler = None
-        self.packet_handler = None
-        self.calibration = None
-        self.is_connected = False
-        self.group_readers = {}
-        self.group_writers = {}
-        self.logs = {}
-
-    def connect(self):
-        if self.is_connected:
-            raise DeviceAlreadyConnectedError(
-                f"DynamixelMotorsBus({self.port}) is already connected. Do not call `motors_bus.connect()` twice."
-            )
-
-        if self.mock:
-            import tests.motors.mock_dynamixel_sdk as dxl
-        else:
-            import dynamixel_sdk as dxl
+        super().__init__(port, motors)
 
+    def _set_handlers(self):
         self.port_handler = dxl.PortHandler(self.port)
         self.packet_handler = dxl.PacketHandler(PROTOCOL_VERSION)
 
-        try:
-            if not self.port_handler.openPort():
-                raise OSError(f"Failed to open port '{self.port}'.")
-        except Exception:
-            traceback.print_exc()
-            print(
-                "\nTry running `python lerobot/scripts/find_motors_bus_port.py` to make sure you are using the correct port.\n"
-            )
-            raise
+    def _set_timeout(self, timeout: int = TIMEOUT_MS):
+        self.port_handler.setPacketTimeoutMillis(timeout)
 
-        # Allow to read and write
-        self.is_connected = True
-
-        self.port_handler.setPacketTimeoutMillis(TIMEOUT_MS)
-
-    def reconnect(self):
-        if self.mock:
-            import tests.motors.mock_dynamixel_sdk as dxl
-        else:
-            import dynamixel_sdk as dxl
-
-        self.port_handler = dxl.PortHandler(self.port)
-        self.packet_handler = dxl.PacketHandler(PROTOCOL_VERSION)
-
-        if not self.port_handler.openPort():
-            raise OSError(f"Failed to open port '{self.port}'.")
-
-        self.is_connected = True
-
-    def are_motors_configured(self):
-        # Only check the motor indices and not baudrate, since if the motor baudrates are incorrect,
-        # a ConnectionError will be raised anyway.
-        try:
-            return (self.motor_indices == self.read("ID")).all()
-        except ConnectionError as e:
-            print(e)
-            return False
-
-    def find_motor_indices(self, possible_ids=None, num_retry=2):
-        if possible_ids is None:
-            possible_ids = range(MAX_ID_RANGE)
-
-        indices = []
-        for idx in tqdm.tqdm(possible_ids):
-            try:
-                present_idx = self.read_with_motor_ids(self.motor_models, [idx], "ID", num_retry=num_retry)[0]
-            except ConnectionError:
-                continue
-
-            if idx != present_idx:
-                # sanity check
-                raise OSError(
-                    "Motor index used to communicate through the bus is not the same as the one present in the motor memory. The motor memory might be damaged."
-                )
-            indices.append(idx)
-
-        return indices
-
-    def set_bus_baudrate(self, baudrate):
-        present_bus_baudrate = self.port_handler.getBaudRate()
-        if present_bus_baudrate != baudrate:
-            print(f"Setting bus baud rate to {baudrate}. Previously {present_bus_baudrate}.")
-            self.port_handler.setBaudRate(baudrate)
-
-            if self.port_handler.getBaudRate() != baudrate:
-                raise OSError("Failed to write bus baud rate.")
-
-    @property
-    def motor_names(self) -> list[str]:
-        return list(self.motors.keys())
-
-    @property
-    def motor_models(self) -> list[str]:
-        return [model for _, model in self.motors.values()]
-
-    @property
-    def motor_indices(self) -> list[int]:
-        return [idx for idx, _ in self.motors.values()]
-
-    def set_calibration(self, calibration: dict[str, list]):
-        self.calibration = calibration
-
-    def apply_calibration_autocorrect(self, values: np.ndarray | list, motor_names: list[str] | None):
+    def _apply_calibration_autocorrect(self, values: np.ndarray | list, motor_names: list[str] | None):
         """This function applies the calibration, automatically detects out of range errors for motors values and attempts to correct.
 
         For more info, see docstring of `apply_calibration` and `autocorrect_calibration`.
@@ -430,7 +269,7 @@ class DynamixelMotorsBus:
             values = self.apply_calibration(values, motor_names)
         except JointOutOfRangeError as e:
             print(e)
-            self.autocorrect_calibration(values, motor_names)
+            self._autocorrect_calibration(values, motor_names)
             values = self.apply_calibration(values, motor_names)
         return values
 
@@ -509,7 +348,7 @@ class DynamixelMotorsBus:
 
         return values
 
-    def autocorrect_calibration(self, values: np.ndarray | list, motor_names: list[str] | None):
+    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.
@@ -606,6 +445,7 @@ class DynamixelMotorsBus:
                 self.calibration["homing_offset"][calib_idx] += resolution * factor
 
     def revert_calibration(self, values: np.ndarray | list, motor_names: list[str] | None):
+        # TODO(aliberts): remove np
         """Inverse of `apply_calibration`."""
         if motor_names is None:
             motor_names = self.motor_names
@@ -645,11 +485,6 @@ class DynamixelMotorsBus:
         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_dynamixel_sdk as dxl
-        else:
-            import dynamixel_sdk as dxl
-
         return_list = True
         if not isinstance(motor_ids, list):
             return_list = False
@@ -682,25 +517,7 @@ class DynamixelMotorsBus:
         else:
             return values[0]
 
-    def read(self, data_name, motor_names: str | list[str] | None = None):
-        if not self.is_connected:
-            raise DeviceNotConnectedError(
-                f"DynamixelMotorsBus({self.port}) is not connected. You need to run `motors_bus.connect()`."
-            )
-
-        start_time = time.perf_counter()
-
-        if self.mock:
-            import tests.motors.mock_dynamixel_sdk as dxl
-        else:
-            import dynamixel_sdk as dxl
-
-        if motor_names is None:
-            motor_names = self.motor_names
-
-        if isinstance(motor_names, str):
-            motor_names = [motor_names]
-
+    def _read(self, data_name, motor_names: str | list[str] | None = None):
         motor_ids = []
         models = []
         for name in motor_names:
@@ -743,24 +560,11 @@ class DynamixelMotorsBus:
             values = values.astype(np.int32)
 
         if data_name in CALIBRATION_REQUIRED and self.calibration is not None:
-            values = self.apply_calibration_autocorrect(values, motor_names)
-
-        # log the number of seconds it took to read the data from the motors
-        delta_ts_name = get_log_name("delta_timestamp_s", "read", data_name, motor_names)
-        self.logs[delta_ts_name] = time.perf_counter() - start_time
-
-        # log the utc time at which the data was received
-        ts_utc_name = get_log_name("timestamp_utc", "read", data_name, motor_names)
-        self.logs[ts_utc_name] = capture_timestamp_utc()
+            values = self._apply_calibration_autocorrect(values, motor_names)
 
         return values
 
     def write_with_motor_ids(self, motor_models, motor_ids, data_name, values, num_retry=NUM_WRITE_RETRY):
-        if self.mock:
-            import tests.motors.mock_dynamixel_sdk as dxl
-        else:
-            import dynamixel_sdk as dxl
-
         if not isinstance(motor_ids, list):
             motor_ids = [motor_ids]
         if not isinstance(values, list):
@@ -784,30 +588,7 @@ class DynamixelMotorsBus:
                 f"{self.packet_handler.getTxRxResult(comm)}"
             )
 
-    def write(self, data_name, values: int | float | np.ndarray, motor_names: str | list[str] | None = None):
-        if not self.is_connected:
-            raise DeviceNotConnectedError(
-                f"DynamixelMotorsBus({self.port}) is not connected. You need to run `motors_bus.connect()`."
-            )
-
-        start_time = time.perf_counter()
-
-        if self.mock:
-            import tests.motors.mock_dynamixel_sdk as dxl
-        else:
-            import dynamixel_sdk as dxl
-
-        if motor_names is None:
-            motor_names = self.motor_names
-
-        if isinstance(motor_names, str):
-            motor_names = [motor_names]
-
-        if isinstance(values, (int, float, np.integer)):
-            values = [int(values)] * len(motor_names)
-
-        values = np.array(values)
-
+    def _write(self, data_name: str, values: list[int], motor_names: list[str]) -> None:
         motor_ids = []
         models = []
         for name in motor_names:
@@ -818,8 +599,6 @@ class DynamixelMotorsBus:
         if data_name in CALIBRATION_REQUIRED and self.calibration is not None:
             values = self.revert_calibration(values, motor_names)
 
-        values = values.tolist()
-
         assert_same_address(self.model_ctrl_table, models, data_name)
         addr, bytes = self.model_ctrl_table[model][data_name]
         group_key = get_group_sync_key(data_name, motor_names)
@@ -844,34 +623,6 @@ class DynamixelMotorsBus:
                 f"{self.packet_handler.getTxRxResult(comm)}"
             )
 
-        # log the number of seconds it took to write the data to the motors
-        delta_ts_name = get_log_name("delta_timestamp_s", "write", data_name, motor_names)
-        self.logs[delta_ts_name] = time.perf_counter() - start_time
-
-        # TODO(rcadene): should we log the time before sending the write command?
-        # log the utc time when the write has been completed
-        ts_utc_name = get_log_name("timestamp_utc", "write", data_name, motor_names)
-        self.logs[ts_utc_name] = capture_timestamp_utc()
-
-    def disconnect(self):
-        if not self.is_connected:
-            raise DeviceNotConnectedError(
-                f"DynamixelMotorsBus({self.port}) is not connected. Try running `motors_bus.connect()` first."
-            )
-
-        if self.port_handler is not None:
-            self.port_handler.closePort()
-            self.port_handler = None
-
-        self.packet_handler = None
-        self.group_readers = {}
-        self.group_writers = {}
-        self.is_connected = False
-
-    def __del__(self):
-        if getattr(self, "is_connected", False):
-            self.disconnect()
-
 
 def set_operating_mode(arm: DynamixelMotorsBus):
     if (arm.read("Torque_Enable") != TorqueMode.DISABLED.value).any():
diff --git a/lerobot/common/motors/dynamixel/dynamixel_old.py b/lerobot/common/motors/dynamixel/dynamixel_old.py
new file mode 100644
index 00000000..55f6069b
--- /dev/null
+++ b/lerobot/common/motors/dynamixel/dynamixel_old.py
@@ -0,0 +1,895 @@
+# 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 enum
+import logging
+import math
+import time
+import traceback
+from copy import deepcopy
+
+import numpy as np
+import tqdm
+
+from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError
+from lerobot.common.utils.utils import capture_timestamp_utc
+
+PROTOCOL_VERSION = 2.0
+BAUDRATE = 1_000_000
+TIMEOUT_MS = 1000
+
+MAX_ID_RANGE = 252
+
+# The following bounds define the lower and upper joints range (after calibration).
+# For joints in degree (i.e. revolute joints), their nominal range is [-180, 180] degrees
+# which corresponds to a half rotation on the left and half rotation on the right.
+# Some joints might require higher range, so we allow up to [-270, 270] degrees until
+# an error is raised.
+LOWER_BOUND_DEGREE = -270
+UPPER_BOUND_DEGREE = 270
+# For joints in percentage (i.e. joints that move linearly like the prismatic joint of a gripper),
+# their nominal range is [0, 100] %. For instance, for Aloha gripper, 0% is fully
+# closed, and 100% is fully open. To account for slight calibration issue, we allow up to
+# [-10, 110] until an error is raised.
+LOWER_BOUND_LINEAR = -10
+UPPER_BOUND_LINEAR = 110
+
+HALF_TURN_DEGREE = 180
+
+# https://emanual.robotis.com/docs/en/dxl/x/xl330-m077
+# https://emanual.robotis.com/docs/en/dxl/x/xl330-m288
+# https://emanual.robotis.com/docs/en/dxl/x/xl430-w250
+# https://emanual.robotis.com/docs/en/dxl/x/xm430-w350
+# https://emanual.robotis.com/docs/en/dxl/x/xm540-w270
+# https://emanual.robotis.com/docs/en/dxl/x/xc430-w150
+
+# data_name: (address, size_byte)
+X_SERIES_CONTROL_TABLE = {
+    "Model_Number": (0, 2),
+    "Model_Information": (2, 4),
+    "Firmware_Version": (6, 1),
+    "ID": (7, 1),
+    "Baud_Rate": (8, 1),
+    "Return_Delay_Time": (9, 1),
+    "Drive_Mode": (10, 1),
+    "Operating_Mode": (11, 1),
+    "Secondary_ID": (12, 1),
+    "Protocol_Type": (13, 1),
+    "Homing_Offset": (20, 4),
+    "Moving_Threshold": (24, 4),
+    "Temperature_Limit": (31, 1),
+    "Max_Voltage_Limit": (32, 2),
+    "Min_Voltage_Limit": (34, 2),
+    "PWM_Limit": (36, 2),
+    "Current_Limit": (38, 2),
+    "Acceleration_Limit": (40, 4),
+    "Velocity_Limit": (44, 4),
+    "Max_Position_Limit": (48, 4),
+    "Min_Position_Limit": (52, 4),
+    "Shutdown": (63, 1),
+    "Torque_Enable": (64, 1),
+    "LED": (65, 1),
+    "Status_Return_Level": (68, 1),
+    "Registered_Instruction": (69, 1),
+    "Hardware_Error_Status": (70, 1),
+    "Velocity_I_Gain": (76, 2),
+    "Velocity_P_Gain": (78, 2),
+    "Position_D_Gain": (80, 2),
+    "Position_I_Gain": (82, 2),
+    "Position_P_Gain": (84, 2),
+    "Feedforward_2nd_Gain": (88, 2),
+    "Feedforward_1st_Gain": (90, 2),
+    "Bus_Watchdog": (98, 1),
+    "Goal_PWM": (100, 2),
+    "Goal_Current": (102, 2),
+    "Goal_Velocity": (104, 4),
+    "Profile_Acceleration": (108, 4),
+    "Profile_Velocity": (112, 4),
+    "Goal_Position": (116, 4),
+    "Realtime_Tick": (120, 2),
+    "Moving": (122, 1),
+    "Moving_Status": (123, 1),
+    "Present_PWM": (124, 2),
+    "Present_Current": (126, 2),
+    "Present_Velocity": (128, 4),
+    "Present_Position": (132, 4),
+    "Velocity_Trajectory": (136, 4),
+    "Position_Trajectory": (140, 4),
+    "Present_Input_Voltage": (144, 2),
+    "Present_Temperature": (146, 1),
+}
+
+X_SERIES_BAUDRATE_TABLE = {
+    0: 9_600,
+    1: 57_600,
+    2: 115_200,
+    3: 1_000_000,
+    4: 2_000_000,
+    5: 3_000_000,
+    6: 4_000_000,
+}
+
+CALIBRATION_REQUIRED = ["Goal_Position", "Present_Position"]
+CONVERT_UINT32_TO_INT32_REQUIRED = ["Goal_Position", "Present_Position"]
+
+MODEL_CONTROL_TABLE = {
+    "x_series": X_SERIES_CONTROL_TABLE,
+    "xl330-m077": X_SERIES_CONTROL_TABLE,
+    "xl330-m288": X_SERIES_CONTROL_TABLE,
+    "xl430-w250": X_SERIES_CONTROL_TABLE,
+    "xm430-w350": X_SERIES_CONTROL_TABLE,
+    "xm540-w270": X_SERIES_CONTROL_TABLE,
+    "xc430-w150": X_SERIES_CONTROL_TABLE,
+}
+
+MODEL_RESOLUTION = {
+    "x_series": 4096,
+    "xl330-m077": 4096,
+    "xl330-m288": 4096,
+    "xl430-w250": 4096,
+    "xm430-w350": 4096,
+    "xm540-w270": 4096,
+    "xc430-w150": 4096,
+}
+
+MODEL_BAUDRATE_TABLE = {
+    "x_series": X_SERIES_BAUDRATE_TABLE,
+    "xl330-m077": X_SERIES_BAUDRATE_TABLE,
+    "xl330-m288": X_SERIES_BAUDRATE_TABLE,
+    "xl430-w250": X_SERIES_BAUDRATE_TABLE,
+    "xm430-w350": X_SERIES_BAUDRATE_TABLE,
+    "xm540-w270": X_SERIES_BAUDRATE_TABLE,
+    "xc430-w150": X_SERIES_BAUDRATE_TABLE,
+}
+
+NUM_READ_RETRY = 10
+NUM_WRITE_RETRY = 10
+
+
+def convert_degrees_to_steps(degrees: float | np.ndarray, models: str | list[str]) -> np.ndarray:
+    """This function converts the degree range to the step range for indicating motors rotation.
+    It assumes a motor achieves a full rotation by going from -180 degree position to +180.
+    The motor resolution (e.g. 4096) corresponds to the number of steps needed to achieve a full rotation.
+    """
+    resolutions = [MODEL_RESOLUTION[model] for model in models]
+    steps = degrees / 180 * np.array(resolutions) / 2
+    steps = steps.astype(int)
+    return steps
+
+
+def convert_to_bytes(value, bytes, mock=False):
+    if mock:
+        return value
+
+    import dynamixel_sdk as dxl
+
+    # Note: No need to convert back into unsigned int, since this byte preprocessing
+    # already handles it for us.
+    if bytes == 1:
+        data = [
+            dxl.DXL_LOBYTE(dxl.DXL_LOWORD(value)),
+        ]
+    elif bytes == 2:
+        data = [
+            dxl.DXL_LOBYTE(dxl.DXL_LOWORD(value)),
+            dxl.DXL_HIBYTE(dxl.DXL_LOWORD(value)),
+        ]
+    elif bytes == 4:
+        data = [
+            dxl.DXL_LOBYTE(dxl.DXL_LOWORD(value)),
+            dxl.DXL_HIBYTE(dxl.DXL_LOWORD(value)),
+            dxl.DXL_LOBYTE(dxl.DXL_HIWORD(value)),
+            dxl.DXL_HIBYTE(dxl.DXL_HIWORD(value)),
+        ]
+    else:
+        raise NotImplementedError(
+            f"Value of the number of bytes to be sent is expected to be in [1, 2, 4], but "
+            f"{bytes} is provided instead."
+        )
+    return data
+
+
+def get_group_sync_key(data_name, motor_names):
+    group_key = f"{data_name}_" + "_".join(motor_names)
+    return group_key
+
+
+def get_result_name(fn_name, data_name, motor_names):
+    group_key = get_group_sync_key(data_name, motor_names)
+    rslt_name = f"{fn_name}_{group_key}"
+    return rslt_name
+
+
+def get_queue_name(fn_name, data_name, motor_names):
+    group_key = get_group_sync_key(data_name, motor_names)
+    queue_name = f"{fn_name}_{group_key}"
+    return queue_name
+
+
+def get_log_name(var_name, fn_name, data_name, motor_names):
+    group_key = get_group_sync_key(data_name, motor_names)
+    log_name = f"{var_name}_{fn_name}_{group_key}"
+    return log_name
+
+
+def assert_same_address(model_ctrl_table, motor_models, data_name):
+    all_addr = []
+    all_bytes = []
+    for model in motor_models:
+        addr, bytes = model_ctrl_table[model][data_name]
+        all_addr.append(addr)
+        all_bytes.append(bytes)
+
+    if len(set(all_addr)) != 1:
+        raise NotImplementedError(
+            f"At least two motor models use a different address for `data_name`='{data_name}' ({list(zip(motor_models, all_addr, strict=False))}). Contact a LeRobot maintainer."
+        )
+
+    if len(set(all_bytes)) != 1:
+        raise NotImplementedError(
+            f"At least two motor models use a different bytes representation for `data_name`='{data_name}' ({list(zip(motor_models, all_bytes, strict=False))}). Contact a LeRobot maintainer."
+        )
+
+
+class TorqueMode(enum.Enum):
+    ENABLED = 1
+    DISABLED = 0
+
+
+class DriveMode(enum.Enum):
+    NON_INVERTED = 0
+    INVERTED = 1
+
+
+class CalibrationMode(enum.Enum):
+    # Joints with rotational motions are expressed in degrees in nominal range of [-180, 180]
+    DEGREE = 0
+    # Joints with linear motions (like gripper of Aloha) are expressed in nominal range of [0, 100]
+    LINEAR = 1
+
+
+class JointOutOfRangeError(Exception):
+    def __init__(self, message="Joint is out of range"):
+        self.message = message
+        super().__init__(self.message)
+
+
+class DynamixelMotorsBus:
+    """
+    The DynamixelMotorsBus class allows to efficiently read and write to the attached motors. It relies on
+    the python dynamixel sdk to communicate with the motors. For more info, see the [Dynamixel SDK Documentation](https://emanual.robotis.com/docs/en/software/dynamixel/dynamixel_sdk/sample_code/python_read_write_protocol_2_0/#python-read-write-protocol-20).
+
+    A DynamixelMotorsBus instance requires a port (e.g. `DynamixelMotorsBus(port="/dev/tty.usbmodem575E0031751"`)).
+    To find the port, you can run our utility script:
+    ```bash
+    python lerobot/scripts/find_motors_bus_port.py
+    >>> Finding all available ports for the MotorBus.
+    >>> ['/dev/tty.usbmodem575E0032081', '/dev/tty.usbmodem575E0031751']
+    >>> Remove the usb cable from your DynamixelMotorsBus and press Enter when done.
+    >>> The port of this DynamixelMotorsBus is /dev/tty.usbmodem575E0031751.
+    >>> Reconnect the usb cable.
+    ```
+
+    Example of usage for 1 motor connected to the bus:
+    ```python
+    motor_name = "gripper"
+    motor_index = 6
+    motor_model = "xl330-m288"
+
+    motors_bus = DynamixelMotorsBus(
+        port="/dev/tty.usbmodem575E0031751",
+        motors={motor_name: (motor_index, motor_model)},
+    )
+    motors_bus.connect()
+
+    position = motors_bus.read("Present_Position")
+
+    # move from a few motor steps as an example
+    few_steps = 30
+    motors_bus.write("Goal_Position", position + few_steps)
+
+    # when done, consider disconnecting
+    motors_bus.disconnect()
+    ```
+    """
+
+    def __init__(
+        self,
+        port: str,
+        motors: dict[str, tuple[int, str]],
+        mock: bool = False,
+    ):
+        self.port = port
+        self.motors = motors
+        self.mock = mock
+
+        self.model_ctrl_table = deepcopy(MODEL_CONTROL_TABLE)
+        self.model_resolution = deepcopy(MODEL_RESOLUTION)
+
+        self.port_handler = None
+        self.packet_handler = None
+        self.calibration = None
+        self.is_connected = False
+        self.group_readers = {}
+        self.group_writers = {}
+        self.logs = {}
+
+    def connect(self):
+        if self.is_connected:
+            raise DeviceAlreadyConnectedError(
+                f"DynamixelMotorsBus({self.port}) is already connected. Do not call `motors_bus.connect()` twice."
+            )
+
+        if self.mock:
+            import tests.mock_dynamixel_sdk as dxl
+        else:
+            import dynamixel_sdk as dxl
+
+        self.port_handler = dxl.PortHandler(self.port)
+        self.packet_handler = dxl.PacketHandler(PROTOCOL_VERSION)
+
+        try:
+            if not self.port_handler.openPort():
+                raise OSError(f"Failed to open port '{self.port}'.")
+        except Exception:
+            traceback.print_exc()
+            print(
+                "\nTry running `python lerobot/scripts/find_motors_bus_port.py` to make sure you are using the correct port.\n"
+            )
+            raise
+
+        # Allow to read and write
+        self.is_connected = True
+
+        self.port_handler.setPacketTimeoutMillis(TIMEOUT_MS)
+
+    def reconnect(self):
+        if self.mock:
+            import tests.mock_dynamixel_sdk as dxl
+        else:
+            import dynamixel_sdk as dxl
+
+        self.port_handler = dxl.PortHandler(self.port)
+        self.packet_handler = dxl.PacketHandler(PROTOCOL_VERSION)
+
+        if not self.port_handler.openPort():
+            raise OSError(f"Failed to open port '{self.port}'.")
+
+        self.is_connected = True
+
+    def are_motors_configured(self):
+        # Only check the motor indices and not baudrate, since if the motor baudrates are incorrect,
+        # a ConnectionError will be raised anyway.
+        try:
+            return (self.motor_indices == self.read("ID")).all()
+        except ConnectionError as e:
+            print(e)
+            return False
+
+    def find_motor_indices(self, possible_ids=None, num_retry=2):
+        if possible_ids is None:
+            possible_ids = range(MAX_ID_RANGE)
+
+        indices = []
+        for idx in tqdm.tqdm(possible_ids):
+            try:
+                present_idx = self.read_with_motor_ids(self.motor_models, [idx], "ID", num_retry=num_retry)[0]
+            except ConnectionError:
+                continue
+
+            if idx != present_idx:
+                # sanity check
+                raise OSError(
+                    "Motor index used to communicate through the bus is not the same as the one present in the motor memory. The motor memory might be damaged."
+                )
+            indices.append(idx)
+
+        return indices
+
+    def set_bus_baudrate(self, baudrate):
+        present_bus_baudrate = self.port_handler.getBaudRate()
+        if present_bus_baudrate != baudrate:
+            print(f"Setting bus baud rate to {baudrate}. Previously {present_bus_baudrate}.")
+            self.port_handler.setBaudRate(baudrate)
+
+            if self.port_handler.getBaudRate() != baudrate:
+                raise OSError("Failed to write bus baud rate.")
+
+    @property
+    def motor_names(self) -> list[str]:
+        return list(self.motors.keys())
+
+    @property
+    def motor_models(self) -> list[str]:
+        return [model for _, model in self.motors.values()]
+
+    @property
+    def motor_indices(self) -> list[int]:
+        return [idx for idx, _ in self.motors.values()]
+
+    def set_calibration(self, calibration: dict[str, list]):
+        self.calibration = calibration
+
+    def apply_calibration_autocorrect(self, values: np.ndarray | list, motor_names: list[str] | None):
+        """This function applies the calibration, automatically detects out of range errors for motors values and attempts 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, dynamixel xl330-m077 have a resolution of 4096, and
+        at any position in their original range, let's say the position 56734, they complete a full rotation clockwise by moving to 60830,
+        or anticlockwise by moving to 52638. The position in the original range is arbitrary and might change a lot between each motor.
+        To harmonize between motors of the same model, different robots, or even models of different brands, we propose to work
+        in the centered nominal degree range ]-180, 180[.
+        """
+        if motor_names is None:
+            motor_names = self.motor_names
+
+        # Convert from unsigned int32 original range [0, 2**32] to signed float32 range
+        values = values.astype(np.float32)
+
+        for i, name in enumerate(motor_names):
+            calib_idx = self.calibration["motor_names"].index(name)
+            calib_mode = self.calibration["calib_mode"][calib_idx]
+
+            if CalibrationMode[calib_mode] == CalibrationMode.DEGREE:
+                drive_mode = self.calibration["drive_mode"][calib_idx]
+                homing_offset = self.calibration["homing_offset"][calib_idx]
+                _, model = self.motors[name]
+                resolution = self.model_resolution[model]
+
+                # Update direction of rotation of the motor to match between leader and follower.
+                # In fact, the motor of the leader for a given joint can be assembled in an
+                # opposite direction in term of rotation than the motor of the follower on the same joint.
+                if drive_mode:
+                    values[i] *= -1
+
+                # Convert from range [-2**31, 2**31] to
+                # nominal range [-resolution//2, resolution//2] (e.g. [-2048, 2048])
+                values[i] += homing_offset
+
+                # Convert from range [-resolution//2, resolution//2] to
+                # universal float32 centered degree range [-180, 180]
+                # (e.g. 2048 / (4096 // 2) * 180 = 180)
+                values[i] = values[i] / (resolution // 2) * HALF_TURN_DEGREE
+
+                if (values[i] < LOWER_BOUND_DEGREE) or (values[i] > UPPER_BOUND_DEGREE):
+                    raise JointOutOfRangeError(
+                        f"Wrong motor position range detected for {name}. "
+                        f"Expected to be in nominal range of [-{HALF_TURN_DEGREE}, {HALF_TURN_DEGREE}] degrees (a full rotation), "
+                        f"with a maximum range of [{LOWER_BOUND_DEGREE}, {UPPER_BOUND_DEGREE}] degrees to account for joints that can rotate a bit more, "
+                        f"but present value is {values[i]} degree. "
+                        "This might be due to a cable connection issue creating an artificial 360 degrees jump in motor values. "
+                        "You need to recalibrate by running: `python lerobot/scripts/control_robot.py calibrate`"
+                    )
+
+            elif CalibrationMode[calib_mode] == CalibrationMode.LINEAR:
+                start_pos = self.calibration["start_pos"][calib_idx]
+                end_pos = self.calibration["end_pos"][calib_idx]
+
+                # Rescale the present position to a nominal range [0, 100] %,
+                # useful for joints with linear motions like Aloha gripper
+                values[i] = (values[i] - start_pos) / (end_pos - start_pos) * 100
+
+                if (values[i] < LOWER_BOUND_LINEAR) or (values[i] > UPPER_BOUND_LINEAR):
+                    raise JointOutOfRangeError(
+                        f"Wrong motor position range detected for {name}. "
+                        f"Expected to be in nominal range of [0, 100] % (a full linear translation), "
+                        f"with a maximum range of [{LOWER_BOUND_LINEAR}, {UPPER_BOUND_LINEAR}] % to account for some imprecision during calibration, "
+                        f"but present value is {values[i]} %. "
+                        "This might be due to a cable connection issue creating an artificial jump in motor values. "
+                        "You need to recalibrate by running: `python lerobot/scripts/control_robot.py calibrate`"
+                    )
+
+        return values
+
+    def autocorrect_calibration(self, values: np.ndarray | list, motor_names: list[str] | None):
+        """This function automatically detects issues with values of motors after calibration, and correct for these issues.
+
+        Some motors might have values outside of expected maximum bounds after calibration.
+        For instance, for a joint in degree, its value can be outside [-270, 270] degrees, which is totally unexpected given
+        a nominal range of [-180, 180] degrees, which represents half a turn to the left or right starting from zero position.
+
+        Known issues:
+        #1: Motor value randomly shifts of a full turn, caused by hardware/connection errors.
+        #2: Motor internal homing offset is shifted by a full turn, caused by using default calibration (e.g Aloha).
+        #3: motor internal homing offset is shifted by 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]
+
+                # 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 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
+                # (- (resolution // 2) - values[i] - homing_offset) / resolution <= factor <= ((resolution // 2) - values[i] - homing_offset) / resolution
+                low_factor = (-(resolution // 2) - values[i] - homing_offset) / resolution
+                upp_factor = ((resolution // 2) - values[i] - homing_offset) / resolution
+
+            elif CalibrationMode[calib_mode] == CalibrationMode.LINEAR:
+                start_pos = self.calibration["start_pos"][calib_idx]
+                end_pos = self.calibration["end_pos"][calib_idx]
+
+                # Convert from initial range to range [0, 100] in %
+                calib_val = (values[i] - start_pos) / (end_pos - start_pos) * 100
+                in_range = (calib_val > LOWER_BOUND_LINEAR) and (calib_val < UPPER_BOUND_LINEAR)
+
+                # Solve this inequality to find the factor to shift the range into [0, 100] %
+                # values[i] = (values[i] - start_pos + resolution * factor) / (end_pos + resolution * factor - start_pos - resolution * factor) * 100
+                # values[i] = (values[i] - start_pos + resolution * factor) / (end_pos - start_pos) * 100
+                # 0 <= (values[i] - start_pos + resolution * factor) / (end_pos - start_pos) * 100 <= 100
+                # (start_pos - values[i]) / resolution <= factor <= (end_pos - values[i]) / resolution
+                low_factor = (start_pos - values[i]) / resolution
+                upp_factor = (end_pos - values[i]) / resolution
+
+            if not in_range:
+                # Get first integer between the two bounds
+                if low_factor < upp_factor:
+                    factor = math.ceil(low_factor)
+
+                    if factor > upp_factor:
+                        raise ValueError(f"No integer found between bounds [{low_factor=}, {upp_factor=}]")
+                else:
+                    factor = math.ceil(upp_factor)
+
+                    if factor > low_factor:
+                        raise ValueError(f"No integer found between bounds [{low_factor=}, {upp_factor=}]")
+
+                if CalibrationMode[calib_mode] == CalibrationMode.DEGREE:
+                    out_of_range_str = f"{LOWER_BOUND_DEGREE} < {calib_val} < {UPPER_BOUND_DEGREE} degrees"
+                    in_range_str = f"{LOWER_BOUND_DEGREE} < {calib_val} < {UPPER_BOUND_DEGREE} degrees"
+                elif CalibrationMode[calib_mode] == CalibrationMode.LINEAR:
+                    out_of_range_str = f"{LOWER_BOUND_LINEAR} < {calib_val} < {UPPER_BOUND_LINEAR} %"
+                    in_range_str = f"{LOWER_BOUND_LINEAR} < {calib_val} < {UPPER_BOUND_LINEAR} %"
+
+                logging.warning(
+                    f"Auto-correct calibration of motor '{name}' by shifting value by {abs(factor)} full turns, "
+                    f"from '{out_of_range_str}' to '{in_range_str}'."
+                )
+
+                # A full turn corresponds to 360 degrees but also to 4096 steps for a motor resolution of 4096.
+                self.calibration["homing_offset"][calib_idx] += resolution * factor
+
+    def revert_calibration(self, values: np.ndarray | list, motor_names: list[str] | None):
+        """Inverse of `apply_calibration`."""
+        if motor_names is None:
+            motor_names = self.motor_names
+
+        for i, name in enumerate(motor_names):
+            calib_idx = self.calibration["motor_names"].index(name)
+            calib_mode = self.calibration["calib_mode"][calib_idx]
+
+            if CalibrationMode[calib_mode] == CalibrationMode.DEGREE:
+                drive_mode = self.calibration["drive_mode"][calib_idx]
+                homing_offset = self.calibration["homing_offset"][calib_idx]
+                _, model = self.motors[name]
+                resolution = self.model_resolution[model]
+
+                # Convert from nominal 0-centered degree range [-180, 180] to
+                # 0-centered resolution range (e.g. [-2048, 2048] for resolution=4096)
+                values[i] = values[i] / HALF_TURN_DEGREE * (resolution // 2)
+
+                # 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
+
+            elif CalibrationMode[calib_mode] == CalibrationMode.LINEAR:
+                start_pos = self.calibration["start_pos"][calib_idx]
+                end_pos = self.calibration["end_pos"][calib_idx]
+
+                # Convert from nominal lnear range of [0, 100] % to
+                # actual motor range of values which can be arbitrary.
+                values[i] = values[i] / 100 * (end_pos - start_pos) + start_pos
+
+        values = np.round(values).astype(np.int32)
+        return values
+
+    def read_with_motor_ids(self, motor_models, motor_ids, data_name, num_retry=NUM_READ_RETRY):
+        if self.mock:
+            import tests.mock_dynamixel_sdk as dxl
+        else:
+            import dynamixel_sdk as dxl
+
+        return_list = True
+        if not isinstance(motor_ids, list):
+            return_list = False
+            motor_ids = [motor_ids]
+
+        assert_same_address(self.model_ctrl_table, self.motor_models, data_name)
+        addr, bytes = self.model_ctrl_table[motor_models[0]][data_name]
+        group = dxl.GroupSyncRead(self.port_handler, self.packet_handler, addr, bytes)
+        for idx in motor_ids:
+            group.addParam(idx)
+
+        for _ in range(num_retry):
+            comm = group.txRxPacket()
+            if comm == dxl.COMM_SUCCESS:
+                break
+
+        if comm != dxl.COMM_SUCCESS:
+            raise ConnectionError(
+                f"Read failed due to communication error on port {self.port_handler.port_name} for indices {motor_ids}: "
+                f"{self.packet_handler.getTxRxResult(comm)}"
+            )
+
+        values = []
+        for idx in motor_ids:
+            value = group.getData(idx, addr, bytes)
+            values.append(value)
+
+        if return_list:
+            return values
+        else:
+            return values[0]
+
+    def read(self, data_name, motor_names: str | list[str] | None = None):
+        if not self.is_connected:
+            raise DeviceNotConnectedError(
+                f"DynamixelMotorsBus({self.port}) is not connected. You need to run `motors_bus.connect()`."
+            )
+
+        start_time = time.perf_counter()
+
+        if self.mock:
+            import tests.mock_dynamixel_sdk as dxl
+        else:
+            import dynamixel_sdk as dxl
+
+        if motor_names is None:
+            motor_names = self.motor_names
+
+        if isinstance(motor_names, str):
+            motor_names = [motor_names]
+
+        motor_ids = []
+        models = []
+        for name in motor_names:
+            motor_idx, model = self.motors[name]
+            motor_ids.append(motor_idx)
+            models.append(model)
+
+        assert_same_address(self.model_ctrl_table, models, data_name)
+        addr, bytes = self.model_ctrl_table[model][data_name]
+        group_key = get_group_sync_key(data_name, motor_names)
+
+        if data_name not in self.group_readers:
+            # create new group reader
+            self.group_readers[group_key] = dxl.GroupSyncRead(
+                self.port_handler, self.packet_handler, addr, bytes
+            )
+            for idx in motor_ids:
+                self.group_readers[group_key].addParam(idx)
+
+        for _ in range(NUM_READ_RETRY):
+            comm = self.group_readers[group_key].txRxPacket()
+            if comm == dxl.COMM_SUCCESS:
+                break
+
+        if comm != dxl.COMM_SUCCESS:
+            raise ConnectionError(
+                f"Read failed due to communication error on port {self.port} for group_key {group_key}: "
+                f"{self.packet_handler.getTxRxResult(comm)}"
+            )
+
+        values = []
+        for idx in motor_ids:
+            value = self.group_readers[group_key].getData(idx, addr, bytes)
+            values.append(value)
+
+        values = np.array(values)
+
+        # Convert to signed int to use range [-2048, 2048] for our motor positions.
+        if data_name in CONVERT_UINT32_TO_INT32_REQUIRED:
+            values = values.astype(np.int32)
+
+        if data_name in CALIBRATION_REQUIRED and self.calibration is not None:
+            values = self.apply_calibration_autocorrect(values, motor_names)
+
+        # log the number of seconds it took to read the data from the motors
+        delta_ts_name = get_log_name("delta_timestamp_s", "read", data_name, motor_names)
+        self.logs[delta_ts_name] = time.perf_counter() - start_time
+
+        # log the utc time at which the data was received
+        ts_utc_name = get_log_name("timestamp_utc", "read", data_name, motor_names)
+        self.logs[ts_utc_name] = capture_timestamp_utc()
+
+        return values
+
+    def write_with_motor_ids(self, motor_models, motor_ids, data_name, values, num_retry=NUM_WRITE_RETRY):
+        if self.mock:
+            import tests.mock_dynamixel_sdk as dxl
+        else:
+            import dynamixel_sdk as dxl
+
+        if not isinstance(motor_ids, list):
+            motor_ids = [motor_ids]
+        if not isinstance(values, list):
+            values = [values]
+
+        assert_same_address(self.model_ctrl_table, motor_models, data_name)
+        addr, bytes = self.model_ctrl_table[motor_models[0]][data_name]
+        group = dxl.GroupSyncWrite(self.port_handler, self.packet_handler, addr, bytes)
+        for idx, value in zip(motor_ids, values, strict=True):
+            data = convert_to_bytes(value, bytes, self.mock)
+            group.addParam(idx, data)
+
+        for _ in range(num_retry):
+            comm = group.txPacket()
+            if comm == dxl.COMM_SUCCESS:
+                break
+
+        if comm != dxl.COMM_SUCCESS:
+            raise ConnectionError(
+                f"Write failed due to communication error on port {self.port_handler.port_name} for indices {motor_ids}: "
+                f"{self.packet_handler.getTxRxResult(comm)}"
+            )
+
+    def write(self, data_name, values: int | float | np.ndarray, motor_names: str | list[str] | None = None):
+        if not self.is_connected:
+            raise DeviceNotConnectedError(
+                f"DynamixelMotorsBus({self.port}) is not connected. You need to run `motors_bus.connect()`."
+            )
+
+        start_time = time.perf_counter()
+
+        if self.mock:
+            import tests.mock_dynamixel_sdk as dxl
+        else:
+            import dynamixel_sdk as dxl
+
+        if motor_names is None:
+            motor_names = self.motor_names
+
+        if isinstance(motor_names, str):
+            motor_names = [motor_names]
+
+        if isinstance(values, (int, float, np.integer)):
+            values = [int(values)] * len(motor_names)
+
+        values = np.array(values)
+
+        motor_ids = []
+        models = []
+        for name in motor_names:
+            motor_idx, model = self.motors[name]
+            motor_ids.append(motor_idx)
+            models.append(model)
+
+        if data_name in CALIBRATION_REQUIRED and self.calibration is not None:
+            values = self.revert_calibration(values, motor_names)
+
+        values = values.tolist()
+
+        assert_same_address(self.model_ctrl_table, models, data_name)
+        addr, bytes = self.model_ctrl_table[model][data_name]
+        group_key = get_group_sync_key(data_name, motor_names)
+
+        init_group = data_name not in self.group_readers
+        if init_group:
+            self.group_writers[group_key] = dxl.GroupSyncWrite(
+                self.port_handler, self.packet_handler, addr, bytes
+            )
+
+        for idx, value in zip(motor_ids, values, strict=True):
+            data = convert_to_bytes(value, bytes, self.mock)
+            if init_group:
+                self.group_writers[group_key].addParam(idx, data)
+            else:
+                self.group_writers[group_key].changeParam(idx, data)
+
+        comm = self.group_writers[group_key].txPacket()
+        if comm != dxl.COMM_SUCCESS:
+            raise ConnectionError(
+                f"Write failed due to communication error on port {self.port} for group_key {group_key}: "
+                f"{self.packet_handler.getTxRxResult(comm)}"
+            )
+
+        # log the number of seconds it took to write the data to the motors
+        delta_ts_name = get_log_name("delta_timestamp_s", "write", data_name, motor_names)
+        self.logs[delta_ts_name] = time.perf_counter() - start_time
+
+        # TODO(rcadene): should we log the time before sending the write command?
+        # log the utc time when the write has been completed
+        ts_utc_name = get_log_name("timestamp_utc", "write", data_name, motor_names)
+        self.logs[ts_utc_name] = capture_timestamp_utc()
+
+    def disconnect(self):
+        if not self.is_connected:
+            raise DeviceNotConnectedError(
+                f"DynamixelMotorsBus({self.port}) is not connected. Try running `motors_bus.connect()` first."
+            )
+
+        if self.port_handler is not None:
+            self.port_handler.closePort()
+            self.port_handler = None
+
+        self.packet_handler = None
+        self.group_readers = {}
+        self.group_writers = {}
+        self.is_connected = False
+
+    def __del__(self):
+        if getattr(self, "is_connected", False):
+            self.disconnect()
+
+
+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/feetech/feetech.py b/lerobot/common/motors/feetech/feetech.py
index 8a34d1d3..450d3efc 100644
--- a/lerobot/common/motors/feetech/feetech.py
+++ b/lerobot/common/motors/feetech/feetech.py
@@ -12,16 +12,18 @@
 # See the License for the specific language governing permissions and
 # limitations under the License.
 
-import enum
-import time
-import traceback
 from copy import deepcopy
 
 import numpy as np
-import tqdm
+import scservo_sdk as scs
 
-from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError
-from lerobot.common.utils.utils import capture_timestamp_utc
+from ..motors_bus import (
+    CalibrationMode,
+    JointOutOfRangeError,
+    MotorsBus,
+    assert_same_address,
+    get_group_sync_key,
+)
 
 PROTOCOL_VERSION = 0
 BAUDRATE = 1_000_000
@@ -215,72 +217,7 @@ def convert_to_bytes(value, bytes, mock=False):
     return data
 
 
-def get_group_sync_key(data_name, motor_names):
-    group_key = f"{data_name}_" + "_".join(motor_names)
-    return group_key
-
-
-def get_result_name(fn_name, data_name, motor_names):
-    group_key = get_group_sync_key(data_name, motor_names)
-    rslt_name = f"{fn_name}_{group_key}"
-    return rslt_name
-
-
-def get_queue_name(fn_name, data_name, motor_names):
-    group_key = get_group_sync_key(data_name, motor_names)
-    queue_name = f"{fn_name}_{group_key}"
-    return queue_name
-
-
-def get_log_name(var_name, fn_name, data_name, motor_names):
-    group_key = get_group_sync_key(data_name, motor_names)
-    log_name = f"{var_name}_{fn_name}_{group_key}"
-    return log_name
-
-
-def assert_same_address(model_ctrl_table, motor_models, data_name):
-    all_addr = []
-    all_bytes = []
-    for model in motor_models:
-        addr, bytes = model_ctrl_table[model][data_name]
-        all_addr.append(addr)
-        all_bytes.append(bytes)
-
-    if len(set(all_addr)) != 1:
-        raise NotImplementedError(
-            f"At least two motor models use a different address for `data_name`='{data_name}' ({list(zip(motor_models, all_addr, strict=False))}). Contact a LeRobot maintainer."
-        )
-
-    if len(set(all_bytes)) != 1:
-        raise NotImplementedError(
-            f"At least two motor models use a different bytes representation for `data_name`='{data_name}' ({list(zip(motor_models, all_bytes, strict=False))}). Contact a LeRobot maintainer."
-        )
-
-
-class TorqueMode(enum.Enum):
-    ENABLED = 1
-    DISABLED = 0
-
-
-class DriveMode(enum.Enum):
-    NON_INVERTED = 0
-    INVERTED = 1
-
-
-class CalibrationMode(enum.Enum):
-    # Joints with rotational motions are expressed in degrees in nominal range of [-180, 180]
-    DEGREE = 0
-    # Joints with linear motions (like gripper of Aloha) are expressed in nominal range of [0, 100]
-    LINEAR = 1
-
-
-class JointOutOfRangeError(Exception):
-    def __init__(self, message="Joint is out of range"):
-        self.message = message
-        super().__init__(self.message)
-
-
-class FeetechMotorsBus:
+class FeetechMotorsBus(MotorsBus):
     """
     The FeetechMotorsBus class allows to efficiently read and write to the attached motors. It relies on
     the python feetech sdk to communicate with the motors. For more info, see the [feetech SDK Documentation](https://emanual.robotis.com/docs/en/software/feetech/feetech_sdk/sample_code/python_read_write_protocol_2_0/#python-read-write-protocol-20).
@@ -319,122 +256,22 @@ class FeetechMotorsBus:
     ```
     """
 
+    model_ctrl_table = deepcopy(MODEL_CONTROL_TABLE)
+    model_resolution = deepcopy(MODEL_RESOLUTION)
+
     def __init__(
         self,
         port: str,
         motors: dict[str, tuple[int, str]],
-        mock: bool = False,
     ):
-        self.port = port
-        self.motors = motors
-        self.mock = mock
-
-        self.model_ctrl_table = deepcopy(MODEL_CONTROL_TABLE)
-        self.model_resolution = deepcopy(MODEL_RESOLUTION)
-
-        self.port_handler = None
-        self.packet_handler = None
-        self.calibration = None
-        self.is_connected = False
-        self.group_readers = {}
-        self.group_writers = {}
-        self.logs = {}
-
-    def connect(self):
-        if self.is_connected:
-            raise DeviceAlreadyConnectedError(
-                f"FeetechMotorsBus({self.port}) is already connected. Do not call `motors_bus.connect()` twice."
-            )
-
-        if self.mock:
-            import tests.motors.mock_scservo_sdk as scs
-        else:
-            import scservo_sdk as scs
+        super().__init__(port, motors)
 
+    def _set_handlers(self):
         self.port_handler = scs.PortHandler(self.port)
         self.packet_handler = scs.PacketHandler(PROTOCOL_VERSION)
 
-        try:
-            if not self.port_handler.openPort():
-                raise OSError(f"Failed to open port '{self.port}'.")
-        except Exception:
-            traceback.print_exc()
-            print(
-                "\nTry running `python lerobot/scripts/find_motors_bus_port.py` to make sure you are using the correct port.\n"
-            )
-            raise
-
-        # Allow to read and write
-        self.is_connected = True
-
-        self.port_handler.setPacketTimeoutMillis(TIMEOUT_MS)
-
-    def reconnect(self):
-        if self.mock:
-            import tests.motors.mock_scservo_sdk as scs
-        else:
-            import scservo_sdk as scs
-
-        self.port_handler = scs.PortHandler(self.port)
-        self.packet_handler = scs.PacketHandler(PROTOCOL_VERSION)
-
-        if not self.port_handler.openPort():
-            raise OSError(f"Failed to open port '{self.port}'.")
-
-        self.is_connected = True
-
-    def are_motors_configured(self):
-        # Only check the motor indices and not baudrate, since if the motor baudrates are incorrect,
-        # a ConnectionError will be raised anyway.
-        try:
-            return (self.motor_indices == self.read("ID")).all()
-        except ConnectionError as e:
-            print(e)
-            return False
-
-    def find_motor_indices(self, possible_ids=None, num_retry=2):
-        if possible_ids is None:
-            possible_ids = range(MAX_ID_RANGE)
-
-        indices = []
-        for idx in tqdm.tqdm(possible_ids):
-            try:
-                present_idx = self.read_with_motor_ids(self.motor_models, [idx], "ID", num_retry=num_retry)[0]
-            except ConnectionError:
-                continue
-
-            if idx != present_idx:
-                # sanity check
-                raise OSError(
-                    "Motor index used to communicate through the bus is not the same as the one present in the motor memory. The motor memory might be damaged."
-                )
-            indices.append(idx)
-
-        return indices
-
-    def set_bus_baudrate(self, baudrate):
-        present_bus_baudrate = self.port_handler.getBaudRate()
-        if present_bus_baudrate != baudrate:
-            print(f"Setting bus baud rate to {baudrate}. Previously {present_bus_baudrate}.")
-            self.port_handler.setBaudRate(baudrate)
-
-            if self.port_handler.getBaudRate() != baudrate:
-                raise OSError("Failed to write bus baud rate.")
-
-    @property
-    def motor_names(self) -> list[str]:
-        return list(self.motors.keys())
-
-    @property
-    def motor_models(self) -> list[str]:
-        return [model for _, model in self.motors.values()]
-
-    @property
-    def motor_indices(self) -> list[int]:
-        return [idx for idx, _ in self.motors.values()]
-
-    def set_calibration(self, calibration: dict[str, list]):
-        self.calibration = calibration
+    def _set_timeout(self, timeout: int = TIMEOUT_MS):
+        self.port_handler.setPacketTimeoutMillis(timeout)
 
     def apply_calibration(self, values: np.ndarray | list, motor_names: list[str] | None):
         if motor_names is None:
@@ -502,11 +339,6 @@ class FeetechMotorsBus:
         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
-        else:
-            import scservo_sdk as scs
-
         return_list = True
         if not isinstance(motor_ids, list):
             return_list = False
@@ -539,25 +371,7 @@ class FeetechMotorsBus:
         else:
             return values[0]
 
-    def read(self, data_name, motor_names: str | list[str] | None = None):
-        if self.mock:
-            import tests.motors.mock_scservo_sdk as scs
-        else:
-            import scservo_sdk as scs
-
-        if not self.is_connected:
-            raise DeviceNotConnectedError(
-                f"FeetechMotorsBus({self.port}) is not connected. You need to run `motors_bus.connect()`."
-            )
-
-        start_time = time.perf_counter()
-
-        if motor_names is None:
-            motor_names = self.motor_names
-
-        if isinstance(motor_names, str):
-            motor_names = [motor_names]
-
+    def _read(self, data_name, motor_names: str | list[str] | None = None):
         motor_ids = []
         models = []
         for name in motor_names:
@@ -602,22 +416,9 @@ class FeetechMotorsBus:
         if data_name in CALIBRATION_REQUIRED and self.calibration is not None:
             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)
-        self.logs[delta_ts_name] = time.perf_counter() - start_time
-
-        # log the utc time at which the data was received
-        ts_utc_name = get_log_name("timestamp_utc", "read", data_name, motor_names)
-        self.logs[ts_utc_name] = capture_timestamp_utc()
-
         return values
 
     def write_with_motor_ids(self, motor_models, motor_ids, data_name, values, num_retry=NUM_WRITE_RETRY):
-        if self.mock:
-            import tests.motors.mock_scservo_sdk as scs
-        else:
-            import scservo_sdk as scs
-
         if not isinstance(motor_ids, list):
             motor_ids = [motor_ids]
         if not isinstance(values, list):
@@ -641,30 +442,7 @@ class FeetechMotorsBus:
                 f"{self.packet_handler.getTxRxResult(comm)}"
             )
 
-    def write(self, data_name, values: int | float | np.ndarray, motor_names: str | list[str] | None = None):
-        if not self.is_connected:
-            raise DeviceNotConnectedError(
-                f"FeetechMotorsBus({self.port}) is not connected. You need to run `motors_bus.connect()`."
-            )
-
-        start_time = time.perf_counter()
-
-        if self.mock:
-            import tests.motors.mock_scservo_sdk as scs
-        else:
-            import scservo_sdk as scs
-
-        if motor_names is None:
-            motor_names = self.motor_names
-
-        if isinstance(motor_names, str):
-            motor_names = [motor_names]
-
-        if isinstance(values, (int, float, np.integer)):
-            values = [int(values)] * len(motor_names)
-
-        values = np.array(values)
-
+    def _write(self, data_name: str, values: list[int], motor_names: list[str]) -> None:
         motor_ids = []
         models = []
         for name in motor_names:
@@ -675,8 +453,6 @@ class FeetechMotorsBus:
         if data_name in CALIBRATION_REQUIRED and self.calibration is not None:
             values = self.revert_calibration(values, motor_names)
 
-        values = values.tolist()
-
         assert_same_address(self.model_ctrl_table, models, data_name)
         addr, bytes = self.model_ctrl_table[model][data_name]
         group_key = get_group_sync_key(data_name, motor_names)
@@ -700,31 +476,3 @@ class FeetechMotorsBus:
                 f"Write failed due to communication error on port {self.port} for group_key {group_key}: "
                 f"{self.packet_handler.getTxRxResult(comm)}"
             )
-
-        # log the number of seconds it took to write the data to the motors
-        delta_ts_name = get_log_name("delta_timestamp_s", "write", data_name, motor_names)
-        self.logs[delta_ts_name] = time.perf_counter() - start_time
-
-        # TODO(rcadene): should we log the time before sending the write command?
-        # log the utc time when the write has been completed
-        ts_utc_name = get_log_name("timestamp_utc", "write", data_name, motor_names)
-        self.logs[ts_utc_name] = capture_timestamp_utc()
-
-    def disconnect(self):
-        if not self.is_connected:
-            raise DeviceNotConnectedError(
-                f"FeetechMotorsBus({self.port}) is not connected. Try running `motors_bus.connect()` first."
-            )
-
-        if self.port_handler is not None:
-            self.port_handler.closePort()
-            self.port_handler = None
-
-        self.packet_handler = None
-        self.group_readers = {}
-        self.group_writers = {}
-        self.is_connected = False
-
-    def __del__(self):
-        if getattr(self, "is_connected", False):
-            self.disconnect()
diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py
index ca95a4da..a6a9297e 100644
--- a/lerobot/common/motors/motors_bus.py
+++ b/lerobot/common/motors/motors_bus.py
@@ -1,29 +1,279 @@
+#!/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.
+
+# TODO(aliberts): This noqa is for the PortHandler / PacketHandler Protocols
+# Add block noqa when feature below is available
+# https://github.com/astral-sh/ruff/issues/3711
+# ruff: noqa: N802
+
 import abc
+import enum
+import time
+import traceback
+from typing import Protocol
+
+import numpy as np
+import tqdm
+
+from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError
+from lerobot.common.utils.utils import capture_timestamp_utc
+
+MAX_ID_RANGE = 252
+
+
+def get_group_sync_key(data_name: str, motor_names: list[str]):
+    group_key = f"{data_name}_" + "_".join(motor_names)
+    return group_key
+
+
+def get_result_name(fn_name: str, data_name: str, motor_names: list[str]):
+    group_key = get_group_sync_key(data_name, motor_names)
+    rslt_name = f"{fn_name}_{group_key}"
+    return rslt_name
+
+
+def get_queue_name(fn_name: str, data_name: str, motor_names: list[str]):
+    group_key = get_group_sync_key(data_name, motor_names)
+    queue_name = f"{fn_name}_{group_key}"
+    return queue_name
+
+
+def get_log_name(var_name: str, fn_name: str, data_name: str, motor_names: list[str]):
+    group_key = get_group_sync_key(data_name, motor_names)
+    log_name = f"{var_name}_{fn_name}_{group_key}"
+    return log_name
+
+
+def assert_same_address(model_ctrl_table: dict[str, dict], motor_models: list[str], data_name: str):
+    all_addr = []
+    all_bytes = []
+    for model in motor_models:
+        addr, bytes = model_ctrl_table[model][data_name]
+        all_addr.append(addr)
+        all_bytes.append(bytes)
+
+    if len(set(all_addr)) != 1:
+        raise NotImplementedError(
+            f"At least two motor models use a different address for `data_name`='{data_name}' ({list(zip(motor_models, all_addr, strict=False))}). Contact a LeRobot maintainer."
+        )
+
+    if len(set(all_bytes)) != 1:
+        raise NotImplementedError(
+            f"At least two motor models use a different bytes representation for `data_name`='{data_name}' ({list(zip(motor_models, all_bytes, strict=False))}). Contact a LeRobot maintainer."
+        )
+
+
+class TorqueMode(enum.Enum):
+    ENABLED = 1
+    DISABLED = 0
+
+
+class DriveMode(enum.Enum):
+    NON_INVERTED = 0
+    INVERTED = 1
+
+
+class CalibrationMode(enum.Enum):
+    # Joints with rotational motions are expressed in degrees in nominal range of [-180, 180]
+    DEGREE = 0
+    # Joints with liner motions (like gripper of Aloha) are expressed in nominal range of [0, 100]
+    LINEAR = 1
+
+
+class JointOutOfRangeError(Exception):
+    def __init__(self, message="Joint is out of range"):
+        self.message = message
+        super().__init__(self.message)
+
+
+class PortHandler(Protocol):
+    def __init__(self, port_name):
+        self.is_open: bool
+        self.baudrate: int
+        self.packet_start_time: float
+        self.packet_timeout: float
+        self.tx_time_per_byte: float
+        self.is_using: bool
+        self.port_name: str
+        self.ser: object
+
+    def openPort(self): ...
+    def closePort(self): ...
+    def clearPort(self): ...
+    def setPortName(self, port_name): ...
+    def getPortName(self): ...
+    def setBaudRate(self, baudrate): ...
+    def getBaudRate(self): ...
+    def getBytesAvailable(self): ...
+    def readPort(self, length): ...
+    def writePort(self, packet): ...
+    def setPacketTimeout(self, packet_length): ...
+    def setPacketTimeoutMillis(self, msec): ...
+    def isPacketTimeout(self): ...
+    def getCurrentTime(self): ...
+    def getTimeSinceStart(self): ...
+    def setupPort(self, cflag_baud): ...
+    def getCFlagBaud(self, baudrate): ...
+
+
+class PacketHandler(Protocol):
+    def getTxRxResult(self, result): ...
+    def getRxPacketError(self, error): ...
+    def txPacket(self, port, txpacket): ...
+    def rxPacket(self, port): ...
+    def txRxPacket(self, port, txpacket): ...
+    def ping(self, port, id): ...
+    def action(self, port, id): ...
+    def readTx(self, port, id, address, length): ...
+    def readRx(self, port, id, length): ...
+    def readTxRx(self, port, id, address, length): ...
+    def read1ByteTx(self, port, id, address): ...
+    def read1ByteRx(self, port, id): ...
+    def read1ByteTxRx(self, port, id, address): ...
+    def read2ByteTx(self, port, id, address): ...
+    def read2ByteRx(self, port, id): ...
+    def read2ByteTxRx(self, port, id, address): ...
+    def read4ByteTx(self, port, id, address): ...
+    def read4ByteRx(self, port, id): ...
+    def read4ByteTxRx(self, port, id, address): ...
+    def writeTxOnly(self, port, id, address, length, data): ...
+    def writeTxRx(self, port, id, address, length, data): ...
+    def write1ByteTxOnly(self, port, id, address, data): ...
+    def write1ByteTxRx(self, port, id, address, data): ...
+    def write2ByteTxOnly(self, port, id, address, data): ...
+    def write2ByteTxRx(self, port, id, address, data): ...
+    def write4ByteTxOnly(self, port, id, address, data): ...
+    def write4ByteTxRx(self, port, id, address, data): ...
+    def regWriteTxOnly(self, port, id, address, length, data): ...
+    def regWriteTxRx(self, port, id, address, length, data): ...
+    def syncReadTx(self, port, start_address, data_length, param, param_length): ...
+    def syncWriteTxOnly(self, port, start_address, data_length, param, param_length): ...
 
 
 class MotorsBus(abc.ABC):
     """The main LeRobot class for implementing motors buses."""
 
+    model_ctrl_table: dict[str, dict]
+    model_resolution_table: dict[str, int]
+
     def __init__(
         self,
+        port: str,
         motors: dict[str, tuple[int, str]],
     ):
+        self.port = port
         self.motors = motors
+        self.port_handler: PortHandler | None = None
+        self.packet_handler: PacketHandler | None = None
+
+        self.group_readers = {}
+        self.group_writers = {}
+        self.logs = {}
+
+        self.calibration = None
+        self.is_connected: bool = False
 
     def __len__(self):
         return len(self.motors)
 
-    @abc.abstractmethod
+    @property
+    def motor_names(self) -> list[str]:
+        return list(self.motors)
+
+    @property
+    def motor_models(self) -> list[str]:
+        return [model for _, model in self.motors.values()]
+
+    @property
+    def motor_indices(self) -> list[int]:
+        return [idx for idx, _ in self.motors.values()]
+
     def connect(self):
+        if self.is_connected:
+            raise DeviceAlreadyConnectedError(
+                f"{self.__name__}({self.port}) is already connected. Do not call `{self.__name__}.connect()` twice."
+            )
+
+        self._set_handlers()
+
+        try:
+            if not self.port_handler.openPort():
+                raise OSError(f"Failed to open port '{self.port}'.")
+        except Exception:
+            traceback.print_exc()
+            print(
+                "\nTry running `python lerobot/scripts/find_motors_bus_port.py` to make sure you are using the correct port.\n"
+            )
+            raise
+
+        self._set_timeout()
+
+        # Allow to read and write
+        self.is_connected = True
+
+    @abc.abstractmethod
+    def _set_handlers(self):
         pass
 
     @abc.abstractmethod
-    def reconnect(self):
+    def _set_timeout(self, timeout: int):
         pass
 
-    @abc.abstractmethod
-    def set_calibration(self, calibration: dict[str, list]):
-        pass
+    def are_motors_configured(self):
+        """
+        Only check the motor indices and not baudrate, since if the motor baudrates are incorrect, a
+        ConnectionError will be raised anyway.
+        """
+        try:
+            return (self.motor_indices == self.read("ID")).all()
+        except ConnectionError as e:
+            print(e)
+            return False
+
+    def find_motor_indices(self, possible_ids: list[str] = None, num_retry: int = 2):
+        if possible_ids is None:
+            possible_ids = range(MAX_ID_RANGE)
+
+        indices = []
+        for idx in tqdm.tqdm(possible_ids):
+            try:
+                present_idx = self.read_with_motor_ids(self.motor_models, [idx], "ID", num_retry=num_retry)[0]
+            except ConnectionError:
+                continue
+
+            if idx != present_idx:
+                # sanity check
+                raise OSError(
+                    "Motor index used to communicate through the bus is not the same as the one present in the motor memory. The motor memory might be damaged."
+                )
+            indices.append(idx)
+
+        return indices
+
+    def set_baudrate(self, baudrate):
+        present_bus_baudrate = self.port_handler.getBaudRate()
+        if present_bus_baudrate != baudrate:
+            print(f"Setting bus baud rate to {baudrate}. Previously {present_bus_baudrate}.")
+            self.port_handler.setBaudRate(baudrate)
+
+            if self.port_handler.getBaudRate() != baudrate:
+                raise OSError("Failed to write bus baud rate.")
+
+    def set_calibration(self, calibration_dict: dict[str, list]):
+        self.calibration = calibration_dict
 
     @abc.abstractmethod
     def apply_calibration(self):
@@ -33,14 +283,84 @@ class MotorsBus(abc.ABC):
     def revert_calibration(self):
         pass
 
-    @abc.abstractmethod
-    def read(self):
-        pass
+    def read(self, data_name, motor_names: str | list[str] | None = None):
+        if not self.is_connected:
+            raise DeviceNotConnectedError(
+                f"{self.__name__}({self.port}) is not connected. You need to run `{self.__name__}.connect()`."
+            )
+
+        start_time = time.perf_counter()
+        if motor_names is None:
+            motor_names = self.motor_names
+
+        if isinstance(motor_names, str):
+            motor_names = [motor_names]
+
+        values = self._read(data_name, motor_names)
+
+        # log the number of seconds it took to read the data from the motors
+        delta_ts_name = get_log_name("delta_timestamp_s", "read", data_name, motor_names)
+        self.logs[delta_ts_name] = time.perf_counter() - start_time
+
+        # log the utc time at which the data was received
+        ts_utc_name = get_log_name("timestamp_utc", "read", data_name, motor_names)
+        self.logs[ts_utc_name] = capture_timestamp_utc()
+
+        return values
 
     @abc.abstractmethod
-    def write(self):
+    def _read(self, data_name, motor_names: str | list[str] | None = None):
         pass
 
+    def write(
+        self, data_name: str, values: int | float | np.ndarray, motor_names: str | list[str] | None = None
+    ):
+        if not self.is_connected:
+            raise DeviceNotConnectedError(
+                f"{self.__name__}({self.port}) is not connected. You need to run `{self.__name__}.connect()`."
+            )
+
+        start_time = time.perf_counter()
+
+        if motor_names is None:
+            motor_names = self.motor_names
+
+        if isinstance(motor_names, str):
+            motor_names = [motor_names]
+
+        if isinstance(values, (int, float, np.integer)):
+            values = [int(values)] * len(motor_names)
+
+        self._write(data_name, values, motor_names)
+
+        # log the number of seconds it took to write the data to the motors
+        delta_ts_name = get_log_name("delta_timestamp_s", "write", data_name, motor_names)
+        self.logs[delta_ts_name] = time.perf_counter() - start_time
+
+        # TODO(rcadene): should we log the time before sending the write command?
+        # log the utc time when the write has been completed
+        ts_utc_name = get_log_name("timestamp_utc", "write", data_name, motor_names)
+        self.logs[ts_utc_name] = capture_timestamp_utc()
+
     @abc.abstractmethod
+    def _write(self, data_name: str, values: list[int], motor_names: list[str]) -> None:
+        pass
+
     def disconnect(self):
-        pass
+        if not self.is_connected:
+            raise DeviceNotConnectedError(
+                f"{self.__name__}({self.port}) is not connected. Try running `{self.__name__}.connect()` first."
+            )
+
+        if self.port_handler is not None:
+            self.port_handler.closePort()
+            self.port_handler = None
+
+        self.packet_handler = None
+        self.group_readers = {}
+        self.group_writers = {}
+        self.is_connected = False
+
+    def __del__(self):
+        if self.is_connected:
+            self.disconnect()

From e33ca2c98074e103447ed4fc23f03dc7e42bd9dd Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sat, 15 Mar 2025 13:10:57 +0100
Subject: [PATCH 036/171] Fix TorqueMode imports

---
 lerobot/common/motors/__init__.py                    | 4 ++--
 lerobot/common/motors/dynamixel/__init__.py          | 4 ++--
 lerobot/common/motors/feetech/__init__.py            | 3 +--
 lerobot/common/motors/feetech/feetech_calibration.py | 3 +--
 lerobot/common/robots/koch/robot_koch.py             | 2 +-
 lerobot/common/robots/moss/robot_moss.py             | 2 +-
 lerobot/common/robots/so100/robot_so100.py           | 2 +-
 lerobot/common/robots/viperx/robot_viperx.py         | 2 +-
 lerobot/common/teleoperators/koch/teleop_koch.py     | 2 +-
 lerobot/common/teleoperators/so100/teleop_so100.py   | 2 +-
 lerobot/common/teleoperators/widowx/teleop_widowx.py | 2 +-
 11 files changed, 13 insertions(+), 15 deletions(-)

diff --git a/lerobot/common/motors/__init__.py b/lerobot/common/motors/__init__.py
index 6c8699a1..a746ba96 100644
--- a/lerobot/common/motors/__init__.py
+++ b/lerobot/common/motors/__init__.py
@@ -1,3 +1,3 @@
-from .motors_bus import MotorsBus
+from .motors_bus import CalibrationMode, DriveMode, MotorsBus, TorqueMode
 
-__all__ = ["MotorsBus"]
+__all__ = ["CalibrationMode", "DriveMode", "MotorsBus", "TorqueMode"]
diff --git a/lerobot/common/motors/dynamixel/__init__.py b/lerobot/common/motors/dynamixel/__init__.py
index fbe65a27..77c4bd00 100644
--- a/lerobot/common/motors/dynamixel/__init__.py
+++ b/lerobot/common/motors/dynamixel/__init__.py
@@ -1,4 +1,4 @@
-from .dynamixel import DynamixelMotorsBus, TorqueMode, set_operating_mode
+from .dynamixel import DynamixelMotorsBus, set_operating_mode
 from .dynamixel_calibration import run_arm_calibration
 
-__all__ = ["DynamixelMotorsBus", "TorqueMode", "set_operating_mode", "run_arm_calibration"]
+__all__ = ["DynamixelMotorsBus", "set_operating_mode", "run_arm_calibration"]
diff --git a/lerobot/common/motors/feetech/__init__.py b/lerobot/common/motors/feetech/__init__.py
index a0c15dbf..0134b92d 100644
--- a/lerobot/common/motors/feetech/__init__.py
+++ b/lerobot/common/motors/feetech/__init__.py
@@ -1,9 +1,8 @@
-from .feetech import FeetechMotorsBus, TorqueMode
+from .feetech import FeetechMotorsBus
 from .feetech_calibration import apply_feetech_offsets_from_calibration, run_full_arm_calibration
 
 __all__ = [
     "FeetechMotorsBus",
-    "TorqueMode",
     "apply_feetech_offsets_from_calibration",
     "run_full_arm_calibration",
 ]
diff --git a/lerobot/common/motors/feetech/feetech_calibration.py b/lerobot/common/motors/feetech/feetech_calibration.py
index 262a5b6e..de4ed83f 100644
--- a/lerobot/common/motors/feetech/feetech_calibration.py
+++ b/lerobot/common/motors/feetech/feetech_calibration.py
@@ -13,11 +13,10 @@
 # limitations under the License.
 import numpy as np
 
-from ..motors_bus import MotorsBus
+from ..motors_bus import MotorsBus, TorqueMode
 from .feetech import (
     CalibrationMode,
     FeetechMotorsBus,
-    TorqueMode,
 )
 
 URL_TEMPLATE = (
diff --git a/lerobot/common/robots/koch/robot_koch.py b/lerobot/common/robots/koch/robot_koch.py
index 3c34bd7b..67008f5f 100644
--- a/lerobot/common/robots/koch/robot_koch.py
+++ b/lerobot/common/robots/koch/robot_koch.py
@@ -23,9 +23,9 @@ 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 import TorqueMode
 from lerobot.common.motors.dynamixel import (
     DynamixelMotorsBus,
-    TorqueMode,
     run_arm_calibration,
     set_operating_mode,
 )
diff --git a/lerobot/common/robots/moss/robot_moss.py b/lerobot/common/robots/moss/robot_moss.py
index bc6fd2b1..0f7e5e77 100644
--- a/lerobot/common/robots/moss/robot_moss.py
+++ b/lerobot/common/robots/moss/robot_moss.py
@@ -23,9 +23,9 @@ 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 import TorqueMode
 from lerobot.common.motors.feetech import (
     FeetechMotorsBus,
-    TorqueMode,
     apply_feetech_offsets_from_calibration,
     run_full_arm_calibration,
 )
diff --git a/lerobot/common/robots/so100/robot_so100.py b/lerobot/common/robots/so100/robot_so100.py
index 3bef7042..13229709 100644
--- a/lerobot/common/robots/so100/robot_so100.py
+++ b/lerobot/common/robots/so100/robot_so100.py
@@ -23,9 +23,9 @@ 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 import TorqueMode
 from lerobot.common.motors.feetech import (
     FeetechMotorsBus,
-    TorqueMode,
     apply_feetech_offsets_from_calibration,
     run_full_arm_calibration,
 )
diff --git a/lerobot/common/robots/viperx/robot_viperx.py b/lerobot/common/robots/viperx/robot_viperx.py
index 058ac0ff..7dbc8d34 100644
--- a/lerobot/common/robots/viperx/robot_viperx.py
+++ b/lerobot/common/robots/viperx/robot_viperx.py
@@ -13,9 +13,9 @@ 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 import TorqueMode
 from lerobot.common.motors.dynamixel import (
     DynamixelMotorsBus,
-    TorqueMode,
     run_arm_calibration,
 )
 
diff --git a/lerobot/common/teleoperators/koch/teleop_koch.py b/lerobot/common/teleoperators/koch/teleop_koch.py
index e5c3fc92..ad9745d5 100644
--- a/lerobot/common/teleoperators/koch/teleop_koch.py
+++ b/lerobot/common/teleoperators/koch/teleop_koch.py
@@ -21,9 +21,9 @@ import time
 import numpy as np
 
 from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError
+from lerobot.common.motors import TorqueMode
 from lerobot.common.motors.dynamixel import (
     DynamixelMotorsBus,
-    TorqueMode,
     run_arm_calibration,
     set_operating_mode,
 )
diff --git a/lerobot/common/teleoperators/so100/teleop_so100.py b/lerobot/common/teleoperators/so100/teleop_so100.py
index 13c928c3..90af62a8 100644
--- a/lerobot/common/teleoperators/so100/teleop_so100.py
+++ b/lerobot/common/teleoperators/so100/teleop_so100.py
@@ -21,9 +21,9 @@ import time
 import numpy as np
 
 from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError
+from lerobot.common.motors import TorqueMode
 from lerobot.common.motors.feetech import (
     FeetechMotorsBus,
-    TorqueMode,
     apply_feetech_offsets_from_calibration,
     run_full_arm_calibration,
 )
diff --git a/lerobot/common/teleoperators/widowx/teleop_widowx.py b/lerobot/common/teleoperators/widowx/teleop_widowx.py
index fbb658e7..a661b003 100644
--- a/lerobot/common/teleoperators/widowx/teleop_widowx.py
+++ b/lerobot/common/teleoperators/widowx/teleop_widowx.py
@@ -21,9 +21,9 @@ import time
 import numpy as np
 
 from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError
+from lerobot.common.motors import TorqueMode
 from lerobot.common.motors.dynamixel import (
     DynamixelMotorsBus,
-    TorqueMode,
     run_arm_calibration,
 )
 

From ad0bacbfe4a2d969609505d7eb72bced5c7bd5e8 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sat, 15 Mar 2025 13:11:56 +0100
Subject: [PATCH 037/171] Ass model_baudrate_table

---
 lerobot/common/motors/dynamixel/dynamixel.py | 3 ++-
 lerobot/common/motors/feetech/feetech.py     | 3 ++-
 lerobot/common/motors/motors_bus.py          | 1 +
 3 files changed, 5 insertions(+), 2 deletions(-)

diff --git a/lerobot/common/motors/dynamixel/dynamixel.py b/lerobot/common/motors/dynamixel/dynamixel.py
index bced8775..5208389d 100644
--- a/lerobot/common/motors/dynamixel/dynamixel.py
+++ b/lerobot/common/motors/dynamixel/dynamixel.py
@@ -244,7 +244,8 @@ class DynamixelMotorsBus(MotorsBus):
     """
 
     model_ctrl_table = deepcopy(MODEL_CONTROL_TABLE)
-    model_resolution = deepcopy(MODEL_RESOLUTION)
+    model_resolution_table = deepcopy(MODEL_RESOLUTION)
+    model_baudrate_table = deepcopy(MODEL_BAUDRATE_TABLE)
 
     def __init__(
         self,
diff --git a/lerobot/common/motors/feetech/feetech.py b/lerobot/common/motors/feetech/feetech.py
index 450d3efc..c62f63d6 100644
--- a/lerobot/common/motors/feetech/feetech.py
+++ b/lerobot/common/motors/feetech/feetech.py
@@ -257,7 +257,8 @@ class FeetechMotorsBus(MotorsBus):
     """
 
     model_ctrl_table = deepcopy(MODEL_CONTROL_TABLE)
-    model_resolution = deepcopy(MODEL_RESOLUTION)
+    model_resolution_table = deepcopy(MODEL_RESOLUTION)
+    model_baudrate_table = deepcopy(MODEL_BAUDRATE_TABLE)
 
     def __init__(
         self,
diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py
index a6a9297e..0a5396d7 100644
--- a/lerobot/common/motors/motors_bus.py
+++ b/lerobot/common/motors/motors_bus.py
@@ -168,6 +168,7 @@ class MotorsBus(abc.ABC):
 
     model_ctrl_table: dict[str, dict]
     model_resolution_table: dict[str, int]
+    model_baudrate_table: dict[str, dict]
 
     def __init__(
         self,

From 5006da72ff852eb53524353490cb33a5a86c4820 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sat, 15 Mar 2025 13:13:26 +0100
Subject: [PATCH 038/171] Update configure_motor script

---
 lerobot/scripts/configure_motor.py | 95 ++++++++++--------------------
 1 file changed, 30 insertions(+), 65 deletions(-)

diff --git a/lerobot/scripts/configure_motor.py b/lerobot/scripts/configure_motor.py
index 6569db19..617db2fc 100644
--- a/lerobot/scripts/configure_motor.py
+++ b/lerobot/scripts/configure_motor.py
@@ -28,71 +28,31 @@ python lerobot/scripts/configure_motor.py \
 import argparse
 import time
 
+from lerobot.common.motors.dynamixel.dynamixel import MODEL_RESOLUTION as DXL_MODEL_RESOLUTION
+from lerobot.common.motors.feetech.feetech import MODEL_RESOLUTION as FTCH_MODEL_RESOLUTION
 
-def get_motor_bus_cls(brand: str) -> tuple:
+
+def configure_motor(port, brand, model, target_motor_idx, target_baudrate):
     if brand == "feetech":
-        from lerobot.common.motors.configs import FeetechMotorsBusConfig
-        from lerobot.common.motors.feetech.feetech import (
-            MODEL_BAUDRATE_TABLE,
-            SCS_SERIES_BAUDRATE_TABLE,
-            FeetechMotorsBus,
-        )
+        from lerobot.common.motors.feetech.feetech import FeetechMotorsBus
 
-        return FeetechMotorsBusConfig, FeetechMotorsBus, MODEL_BAUDRATE_TABLE, SCS_SERIES_BAUDRATE_TABLE
+        motor_bus = FeetechMotorsBus(port=port, motors={"motor": (target_motor_idx, model)})
 
     elif brand == "dynamixel":
-        from lerobot.common.motors.configs import DynamixelMotorsBusConfig
-        from lerobot.common.motors.dynamixel.dynamixel import (
-            MODEL_BAUDRATE_TABLE,
-            X_SERIES_BAUDRATE_TABLE,
-            DynamixelMotorsBus,
-        )
+        from lerobot.common.motors.dynamixel.dynamixel import DynamixelMotorsBus
 
-        return DynamixelMotorsBusConfig, DynamixelMotorsBus, MODEL_BAUDRATE_TABLE, X_SERIES_BAUDRATE_TABLE
+        motor_bus = DynamixelMotorsBus(port=port, motors={"motor": (target_motor_idx, model)})
 
-    else:
-        raise ValueError(
-            f"Currently we do not support this motor brand: {brand}. We currently support feetech and dynamixel motors."
-        )
-
-
-def configure_motor(port, brand, model, motor_idx_des, baudrate_des):
-    motor_bus_config_cls, motor_bus_cls, model_baudrate_table, series_baudrate_table = get_motor_bus_cls(
-        brand
-    )
-
-    # Check if the provided model exists in the model_baud_rate_table
-    if model not in model_baudrate_table:
-        raise ValueError(
-            f"Invalid model '{model}' for brand '{brand}'. Supported models: {list(model_baudrate_table.keys())}"
-        )
-
-    # Setup motor names, indices, and models
-    motor_name = "motor"
-    motor_index_arbitrary = motor_idx_des  # Use the motor ID passed via argument
-    motor_model = model  # Use the motor model passed via argument
-
-    config = motor_bus_config_cls(port=port, motors={motor_name: (motor_index_arbitrary, motor_model)})
-
-    # Initialize the MotorBus with the correct port and motor configurations
-    motor_bus = motor_bus_cls(config=config)
-
-    # Try to connect to the motor bus and handle any connection-specific errors
-    try:
-        motor_bus.connect()
-        print(f"Connected on port {motor_bus.port}")
-    except OSError as e:
-        print(f"Error occurred when connecting to the motor bus: {e}")
-        return
+    motor_bus.connect()
 
     # Motor bus is connected, proceed with the rest of the operations
     try:
         print("Scanning all baudrates and motor indices")
-        all_baudrates = set(series_baudrate_table.values())
+        model_baudrates = list(motor_bus.model_baudrate_table[model].values())
         motor_index = -1  # Set the motor index to an out-of-range value.
 
-        for baudrate in all_baudrates:
-            motor_bus.set_bus_baudrate(baudrate)
+        for baudrate in model_baudrates:
+            motor_bus.set_baudrate(baudrate)
             present_ids = motor_bus.find_motor_indices(list(range(1, 10)))
             if len(present_ids) > 1:
                 raise ValueError(
@@ -116,14 +76,14 @@ def configure_motor(port, brand, model, motor_idx_des, baudrate_des):
             # Allows ID and BAUDRATE to be written in memory
             motor_bus.write_with_motor_ids(motor_bus.motor_models, motor_index, "Lock", 0)
 
-        if baudrate != baudrate_des:
-            print(f"Setting its baudrate to {baudrate_des}")
-            baudrate_idx = list(series_baudrate_table.values()).index(baudrate_des)
+        if baudrate != target_baudrate:
+            print(f"Setting its baudrate to {target_baudrate}")
+            baudrate_idx = model_baudrates.index(target_baudrate)
 
             # The write can fail, so we allow retries
             motor_bus.write_with_motor_ids(motor_bus.motor_models, motor_index, "Baud_Rate", baudrate_idx)
             time.sleep(0.5)
-            motor_bus.set_bus_baudrate(baudrate_des)
+            motor_bus.set_bus_baudrate(target_baudrate)
             present_baudrate_idx = motor_bus.read_with_motor_ids(
                 motor_bus.motor_models, motor_index, "Baud_Rate", num_retry=2
             )
@@ -131,13 +91,15 @@ def configure_motor(port, brand, model, motor_idx_des, baudrate_des):
             if present_baudrate_idx != baudrate_idx:
                 raise OSError("Failed to write baudrate.")
 
-        print(f"Setting its index to desired index {motor_idx_des}")
+        print(f"Setting its index to desired index {target_motor_idx}")
         if brand == "feetech":
             motor_bus.write_with_motor_ids(motor_bus.motor_models, motor_index, "Lock", 0)
-        motor_bus.write_with_motor_ids(motor_bus.motor_models, motor_index, "ID", motor_idx_des)
+        motor_bus.write_with_motor_ids(motor_bus.motor_models, motor_index, "ID", target_motor_idx)
 
-        present_idx = motor_bus.read_with_motor_ids(motor_bus.motor_models, motor_idx_des, "ID", num_retry=2)
-        if present_idx != motor_idx_des:
+        present_idx = motor_bus.read_with_motor_ids(
+            motor_bus.motor_models, target_motor_idx, "ID", num_retry=2
+        )
+        if present_idx != target_motor_idx:
             raise OSError("Failed to write index.")
 
         if brand == "feetech":
@@ -157,18 +119,21 @@ def configure_motor(port, brand, model, motor_idx_des, baudrate_des):
         print(f"Error occurred during motor configuration: {e}")
 
     finally:
-        motor_bus.disconnect()
+        if motor_bus.is_connected:
+            motor_bus.disconnect()
         print("Disconnected from motor bus.")
 
 
 if __name__ == "__main__":
+    model_choices = [*FTCH_MODEL_RESOLUTION.keys(), *DXL_MODEL_RESOLUTION.keys()]
+    brand_choices = ["feetech", "dynamixel"]
     parser = argparse.ArgumentParser()
-    parser.add_argument("--port", type=str, required=True, help="Motors bus port (e.g. dynamixel,feetech)")
-    parser.add_argument("--brand", type=str, required=True, help="Motor brand (e.g. dynamixel,feetech)")
-    parser.add_argument("--model", type=str, required=True, help="Motor model (e.g. xl330-m077,sts3215)")
+    parser.add_argument("--port", type=str, required=True, help="Motors bus port")
+    parser.add_argument("--brand", type=str, required=True, choices=brand_choices, help="Motor brand")
+    parser.add_argument("--model", type=str, required=True, choices=model_choices, help="Motor model")
     parser.add_argument("--ID", type=int, required=True, help="Desired ID of the current motor (e.g. 1,2,3)")
     parser.add_argument(
-        "--baudrate", type=int, default=1000000, help="Desired baudrate for the motor (default: 1000000)"
+        "--baudrate", type=int, default=1_000_000, help="Desired baudrate for the motor (default: 1_000_000)"
     )
     args = parser.parse_args()
 

From 2037cc0219a39737990a83cdf8875b7ce43c847a Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sat, 15 Mar 2025 13:14:05 +0100
Subject: [PATCH 039/171] Rename ID -> id

---
 examples/7_get_started_with_real_robot.md | 4 ++--
 lerobot/common/robots/moss/README.md      | 4 ++--
 lerobot/common/robots/so100/README.md     | 4 ++--
 lerobot/scripts/configure_motor.py        | 6 +++---
 4 files changed, 9 insertions(+), 9 deletions(-)

diff --git a/examples/7_get_started_with_real_robot.md b/examples/7_get_started_with_real_robot.md
index 894c44a3..59accd7f 100644
--- a/examples/7_get_started_with_real_robot.md
+++ b/examples/7_get_started_with_real_robot.md
@@ -87,7 +87,7 @@ python lerobot/scripts/configure_motor.py \
   --brand dynamixel \
   --model xl330-m288 \
   --baudrate 1000000 \
-  --ID 1
+  --id 1
 ```
 
 Then unplug your first motor and plug the second motor and set its ID to 2.
@@ -97,7 +97,7 @@ python lerobot/scripts/configure_motor.py \
   --brand dynamixel \
   --model xl330-m288 \
   --baudrate 1000000 \
-  --ID 2
+  --id 2
 ```
 
 Redo the process for all your motors until ID 6.
diff --git a/lerobot/common/robots/moss/README.md b/lerobot/common/robots/moss/README.md
index d2e02076..de7dd156 100644
--- a/lerobot/common/robots/moss/README.md
+++ b/lerobot/common/robots/moss/README.md
@@ -139,7 +139,7 @@ python lerobot/scripts/configure_motor.py \
   --brand feetech \
   --model sts3215 \
   --baudrate 1000000 \
-  --ID 1
+  --id 1
 ```
 
 Note: These motors are currently limitated. They can take values between 0 and 4096 only, which corresponds to a full turn. They can't turn more than that. 2048 is at the middle of this range, so we can take -2048 steps (180 degrees anticlockwise) and reach the maximum range, or take +2048 steps (180 degrees clockwise) and reach the maximum range. The configuration step also sets the homing offset to 0, so that if you misassembled the arm, you can always update the homing offset to account for a shift up to ± 2048 steps (± 180 degrees).
@@ -151,7 +151,7 @@ python lerobot/scripts/configure_motor.py \
   --brand feetech \
   --model sts3215 \
   --baudrate 1000000 \
-  --ID 2
+  --id 2
 ```
 
 Redo the process for all your motors until ID 6. Do the same for the 6 motors of the leader arm.
diff --git a/lerobot/common/robots/so100/README.md b/lerobot/common/robots/so100/README.md
index b8b45aa5..297667df 100644
--- a/lerobot/common/robots/so100/README.md
+++ b/lerobot/common/robots/so100/README.md
@@ -191,7 +191,7 @@ python lerobot/scripts/configure_motor.py \
   --brand feetech \
   --model sts3215 \
   --baudrate 1000000 \
-  --ID 1
+  --id 1
 ```
 
 > [!NOTE]
@@ -204,7 +204,7 @@ python lerobot/scripts/configure_motor.py \
   --brand feetech \
   --model sts3215 \
   --baudrate 1000000 \
-  --ID 2
+  --id 2
 ```
 
 Redo the process for all your motors until ID 6. Do the same for the 6 motors of the leader arm.
diff --git a/lerobot/scripts/configure_motor.py b/lerobot/scripts/configure_motor.py
index 617db2fc..b434fed6 100644
--- a/lerobot/scripts/configure_motor.py
+++ b/lerobot/scripts/configure_motor.py
@@ -21,7 +21,7 @@ python lerobot/scripts/configure_motor.py \
   --brand feetech \
   --model sts3215 \
   --baudrate 1000000 \
-  --ID 1
+  --id 1
 ```
 """
 
@@ -131,10 +131,10 @@ if __name__ == "__main__":
     parser.add_argument("--port", type=str, required=True, help="Motors bus port")
     parser.add_argument("--brand", type=str, required=True, choices=brand_choices, help="Motor brand")
     parser.add_argument("--model", type=str, required=True, choices=model_choices, help="Motor model")
-    parser.add_argument("--ID", type=int, required=True, help="Desired ID of the current motor (e.g. 1,2,3)")
+    parser.add_argument("--id", type=int, required=True, help="Desired ID of the current motor (e.g. 1,2,3)")
     parser.add_argument(
         "--baudrate", type=int, default=1_000_000, help="Desired baudrate for the motor (default: 1_000_000)"
     )
     args = parser.parse_args()
 
-    configure_motor(args.port, args.brand, args.model, args.ID, args.baudrate)
+    configure_motor(args.port, args.brand, args.model, args.id, args.baudrate)

From fa8ba9e4e228bc83ee3f48c3a4a0bb59928215ec Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sat, 15 Mar 2025 13:14:29 +0100
Subject: [PATCH 040/171] Rename set_operating_mode arg

---
 lerobot/common/motors/dynamixel/dynamixel.py | 10 +++++-----
 1 file changed, 5 insertions(+), 5 deletions(-)

diff --git a/lerobot/common/motors/dynamixel/dynamixel.py b/lerobot/common/motors/dynamixel/dynamixel.py
index 5208389d..b3e11053 100644
--- a/lerobot/common/motors/dynamixel/dynamixel.py
+++ b/lerobot/common/motors/dynamixel/dynamixel.py
@@ -625,18 +625,18 @@ class DynamixelMotorsBus(MotorsBus):
             )
 
 
-def set_operating_mode(arm: DynamixelMotorsBus):
-    if (arm.read("Torque_Enable") != TorqueMode.DISABLED.value).any():
+def set_operating_mode(bus: DynamixelMotorsBus):
+    if (bus.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"]
+    all_motors_except_gripper = [name for name in bus.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)
+        bus.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,
@@ -644,4 +644,4 @@ def set_operating_mode(arm: DynamixelMotorsBus):
     # 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")
+    bus.write("Operating_Mode", 5, "gripper")

From 0f972661e16f4ca0b43d21daa94c0c816215acbb Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sat, 15 Mar 2025 19:22:12 +0100
Subject: [PATCH 041/171] Move imports & remove mock entirely

---
 lerobot/common/motors/dynamixel/dynamixel.py | 28 ++++++++++++--------
 lerobot/common/motors/feetech/feetech.py     | 28 ++++++++++++--------
 2 files changed, 34 insertions(+), 22 deletions(-)

diff --git a/lerobot/common/motors/dynamixel/dynamixel.py b/lerobot/common/motors/dynamixel/dynamixel.py
index b3e11053..b0f9556f 100644
--- a/lerobot/common/motors/dynamixel/dynamixel.py
+++ b/lerobot/common/motors/dynamixel/dynamixel.py
@@ -16,7 +16,6 @@ import logging
 import math
 from copy import deepcopy
 
-import dynamixel_sdk as dxl
 import numpy as np
 
 from ..motors_bus import (
@@ -172,24 +171,21 @@ def convert_degrees_to_steps(degrees: float | np.ndarray, models: str | list[str
     return steps
 
 
-def convert_to_bytes(value, bytes, mock=False):
-    if mock:
-        return value
-
+def convert_to_bytes(value, n_bytes: int):
     import dynamixel_sdk as dxl
 
     # Note: No need to convert back into unsigned int, since this byte preprocessing
     # already handles it for us.
-    if bytes == 1:
+    if n_bytes == 1:
         data = [
             dxl.DXL_LOBYTE(dxl.DXL_LOWORD(value)),
         ]
-    elif bytes == 2:
+    elif n_bytes == 2:
         data = [
             dxl.DXL_LOBYTE(dxl.DXL_LOWORD(value)),
             dxl.DXL_HIBYTE(dxl.DXL_LOWORD(value)),
         ]
-    elif bytes == 4:
+    elif n_bytes == 4:
         data = [
             dxl.DXL_LOBYTE(dxl.DXL_LOWORD(value)),
             dxl.DXL_HIBYTE(dxl.DXL_LOWORD(value)),
@@ -199,7 +195,7 @@ def convert_to_bytes(value, bytes, mock=False):
     else:
         raise NotImplementedError(
             f"Value of the number of bytes to be sent is expected to be in [1, 2, 4], but "
-            f"{bytes} is provided instead."
+            f"{n_bytes} is provided instead."
         )
     return data
 
@@ -255,6 +251,8 @@ class DynamixelMotorsBus(MotorsBus):
         super().__init__(port, motors)
 
     def _set_handlers(self):
+        import dynamixel_sdk as dxl
+
         self.port_handler = dxl.PortHandler(self.port)
         self.packet_handler = dxl.PacketHandler(PROTOCOL_VERSION)
 
@@ -486,6 +484,8 @@ class DynamixelMotorsBus(MotorsBus):
         return values
 
     def read_with_motor_ids(self, motor_models, motor_ids, data_name, num_retry=NUM_READ_RETRY):
+        import dynamixel_sdk as dxl
+
         return_list = True
         if not isinstance(motor_ids, list):
             return_list = False
@@ -519,6 +519,8 @@ class DynamixelMotorsBus(MotorsBus):
             return values[0]
 
     def _read(self, data_name, motor_names: str | list[str] | None = None):
+        import dynamixel_sdk as dxl
+
         motor_ids = []
         models = []
         for name in motor_names:
@@ -566,6 +568,8 @@ class DynamixelMotorsBus(MotorsBus):
         return values
 
     def write_with_motor_ids(self, motor_models, motor_ids, data_name, values, num_retry=NUM_WRITE_RETRY):
+        import dynamixel_sdk as dxl
+
         if not isinstance(motor_ids, list):
             motor_ids = [motor_ids]
         if not isinstance(values, list):
@@ -575,7 +579,7 @@ class DynamixelMotorsBus(MotorsBus):
         addr, bytes = self.model_ctrl_table[motor_models[0]][data_name]
         group = dxl.GroupSyncWrite(self.port_handler, self.packet_handler, addr, bytes)
         for idx, value in zip(motor_ids, values, strict=True):
-            data = convert_to_bytes(value, bytes, self.mock)
+            data = convert_to_bytes(value, bytes)
             group.addParam(idx, data)
 
         for _ in range(num_retry):
@@ -590,6 +594,8 @@ class DynamixelMotorsBus(MotorsBus):
             )
 
     def _write(self, data_name: str, values: list[int], motor_names: list[str]) -> None:
+        import dynamixel_sdk as dxl
+
         motor_ids = []
         models = []
         for name in motor_names:
@@ -611,7 +617,7 @@ class DynamixelMotorsBus(MotorsBus):
             )
 
         for idx, value in zip(motor_ids, values, strict=True):
-            data = convert_to_bytes(value, bytes, self.mock)
+            data = convert_to_bytes(value, bytes)
             if init_group:
                 self.group_writers[group_key].addParam(idx, data)
             else:
diff --git a/lerobot/common/motors/feetech/feetech.py b/lerobot/common/motors/feetech/feetech.py
index c62f63d6..a0bcc083 100644
--- a/lerobot/common/motors/feetech/feetech.py
+++ b/lerobot/common/motors/feetech/feetech.py
@@ -15,7 +15,6 @@
 from copy import deepcopy
 
 import numpy as np
-import scservo_sdk as scs
 
 from ..motors_bus import (
     CalibrationMode,
@@ -185,24 +184,21 @@ def adjusted_to_motor_ticks(adjusted_pos: int, model: str, motorbus, motor_id: i
     return ticks
 
 
-def convert_to_bytes(value, bytes, mock=False):
-    if mock:
-        return value
-
+def convert_to_bytes(value, n_bytes: int):
     import scservo_sdk as scs
 
     # Note: No need to convert back into unsigned int, since this byte preprocessing
     # already handles it for us.
-    if bytes == 1:
+    if n_bytes == 1:
         data = [
             scs.SCS_LOBYTE(scs.SCS_LOWORD(value)),
         ]
-    elif bytes == 2:
+    elif n_bytes == 2:
         data = [
             scs.SCS_LOBYTE(scs.SCS_LOWORD(value)),
             scs.SCS_HIBYTE(scs.SCS_LOWORD(value)),
         ]
-    elif bytes == 4:
+    elif n_bytes == 4:
         data = [
             scs.SCS_LOBYTE(scs.SCS_LOWORD(value)),
             scs.SCS_HIBYTE(scs.SCS_LOWORD(value)),
@@ -212,7 +208,7 @@ def convert_to_bytes(value, bytes, mock=False):
     else:
         raise NotImplementedError(
             f"Value of the number of bytes to be sent is expected to be in [1, 2, 4], but "
-            f"{bytes} is provided instead."
+            f"{n_bytes} is provided instead."
         )
     return data
 
@@ -268,6 +264,8 @@ class FeetechMotorsBus(MotorsBus):
         super().__init__(port, motors)
 
     def _set_handlers(self):
+        import scservo_sdk as scs
+
         self.port_handler = scs.PortHandler(self.port)
         self.packet_handler = scs.PacketHandler(PROTOCOL_VERSION)
 
@@ -340,6 +338,8 @@ class FeetechMotorsBus(MotorsBus):
         return values
 
     def read_with_motor_ids(self, motor_models, motor_ids, data_name, num_retry=NUM_READ_RETRY):
+        import scservo_sdk as scs
+
         return_list = True
         if not isinstance(motor_ids, list):
             return_list = False
@@ -373,6 +373,8 @@ class FeetechMotorsBus(MotorsBus):
             return values[0]
 
     def _read(self, data_name, motor_names: str | list[str] | None = None):
+        import scservo_sdk as scs
+
         motor_ids = []
         models = []
         for name in motor_names:
@@ -420,6 +422,8 @@ class FeetechMotorsBus(MotorsBus):
         return values
 
     def write_with_motor_ids(self, motor_models, motor_ids, data_name, values, num_retry=NUM_WRITE_RETRY):
+        import scservo_sdk as scs
+
         if not isinstance(motor_ids, list):
             motor_ids = [motor_ids]
         if not isinstance(values, list):
@@ -429,7 +433,7 @@ class FeetechMotorsBus(MotorsBus):
         addr, bytes = self.model_ctrl_table[motor_models[0]][data_name]
         group = scs.GroupSyncWrite(self.port_handler, self.packet_handler, addr, bytes)
         for idx, value in zip(motor_ids, values, strict=True):
-            data = convert_to_bytes(value, bytes, self.mock)
+            data = convert_to_bytes(value, bytes)
             group.addParam(idx, data)
 
         for _ in range(num_retry):
@@ -444,6 +448,8 @@ class FeetechMotorsBus(MotorsBus):
             )
 
     def _write(self, data_name: str, values: list[int], motor_names: list[str]) -> None:
+        import scservo_sdk as scs
+
         motor_ids = []
         models = []
         for name in motor_names:
@@ -465,7 +471,7 @@ class FeetechMotorsBus(MotorsBus):
             )
 
         for idx, value in zip(motor_ids, values, strict=True):
-            data = convert_to_bytes(value, bytes, self.mock)
+            data = convert_to_bytes(value, bytes)
             if init_group:
                 self.group_writers[group_key].addParam(idx, data)
             else:

From 858678786ab45ad436c21cae9921963542f4a5d5 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sat, 15 Mar 2025 19:22:40 +0100
Subject: [PATCH 042/171] Remove unused functions

---
 lerobot/common/motors/motors_bus.py | 12 ------------
 1 file changed, 12 deletions(-)

diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py
index 0a5396d7..65fe54da 100644
--- a/lerobot/common/motors/motors_bus.py
+++ b/lerobot/common/motors/motors_bus.py
@@ -39,18 +39,6 @@ def get_group_sync_key(data_name: str, motor_names: list[str]):
     return group_key
 
 
-def get_result_name(fn_name: str, data_name: str, motor_names: list[str]):
-    group_key = get_group_sync_key(data_name, motor_names)
-    rslt_name = f"{fn_name}_{group_key}"
-    return rslt_name
-
-
-def get_queue_name(fn_name: str, data_name: str, motor_names: list[str]):
-    group_key = get_group_sync_key(data_name, motor_names)
-    queue_name = f"{fn_name}_{group_key}"
-    return queue_name
-
-
 def get_log_name(var_name: str, fn_name: str, data_name: str, motor_names: list[str]):
     group_key = get_group_sync_key(data_name, motor_names)
     log_name = f"{var_name}_{fn_name}_{group_key}"

From bd5b181dfde6b26f34f9bafc37f988fd06e9c4ec Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sat, 15 Mar 2025 21:33:45 +0100
Subject: [PATCH 043/171] Improve type hints

---
 lerobot/common/motors/dynamixel/dynamixel.py |  2 +-
 lerobot/common/motors/feetech/feetech.py     |  2 +-
 lerobot/common/motors/motors_bus.py          | 29 +++++++++++---------
 3 files changed, 18 insertions(+), 15 deletions(-)

diff --git a/lerobot/common/motors/dynamixel/dynamixel.py b/lerobot/common/motors/dynamixel/dynamixel.py
index b0f9556f..8f780de0 100644
--- a/lerobot/common/motors/dynamixel/dynamixel.py
+++ b/lerobot/common/motors/dynamixel/dynamixel.py
@@ -518,7 +518,7 @@ class DynamixelMotorsBus(MotorsBus):
         else:
             return values[0]
 
-    def _read(self, data_name, motor_names: str | list[str] | None = None):
+    def _read(self, data_name: str, motor_names: list[str]):
         import dynamixel_sdk as dxl
 
         motor_ids = []
diff --git a/lerobot/common/motors/feetech/feetech.py b/lerobot/common/motors/feetech/feetech.py
index a0bcc083..3b4d4e84 100644
--- a/lerobot/common/motors/feetech/feetech.py
+++ b/lerobot/common/motors/feetech/feetech.py
@@ -372,7 +372,7 @@ class FeetechMotorsBus(MotorsBus):
         else:
             return values[0]
 
-    def _read(self, data_name, motor_names: str | list[str] | None = None):
+    def _read(self, data_name: str, motor_names: list[str]):
         import scservo_sdk as scs
 
         motor_ids = []
diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py
index 65fe54da..e2fdcb73 100644
--- a/lerobot/common/motors/motors_bus.py
+++ b/lerobot/common/motors/motors_bus.py
@@ -20,9 +20,9 @@
 # ruff: noqa: N802
 
 import abc
-import enum
 import time
 import traceback
+from enum import Enum
 from typing import Protocol
 
 import numpy as np
@@ -34,18 +34,18 @@ from lerobot.common.utils.utils import capture_timestamp_utc
 MAX_ID_RANGE = 252
 
 
-def get_group_sync_key(data_name: str, motor_names: list[str]):
+def get_group_sync_key(data_name: str, motor_names: list[str]) -> str:
     group_key = f"{data_name}_" + "_".join(motor_names)
     return group_key
 
 
-def get_log_name(var_name: str, fn_name: str, data_name: str, motor_names: list[str]):
+def get_log_name(var_name: str, fn_name: str, data_name: str, motor_names: list[str]) -> str:
     group_key = get_group_sync_key(data_name, motor_names)
     log_name = f"{var_name}_{fn_name}_{group_key}"
     return log_name
 
 
-def assert_same_address(model_ctrl_table: dict[str, dict], motor_models: list[str], data_name: str):
+def assert_same_address(model_ctrl_table: dict[str, dict], motor_models: list[str], data_name: str) -> None:
     all_addr = []
     all_bytes = []
     for model in motor_models:
@@ -55,26 +55,28 @@ def assert_same_address(model_ctrl_table: dict[str, dict], motor_models: list[st
 
     if len(set(all_addr)) != 1:
         raise NotImplementedError(
-            f"At least two motor models use a different address for `data_name`='{data_name}' ({list(zip(motor_models, all_addr, strict=False))}). Contact a LeRobot maintainer."
+            f"At least two motor models use a different address for `data_name`='{data_name}'"
+            f"({list(zip(motor_models, all_addr, strict=False))}). Contact a LeRobot maintainer."
         )
 
     if len(set(all_bytes)) != 1:
         raise NotImplementedError(
-            f"At least two motor models use a different bytes representation for `data_name`='{data_name}' ({list(zip(motor_models, all_bytes, strict=False))}). Contact a LeRobot maintainer."
+            f"At least two motor models use a different bytes representation for `data_name`='{data_name}'"
+            f"({list(zip(motor_models, all_bytes, strict=False))}). Contact a LeRobot maintainer."
         )
 
 
-class TorqueMode(enum.Enum):
+class TorqueMode(Enum):
     ENABLED = 1
     DISABLED = 0
 
 
-class DriveMode(enum.Enum):
+class DriveMode(Enum):
     NON_INVERTED = 0
     INVERTED = 1
 
 
-class CalibrationMode(enum.Enum):
+class CalibrationMode(Enum):
     # Joints with rotational motions are expressed in degrees in nominal range of [-180, 180]
     DEGREE = 0
     # Joints with liner motions (like gripper of Aloha) are expressed in nominal range of [0, 100]
@@ -246,7 +248,8 @@ class MotorsBus(abc.ABC):
             if idx != present_idx:
                 # sanity check
                 raise OSError(
-                    "Motor index used to communicate through the bus is not the same as the one present in the motor memory. The motor memory might be damaged."
+                    "Motor index used to communicate through the bus is not the same as the one present in the motor "
+                    "memory. The motor memory might be damaged."
                 )
             indices.append(idx)
 
@@ -298,12 +301,12 @@ class MotorsBus(abc.ABC):
         return values
 
     @abc.abstractmethod
-    def _read(self, data_name, motor_names: str | list[str] | None = None):
+    def _read(self, data_name: str, motor_names: list[str]):
         pass
 
     def write(
         self, data_name: str, values: int | float | np.ndarray, motor_names: str | list[str] | None = None
-    ):
+    ) -> None:
         if not self.is_connected:
             raise DeviceNotConnectedError(
                 f"{self.__name__}({self.port}) is not connected. You need to run `{self.__name__}.connect()`."
@@ -335,7 +338,7 @@ class MotorsBus(abc.ABC):
     def _write(self, data_name: str, values: list[int], motor_names: list[str]) -> None:
         pass
 
-    def disconnect(self):
+    def disconnect(self) -> None:
         if not self.is_connected:
             raise DeviceNotConnectedError(
                 f"{self.__name__}({self.port}) is not connected. Try running `{self.__name__}.connect()` first."

From eeeccdba53c9b502963d5f683cc4e6f4f971b196 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sat, 15 Mar 2025 21:42:54 +0100
Subject: [PATCH 044/171] Update docstrings

---
 lerobot/common/motors/dynamixel/dynamixel.py | 38 ++----------------
 lerobot/common/motors/feetech/feetech.py     | 37 +-----------------
 lerobot/common/motors/motors_bus.py          | 41 +++++++++++++++++++-
 3 files changed, 45 insertions(+), 71 deletions(-)

diff --git a/lerobot/common/motors/dynamixel/dynamixel.py b/lerobot/common/motors/dynamixel/dynamixel.py
index 8f780de0..1e223bfa 100644
--- a/lerobot/common/motors/dynamixel/dynamixel.py
+++ b/lerobot/common/motors/dynamixel/dynamixel.py
@@ -202,41 +202,9 @@ def convert_to_bytes(value, n_bytes: int):
 
 class DynamixelMotorsBus(MotorsBus):
     """
-    The DynamixelMotorsBus class allows to efficiently read and write to the attached motors. It relies on
-    the python dynamixel sdk to communicate with the motors. For more info, see the [Dynamixel SDK Documentation](https://emanual.robotis.com/docs/en/software/dynamixel/dynamixel_sdk/sample_code/python_read_write_protocol_2_0/#python-read-write-protocol-20).
-
-    A DynamixelMotorsBus instance requires a port (e.g. `DynamixelMotorsBus(port="/dev/tty.usbmodem575E0031751"`)).
-    To find the port, you can run our utility script:
-    ```bash
-    python lerobot/scripts/find_motors_bus_port.py
-    >>> Finding all available ports for the MotorBus.
-    >>> ['/dev/tty.usbmodem575E0032081', '/dev/tty.usbmodem575E0031751']
-    >>> Remove the usb cable from your DynamixelMotorsBus and press Enter when done.
-    >>> The port of this DynamixelMotorsBus is /dev/tty.usbmodem575E0031751.
-    >>> Reconnect the usb cable.
-    ```
-
-    Example of usage for 1 motor connected to the bus:
-    ```python
-    motor_name = "gripper"
-    motor_index = 6
-    motor_model = "xl330-m288"
-
-    motors_bus = DynamixelMotorsBus(
-        port="/dev/tty.usbmodem575E0031751",
-        motors={motor_name: (motor_index, motor_model)},
-    )
-    motors_bus.connect()
-
-    position = motors_bus.read("Present_Position")
-
-    # move from a few motor steps as an example
-    few_steps = 30
-    motors_bus.write("Goal_Position", position + few_steps)
-
-    # when done, consider disconnecting
-    motors_bus.disconnect()
-    ```
+    The Dynamixel implementation for a MotorsBus. It relies on the python dynamixel sdk to communicate with
+    the motors. For more info, see the Dynamixel SDK Documentation:
+    https://emanual.robotis.com/docs/en/software/dynamixel/dynamixel_sdk/sample_code/python_read_write_protocol_2_0/#python-read-write-protocol-20).
     """
 
     model_ctrl_table = deepcopy(MODEL_CONTROL_TABLE)
diff --git a/lerobot/common/motors/feetech/feetech.py b/lerobot/common/motors/feetech/feetech.py
index 3b4d4e84..1179a4e5 100644
--- a/lerobot/common/motors/feetech/feetech.py
+++ b/lerobot/common/motors/feetech/feetech.py
@@ -215,41 +215,8 @@ def convert_to_bytes(value, n_bytes: int):
 
 class FeetechMotorsBus(MotorsBus):
     """
-    The FeetechMotorsBus class allows to efficiently read and write to the attached motors. It relies on
-    the python feetech sdk to communicate with the motors. For more info, see the [feetech SDK Documentation](https://emanual.robotis.com/docs/en/software/feetech/feetech_sdk/sample_code/python_read_write_protocol_2_0/#python-read-write-protocol-20).
-
-    A FeetechMotorsBus instance requires a port (e.g. `FeetechMotorsBus(port="/dev/tty.usbmodem575E0031751"`)).
-    To find the port, you can run our utility script:
-    ```bash
-    python lerobot/scripts/find_motors_bus_port.py
-    >>> Finding all available ports for the MotorsBus.
-    >>> ['/dev/tty.usbmodem575E0032081', '/dev/tty.usbmodem575E0031751']
-    >>> Remove the usb cable from your FeetechMotorsBus and press Enter when done.
-    >>> The port of this FeetechMotorsBus is /dev/tty.usbmodem575E0031751.
-    >>> Reconnect the usb cable.
-    ```
-
-    Example of usage for 1 motor connected to the bus:
-    ```python
-    motor_name = "gripper"
-    motor_index = 6
-    motor_model = "sts3215"
-
-    motors_bus = FeetechMotorsBus(
-        port="/dev/tty.usbmodem575E0031751",
-        motors={motor_name: (motor_index, motor_model)},
-    )
-    motors_bus.connect()
-
-    position = motors_bus.read("Present_Position")
-
-    # move from a few motor steps as an example
-    few_steps = 30
-    motors_bus.write("Goal_Position", position + few_steps)
-
-    # when done, consider disconnecting
-    motors_bus.disconnect()
-    ```
+    The FeetechMotorsBus class allows to efficiently read and write to the attached motors. It relies on the
+    python feetech sdk to communicate with the motors, which is itself based on the dynamixel sdk.
     """
 
     model_ctrl_table = deepcopy(MODEL_CONTROL_TABLE)
diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py
index e2fdcb73..26ae3836 100644
--- a/lerobot/common/motors/motors_bus.py
+++ b/lerobot/common/motors/motors_bus.py
@@ -154,7 +154,46 @@ class PacketHandler(Protocol):
 
 
 class MotorsBus(abc.ABC):
-    """The main LeRobot class for implementing motors buses."""
+    """The main LeRobot class for implementing motors buses.
+
+    There are currently two implementations of this abstract class:
+        - DynamixelMotorsBus
+        - FeetechMotorsBus
+
+    Note: This class may evolve in the future should we add support for other manufacturers SDKs.
+
+    A MotorsBus allows to efficiently read and write to the attached motors.
+    It represents a several motors daisy-chained together and connected through a serial port.
+
+    A MotorsBus subclass instance requires a port (e.g. `FeetechMotorsBus(port="/dev/tty.usbmodem575E0031751"`)).
+    To find the port, you can run our utility script:
+    ```bash
+    python lerobot/scripts/find_motors_bus_port.py
+    >>> Finding all available ports for the MotorsBus.
+    >>> ['/dev/tty.usbmodem575E0032081', '/dev/tty.usbmodem575E0031751']
+    >>> Remove the usb cable from your MotorsBus and press Enter when done.
+    >>> The port of this MotorsBus is /dev/tty.usbmodem575E0031751.
+    >>> Reconnect the usb cable.
+    ```
+
+    Example of usage for 1 Feetech sts3215 motor connected to the bus:
+    ```python
+    motors_bus = FeetechMotorsBus(
+        port="/dev/tty.usbmodem575E0031751",
+        motors={"gripper": (6, "sts3215")},
+    )
+    motors_bus.connect()
+
+    position = motors_bus.read("Present_Position")
+
+    # Move from a few motor steps as an example
+    few_steps = 30
+    motors_bus.write("Goal_Position", position + few_steps)
+
+    # When done, properly disconnect the port using
+    motors_bus.disconnect()
+    ```
+    """
 
     model_ctrl_table: dict[str, dict]
     model_resolution_table: dict[str, int]

From 3362b665e6a31a4ea719b82583d6d7371498cff1 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sat, 15 Mar 2025 21:44:01 +0100
Subject: [PATCH 045/171] Move test files

---
 tests/{motors => mocks}/mock_dynamixel_sdk.py       | 3 +--
 tests/{motors => mocks}/mock_scservo_sdk.py         | 2 --
 tests/motors/{test_motors.py => test_motors_bus.py} | 0
 3 files changed, 1 insertion(+), 4 deletions(-)
 rename tests/{motors => mocks}/mock_dynamixel_sdk.py (98%)
 rename tests/{motors => mocks}/mock_scservo_sdk.py (98%)
 rename tests/motors/{test_motors.py => test_motors_bus.py} (100%)

diff --git a/tests/motors/mock_dynamixel_sdk.py b/tests/mocks/mock_dynamixel_sdk.py
similarity index 98%
rename from tests/motors/mock_dynamixel_sdk.py
rename to tests/mocks/mock_dynamixel_sdk.py
index ee399f96..a4d36bd9 100644
--- a/tests/motors/mock_dynamixel_sdk.py
+++ b/tests/mocks/mock_dynamixel_sdk.py
@@ -11,6 +11,7 @@
 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
 # See the License for the specific language governing permissions and
 # limitations under the License.
+
 """Mocked classes and functions from dynamixel_sdk to allow for continuous integration
 and testing code logic that requires hardware and devices (e.g. robot arms, cameras)
 
@@ -18,8 +19,6 @@ Warning: These mocked versions are minimalist. They do not exactly mock every be
 from the original classes and functions (e.g. return types might be None instead of boolean).
 """
 
-# from dynamixel_sdk import COMM_SUCCESS
-
 DEFAULT_BAUDRATE = 9_600
 COMM_SUCCESS = 0  # tx or rx packet communication success
 
diff --git a/tests/motors/mock_scservo_sdk.py b/tests/mocks/mock_scservo_sdk.py
similarity index 98%
rename from tests/motors/mock_scservo_sdk.py
rename to tests/mocks/mock_scservo_sdk.py
index 37f6d0d5..5bbb758d 100644
--- a/tests/motors/mock_scservo_sdk.py
+++ b/tests/mocks/mock_scservo_sdk.py
@@ -18,8 +18,6 @@ Warning: These mocked versions are minimalist. They do not exactly mock every be
 from the original classes and functions (e.g. return types might be None instead of boolean).
 """
 
-# from dynamixel_sdk import COMM_SUCCESS
-
 DEFAULT_BAUDRATE = 1_000_000
 COMM_SUCCESS = 0  # tx or rx packet communication success
 
diff --git a/tests/motors/test_motors.py b/tests/motors/test_motors_bus.py
similarity index 100%
rename from tests/motors/test_motors.py
rename to tests/motors/test_motors_bus.py

From 7f23972f3f4ac96d1c32474b7092abd3990c21fe Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sat, 15 Mar 2025 21:45:05 +0100
Subject: [PATCH 046/171] Add Feetech & Dxl basic tests

---
 tests/motors/test_dynamixel.py | 24 ++++++++++++++++++++++++
 tests/motors/test_feetech.py   | 24 ++++++++++++++++++++++++
 2 files changed, 48 insertions(+)
 create mode 100644 tests/motors/test_dynamixel.py
 create mode 100644 tests/motors/test_feetech.py

diff --git a/tests/motors/test_dynamixel.py b/tests/motors/test_dynamixel.py
new file mode 100644
index 00000000..de18f8dd
--- /dev/null
+++ b/tests/motors/test_dynamixel.py
@@ -0,0 +1,24 @@
+import sys
+from unittest.mock import patch
+
+import pytest
+
+from tests.mocks import mock_dynamixel_sdk
+
+
+@pytest.fixture(autouse=True)
+def patch_dynamixel_sdk():
+    with patch.dict(sys.modules, {"dynamixel_sdk": mock_dynamixel_sdk}):
+        yield
+
+
+def test_patch_sdk():
+    assert "dynamixel_sdk" in sys.modules  # Should be patched
+    assert sys.modules["dynamixel_sdk"] is mock_dynamixel_sdk  # Should match the mock
+
+
+def test_abc_implementation():
+    from lerobot.common.motors.dynamixel import DynamixelMotorsBus
+
+    # Instantiation should raise an error if the class doesn't implements abstract methods/properties
+    DynamixelMotorsBus(port="/dev/dummy-port", motors={"dummy", (1, "xl330-m077")})
diff --git a/tests/motors/test_feetech.py b/tests/motors/test_feetech.py
new file mode 100644
index 00000000..bd9368df
--- /dev/null
+++ b/tests/motors/test_feetech.py
@@ -0,0 +1,24 @@
+import sys
+from unittest.mock import patch
+
+import pytest
+
+from tests.mocks import mock_scservo_sdk
+
+
+@pytest.fixture(autouse=True)
+def patch_scservo_sdk():
+    with patch.dict(sys.modules, {"scservo_sdk": mock_scservo_sdk}):
+        yield
+
+
+def test_patch_sdk():
+    assert "scservo_sdk" in sys.modules  # Should be patched
+    assert sys.modules["scservo_sdk"] is mock_scservo_sdk  # Should match the mock
+
+
+def test_abc_implementation():
+    from lerobot.common.motors.feetech import FeetechMotorsBus
+
+    # Instantiation should raise an error if the class doesn't implements abstract methods/properties
+    FeetechMotorsBus(port="/dev/dummy-port", motors={"dummy", (1, "sts3215")})

From 7a7af82e35046fc42b0e2be441d8c2326c9fb9c4 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sat, 15 Mar 2025 21:53:42 +0100
Subject: [PATCH 047/171] Nit docstring

---
 lerobot/common/motors/dynamixel/dynamixel.py | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/lerobot/common/motors/dynamixel/dynamixel.py b/lerobot/common/motors/dynamixel/dynamixel.py
index 1e223bfa..5797a493 100644
--- a/lerobot/common/motors/dynamixel/dynamixel.py
+++ b/lerobot/common/motors/dynamixel/dynamixel.py
@@ -204,7 +204,7 @@ class DynamixelMotorsBus(MotorsBus):
     """
     The Dynamixel implementation for a MotorsBus. It relies on the python dynamixel sdk to communicate with
     the motors. For more info, see the Dynamixel SDK Documentation:
-    https://emanual.robotis.com/docs/en/software/dynamixel/dynamixel_sdk/sample_code/python_read_write_protocol_2_0/#python-read-write-protocol-20).
+    https://emanual.robotis.com/docs/en/software/dynamixel/dynamixel_sdk/sample_code/python_read_write_protocol_2_0/#python-read-write-protocol-20
     """
 
     model_ctrl_table = deepcopy(MODEL_CONTROL_TABLE)

From f6a2396484c86cc16c98444554ff69b817930b06 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sat, 15 Mar 2025 22:19:50 +0100
Subject: [PATCH 048/171] Move test_configure_motors_all_ids_1

---
 tests/motors/test_dynamixel.py  | 25 +++++++++++++++++++++++-
 tests/motors/test_feetech.py    | 25 +++++++++++++++++++++++-
 tests/motors/test_motors_bus.py | 34 ---------------------------------
 3 files changed, 48 insertions(+), 36 deletions(-)

diff --git a/tests/motors/test_dynamixel.py b/tests/motors/test_dynamixel.py
index de18f8dd..ba6d75ba 100644
--- a/tests/motors/test_dynamixel.py
+++ b/tests/motors/test_dynamixel.py
@@ -21,4 +21,27 @@ def test_abc_implementation():
     from lerobot.common.motors.dynamixel import DynamixelMotorsBus
 
     # Instantiation should raise an error if the class doesn't implements abstract methods/properties
-    DynamixelMotorsBus(port="/dev/dummy-port", motors={"dummy", (1, "xl330-m077")})
+    DynamixelMotorsBus(port="/dev/dummy-port", motors={"dummy": (1, "xl330-m077")})
+
+
+def test_configure_motors_all_ids_1():
+    from lerobot.common.motors.dynamixel import DynamixelMotorsBus
+
+    # see X_SERIES_BAUDRATE_TABLE
+    smaller_baudrate = 9_600
+    smaller_baudrate_value = 0
+
+    # This test expect the configuration was already correct.
+    motors_bus = DynamixelMotorsBus(port="/dev/dummy-port", motors={"dummy": (1, "xl330-m077")})
+    motors_bus.connect()
+    motors_bus.write("Baud_Rate", [smaller_baudrate_value] * len(motors_bus))
+
+    motors_bus.set_baudrate(smaller_baudrate)
+    motors_bus.write("ID", [1] * len(motors_bus))
+    del motors_bus
+
+    # Test configure
+    motors_bus = DynamixelMotorsBus(port="/dev/dummy-port", motors={"dummy": (1, "xl330-m077")})
+    motors_bus.connect()
+    assert motors_bus.are_motors_configured()
+    del motors_bus
diff --git a/tests/motors/test_feetech.py b/tests/motors/test_feetech.py
index bd9368df..9805de84 100644
--- a/tests/motors/test_feetech.py
+++ b/tests/motors/test_feetech.py
@@ -21,4 +21,27 @@ def test_abc_implementation():
     from lerobot.common.motors.feetech import FeetechMotorsBus
 
     # Instantiation should raise an error if the class doesn't implements abstract methods/properties
-    FeetechMotorsBus(port="/dev/dummy-port", motors={"dummy", (1, "sts3215")})
+    FeetechMotorsBus(port="/dev/dummy-port", motors={"dummy": (1, "sts3215")})
+
+
+def test_configure_motors_all_ids_1():
+    from lerobot.common.motors.feetech import FeetechMotorsBus
+
+    # see SCS_SERIES_BAUDRATE_TABLE
+    smaller_baudrate = 19_200
+    smaller_baudrate_value = 7
+
+    # This test expect the configuration was already correct.
+    motors_bus = FeetechMotorsBus(port="/dev/dummy-port", motors={"dummy": (1, "sts3215")})
+    motors_bus.connect()
+    motors_bus.write("Baud_Rate", [smaller_baudrate_value] * len(motors_bus))
+
+    motors_bus.set_baudrate(smaller_baudrate)
+    motors_bus.write("ID", [1] * len(motors_bus))
+    del motors_bus
+
+    # Test configure
+    motors_bus = FeetechMotorsBus(port="/dev/dummy-port", motors={"dummy": (1, "sts3215")})
+    motors_bus.connect()
+    assert motors_bus.are_motors_configured()
+    del motors_bus
diff --git a/tests/motors/test_motors_bus.py b/tests/motors/test_motors_bus.py
index 44c273d2..51588a58 100644
--- a/tests/motors/test_motors_bus.py
+++ b/tests/motors/test_motors_bus.py
@@ -59,40 +59,6 @@ def test_find_port(request, motor_type, mock):
         find_port()
 
 
-@pytest.mark.parametrize("motor_type, mock", TEST_MOTOR_TYPES)
-@require_motor
-def test_configure_motors_all_ids_1(request, motor_type, mock):
-    if mock:
-        request.getfixturevalue("patch_builtins_input")
-
-    if motor_type == "dynamixel":
-        # see X_SERIES_BAUDRATE_TABLE
-        smaller_baudrate = 9_600
-        smaller_baudrate_value = 0
-    elif motor_type == "feetech":
-        # see SCS_SERIES_BAUDRATE_TABLE
-        smaller_baudrate = 19_200
-        smaller_baudrate_value = 7
-    else:
-        raise ValueError(motor_type)
-
-    input("Are you sure you want to re-configure the motors? Press enter to continue...")
-    # This test expect the configuration was already correct.
-    motors_bus = make_motors_bus(motor_type, mock=mock)
-    motors_bus.connect()
-    motors_bus.write("Baud_Rate", [smaller_baudrate_value] * len(motors_bus.motors))
-
-    motors_bus.set_bus_baudrate(smaller_baudrate)
-    motors_bus.write("ID", [1] * len(motors_bus.motors))
-    del motors_bus
-
-    # Test configure
-    motors_bus = make_motors_bus(motor_type, mock=mock)
-    motors_bus.connect()
-    assert motors_bus.are_motors_configured()
-    del motors_bus
-
-
 @pytest.mark.parametrize("motor_type, mock", TEST_MOTOR_TYPES)
 @require_motor
 def test_motors_bus(request, motor_type, mock):

From 8d659a6aa934300334f3a2248703807c1605643f Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sat, 15 Mar 2025 22:26:47 +0100
Subject: [PATCH 049/171] Update mock SDKs

---
 tests/mocks/mock_dynamixel_sdk.py | 31 ++++++++++++++++++++++++++++--
 tests/mocks/mock_scservo_sdk.py   | 32 +++++++++++++++++++++++++++++--
 2 files changed, 59 insertions(+), 4 deletions(-)

diff --git a/tests/mocks/mock_dynamixel_sdk.py b/tests/mocks/mock_dynamixel_sdk.py
index a4d36bd9..6212285e 100644
--- a/tests/mocks/mock_dynamixel_sdk.py
+++ b/tests/mocks/mock_dynamixel_sdk.py
@@ -12,8 +12,10 @@
 # See the License for the specific language governing permissions and
 # limitations under the License.
 
-"""Mocked classes and functions from dynamixel_sdk to allow for continuous integration
-and testing code logic that requires hardware and devices (e.g. robot arms, cameras)
+# ruff: noqa: N802, E741
+
+"""
+Mocked classes and functions from dynamixel_sdk to allow for testing DynamixelMotorsBus code.
 
 Warning: These mocked versions are minimalist. They do not exactly mock every behaviors
 from the original classes and functions (e.g. return types might be None instead of boolean).
@@ -43,6 +45,31 @@ def get_default_motor_values(motor_index):
     }
 
 
+# Macro for Control Table Value
+def DXL_MAKEWORD(a, b):
+    return (a & 0xFF) | ((b & 0xFF) << 8)
+
+
+def DXL_MAKEDWORD(a, b):
+    return (a & 0xFFFF) | (b & 0xFFFF) << 16
+
+
+def DXL_LOWORD(l):
+    return l & 0xFFFF
+
+
+def DXL_HIWORD(l):
+    return (l >> 16) & 0xFFFF
+
+
+def DXL_LOBYTE(w):
+    return w & 0xFF
+
+
+def DXL_HIBYTE(w):
+    return (w >> 8) & 0xFF
+
+
 class PortHandler:
     def __init__(self, port):
         self.port = port
diff --git a/tests/mocks/mock_scservo_sdk.py b/tests/mocks/mock_scservo_sdk.py
index 5bbb758d..21a3652b 100644
--- a/tests/mocks/mock_scservo_sdk.py
+++ b/tests/mocks/mock_scservo_sdk.py
@@ -11,8 +11,11 @@
 # 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.
-"""Mocked classes and functions from dynamixel_sdk to allow for continuous integration
-and testing code logic that requires hardware and devices (e.g. robot arms, cameras)
+
+# ruff: noqa: N802, E741
+
+"""
+Mocked classes and functions from scservo_sdk to allow for testing FeetechMotorsBus code.
 
 Warning: These mocked versions are minimalist. They do not exactly mock every behaviors
 from the original classes and functions (e.g. return types might be None instead of boolean).
@@ -52,6 +55,31 @@ def get_default_motor_values(motor_index):
     }
 
 
+# Macro for Control Table Value
+def SCS_MAKEWORD(a, b):
+    return (a & 0xFF) | ((b & 0xFF) << 8)
+
+
+def SCS_MAKEDWORD(a, b):
+    return (a & 0xFFFF) | (b & 0xFFFF) << 16
+
+
+def SCS_LOWORD(l):
+    return l & 0xFFFF
+
+
+def SCS_HIWORD(l):
+    return (l >> 16) & 0xFFFF
+
+
+def SCS_LOBYTE(w):
+    return w & 0xFF
+
+
+def SCS_HIBYTE(w):
+    return (w >> 8) & 0xFF
+
+
 class PortHandler:
     def __init__(self, port):
         self.port = port

From c85a9253e73c664b63fabc9c778fc6fbcc1c4ecf Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sat, 15 Mar 2025 23:43:26 +0100
Subject: [PATCH 050/171] Move imports

---
 tests/motors/test_dynamixel.py | 5 +----
 tests/motors/test_feetech.py   | 5 +----
 2 files changed, 2 insertions(+), 8 deletions(-)

diff --git a/tests/motors/test_dynamixel.py b/tests/motors/test_dynamixel.py
index ba6d75ba..22cdef23 100644
--- a/tests/motors/test_dynamixel.py
+++ b/tests/motors/test_dynamixel.py
@@ -3,6 +3,7 @@ from unittest.mock import patch
 
 import pytest
 
+from lerobot.common.motors.dynamixel import DynamixelMotorsBus
 from tests.mocks import mock_dynamixel_sdk
 
 
@@ -18,15 +19,11 @@ def test_patch_sdk():
 
 
 def test_abc_implementation():
-    from lerobot.common.motors.dynamixel import DynamixelMotorsBus
-
     # Instantiation should raise an error if the class doesn't implements abstract methods/properties
     DynamixelMotorsBus(port="/dev/dummy-port", motors={"dummy": (1, "xl330-m077")})
 
 
 def test_configure_motors_all_ids_1():
-    from lerobot.common.motors.dynamixel import DynamixelMotorsBus
-
     # see X_SERIES_BAUDRATE_TABLE
     smaller_baudrate = 9_600
     smaller_baudrate_value = 0
diff --git a/tests/motors/test_feetech.py b/tests/motors/test_feetech.py
index 9805de84..6c580f6a 100644
--- a/tests/motors/test_feetech.py
+++ b/tests/motors/test_feetech.py
@@ -3,6 +3,7 @@ from unittest.mock import patch
 
 import pytest
 
+from lerobot.common.motors.feetech import FeetechMotorsBus
 from tests.mocks import mock_scservo_sdk
 
 
@@ -18,15 +19,11 @@ def test_patch_sdk():
 
 
 def test_abc_implementation():
-    from lerobot.common.motors.feetech import FeetechMotorsBus
-
     # Instantiation should raise an error if the class doesn't implements abstract methods/properties
     FeetechMotorsBus(port="/dev/dummy-port", motors={"dummy": (1, "sts3215")})
 
 
 def test_configure_motors_all_ids_1():
-    from lerobot.common.motors.feetech import FeetechMotorsBus
-
     # see SCS_SERIES_BAUDRATE_TABLE
     smaller_baudrate = 19_200
     smaller_baudrate_value = 7

From 9358d334c7a861644ab5e15fd9eec79385bcdf4c Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Wed, 19 Mar 2025 18:44:05 +0100
Subject: [PATCH 051/171] Rewrite MotorsBus

---
 lerobot/common/motors/motors_bus.py | 371 ++++++++++++++++++++++------
 1 file changed, 289 insertions(+), 82 deletions(-)

diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py
index 26ae3836..24683730 100644
--- a/lerobot/common/motors/motors_bus.py
+++ b/lerobot/common/motors/motors_bus.py
@@ -20,13 +20,17 @@
 # ruff: noqa: N802
 
 import abc
+import json
 import time
-import traceback
 from enum import Enum
+from functools import cached_property
+from pathlib import Path
+from pprint import pformat
 from typing import Protocol
 
-import numpy as np
+import serial
 import tqdm
+from deepdiff import DeepDiff
 
 from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError
 from lerobot.common.utils.utils import capture_timestamp_utc
@@ -34,8 +38,8 @@ from lerobot.common.utils.utils import capture_timestamp_utc
 MAX_ID_RANGE = 252
 
 
-def get_group_sync_key(data_name: str, motor_names: list[str]) -> str:
-    group_key = f"{data_name}_" + "_".join(motor_names)
+def get_group_sync_key(data_name: str, motor_ids: list[int]) -> str:
+    group_key = f"{data_name}_" + "_".join([str(idx) for idx in motor_ids])
     return group_key
 
 
@@ -98,7 +102,7 @@ class PortHandler(Protocol):
         self.tx_time_per_byte: float
         self.is_using: bool
         self.port_name: str
-        self.ser: object
+        self.ser: serial.Serial
 
     def openPort(self): ...
     def closePort(self): ...
@@ -153,6 +157,46 @@ class PacketHandler(Protocol):
     def syncWriteTxOnly(self, port, start_address, data_length, param, param_length): ...
 
 
+class GroupSyncRead(Protocol):
+    def __init__(self, port, ph, start_address, data_length):
+        self.port: str
+        self.ph: PortHandler
+        self.start_address: int
+        self.data_length: int
+        self.last_result: bool
+        self.is_param_changed: bool
+        self.param: list
+        self.data_dict: dict
+
+    def makeParam(self): ...
+    def addParam(self, id): ...
+    def removeParam(self, id): ...
+    def clearParam(self): ...
+    def txPacket(self): ...
+    def rxPacket(self): ...
+    def txRxPacket(self): ...
+    def isAvailable(self, id, address, data_length): ...
+    def getData(self, id, address, data_length): ...
+
+
+class GroupSyncWrite(Protocol):
+    def __init__(self, port, ph, start_address, data_length):
+        self.port: str
+        self.ph: PortHandler
+        self.start_address: int
+        self.data_length: int
+        self.is_param_changed: bool
+        self.param: list
+        self.data_dict: dict
+
+    def makeParam(self): ...
+    def addParam(self, id, data): ...
+    def removeParam(self, id): ...
+    def changeParam(self, id, data): ...
+    def clearParam(self): ...
+    def txPacket(self): ...
+
+
 class MotorsBus(abc.ABC):
     """The main LeRobot class for implementing motors buses.
 
@@ -163,7 +207,7 @@ class MotorsBus(abc.ABC):
     Note: This class may evolve in the future should we add support for other manufacturers SDKs.
 
     A MotorsBus allows to efficiently read and write to the attached motors.
-    It represents a several motors daisy-chained together and connected through a serial port.
+    It represents several motors daisy-chained together and connected through a serial port.
 
     A MotorsBus subclass instance requires a port (e.g. `FeetechMotorsBus(port="/dev/tty.usbmodem575E0031751"`)).
     To find the port, you can run our utility script:
@@ -198,6 +242,8 @@ class MotorsBus(abc.ABC):
     model_ctrl_table: dict[str, dict]
     model_resolution_table: dict[str, int]
     model_baudrate_table: dict[str, dict]
+    calibration_required: list[str]
+    default_timeout: int
 
     def __init__(
         self,
@@ -206,73 +252,121 @@ class MotorsBus(abc.ABC):
     ):
         self.port = port
         self.motors = motors
-        self.port_handler: PortHandler | None = None
-        self.packet_handler: PacketHandler | None = None
+        self._validate_motors()
 
-        self.group_readers = {}
-        self.group_writers = {}
-        self.logs = {}
+        self.port_handler: PortHandler
+        self.packet_handler: PacketHandler
+        self.reader: GroupSyncRead
+        self.writer: GroupSyncWrite
 
+        self.logs = {}  # TODO(aliberts): use subclass logger
         self.calibration = None
-        self.is_connected: bool = False
+
+        self._id_to_model = dict(self.motors.values())
+        self._id_to_name = {idx: name for name, (idx, _) in self.motors.items()}
 
     def __len__(self):
         return len(self.motors)
 
-    @property
+    def __repr__(self):
+        return (
+            f"{self.__class__.__name__}(\n"
+            f"    Port: '{self.port}',\n"
+            f"    Motors: \n{pformat(self.motors, indent=8)},\n"
+            ")',\n"
+        )
+
+    @cached_property
+    def _has_different_ctrl_tables(self) -> bool:
+        if len(self.motor_models) < 2:
+            return False
+
+        first_table = self.model_ctrl_table[self.motor_models[0]]
+        return any(DeepDiff(first_table, self.model_ctrl_table[model]) for model in self.motor_models[1:])
+
+    def idx_to_model(self, idx: int) -> str:
+        return self._id_to_model[idx]
+
+    def idx_to_name(self, idx: int) -> str:
+        return self._id_to_name[idx]
+
+    @cached_property
     def motor_names(self) -> list[str]:
         return list(self.motors)
 
-    @property
+    @cached_property
     def motor_models(self) -> list[str]:
         return [model for _, model in self.motors.values()]
 
-    @property
-    def motor_indices(self) -> list[int]:
+    @cached_property
+    def motor_ids(self) -> list[int]:
         return [idx for idx, _ in self.motors.values()]
 
-    def connect(self):
+    def _validate_motors(self) -> None:
+        # TODO(aliberts): improve error messages for this (display problematics values)
+        if len(self.motor_ids) != len(set(self.motor_ids)):
+            raise ValueError("Some motors have the same id.")
+
+        if len(self.motor_names) != len(set(self.motor_names)):
+            raise ValueError("Some motors have the same name.")
+
+        if any(model not in self.model_resolution_table for model in self.motor_models):
+            raise ValueError("Some motors models are not available.")
+
+    @property
+    def is_connected(self) -> bool:
+        return self.port_handler.is_open
+
+    def connect(self) -> None:
         if self.is_connected:
             raise DeviceAlreadyConnectedError(
-                f"{self.__name__}({self.port}) is already connected. Do not call `{self.__name__}.connect()` twice."
+                f"{self.__class__.__name__}('{self.port}') is already connected. Do not call `{self.__class__.__name__}.connect()` twice."
             )
 
-        self._set_handlers()
-
         try:
             if not self.port_handler.openPort():
                 raise OSError(f"Failed to open port '{self.port}'.")
-        except Exception:
-            traceback.print_exc()
+        except (FileNotFoundError, OSError, serial.SerialException) as e:
             print(
-                "\nTry running `python lerobot/scripts/find_motors_bus_port.py` to make sure you are using the correct port.\n"
+                f"\nCould not connect on port '{self.port}'. Make sure you are using the correct port."
+                "\nTry running `python lerobot/scripts/find_motors_bus_port.py`\n"
             )
-            raise
+            raise e
 
-        self._set_timeout()
+        self.set_timeout()
 
-        # Allow to read and write
-        self.is_connected = True
+    def set_timeout(self, timeout_ms: int | None = None):
+        timeout_ms = timeout_ms if timeout_ms is not None else self.default_timeout
+        self.port_handler.setPacketTimeoutMillis(timeout_ms)
 
-    @abc.abstractmethod
-    def _set_handlers(self):
-        pass
-
-    @abc.abstractmethod
-    def _set_timeout(self, timeout: int):
-        pass
-
-    def are_motors_configured(self):
+    @property
+    def are_motors_configured(self) -> bool:
         """
         Only check the motor indices and not baudrate, since if the motor baudrates are incorrect, a
         ConnectionError will be raised anyway.
         """
         try:
-            return (self.motor_indices == self.read("ID")).all()
+            # TODO(aliberts): use ping instead
+            return (self.motor_ids == self.read("ID")).all()
         except ConnectionError as e:
             print(e)
             return False
 
+    def ping(self, motor: str | int, num_retry: int | None = None) -> int:
+        idx = self.get_safe_id(motor)
+        for _ in range(num_retry):
+            model_number, comm, _ = self.packet_handler.ping(self.port, idx)
+            if self._is_comm_success(comm):
+                return model_number
+
+        # TODO(aliberts): Should we?
+        return comm
+
+    @abc.abstractmethod
+    def broadcast_ping(self, num_retry: int | None = None):
+        ...
+        # TODO(aliberts): this will replace 'find_motor_indices'
+
     def find_motor_indices(self, possible_ids: list[str] = None, num_retry: int = 2):
         if possible_ids is None:
             possible_ids = range(MAX_ID_RANGE)
@@ -280,7 +374,7 @@ class MotorsBus(abc.ABC):
         indices = []
         for idx in tqdm.tqdm(possible_ids):
             try:
-                present_idx = self.read_with_motor_ids(self.motor_models, [idx], "ID", num_retry=num_retry)[0]
+                present_idx = self.read("ID", idx, num_retry=num_retry)[0]
             except ConnectionError:
                 continue
 
@@ -294,7 +388,7 @@ class MotorsBus(abc.ABC):
 
         return indices
 
-    def set_baudrate(self, baudrate):
+    def set_baudrate(self, baudrate) -> None:
         present_bus_baudrate = self.port_handler.getBaudRate()
         if present_bus_baudrate != baudrate:
             print(f"Setting bus baud rate to {baudrate}. Previously {present_bus_baudrate}.")
@@ -303,94 +397,207 @@ class MotorsBus(abc.ABC):
             if self.port_handler.getBaudRate() != baudrate:
                 raise OSError("Failed to write bus baud rate.")
 
-    def set_calibration(self, calibration_dict: dict[str, list]):
-        self.calibration = calibration_dict
+    def set_calibration(self, calibration_fpath: Path) -> None:
+        with open(calibration_fpath) as f:
+            calibration = json.load(f)
+
+        self.calibration = {int(idx): val for idx, val in calibration.items()}
 
     @abc.abstractmethod
-    def apply_calibration(self):
+    def calibrate_values(self, ids_values: dict[int, int]) -> dict[int, float]:
         pass
 
     @abc.abstractmethod
-    def revert_calibration(self):
+    def uncalibrate_values(self, ids_values: dict[int, float]) -> dict[int, int]:
         pass
 
-    def read(self, data_name, motor_names: str | list[str] | None = None):
+    @abc.abstractmethod
+    def _is_comm_success(self, comm: int) -> bool:
+        pass
+
+    @staticmethod
+    @abc.abstractmethod
+    def split_int_bytes(value: int, n_bytes: int) -> list[int]:
+        """
+        Splits an unsigned integer into a list of bytes in little-endian order.
+
+        This function extracts the individual bytes of an integer based on the
+        specified number of bytes (`n_bytes`). The output is a list of integers,
+        each representing a byte (0-255).
+
+        **Byte order:** The function returns bytes in **little-endian format**,
+        meaning the least significant byte (LSB) comes first.
+
+        Args:
+            value (int): The unsigned integer to be converted into a byte list. Must be within
+                the valid range for the specified `n_bytes`.
+            n_bytes (int): The number of bytes to use for conversion. Supported values:
+                - 1 (for values 0 to 255)
+                - 2 (for values 0 to 65,535)
+                - 4 (for values 0 to 4,294,967,295)
+
+        Raises:
+            ValueError: If `value` is negative or exceeds the maximum allowed for `n_bytes`.
+            NotImplementedError: If `n_bytes` is not 1, 2, or 4.
+
+        Returns:
+            list[int]: A list of integers, each representing a byte in **little-endian order**.
+
+        Examples:
+            >>> split_int_bytes(0x12, 1)
+            [18]
+            >>> split_int_bytes(0x1234, 2)
+            [52, 18]  # 0x1234 → 0x34 0x12 (little-endian)
+            >>> split_int_bytes(0x12345678, 4)
+            [120, 86, 52, 18]  # 0x12345678 → 0x78 0x56 0x34 0x12
+        """
+        pass
+
+    def get_safe_id(self, motor: str | int) -> int:
+        if isinstance(motor, str):
+            return self.motors[motor][0]
+        elif isinstance(motor, int):
+            return motor
+        else:
+            raise ValueError(f"{motor} should be int or str.")
+
+    def read(
+        self, data_name: str, motors: str | int | list[str | int] | None = None, num_retry: int = 1
+    ) -> dict[str, float]:
         if not self.is_connected:
             raise DeviceNotConnectedError(
-                f"{self.__name__}({self.port}) is not connected. You need to run `{self.__name__}.connect()`."
+                f"{self.__class__.__name__}('{self.port}') is not connected. You need to run `{self.__class__.__name__}.connect()`."
             )
 
         start_time = time.perf_counter()
-        if motor_names is None:
-            motor_names = self.motor_names
 
-        if isinstance(motor_names, str):
-            motor_names = [motor_names]
+        if motors is None:
+            motors = self.motor_ids
 
-        values = self._read(data_name, motor_names)
+        if isinstance(motors, (str, int)):
+            motors = [motors]
+
+        motor_ids = [self.get_safe_id(motor) for motor in motors]
+        if self._has_different_ctrl_tables:
+            models = [self.idx_to_model(idx) for idx in motor_ids]
+            assert_same_address(self.model_ctrl_table, models, data_name)
+
+        model = self.idx_to_model(next(iter(motor_ids)))
+        addr, n_bytes = self.model_ctrl_table[model][data_name]
+
+        comm, ids_values = self._read(motor_ids, addr, n_bytes, num_retry)
+        if not self._is_comm_success(comm):
+            raise ConnectionError(
+                f"Failed to read {data_name} on port {self.port} for ids {motor_ids}:"
+                f"{self.packet_handler.getTxRxResult(comm)}"
+            )
+
+        if data_name in self.calibration_required and self.calibration is not None:
+            ids_values = self.calibrate_values(ids_values)
+
+        # TODO(aliberts): return keys in the same format we got them?
+        ids_values = {self.idx_to_name(idx): val for idx, val in ids_values.items()}
 
         # 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)
+        delta_ts_name = get_log_name("delta_timestamp_s", "read", data_name, motor_ids)
         self.logs[delta_ts_name] = time.perf_counter() - start_time
 
         # log the utc time at which the data was received
-        ts_utc_name = get_log_name("timestamp_utc", "read", data_name, motor_names)
+        ts_utc_name = get_log_name("timestamp_utc", "read", data_name, motor_ids)
         self.logs[ts_utc_name] = capture_timestamp_utc()
 
-        return values
+        return ids_values
 
-    @abc.abstractmethod
-    def _read(self, data_name: str, motor_names: list[str]):
-        pass
+    def _read(
+        self, motor_ids: list[str], address: int, n_bytes: int, num_retry: int = 1
+    ) -> tuple[int, dict[int, int]]:
+        self.reader.clearParam()
+        self.reader.start_address = address
+        self.reader.data_length = n_bytes
 
-    def write(
-        self, data_name: str, values: int | float | np.ndarray, motor_names: str | list[str] | None = None
-    ) -> None:
+        # FIXME(aliberts, pkooij): We should probably not have to do this.
+        # Let's try to see if we can do with better comm status handling instead.
+        # self.port_handler.ser.reset_output_buffer()
+        # self.port_handler.ser.reset_input_buffer()
+
+        for idx in motor_ids:
+            self.reader.addParam(idx)
+
+        for _ in range(num_retry):
+            comm = self.reader.txRxPacket()
+            if self._is_comm_success(comm):
+                break
+
+        values = {idx: self.reader.getData(idx, address, n_bytes) for idx in motor_ids}
+        return comm, values
+
+    # TODO(aliberts, pkooij): Implementing something like this could get much faster read times.
+    # Note: this could be at the cost of increase latency between the moment the data is produced by the
+    # motors and the moment it is used by a policy
+    # def _async_read(self, motor_ids: list[str], address: int, n_bytes: int):
+    #     self.reader.rxPacket()
+    #     self.reader.txPacket()
+    #     for idx in motor_ids:
+    #         value = self.reader.getData(idx, address, n_bytes)
+
+    def write(self, data_name: str, values_dict: dict[str | int, int], num_retry: int = 1) -> None:
         if not self.is_connected:
             raise DeviceNotConnectedError(
-                f"{self.__name__}({self.port}) is not connected. You need to run `{self.__name__}.connect()`."
+                f"{self.__class__.__name__}('{self.port}') is not connected. You need to run `{self.__class__.__name__}.connect()`."
             )
 
         start_time = time.perf_counter()
 
-        if motor_names is None:
-            motor_names = self.motor_names
+        ids_values = {self.get_safe_id(motor): val for motor, val in values_dict.items()}
 
-        if isinstance(motor_names, str):
-            motor_names = [motor_names]
+        if self._has_different_ctrl_tables:
+            models = [self.idx_to_model(idx) for idx in ids_values]
+            assert_same_address(self.model_ctrl_table, models, data_name)
 
-        if isinstance(values, (int, float, np.integer)):
-            values = [int(values)] * len(motor_names)
+        if data_name in self.calibration_required and self.calibration is not None:
+            ids_values = self.uncalibrate_values(ids_values)
 
-        self._write(data_name, values, motor_names)
+        model = self.idx_to_model(next(iter(ids_values)))
+        addr, n_bytes = self.model_ctrl_table[model][data_name]
+
+        comm = self._write(ids_values, addr, n_bytes, num_retry)
+        if not self._is_comm_success(comm):
+            raise ConnectionError(
+                f"Failed to write {data_name} on port {self.port} for ids {list(ids_values)}:"
+                f"{self.packet_handler.getTxRxResult(comm)}"
+            )
 
         # log the number of seconds it took to write the data to the motors
-        delta_ts_name = get_log_name("delta_timestamp_s", "write", data_name, motor_names)
+        delta_ts_name = get_log_name("delta_timestamp_s", "write", data_name, list(ids_values))
         self.logs[delta_ts_name] = time.perf_counter() - start_time
 
-        # TODO(rcadene): should we log the time before sending the write command?
         # log the utc time when the write has been completed
-        ts_utc_name = get_log_name("timestamp_utc", "write", data_name, motor_names)
+        ts_utc_name = get_log_name("timestamp_utc", "write", data_name, list(ids_values))
         self.logs[ts_utc_name] = capture_timestamp_utc()
 
-    @abc.abstractmethod
-    def _write(self, data_name: str, values: list[int], motor_names: list[str]) -> None:
-        pass
+    def _write(self, ids_values: dict[int, int], address: int, n_bytes: int, num_retry: int = 1) -> int:
+        self.writer.clearParam()
+        self.writer.start_address = address
+        self.writer.data_length = n_bytes
+
+        for idx, value in ids_values.items():
+            data = self.split_int_bytes(value, n_bytes)
+            self.writer.addParam(idx, data)
+
+        for _ in range(num_retry):
+            comm = self.writer.txPacket()
+            if self._is_comm_success(comm):
+                break
+
+        return comm
 
     def disconnect(self) -> None:
         if not self.is_connected:
             raise DeviceNotConnectedError(
-                f"{self.__name__}({self.port}) is not connected. Try running `{self.__name__}.connect()` first."
+                f"{self.__class__.__name__}('{self.port}') is not connected. Try running `{self.__class__.__name__}.connect()` first."
             )
 
-        if self.port_handler is not None:
-            self.port_handler.closePort()
-            self.port_handler = None
-
-        self.packet_handler = None
-        self.group_readers = {}
-        self.group_writers = {}
-        self.is_connected = False
+        self.port_handler.closePort()
 
     def __del__(self):
         if self.is_connected:

From 97494c6a39a58124c18b490e3701172a8510b3a0 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Wed, 19 Mar 2025 18:46:04 +0100
Subject: [PATCH 052/171] (WIP) Implement Dynamixel

---
 lerobot/common/motors/dynamixel/dynamixel.py | 479 ++-----------------
 1 file changed, 53 insertions(+), 426 deletions(-)

diff --git a/lerobot/common/motors/dynamixel/dynamixel.py b/lerobot/common/motors/dynamixel/dynamixel.py
index 5797a493..413ed173 100644
--- a/lerobot/common/motors/dynamixel/dynamixel.py
+++ b/lerobot/common/motors/dynamixel/dynamixel.py
@@ -12,24 +12,21 @@
 # See the License for the specific language governing permissions and
 # limitations under the License.
 
-import logging
-import math
+# TODO(aliberts): Should we implement FastSyncRead/Write?
+# https://github.com/ROBOTIS-GIT/DynamixelSDK/pull/643
+# https://github.com/ROBOTIS-GIT/DynamixelSDK/releases/tag/3.8.2
+# https://emanual.robotis.com/docs/en/dxl/protocol2/#fast-sync-read-0x8a
+# -> Need to check compatibility across models
+
 from copy import deepcopy
 
 import numpy as np
 
-from ..motors_bus import (
-    CalibrationMode,
-    JointOutOfRangeError,
-    MotorsBus,
-    TorqueMode,
-    assert_same_address,
-    get_group_sync_key,
-)
+from ..motors_bus import MotorsBus
 
 PROTOCOL_VERSION = 2.0
 BAUDRATE = 1_000_000
-TIMEOUT_MS = 1000
+DEFAULT_TIMEOUT_MS = 1000
 
 MAX_ID_RANGE = 252
 
@@ -171,35 +168,6 @@ def convert_degrees_to_steps(degrees: float | np.ndarray, models: str | list[str
     return steps
 
 
-def convert_to_bytes(value, n_bytes: int):
-    import dynamixel_sdk as dxl
-
-    # Note: No need to convert back into unsigned int, since this byte preprocessing
-    # already handles it for us.
-    if n_bytes == 1:
-        data = [
-            dxl.DXL_LOBYTE(dxl.DXL_LOWORD(value)),
-        ]
-    elif n_bytes == 2:
-        data = [
-            dxl.DXL_LOBYTE(dxl.DXL_LOWORD(value)),
-            dxl.DXL_HIBYTE(dxl.DXL_LOWORD(value)),
-        ]
-    elif n_bytes == 4:
-        data = [
-            dxl.DXL_LOBYTE(dxl.DXL_LOWORD(value)),
-            dxl.DXL_HIBYTE(dxl.DXL_LOWORD(value)),
-            dxl.DXL_LOBYTE(dxl.DXL_HIWORD(value)),
-            dxl.DXL_HIBYTE(dxl.DXL_HIWORD(value)),
-        ]
-    else:
-        raise NotImplementedError(
-            f"Value of the number of bytes to be sent is expected to be in [1, 2, 4], but "
-            f"{n_bytes} is provided instead."
-        )
-    return data
-
-
 class DynamixelMotorsBus(MotorsBus):
     """
     The Dynamixel implementation for a MotorsBus. It relies on the python dynamixel sdk to communicate with
@@ -210,6 +178,8 @@ class DynamixelMotorsBus(MotorsBus):
     model_ctrl_table = deepcopy(MODEL_CONTROL_TABLE)
     model_resolution_table = deepcopy(MODEL_RESOLUTION)
     model_baudrate_table = deepcopy(MODEL_BAUDRATE_TABLE)
+    calibration_required = deepcopy(CALIBRATION_REQUIRED)
+    default_timeout = DEFAULT_TIMEOUT_MS
 
     def __init__(
         self,
@@ -217,405 +187,62 @@ class DynamixelMotorsBus(MotorsBus):
         motors: dict[str, tuple[int, str]],
     ):
         super().__init__(port, motors)
-
-    def _set_handlers(self):
         import dynamixel_sdk as dxl
 
         self.port_handler = dxl.PortHandler(self.port)
         self.packet_handler = dxl.PacketHandler(PROTOCOL_VERSION)
+        self.reader = dxl.GroupSyncRead(self.port_handler, self.packet_handler, 0, 0)
+        self.writer = dxl.GroupSyncWrite(self.port_handler, self.packet_handler, 0, 0)
 
-    def _set_timeout(self, timeout: int = TIMEOUT_MS):
-        self.port_handler.setPacketTimeoutMillis(timeout)
+    def broadcast_ping(self) -> tuple[list, int]:
+        data_list, comm = self.packet_handler.broadcastPing(self.port_handler)
+        # TODO(aliberts): translate data_list into {id: model}
+        return data_list, comm
 
-    def _apply_calibration_autocorrect(self, values: np.ndarray | list, motor_names: list[str] | None):
-        """This function applies the calibration, automatically detects out of range errors for motors values and attempts to correct.
+    def calibrate_values(self, ids_values: dict[int, int]) -> dict[int, float]:
+        # TODO
+        return ids_values
 
-        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 uncalibrate_values(self, ids_values: dict[int, float]) -> dict[int, int]:
+        # TODO
+        return ids_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, dynamixel xl330-m077 have a resolution of 4096, and
-        at any position in their original range, let's say the position 56734, they complete a full rotation clockwise by moving to 60830,
-        or anticlockwise by moving to 52638. The position in the original range is arbitrary and might change a lot between each motor.
-        To harmonize between motors of the same model, different robots, or even models of different brands, we propose to work
-        in the centered nominal degree range ]-180, 180[.
-        """
-        if motor_names is None:
-            motor_names = self.motor_names
-
-        # Convert from unsigned int32 original range [0, 2**32] to signed float32 range
-        values = values.astype(np.float32)
-
-        for i, name in enumerate(motor_names):
-            calib_idx = self.calibration["motor_names"].index(name)
-            calib_mode = self.calibration["calib_mode"][calib_idx]
-
-            if CalibrationMode[calib_mode] == CalibrationMode.DEGREE:
-                drive_mode = self.calibration["drive_mode"][calib_idx]
-                homing_offset = self.calibration["homing_offset"][calib_idx]
-                _, model = self.motors[name]
-                resolution = self.model_resolution[model]
-
-                # Update direction of rotation of the motor to match between leader and follower.
-                # In fact, the motor of the leader for a given joint can be assembled in an
-                # opposite direction in term of rotation than the motor of the follower on the same joint.
-                if drive_mode:
-                    values[i] *= -1
-
-                # Convert from range [-2**31, 2**31] to
-                # nominal range [-resolution//2, resolution//2] (e.g. [-2048, 2048])
-                values[i] += homing_offset
-
-                # Convert from range [-resolution//2, resolution//2] to
-                # universal float32 centered degree range [-180, 180]
-                # (e.g. 2048 / (4096 // 2) * 180 = 180)
-                values[i] = values[i] / (resolution // 2) * HALF_TURN_DEGREE
-
-                if (values[i] < LOWER_BOUND_DEGREE) or (values[i] > UPPER_BOUND_DEGREE):
-                    raise JointOutOfRangeError(
-                        f"Wrong motor position range detected for {name}. "
-                        f"Expected to be in nominal range of [-{HALF_TURN_DEGREE}, {HALF_TURN_DEGREE}] degrees (a full rotation), "
-                        f"with a maximum range of [{LOWER_BOUND_DEGREE}, {UPPER_BOUND_DEGREE}] degrees to account for joints that can rotate a bit more, "
-                        f"but present value is {values[i]} degree. "
-                        "This might be due to a cable connection issue creating an artificial 360 degrees jump in motor values. "
-                        "You need to recalibrate by running: `python lerobot/scripts/control_robot.py calibrate`"
-                    )
-
-            elif CalibrationMode[calib_mode] == CalibrationMode.LINEAR:
-                start_pos = self.calibration["start_pos"][calib_idx]
-                end_pos = self.calibration["end_pos"][calib_idx]
-
-                # Rescale the present position to a nominal range [0, 100] %,
-                # useful for joints with linear motions like Aloha gripper
-                values[i] = (values[i] - start_pos) / (end_pos - start_pos) * 100
-
-                if (values[i] < LOWER_BOUND_LINEAR) or (values[i] > UPPER_BOUND_LINEAR):
-                    raise JointOutOfRangeError(
-                        f"Wrong motor position range detected for {name}. "
-                        f"Expected to be in nominal range of [0, 100] % (a full linear translation), "
-                        f"with a maximum range of [{LOWER_BOUND_LINEAR}, {UPPER_BOUND_LINEAR}] % to account for some imprecision during calibration, "
-                        f"but present value is {values[i]} %. "
-                        "This might be due to a cable connection issue creating an artificial jump in motor values. "
-                        "You need to recalibrate by running: `python lerobot/scripts/control_robot.py calibrate`"
-                    )
-
-        return values
-
-    def _autocorrect_calibration(self, values: np.ndarray | list, motor_names: list[str] | None):
-        """This function automatically detects issues with values of motors after calibration, and correct for these issues.
-
-        Some motors might have values outside of expected maximum bounds after calibration.
-        For instance, for a joint in degree, its value can be outside [-270, 270] degrees, which is totally unexpected given
-        a nominal range of [-180, 180] degrees, which represents half a turn to the left or right starting from zero position.
-
-        Known issues:
-        #1: Motor value randomly shifts of a full turn, caused by hardware/connection errors.
-        #2: Motor internal homing offset is shifted by a full turn, caused by using default calibration (e.g Aloha).
-        #3: motor internal homing offset is shifted by 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]
-
-                # 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 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
-                # (- (resolution // 2) - values[i] - homing_offset) / resolution <= factor <= ((resolution // 2) - values[i] - homing_offset) / resolution
-                low_factor = (-(resolution // 2) - values[i] - homing_offset) / resolution
-                upp_factor = ((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):
-        # TODO(aliberts): remove np
-        """Inverse of `apply_calibration`."""
-        if motor_names is None:
-            motor_names = self.motor_names
-
-        for i, name in enumerate(motor_names):
-            calib_idx = self.calibration["motor_names"].index(name)
-            calib_mode = self.calibration["calib_mode"][calib_idx]
-
-            if CalibrationMode[calib_mode] == CalibrationMode.DEGREE:
-                drive_mode = self.calibration["drive_mode"][calib_idx]
-                homing_offset = self.calibration["homing_offset"][calib_idx]
-                _, model = self.motors[name]
-                resolution = self.model_resolution[model]
-
-                # Convert from nominal 0-centered degree range [-180, 180] to
-                # 0-centered resolution range (e.g. [-2048, 2048] for resolution=4096)
-                values[i] = values[i] / HALF_TURN_DEGREE * (resolution // 2)
-
-                # 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
-
-            elif CalibrationMode[calib_mode] == CalibrationMode.LINEAR:
-                start_pos = self.calibration["start_pos"][calib_idx]
-                end_pos = self.calibration["end_pos"][calib_idx]
-
-                # Convert from nominal lnear range of [0, 100] % to
-                # actual motor range of values which can be arbitrary.
-                values[i] = values[i] / 100 * (end_pos - start_pos) + start_pos
-
-        values = np.round(values).astype(np.int32)
-        return values
-
-    def read_with_motor_ids(self, motor_models, motor_ids, data_name, num_retry=NUM_READ_RETRY):
+    def _is_comm_success(self, comm: int) -> bool:
         import dynamixel_sdk as dxl
 
-        return_list = True
-        if not isinstance(motor_ids, list):
-            return_list = False
-            motor_ids = [motor_ids]
+        return comm == dxl.COMM_SUCCESS
 
-        assert_same_address(self.model_ctrl_table, self.motor_models, data_name)
-        addr, bytes = self.model_ctrl_table[motor_models[0]][data_name]
-        group = dxl.GroupSyncRead(self.port_handler, self.packet_handler, addr, bytes)
-        for idx in motor_ids:
-            group.addParam(idx)
+    @staticmethod
+    def split_int_bytes(value: int, n_bytes: int) -> list[int]:
+        # Validate input
+        if value < 0:
+            raise ValueError(f"Negative values are not allowed: {value}")
 
-        for _ in range(num_retry):
-            comm = group.txRxPacket()
-            if comm == dxl.COMM_SUCCESS:
-                break
+        max_value = {1: 0xFF, 2: 0xFFFF, 4: 0xFFFFFFFF}.get(n_bytes)
+        if max_value is None:
+            raise NotImplementedError(f"Unsupported byte size: {n_bytes}. Expected [1, 2, 4].")
 
-        if comm != dxl.COMM_SUCCESS:
-            raise ConnectionError(
-                f"Read failed due to communication error on port {self.port_handler.port_name} for indices {motor_ids}: "
-                f"{self.packet_handler.getTxRxResult(comm)}"
-            )
+        if value > max_value:
+            raise ValueError(f"Value {value} exceeds the maximum for {n_bytes} bytes ({max_value}).")
 
-        values = []
-        for idx in motor_ids:
-            value = group.getData(idx, addr, bytes)
-            values.append(value)
-
-        if return_list:
-            return values
-        else:
-            return values[0]
-
-    def _read(self, data_name: str, motor_names: list[str]):
         import dynamixel_sdk as dxl
 
-        motor_ids = []
-        models = []
-        for name in motor_names:
-            motor_idx, model = self.motors[name]
-            motor_ids.append(motor_idx)
-            models.append(model)
-
-        assert_same_address(self.model_ctrl_table, models, data_name)
-        addr, bytes = self.model_ctrl_table[model][data_name]
-        group_key = get_group_sync_key(data_name, motor_names)
-
-        if data_name not in self.group_readers:
-            # create new group reader
-            self.group_readers[group_key] = dxl.GroupSyncRead(
-                self.port_handler, self.packet_handler, addr, bytes
-            )
-            for idx in motor_ids:
-                self.group_readers[group_key].addParam(idx)
-
-        for _ in range(NUM_READ_RETRY):
-            comm = self.group_readers[group_key].txRxPacket()
-            if comm == dxl.COMM_SUCCESS:
-                break
-
-        if comm != dxl.COMM_SUCCESS:
-            raise ConnectionError(
-                f"Read failed due to communication error on port {self.port} for group_key {group_key}: "
-                f"{self.packet_handler.getTxRxResult(comm)}"
-            )
-
-        values = []
-        for idx in motor_ids:
-            value = self.group_readers[group_key].getData(idx, addr, bytes)
-            values.append(value)
-
-        values = np.array(values)
-
-        # Convert to signed int to use range [-2048, 2048] for our motor positions.
-        if data_name in CONVERT_UINT32_TO_INT32_REQUIRED:
-            values = values.astype(np.int32)
-
-        if data_name in CALIBRATION_REQUIRED and self.calibration is not None:
-            values = self._apply_calibration_autocorrect(values, motor_names)
-
-        return values
-
-    def write_with_motor_ids(self, motor_models, motor_ids, data_name, values, num_retry=NUM_WRITE_RETRY):
-        import dynamixel_sdk as dxl
-
-        if not isinstance(motor_ids, list):
-            motor_ids = [motor_ids]
-        if not isinstance(values, list):
-            values = [values]
-
-        assert_same_address(self.model_ctrl_table, motor_models, data_name)
-        addr, bytes = self.model_ctrl_table[motor_models[0]][data_name]
-        group = dxl.GroupSyncWrite(self.port_handler, self.packet_handler, addr, bytes)
-        for idx, value in zip(motor_ids, values, strict=True):
-            data = convert_to_bytes(value, bytes)
-            group.addParam(idx, data)
-
-        for _ in range(num_retry):
-            comm = group.txPacket()
-            if comm == dxl.COMM_SUCCESS:
-                break
-
-        if comm != dxl.COMM_SUCCESS:
-            raise ConnectionError(
-                f"Write failed due to communication error on port {self.port_handler.port_name} for indices {motor_ids}: "
-                f"{self.packet_handler.getTxRxResult(comm)}"
-            )
-
-    def _write(self, data_name: str, values: list[int], motor_names: list[str]) -> None:
-        import dynamixel_sdk as dxl
-
-        motor_ids = []
-        models = []
-        for name in motor_names:
-            motor_idx, model = self.motors[name]
-            motor_ids.append(motor_idx)
-            models.append(model)
-
-        if data_name in CALIBRATION_REQUIRED and self.calibration is not None:
-            values = self.revert_calibration(values, motor_names)
-
-        assert_same_address(self.model_ctrl_table, models, data_name)
-        addr, bytes = self.model_ctrl_table[model][data_name]
-        group_key = get_group_sync_key(data_name, motor_names)
-
-        init_group = data_name not in self.group_readers
-        if init_group:
-            self.group_writers[group_key] = dxl.GroupSyncWrite(
-                self.port_handler, self.packet_handler, addr, bytes
-            )
-
-        for idx, value in zip(motor_ids, values, strict=True):
-            data = convert_to_bytes(value, bytes)
-            if init_group:
-                self.group_writers[group_key].addParam(idx, data)
-            else:
-                self.group_writers[group_key].changeParam(idx, data)
-
-        comm = self.group_writers[group_key].txPacket()
-        if comm != dxl.COMM_SUCCESS:
-            raise ConnectionError(
-                f"Write failed due to communication error on port {self.port} for group_key {group_key}: "
-                f"{self.packet_handler.getTxRxResult(comm)}"
-            )
-
-
-def set_operating_mode(bus: DynamixelMotorsBus):
-    if (bus.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 bus.motor_names if name != "gripper"]
-    if len(all_motors_except_gripper) > 0:
-        # 4 corresponds to Extended Position on Koch motors
-        bus.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"
-    bus.write("Operating_Mode", 5, "gripper")
+        # Note: No need to convert back into unsigned int, since this byte preprocessing
+        # already handles it for us.
+        if n_bytes == 1:
+            data = [
+                dxl.DXL_LOBYTE(dxl.DXL_LOWORD(value)),
+            ]
+        elif n_bytes == 2:
+            data = [
+                dxl.DXL_LOBYTE(dxl.DXL_LOWORD(value)),
+                dxl.DXL_HIBYTE(dxl.DXL_LOWORD(value)),
+            ]
+        elif n_bytes == 4:
+            data = [
+                dxl.DXL_LOBYTE(dxl.DXL_LOWORD(value)),
+                dxl.DXL_HIBYTE(dxl.DXL_LOWORD(value)),
+                dxl.DXL_LOBYTE(dxl.DXL_HIWORD(value)),
+                dxl.DXL_HIBYTE(dxl.DXL_HIWORD(value)),
+            ]
+        return data

From 794f6e00fccd15e6e794aafddadfb8ab3fd4e475 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Wed, 19 Mar 2025 18:57:29 +0100
Subject: [PATCH 053/171] Introduce Dxl packet mocking logic

---
 tests/mocks/mock_dynamixel.py | 306 ++++++++++++++++++++++++++++++++++
 1 file changed, 306 insertions(+)
 create mode 100644 tests/mocks/mock_dynamixel.py

diff --git a/tests/mocks/mock_dynamixel.py b/tests/mocks/mock_dynamixel.py
new file mode 100644
index 00000000..8176d766
--- /dev/null
+++ b/tests/mocks/mock_dynamixel.py
@@ -0,0 +1,306 @@
+import abc
+import random
+from typing import Callable
+
+import dynamixel_sdk as dxl
+import serial
+from mock_serial import MockSerial
+
+from lerobot.common.motors.dynamixel.dynamixel import X_SERIES_CONTROL_TABLE
+
+# https://emanual.robotis.com/docs/en/dxl/crc/
+DXL_CRC_TABLE = [
+    0x0000, 0x8005, 0x800F, 0x000A, 0x801B, 0x001E, 0x0014,
+    0x8011, 0x8033, 0x0036, 0x003C, 0x8039, 0x0028, 0x802D,
+    0x8027, 0x0022, 0x8063, 0x0066, 0x006C, 0x8069, 0x0078,
+    0x807D, 0x8077, 0x0072, 0x0050, 0x8055, 0x805F, 0x005A,
+    0x804B, 0x004E, 0x0044, 0x8041, 0x80C3, 0x00C6, 0x00CC,
+    0x80C9, 0x00D8, 0x80DD, 0x80D7, 0x00D2, 0x00F0, 0x80F5,
+    0x80FF, 0x00FA, 0x80EB, 0x00EE, 0x00E4, 0x80E1, 0x00A0,
+    0x80A5, 0x80AF, 0x00AA, 0x80BB, 0x00BE, 0x00B4, 0x80B1,
+    0x8093, 0x0096, 0x009C, 0x8099, 0x0088, 0x808D, 0x8087,
+    0x0082, 0x8183, 0x0186, 0x018C, 0x8189, 0x0198, 0x819D,
+    0x8197, 0x0192, 0x01B0, 0x81B5, 0x81BF, 0x01BA, 0x81AB,
+    0x01AE, 0x01A4, 0x81A1, 0x01E0, 0x81E5, 0x81EF, 0x01EA,
+    0x81FB, 0x01FE, 0x01F4, 0x81F1, 0x81D3, 0x01D6, 0x01DC,
+    0x81D9, 0x01C8, 0x81CD, 0x81C7, 0x01C2, 0x0140, 0x8145,
+    0x814F, 0x014A, 0x815B, 0x015E, 0x0154, 0x8151, 0x8173,
+    0x0176, 0x017C, 0x8179, 0x0168, 0x816D, 0x8167, 0x0162,
+    0x8123, 0x0126, 0x012C, 0x8129, 0x0138, 0x813D, 0x8137,
+    0x0132, 0x0110, 0x8115, 0x811F, 0x011A, 0x810B, 0x010E,
+    0x0104, 0x8101, 0x8303, 0x0306, 0x030C, 0x8309, 0x0318,
+    0x831D, 0x8317, 0x0312, 0x0330, 0x8335, 0x833F, 0x033A,
+    0x832B, 0x032E, 0x0324, 0x8321, 0x0360, 0x8365, 0x836F,
+    0x036A, 0x837B, 0x037E, 0x0374, 0x8371, 0x8353, 0x0356,
+    0x035C, 0x8359, 0x0348, 0x834D, 0x8347, 0x0342, 0x03C0,
+    0x83C5, 0x83CF, 0x03CA, 0x83DB, 0x03DE, 0x03D4, 0x83D1,
+    0x83F3, 0x03F6, 0x03FC, 0x83F9, 0x03E8, 0x83ED, 0x83E7,
+    0x03E2, 0x83A3, 0x03A6, 0x03AC, 0x83A9, 0x03B8, 0x83BD,
+    0x83B7, 0x03B2, 0x0390, 0x8395, 0x839F, 0x039A, 0x838B,
+    0x038E, 0x0384, 0x8381, 0x0280, 0x8285, 0x828F, 0x028A,
+    0x829B, 0x029E, 0x0294, 0x8291, 0x82B3, 0x02B6, 0x02BC,
+    0x82B9, 0x02A8, 0x82AD, 0x82A7, 0x02A2, 0x82E3, 0x02E6,
+    0x02EC, 0x82E9, 0x02F8, 0x82FD, 0x82F7, 0x02F2, 0x02D0,
+    0x82D5, 0x82DF, 0x02DA, 0x82CB, 0x02CE, 0x02C4, 0x82C1,
+    0x8243, 0x0246, 0x024C, 0x8249, 0x0258, 0x825D, 0x8257,
+    0x0252, 0x0270, 0x8275, 0x827F, 0x027A, 0x826B, 0x026E,
+    0x0264, 0x8261, 0x0220, 0x8225, 0x822F, 0x022A, 0x823B,
+    0x023E, 0x0234, 0x8231, 0x8213, 0x0216, 0x021C, 0x8219,
+    0x0208, 0x820D, 0x8207, 0x0202
+]  # fmt: skip
+
+# https://emanual.robotis.com/docs/en/dxl/protocol2/#instruction
+INSTRUCTION_TYPES = {
+    "Ping": 0x01,	                # Checks whether the Packet has arrived at a device with the same ID as the specified packet ID
+    "Read": 0x02,	                # Read data from the Device
+    "Write": 0x03,	                # Write data to the Device
+    "Reg_Write": 0x04,	            # Register the Instruction Packet in standby status; Packet can later be executed using the Action command
+    "Action": 0x05,	                # Executes a Packet that was registered beforehand using Reg Write
+    "Factory_Reset": 0x06,	        # Resets the Control Table to its initial factory default settings
+    "Reboot": 0x08,	                # Reboot the Device
+    "Clear": 0x10,	                # Reset certain information stored in memory
+    "Control_Table_Backup": 0x20,	# Store current Control Table status data to a Backup or to restore backup EEPROM data.
+    "Status": 0x55,	                # Return packet sent following the execution of an Instruction Packet
+    "Sync_Read": 0x82,	            # Read data from multiple devices with the same Address with the same length at once
+    "Sync_Write": 0x83,	            # Write data to multiple devices with the same Address with the same length at once
+    "Fast_Sync_Read": 0x8A,	        # Read data from multiple devices with the same Address with the same length at once
+    "Bulk_Read": 0x92,	            # Read data from multiple devices with different Addresses with different lengths at once
+    "Bulk_Write": 0x93,	            # Write data to multiple devices with different Addresses with different lengths at once
+    "Fast_Bulk_Read": 0x9A,	        # Read data from multiple devices with different Addresses with different lengths at once
+}  # fmt: skip
+
+# https://emanual.robotis.com/docs/en/dxl/protocol2/#error
+STATUS_TYPE = {
+    "Success": 0x00, 	        # No error
+    "Result_Fail": 0x01, 	    # Failed to process the sent Instruction Packet
+    "Instruction_Error": 0x02, 	# An undefined Instruction has been usedAction has been used without Reg Write
+    "CRC_Error": 0x03, 	        # The CRC of the sent Packet does not match the expected value
+    "Data_Range_Error": 0x04, 	# Data to be written to the specified Address is outside the range of the minimum/maximum value
+    "Data_Length_Error": 0x05, 	# Attempted to write Data that is shorter than the required data length of the specified Address
+                                #     (ex: when you attempt to only use 2 bytes of a register that has been defined as 4 bytes)
+    "Data_Limit_Error": 0x06,	# Data to be written to the specified Address is outside of the configured Limit value
+    "Access_Error": 0x07,	    # Attempted to write a value to an Address that is Read Only or has not been defined
+                                # Attempted to read a value from an Address that is Write Only or has not been defined
+                                # Attempted to write a value to an EEPROM register while Torque was Enabled.
+}  # fmt: skip
+
+
+class MockDynamixelPacketv2(abc.ABC):
+    @staticmethod
+    def _compute_crc(crc_accum: int, data_blk: list[int], data_blk_size: int) -> int:
+        for j in range(data_blk_size):
+            i = ((crc_accum >> 8) ^ data_blk[j]) & 0xFF
+            crc_accum = ((crc_accum << 8) ^ DXL_CRC_TABLE[i]) & 0xFFFF
+        return crc_accum
+
+    @classmethod
+    def build(cls, dxl_id: int, params: list[int], *args, **kwargs) -> bytes:
+        packet = cls._build(dxl_id, params, *args, **kwargs)
+        crc = cls._compute_crc(0, packet, len(packet) - 2)
+        packet[-2] = crc & 0xFF  # lower byte
+        packet[-1] = (crc >> 8) & 0xFF  # upper byte
+        return bytes(packet)
+
+    @abc.abstractclassmethod
+    def _build(cls, dxl_id: int, params: list[int], *args, **kwargs):
+        pass
+
+
+class MockInstructionPacket(MockDynamixelPacketv2):
+    """
+    Helper class to build valid Dynamixel Protocol 2.0 Instruction Packets with correct CRC.
+
+    Protocol 2.0 Instruction Packet structure
+    (from https://emanual.robotis.com/docs/en/dxl/protocol2/#instruction-packet)
+
+        0xFF 0xFF 0xFD 0x00    # 4-byte header
+        <servo_id>             # typically 0x01
+        <length L> <length H>  # 2-byte length of (instruction+error+params+CRC)
+        <instruction>          # instruction type
+        <parameters...>        # for a 4-byte read, we have 4 param bytes
+        <crc_low> <crc_high>   # 16-bit CRC
+    """
+
+    @classmethod
+    def _build(cls, dxl_id: int, params: list[int], instruct_type: str):
+        instruct_value = INSTRUCTION_TYPES[instruct_type]
+
+        # For Protocol 2.0, "length" = (number_of_params + 3),
+        #    where:
+        #        +1 is for <instruction> byte,
+        #        +2 is for the CRC at the end.
+        # The official Dynamixel SDK sometimes uses (+7) logic for sync reads
+        # because it includes special sub-parameters. But at core:
+        #    length = (instruction byte) + (len(params)) + (CRC16 =2).
+        packet_length = len(params) + 3
+        return bytearray(
+            [
+                0xFF, 0xFF, 0xFD, 0x00,         # header
+                dxl_id,                         # servo id
+                packet_length & 0xFF,           # length_l
+                (packet_length >> 8) & 0xFF,    # length_h
+                instruct_value,                 # instruction type
+                *params,                        # data bytes
+                0x00, 0x00                      # placeholder for CRC
+            ]
+        )  # fmt: skip
+
+    @classmethod
+    def sync_read(
+        cls,
+        dxl_ids: list[int],
+        start_address: int,
+        data_length: int,
+    ) -> bytes:
+        """
+        Helper method to build a "Sync Read" broadcast instruction.
+
+        The official SDK might add some “stuffing” or check param_length,
+        but this is enough for basic compliance if you want a raw packet.
+
+        The parameters for Sync Read (Protocol 2.0) are:
+            param[0]   = start_address L
+            param[1]   = start_address H
+            param[2]   = data_length L
+            param[3]   = data_length H
+            param[4+]  = motor IDs to read from
+        """
+        # Example param: [LowAddr, HighAddr, LowLen, HighLen, ID1, ID2, ...]
+        params = [
+            (start_address & 0xFF),
+            ((start_address >> 8) & 0xFF),
+            (data_length & 0xFF),
+            ((data_length >> 8) & 0xFF),
+        ] + dxl_ids
+
+        # broadcast ID: 0xFE
+        return cls.build(dxl_id=0xFE, instruct_type="Sync_Read", params=params)
+
+
+class MockStatusPacket(MockDynamixelPacketv2):
+    """
+    Helper class to build valid Dynamixel Protocol 2.0 Status Packets with correct CRC.
+
+    Protocol 2.0 Status Packet structure
+    (from https://emanual.robotis.com/docs/en/dxl/protocol2/#status-packet)
+
+        0xFF 0xFF 0xFD 0x00   # 4-byte header
+        <servo_id>            # typically 0x01
+        <length L> <length H> # 2-byte length of (instruction+error+params+CRC)
+        0x55                  # instruction = 0x55 means "status packet"
+        <error>               # 0 if no error
+        <parameters...>       # for a 4-byte read, we have 4 param bytes
+        <crc_low> <crc_high>  # 16-bit CRC
+    """
+
+    @classmethod
+    def _build(cls, dxl_id: int, params: list[int], status: str = "Success") -> bytearray:
+        status_byte = STATUS_TYPE[status]
+        return bytearray(
+            [
+                0xFF, 0xFF, 0xFD, 0x00,     # header
+                dxl_id,                     # servo id
+                0x08, 0x00,                 # length_l, length_h = 8
+                0x55,                       # instruction = status
+                status_byte,                # status
+                *params,                    # data bytes
+                0x00, 0x00                  # placeholder for CRC
+            ]
+        )  # fmt: skip
+
+    @classmethod
+    def present_position(cls, dxl_id: int, pos: int | None = None, min_max_range: tuple = (0, 4095)) -> bytes:
+        """Builds a 'Present_Position' packet.
+
+        Args:
+            pos (int | None, optional): Desired 'Present_Position'. If None, it will use a random value in the
+                min_max_range. Defaults to None.
+            min_max_range (tuple, optional): Min/max range to generate the position values used for when 'pos'
+                is None. Note that the bounds are included in the range. Defaults to (0, 4095).
+
+        Returns:
+            bytes: The raw 'Present_Position' status packet ready to be sent through serial.
+        """
+        pos = random.randint(*min_max_range) if pos is None else pos
+        # [lower pos 8 bits, higher pos 8 bits, 0, 0]
+        params = [pos & 0xFF, (pos >> 8) & 0xFF, 0, 0]
+        return cls.build(dxl_id, params)
+
+
+class MockPortHandler(dxl.PortHandler):
+    def setupPort(self, baud):  # noqa: N802
+        if self.is_open:
+            self.closePort()
+
+        self.ser = serial.Serial(
+            port=self.port_name,
+            # baudrate=self.baudrate,  <- This is forbidden for ttys ports (on macos at least)
+            # parity = serial.PARITY_ODD,
+            # stopbits = serial.STOPBITS_TWO,
+            bytesize=serial.EIGHTBITS,
+            timeout=0,
+        )
+        self.is_open = True
+        self.ser.reset_input_buffer()
+        self.tx_time_per_byte = (1000.0 / self.baudrate) * 10.0
+
+        return True
+
+
+class MockMotors(MockSerial):
+    ctrl_table = X_SERIES_CONTROL_TABLE
+
+    def __init__(self, dlx_ids: list[int], default_stubs: bool = True):
+        super().__init__()
+        self._ids = dlx_ids
+        self.open()
+
+        if default_stubs:
+            self._create_stubs("Present_Position")
+
+    def _create_stubs(self, data_name: str):
+        address, length = self.ctrl_table[data_name]
+
+        # sync read all motors
+        sync_read_request_all = MockInstructionPacket.sync_read(self._ids, address, length)
+        sync_read_response_all = self._create_present_pos_send_fn(self._ids, data_name)
+        self.stub(
+            name=f"SyncRead_{data_name}_all",
+            receive_bytes=sync_read_request_all,
+            send_fn=sync_read_response_all,
+        )
+
+        # sync read single motors
+        for idx in self._ids:
+            sync_read_request_single = MockInstructionPacket.sync_read([idx], address, length)
+            sync_read_response_single = self._create_present_pos_send_fn([idx], data_name)
+            self.stub(
+                name=f"SyncRead_{data_name}_{idx}",
+                receive_bytes=sync_read_request_single,
+                send_fn=sync_read_response_single,
+            )
+
+    def _create_present_pos_send_fn(
+        self, dxl_ids: list[int], data_name: str, num_invalid_try: int | None = None
+    ) -> Callable[[int], bytes]:
+        # if data_name == "Present_Position":
+        #     packet_generator = MockStatusPacket.present_position
+        # else:
+        #     # TODO(aliberts): add "Goal_Position"
+        #     raise NotImplementedError
+
+        def send_fn(_call_count: int) -> bytes:
+            if num_invalid_try is not None and num_invalid_try >= _call_count:
+                return bytes(0)
+
+            first_packet = MockStatusPacket.present_position(next(iter(dxl_ids)))
+            if len(dxl_ids) == 1:
+                return first_packet
+
+            packets = first_packet
+            for idx in dxl_ids:
+                packets += MockStatusPacket.present_position(dxl_id=idx)
+
+            return packets
+
+        return send_fn

From e4a6d035f990d7727f2e4acc9d7b93da52845981 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Wed, 19 Mar 2025 19:02:25 +0100
Subject: [PATCH 054/171] Remove Dxl mock sdk & update tests

---
 tests/mocks/mock_dynamixel_sdk.py | 133 -----------------------
 tests/motors/test_dynamixel.py    | 168 +++++++++++++++++++++++++-----
 2 files changed, 144 insertions(+), 157 deletions(-)
 delete mode 100644 tests/mocks/mock_dynamixel_sdk.py

diff --git a/tests/mocks/mock_dynamixel_sdk.py b/tests/mocks/mock_dynamixel_sdk.py
deleted file mode 100644
index 6212285e..00000000
--- a/tests/mocks/mock_dynamixel_sdk.py
+++ /dev/null
@@ -1,133 +0,0 @@
-# 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.
-
-# ruff: noqa: N802, E741
-
-"""
-Mocked classes and functions from dynamixel_sdk to allow for testing DynamixelMotorsBus code.
-
-Warning: These mocked versions are minimalist. They do not exactly mock every behaviors
-from the original classes and functions (e.g. return types might be None instead of boolean).
-"""
-
-DEFAULT_BAUDRATE = 9_600
-COMM_SUCCESS = 0  # tx or rx packet communication success
-
-
-def convert_to_bytes(value, bytes):
-    # TODO(rcadene): remove need to mock `convert_to_bytes` by implemented the inverse transform
-    # `convert_bytes_to_value`
-    del bytes  # unused
-    return value
-
-
-def get_default_motor_values(motor_index):
-    return {
-        # Key (int) are from X_SERIES_CONTROL_TABLE
-        7: motor_index,  # ID
-        8: DEFAULT_BAUDRATE,  # Baud_rate
-        10: 0,  # Drive_Mode
-        64: 0,  # Torque_Enable
-        # Set 2560 since calibration values for Aloha gripper is between start_pos=2499 and end_pos=3144
-        # For other joints, 2560 will be autocorrected to be in calibration range
-        132: 2560,  # Present_Position
-    }
-
-
-# Macro for Control Table Value
-def DXL_MAKEWORD(a, b):
-    return (a & 0xFF) | ((b & 0xFF) << 8)
-
-
-def DXL_MAKEDWORD(a, b):
-    return (a & 0xFFFF) | (b & 0xFFFF) << 16
-
-
-def DXL_LOWORD(l):
-    return l & 0xFFFF
-
-
-def DXL_HIWORD(l):
-    return (l >> 16) & 0xFFFF
-
-
-def DXL_LOBYTE(w):
-    return w & 0xFF
-
-
-def DXL_HIBYTE(w):
-    return (w >> 8) & 0xFF
-
-
-class PortHandler:
-    def __init__(self, port):
-        self.port = port
-        # factory default baudrate
-        self.baudrate = DEFAULT_BAUDRATE
-
-    def openPort(self):  # noqa: N802
-        return True
-
-    def closePort(self):  # noqa: N802
-        pass
-
-    def setPacketTimeoutMillis(self, timeout_ms):  # noqa: N802
-        del timeout_ms  # unused
-
-    def getBaudRate(self):  # noqa: N802
-        return self.baudrate
-
-    def setBaudRate(self, baudrate):  # noqa: N802
-        self.baudrate = baudrate
-
-
-class PacketHandler:
-    def __init__(self, protocol_version):
-        del protocol_version  # unused
-        # Use packet_handler.data to communicate across Read and Write
-        self.data = {}
-
-
-class GroupSyncRead:
-    def __init__(self, port_handler, packet_handler, address, bytes):
-        self.packet_handler = packet_handler
-
-    def addParam(self, motor_index):  # noqa: N802
-        # Initialize motor default values
-        if motor_index not in self.packet_handler.data:
-            self.packet_handler.data[motor_index] = get_default_motor_values(motor_index)
-
-    def txRxPacket(self):  # noqa: N802
-        return COMM_SUCCESS
-
-    def getData(self, index, address, bytes):  # noqa: N802
-        return self.packet_handler.data[index][address]
-
-
-class GroupSyncWrite:
-    def __init__(self, port_handler, packet_handler, address, bytes):
-        self.packet_handler = packet_handler
-        self.address = address
-
-    def addParam(self, index, data):  # noqa: N802
-        # Initialize motor default values
-        if index not in self.packet_handler.data:
-            self.packet_handler.data[index] = get_default_motor_values(index)
-        self.changeParam(index, data)
-
-    def txPacket(self):  # noqa: N802
-        return COMM_SUCCESS
-
-    def changeParam(self, index, data):  # noqa: N802
-        self.packet_handler.data[index][self.address] = data
diff --git a/tests/motors/test_dynamixel.py b/tests/motors/test_dynamixel.py
index 22cdef23..37bb0b46 100644
--- a/tests/motors/test_dynamixel.py
+++ b/tests/motors/test_dynamixel.py
@@ -1,21 +1,55 @@
-import sys
 from unittest.mock import patch
 
+import dynamixel_sdk as dxl
 import pytest
 
-from lerobot.common.motors.dynamixel import DynamixelMotorsBus
-from tests.mocks import mock_dynamixel_sdk
+from lerobot.common.motors.dynamixel.dynamixel import DynamixelMotorsBus
+from tests.mocks.mock_dynamixel import MockInstructionPacket, MockMotors, MockPortHandler
 
 
 @pytest.fixture(autouse=True)
-def patch_dynamixel_sdk():
-    with patch.dict(sys.modules, {"dynamixel_sdk": mock_dynamixel_sdk}):
-        yield
+def patch_port_handler():
+    with patch.object(dxl, "PortHandler", MockPortHandler):
+        yield  # Patch is applied for the duration of each test
 
 
-def test_patch_sdk():
-    assert "dynamixel_sdk" in sys.modules  # Should be patched
-    assert sys.modules["dynamixel_sdk"] is mock_dynamixel_sdk  # Should match the mock
+def test_autouse_patch():
+    """Ensure that the autouse fixture correctly patches dxl.PortHandler with MockPortHandler."""
+    assert dxl.PortHandler is MockPortHandler
+
+
+@pytest.mark.parametrize(
+    "value, n_bytes, expected",
+    [
+        (0x12,       1, [0x12]),                    # Single byte
+        (0x1234,     2, [0x34, 0x12]),              # Two bytes
+        (0x12345678, 4, [0x78, 0x56, 0x34, 0x12]),  # Four bytes
+        (0,          1, [0x00]),                    # Zero with 1 byte
+        (0,          2, [0x00, 0x00]),              # Zero with 2 bytes
+        (0,          4, [0x00, 0x00, 0x00, 0x00]),  # Zero with 4 bytes
+        (255,        1, [0xFF]),                    # Max single byte
+        (65535,      2, [0xFF, 0xFF]),              # Max two bytes
+        (4294967295, 4, [0xFF, 0xFF, 0xFF, 0xFF]),  # Max four bytes
+    ],
+)  # fmt: skip
+def test_split_int_bytes(value, n_bytes, expected):
+    assert DynamixelMotorsBus.split_int_bytes(value, n_bytes) == expected
+
+
+def test_split_int_bytes_invalid_n_bytes():
+    with pytest.raises(NotImplementedError):
+        DynamixelMotorsBus.split_int_bytes(100, 3)
+
+
+def test_split_int_bytes_negative_numbers():
+    with pytest.raises(ValueError):
+        neg = DynamixelMotorsBus.split_int_bytes(-1, 1)
+        print(neg)
+
+
+def test_split_int_bytes_large_number():
+    with pytest.raises(ValueError):
+        DynamixelMotorsBus.split_int_bytes(2**32, 4)  # 4-byte max is 0xFFFFFFFF
 
 
 def test_abc_implementation():
@@ -23,22 +57,108 @@ def test_abc_implementation():
     DynamixelMotorsBus(port="/dev/dummy-port", motors={"dummy": (1, "xl330-m077")})
 
 
-def test_configure_motors_all_ids_1():
-    # see X_SERIES_BAUDRATE_TABLE
-    smaller_baudrate = 9_600
-    smaller_baudrate_value = 0
-
-    # This test expect the configuration was already correct.
-    motors_bus = DynamixelMotorsBus(port="/dev/dummy-port", motors={"dummy": (1, "xl330-m077")})
+@pytest.mark.parametrize(
+    "motors",
+    [
+        None,
+        [1, 2, 3],
+        ["dummy_1", "dummy_2", "dummy_3"],
+        [1, "dummy_2", 3],  # Mixed
+    ],
+)
+def test_read_all_motors(motors):
+    mock_motors = MockMotors([1, 2, 3])
+    motors_bus = DynamixelMotorsBus(
+        port=mock_motors.port,
+        motors={
+            "dummy_1": (1, "xl330-m077"),
+            "dummy_2": (2, "xl330-m077"),
+            "dummy_3": (3, "xl330-m077"),
+        },
+    )
     motors_bus.connect()
-    motors_bus.write("Baud_Rate", [smaller_baudrate_value] * len(motors_bus))
 
-    motors_bus.set_baudrate(smaller_baudrate)
-    motors_bus.write("ID", [1] * len(motors_bus))
-    del motors_bus
+    pos_dict = motors_bus.read("Present_Position", motors=motors)
 
-    # Test configure
-    motors_bus = DynamixelMotorsBus(port="/dev/dummy-port", motors={"dummy": (1, "xl330-m077")})
+    assert mock_motors.stubs["SyncRead_Present_Position_all"].called
+    assert len(pos_dict) == 3
+    assert all(pos >= 0 and pos <= 4095 for pos in pos_dict.values())
+
+
+@pytest.mark.parametrize("idx", [1, 2, 3])
+def test_read_single_motor_name(idx):
+    mock_motors = MockMotors([1, 2, 3])
+    motors_bus = DynamixelMotorsBus(
+        port=mock_motors.port,
+        motors={
+            "dummy_1": (1, "xl330-m077"),
+            "dummy_2": (2, "xl330-m077"),
+            "dummy_3": (3, "xl330-m077"),
+        },
+    )
     motors_bus.connect()
-    assert motors_bus.are_motors_configured()
-    del motors_bus
+
+    pos_dict = motors_bus.read("Present_Position", f"dummy_{idx}")
+
+    assert mock_motors.stubs[f"SyncRead_Present_Position_{idx}"].called
+    assert len(pos_dict) == 1
+    assert all(pos >= 0 and pos <= 4095 for pos in pos_dict.values())
+
+
+@pytest.mark.parametrize("idx", [1, 2, 3])
+def test_read_single_motor_id(idx):
+    mock_motors = MockMotors([1, 2, 3])
+    motors_bus = DynamixelMotorsBus(
+        port=mock_motors.port,
+        motors={
+            "dummy_1": (1, "xl330-m077"),
+            "dummy_2": (2, "xl330-m077"),
+            "dummy_3": (3, "xl330-m077"),
+        },
+    )
+    motors_bus.connect()
+
+    pos_dict = motors_bus.read("Present_Position", idx)
+
+    assert mock_motors.stubs[f"SyncRead_Present_Position_{idx}"].called
+    assert len(pos_dict) == 1
+    assert all(pos >= 0 and pos <= 4095 for pos in pos_dict.values())
+
+
+@pytest.mark.parametrize(
+    "num_retry, num_invalid_try",
+    [
+        [1, 2],
+        [2, 3],
+        [3, 2],
+        [2, 1],
+    ],
+)
+def test_read_num_retry(num_retry, num_invalid_try):
+    mock_motors = MockMotors([1, 2, 3], default_stubs=None)
+    address, length = mock_motors.ctrl_table["Present_Position"]
+    receive_bytes = MockInstructionPacket.sync_read([1], address, length)
+    send_fn = mock_motors._create_present_pos_send_fn(
+        [1], "Present_Position", num_invalid_try=num_invalid_try
+    )
+    mock_motors.stub(name="num_retry", receive_bytes=receive_bytes, send_fn=send_fn)
+
+    motors_bus = DynamixelMotorsBus(
+        port=mock_motors.port,
+        motors={
+            "dummy_1": (1, "xl330-m077"),
+            "dummy_2": (2, "xl330-m077"),
+            "dummy_3": (3, "xl330-m077"),
+        },
+    )
+    motors_bus.connect()
+
+    if num_retry >= num_invalid_try:
+        pos_dict = motors_bus.read("Present_Position", 1, num_retry=num_retry)
+        assert len(pos_dict) == 1
+        assert all(pos >= 0 and pos <= 4095 for pos in pos_dict.values())
+    else:
+        with pytest.raises(ConnectionError):
+            _ = motors_bus.read("Present_Position", 1, num_retry=num_retry)
+
+    assert mock_motors.stubs["num_retry"].calls == num_retry

From 6a77189f50cd236ca88214ed8931264e1770f8f6 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Wed, 19 Mar 2025 19:02:58 +0100
Subject: [PATCH 055/171] Fix import

---
 lerobot/common/motors/dynamixel/__init__.py | 4 ++--
 1 file changed, 2 insertions(+), 2 deletions(-)

diff --git a/lerobot/common/motors/dynamixel/__init__.py b/lerobot/common/motors/dynamixel/__init__.py
index 77c4bd00..cd86bca1 100644
--- a/lerobot/common/motors/dynamixel/__init__.py
+++ b/lerobot/common/motors/dynamixel/__init__.py
@@ -1,4 +1,4 @@
-from .dynamixel import DynamixelMotorsBus, set_operating_mode
+from .dynamixel import DynamixelMotorsBus
 from .dynamixel_calibration import run_arm_calibration
 
-__all__ = ["DynamixelMotorsBus", "set_operating_mode", "run_arm_calibration"]
+__all__ = ["DynamixelMotorsBus", "run_arm_calibration"]

From f527adf7a9998d77103928457cc0fce976150ef6 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Wed, 19 Mar 2025 19:03:34 +0100
Subject: [PATCH 056/171] Add mock-serial

---
 pyproject.toml | 4 ++--
 1 file changed, 2 insertions(+), 2 deletions(-)

diff --git a/pyproject.toml b/pyproject.toml
index f1f836b4..d810517a 100644
--- a/pyproject.toml
+++ b/pyproject.toml
@@ -53,7 +53,7 @@ dependencies = [
     "einops>=0.8.0",
     "flask>=3.0.3",
     "gdown>=5.1.0",
-    "gymnasium==0.29.1",                                                 # TODO(rcadene, aliberts): Make gym 1.0.0 work
+    "gymnasium==0.29.1", # TODO(rcadene, aliberts): Make gym 1.0.0 work
     "h5py>=3.10.0",
     "huggingface-hub[hf-transfer,cli]>=0.27.1 ; python_version < '4.0'",
     "imageio[ffmpeg]>=2.34.0",
@@ -92,7 +92,7 @@ stretch = [
     "pyrealsense2>=2.55.1.6486 ; sys_platform != 'darwin'",
     "pynput>=1.7.7",
 ]
-test = ["pytest>=8.1.0", "pytest-cov>=5.0.0", "pyserial>=3.5"]
+test = ["pytest>=8.1.0", "pytest-cov>=5.0.0", "pyserial>=3.5", "mock-serial>=0.0.1 ; sys_platform != 'win32'"]
 umi = ["imagecodecs>=2024.1.1"]
 video_benchmark = ["scikit-image>=0.23.2", "pandas>=2.2.2"]
 xarm = ["gym-xarm>=0.1.1 ; python_version < '4.0'"]

From 64ce2669ca5cf186342b503edae19db05310d49a Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Thu, 20 Mar 2025 09:33:33 +0100
Subject: [PATCH 057/171] Add bytes stuffing

---
 tests/mocks/mock_dynamixel.py | 67 +++++++++++++++++++++++++++++------
 1 file changed, 56 insertions(+), 11 deletions(-)

diff --git a/tests/mocks/mock_dynamixel.py b/tests/mocks/mock_dynamixel.py
index 8176d766..57f58d6f 100644
--- a/tests/mocks/mock_dynamixel.py
+++ b/tests/mocks/mock_dynamixel.py
@@ -86,25 +86,70 @@ STATUS_TYPE = {
 
 
 class MockDynamixelPacketv2(abc.ABC):
-    @staticmethod
-    def _compute_crc(crc_accum: int, data_blk: list[int], data_blk_size: int) -> int:
-        for j in range(data_blk_size):
-            i = ((crc_accum >> 8) ^ data_blk[j]) & 0xFF
-            crc_accum = ((crc_accum << 8) ^ DXL_CRC_TABLE[i]) & 0xFFFF
-        return crc_accum
-
     @classmethod
     def build(cls, dxl_id: int, params: list[int], *args, **kwargs) -> bytes:
         packet = cls._build(dxl_id, params, *args, **kwargs)
-        crc = cls._compute_crc(0, packet, len(packet) - 2)
-        packet[-2] = crc & 0xFF  # lower byte
-        packet[-1] = (crc >> 8) & 0xFF  # upper byte
+        packet = cls._add_stuffing(packet)
+        packet = cls._add_crc(packet)
         return bytes(packet)
 
     @abc.abstractclassmethod
-    def _build(cls, dxl_id: int, params: list[int], *args, **kwargs):
+    def _build(cls, dxl_id: int, params: list[int], *args, **kwargs) -> bytearray:
         pass
 
+    @staticmethod
+    def _add_stuffing(packet: bytearray) -> bytearray:
+        packet_length_in = dxl.DXL_MAKEWORD(packet[dxl.PKT_LENGTH_L], packet[dxl.PKT_LENGTH_H])
+        packet_length_out = packet_length_in
+
+        temp = [0] * dxl.TXPACKET_MAX_LEN
+
+        # FF FF FD XX ID LEN_L LEN_H
+        temp[dxl.PKT_HEADER0 : dxl.PKT_HEADER0 + dxl.PKT_LENGTH_H + 1] = packet[
+            dxl.PKT_HEADER0 : dxl.PKT_HEADER0 + dxl.PKT_LENGTH_H + 1
+        ]
+
+        index = dxl.PKT_INSTRUCTION
+
+        for i in range(0, packet_length_in - 2):  # except CRC
+            temp[index] = packet[i + dxl.PKT_INSTRUCTION]
+            index = index + 1
+            if (
+                packet[i + dxl.PKT_INSTRUCTION] == 0xFD
+                and packet[i + dxl.PKT_INSTRUCTION - 1] == 0xFF
+                and packet[i + dxl.PKT_INSTRUCTION - 2] == 0xFF
+            ):
+                # FF FF FD
+                temp[index] = 0xFD
+                index = index + 1
+                packet_length_out = packet_length_out + 1
+
+        temp[index] = packet[dxl.PKT_INSTRUCTION + packet_length_in - 2]
+        temp[index + 1] = packet[dxl.PKT_INSTRUCTION + packet_length_in - 1]
+        index = index + 2
+
+        if packet_length_in != packet_length_out:
+            packet = [0] * index
+
+        packet[0:index] = temp[0:index]
+
+        packet[dxl.PKT_LENGTH_L] = dxl.DXL_LOBYTE(packet_length_out)
+        packet[dxl.PKT_LENGTH_H] = dxl.DXL_HIBYTE(packet_length_out)
+
+        return packet
+
+    @staticmethod
+    def _add_crc(packet: bytearray) -> int:
+        crc = 0
+        for j in range(len(packet) - 2):
+            i = ((crc >> 8) ^ packet[j]) & 0xFF
+            crc = ((crc << 8) ^ DXL_CRC_TABLE[i]) & 0xFFFF
+
+        packet[-2] = dxl.DXL_LOBYTE(crc)
+        packet[-1] = dxl.DXL_HIBYTE(crc)
+
+        return packet
+
 
 class MockInstructionPacket(MockDynamixelPacketv2):
     """

From 2d56f350711564276fadd11017ae25082b8e0f0f Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Thu, 20 Mar 2025 09:36:17 +0100
Subject: [PATCH 058/171] Improve formats & docstrings

---
 tests/mocks/mock_dynamixel.py | 106 +++++++++++++++-------------------
 1 file changed, 48 insertions(+), 58 deletions(-)

diff --git a/tests/mocks/mock_dynamixel.py b/tests/mocks/mock_dynamixel.py
index 57f58d6f..baf5a0ab 100644
--- a/tests/mocks/mock_dynamixel.py
+++ b/tests/mocks/mock_dynamixel.py
@@ -51,34 +51,34 @@ DXL_CRC_TABLE = [
 
 # https://emanual.robotis.com/docs/en/dxl/protocol2/#instruction
 INSTRUCTION_TYPES = {
-    "Ping": 0x01,	                # Checks whether the Packet has arrived at a device with the same ID as the specified packet ID
-    "Read": 0x02,	                # Read data from the Device
-    "Write": 0x03,	                # Write data to the Device
-    "Reg_Write": 0x04,	            # Register the Instruction Packet in standby status; Packet can later be executed using the Action command
-    "Action": 0x05,	                # Executes a Packet that was registered beforehand using Reg Write
-    "Factory_Reset": 0x06,	        # Resets the Control Table to its initial factory default settings
-    "Reboot": 0x08,	                # Reboot the Device
-    "Clear": 0x10,	                # Reset certain information stored in memory
-    "Control_Table_Backup": 0x20,	# Store current Control Table status data to a Backup or to restore backup EEPROM data.
-    "Status": 0x55,	                # Return packet sent following the execution of an Instruction Packet
-    "Sync_Read": 0x82,	            # Read data from multiple devices with the same Address with the same length at once
-    "Sync_Write": 0x83,	            # Write data to multiple devices with the same Address with the same length at once
-    "Fast_Sync_Read": 0x8A,	        # Read data from multiple devices with the same Address with the same length at once
-    "Bulk_Read": 0x92,	            # Read data from multiple devices with different Addresses with different lengths at once
-    "Bulk_Write": 0x93,	            # Write data to multiple devices with different Addresses with different lengths at once
-    "Fast_Bulk_Read": 0x9A,	        # Read data from multiple devices with different Addresses with different lengths at once
+    "Ping": 0x01,	               # Checks whether the Packet has arrived at a device with the same ID as the specified packet ID
+    "Read": 0x02,	               # Read data from the Device
+    "Write": 0x03,	               # Write data to the Device
+    "Reg_Write": 0x04,	           # Register the Instruction Packet in standby status; Packet can later be executed using the Action command
+    "Action": 0x05,	               # Executes a Packet that was registered beforehand using Reg Write
+    "Factory_Reset": 0x06,	       # Resets the Control Table to its initial factory default settings
+    "Reboot": 0x08,	               # Reboot the Device
+    "Clear": 0x10,	               # Reset certain information stored in memory
+    "Control_Table_Backup": 0x20,  # Store current Control Table status data to a Backup or to restore backup EEPROM data.
+    "Status": 0x55,	               # Return packet sent following the execution of an Instruction Packet
+    "Sync_Read": 0x82,	           # Read data from multiple devices with the same Address with the same length at once
+    "Sync_Write": 0x83,	           # Write data to multiple devices with the same Address with the same length at once
+    "Fast_Sync_Read": 0x8A,	       # Read data from multiple devices with the same Address with the same length at once
+    "Bulk_Read": 0x92,	           # Read data from multiple devices with different Addresses with different lengths at once
+    "Bulk_Write": 0x93,	           # Write data to multiple devices with different Addresses with different lengths at once
+    "Fast_Bulk_Read": 0x9A,	       # Read data from multiple devices with different Addresses with different lengths at once
 }  # fmt: skip
 
 # https://emanual.robotis.com/docs/en/dxl/protocol2/#error
-STATUS_TYPE = {
+ERROR_TYPE = {
     "Success": 0x00, 	        # No error
     "Result_Fail": 0x01, 	    # Failed to process the sent Instruction Packet
-    "Instruction_Error": 0x02, 	# An undefined Instruction has been usedAction has been used without Reg Write
+    "Instruction_Error": 0x02,  # An undefined Instruction has been usedAction has been used without Reg Write
     "CRC_Error": 0x03, 	        # The CRC of the sent Packet does not match the expected value
-    "Data_Range_Error": 0x04, 	# Data to be written to the specified Address is outside the range of the minimum/maximum value
-    "Data_Length_Error": 0x05, 	# Attempted to write Data that is shorter than the required data length of the specified Address
+    "Data_Range_Error": 0x04,   # Data to be written to the specified Address is outside the range of the minimum/maximum value
+    "Data_Length_Error": 0x05,  # Attempted to write Data that is shorter than the required data length of the specified Address
                                 #     (ex: when you attempt to only use 2 bytes of a register that has been defined as 4 bytes)
-    "Data_Limit_Error": 0x06,	# Data to be written to the specified Address is outside of the configured Limit value
+    "Data_Limit_Error": 0x06,   # Data to be written to the specified Address is outside of the configured Limit value
     "Access_Error": 0x07,	    # Attempted to write a value to an Address that is Read Only or has not been defined
                                 # Attempted to read a value from an Address that is Write Only or has not been defined
                                 # Attempted to write a value to an EEPROM register while Torque was Enabled.
@@ -153,17 +153,15 @@ class MockDynamixelPacketv2(abc.ABC):
 
 class MockInstructionPacket(MockDynamixelPacketv2):
     """
-    Helper class to build valid Dynamixel Protocol 2.0 Instruction Packets with correct CRC.
+    Helper class to build valid Dynamixel Protocol 2.0 Instruction Packets.
 
     Protocol 2.0 Instruction Packet structure
     (from https://emanual.robotis.com/docs/en/dxl/protocol2/#instruction-packet)
 
-        0xFF 0xFF 0xFD 0x00    # 4-byte header
-        <servo_id>             # typically 0x01
-        <length L> <length H>  # 2-byte length of (instruction+error+params+CRC)
-        <instruction>          # instruction type
-        <parameters...>        # for a 4-byte read, we have 4 param bytes
-        <crc_low> <crc_high>   # 16-bit CRC
+    | Header              | Packet ID | Length      | Instruction | Params            | CRC         |
+    | ------------------- | --------- | ----------- | ----------- | ----------------- | ----------- |
+    | 0xFF 0xFF 0xFD 0x00 | ID        | Len_L Len_H | Instr       | Param 1 … Param N | CRC_L CRC_H |
+
     """
 
     @classmethod
@@ -182,8 +180,8 @@ class MockInstructionPacket(MockDynamixelPacketv2):
             [
                 0xFF, 0xFF, 0xFD, 0x00,         # header
                 dxl_id,                         # servo id
-                packet_length & 0xFF,           # length_l
-                (packet_length >> 8) & 0xFF,    # length_h
+                dxl.DXL_LOBYTE(packet_length),  # length_l
+                dxl.DXL_HIBYTE(packet_length),  # length_h
                 instruct_value,                 # instruction type
                 *params,                        # data bytes
                 0x00, 0x00                      # placeholder for CRC
@@ -198,10 +196,8 @@ class MockInstructionPacket(MockDynamixelPacketv2):
         data_length: int,
     ) -> bytes:
         """
-        Helper method to build a "Sync Read" broadcast instruction.
-
-        The official SDK might add some “stuffing” or check param_length,
-        but this is enough for basic compliance if you want a raw packet.
+        Helper method to build a Sync Read broadcast instruction.
+        (from https://emanual.robotis.com/docs/en/dxl/protocol2/#sync-read-0x82)
 
         The parameters for Sync Read (Protocol 2.0) are:
             param[0]   = start_address L
@@ -210,46 +206,40 @@ class MockInstructionPacket(MockDynamixelPacketv2):
             param[3]   = data_length H
             param[4+]  = motor IDs to read from
         """
-        # Example param: [LowAddr, HighAddr, LowLen, HighLen, ID1, ID2, ...]
         params = [
-            (start_address & 0xFF),
-            ((start_address >> 8) & 0xFF),
-            (data_length & 0xFF),
-            ((data_length >> 8) & 0xFF),
+            dxl.DXL_LOBYTE(start_address),
+            dxl.DXL_HIBYTE(start_address),
+            dxl.DXL_LOBYTE(data_length),
+            dxl.DXL_HIBYTE(data_length),
         ] + dxl_ids
 
-        # broadcast ID: 0xFE
-        return cls.build(dxl_id=0xFE, instruct_type="Sync_Read", params=params)
+        return cls.build(dxl_id=dxl.BROADCAST_ID, instruct_type="Sync_Read", params=params)
 
 
 class MockStatusPacket(MockDynamixelPacketv2):
     """
-    Helper class to build valid Dynamixel Protocol 2.0 Status Packets with correct CRC.
+    Helper class to build valid Dynamixel Protocol 2.0 Status Packets.
 
     Protocol 2.0 Status Packet structure
     (from https://emanual.robotis.com/docs/en/dxl/protocol2/#status-packet)
 
-        0xFF 0xFF 0xFD 0x00   # 4-byte header
-        <servo_id>            # typically 0x01
-        <length L> <length H> # 2-byte length of (instruction+error+params+CRC)
-        0x55                  # instruction = 0x55 means "status packet"
-        <error>               # 0 if no error
-        <parameters...>       # for a 4-byte read, we have 4 param bytes
-        <crc_low> <crc_high>  # 16-bit CRC
+    | Header              | Packet ID | Length      | Instruction | Error | Params            | CRC         |
+    | ------------------- | --------- | ----------- | ----------- | ----- | ----------------- | ----------- |
+    | 0xFF 0xFF 0xFD 0x00 | ID        | Len_L Len_H | 0x55        | Err   | Param 1 … Param N | CRC_L CRC_H |
     """
 
     @classmethod
-    def _build(cls, dxl_id: int, params: list[int], status: str = "Success") -> bytearray:
-        status_byte = STATUS_TYPE[status]
+    def _build(cls, dxl_id: int, params: list[int], error: str = "Success") -> bytearray:
+        err_byte = ERROR_TYPE[error]
         return bytearray(
             [
-                0xFF, 0xFF, 0xFD, 0x00,     # header
-                dxl_id,                     # servo id
-                0x08, 0x00,                 # length_l, length_h = 8
-                0x55,                       # instruction = status
-                status_byte,                # status
-                *params,                    # data bytes
-                0x00, 0x00                  # placeholder for CRC
+                0xFF, 0xFF, 0xFD, 0x00,  # header
+                dxl_id,                  # servo id
+                0x08, 0x00,              # length_l, length_h = 8
+                0x55,                    # instruction = 'status'
+                err_byte,                # error
+                *params,                 # data bytes
+                0x00, 0x00               # placeholder for CRC
             ]
         )  # fmt: skip
 

From c1c71fb994627457a18e4820637aa9f6250b64ca Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Thu, 20 Mar 2025 09:38:36 +0100
Subject: [PATCH 059/171] Ignore patching when not on MacOS

---
 tests/mocks/mock_dynamixel.py  |  9 +++++++--
 tests/motors/test_dynamixel.py | 11 ++++++++---
 2 files changed, 15 insertions(+), 5 deletions(-)

diff --git a/tests/mocks/mock_dynamixel.py b/tests/mocks/mock_dynamixel.py
index baf5a0ab..5549cf18 100644
--- a/tests/mocks/mock_dynamixel.py
+++ b/tests/mocks/mock_dynamixel.py
@@ -263,13 +263,18 @@ class MockStatusPacket(MockDynamixelPacketv2):
 
 
 class MockPortHandler(dxl.PortHandler):
-    def setupPort(self, baud):  # noqa: N802
+    """
+    This class overwrite the 'setupPort' method of the dynamixel PortHandler because it can specify
+    baudrates that are not supported with a serial port on MacOS.
+    """
+
+    def setupPort(self, cflag_baud):  # noqa: N802
         if self.is_open:
             self.closePort()
 
         self.ser = serial.Serial(
             port=self.port_name,
-            # baudrate=self.baudrate,  <- This is forbidden for ttys ports (on macos at least)
+            # baudrate=self.baudrate,  <- This will fail on MacOS
             # parity = serial.PARITY_ODD,
             # stopbits = serial.STOPBITS_TWO,
             bytesize=serial.EIGHTBITS,
diff --git a/tests/motors/test_dynamixel.py b/tests/motors/test_dynamixel.py
index 37bb0b46..77f6bd73 100644
--- a/tests/motors/test_dynamixel.py
+++ b/tests/motors/test_dynamixel.py
@@ -1,3 +1,4 @@
+import sys
 from unittest.mock import patch
 
 import dynamixel_sdk as dxl
@@ -9,12 +10,16 @@ from tests.mocks.mock_dynamixel import MockInstructionPacket, MockMotors, MockPo
 
 @pytest.fixture(autouse=True)
 def patch_port_handler():
-    with patch.object(dxl, "PortHandler", MockPortHandler):
-        yield  # Patch is applied for the duration of each test
+    if sys.platform == "darwin":
+        with patch.object(dxl, "PortHandler", MockPortHandler):
+            yield
+    else:
+        yield
 
 
+@pytest.mark.skipif(sys.platform != "darwin", reason=f"No patching needed on {sys.platform=}")
 def test_autouse_patch():
-    """Ensure that the autouse fixture correctly patches dxl.PortHandler with MockPortHandler."""
+    """Ensures that the autouse fixture correctly patches dxl.PortHandler with MockPortHandler."""
     assert dxl.PortHandler is MockPortHandler
 
 

From 2c1bb766ffd3836e7ec5d87075952db023d68ff4 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Thu, 20 Mar 2025 09:40:58 +0100
Subject: [PATCH 060/171] Refactor MockMotors, add return values

---
 tests/mocks/mock_dynamixel.py  | 81 ++++++++++++++++++++--------------
 tests/motors/test_dynamixel.py | 63 ++++++++++++++++----------
 2 files changed, 86 insertions(+), 58 deletions(-)

diff --git a/tests/mocks/mock_dynamixel.py b/tests/mocks/mock_dynamixel.py
index 5549cf18..cccc3c20 100644
--- a/tests/mocks/mock_dynamixel.py
+++ b/tests/mocks/mock_dynamixel.py
@@ -288,59 +288,72 @@ class MockPortHandler(dxl.PortHandler):
 
 
 class MockMotors(MockSerial):
+    """
+    This class will simulate physical motors by responding with valid status packets upon receiving some
+    instruction packets. It is meant to test MotorsBus classes.
+
+    'data_name' supported:
+        - Present_Position
+    """
+
     ctrl_table = X_SERIES_CONTROL_TABLE
 
-    def __init__(self, dlx_ids: list[int], default_stubs: bool = True):
+    def __init__(self, dlx_ids: list[int]):
         super().__init__()
         self._ids = dlx_ids
         self.open()
 
-        if default_stubs:
-            self._create_stubs("Present_Position")
-
-    def _create_stubs(self, data_name: str):
+    def build_single_motor_stubs(
+        self, data_name: str, return_value: int | None = None, num_invalid_try: int | None = None
+    ) -> None:
         address, length = self.ctrl_table[data_name]
-
-        # sync read all motors
-        sync_read_request_all = MockInstructionPacket.sync_read(self._ids, address, length)
-        sync_read_response_all = self._create_present_pos_send_fn(self._ids, data_name)
-        self.stub(
-            name=f"SyncRead_{data_name}_all",
-            receive_bytes=sync_read_request_all,
-            send_fn=sync_read_response_all,
-        )
-
-        # sync read single motors
         for idx in self._ids:
-            sync_read_request_single = MockInstructionPacket.sync_read([idx], address, length)
-            sync_read_response_single = self._create_present_pos_send_fn([idx], data_name)
+            if data_name == "Present_Position":
+                sync_read_request_single = MockInstructionPacket.sync_read([idx], address, length)
+                sync_read_response_single = self._build_present_pos_send_fn(
+                    [idx], [return_value], num_invalid_try
+                )
+            else:
+                raise NotImplementedError  # TODO(aliberts): add ping?
+
             self.stub(
                 name=f"SyncRead_{data_name}_{idx}",
                 receive_bytes=sync_read_request_single,
                 send_fn=sync_read_response_single,
             )
 
-    def _create_present_pos_send_fn(
-        self, dxl_ids: list[int], data_name: str, num_invalid_try: int | None = None
+    def build_all_motors_stub(
+        self, data_name: str, return_values: list[int] | None = None, num_invalid_try: int | None = None
+    ) -> None:
+        address, length = self.ctrl_table[data_name]
+        if data_name == "Present_Position":
+            sync_read_request_all = MockInstructionPacket.sync_read(self._ids, address, length)
+            sync_read_response_all = self._build_present_pos_send_fn(
+                self._ids, return_values, num_invalid_try
+            )
+        else:
+            raise NotImplementedError  # TODO(aliberts): add ping?
+
+        self.stub(
+            name=f"SyncRead_{data_name}_all",
+            receive_bytes=sync_read_request_all,
+            send_fn=sync_read_response_all,
+        )
+
+    def _build_present_pos_send_fn(
+        self, dxl_ids: list[int], return_pos: list[int] | None = None, num_invalid_try: int | None = None
     ) -> Callable[[int], bytes]:
-        # if data_name == "Present_Position":
-        #     packet_generator = MockStatusPacket.present_position
-        # else:
-        #     # TODO(aliberts): add "Goal_Position"
-        #     raise NotImplementedError
+        return_pos = [None for _ in dxl_ids] if return_pos is None else return_pos
+        assert len(return_pos) == len(dxl_ids)
 
         def send_fn(_call_count: int) -> bytes:
             if num_invalid_try is not None and num_invalid_try >= _call_count:
-                return bytes(0)
-
-            first_packet = MockStatusPacket.present_position(next(iter(dxl_ids)))
-            if len(dxl_ids) == 1:
-                return first_packet
-
-            packets = first_packet
-            for idx in dxl_ids:
-                packets += MockStatusPacket.present_position(dxl_id=idx)
+                return b""
 
+            packets = b"".join(
+                MockStatusPacket.present_position(idx, pos)
+                for idx, pos in zip(dxl_ids, return_pos, strict=True)
+            )
             return packets
 
         return send_fn
diff --git a/tests/motors/test_dynamixel.py b/tests/motors/test_dynamixel.py
index 77f6bd73..afdeb7f9 100644
--- a/tests/motors/test_dynamixel.py
+++ b/tests/motors/test_dynamixel.py
@@ -5,7 +5,7 @@ import dynamixel_sdk as dxl
 import pytest
 
 from lerobot.common.motors.dynamixel.dynamixel import DynamixelMotorsBus
-from tests.mocks.mock_dynamixel import MockInstructionPacket, MockMotors, MockPortHandler
+from tests.mocks.mock_dynamixel import MockMotors, MockPortHandler
 
 
 @pytest.fixture(autouse=True)
@@ -68,11 +68,13 @@ def test_abc_implementation():
         None,
         [1, 2, 3],
         ["dummy_1", "dummy_2", "dummy_3"],
-        [1, "dummy_2", 3],  # Mixed
+        [1, "dummy_2", 3],
     ],
 )
 def test_read_all_motors(motors):
     mock_motors = MockMotors([1, 2, 3])
+    positions = [1337, 42, 4016]
+    mock_motors.build_all_motors_stub("Present_Position", return_values=positions)
     motors_bus = DynamixelMotorsBus(
         port=mock_motors.port,
         motors={
@@ -86,13 +88,22 @@ def test_read_all_motors(motors):
     pos_dict = motors_bus.read("Present_Position", motors=motors)
 
     assert mock_motors.stubs["SyncRead_Present_Position_all"].called
-    assert len(pos_dict) == 3
+    assert all(returned_pos == pos for returned_pos, pos in zip(pos_dict.values(), positions, strict=True))
+    assert set(pos_dict) == {"dummy_1", "dummy_2", "dummy_3"}
     assert all(pos >= 0 and pos <= 4095 for pos in pos_dict.values())
 
 
-@pytest.mark.parametrize("idx", [1, 2, 3])
-def test_read_single_motor_name(idx):
+@pytest.mark.parametrize(
+    "idx, pos",
+    [
+        [1, 1337],
+        [2, 42],
+        [3, 4016],
+    ],
+)
+def test_read_single_motor_by_name(idx, pos):
     mock_motors = MockMotors([1, 2, 3])
+    mock_motors.build_single_motor_stubs("Present_Position", return_value=pos)
     motors_bus = DynamixelMotorsBus(
         port=mock_motors.port,
         motors={
@@ -106,13 +117,21 @@ def test_read_single_motor_name(idx):
     pos_dict = motors_bus.read("Present_Position", f"dummy_{idx}")
 
     assert mock_motors.stubs[f"SyncRead_Present_Position_{idx}"].called
-    assert len(pos_dict) == 1
+    assert pos_dict == {f"dummy_{idx}": pos}
     assert all(pos >= 0 and pos <= 4095 for pos in pos_dict.values())
 
 
-@pytest.mark.parametrize("idx", [1, 2, 3])
-def test_read_single_motor_id(idx):
+@pytest.mark.parametrize(
+    "idx, pos",
+    [
+        [1, 1337],
+        [2, 42],
+        [3, 4016],
+    ],
+)
+def test_read_single_motor_by_id(idx, pos):
     mock_motors = MockMotors([1, 2, 3])
+    mock_motors.build_single_motor_stubs("Present_Position", return_value=pos)
     motors_bus = DynamixelMotorsBus(
         port=mock_motors.port,
         motors={
@@ -126,28 +145,24 @@ def test_read_single_motor_id(idx):
     pos_dict = motors_bus.read("Present_Position", idx)
 
     assert mock_motors.stubs[f"SyncRead_Present_Position_{idx}"].called
-    assert len(pos_dict) == 1
+    assert pos_dict == {f"dummy_{idx}": pos}
     assert all(pos >= 0 and pos <= 4095 for pos in pos_dict.values())
 
 
 @pytest.mark.parametrize(
-    "num_retry, num_invalid_try",
+    "num_retry, num_invalid_try, pos",
     [
-        [1, 2],
-        [2, 3],
-        [3, 2],
-        [2, 1],
+        [1, 2, 1337],
+        [2, 3, 42],
+        [3, 2, 4016],
+        [2, 1, 999],
     ],
 )
-def test_read_num_retry(num_retry, num_invalid_try):
-    mock_motors = MockMotors([1, 2, 3], default_stubs=None)
-    address, length = mock_motors.ctrl_table["Present_Position"]
-    receive_bytes = MockInstructionPacket.sync_read([1], address, length)
-    send_fn = mock_motors._create_present_pos_send_fn(
-        [1], "Present_Position", num_invalid_try=num_invalid_try
+def test_read_num_retry(num_retry, num_invalid_try, pos):
+    mock_motors = MockMotors([1, 2, 3])
+    mock_motors.build_single_motor_stubs(
+        "Present_Position", return_value=pos, num_invalid_try=num_invalid_try
     )
-    mock_motors.stub(name="num_retry", receive_bytes=receive_bytes, send_fn=send_fn)
-
     motors_bus = DynamixelMotorsBus(
         port=mock_motors.port,
         motors={
@@ -160,10 +175,10 @@ def test_read_num_retry(num_retry, num_invalid_try):
 
     if num_retry >= num_invalid_try:
         pos_dict = motors_bus.read("Present_Position", 1, num_retry=num_retry)
-        assert len(pos_dict) == 1
+        assert pos_dict == {"dummy_1": pos}
         assert all(pos >= 0 and pos <= 4095 for pos in pos_dict.values())
     else:
         with pytest.raises(ConnectionError):
             _ = motors_bus.read("Present_Position", 1, num_retry=num_retry)
 
-    assert mock_motors.stubs["num_retry"].calls == num_retry
+    assert mock_motors.stubs["SyncRead_Present_Position_1"].calls == num_retry

From dd1f33e5ed2909af4da19e50f29c0c53c8ab0951 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Thu, 20 Mar 2025 09:44:47 +0100
Subject: [PATCH 061/171] Add pytest param ids

---
 tests/motors/test_dynamixel.py | 32 ++++++++++++++++++++++----------
 1 file changed, 22 insertions(+), 10 deletions(-)

diff --git a/tests/motors/test_dynamixel.py b/tests/motors/test_dynamixel.py
index afdeb7f9..371e7864 100644
--- a/tests/motors/test_dynamixel.py
+++ b/tests/motors/test_dynamixel.py
@@ -26,15 +26,26 @@ def test_autouse_patch():
 @pytest.mark.parametrize(
     "value, n_bytes, expected",
     [
-        (0x12,       1, [0x12]),                    # Single byte
-        (0x1234,     2, [0x34, 0x12]),              # Two bytes
-        (0x12345678, 4, [0x78, 0x56, 0x34, 0x12]),  # Four bytes
-        (0,          1, [0x00]),                    # Zero with 1 byte
-        (0,          2, [0x00, 0x00]),              # Zero with 2 bytes
-        (0,          4, [0x00, 0x00, 0x00, 0x00]),  # Zero with 4 bytes
-        (255,        1, [0xFF]),                    # Max single byte
-        (65535,      2, [0xFF, 0xFF]),              # Max two bytes
-        (4294967295, 4, [0xFF, 0xFF, 0xFF, 0xFF]),  # Max four bytes
+        (0x12,       1, [0x12]),
+        (0x1234,     2, [0x34, 0x12]),
+        (0x12345678, 4, [0x78, 0x56, 0x34, 0x12]),
+        (0,          1, [0x00]),
+        (0,          2, [0x00, 0x00]),
+        (0,          4, [0x00, 0x00, 0x00, 0x00]),
+        (255,        1, [0xFF]),
+        (65535,      2, [0xFF, 0xFF]),
+        (4294967295, 4, [0xFF, 0xFF, 0xFF, 0xFF]),
+    ],
+    ids=[
+        "1 byte",
+        "2 bytes",
+        "4 bytes",
+        "0 with 1 byte",
+        "0 with 2 bytes",
+        "0 with 4 bytes",
+        "max single byte",
+        "max two bytes",
+        "max four bytes",
     ],
 )  # fmt: skip
 def test_split_int_bytes(value, n_bytes, expected):
@@ -58,7 +69,7 @@ def test_split_int_bytes_large_number():
 
 
 def test_abc_implementation():
-    # Instantiation should raise an error if the class doesn't implements abstract methods/properties
+    """Instantiation should raise an error if the class doesn't implement abstract methods/properties."""
     DynamixelMotorsBus(port="/dev/dummy-port", motors={"dummy": (1, "xl330-m077")})
 
 
@@ -70,6 +81,7 @@ def test_abc_implementation():
         ["dummy_1", "dummy_2", "dummy_3"],
         [1, "dummy_2", 3],
     ],
+    ids=["None", "by ids", "by names", "mixed"],
 )
 def test_read_all_motors(motors):
     mock_motors = MockMotors([1, 2, 3])

From 2c68c6ca4097e3755da11b2b0e1ba05b6ec88617 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Thu, 20 Mar 2025 10:22:47 +0100
Subject: [PATCH 062/171] Implement FeetechMotorsBus & move functions to
 calibration

---
 lerobot/common/motors/feetech/feetech.py      | 348 +++---------------
 .../motors/feetech/feetech_calibration.py     |  76 +++-
 2 files changed, 113 insertions(+), 311 deletions(-)

diff --git a/lerobot/common/motors/feetech/feetech.py b/lerobot/common/motors/feetech/feetech.py
index 1179a4e5..396388f8 100644
--- a/lerobot/common/motors/feetech/feetech.py
+++ b/lerobot/common/motors/feetech/feetech.py
@@ -14,19 +14,11 @@
 
 from copy import deepcopy
 
-import numpy as np
-
-from ..motors_bus import (
-    CalibrationMode,
-    JointOutOfRangeError,
-    MotorsBus,
-    assert_same_address,
-    get_group_sync_key,
-)
+from ..motors_bus import MotorsBus
 
 PROTOCOL_VERSION = 0
 BAUDRATE = 1_000_000
-TIMEOUT_MS = 1000
+DEFAULT_TIMEOUT_MS = 1000
 
 MAX_ID_RANGE = 252
 
@@ -125,94 +117,6 @@ NUM_READ_RETRY = 20
 NUM_WRITE_RETRY = 20
 
 
-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:
-    """
-    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, n_bytes: int):
-    import scservo_sdk as scs
-
-    # Note: No need to convert back into unsigned int, since this byte preprocessing
-    # already handles it for us.
-    if n_bytes == 1:
-        data = [
-            scs.SCS_LOBYTE(scs.SCS_LOWORD(value)),
-        ]
-    elif n_bytes == 2:
-        data = [
-            scs.SCS_LOBYTE(scs.SCS_LOWORD(value)),
-            scs.SCS_HIBYTE(scs.SCS_LOWORD(value)),
-        ]
-    elif n_bytes == 4:
-        data = [
-            scs.SCS_LOBYTE(scs.SCS_LOWORD(value)),
-            scs.SCS_HIBYTE(scs.SCS_LOWORD(value)),
-            scs.SCS_LOBYTE(scs.SCS_HIWORD(value)),
-            scs.SCS_HIBYTE(scs.SCS_HIWORD(value)),
-        ]
-    else:
-        raise NotImplementedError(
-            f"Value of the number of bytes to be sent is expected to be in [1, 2, 4], but "
-            f"{n_bytes} is provided instead."
-        )
-    return data
-
-
 class FeetechMotorsBus(MotorsBus):
     """
     The FeetechMotorsBus class allows to efficiently read and write to the attached motors. It relies on the
@@ -222,6 +126,8 @@ class FeetechMotorsBus(MotorsBus):
     model_ctrl_table = deepcopy(MODEL_CONTROL_TABLE)
     model_resolution_table = deepcopy(MODEL_RESOLUTION)
     model_baudrate_table = deepcopy(MODEL_BAUDRATE_TABLE)
+    calibration_required = deepcopy(CALIBRATION_REQUIRED)
+    default_timeout = DEFAULT_TIMEOUT_MS
 
     def __init__(
         self,
@@ -229,224 +135,60 @@ class FeetechMotorsBus(MotorsBus):
         motors: dict[str, tuple[int, str]],
     ):
         super().__init__(port, motors)
-
-    def _set_handlers(self):
         import scservo_sdk as scs
 
         self.port_handler = scs.PortHandler(self.port)
         self.packet_handler = scs.PacketHandler(PROTOCOL_VERSION)
+        self.reader = scs.GroupSyncRead(self.packet_handler, self.packet_handler, 0, 0)
+        self.writer = scs.GroupSyncWrite(self.packet_handler, self.packet_handler, 0, 0)
 
-    def _set_timeout(self, timeout: int = TIMEOUT_MS):
-        self.port_handler.setPacketTimeoutMillis(timeout)
+    def broadcast_ping(self, num_retry: int | None = None):
+        raise NotImplementedError  # TODO
 
-    def apply_calibration(self, values: np.ndarray | list, motor_names: list[str] | None):
-        if motor_names is None:
-            motor_names = self.motor_names
+    def calibrate_values(self, ids_values: dict[int, int]) -> dict[int, float]:
+        # TODO
+        return ids_values
 
-        # Convert from unsigned int32 original range [0, 2**32] to signed float32 range
-        values = values.astype(np.float32)
+    def uncalibrate_values(self, ids_values: dict[int, float]) -> dict[int, int]:
+        # TODO
+        return ids_values
 
-        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:
-                motor_idx, model = self.motors[name]
-
-                # 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]
-                end_pos = self.calibration["end_pos"][calib_idx]
-
-                # Rescale the present position to a nominal range [0, 100] %,
-                # useful for joints with linear motions like Aloha gripper
-                values[i] = (values[i] - start_pos) / (end_pos - start_pos) * 100
-
-                if (values[i] < LOWER_BOUND_LINEAR) or (values[i] > UPPER_BOUND_LINEAR):
-                    raise JointOutOfRangeError(
-                        f"Wrong motor position range detected for {name}. "
-                        f"Expected to be in nominal range of [0, 100] % (a full linear translation), "
-                        f"with a maximum range of [{LOWER_BOUND_LINEAR}, {UPPER_BOUND_LINEAR}] % to account for some imprecision during calibration, "
-                        f"but present value is {values[i]} %. "
-                        "This might be due to a cable connection issue creating an artificial jump in motor values. "
-                        "You need to recalibrate by running: `python lerobot/scripts/control_robot.py calibrate`"
-                    )
-
-        return values
-
-    def revert_calibration(self, values: np.ndarray | list, motor_names: list[str] | None):
-        """Inverse of `apply_calibration`."""
-        if motor_names is None:
-            motor_names = self.motor_names
-
-        for i, name in enumerate(motor_names):
-            calib_idx = self.calibration["motor_names"].index(name)
-            calib_mode = self.calibration["calib_mode"][calib_idx]
-
-            if CalibrationMode[calib_mode] == CalibrationMode.DEGREE:
-                motor_idx, model = self.motors[name]
-
-                # 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]
-                end_pos = self.calibration["end_pos"][calib_idx]
-
-                # Convert from nominal lnear range of [0, 100] % to
-                # actual motor range of values which can be arbitrary.
-                values[i] = values[i] / 100 * (end_pos - start_pos) + start_pos
-
-        values = np.round(values).astype(np.int32)
-        return values
-
-    def read_with_motor_ids(self, motor_models, motor_ids, data_name, num_retry=NUM_READ_RETRY):
+    def _is_comm_success(self, comm: int) -> bool:
         import scservo_sdk as scs
 
-        return_list = True
-        if not isinstance(motor_ids, list):
-            return_list = False
-            motor_ids = [motor_ids]
+        return comm == scs.COMM_SUCCESS
 
-        assert_same_address(self.model_ctrl_table, self.motor_models, data_name)
-        addr, bytes = self.model_ctrl_table[motor_models[0]][data_name]
-        group = scs.GroupSyncRead(self.port_handler, self.packet_handler, addr, bytes)
-        for idx in motor_ids:
-            group.addParam(idx)
+    @staticmethod
+    def split_int_bytes(value: int, n_bytes: int) -> list[int]:
+        # Validate input
+        if value < 0:
+            raise ValueError(f"Negative values are not allowed: {value}")
 
-        for _ in range(num_retry):
-            comm = group.txRxPacket()
-            if comm == scs.COMM_SUCCESS:
-                break
+        max_value = {1: 0xFF, 2: 0xFFFF, 4: 0xFFFFFFFF}.get(n_bytes)
+        if max_value is None:
+            raise NotImplementedError(f"Unsupported byte size: {n_bytes}. Expected [1, 2, 4].")
 
-        if comm != scs.COMM_SUCCESS:
-            raise ConnectionError(
-                f"Read failed due to communication error on port {self.port_handler.port_name} for indices {motor_ids}: "
-                f"{self.packet_handler.getTxRxResult(comm)}"
-            )
+        if value > max_value:
+            raise ValueError(f"Value {value} exceeds the maximum for {n_bytes} bytes ({max_value}).")
 
-        values = []
-        for idx in motor_ids:
-            value = group.getData(idx, addr, bytes)
-            values.append(value)
-
-        if return_list:
-            return values
-        else:
-            return values[0]
-
-    def _read(self, data_name: str, motor_names: list[str]):
         import scservo_sdk as scs
 
-        motor_ids = []
-        models = []
-        for name in motor_names:
-            motor_idx, model = self.motors[name]
-            motor_ids.append(motor_idx)
-            models.append(model)
-
-        assert_same_address(self.model_ctrl_table, models, data_name)
-        addr, bytes = self.model_ctrl_table[model][data_name]
-        group_key = get_group_sync_key(data_name, motor_names)
-
-        if data_name not in self.group_readers:
-            # Very Important to flush the buffer!
-            self.port_handler.ser.reset_output_buffer()
-            self.port_handler.ser.reset_input_buffer()
-
-            # Create new group reader
-            self.group_readers[group_key] = scs.GroupSyncRead(
-                self.port_handler, self.packet_handler, addr, bytes
-            )
-            for idx in motor_ids:
-                self.group_readers[group_key].addParam(idx)
-
-        for _ in range(NUM_READ_RETRY):
-            comm = self.group_readers[group_key].txRxPacket()
-            if comm == scs.COMM_SUCCESS:
-                break
-
-        if comm != scs.COMM_SUCCESS:
-            raise ConnectionError(
-                f"Read failed due to communication error on port {self.port} for group_key {group_key}: "
-                f"{self.packet_handler.getTxRxResult(comm)}"
-            )
-
-        values = []
-        for idx in motor_ids:
-            value = self.group_readers[group_key].getData(idx, addr, bytes)
-            values.append(value)
-
-        values = np.array(values)
-
-        if data_name in CALIBRATION_REQUIRED and self.calibration is not None:
-            values = self.apply_calibration(values, motor_names)
-
-        return values
-
-    def write_with_motor_ids(self, motor_models, motor_ids, data_name, values, num_retry=NUM_WRITE_RETRY):
-        import scservo_sdk as scs
-
-        if not isinstance(motor_ids, list):
-            motor_ids = [motor_ids]
-        if not isinstance(values, list):
-            values = [values]
-
-        assert_same_address(self.model_ctrl_table, motor_models, data_name)
-        addr, bytes = self.model_ctrl_table[motor_models[0]][data_name]
-        group = scs.GroupSyncWrite(self.port_handler, self.packet_handler, addr, bytes)
-        for idx, value in zip(motor_ids, values, strict=True):
-            data = convert_to_bytes(value, bytes)
-            group.addParam(idx, data)
-
-        for _ in range(num_retry):
-            comm = group.txPacket()
-            if comm == scs.COMM_SUCCESS:
-                break
-
-        if comm != scs.COMM_SUCCESS:
-            raise ConnectionError(
-                f"Write failed due to communication error on port {self.port_handler.port_name} for indices {motor_ids}: "
-                f"{self.packet_handler.getTxRxResult(comm)}"
-            )
-
-    def _write(self, data_name: str, values: list[int], motor_names: list[str]) -> None:
-        import scservo_sdk as scs
-
-        motor_ids = []
-        models = []
-        for name in motor_names:
-            motor_idx, model = self.motors[name]
-            motor_ids.append(motor_idx)
-            models.append(model)
-
-        if data_name in CALIBRATION_REQUIRED and self.calibration is not None:
-            values = self.revert_calibration(values, motor_names)
-
-        assert_same_address(self.model_ctrl_table, models, data_name)
-        addr, bytes = self.model_ctrl_table[model][data_name]
-        group_key = get_group_sync_key(data_name, motor_names)
-
-        init_group = data_name not in self.group_readers
-        if init_group:
-            self.group_writers[group_key] = scs.GroupSyncWrite(
-                self.port_handler, self.packet_handler, addr, bytes
-            )
-
-        for idx, value in zip(motor_ids, values, strict=True):
-            data = convert_to_bytes(value, bytes)
-            if init_group:
-                self.group_writers[group_key].addParam(idx, data)
-            else:
-                self.group_writers[group_key].changeParam(idx, data)
-
-        comm = self.group_writers[group_key].txPacket()
-        if comm != scs.COMM_SUCCESS:
-            raise ConnectionError(
-                f"Write failed due to communication error on port {self.port} for group_key {group_key}: "
-                f"{self.packet_handler.getTxRxResult(comm)}"
-            )
+        # Note: No need to convert back into unsigned int, since this byte preprocessing
+        # already handles it for us.
+        if n_bytes == 1:
+            data = [
+                scs.SCS_LOBYTE(scs.SCS_LOWORD(value)),
+            ]
+        elif n_bytes == 2:
+            data = [
+                scs.SCS_LOBYTE(scs.SCS_LOWORD(value)),
+                scs.SCS_HIBYTE(scs.SCS_LOWORD(value)),
+            ]
+        elif n_bytes == 4:
+            data = [
+                scs.SCS_LOBYTE(scs.SCS_LOWORD(value)),
+                scs.SCS_HIBYTE(scs.SCS_LOWORD(value)),
+                scs.SCS_LOBYTE(scs.SCS_HIWORD(value)),
+                scs.SCS_HIBYTE(scs.SCS_HIWORD(value)),
+            ]
+        return data
diff --git a/lerobot/common/motors/feetech/feetech_calibration.py b/lerobot/common/motors/feetech/feetech_calibration.py
index de4ed83f..f967f82d 100644
--- a/lerobot/common/motors/feetech/feetech_calibration.py
+++ b/lerobot/common/motors/feetech/feetech_calibration.py
@@ -13,11 +13,12 @@
 # limitations under the License.
 import numpy as np
 
-from ..motors_bus import MotorsBus, TorqueMode
-from .feetech import (
+from ..motors_bus import (
     CalibrationMode,
-    FeetechMotorsBus,
+    MotorsBus,
+    TorqueMode,
 )
+from .feetech import MODEL_RESOLUTION, FeetechMotorsBus
 
 URL_TEMPLATE = (
     "https://raw.githubusercontent.com/huggingface/lerobot/main/media/{robot}/{arm}_{position}.webp"
@@ -140,19 +141,19 @@ def run_full_arm_calibration(arm: MotorsBus, robot_type: str, arm_name: str, arm
     )  # TODO(pepijn): replace with new instruction homing pos (all motors in middle) in tutorial
     input("Press Enter to continue...")
 
-    start_positions = np.zeros(len(arm.motor_indices))
-    end_positions = np.zeros(len(arm.motor_indices))
-    encoder_offsets = np.zeros(len(arm.motor_indices))
+    start_positions = np.zeros(len(arm.motor_ids))
+    end_positions = np.zeros(len(arm.motor_ids))
+    encoder_offsets = np.zeros(len(arm.motor_ids))
 
     modes = get_calibration_modes(arm)
 
-    for i, motor_id in enumerate(arm.motor_indices):
+    for i, motor_id in enumerate(arm.motor_ids):
         if modes[i] == CalibrationMode.DEGREE.name:
             encoder_offsets[i] = calibrate_homing_motor(motor_id, arm)
             start_positions[i] = 0
             end_positions[i] = 0
 
-    for i, motor_id in enumerate(arm.motor_indices):
+    for i, motor_id in enumerate(arm.motor_ids):
         if modes[i] == CalibrationMode.LINEAR.name:
             start_positions[i], end_positions[i] = calibrate_linear_motor(motor_id, arm)
             encoder_offsets[i] = 0
@@ -251,3 +252,62 @@ def apply_feetech_offsets_from_calibration(motorsbus: FeetechMotorsBus, calibrat
 
     motorsbus.write("Lock", 0)
     print("Offsets have been saved to EEPROM successfully.")
+
+
+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:
+    """
+    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

From e2c8bc6948b8d19acbc09343ebd8627cc1275be2 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Thu, 20 Mar 2025 13:57:15 +0100
Subject: [PATCH 063/171] Fix packet length, remove bytearray for easier debug,
 improve doctrings

---
 tests/mocks/mock_dynamixel.py | 110 ++++++++++++++++++----------------
 1 file changed, 60 insertions(+), 50 deletions(-)

diff --git a/tests/mocks/mock_dynamixel.py b/tests/mocks/mock_dynamixel.py
index cccc3c20..e45ff1b4 100644
--- a/tests/mocks/mock_dynamixel.py
+++ b/tests/mocks/mock_dynamixel.py
@@ -87,18 +87,32 @@ ERROR_TYPE = {
 
 class MockDynamixelPacketv2(abc.ABC):
     @classmethod
-    def build(cls, dxl_id: int, params: list[int], *args, **kwargs) -> bytes:
-        packet = cls._build(dxl_id, params, *args, **kwargs)
+    def build(cls, dxl_id: int, params: list[int], length: list[int], *args, **kwargs) -> bytes:
+        packet = cls._build(dxl_id, params, length, *args, **kwargs)
         packet = cls._add_stuffing(packet)
         packet = cls._add_crc(packet)
         return bytes(packet)
 
     @abc.abstractclassmethod
-    def _build(cls, dxl_id: int, params: list[int], *args, **kwargs) -> bytearray:
+    def _build(cls, dxl_id: int, params: list[int], length: int, *args, **kwargs) -> list[int]:
         pass
 
     @staticmethod
-    def _add_stuffing(packet: bytearray) -> bytearray:
+    def _add_stuffing(packet: list[int]) -> list[int]:
+        """
+        Byte stuffing is a method of adding additional data to generated instruction packets to ensure that
+        the packets are processed successfully. When the byte pattern "0xFF 0xFF 0xFD" appears in a packet,
+        byte stuffing adds 0xFD to the end of the pattern to convert it to “0xFF 0xFF 0xFD 0xFD” to ensure
+        that it is not interpreted as the header at the start of another packet.
+
+        Source: https://emanual.robotis.com/docs/en/dxl/protocol2/#transmission-process
+
+        Args:
+            packet (list[int]): The raw packet without stuffing.
+
+        Returns:
+            list[int]: The packet stuffed if it contained a "0xFF 0xFF 0xFD" byte sequence in its data bytes.
+        """
         packet_length_in = dxl.DXL_MAKEWORD(packet[dxl.PKT_LENGTH_L], packet[dxl.PKT_LENGTH_H])
         packet_length_out = packet_length_in
 
@@ -139,7 +153,7 @@ class MockDynamixelPacketv2(abc.ABC):
         return packet
 
     @staticmethod
-    def _add_crc(packet: bytearray) -> int:
+    def _add_crc(packet: list[int]) -> list[int]:
         crc = 0
         for j in range(len(packet) - 2):
             i = ((crc >> 8) ^ packet[j]) & 0xFF
@@ -165,28 +179,17 @@ class MockInstructionPacket(MockDynamixelPacketv2):
     """
 
     @classmethod
-    def _build(cls, dxl_id: int, params: list[int], instruct_type: str):
+    def _build(cls, dxl_id: int, params: list[int], length: int, instruct_type: str) -> list[int]:
         instruct_value = INSTRUCTION_TYPES[instruct_type]
-
-        # For Protocol 2.0, "length" = (number_of_params + 3),
-        #    where:
-        #        +1 is for <instruction> byte,
-        #        +2 is for the CRC at the end.
-        # The official Dynamixel SDK sometimes uses (+7) logic for sync reads
-        # because it includes special sub-parameters. But at core:
-        #    length = (instruction byte) + (len(params)) + (CRC16 =2).
-        packet_length = len(params) + 3
-        return bytearray(
-            [
-                0xFF, 0xFF, 0xFD, 0x00,         # header
-                dxl_id,                         # servo id
-                dxl.DXL_LOBYTE(packet_length),  # length_l
-                dxl.DXL_HIBYTE(packet_length),  # length_h
-                instruct_value,                 # instruction type
-                *params,                        # data bytes
-                0x00, 0x00                      # placeholder for CRC
-            ]
-        )  # fmt: skip
+        return [
+            0xFF, 0xFF, 0xFD, 0x00,  # header
+            dxl_id,                  # servo id
+            dxl.DXL_LOBYTE(length),  # length_l
+            dxl.DXL_HIBYTE(length),  # length_h
+            instruct_value,          # instruction type
+            *params,                 # data bytes
+            0x00, 0x00               # placeholder for CRC
+        ]  # fmt: skip
 
     @classmethod
     def sync_read(
@@ -196,24 +199,31 @@ class MockInstructionPacket(MockDynamixelPacketv2):
         data_length: int,
     ) -> bytes:
         """
-        Helper method to build a Sync Read broadcast instruction.
+        Builds a "Sync_Read" broadcast instruction.
         (from https://emanual.robotis.com/docs/en/dxl/protocol2/#sync-read-0x82)
 
-        The parameters for Sync Read (Protocol 2.0) are:
+        The parameters for Sync_Read (Protocol 2.0) are:
             param[0]   = start_address L
             param[1]   = start_address H
             param[2]   = data_length L
             param[3]   = data_length H
             param[4+]  = motor IDs to read from
+
+        And 'length' = (number_of_params + 7), where:
+            +1 is for instruction byte,
+            +2 is for the address bytes,
+            +2 is for the length bytes,
+            +2 is for the CRC at the end.
         """
         params = [
             dxl.DXL_LOBYTE(start_address),
             dxl.DXL_HIBYTE(start_address),
             dxl.DXL_LOBYTE(data_length),
             dxl.DXL_HIBYTE(data_length),
-        ] + dxl_ids
-
-        return cls.build(dxl_id=dxl.BROADCAST_ID, instruct_type="Sync_Read", params=params)
+            *dxl_ids,
+        ]
+        length = len(dxl_ids) + 7
+        return cls.build(dxl_id=dxl.BROADCAST_ID, params=params, length=length, instruct_type="Sync_Read")
 
 
 class MockStatusPacket(MockDynamixelPacketv2):
@@ -229,27 +239,27 @@ class MockStatusPacket(MockDynamixelPacketv2):
     """
 
     @classmethod
-    def _build(cls, dxl_id: int, params: list[int], error: str = "Success") -> bytearray:
+    def _build(cls, dxl_id: int, params: list[int], length: int, error: str = "Success") -> list[int]:
         err_byte = ERROR_TYPE[error]
-        return bytearray(
-            [
-                0xFF, 0xFF, 0xFD, 0x00,  # header
-                dxl_id,                  # servo id
-                0x08, 0x00,              # length_l, length_h = 8
-                0x55,                    # instruction = 'status'
-                err_byte,                # error
-                *params,                 # data bytes
-                0x00, 0x00               # placeholder for CRC
-            ]
-        )  # fmt: skip
+        return [
+            0xFF, 0xFF, 0xFD, 0x00,  # header
+            dxl_id,                  # servo id
+            dxl.DXL_LOBYTE(length),  # length_l
+            dxl.DXL_HIBYTE(length),  # length_h
+            0x55,                    # instruction = 'status'
+            err_byte,                # error
+            *params,                 # data bytes
+            0x00, 0x00               # placeholder for CRC
+        ]  # fmt: skip
 
     @classmethod
     def present_position(cls, dxl_id: int, pos: int | None = None, min_max_range: tuple = (0, 4095)) -> bytes:
-        """Builds a 'Present_Position' packet.
+        """Builds a 'Present_Position' status packet.
 
         Args:
-            pos (int | None, optional): Desired 'Present_Position'. If None, it will use a random value in the
-                min_max_range. Defaults to None.
+            dxl_id (int): List of the servos ids
+            pos (int | None, optional): Desired 'Present_Position' to be returned in the packet. If None, it
+                will use a random value in the min_max_range. Defaults to None.
             min_max_range (tuple, optional): Min/max range to generate the position values used for when 'pos'
                 is None. Note that the bounds are included in the range. Defaults to (0, 4095).
 
@@ -257,14 +267,14 @@ class MockStatusPacket(MockDynamixelPacketv2):
             bytes: The raw 'Present_Position' status packet ready to be sent through serial.
         """
         pos = random.randint(*min_max_range) if pos is None else pos
-        # [lower pos 8 bits, higher pos 8 bits, 0, 0]
-        params = [pos & 0xFF, (pos >> 8) & 0xFF, 0, 0]
-        return cls.build(dxl_id, params)
+        params = [dxl.DXL_LOBYTE(pos), dxl.DXL_HIBYTE(pos), 0, 0]
+        length = 8
+        return cls.build(dxl_id, params=params, length=length)
 
 
 class MockPortHandler(dxl.PortHandler):
     """
-    This class overwrite the 'setupPort' method of the dynamixel PortHandler because it can specify
+    This class overwrite the 'setupPort' method of the Dynamixel PortHandler because it can specify
     baudrates that are not supported with a serial port on MacOS.
     """
 

From 9af0a9bf37240ebff09e06dab0710e496a1d91cb Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Thu, 20 Mar 2025 13:58:02 +0100
Subject: [PATCH 064/171] Add mock_feetech

---
 tests/mocks/mock_feetech.py | 245 ++++++++++++++++++++++++++++++++++++
 1 file changed, 245 insertions(+)
 create mode 100644 tests/mocks/mock_feetech.py

diff --git a/tests/mocks/mock_feetech.py b/tests/mocks/mock_feetech.py
new file mode 100644
index 00000000..431707c5
--- /dev/null
+++ b/tests/mocks/mock_feetech.py
@@ -0,0 +1,245 @@
+import abc
+import random
+from typing import Callable
+
+import scservo_sdk as scs
+import serial
+from mock_serial import MockSerial
+
+from lerobot.common.motors.feetech.feetech import SCS_SERIES_CONTROL_TABLE
+
+# https://files.waveshare.com/upload/2/27/Communication_Protocol_User_Manual-EN%28191218-0923%29.pdf
+INSTRUCTION_TYPES = {
+    "Ping": 0x01,	        # Checks whether the Packet has arrived at a device with the same ID as the specified packet ID
+    "Read": 0x02,	        # Read data from the Device
+    "Write": 0x03,	        # Write data to the Device
+    "Reg_Write": 0x04,	    # Register the Instruction Packet in standby status; Packet can later be executed using the Action command
+    "Action": 0x05,	        # Executes a Packet that was registered beforehand using Reg Write
+    "Factory_Reset": 0x06,  # Resets the Control Table to its initial factory default settings
+    "Sync_Read": 0x82,	           # Read data from multiple devices with the same Address with the same length at once
+    "Sync_Write": 0x83,	    # Write data to multiple devices with the same Address with the same length at once
+}  # fmt: skip
+
+ERROR_TYPE = {
+    "Success": 0x00,
+    "Voltage": 0x01,
+    "Angle": 0x02,
+    "Overheat": 0x04,
+    "Overele": 0x08,
+    "Overload": 0x20,
+}
+
+
+class MockFeetechPacket(abc.ABC):
+    @classmethod
+    def build(cls, scs_id: int, params: list[int], length: int, *args, **kwargs) -> bytes:
+        packet = cls._build(scs_id, params, length, *args, **kwargs)
+        packet = cls._add_checksum(packet)
+        return bytes(packet)
+
+    @abc.abstractclassmethod
+    def _build(cls, scs_id: int, params: list[int], length: int, *args, **kwargs) -> list[int]:
+        pass
+
+    @staticmethod
+    def _add_checksum(packet: list[int]) -> list[int]:
+        checksum = 0
+        for idx in range(2, len(packet) - 1):  # except header & checksum
+            checksum += packet[idx]
+
+        packet[-1] = scs.SCS_LOBYTE(~checksum)
+
+        return packet
+
+
+class MockInstructionPacket(MockFeetechPacket):
+    """
+    Helper class to build valid Feetech Instruction Packets.
+
+    Instruction Packet structure
+    (from https://files.waveshare.com/upload/2/27/Communication_Protocol_User_Manual-EN%28191218-0923%29.pdf)
+
+    | Header    | Packet ID | Length | Instruction | Params            | Checksum |
+    | --------- | --------- | ------ | ----------- | ----------------- | -------- |
+    | 0xFF 0xFF | ID        | Len    | Instr       | Param 1 … Param N | Sum      |
+
+    """
+
+    @classmethod
+    def _build(cls, scs_id: int, params: list[int], length: int, instruct_type: str) -> list[int]:
+        instruct_value = INSTRUCTION_TYPES[instruct_type]
+        return [
+            0xFF, 0xFF,      # header
+            scs_id,          # servo id
+            length,          # length
+            instruct_value,  # instruction type
+            *params,         # data bytes
+            0x00,            # placeholder for checksum
+        ]  # fmt: skip
+
+    @classmethod
+    def sync_read(
+        cls,
+        scs_ids: list[int],
+        start_address: int,
+        data_length: int,
+    ) -> bytes:
+        """
+        Builds a "Sync_Read" broadcast instruction.
+
+        The parameters for Sync Read (Protocol 2.0) are:
+            param[0]   = start_address
+            param[1]   = data_length
+            param[2+]  = motor IDs to read from
+
+        And 'length' = (number_of_params + 7), where:
+            +1 is for instruction byte,
+            +1 is for the address byte,
+            +1 is for the length bytes,
+            +1 is for the checksum at the end.
+        """
+        params = [start_address, data_length, *scs_ids]
+        length = len(scs_ids) + 4
+        return cls.build(scs_id=scs.BROADCAST_ID, params=params, length=length, instruct_type="Sync_Read")
+
+
+class MockStatusPacket(MockFeetechPacket):
+    """
+    Helper class to build valid Feetech Status Packets.
+
+    Status Packet structure
+    (from https://files.waveshare.com/upload/2/27/Communication_Protocol_User_Manual-EN%28191218-0923%29.pdf)
+
+    | Header    | Packet ID | Length | Error | Params            | Checksum |
+    | --------- | --------- | ------ | ----- | ----------------- | -------- |
+    | 0xFF 0xFF | ID        | Len    | Err   | Param 1 … Param N | Sum      |
+
+    """
+
+    @classmethod
+    def _build(cls, scs_id: int, params: list[int], length: int, error: str = "Success") -> list[int]:
+        err_byte = ERROR_TYPE[error]
+        return [
+            0xFF, 0xFF,  # header
+            scs_id,      # servo id
+            length,      # length
+            err_byte,    # status
+            *params,     # data bytes
+            0x00,        # placeholder for checksum
+        ]  # fmt: skip
+
+    @classmethod
+    def present_position(cls, scs_id: int, pos: int | None = None, min_max_range: tuple = (0, 4095)) -> bytes:
+        """Builds a 'Present_Position' status packet.
+
+        Args:
+            scs_id (int): List of the servos ids
+            pos (int | None, optional): Desired 'Present_Position' to be returned in the packet. If None, it
+                will use a random value in the min_max_range. Defaults to None.
+            min_max_range (tuple, optional): Min/max range to generate the position values used for when 'pos'
+                is None. Note that the bounds are included in the range. Defaults to (0, 4095).
+
+        Returns:
+            bytes: The raw 'Present_Position' status packet ready to be sent through serial.
+        """
+        pos = random.randint(*min_max_range) if pos is None else pos
+        params = [scs.SCS_LOBYTE(pos), scs.SCS_HIBYTE(pos)]
+        length = 4
+        return cls.build(scs_id, params=params, length=length)
+
+
+class MockPortHandler(scs.PortHandler):
+    """
+    This class overwrite the 'setupPort' method of the Feetech PortHandler because it can specify
+    baudrates that are not supported with a serial port on MacOS.
+    """
+
+    def setupPort(self, cflag_baud):  # noqa: N802
+        if self.is_open:
+            self.closePort()
+
+        self.ser = serial.Serial(
+            port=self.port_name,
+            # baudrate=self.baudrate,  <- This will fail on MacOS
+            # parity = serial.PARITY_ODD,
+            # stopbits = serial.STOPBITS_TWO,
+            bytesize=serial.EIGHTBITS,
+            timeout=0,
+        )
+        self.is_open = True
+        self.ser.reset_input_buffer()
+        self.tx_time_per_byte = (1000.0 / self.baudrate) * 10.0
+
+        return True
+
+
+class MockMotors(MockSerial):
+    """
+    This class will simulate physical motors by responding with valid status packets upon receiving some
+    instruction packets. It is meant to test MotorsBus classes.
+
+    'data_name' supported:
+        - Present_Position
+    """
+
+    ctrl_table = SCS_SERIES_CONTROL_TABLE
+
+    def __init__(self, scs_ids: list[int]):
+        super().__init__()
+        self._ids = scs_ids
+        self.open()
+
+    def build_single_motor_stubs(
+        self, data_name: str, return_value: int | None = None, num_invalid_try: int | None = None
+    ) -> None:
+        address, length = self.ctrl_table[data_name]
+        for idx in self._ids:
+            if data_name == "Present_Position":
+                sync_read_request_single = MockInstructionPacket.sync_read([idx], address, length)
+                sync_read_response_single = self._build_present_pos_send_fn(
+                    [idx], [return_value], num_invalid_try
+                )
+            else:
+                raise NotImplementedError  # TODO(aliberts): add ping?
+
+            self.stub(
+                name=f"SyncRead_{data_name}_{idx}",
+                receive_bytes=sync_read_request_single,
+                send_fn=sync_read_response_single,
+            )
+
+    def build_all_motors_stub(
+        self, data_name: str, return_values: list[int] | None = None, num_invalid_try: int | None = None
+    ) -> None:
+        address, length = self.ctrl_table[data_name]
+        if data_name == "Present_Position":
+            sync_read_request_all = MockInstructionPacket.sync_read(self._ids, address, length)
+            sync_read_response_all = self._build_present_pos_send_fn(
+                self._ids, return_values, num_invalid_try
+            )
+        else:
+            raise NotImplementedError  # TODO(aliberts): add ping?
+
+        self.stub(
+            name=f"SyncRead_{data_name}_all",
+            receive_bytes=sync_read_request_all,
+            send_fn=sync_read_response_all,
+        )
+
+    def _build_present_pos_send_fn(
+        self, scs_ids: list[int], return_pos: list[int] | None = None, num_invalid_try: int | None = None
+    ) -> Callable[[int], bytes]:
+        return_pos = [None for _ in scs_ids] if return_pos is None else return_pos
+        assert len(return_pos) == len(scs_ids)
+
+        def send_fn(_call_count: int) -> bytes:
+            if num_invalid_try is not None and num_invalid_try >= _call_count:
+                return b""
+
+            packets = b"".join(
+                MockStatusPacket.present_position(idx, pos)
+                for idx, pos in zip(scs_ids, return_pos, strict=True)
+            )
+            return packets
+
+        return send_fn

From a15767aff126e0cb1ee6469468962d46a28dcd9d Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Thu, 20 Mar 2025 13:59:00 +0100
Subject: [PATCH 065/171] Fix feetech reader/writer

---
 lerobot/common/motors/feetech/feetech.py | 4 ++--
 1 file changed, 2 insertions(+), 2 deletions(-)

diff --git a/lerobot/common/motors/feetech/feetech.py b/lerobot/common/motors/feetech/feetech.py
index 396388f8..5a315bf9 100644
--- a/lerobot/common/motors/feetech/feetech.py
+++ b/lerobot/common/motors/feetech/feetech.py
@@ -139,8 +139,8 @@ class FeetechMotorsBus(MotorsBus):
 
         self.port_handler = scs.PortHandler(self.port)
         self.packet_handler = scs.PacketHandler(PROTOCOL_VERSION)
-        self.reader = scs.GroupSyncRead(self.packet_handler, self.packet_handler, 0, 0)
-        self.writer = scs.GroupSyncWrite(self.packet_handler, self.packet_handler, 0, 0)
+        self.reader = scs.GroupSyncRead(self.port_handler, self.packet_handler, 0, 0)
+        self.writer = scs.GroupSyncWrite(self.port_handler, self.packet_handler, 0, 0)
 
     def broadcast_ping(self, num_retry: int | None = None):
         raise NotImplementedError  # TODO

From bc020ee0a42b2207f31adada6ca23bd3b7abcb2a Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Thu, 20 Mar 2025 14:00:10 +0100
Subject: [PATCH 066/171] Remove mock_feetech sdk & add feetech new tests

---
 tests/mocks/mock_scservo_sdk.py | 151 ------------------------
 tests/motors/test_feetech.py    | 196 ++++++++++++++++++++++++++++----
 2 files changed, 174 insertions(+), 173 deletions(-)
 delete mode 100644 tests/mocks/mock_scservo_sdk.py

diff --git a/tests/mocks/mock_scservo_sdk.py b/tests/mocks/mock_scservo_sdk.py
deleted file mode 100644
index 21a3652b..00000000
--- a/tests/mocks/mock_scservo_sdk.py
+++ /dev/null
@@ -1,151 +0,0 @@
-# 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.
-
-# ruff: noqa: N802, E741
-
-"""
-Mocked classes and functions from scservo_sdk to allow for testing FeetechMotorsBus code.
-
-Warning: These mocked versions are minimalist. They do not exactly mock every behaviors
-from the original classes and functions (e.g. return types might be None instead of boolean).
-"""
-
-DEFAULT_BAUDRATE = 1_000_000
-COMM_SUCCESS = 0  # tx or rx packet communication success
-
-
-def convert_to_bytes(value, bytes):
-    # TODO(rcadene): remove need to mock `convert_to_bytes` by implemented the inverse transform
-    # `convert_bytes_to_value`
-    del bytes  # unused
-    return value
-
-
-def get_default_motor_values(motor_index):
-    return {
-        # Key (int) are from SCS_SERIES_CONTROL_TABLE
-        5: motor_index,  # ID
-        6: DEFAULT_BAUDRATE,  # Baud_rate
-        10: 0,  # Drive_Mode
-        21: 32,  # P_Coefficient
-        22: 32,  # D_Coefficient
-        23: 0,  # I_Coefficient
-        40: 0,  # Torque_Enable
-        41: 254,  # Acceleration
-        31: -2047,  # Offset
-        33: 0,  # Mode
-        55: 1,  # Lock
-        # Set 2560 since calibration values for Aloha gripper is between start_pos=2499 and end_pos=3144
-        # For other joints, 2560 will be autocorrected to be in calibration range
-        56: 2560,  # Present_Position
-        58: 0,  # Present_Speed
-        69: 0,  # Present_Current
-        85: 150,  # Maximum_Acceleration
-    }
-
-
-# Macro for Control Table Value
-def SCS_MAKEWORD(a, b):
-    return (a & 0xFF) | ((b & 0xFF) << 8)
-
-
-def SCS_MAKEDWORD(a, b):
-    return (a & 0xFFFF) | (b & 0xFFFF) << 16
-
-
-def SCS_LOWORD(l):
-    return l & 0xFFFF
-
-
-def SCS_HIWORD(l):
-    return (l >> 16) & 0xFFFF
-
-
-def SCS_LOBYTE(w):
-    return w & 0xFF
-
-
-def SCS_HIBYTE(w):
-    return (w >> 8) & 0xFF
-
-
-class PortHandler:
-    def __init__(self, port):
-        self.port = port
-        # factory default baudrate
-        self.baudrate = DEFAULT_BAUDRATE
-        self.ser = SerialMock()
-
-    def openPort(self):  # noqa: N802
-        return True
-
-    def closePort(self):  # noqa: N802
-        pass
-
-    def setPacketTimeoutMillis(self, timeout_ms):  # noqa: N802
-        del timeout_ms  # unused
-
-    def getBaudRate(self):  # noqa: N802
-        return self.baudrate
-
-    def setBaudRate(self, baudrate):  # noqa: N802
-        self.baudrate = baudrate
-
-
-class PacketHandler:
-    def __init__(self, protocol_version):
-        del protocol_version  # unused
-        # Use packet_handler.data to communicate across Read and Write
-        self.data = {}
-
-
-class GroupSyncRead:
-    def __init__(self, port_handler, packet_handler, address, bytes):
-        self.packet_handler = packet_handler
-
-    def addParam(self, motor_index):  # noqa: N802
-        # Initialize motor default values
-        if motor_index not in self.packet_handler.data:
-            self.packet_handler.data[motor_index] = get_default_motor_values(motor_index)
-
-    def txRxPacket(self):  # noqa: N802
-        return COMM_SUCCESS
-
-    def getData(self, index, address, bytes):  # noqa: N802
-        return self.packet_handler.data[index][address]
-
-
-class GroupSyncWrite:
-    def __init__(self, port_handler, packet_handler, address, bytes):
-        self.packet_handler = packet_handler
-        self.address = address
-
-    def addParam(self, index, data):  # noqa: N802
-        if index not in self.packet_handler.data:
-            self.packet_handler.data[index] = get_default_motor_values(index)
-        self.changeParam(index, data)
-
-    def txPacket(self):  # noqa: N802
-        return COMM_SUCCESS
-
-    def changeParam(self, index, data):  # noqa: N802
-        self.packet_handler.data[index][self.address] = data
-
-
-class SerialMock:
-    def reset_output_buffer(self):
-        pass
-
-    def reset_input_buffer(self):
-        pass
diff --git a/tests/motors/test_feetech.py b/tests/motors/test_feetech.py
index 6c580f6a..42292fb0 100644
--- a/tests/motors/test_feetech.py
+++ b/tests/motors/test_feetech.py
@@ -2,43 +2,195 @@ import sys
 from unittest.mock import patch
 
 import pytest
+import scservo_sdk as scs
 
 from lerobot.common.motors.feetech import FeetechMotorsBus
-from tests.mocks import mock_scservo_sdk
+from tests.mocks.mock_feetech import MockMotors, MockPortHandler
 
 
 @pytest.fixture(autouse=True)
-def patch_scservo_sdk():
-    with patch.dict(sys.modules, {"scservo_sdk": mock_scservo_sdk}):
+def patch_port_handler():
+    if sys.platform == "darwin":
+        with patch.object(scs, "PortHandler", MockPortHandler):
+            yield
+    else:
         yield
 
 
-def test_patch_sdk():
-    assert "scservo_sdk" in sys.modules  # Should be patched
-    assert sys.modules["scservo_sdk"] is mock_scservo_sdk  # Should match the mock
+@pytest.mark.skipif(sys.platform != "darwin", reason=f"No patching needed on {sys.platform=}")
+def test_autouse_patch():
+    """Ensures that the autouse fixture correctly patches scs.PortHandler with MockPortHandler."""
+    assert scs.PortHandler is MockPortHandler
+
+
+@pytest.mark.parametrize(
+    "value, n_bytes, expected",
+    [
+        (0x12,       1, [0x12]),
+        (0x1234,     2, [0x34, 0x12]),
+        (0x12345678, 4, [0x78, 0x56, 0x34, 0x12]),
+        (0,          1, [0x00]),
+        (0,          2, [0x00, 0x00]),
+        (0,          4, [0x00, 0x00, 0x00, 0x00]),
+        (255,        1, [0xFF]),
+        (65535,      2, [0xFF, 0xFF]),
+        (4294967295, 4, [0xFF, 0xFF, 0xFF, 0xFF]),
+    ],
+    ids=[
+        "1 byte",
+        "2 bytes",
+        "4 bytes",
+        "0 with 1 byte",
+        "0 with 2 bytes",
+        "0 with 4 bytes",
+        "max single byte",
+        "max two bytes",
+        "max four bytes",
+    ],
+)  # fmt: skip
+def test_split_int_bytes(value, n_bytes, expected):
+    assert FeetechMotorsBus.split_int_bytes(value, n_bytes) == expected
+
+
+def test_split_int_bytes_invalid_n_bytes():
+    with pytest.raises(NotImplementedError):
+        FeetechMotorsBus.split_int_bytes(100, 3)
+
+
+def test_split_int_bytes_negative_numbers():
+    with pytest.raises(ValueError):
+        neg = FeetechMotorsBus.split_int_bytes(-1, 1)
+        print(neg)
+
+
+def test_split_int_bytes_large_number():
+    with pytest.raises(ValueError):
+        FeetechMotorsBus.split_int_bytes(2**32, 4)  # 4-byte max is 0xFFFFFFFF
 
 
 def test_abc_implementation():
-    # Instantiation should raise an error if the class doesn't implements abstract methods/properties
+    """Instantiation should raise an error if the class doesn't implement abstract methods/properties."""
     FeetechMotorsBus(port="/dev/dummy-port", motors={"dummy": (1, "sts3215")})
 
 
-def test_configure_motors_all_ids_1():
-    # see SCS_SERIES_BAUDRATE_TABLE
-    smaller_baudrate = 19_200
-    smaller_baudrate_value = 7
-
-    # This test expect the configuration was already correct.
-    motors_bus = FeetechMotorsBus(port="/dev/dummy-port", motors={"dummy": (1, "sts3215")})
+@pytest.mark.parametrize(
+    "motors",
+    [
+        None,
+        [1, 2, 3],
+        ["dummy_1", "dummy_2", "dummy_3"],
+        [1, "dummy_2", 3],
+    ],
+    ids=["None", "by ids", "by names", "mixed"],
+)
+def test_read_all_motors(motors):
+    mock_motors = MockMotors([1, 2, 3])
+    positions = [1337, 42, 4016]
+    mock_motors.build_all_motors_stub("Present_Position", return_values=positions)
+    motors_bus = FeetechMotorsBus(
+        port=mock_motors.port,
+        motors={
+            "dummy_1": (1, "sts3215"),
+            "dummy_2": (2, "sts3215"),
+            "dummy_3": (3, "sts3215"),
+        },
+    )
     motors_bus.connect()
-    motors_bus.write("Baud_Rate", [smaller_baudrate_value] * len(motors_bus))
 
-    motors_bus.set_baudrate(smaller_baudrate)
-    motors_bus.write("ID", [1] * len(motors_bus))
-    del motors_bus
+    pos_dict = motors_bus.read("Present_Position", motors=motors)
 
-    # Test configure
-    motors_bus = FeetechMotorsBus(port="/dev/dummy-port", motors={"dummy": (1, "sts3215")})
+    assert mock_motors.stubs["SyncRead_Present_Position_all"].called
+    assert all(returned_pos == pos for returned_pos, pos in zip(pos_dict.values(), positions, strict=True))
+    assert set(pos_dict) == {"dummy_1", "dummy_2", "dummy_3"}
+    assert all(pos >= 0 and pos <= 4095 for pos in pos_dict.values())
+
+
+@pytest.mark.parametrize(
+    "idx, pos",
+    [
+        [1, 1337],
+        [2, 42],
+        [3, 4016],
+    ],
+)
+def test_read_single_motor_by_name(idx, pos):
+    mock_motors = MockMotors([1, 2, 3])
+    mock_motors.build_single_motor_stubs("Present_Position", return_value=pos)
+    motors_bus = FeetechMotorsBus(
+        port=mock_motors.port,
+        motors={
+            "dummy_1": (1, "sts3215"),
+            "dummy_2": (2, "sts3215"),
+            "dummy_3": (3, "sts3215"),
+        },
+    )
     motors_bus.connect()
-    assert motors_bus.are_motors_configured()
-    del motors_bus
+
+    pos_dict = motors_bus.read("Present_Position", f"dummy_{idx}")
+
+    assert mock_motors.stubs[f"SyncRead_Present_Position_{idx}"].called
+    assert pos_dict == {f"dummy_{idx}": pos}
+    assert all(pos >= 0 and pos <= 4095 for pos in pos_dict.values())
+
+
+@pytest.mark.parametrize(
+    "idx, pos",
+    [
+        [1, 1337],
+        [2, 42],
+        [3, 4016],
+    ],
+)
+def test_read_single_motor_by_id(idx, pos):
+    mock_motors = MockMotors([1, 2, 3])
+    mock_motors.build_single_motor_stubs("Present_Position", return_value=pos)
+    motors_bus = FeetechMotorsBus(
+        port=mock_motors.port,
+        motors={
+            "dummy_1": (1, "sts3215"),
+            "dummy_2": (2, "sts3215"),
+            "dummy_3": (3, "sts3215"),
+        },
+    )
+    motors_bus.connect()
+
+    pos_dict = motors_bus.read("Present_Position", idx)
+
+    assert mock_motors.stubs[f"SyncRead_Present_Position_{idx}"].called
+    assert pos_dict == {f"dummy_{idx}": pos}
+    assert all(pos >= 0 and pos <= 4095 for pos in pos_dict.values())
+
+
+@pytest.mark.parametrize(
+    "num_retry, num_invalid_try, pos",
+    [
+        [1, 2, 1337],
+        [2, 3, 42],
+        [3, 2, 4016],
+        [2, 1, 999],
+    ],
+)
+def test_read_num_retry(num_retry, num_invalid_try, pos):
+    mock_motors = MockMotors([1, 2, 3])
+    mock_motors.build_single_motor_stubs(
+        "Present_Position", return_value=pos, num_invalid_try=num_invalid_try
+    )
+    motors_bus = FeetechMotorsBus(
+        port=mock_motors.port,
+        motors={
+            "dummy_1": (1, "sts3215"),
+            "dummy_2": (2, "sts3215"),
+            "dummy_3": (3, "sts3215"),
+        },
+    )
+    motors_bus.connect()
+
+    if num_retry >= num_invalid_try:
+        pos_dict = motors_bus.read("Present_Position", 1, num_retry=num_retry)
+        assert pos_dict == {"dummy_1": pos}
+        assert all(pos >= 0 and pos <= 4095 for pos in pos_dict.values())
+    else:
+        with pytest.raises(ConnectionError):
+            _ = motors_bus.read("Present_Position", 1, num_retry=num_retry)
+
+    assert mock_motors.stubs["SyncRead_Present_Position_1"].calls == num_retry

From dd80dbb4cd61d0ad5ff16b51e4763c0df8a9e17d Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Thu, 20 Mar 2025 14:01:34 +0100
Subject: [PATCH 067/171] Simplify Dxl motors bus import

---
 tests/motors/test_dynamixel.py | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/tests/motors/test_dynamixel.py b/tests/motors/test_dynamixel.py
index 371e7864..ec391dc4 100644
--- a/tests/motors/test_dynamixel.py
+++ b/tests/motors/test_dynamixel.py
@@ -4,7 +4,7 @@ from unittest.mock import patch
 import dynamixel_sdk as dxl
 import pytest
 
-from lerobot.common.motors.dynamixel.dynamixel import DynamixelMotorsBus
+from lerobot.common.motors.dynamixel import DynamixelMotorsBus
 from tests.mocks.mock_dynamixel import MockMotors, MockPortHandler
 
 

From 74d56834af0e32481705a1ea9ce3957fd65ce776 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Thu, 20 Mar 2025 14:03:11 +0100
Subject: [PATCH 068/171] Fix dxl calib import

---
 lerobot/common/motors/dynamixel/dynamixel_calibration.py | 4 +---
 1 file changed, 1 insertion(+), 3 deletions(-)

diff --git a/lerobot/common/motors/dynamixel/dynamixel_calibration.py b/lerobot/common/motors/dynamixel/dynamixel_calibration.py
index 9426d1f8..881435d1 100644
--- a/lerobot/common/motors/dynamixel/dynamixel_calibration.py
+++ b/lerobot/common/motors/dynamixel/dynamixel_calibration.py
@@ -17,10 +17,8 @@
 
 import numpy as np
 
-from ..motors_bus import MotorsBus
+from ..motors_bus import CalibrationMode, MotorsBus, TorqueMode
 from .dynamixel import (
-    CalibrationMode,
-    TorqueMode,
     convert_degrees_to_steps,
 )
 

From 34cd1e47bfc82d4f80d18ac479752a3e347e13a8 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Thu, 20 Mar 2025 14:07:55 +0100
Subject: [PATCH 069/171] Remove obsolete test

---
 tests/motors/test_motors_bus.py | 123 --------------------------------
 1 file changed, 123 deletions(-)
 delete mode 100644 tests/motors/test_motors_bus.py

diff --git a/tests/motors/test_motors_bus.py b/tests/motors/test_motors_bus.py
deleted file mode 100644
index 51588a58..00000000
--- a/tests/motors/test_motors_bus.py
+++ /dev/null
@@ -1,123 +0,0 @@
-# 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.
-"""
-Tests for physical motors and their mocked versions.
-If the physical motors are not connected to the computer, or not working,
-the test will be skipped.
-
-Example of running a specific test:
-```bash
-pytest -sx tests/test_motors.py::test_find_port
-pytest -sx tests/test_motors.py::test_motors_bus
-```
-
-Example of running test on real dynamixel motors connected to the computer:
-```bash
-pytest -sx 'tests/test_motors.py::test_motors_bus[dynamixel-False]'
-```
-
-Example of running test on a mocked version of dynamixel motors:
-```bash
-pytest -sx 'tests/test_motors.py::test_motors_bus[dynamixel-True]'
-```
-"""
-
-# TODO(rcadene): measure fps in nightly?
-# TODO(rcadene): test logs
-# TODO(rcadene): test calibration
-# TODO(rcadene): add compatibility with other motors bus
-
-import time
-
-import numpy as np
-import pytest
-
-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
-
-
-@pytest.mark.parametrize("motor_type, mock", TEST_MOTOR_TYPES)
-@require_motor
-def test_find_port(request, motor_type, mock):
-    if mock:
-        request.getfixturevalue("patch_builtins_input")
-        with pytest.raises(OSError):
-            find_port()
-    else:
-        find_port()
-
-
-@pytest.mark.parametrize("motor_type, mock", TEST_MOTOR_TYPES)
-@require_motor
-def test_motors_bus(request, motor_type, mock):
-    if mock:
-        request.getfixturevalue("patch_builtins_input")
-
-    motors_bus = make_motors_bus(motor_type, mock=mock)
-
-    # Test reading and writing before connecting raises an error
-    with pytest.raises(DeviceNotConnectedError):
-        motors_bus.read("Torque_Enable")
-    with pytest.raises(DeviceNotConnectedError):
-        motors_bus.write("Torque_Enable", 1)
-    with pytest.raises(DeviceNotConnectedError):
-        motors_bus.disconnect()
-
-    # Test deleting the object without connecting first
-    del motors_bus
-
-    # Test connecting
-    motors_bus = make_motors_bus(motor_type, mock=mock)
-    motors_bus.connect()
-
-    # Test connecting twice raises an error
-    with pytest.raises(DeviceAlreadyConnectedError):
-        motors_bus.connect()
-
-    # Test disabling torque and reading torque on all motors
-    motors_bus.write("Torque_Enable", 0)
-    values = motors_bus.read("Torque_Enable")
-    assert isinstance(values, np.ndarray)
-    assert len(values) == len(motors_bus.motors)
-    assert (values == 0).all()
-
-    # Test writing torque on a specific motor
-    motors_bus.write("Torque_Enable", 1, "gripper")
-
-    # Test reading torque from this specific motor. It is now 1
-    values = motors_bus.read("Torque_Enable", "gripper")
-    assert len(values) == 1
-    assert values[0] == 1
-
-    # Test reading torque from all motors. It is 1 for the specific motor,
-    # and 0 on the others.
-    values = motors_bus.read("Torque_Enable")
-    gripper_index = motors_bus.motor_names.index("gripper")
-    assert values[gripper_index] == 1
-    assert values.sum() == 1  # gripper is the only motor to have torque 1
-
-    # Test writing torque on all motors and it is 1 for all.
-    motors_bus.write("Torque_Enable", 1)
-    values = motors_bus.read("Torque_Enable")
-    assert (values == 1).all()
-
-    # Test ordering the motors to move slightly (+1 value among 4096) and this move
-    # can be executed and seen by the motor position sensor
-    values = motors_bus.read("Present_Position")
-    motors_bus.write("Goal_Position", values + 1)
-    # Give time for the motors to move to the goal position
-    time.sleep(1)
-    new_values = motors_bus.read("Present_Position")
-    assert (new_values == values).all()

From 02a1cf6a4e80b4e126a92a65e358dfa616b29517 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Thu, 20 Mar 2025 14:33:36 +0100
Subject: [PATCH 070/171] Fix calibration visualization

---
 .../calibration_visualization_so100.py        | 47 ++++++++++---------
 1 file changed, 26 insertions(+), 21 deletions(-)

diff --git a/lerobot/scripts/calibration_visualization_so100.py b/lerobot/scripts/calibration_visualization_so100.py
index 33573d8b..10ac7c4d 100644
--- a/lerobot/scripts/calibration_visualization_so100.py
+++ b/lerobot/scripts/calibration_visualization_so100.py
@@ -17,7 +17,8 @@ from dataclasses import dataclass
 
 import draccus
 
-from lerobot.common.motors.feetech.feetech import (
+from lerobot.common.motors import MotorsBus
+from lerobot.common.motors.feetech.feetech_calibration import (
     adjusted_to_homing_ticks,
     adjusted_to_motor_ticks,
     convert_degrees_to_ticks,
@@ -30,7 +31,7 @@ from lerobot.common.teleoperators.so100 import SO100Teleop, SO100TeleopConfig  #
 
 
 @dataclass
-class DebugFeetechConfig:
+class DebugConfig:
     teleop: TeleoperatorConfig | None = None
     robot: RobotConfig | None = None
 
@@ -40,48 +41,52 @@ class DebugFeetechConfig:
 
 
 @draccus.wrap()
-def debug_feetech_positions(cfg: DebugFeetechConfig):
+def debug_device_calibration(cfg: DebugConfig):
+    # TODO(aliberts): make device and automatically get its motors_bus
+    device = SO100Teleop(cfg.teleop) if cfg.teleop else SO100Robot(cfg.robot)
+    visualize_motors_bus(device.arm)
+
+
+def visualize_motors_bus(motor_bus: MotorsBus):
     """
     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()
+    motor_bus.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.")
+    # values_dict = {idx: 0 for idx in motors_bus.motor_ids}
+    # motor_bus.write("Torque_Enable", values_dict)
+    # 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"
-            )
+            raw_positions = motor_bus.read("Present_Position")
 
-            # Read *already-homed* positions
-            homed_positions = device.arm.read("Present_Position")
+            # # Read *already-homed* positions
+            # homed_positions = motor_bus.read("Present_Position")
 
-            for i, name in enumerate(device.arm.motor_names):
-                motor_idx, model = device.arm.motors[name]
+            for name, raw_ticks in raw_positions.items():
+                idx = motor_bus.motors[name][0]
+                model = motor_bus.motors[name][1]
 
-                raw_ticks = raw_positions[i]  # 0..4095
-                homed_val = homed_positions[i]  # degrees or % if linear
+                # 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)
+                manual_adjusted = adjusted_to_homing_ticks(raw_ticks, model, motor_bus, 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)
+                inv_ticks = adjusted_to_motor_ticks(manual_ticks, model, motor_bus, idx)
 
                 print(
                     f"{name:15s} | "
                     f"RAW={raw_ticks:4d} | "
-                    f"HOMED_FROM_READ={homed_val:7.2f} | "
+                    # 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} | "
@@ -93,8 +98,8 @@ def debug_feetech_positions(cfg: DebugFeetechConfig):
         pass
     finally:
         print("\nExiting. Disconnecting bus...")
-        device.disconnect()
+        motor_bus.disconnect()
 
 
 if __name__ == "__main__":
-    debug_feetech_positions()
+    debug_device_calibration()

From 287dc13d96766d7fac9bcc4e254911a6d2886ff7 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Thu, 20 Mar 2025 14:44:23 +0100
Subject: [PATCH 071/171] Remove CLI for calibration visualization + move to
 debugging

---
 .../debugging/motors_bus.py}                  | 63 ++++++-------------
 .../motors/feetech/feetech_calibration.py     | 12 ++--
 2 files changed, 26 insertions(+), 49 deletions(-)
 rename lerobot/{scripts/calibration_visualization_so100.py => common/debugging/motors_bus.py} (57%)

diff --git a/lerobot/scripts/calibration_visualization_so100.py b/lerobot/common/debugging/motors_bus.py
similarity index 57%
rename from lerobot/scripts/calibration_visualization_so100.py
rename to lerobot/common/debugging/motors_bus.py
index 10ac7c4d..f41a454b 100644
--- a/lerobot/scripts/calibration_visualization_so100.py
+++ b/lerobot/common/debugging/motors_bus.py
@@ -1,21 +1,18 @@
 """
-usage:
+Usage example
 
 ```python
-python lerobot/scripts/calibration_visualization_so100.py \
-    --teleop.type=so100 \
-    --teleop.port=/dev/tty.usbmodem58760430541
+from lerobot.common.debugging.motors_bus import visualize_motors_bus
+from lerobot.common.robots.so100 import SO100Robot, SO100RobotConfig
 
-python lerobot/scripts/calibration_visualization_so100.py \
-    --robot.type=so100 \
-    --robot.port=/dev/tty.usbmodem585A0084711
+cfg = SO100RobotConfig(port="/dev/tty.usbmodem58760430541")
+so100 = SO100Robot(cfg)
+
+visualize_motors_bus(so100.arm)
 ```
 """
 
 import time
-from dataclasses import dataclass
-
-import draccus
 
 from lerobot.common.motors import MotorsBus
 from lerobot.common.motors.feetech.feetech_calibration import (
@@ -24,64 +21,44 @@ from lerobot.common.motors.feetech.feetech_calibration import (
     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 DebugConfig:
-    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_device_calibration(cfg: DebugConfig):
-    # TODO(aliberts): make device and automatically get its motors_bus
-    device = SO100Teleop(cfg.teleop) if cfg.teleop else SO100Robot(cfg.robot)
-    visualize_motors_bus(device.arm)
-
-
-def visualize_motors_bus(motor_bus: MotorsBus):
+def visualize_motors_bus(motors_bus: MotorsBus):
     """
     Reads each joint's (1) raw ticks, (2) homed ticks, (3) degrees, and (4) invert-adjusted ticks.
     """
-    motor_bus.connect()
+    if not motors_bus.is_connected:
+        motors_bus.connect()
 
     # Disable torque on all motors so you can move them freely by hand
-    # values_dict = {idx: 0 for idx in motors_bus.motor_ids}
-    # motor_bus.write("Torque_Enable", values_dict)
-    # print("Torque disabled on all joints.")
+    values_dict = {idx: 0 for idx in motors_bus.motor_ids}
+    motors_bus.write("Torque_Enable", values_dict)
+    print("Torque disabled on all joints.")
 
     try:
         print("\nPress Ctrl+C to quit.\n")
         while True:
             # Read *raw* positions (no calibration).
-            raw_positions = motor_bus.read("Present_Position")
+            raw_positions = motors_bus.read("Present_Position")
 
             # # Read *already-homed* positions
             # homed_positions = motor_bus.read("Present_Position")
 
             for name, raw_ticks in raw_positions.items():
-                idx = motor_bus.motors[name][0]
-                model = motor_bus.motors[name][1]
+                idx = motors_bus.motors[name][0]
+                model = motors_bus.motors[name][1]
 
                 # 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, motor_bus, idx)
+                manual_adjusted = adjusted_to_homing_ticks(raw_ticks, model, motors_bus, 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, motor_bus, idx)
+                inv_ticks = adjusted_to_motor_ticks(manual_ticks, model, motors_bus, idx)
 
                 print(
                     f"{name:15s} | "
@@ -98,8 +75,8 @@ def visualize_motors_bus(motor_bus: MotorsBus):
         pass
     finally:
         print("\nExiting. Disconnecting bus...")
-        motor_bus.disconnect()
+        motors_bus.disconnect()
 
 
 if __name__ == "__main__":
-    debug_device_calibration()
+    visualize_motors_bus()
diff --git a/lerobot/common/motors/feetech/feetech_calibration.py b/lerobot/common/motors/feetech/feetech_calibration.py
index f967f82d..ad51f222 100644
--- a/lerobot/common/motors/feetech/feetech_calibration.py
+++ b/lerobot/common/motors/feetech/feetech_calibration.py
@@ -266,7 +266,7 @@ def convert_degrees_to_ticks(degrees, model):
     return int(degrees * (resolutions / 360.0))
 
 
-def adjusted_to_homing_ticks(raw_motor_ticks: int, model: str, motorbus, motor_id: int) -> int:
+def adjusted_to_homing_ticks(raw_motor_ticks: int, model: str, motor_bus: MotorsBus, motor_id: int) -> int:
     """
     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).
@@ -282,8 +282,8 @@ def adjusted_to_homing_ticks(raw_motor_ticks: int, model: str, motorbus, motor_i
 
     # 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 motor_bus.calibration is not None:
+        drive_mode = motor_bus.calibration["drive_mode"][motor_id - 1]
 
     if drive_mode:
         ticks *= -1
@@ -291,15 +291,15 @@ def adjusted_to_homing_ticks(raw_motor_ticks: int, model: str, motorbus, motor_i
     return ticks
 
 
-def adjusted_to_motor_ticks(adjusted_pos: int, model: str, motorbus, motor_id: int) -> int:
+def adjusted_to_motor_ticks(adjusted_pos: int, model: str, motor_bus: MotorsBus, 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 motor_bus.calibration is not None:
+        drive_mode = motor_bus.calibration["drive_mode"][motor_id - 1]
 
     if drive_mode:
         adjusted_pos *= -1

From 17a4447cefa24e7b5f5710ed26f2ebd78dbb56e1 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Thu, 20 Mar 2025 14:45:18 +0100
Subject: [PATCH 072/171] Add debugging init

---
 lerobot/common/debugging/__init__.py | 3 +++
 1 file changed, 3 insertions(+)
 create mode 100644 lerobot/common/debugging/__init__.py

diff --git a/lerobot/common/debugging/__init__.py b/lerobot/common/debugging/__init__.py
new file mode 100644
index 00000000..e137aa31
--- /dev/null
+++ b/lerobot/common/debugging/__init__.py
@@ -0,0 +1,3 @@
+from .motors_bus import visualize_motors_bus
+
+__all__ = ["visualize_motors_bus"]

From 375499c323946838948a5c3361b07603c6f31c59 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Thu, 20 Mar 2025 14:47:17 +0100
Subject: [PATCH 073/171] Remove set_operating_mode

---
 lerobot/common/robots/koch/robot_koch.py       | 18 ++++++++++++++++--
 .../common/teleoperators/koch/teleop_koch.py   | 18 ++++++++++++++++--
 2 files changed, 32 insertions(+), 4 deletions(-)

diff --git a/lerobot/common/robots/koch/robot_koch.py b/lerobot/common/robots/koch/robot_koch.py
index 67008f5f..ff2bdb65 100644
--- a/lerobot/common/robots/koch/robot_koch.py
+++ b/lerobot/common/robots/koch/robot_koch.py
@@ -27,7 +27,6 @@ from lerobot.common.motors import TorqueMode
 from lerobot.common.motors.dynamixel import (
     DynamixelMotorsBus,
     run_arm_calibration,
-    set_operating_mode,
 )
 
 from ..robot import Robot
@@ -103,7 +102,22 @@ class KochRobot(Robot):
         self.arm.write("Torque_Enable", TorqueMode.DISABLED.value)
         self.calibrate()
 
-        set_operating_mode(self.arm)
+        # 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 Koch motors
+            self.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"
+        self.arm.write("Operating_Mode", 5, "gripper")
 
         # 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
diff --git a/lerobot/common/teleoperators/koch/teleop_koch.py b/lerobot/common/teleoperators/koch/teleop_koch.py
index ad9745d5..82393655 100644
--- a/lerobot/common/teleoperators/koch/teleop_koch.py
+++ b/lerobot/common/teleoperators/koch/teleop_koch.py
@@ -25,7 +25,6 @@ from lerobot.common.motors import TorqueMode
 from lerobot.common.motors.dynamixel import (
     DynamixelMotorsBus,
     run_arm_calibration,
-    set_operating_mode,
 )
 
 from ..teleoperator import Teleoperator
@@ -88,7 +87,22 @@ class KochTeleop(Teleoperator):
         self.arm.write("Torque_Enable", TorqueMode.DISABLED.value)
         self.calibrate()
 
-        set_operating_mode(self.arm)
+        # 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 Koch motors
+            self.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"
+        self.arm.write("Operating_Mode", 5, "gripper")
 
         # Enable torque on the gripper and move it to 45 degrees so that we can use it as a trigger.
         logging.info("Activating torque.")

From 43bc9404bb6cfb7af7bf15038d74762fef53b405 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Thu, 20 Mar 2025 14:47:53 +0100
Subject: [PATCH 074/171] Remove motors from koch teleop config

---
 .../common/teleoperators/koch/configuration_koch.py  | 10 ----------
 lerobot/common/teleoperators/koch/teleop_koch.py     | 12 ++++++------
 2 files changed, 6 insertions(+), 16 deletions(-)

diff --git a/lerobot/common/teleoperators/koch/configuration_koch.py b/lerobot/common/teleoperators/koch/configuration_koch.py
index 334c3134..2c6a2969 100644
--- a/lerobot/common/teleoperators/koch/configuration_koch.py
+++ b/lerobot/common/teleoperators/koch/configuration_koch.py
@@ -28,13 +28,3 @@ class KochTeleopConfig(TeleoperatorConfig):
     # 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
index 82393655..b394019a 100644
--- a/lerobot/common/teleoperators/koch/teleop_koch.py
+++ b/lerobot/common/teleoperators/koch/teleop_koch.py
@@ -49,12 +49,12 @@ class KochTeleop(Teleoperator):
         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, "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"),
             },
         )
 

From 715d4557af6009dfa9174eab29918b5a874b9e32 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Fri, 21 Mar 2025 11:22:02 +0100
Subject: [PATCH 075/171] Ruff ignore F401 & F403 for init files

---
 pyproject.toml | 3 +++
 1 file changed, 3 insertions(+)

diff --git a/pyproject.toml b/pyproject.toml
index d8cfcfa4..8d285bd7 100644
--- a/pyproject.toml
+++ b/pyproject.toml
@@ -108,6 +108,9 @@ exclude = ["tests/artifacts/**/*.safetensors"]
 [tool.ruff.lint]
 select = ["E4", "E7", "E9", "F", "I", "N", "B", "C4", "SIM"]
 
+[tool.ruff.lint.per-file-ignores]
+"__init__.py" = ["F401", "F403"]
+
 [tool.bandit]
 exclude_dirs = [
     "tests",

From 56c04ffc5313226f66b79bbe02e9074d68bc7724 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Fri, 21 Mar 2025 11:28:11 +0100
Subject: [PATCH 076/171] Move dxl table & cleanup

---
 lerobot/common/motors/dynamixel/__init__.py  |   3 +-
 lerobot/common/motors/dynamixel/dynamixel.py | 138 +------------------
 lerobot/common/motors/dynamixel/tables.py    | 110 +++++++++++++++
 tests/mocks/mock_dynamixel.py                |   2 +-
 4 files changed, 113 insertions(+), 140 deletions(-)
 create mode 100644 lerobot/common/motors/dynamixel/tables.py

diff --git a/lerobot/common/motors/dynamixel/__init__.py b/lerobot/common/motors/dynamixel/__init__.py
index cd86bca1..1bd35361 100644
--- a/lerobot/common/motors/dynamixel/__init__.py
+++ b/lerobot/common/motors/dynamixel/__init__.py
@@ -1,4 +1,3 @@
 from .dynamixel import DynamixelMotorsBus
 from .dynamixel_calibration import run_arm_calibration
-
-__all__ = ["DynamixelMotorsBus", "run_arm_calibration"]
+from .tables import *
diff --git a/lerobot/common/motors/dynamixel/dynamixel.py b/lerobot/common/motors/dynamixel/dynamixel.py
index 413ed173..072e995c 100644
--- a/lerobot/common/motors/dynamixel/dynamixel.py
+++ b/lerobot/common/motors/dynamixel/dynamixel.py
@@ -20,153 +20,17 @@
 
 from copy import deepcopy
 
-import numpy as np
-
 from ..motors_bus import MotorsBus
+from .tables import MODEL_BAUDRATE_TABLE, MODEL_CONTROL_TABLE, MODEL_RESOLUTION
 
 PROTOCOL_VERSION = 2.0
 BAUDRATE = 1_000_000
 DEFAULT_TIMEOUT_MS = 1000
-
 MAX_ID_RANGE = 252
 
-# The following bounds define the lower and upper joints range (after calibration).
-# For joints in degree (i.e. revolute joints), their nominal range is [-180, 180] degrees
-# which corresponds to a half rotation on the left and half rotation on the right.
-# Some joints might require higher range, so we allow up to [-270, 270] degrees until
-# an error is raised.
-LOWER_BOUND_DEGREE = -270
-UPPER_BOUND_DEGREE = 270
-
-# For joints in percentage (i.e. joints that move linearly like the prismatic joint of a gripper),
-# their nominal range is [0, 100] %. For instance, for Aloha gripper, 0% is fully
-# closed, and 100% is fully open. To account for slight calibration issue, we allow up to
-# [-10, 110] until an error is raised.
-LOWER_BOUND_LINEAR = -10
-UPPER_BOUND_LINEAR = 110
-
-HALF_TURN_DEGREE = 180
-
-# https://emanual.robotis.com/docs/en/dxl/x/xl330-m077
-# https://emanual.robotis.com/docs/en/dxl/x/xl330-m288
-# https://emanual.robotis.com/docs/en/dxl/x/xl430-w250
-# https://emanual.robotis.com/docs/en/dxl/x/xm430-w350
-# https://emanual.robotis.com/docs/en/dxl/x/xm540-w270
-# https://emanual.robotis.com/docs/en/dxl/x/xc430-w150
-
-# data_name: (address, size_byte)
-X_SERIES_CONTROL_TABLE = {
-    "Model_Number": (0, 2),
-    "Model_Information": (2, 4),
-    "Firmware_Version": (6, 1),
-    "ID": (7, 1),
-    "Baud_Rate": (8, 1),
-    "Return_Delay_Time": (9, 1),
-    "Drive_Mode": (10, 1),
-    "Operating_Mode": (11, 1),
-    "Secondary_ID": (12, 1),
-    "Protocol_Type": (13, 1),
-    "Homing_Offset": (20, 4),
-    "Moving_Threshold": (24, 4),
-    "Temperature_Limit": (31, 1),
-    "Max_Voltage_Limit": (32, 2),
-    "Min_Voltage_Limit": (34, 2),
-    "PWM_Limit": (36, 2),
-    "Current_Limit": (38, 2),
-    "Acceleration_Limit": (40, 4),
-    "Velocity_Limit": (44, 4),
-    "Max_Position_Limit": (48, 4),
-    "Min_Position_Limit": (52, 4),
-    "Shutdown": (63, 1),
-    "Torque_Enable": (64, 1),
-    "LED": (65, 1),
-    "Status_Return_Level": (68, 1),
-    "Registered_Instruction": (69, 1),
-    "Hardware_Error_Status": (70, 1),
-    "Velocity_I_Gain": (76, 2),
-    "Velocity_P_Gain": (78, 2),
-    "Position_D_Gain": (80, 2),
-    "Position_I_Gain": (82, 2),
-    "Position_P_Gain": (84, 2),
-    "Feedforward_2nd_Gain": (88, 2),
-    "Feedforward_1st_Gain": (90, 2),
-    "Bus_Watchdog": (98, 1),
-    "Goal_PWM": (100, 2),
-    "Goal_Current": (102, 2),
-    "Goal_Velocity": (104, 4),
-    "Profile_Acceleration": (108, 4),
-    "Profile_Velocity": (112, 4),
-    "Goal_Position": (116, 4),
-    "Realtime_Tick": (120, 2),
-    "Moving": (122, 1),
-    "Moving_Status": (123, 1),
-    "Present_PWM": (124, 2),
-    "Present_Current": (126, 2),
-    "Present_Velocity": (128, 4),
-    "Present_Position": (132, 4),
-    "Velocity_Trajectory": (136, 4),
-    "Position_Trajectory": (140, 4),
-    "Present_Input_Voltage": (144, 2),
-    "Present_Temperature": (146, 1),
-}
-
-X_SERIES_BAUDRATE_TABLE = {
-    0: 9_600,
-    1: 57_600,
-    2: 115_200,
-    3: 1_000_000,
-    4: 2_000_000,
-    5: 3_000_000,
-    6: 4_000_000,
-}
-
 CALIBRATION_REQUIRED = ["Goal_Position", "Present_Position"]
 CONVERT_UINT32_TO_INT32_REQUIRED = ["Goal_Position", "Present_Position"]
 
-MODEL_CONTROL_TABLE = {
-    "x_series": X_SERIES_CONTROL_TABLE,
-    "xl330-m077": X_SERIES_CONTROL_TABLE,
-    "xl330-m288": X_SERIES_CONTROL_TABLE,
-    "xl430-w250": X_SERIES_CONTROL_TABLE,
-    "xm430-w350": X_SERIES_CONTROL_TABLE,
-    "xm540-w270": X_SERIES_CONTROL_TABLE,
-    "xc430-w150": X_SERIES_CONTROL_TABLE,
-}
-
-MODEL_RESOLUTION = {
-    "x_series": 4096,
-    "xl330-m077": 4096,
-    "xl330-m288": 4096,
-    "xl430-w250": 4096,
-    "xm430-w350": 4096,
-    "xm540-w270": 4096,
-    "xc430-w150": 4096,
-}
-
-MODEL_BAUDRATE_TABLE = {
-    "x_series": X_SERIES_BAUDRATE_TABLE,
-    "xl330-m077": X_SERIES_BAUDRATE_TABLE,
-    "xl330-m288": X_SERIES_BAUDRATE_TABLE,
-    "xl430-w250": X_SERIES_BAUDRATE_TABLE,
-    "xm430-w350": X_SERIES_BAUDRATE_TABLE,
-    "xm540-w270": X_SERIES_BAUDRATE_TABLE,
-    "xc430-w150": X_SERIES_BAUDRATE_TABLE,
-}
-
-NUM_READ_RETRY = 10
-NUM_WRITE_RETRY = 10
-
-
-def convert_degrees_to_steps(degrees: float | np.ndarray, models: str | list[str]) -> np.ndarray:
-    """This function converts the degree range to the step range for indicating motors rotation.
-    It assumes a motor achieves a full rotation by going from -180 degree position to +180.
-    The motor resolution (e.g. 4096) corresponds to the number of steps needed to achieve a full rotation.
-    """
-    resolutions = [MODEL_RESOLUTION[model] for model in models]
-    steps = degrees / 180 * np.array(resolutions) / 2
-    steps = steps.astype(int)
-    return steps
-
 
 class DynamixelMotorsBus(MotorsBus):
     """
diff --git a/lerobot/common/motors/dynamixel/tables.py b/lerobot/common/motors/dynamixel/tables.py
new file mode 100644
index 00000000..06c5a0ad
--- /dev/null
+++ b/lerobot/common/motors/dynamixel/tables.py
@@ -0,0 +1,110 @@
+# data_name: (address, size_byte)
+# https://emanual.robotis.com/docs/en/dxl/x/{MODEL}/#control-table
+X_SERIES_CONTROL_TABLE = {
+    "Model_Number": (0, 2),
+    "Model_Information": (2, 4),
+    "Firmware_Version": (6, 1),
+    "ID": (7, 1),
+    "Baud_Rate": (8, 1),
+    "Return_Delay_Time": (9, 1),
+    "Drive_Mode": (10, 1),
+    "Operating_Mode": (11, 1),
+    "Secondary_ID": (12, 1),
+    "Protocol_Type": (13, 1),
+    "Homing_Offset": (20, 4),
+    "Moving_Threshold": (24, 4),
+    "Temperature_Limit": (31, 1),
+    "Max_Voltage_Limit": (32, 2),
+    "Min_Voltage_Limit": (34, 2),
+    "PWM_Limit": (36, 2),
+    "Current_Limit": (38, 2),
+    "Acceleration_Limit": (40, 4),
+    "Velocity_Limit": (44, 4),
+    "Max_Position_Limit": (48, 4),
+    "Min_Position_Limit": (52, 4),
+    "Shutdown": (63, 1),
+    "Torque_Enable": (64, 1),
+    "LED": (65, 1),
+    "Status_Return_Level": (68, 1),
+    "Registered_Instruction": (69, 1),
+    "Hardware_Error_Status": (70, 1),
+    "Velocity_I_Gain": (76, 2),
+    "Velocity_P_Gain": (78, 2),
+    "Position_D_Gain": (80, 2),
+    "Position_I_Gain": (82, 2),
+    "Position_P_Gain": (84, 2),
+    "Feedforward_2nd_Gain": (88, 2),
+    "Feedforward_1st_Gain": (90, 2),
+    "Bus_Watchdog": (98, 1),
+    "Goal_PWM": (100, 2),
+    "Goal_Current": (102, 2),
+    "Goal_Velocity": (104, 4),
+    "Profile_Acceleration": (108, 4),
+    "Profile_Velocity": (112, 4),
+    "Goal_Position": (116, 4),
+    "Realtime_Tick": (120, 2),
+    "Moving": (122, 1),
+    "Moving_Status": (123, 1),
+    "Present_PWM": (124, 2),
+    "Present_Current": (126, 2),
+    "Present_Velocity": (128, 4),
+    "Present_Position": (132, 4),
+    "Velocity_Trajectory": (136, 4),
+    "Position_Trajectory": (140, 4),
+    "Present_Input_Voltage": (144, 2),
+    "Present_Temperature": (146, 1),
+}
+
+# https://emanual.robotis.com/docs/en/dxl/x/{MODEL}/#baud-rate8
+X_SERIES_BAUDRATE_TABLE = {
+    0: 9_600,
+    1: 57_600,
+    2: 115_200,
+    3: 1_000_000,
+    4: 2_000_000,
+    5: 3_000_000,
+    6: 4_000_000,
+}
+
+# {model: model_resolution}
+# https://emanual.robotis.com/docs/en/dxl/x/{MODEL}/#specifications
+MODEL_RESOLUTION = {
+    "x_series": 4096,
+    "xl330-m077": 4096,
+    "xl330-m288": 4096,
+    "xl430-w250": 4096,
+    "xm430-w350": 4096,
+    "xm540-w270": 4096,
+    "xc430-w150": 4096,
+}
+
+# {model: model_number}
+# https://emanual.robotis.com/docs/en/dxl/x/{MODEL}/#control-table-of-eeprom-area
+MODELS_TABLE = {
+    "xl330-m077": 1190,
+    "xl330-m288": 1200,
+    "xl430-w250": 1060,
+    "xm430-w350": 1020,
+    "xm540-w270": 1120,
+    "xc430-w150": 1070,
+}
+
+MODEL_CONTROL_TABLE = {
+    "x_series": X_SERIES_CONTROL_TABLE,
+    "xl330-m077": X_SERIES_CONTROL_TABLE,
+    "xl330-m288": X_SERIES_CONTROL_TABLE,
+    "xl430-w250": X_SERIES_CONTROL_TABLE,
+    "xm430-w350": X_SERIES_CONTROL_TABLE,
+    "xm540-w270": X_SERIES_CONTROL_TABLE,
+    "xc430-w150": X_SERIES_CONTROL_TABLE,
+}
+
+MODEL_BAUDRATE_TABLE = {
+    "x_series": X_SERIES_BAUDRATE_TABLE,
+    "xl330-m077": X_SERIES_BAUDRATE_TABLE,
+    "xl330-m288": X_SERIES_BAUDRATE_TABLE,
+    "xl430-w250": X_SERIES_BAUDRATE_TABLE,
+    "xm430-w350": X_SERIES_BAUDRATE_TABLE,
+    "xm540-w270": X_SERIES_BAUDRATE_TABLE,
+    "xc430-w150": X_SERIES_BAUDRATE_TABLE,
+}
diff --git a/tests/mocks/mock_dynamixel.py b/tests/mocks/mock_dynamixel.py
index e45ff1b4..3f55f058 100644
--- a/tests/mocks/mock_dynamixel.py
+++ b/tests/mocks/mock_dynamixel.py
@@ -6,7 +6,7 @@ import dynamixel_sdk as dxl
 import serial
 from mock_serial import MockSerial
 
-from lerobot.common.motors.dynamixel.dynamixel import X_SERIES_CONTROL_TABLE
+from lerobot.common.motors.dynamixel import X_SERIES_CONTROL_TABLE
 
 # https://emanual.robotis.com/docs/en/dxl/crc/
 DXL_CRC_TABLE = [

From a32081757d408c9b9eeb24188716748ebf75a9f3 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Fri, 21 Mar 2025 12:13:44 +0100
Subject: [PATCH 077/171] Add Motor class

---
 lerobot/common/motors/__init__.py   |  4 +-
 lerobot/common/motors/motors_bus.py | 81 ++++++++++++++++-------------
 tests/motors/test_dynamixel.py      | 53 +++++++++----------
 3 files changed, 71 insertions(+), 67 deletions(-)

diff --git a/lerobot/common/motors/__init__.py b/lerobot/common/motors/__init__.py
index a746ba96..3261ae7e 100644
--- a/lerobot/common/motors/__init__.py
+++ b/lerobot/common/motors/__init__.py
@@ -1,3 +1 @@
-from .motors_bus import CalibrationMode, DriveMode, MotorsBus, TorqueMode
-
-__all__ = ["CalibrationMode", "DriveMode", "MotorsBus", "TorqueMode"]
+from .motors_bus import CalibrationMode, DriveMode, Motor, MotorsBus, TorqueMode
diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py
index 24683730..0ae7d223 100644
--- a/lerobot/common/motors/motors_bus.py
+++ b/lerobot/common/motors/motors_bus.py
@@ -22,11 +22,12 @@
 import abc
 import json
 import time
+from dataclasses import dataclass
 from enum import Enum
 from functools import cached_property
 from pathlib import Path
 from pprint import pformat
-from typing import Protocol
+from typing import Protocol, TypeAlias, Union
 
 import serial
 import tqdm
@@ -35,6 +36,8 @@ from deepdiff import DeepDiff
 from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError
 from lerobot.common.utils.utils import capture_timestamp_utc
 
+MotorLike: TypeAlias = Union[str, int, "Motor"]
+
 MAX_ID_RANGE = 252
 
 
@@ -197,6 +200,12 @@ class GroupSyncWrite(Protocol):
     def txPacket(self): ...
 
 
+@dataclass
+class Motor:
+    id: int
+    model: str
+
+
 class MotorsBus(abc.ABC):
     """The main LeRobot class for implementing motors buses.
 
@@ -248,7 +257,7 @@ class MotorsBus(abc.ABC):
     def __init__(
         self,
         port: str,
-        motors: dict[str, tuple[int, str]],
+        motors: dict[str, Motor],
     ):
         self.port = port
         self.motors = motors
@@ -262,8 +271,8 @@ class MotorsBus(abc.ABC):
         self.logs = {}  # TODO(aliberts): use subclass logger
         self.calibration = None
 
-        self._id_to_model = dict(self.motors.values())
-        self._id_to_name = {idx: name for name, (idx, _) in self.motors.items()}
+        self._id_to_model = {m.id: m.model for m in self.motors.values()}
+        self._id_to_name = {m.id: name for name, m in self.motors.items()}
 
     def __len__(self):
         return len(self.motors)
@@ -278,39 +287,39 @@ class MotorsBus(abc.ABC):
 
     @cached_property
     def _has_different_ctrl_tables(self) -> bool:
-        if len(self.motor_models) < 2:
+        if len(self.models) < 2:
             return False
 
-        first_table = self.model_ctrl_table[self.motor_models[0]]
-        return any(DeepDiff(first_table, self.model_ctrl_table[model]) for model in self.motor_models[1:])
+        first_table = self.model_ctrl_table[self.models[0]]
+        return any(DeepDiff(first_table, self.model_ctrl_table[model]) for model in self.models[1:])
 
-    def idx_to_model(self, idx: int) -> str:
-        return self._id_to_model[idx]
+    def id_to_model(self, motor_id: int) -> str:
+        return self._id_to_model[motor_id]
 
-    def idx_to_name(self, idx: int) -> str:
-        return self._id_to_name[idx]
+    def id_to_name(self, motor_id: int) -> str:
+        return self._id_to_name[motor_id]
 
     @cached_property
-    def motor_names(self) -> list[str]:
+    def names(self) -> list[str]:
         return list(self.motors)
 
     @cached_property
-    def motor_models(self) -> list[str]:
-        return [model for _, model in self.motors.values()]
+    def models(self) -> list[str]:
+        return [m.model for m in self.motors.values()]
 
     @cached_property
-    def motor_ids(self) -> list[int]:
-        return [idx for idx, _ in self.motors.values()]
+    def ids(self) -> list[int]:
+        return [m.id for m in self.motors.values()]
 
     def _validate_motors(self) -> None:
         # TODO(aliberts): improve error messages for this (display problematics values)
-        if len(self.motor_ids) != len(set(self.motor_ids)):
+        if len(self.ids) != len(set(self.ids)):
             raise ValueError("Some motors have the same id.")
 
-        if len(self.motor_names) != len(set(self.motor_names)):
+        if len(self.names) != len(set(self.names)):
             raise ValueError("Some motors have the same name.")
 
-        if any(model not in self.model_resolution_table for model in self.motor_models):
+        if any(model not in self.model_resolution_table for model in self.models):
             raise ValueError("Some motors models are not available.")
 
     @property
@@ -347,13 +356,13 @@ class MotorsBus(abc.ABC):
         """
         try:
             # TODO(aliberts): use ping instead
-            return (self.motor_ids == self.read("ID")).all()
+            return (self.ids == self.read("ID")).all()
         except ConnectionError as e:
             print(e)
             return False
 
-    def ping(self, motor: str | int, num_retry: int | None = None) -> int:
-        idx = self.get_safe_id(motor)
+    def ping(self, motor: MotorLike, num_retry: int | None = None) -> int:
+        idx = self.get_motor_id(motor)
         for _ in range(num_retry):
             model_number, comm, _ = self.packet_handler.ping(self.port, idx)
             if self._is_comm_success(comm):
@@ -453,16 +462,18 @@ class MotorsBus(abc.ABC):
         """
         pass
 
-    def get_safe_id(self, motor: str | int) -> int:
+    def get_motor_id(self, motor: MotorLike) -> int:
         if isinstance(motor, str):
-            return self.motors[motor][0]
+            return self.motors[motor].id
         elif isinstance(motor, int):
             return motor
+        elif isinstance(motor, Motor):
+            return motor.id
         else:
-            raise ValueError(f"{motor} should be int or str.")
+            raise ValueError(f"{motor} should be int, str or Motor.")
 
     def read(
-        self, data_name: str, motors: str | int | list[str | int] | None = None, num_retry: int = 1
+        self, data_name: str, motors: MotorLike | list[MotorLike] | None = None, num_retry: int = 1
     ) -> dict[str, float]:
         if not self.is_connected:
             raise DeviceNotConnectedError(
@@ -472,17 +483,17 @@ class MotorsBus(abc.ABC):
         start_time = time.perf_counter()
 
         if motors is None:
-            motors = self.motor_ids
+            motors = self.ids
 
         if isinstance(motors, (str, int)):
             motors = [motors]
 
-        motor_ids = [self.get_safe_id(motor) for motor in motors]
+        motor_ids = [self.get_motor_id(motor) for motor in motors]
         if self._has_different_ctrl_tables:
-            models = [self.idx_to_model(idx) for idx in motor_ids]
+            models = [self.id_to_model(idx) for idx in motor_ids]
             assert_same_address(self.model_ctrl_table, models, data_name)
 
-        model = self.idx_to_model(next(iter(motor_ids)))
+        model = self.id_to_model(next(iter(motor_ids)))
         addr, n_bytes = self.model_ctrl_table[model][data_name]
 
         comm, ids_values = self._read(motor_ids, addr, n_bytes, num_retry)
@@ -496,7 +507,7 @@ class MotorsBus(abc.ABC):
             ids_values = self.calibrate_values(ids_values)
 
         # TODO(aliberts): return keys in the same format we got them?
-        ids_values = {self.idx_to_name(idx): val for idx, val in ids_values.items()}
+        ids_values = {self.id_to_name(idx): val for idx, val in ids_values.items()}
 
         # 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_ids)
@@ -540,7 +551,7 @@ class MotorsBus(abc.ABC):
     #     for idx in motor_ids:
     #         value = self.reader.getData(idx, address, n_bytes)
 
-    def write(self, data_name: str, values_dict: dict[str | int, int], num_retry: int = 1) -> None:
+    def write(self, data_name: str, values_dict: dict[MotorLike, int], num_retry: int = 1) -> None:
         if not self.is_connected:
             raise DeviceNotConnectedError(
                 f"{self.__class__.__name__}('{self.port}') is not connected. You need to run `{self.__class__.__name__}.connect()`."
@@ -548,16 +559,16 @@ class MotorsBus(abc.ABC):
 
         start_time = time.perf_counter()
 
-        ids_values = {self.get_safe_id(motor): val for motor, val in values_dict.items()}
+        ids_values = {self.get_motor_id(motor): val for motor, val in values_dict.items()}
 
         if self._has_different_ctrl_tables:
-            models = [self.idx_to_model(idx) for idx in ids_values]
+            models = [self.id_to_model(idx) for idx in ids_values]
             assert_same_address(self.model_ctrl_table, models, data_name)
 
         if data_name in self.calibration_required and self.calibration is not None:
             ids_values = self.uncalibrate_values(ids_values)
 
-        model = self.idx_to_model(next(iter(ids_values)))
+        model = self.id_to_model(next(iter(ids_values)))
         addr, n_bytes = self.model_ctrl_table[model][data_name]
 
         comm = self._write(ids_values, addr, n_bytes, num_retry)
diff --git a/tests/motors/test_dynamixel.py b/tests/motors/test_dynamixel.py
index ec391dc4..ce50dd91 100644
--- a/tests/motors/test_dynamixel.py
+++ b/tests/motors/test_dynamixel.py
@@ -4,6 +4,7 @@ from unittest.mock import patch
 import dynamixel_sdk as dxl
 import pytest
 
+from lerobot.common.motors import Motor
 from lerobot.common.motors.dynamixel import DynamixelMotorsBus
 from tests.mocks.mock_dynamixel import MockMotors, MockPortHandler
 
@@ -17,6 +18,15 @@ def patch_port_handler():
         yield
 
 
+@pytest.fixture
+def dummy_motors() -> dict[str, Motor]:
+    return {
+        "dummy_1": Motor(id=1, model="xl430-w250"),
+        "dummy_2": Motor(id=2, model="xm540-w270"),
+        "dummy_3": Motor(id=3, model="xl330-m077"),
+    }
+
+
 @pytest.mark.skipif(sys.platform != "darwin", reason=f"No patching needed on {sys.platform=}")
 def test_autouse_patch():
     """Ensures that the autouse fixture correctly patches dxl.PortHandler with MockPortHandler."""
@@ -68,8 +78,9 @@ def test_split_int_bytes_large_number():
         DynamixelMotorsBus.split_int_bytes(2**32, 4)  # 4-byte max is 0xFFFFFFFF
 
 
-def test_abc_implementation():
+def test_abc_implementation(dummy_motors):
     """Instantiation should raise an error if the class doesn't implement abstract methods/properties."""
+    DynamixelMotorsBus(port="/dev/dummy-port", motors=dummy_motors)
     DynamixelMotorsBus(port="/dev/dummy-port", motors={"dummy": (1, "xl330-m077")})
 
 
@@ -83,17 +94,13 @@ def test_abc_implementation():
     ],
     ids=["None", "by ids", "by names", "mixed"],
 )
-def test_read_all_motors(motors):
+def test_read_all_motors(motors, dummy_motors):
     mock_motors = MockMotors([1, 2, 3])
     positions = [1337, 42, 4016]
-    mock_motors.build_all_motors_stub("Present_Position", return_values=positions)
+    mock_motors.build_sync_read_all_motors_stub("Present_Position", return_values=positions)
     motors_bus = DynamixelMotorsBus(
         port=mock_motors.port,
-        motors={
-            "dummy_1": (1, "xl330-m077"),
-            "dummy_2": (2, "xl330-m077"),
-            "dummy_3": (3, "xl330-m077"),
-        },
+        motors=dummy_motors,
     )
     motors_bus.connect()
 
@@ -113,16 +120,12 @@ def test_read_all_motors(motors):
         [3, 4016],
     ],
 )
-def test_read_single_motor_by_name(idx, pos):
+def test_read_single_motor_by_name(idx, pos, dummy_motors):
     mock_motors = MockMotors([1, 2, 3])
-    mock_motors.build_single_motor_stubs("Present_Position", return_value=pos)
+    mock_motors.build_sync_read_single_motor_stubs("Present_Position", return_value=pos)
     motors_bus = DynamixelMotorsBus(
         port=mock_motors.port,
-        motors={
-            "dummy_1": (1, "xl330-m077"),
-            "dummy_2": (2, "xl330-m077"),
-            "dummy_3": (3, "xl330-m077"),
-        },
+        motors=dummy_motors,
     )
     motors_bus.connect()
 
@@ -141,16 +144,12 @@ def test_read_single_motor_by_name(idx, pos):
         [3, 4016],
     ],
 )
-def test_read_single_motor_by_id(idx, pos):
+def test_read_single_motor_by_id(idx, pos, dummy_motors):
     mock_motors = MockMotors([1, 2, 3])
-    mock_motors.build_single_motor_stubs("Present_Position", return_value=pos)
+    mock_motors.build_sync_read_single_motor_stubs("Present_Position", return_value=pos)
     motors_bus = DynamixelMotorsBus(
         port=mock_motors.port,
-        motors={
-            "dummy_1": (1, "xl330-m077"),
-            "dummy_2": (2, "xl330-m077"),
-            "dummy_3": (3, "xl330-m077"),
-        },
+        motors=dummy_motors,
     )
     motors_bus.connect()
 
@@ -170,18 +169,14 @@ def test_read_single_motor_by_id(idx, pos):
         [2, 1, 999],
     ],
 )
-def test_read_num_retry(num_retry, num_invalid_try, pos):
+def test_read_num_retry(num_retry, num_invalid_try, pos, dummy_motors):
     mock_motors = MockMotors([1, 2, 3])
-    mock_motors.build_single_motor_stubs(
+    mock_motors.build_sync_read_single_motor_stubs(
         "Present_Position", return_value=pos, num_invalid_try=num_invalid_try
     )
     motors_bus = DynamixelMotorsBus(
         port=mock_motors.port,
-        motors={
-            "dummy_1": (1, "xl330-m077"),
-            "dummy_2": (2, "xl330-m077"),
-            "dummy_3": (3, "xl330-m077"),
-        },
+        motors=dummy_motors,
     )
     motors_bus.connect()
 

From 3d119c0ccbfcfaf48ff05fa672a45429d362ab23 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Fri, 21 Mar 2025 12:31:41 +0100
Subject: [PATCH 078/171] Add single value write

---
 lerobot/common/motors/motors_bus.py | 9 +++++++--
 1 file changed, 7 insertions(+), 2 deletions(-)

diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py
index 0ae7d223..725ea454 100644
--- a/lerobot/common/motors/motors_bus.py
+++ b/lerobot/common/motors/motors_bus.py
@@ -551,7 +551,7 @@ class MotorsBus(abc.ABC):
     #     for idx in motor_ids:
     #         value = self.reader.getData(idx, address, n_bytes)
 
-    def write(self, data_name: str, values_dict: dict[MotorLike, int], num_retry: int = 1) -> None:
+    def write(self, data_name: str, values: int | dict[MotorLike, int], num_retry: int = 1) -> None:
         if not self.is_connected:
             raise DeviceNotConnectedError(
                 f"{self.__class__.__name__}('{self.port}') is not connected. You need to run `{self.__class__.__name__}.connect()`."
@@ -559,7 +559,12 @@ class MotorsBus(abc.ABC):
 
         start_time = time.perf_counter()
 
-        ids_values = {self.get_motor_id(motor): val for motor, val in values_dict.items()}
+        if isinstance(values, int):
+            ids_values = {id_: values for id_ in self.ids}
+        elif isinstance(values, dict):
+            ids_values = {self.get_motor_id(motor): val for motor, val in values.items()}
+        else:
+            raise ValueError(f"'values' is expected to be a single value or a dict. Got {values}")
 
         if self._has_different_ctrl_tables:
             models = [self.id_to_model(idx) for idx in ids_values]

From 2abfa5838d05795eb4df535773cb3d2cf67dd8b7 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sat, 22 Mar 2025 00:34:07 +0100
Subject: [PATCH 079/171] Improve read ergonomics & typing, rm
 find_motor_indices

---
 lerobot/common/motors/motors_bus.py | 88 ++++++++++++-----------------
 1 file changed, 37 insertions(+), 51 deletions(-)

diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py
index 725ea454..8343d922 100644
--- a/lerobot/common/motors/motors_bus.py
+++ b/lerobot/common/motors/motors_bus.py
@@ -27,16 +27,16 @@ from enum import Enum
 from functools import cached_property
 from pathlib import Path
 from pprint import pformat
-from typing import Protocol, TypeAlias, Union
+from typing import Protocol, TypeAlias, overload
 
 import serial
-import tqdm
 from deepdiff import DeepDiff
 
 from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError
 from lerobot.common.utils.utils import capture_timestamp_utc
 
-MotorLike: TypeAlias = Union[str, int, "Motor"]
+NameOrID: TypeAlias = str | int
+Value: TypeAlias = int | float
 
 MAX_ID_RANGE = 252
 
@@ -361,41 +361,20 @@ class MotorsBus(abc.ABC):
             print(e)
             return False
 
-    def ping(self, motor: MotorLike, num_retry: int | None = None) -> int:
+    def ping(self, motor: NameOrID, num_retry: int = 0, raise_on_error: bool = False) -> int | None:
         idx = self.get_motor_id(motor)
-        for _ in range(num_retry):
-            model_number, comm, _ = self.packet_handler.ping(self.port, idx)
+        for _ in range(1 + num_retry):
+            model_number, comm, error = self.packet_handler.ping(self.port_handler, idx)
             if self._is_comm_success(comm):
                 return model_number
 
-        # TODO(aliberts): Should we?
-        return comm
+        if raise_on_error:
+            raise ConnectionError(f"Ping motor {motor} returned a {error} error code.")
 
     @abc.abstractmethod
-    def broadcast_ping(self, num_retry: int | None = None):
-        ...
-        # TODO(aliberts): this will replace 'find_motor_indices'
-
-    def find_motor_indices(self, possible_ids: list[str] = None, num_retry: int = 2):
-        if possible_ids is None:
-            possible_ids = range(MAX_ID_RANGE)
-
-        indices = []
-        for idx in tqdm.tqdm(possible_ids):
-            try:
-                present_idx = self.read("ID", idx, num_retry=num_retry)[0]
-            except ConnectionError:
-                continue
-
-            if idx != present_idx:
-                # sanity check
-                raise OSError(
-                    "Motor index used to communicate through the bus is not the same as the one present in the motor "
-                    "memory. The motor memory might be damaged."
-                )
-            indices.append(idx)
-
-        return indices
+    def broadcast_ping(
+        self, num_retry: int = 0, raise_on_error: bool = False
+    ) -> dict[int, list[int, int]] | None: ...
 
     def set_baudrate(self, baudrate) -> None:
         present_bus_baudrate = self.port_handler.getBaudRate()
@@ -462,19 +441,23 @@ class MotorsBus(abc.ABC):
         """
         pass
 
-    def get_motor_id(self, motor: MotorLike) -> int:
+    def get_motor_id(self, motor: NameOrID) -> int:
         if isinstance(motor, str):
             return self.motors[motor].id
         elif isinstance(motor, int):
             return motor
-        elif isinstance(motor, Motor):
-            return motor.id
         else:
-            raise ValueError(f"{motor} should be int, str or Motor.")
+            raise TypeError(f"'{motor}' should be int, str.")
 
+    @overload
+    def read(self, data_name: str, motors: None = ...) -> dict[str, Value]: ...
+    @overload
+    def read(self, data_name: str, motors: NameOrID) -> dict[NameOrID, Value]: ...
+    @overload
+    def read(self, data_name: str, motors: list[NameOrID]) -> dict[NameOrID, Value]: ...
     def read(
-        self, data_name: str, motors: MotorLike | list[MotorLike] | None = None, num_retry: int = 1
-    ) -> dict[str, float]:
+        self, data_name: str, motors: NameOrID | list[NameOrID] | None = None, num_retry: int = 0
+    ) -> dict[NameOrID, Value]:
         if not self.is_connected:
             raise DeviceNotConnectedError(
                 f"{self.__class__.__name__}('{self.port}') is not connected. You need to run `{self.__class__.__name__}.connect()`."
@@ -482,13 +465,17 @@ class MotorsBus(abc.ABC):
 
         start_time = time.perf_counter()
 
+        id_key_map: dict[int, NameOrID] = {}
         if motors is None:
-            motors = self.ids
+            id_key_map = {m.id: name for name, m in self.motors.items()}
+        elif isinstance(motors, (str, int)):
+            id_key_map = {self.get_motor_id(motors): motors}
+        elif isinstance(motors, list):
+            id_key_map = {self.get_motor_id(m): m for m in motors}
+        else:
+            raise TypeError(motors)
 
-        if isinstance(motors, (str, int)):
-            motors = [motors]
-
-        motor_ids = [self.get_motor_id(motor) for motor in motors]
+        motor_ids = list(id_key_map)
         if self._has_different_ctrl_tables:
             models = [self.id_to_model(idx) for idx in motor_ids]
             assert_same_address(self.model_ctrl_table, models, data_name)
@@ -506,8 +493,7 @@ class MotorsBus(abc.ABC):
         if data_name in self.calibration_required and self.calibration is not None:
             ids_values = self.calibrate_values(ids_values)
 
-        # TODO(aliberts): return keys in the same format we got them?
-        ids_values = {self.id_to_name(idx): val for idx, val in ids_values.items()}
+        keys_values = {id_key_map[idx]: val for idx, val in ids_values.items()}
 
         # 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_ids)
@@ -517,10 +503,10 @@ class MotorsBus(abc.ABC):
         ts_utc_name = get_log_name("timestamp_utc", "read", data_name, motor_ids)
         self.logs[ts_utc_name] = capture_timestamp_utc()
 
-        return ids_values
+        return keys_values
 
     def _read(
-        self, motor_ids: list[str], address: int, n_bytes: int, num_retry: int = 1
+        self, motor_ids: list[str], address: int, n_bytes: int, num_retry: int = 0
     ) -> tuple[int, dict[int, int]]:
         self.reader.clearParam()
         self.reader.start_address = address
@@ -534,7 +520,7 @@ class MotorsBus(abc.ABC):
         for idx in motor_ids:
             self.reader.addParam(idx)
 
-        for _ in range(num_retry):
+        for _ in range(1 + num_retry):
             comm = self.reader.txRxPacket()
             if self._is_comm_success(comm):
                 break
@@ -551,7 +537,7 @@ class MotorsBus(abc.ABC):
     #     for idx in motor_ids:
     #         value = self.reader.getData(idx, address, n_bytes)
 
-    def write(self, data_name: str, values: int | dict[MotorLike, int], num_retry: int = 1) -> None:
+    def write(self, data_name: str, values: int | dict[NameOrID, int], num_retry: int = 0) -> None:
         if not self.is_connected:
             raise DeviceNotConnectedError(
                 f"{self.__class__.__name__}('{self.port}') is not connected. You need to run `{self.__class__.__name__}.connect()`."
@@ -591,7 +577,7 @@ class MotorsBus(abc.ABC):
         ts_utc_name = get_log_name("timestamp_utc", "write", data_name, list(ids_values))
         self.logs[ts_utc_name] = capture_timestamp_utc()
 
-    def _write(self, ids_values: dict[int, int], address: int, n_bytes: int, num_retry: int = 1) -> int:
+    def _write(self, ids_values: dict[int, int], address: int, n_bytes: int, num_retry: int = 0) -> int:
         self.writer.clearParam()
         self.writer.start_address = address
         self.writer.data_length = n_bytes
@@ -600,7 +586,7 @@ class MotorsBus(abc.ABC):
             data = self.split_int_bytes(value, n_bytes)
             self.writer.addParam(idx, data)
 
-        for _ in range(num_retry):
+        for _ in range(1 + num_retry):
             comm = self.writer.txPacket()
             if self._is_comm_success(comm):
                 break

From 6fa859fa198c41907366408e5e4e329f95f6609d Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sat, 22 Mar 2025 00:39:41 +0100
Subject: [PATCH 080/171] Improve dynamixel mocking

---
 tests/mocks/mock_dynamixel.py  | 210 +++++++++++++++++++--------------
 tests/motors/test_dynamixel.py |  53 +++++----
 2 files changed, 152 insertions(+), 111 deletions(-)

diff --git a/tests/mocks/mock_dynamixel.py b/tests/mocks/mock_dynamixel.py
index 3f55f058..4ea47aea 100644
--- a/tests/mocks/mock_dynamixel.py
+++ b/tests/mocks/mock_dynamixel.py
@@ -10,43 +10,38 @@ from lerobot.common.motors.dynamixel import X_SERIES_CONTROL_TABLE
 
 # https://emanual.robotis.com/docs/en/dxl/crc/
 DXL_CRC_TABLE = [
-    0x0000, 0x8005, 0x800F, 0x000A, 0x801B, 0x001E, 0x0014,
-    0x8011, 0x8033, 0x0036, 0x003C, 0x8039, 0x0028, 0x802D,
-    0x8027, 0x0022, 0x8063, 0x0066, 0x006C, 0x8069, 0x0078,
-    0x807D, 0x8077, 0x0072, 0x0050, 0x8055, 0x805F, 0x005A,
-    0x804B, 0x004E, 0x0044, 0x8041, 0x80C3, 0x00C6, 0x00CC,
-    0x80C9, 0x00D8, 0x80DD, 0x80D7, 0x00D2, 0x00F0, 0x80F5,
-    0x80FF, 0x00FA, 0x80EB, 0x00EE, 0x00E4, 0x80E1, 0x00A0,
-    0x80A5, 0x80AF, 0x00AA, 0x80BB, 0x00BE, 0x00B4, 0x80B1,
-    0x8093, 0x0096, 0x009C, 0x8099, 0x0088, 0x808D, 0x8087,
-    0x0082, 0x8183, 0x0186, 0x018C, 0x8189, 0x0198, 0x819D,
-    0x8197, 0x0192, 0x01B0, 0x81B5, 0x81BF, 0x01BA, 0x81AB,
-    0x01AE, 0x01A4, 0x81A1, 0x01E0, 0x81E5, 0x81EF, 0x01EA,
-    0x81FB, 0x01FE, 0x01F4, 0x81F1, 0x81D3, 0x01D6, 0x01DC,
-    0x81D9, 0x01C8, 0x81CD, 0x81C7, 0x01C2, 0x0140, 0x8145,
-    0x814F, 0x014A, 0x815B, 0x015E, 0x0154, 0x8151, 0x8173,
-    0x0176, 0x017C, 0x8179, 0x0168, 0x816D, 0x8167, 0x0162,
-    0x8123, 0x0126, 0x012C, 0x8129, 0x0138, 0x813D, 0x8137,
-    0x0132, 0x0110, 0x8115, 0x811F, 0x011A, 0x810B, 0x010E,
-    0x0104, 0x8101, 0x8303, 0x0306, 0x030C, 0x8309, 0x0318,
-    0x831D, 0x8317, 0x0312, 0x0330, 0x8335, 0x833F, 0x033A,
-    0x832B, 0x032E, 0x0324, 0x8321, 0x0360, 0x8365, 0x836F,
-    0x036A, 0x837B, 0x037E, 0x0374, 0x8371, 0x8353, 0x0356,
-    0x035C, 0x8359, 0x0348, 0x834D, 0x8347, 0x0342, 0x03C0,
-    0x83C5, 0x83CF, 0x03CA, 0x83DB, 0x03DE, 0x03D4, 0x83D1,
-    0x83F3, 0x03F6, 0x03FC, 0x83F9, 0x03E8, 0x83ED, 0x83E7,
-    0x03E2, 0x83A3, 0x03A6, 0x03AC, 0x83A9, 0x03B8, 0x83BD,
-    0x83B7, 0x03B2, 0x0390, 0x8395, 0x839F, 0x039A, 0x838B,
-    0x038E, 0x0384, 0x8381, 0x0280, 0x8285, 0x828F, 0x028A,
-    0x829B, 0x029E, 0x0294, 0x8291, 0x82B3, 0x02B6, 0x02BC,
-    0x82B9, 0x02A8, 0x82AD, 0x82A7, 0x02A2, 0x82E3, 0x02E6,
-    0x02EC, 0x82E9, 0x02F8, 0x82FD, 0x82F7, 0x02F2, 0x02D0,
-    0x82D5, 0x82DF, 0x02DA, 0x82CB, 0x02CE, 0x02C4, 0x82C1,
-    0x8243, 0x0246, 0x024C, 0x8249, 0x0258, 0x825D, 0x8257,
-    0x0252, 0x0270, 0x8275, 0x827F, 0x027A, 0x826B, 0x026E,
-    0x0264, 0x8261, 0x0220, 0x8225, 0x822F, 0x022A, 0x823B,
-    0x023E, 0x0234, 0x8231, 0x8213, 0x0216, 0x021C, 0x8219,
-    0x0208, 0x820D, 0x8207, 0x0202
+    0x0000, 0x8005, 0x800F, 0x000A, 0x801B, 0x001E, 0x0014, 0x8011,
+    0x8033, 0x0036, 0x003C, 0x8039, 0x0028, 0x802D, 0x8027, 0x0022,
+    0x8063, 0x0066, 0x006C, 0x8069, 0x0078, 0x807D, 0x8077, 0x0072,
+    0x0050, 0x8055, 0x805F, 0x005A, 0x804B, 0x004E, 0x0044, 0x8041,
+    0x80C3, 0x00C6, 0x00CC, 0x80C9, 0x00D8, 0x80DD, 0x80D7, 0x00D2,
+    0x00F0, 0x80F5, 0x80FF, 0x00FA, 0x80EB, 0x00EE, 0x00E4, 0x80E1,
+    0x00A0, 0x80A5, 0x80AF, 0x00AA, 0x80BB, 0x00BE, 0x00B4, 0x80B1,
+    0x8093, 0x0096, 0x009C, 0x8099, 0x0088, 0x808D, 0x8087, 0x0082,
+    0x8183, 0x0186, 0x018C, 0x8189, 0x0198, 0x819D, 0x8197, 0x0192,
+    0x01B0, 0x81B5, 0x81BF, 0x01BA, 0x81AB, 0x01AE, 0x01A4, 0x81A1,
+    0x01E0, 0x81E5, 0x81EF, 0x01EA, 0x81FB, 0x01FE, 0x01F4, 0x81F1,
+    0x81D3, 0x01D6, 0x01DC, 0x81D9, 0x01C8, 0x81CD, 0x81C7, 0x01C2,
+    0x0140, 0x8145, 0x814F, 0x014A, 0x815B, 0x015E, 0x0154, 0x8151,
+    0x8173, 0x0176, 0x017C, 0x8179, 0x0168, 0x816D, 0x8167, 0x0162,
+    0x8123, 0x0126, 0x012C, 0x8129, 0x0138, 0x813D, 0x8137, 0x0132,
+    0x0110, 0x8115, 0x811F, 0x011A, 0x810B, 0x010E, 0x0104, 0x8101,
+    0x8303, 0x0306, 0x030C, 0x8309, 0x0318, 0x831D, 0x8317, 0x0312,
+    0x0330, 0x8335, 0x833F, 0x033A, 0x832B, 0x032E, 0x0324, 0x8321,
+    0x0360, 0x8365, 0x836F, 0x036A, 0x837B, 0x037E, 0x0374, 0x8371,
+    0x8353, 0x0356, 0x035C, 0x8359, 0x0348, 0x834D, 0x8347, 0x0342,
+    0x03C0, 0x83C5, 0x83CF, 0x03CA, 0x83DB, 0x03DE, 0x03D4, 0x83D1,
+    0x83F3, 0x03F6, 0x03FC, 0x83F9, 0x03E8, 0x83ED, 0x83E7, 0x03E2,
+    0x83A3, 0x03A6, 0x03AC, 0x83A9, 0x03B8, 0x83BD, 0x83B7, 0x03B2,
+    0x0390, 0x8395, 0x839F, 0x039A, 0x838B, 0x038E, 0x0384, 0x8381,
+    0x0280, 0x8285, 0x828F, 0x028A, 0x829B, 0x029E, 0x0294, 0x8291,
+    0x82B3, 0x02B6, 0x02BC, 0x82B9, 0x02A8, 0x82AD, 0x82A7, 0x02A2,
+    0x82E3, 0x02E6, 0x02EC, 0x82E9, 0x02F8, 0x82FD, 0x82F7, 0x02F2,
+    0x02D0, 0x82D5, 0x82DF, 0x02DA, 0x82CB, 0x02CE, 0x02C4, 0x82C1,
+    0x8243, 0x0246, 0x024C, 0x8249, 0x0258, 0x825D, 0x8257, 0x0252,
+    0x0270, 0x8275, 0x827F, 0x027A, 0x826B, 0x026E, 0x0264, 0x8261,
+    0x0220, 0x8225, 0x822F, 0x022A, 0x823B, 0x023E, 0x0234, 0x8231,
+    0x8213, 0x0216, 0x021C, 0x8219, 0x0208, 0x820D, 0x8207, 0x0202
 ]  # fmt: skip
 
 # https://emanual.robotis.com/docs/en/dxl/protocol2/#instruction
@@ -191,6 +186,20 @@ class MockInstructionPacket(MockDynamixelPacketv2):
             0x00, 0x00               # placeholder for CRC
         ]  # fmt: skip
 
+    @classmethod
+    def ping(
+        cls,
+        dxl_id: int,
+    ) -> bytes:
+        """
+        Builds a "Ping" broadcast instruction.
+        (from https://emanual.robotis.com/docs/en/dxl/protocol2/#ping-0x01)
+
+        No parameters required.
+        """
+        params, length = [], 3
+        return cls.build(dxl_id=dxl_id, params=params, length=length, instruct_type="Ping")
+
     @classmethod
     def sync_read(
         cls,
@@ -252,12 +261,32 @@ class MockStatusPacket(MockDynamixelPacketv2):
             0x00, 0x00               # placeholder for CRC
         ]  # fmt: skip
 
+    @classmethod
+    def ping(cls, dxl_id: int, model_nb: int = 1190, firm_ver: int = 50) -> bytes:
+        """Builds a 'Ping' status packet.
+
+        https://emanual.robotis.com/docs/en/dxl/protocol2/#ping-0x01
+
+        Args:
+            dxl_id (int): ID of the servo responding.
+            model_nb (int, optional): Desired 'model number' to be returned in the packet. Defaults to 1190
+                which corresponds to a XL330-M077-T.
+            firm_ver (int, optional): Desired 'firmware version' to be returned in the packet.
+                Defaults to 50.
+
+        Returns:
+            bytes: The raw 'Ping' status packet ready to be sent through serial.
+        """
+        params = [dxl.DXL_LOBYTE(model_nb), dxl.DXL_HIBYTE(model_nb), firm_ver]
+        length = 7
+        return cls.build(dxl_id, params=params, length=length)
+
     @classmethod
     def present_position(cls, dxl_id: int, pos: int | None = None, min_max_range: tuple = (0, 4095)) -> bytes:
         """Builds a 'Present_Position' status packet.
 
         Args:
-            dxl_id (int): List of the servos ids
+            dxl_id (int): Servo id
             pos (int | None, optional): Desired 'Present_Position' to be returned in the packet. If None, it
                 will use a random value in the min_max_range. Defaults to None.
             min_max_range (tuple, optional): Min/max range to generate the position values used for when 'pos'
@@ -308,62 +337,69 @@ class MockMotors(MockSerial):
 
     ctrl_table = X_SERIES_CONTROL_TABLE
 
-    def __init__(self, dlx_ids: list[int]):
+    def __init__(self):
         super().__init__()
-        self._ids = dlx_ids
         self.open()
 
-    def build_single_motor_stubs(
-        self, data_name: str, return_value: int | None = None, num_invalid_try: int | None = None
-    ) -> None:
-        address, length = self.ctrl_table[data_name]
-        for idx in self._ids:
-            if data_name == "Present_Position":
-                sync_read_request_single = MockInstructionPacket.sync_read([idx], address, length)
-                sync_read_response_single = self._build_present_pos_send_fn(
-                    [idx], [return_value], num_invalid_try
-                )
-            else:
-                raise NotImplementedError  # TODO(aliberts): add ping?
-
-            self.stub(
-                name=f"SyncRead_{data_name}_{idx}",
-                receive_bytes=sync_read_request_single,
-                send_fn=sync_read_response_single,
-            )
-
-    def build_all_motors_stub(
-        self, data_name: str, return_values: list[int] | None = None, num_invalid_try: int | None = None
-    ) -> None:
-        address, length = self.ctrl_table[data_name]
-        if data_name == "Present_Position":
-            sync_read_request_all = MockInstructionPacket.sync_read(self._ids, address, length)
-            sync_read_response_all = self._build_present_pos_send_fn(
-                self._ids, return_values, num_invalid_try
-            )
-        else:
-            raise NotImplementedError  # TODO(aliberts): add ping?
-
-        self.stub(
-            name=f"SyncRead_{data_name}_all",
-            receive_bytes=sync_read_request_all,
-            send_fn=sync_read_response_all,
+    def build_broadcast_ping_stub(
+        self, ids_models_firmwares: dict[int, list[int]] | None = None, num_invalid_try: int = 0
+    ) -> str:
+        ping_request = MockInstructionPacket.ping(dxl.BROADCAST_ID)
+        return_packets = b"".join(
+            MockStatusPacket.ping(idx, model, firm_ver)
+            for idx, (model, firm_ver) in ids_models_firmwares.items()
         )
+        ping_response = self._build_send_fn(return_packets, num_invalid_try)
 
-    def _build_present_pos_send_fn(
-        self, dxl_ids: list[int], return_pos: list[int] | None = None, num_invalid_try: int | None = None
-    ) -> Callable[[int], bytes]:
-        return_pos = [None for _ in dxl_ids] if return_pos is None else return_pos
-        assert len(return_pos) == len(dxl_ids)
+        stub_name = "Ping_" + "_".join([str(idx) for idx in ids_models_firmwares])
+        self.stub(
+            name=stub_name,
+            receive_bytes=ping_request,
+            send_fn=ping_response,
+        )
+        return stub_name
 
+    def build_ping_stub(
+        self, dxl_id: int, model_nb: int, firm_ver: int = 50, num_invalid_try: int = 0
+    ) -> str:
+        ping_request = MockInstructionPacket.ping(dxl_id)
+        return_packet = MockStatusPacket.ping(dxl_id, model_nb, firm_ver)
+        ping_response = self._build_send_fn(return_packet, num_invalid_try)
+
+        stub_name = f"Ping_{dxl_id}"
+        self.stub(
+            name=stub_name,
+            receive_bytes=ping_request,
+            send_fn=ping_response,
+        )
+        return stub_name
+
+    def build_sync_read_stub(
+        self, data_name: str, ids_values: dict[int, int] | None = None, num_invalid_try: int = 0
+    ) -> str:
+        address, length = self.ctrl_table[data_name]
+        sync_read_request = MockInstructionPacket.sync_read(list(ids_values), address, length)
+        if data_name != "Present_Position":
+            raise NotImplementedError
+
+        return_packets = b"".join(
+            MockStatusPacket.present_position(idx, pos) for idx, pos in ids_values.items()
+        )
+        sync_read_response = self._build_send_fn(return_packets, num_invalid_try)
+
+        stub_name = f"Sync_Read_{data_name}_" + "_".join([str(idx) for idx in ids_values])
+        self.stub(
+            name=stub_name,
+            receive_bytes=sync_read_request,
+            send_fn=sync_read_response,
+        )
+        return stub_name
+
+    @staticmethod
+    def _build_send_fn(packet: bytes, num_invalid_try: int = 0) -> Callable[[int], bytes]:
         def send_fn(_call_count: int) -> bytes:
-            if num_invalid_try is not None and num_invalid_try >= _call_count:
+            if num_invalid_try >= _call_count:
                 return b""
-
-            packets = b"".join(
-                MockStatusPacket.present_position(idx, pos)
-                for idx, pos in zip(dxl_ids, return_pos, strict=True)
-            )
-            return packets
+            return packet
 
         return send_fn
diff --git a/tests/motors/test_dynamixel.py b/tests/motors/test_dynamixel.py
index ce50dd91..3bccba1f 100644
--- a/tests/motors/test_dynamixel.py
+++ b/tests/motors/test_dynamixel.py
@@ -81,6 +81,7 @@ def test_split_int_bytes_large_number():
 def test_abc_implementation(dummy_motors):
     """Instantiation should raise an error if the class doesn't implement abstract methods/properties."""
     DynamixelMotorsBus(port="/dev/dummy-port", motors=dummy_motors)
+
     DynamixelMotorsBus(port="/dev/dummy-port", motors={"dummy": (1, "xl330-m077")})
 
 
@@ -95,21 +96,24 @@ def test_abc_implementation(dummy_motors):
     ids=["None", "by ids", "by names", "mixed"],
 )
 def test_read_all_motors(motors, dummy_motors):
-    mock_motors = MockMotors([1, 2, 3])
-    positions = [1337, 42, 4016]
-    mock_motors.build_sync_read_all_motors_stub("Present_Position", return_values=positions)
+    mock_motors = MockMotors()
+    expected_positions = {
+        1: 1337,
+        2: 42,
+        3: 4016,
+    }
+    stub_name = mock_motors.build_sync_read_stub("Present_Position", expected_positions)
     motors_bus = DynamixelMotorsBus(
         port=mock_motors.port,
         motors=dummy_motors,
     )
     motors_bus.connect()
 
-    pos_dict = motors_bus.read("Present_Position", motors=motors)
+    positions_read = motors_bus.read("Present_Position", motors=motors)
 
-    assert mock_motors.stubs["SyncRead_Present_Position_all"].called
-    assert all(returned_pos == pos for returned_pos, pos in zip(pos_dict.values(), positions, strict=True))
-    assert set(pos_dict) == {"dummy_1", "dummy_2", "dummy_3"}
-    assert all(pos >= 0 and pos <= 4095 for pos in pos_dict.values())
+    motors = ["dummy_1", "dummy_2", "dummy_3"] if motors is None else motors
+    assert mock_motors.stubs[stub_name].called
+    assert positions_read == dict(zip(motors, expected_positions.values(), strict=True))
 
 
 @pytest.mark.parametrize(
@@ -121,8 +125,9 @@ def test_read_all_motors(motors, dummy_motors):
     ],
 )
 def test_read_single_motor_by_name(idx, pos, dummy_motors):
-    mock_motors = MockMotors([1, 2, 3])
-    mock_motors.build_sync_read_single_motor_stubs("Present_Position", return_value=pos)
+    mock_motors = MockMotors()
+    expected_position = {idx: pos}
+    stub_name = mock_motors.build_sync_read_stub("Present_Position", expected_position)
     motors_bus = DynamixelMotorsBus(
         port=mock_motors.port,
         motors=dummy_motors,
@@ -131,9 +136,8 @@ def test_read_single_motor_by_name(idx, pos, dummy_motors):
 
     pos_dict = motors_bus.read("Present_Position", f"dummy_{idx}")
 
-    assert mock_motors.stubs[f"SyncRead_Present_Position_{idx}"].called
+    assert mock_motors.stubs[stub_name].called
     assert pos_dict == {f"dummy_{idx}": pos}
-    assert all(pos >= 0 and pos <= 4095 for pos in pos_dict.values())
 
 
 @pytest.mark.parametrize(
@@ -145,8 +149,9 @@ def test_read_single_motor_by_name(idx, pos, dummy_motors):
     ],
 )
 def test_read_single_motor_by_id(idx, pos, dummy_motors):
-    mock_motors = MockMotors([1, 2, 3])
-    mock_motors.build_sync_read_single_motor_stubs("Present_Position", return_value=pos)
+    mock_motors = MockMotors()
+    expected_position = {idx: pos}
+    stub_name = mock_motors.build_sync_read_stub("Present_Position", expected_position)
     motors_bus = DynamixelMotorsBus(
         port=mock_motors.port,
         motors=dummy_motors,
@@ -155,24 +160,24 @@ def test_read_single_motor_by_id(idx, pos, dummy_motors):
 
     pos_dict = motors_bus.read("Present_Position", idx)
 
-    assert mock_motors.stubs[f"SyncRead_Present_Position_{idx}"].called
-    assert pos_dict == {f"dummy_{idx}": pos}
-    assert all(pos >= 0 and pos <= 4095 for pos in pos_dict.values())
+    assert mock_motors.stubs[stub_name].called
+    assert pos_dict == {idx: pos}
 
 
 @pytest.mark.parametrize(
     "num_retry, num_invalid_try, pos",
     [
-        [1, 2, 1337],
+        [0, 2, 1337],
         [2, 3, 42],
         [3, 2, 4016],
         [2, 1, 999],
     ],
 )
 def test_read_num_retry(num_retry, num_invalid_try, pos, dummy_motors):
-    mock_motors = MockMotors([1, 2, 3])
-    mock_motors.build_sync_read_single_motor_stubs(
-        "Present_Position", return_value=pos, num_invalid_try=num_invalid_try
+    mock_motors = MockMotors()
+    expected_position = {1: pos}
+    stub_name = mock_motors.build_sync_read_stub(
+        "Present_Position", expected_position, num_invalid_try=num_invalid_try
     )
     motors_bus = DynamixelMotorsBus(
         port=mock_motors.port,
@@ -182,10 +187,10 @@ def test_read_num_retry(num_retry, num_invalid_try, pos, dummy_motors):
 
     if num_retry >= num_invalid_try:
         pos_dict = motors_bus.read("Present_Position", 1, num_retry=num_retry)
-        assert pos_dict == {"dummy_1": pos}
-        assert all(pos >= 0 and pos <= 4095 for pos in pos_dict.values())
+        assert pos_dict == {1: pos}
     else:
         with pytest.raises(ConnectionError):
             _ = motors_bus.read("Present_Position", 1, num_retry=num_retry)
 
-    assert mock_motors.stubs["SyncRead_Present_Position_1"].calls == num_retry
+    expected_calls = min(1 + num_retry, 1 + num_invalid_try)
+    assert mock_motors.stubs[stub_name].calls == expected_calls

From 4fe18808874f462aa889be85e3019fc5146a2cb1 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sat, 22 Mar 2025 00:40:22 +0100
Subject: [PATCH 081/171] Add ping testing

---
 lerobot/common/motors/dynamixel/dynamixel.py | 14 +++++--
 tests/motors/test_dynamixel.py               | 41 +++++++++++++++++++-
 2 files changed, 50 insertions(+), 5 deletions(-)

diff --git a/lerobot/common/motors/dynamixel/dynamixel.py b/lerobot/common/motors/dynamixel/dynamixel.py
index 072e995c..8c5290b4 100644
--- a/lerobot/common/motors/dynamixel/dynamixel.py
+++ b/lerobot/common/motors/dynamixel/dynamixel.py
@@ -58,10 +58,16 @@ class DynamixelMotorsBus(MotorsBus):
         self.reader = dxl.GroupSyncRead(self.port_handler, self.packet_handler, 0, 0)
         self.writer = dxl.GroupSyncWrite(self.port_handler, self.packet_handler, 0, 0)
 
-    def broadcast_ping(self) -> tuple[list, int]:
-        data_list, comm = self.packet_handler.broadcastPing(self.port_handler)
-        # TODO(aliberts): translate data_list into {id: model}
-        return data_list, comm
+    def broadcast_ping(
+        self, num_retry: int = 0, raise_on_error: bool = False
+    ) -> dict[int, list[int, int]] | None:
+        for _ in range(1 + num_retry):
+            data_list, comm = self.packet_handler.broadcastPing(self.port_handler)
+            if self._is_comm_success(comm):
+                return data_list
+
+        if raise_on_error:
+            raise ConnectionError(f"Broadcast ping returned a {comm} comm error.")
 
     def calibrate_values(self, ids_values: dict[int, int]) -> dict[int, float]:
         # TODO
diff --git a/tests/motors/test_dynamixel.py b/tests/motors/test_dynamixel.py
index 3bccba1f..412a4a36 100644
--- a/tests/motors/test_dynamixel.py
+++ b/tests/motors/test_dynamixel.py
@@ -82,7 +82,46 @@ def test_abc_implementation(dummy_motors):
     """Instantiation should raise an error if the class doesn't implement abstract methods/properties."""
     DynamixelMotorsBus(port="/dev/dummy-port", motors=dummy_motors)
 
-    DynamixelMotorsBus(port="/dev/dummy-port", motors={"dummy": (1, "xl330-m077")})
+
+@pytest.mark.parametrize(
+    "idx, model_nb",
+    [
+        [1, 1190],
+        [2, 1200],
+        [3, 1120],
+    ],
+)
+def test_ping(idx, model_nb, dummy_motors):
+    mock_motors = MockMotors()
+    mock_motors.build_ping_stub(idx, model_nb)
+    motors_bus = DynamixelMotorsBus(
+        port=mock_motors.port,
+        motors=dummy_motors,
+    )
+    motors_bus.connect()
+
+    ping_model_nb = motors_bus.ping(idx)
+
+    assert ping_model_nb == model_nb
+
+
+def test_broadcast_ping(dummy_motors):
+    expected_pings = {
+        1: [1060, 50],
+        2: [1120, 30],
+        3: [1190, 10],
+    }
+    mock_motors = MockMotors()
+    mock_motors.build_broadcast_ping_stub(expected_pings)
+    motors_bus = DynamixelMotorsBus(
+        port=mock_motors.port,
+        motors=dummy_motors,
+    )
+    motors_bus.connect()
+
+    ping_list = motors_bus.broadcast_ping()
+
+    assert ping_list == expected_pings
 
 
 @pytest.mark.parametrize(

From fc4a95f18776821b833257df7e0fd7f9ce609cca Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sat, 22 Mar 2025 00:50:01 +0100
Subject: [PATCH 082/171] Add CRC docstring

---
 tests/mocks/mock_dynamixel.py | 11 +++++++++++
 1 file changed, 11 insertions(+)

diff --git a/tests/mocks/mock_dynamixel.py b/tests/mocks/mock_dynamixel.py
index 4ea47aea..10f9b56f 100644
--- a/tests/mocks/mock_dynamixel.py
+++ b/tests/mocks/mock_dynamixel.py
@@ -149,6 +149,17 @@ class MockDynamixelPacketv2(abc.ABC):
 
     @staticmethod
     def _add_crc(packet: list[int]) -> list[int]:
+        """Computes and add CRC to the packet.
+
+        https://emanual.robotis.com/docs/en/dxl/crc/
+        https://en.wikipedia.org/wiki/Cyclic_redundancy_check
+
+        Args:
+            packet (list[int]): The raw packet without CRC (but with placeholders for it).
+
+        Returns:
+            list[int]: The raw packet with a valid CRC.
+        """
         crc = 0
         for j in range(len(packet) - 2):
             i = ((crc >> 8) ^ packet[j]) & 0xFF

From 857f335be936a092c8262f8a4f4066182cef7420 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sat, 22 Mar 2025 01:19:51 +0100
Subject: [PATCH 083/171] Improve feetech mocking

---
 tests/mocks/mock_feetech.py  | 137 ++++++++++++++++++++++------------
 tests/motors/test_feetech.py | 141 ++++++++++++++++++++++-------------
 2 files changed, 179 insertions(+), 99 deletions(-)

diff --git a/tests/mocks/mock_feetech.py b/tests/mocks/mock_feetech.py
index 431707c5..e0a38042 100644
--- a/tests/mocks/mock_feetech.py
+++ b/tests/mocks/mock_feetech.py
@@ -77,6 +77,19 @@ class MockInstructionPacket(MockFeetechPacket):
             0x00,            # placeholder for checksum
         ]  # fmt: skip
 
+    @classmethod
+    def ping(
+        cls,
+        scs_id: int,
+    ) -> bytes:
+        """
+        Builds a "Ping" broadcast instruction.
+
+        No parameters required.
+        """
+        params, length = [], 2
+        return cls.build(scs_id=scs_id, params=params, length=length, instruct_type="Ping")
+
     @classmethod
     def sync_read(
         cls,
@@ -128,6 +141,25 @@ class MockStatusPacket(MockFeetechPacket):
             0x00,        # placeholder for checksum
         ]  # fmt: skip
 
+    @classmethod
+    def ping(cls, scs_id: int, model_nb: int = 1190, firm_ver: int = 50) -> bytes:
+        """Builds a 'Ping' status packet.
+
+        Args:
+            scs_id (int): ID of the servo responding.
+            model_nb (int, optional): Desired 'model number' to be returned in the packet. Defaults to 1190
+                which corresponds to a XL330-M077-T.
+            firm_ver (int, optional): Desired 'firmware version' to be returned in the packet.
+                Defaults to 50.
+
+        Returns:
+            bytes: The raw 'Ping' status packet ready to be sent through serial.
+        """
+        # raise NotImplementedError
+        params = [scs.SCS_LOBYTE(model_nb), scs.SCS_HIBYTE(model_nb), firm_ver]
+        length = 2
+        return cls.build(scs_id, params=params, length=length)
+
     @classmethod
     def present_position(cls, scs_id: int, pos: int | None = None, min_max_range: tuple = (0, 4095)) -> bytes:
         """Builds a 'Present_Position' status packet.
@@ -184,62 +216,69 @@ class MockMotors(MockSerial):
 
     ctrl_table = SCS_SERIES_CONTROL_TABLE
 
-    def __init__(self, scs_ids: list[int]):
+    def __init__(self):
         super().__init__()
-        self._ids = scs_ids
         self.open()
 
-    def build_single_motor_stubs(
-        self, data_name: str, return_value: int | None = None, num_invalid_try: int | None = None
-    ) -> None:
-        address, length = self.ctrl_table[data_name]
-        for idx in self._ids:
-            if data_name == "Present_Position":
-                sync_read_request_single = MockInstructionPacket.sync_read([idx], address, length)
-                sync_read_response_single = self._build_present_pos_send_fn(
-                    [idx], [return_value], num_invalid_try
-                )
-            else:
-                raise NotImplementedError  # TODO(aliberts): add ping?
-
-            self.stub(
-                name=f"SyncRead_{data_name}_{idx}",
-                receive_bytes=sync_read_request_single,
-                send_fn=sync_read_response_single,
-            )
-
-    def build_all_motors_stub(
-        self, data_name: str, return_values: list[int] | None = None, num_invalid_try: int | None = None
-    ) -> None:
-        address, length = self.ctrl_table[data_name]
-        if data_name == "Present_Position":
-            sync_read_request_all = MockInstructionPacket.sync_read(self._ids, address, length)
-            sync_read_response_all = self._build_present_pos_send_fn(
-                self._ids, return_values, num_invalid_try
-            )
-        else:
-            raise NotImplementedError  # TODO(aliberts): add ping?
-
-        self.stub(
-            name=f"SyncRead_{data_name}_all",
-            receive_bytes=sync_read_request_all,
-            send_fn=sync_read_response_all,
+    def build_broadcast_ping_stub(
+        self, ids_models_firmwares: dict[int, list[int]] | None = None, num_invalid_try: int = 0
+    ) -> str:
+        ping_request = MockInstructionPacket.ping(scs.BROADCAST_ID)
+        return_packets = b"".join(
+            MockStatusPacket.ping(idx, model, firm_ver)
+            for idx, (model, firm_ver) in ids_models_firmwares.items()
         )
+        ping_response = self._build_send_fn(return_packets, num_invalid_try)
 
-    def _build_present_pos_send_fn(
-        self, scs_ids: list[int], return_pos: list[int] | None = None, num_invalid_try: int | None = None
-    ) -> Callable[[int], bytes]:
-        return_pos = [None for _ in scs_ids] if return_pos is None else return_pos
-        assert len(return_pos) == len(scs_ids)
+        stub_name = "Ping_" + "_".join([str(idx) for idx in ids_models_firmwares])
+        self.stub(
+            name=stub_name,
+            receive_bytes=ping_request,
+            send_fn=ping_response,
+        )
+        return stub_name
 
+    def build_ping_stub(
+        self, scs_id: int, model_nb: int, firm_ver: int = 50, num_invalid_try: int = 0
+    ) -> str:
+        ping_request = MockInstructionPacket.ping(scs_id)
+        return_packet = MockStatusPacket.ping(scs_id, model_nb, firm_ver)
+        ping_response = self._build_send_fn(return_packet, num_invalid_try)
+
+        stub_name = f"Ping_{scs_id}"
+        self.stub(
+            name=stub_name,
+            receive_bytes=ping_request,
+            send_fn=ping_response,
+        )
+        return stub_name
+
+    def build_sync_read_stub(
+        self, data_name: str, ids_values: dict[int, int] | None = None, num_invalid_try: int = 0
+    ) -> str:
+        address, length = self.ctrl_table[data_name]
+        sync_read_request = MockInstructionPacket.sync_read(list(ids_values), address, length)
+        if data_name != "Present_Position":
+            raise NotImplementedError
+
+        return_packets = b"".join(
+            MockStatusPacket.present_position(idx, pos) for idx, pos in ids_values.items()
+        )
+        sync_read_response = self._build_send_fn(return_packets, num_invalid_try)
+
+        stub_name = f"Sync_Read_{data_name}_" + "_".join([str(idx) for idx in ids_values])
+        self.stub(
+            name=stub_name,
+            receive_bytes=sync_read_request,
+            send_fn=sync_read_response,
+        )
+        return stub_name
+
+    @staticmethod
+    def _build_send_fn(packet: bytes, num_invalid_try: int = 0) -> Callable[[int], bytes]:
         def send_fn(_call_count: int) -> bytes:
-            if num_invalid_try is not None and num_invalid_try >= _call_count:
+            if num_invalid_try >= _call_count:
                 return b""
-
-            packets = b"".join(
-                MockStatusPacket.present_position(idx, pos)
-                for idx, pos in zip(scs_ids, return_pos, strict=True)
-            )
-            return packets
+            return packet
 
         return send_fn
diff --git a/tests/motors/test_feetech.py b/tests/motors/test_feetech.py
index 42292fb0..d4a4397d 100644
--- a/tests/motors/test_feetech.py
+++ b/tests/motors/test_feetech.py
@@ -4,6 +4,7 @@ from unittest.mock import patch
 import pytest
 import scservo_sdk as scs
 
+from lerobot.common.motors import Motor
 from lerobot.common.motors.feetech import FeetechMotorsBus
 from tests.mocks.mock_feetech import MockMotors, MockPortHandler
 
@@ -17,6 +18,15 @@ def patch_port_handler():
         yield
 
 
+@pytest.fixture
+def dummy_motors() -> dict[str, Motor]:
+    return {
+        "dummy_1": Motor(id=1, model="sts3215"),
+        "dummy_2": Motor(id=2, model="sts3215"),
+        "dummy_3": Motor(id=3, model="sts3215"),
+    }
+
+
 @pytest.mark.skipif(sys.platform != "darwin", reason=f"No patching needed on {sys.platform=}")
 def test_autouse_patch():
     """Ensures that the autouse fixture correctly patches scs.PortHandler with MockPortHandler."""
@@ -68,9 +78,52 @@ def test_split_int_bytes_large_number():
         FeetechMotorsBus.split_int_bytes(2**32, 4)  # 4-byte max is 0xFFFFFFFF
 
 
-def test_abc_implementation():
+def test_abc_implementation(dummy_motors):
     """Instantiation should raise an error if the class doesn't implement abstract methods/properties."""
-    FeetechMotorsBus(port="/dev/dummy-port", motors={"dummy": (1, "sts3215")})
+    FeetechMotorsBus(port="/dev/dummy-port", motors=dummy_motors)
+
+
+@pytest.mark.skip("TODO")
+@pytest.mark.parametrize(
+    "idx, model_nb",
+    [
+        [1, 1190],
+        [2, 1200],
+        [3, 1120],
+    ],
+)
+def test_ping(idx, model_nb, dummy_motors):
+    mock_motors = MockMotors()
+    mock_motors.build_ping_stub(idx, model_nb)
+    motors_bus = FeetechMotorsBus(
+        port=mock_motors.port,
+        motors=dummy_motors,
+    )
+    motors_bus.connect()
+
+    ping_model_nb = motors_bus.ping(idx)
+
+    assert ping_model_nb == model_nb
+
+
+@pytest.mark.skip("TODO")
+def test_broadcast_ping(dummy_motors):
+    expected_pings = {
+        1: [1060, 50],
+        2: [1120, 30],
+        3: [1190, 10],
+    }
+    mock_motors = MockMotors()
+    mock_motors.build_broadcast_ping_stub(expected_pings)
+    motors_bus = FeetechMotorsBus(
+        port=mock_motors.port,
+        motors=dummy_motors,
+    )
+    motors_bus.connect()
+
+    ping_list = motors_bus.broadcast_ping()
+
+    assert ping_list == expected_pings
 
 
 @pytest.mark.parametrize(
@@ -83,26 +136,25 @@ def test_abc_implementation():
     ],
     ids=["None", "by ids", "by names", "mixed"],
 )
-def test_read_all_motors(motors):
-    mock_motors = MockMotors([1, 2, 3])
-    positions = [1337, 42, 4016]
-    mock_motors.build_all_motors_stub("Present_Position", return_values=positions)
+def test_read_all_motors(motors, dummy_motors):
+    mock_motors = MockMotors()
+    expected_positions = {
+        1: 1337,
+        2: 42,
+        3: 4016,
+    }
+    stub_name = mock_motors.build_sync_read_stub("Present_Position", expected_positions)
     motors_bus = FeetechMotorsBus(
         port=mock_motors.port,
-        motors={
-            "dummy_1": (1, "sts3215"),
-            "dummy_2": (2, "sts3215"),
-            "dummy_3": (3, "sts3215"),
-        },
+        motors=dummy_motors,
     )
     motors_bus.connect()
 
-    pos_dict = motors_bus.read("Present_Position", motors=motors)
+    positions_read = motors_bus.read("Present_Position", motors=motors)
 
-    assert mock_motors.stubs["SyncRead_Present_Position_all"].called
-    assert all(returned_pos == pos for returned_pos, pos in zip(pos_dict.values(), positions, strict=True))
-    assert set(pos_dict) == {"dummy_1", "dummy_2", "dummy_3"}
-    assert all(pos >= 0 and pos <= 4095 for pos in pos_dict.values())
+    motors = ["dummy_1", "dummy_2", "dummy_3"] if motors is None else motors
+    assert mock_motors.stubs[stub_name].called
+    assert positions_read == dict(zip(motors, expected_positions.values(), strict=True))
 
 
 @pytest.mark.parametrize(
@@ -113,24 +165,20 @@ def test_read_all_motors(motors):
         [3, 4016],
     ],
 )
-def test_read_single_motor_by_name(idx, pos):
-    mock_motors = MockMotors([1, 2, 3])
-    mock_motors.build_single_motor_stubs("Present_Position", return_value=pos)
+def test_read_single_motor_by_name(idx, pos, dummy_motors):
+    mock_motors = MockMotors()
+    expected_position = {idx: pos}
+    stub_name = mock_motors.build_sync_read_stub("Present_Position", expected_position)
     motors_bus = FeetechMotorsBus(
         port=mock_motors.port,
-        motors={
-            "dummy_1": (1, "sts3215"),
-            "dummy_2": (2, "sts3215"),
-            "dummy_3": (3, "sts3215"),
-        },
+        motors=dummy_motors,
     )
     motors_bus.connect()
 
     pos_dict = motors_bus.read("Present_Position", f"dummy_{idx}")
 
-    assert mock_motors.stubs[f"SyncRead_Present_Position_{idx}"].called
+    assert mock_motors.stubs[stub_name].called
     assert pos_dict == {f"dummy_{idx}": pos}
-    assert all(pos >= 0 and pos <= 4095 for pos in pos_dict.values())
 
 
 @pytest.mark.parametrize(
@@ -141,56 +189,49 @@ def test_read_single_motor_by_name(idx, pos):
         [3, 4016],
     ],
 )
-def test_read_single_motor_by_id(idx, pos):
-    mock_motors = MockMotors([1, 2, 3])
-    mock_motors.build_single_motor_stubs("Present_Position", return_value=pos)
+def test_read_single_motor_by_id(idx, pos, dummy_motors):
+    mock_motors = MockMotors()
+    expected_position = {idx: pos}
+    stub_name = mock_motors.build_sync_read_stub("Present_Position", expected_position)
     motors_bus = FeetechMotorsBus(
         port=mock_motors.port,
-        motors={
-            "dummy_1": (1, "sts3215"),
-            "dummy_2": (2, "sts3215"),
-            "dummy_3": (3, "sts3215"),
-        },
+        motors=dummy_motors,
     )
     motors_bus.connect()
 
     pos_dict = motors_bus.read("Present_Position", idx)
 
-    assert mock_motors.stubs[f"SyncRead_Present_Position_{idx}"].called
-    assert pos_dict == {f"dummy_{idx}": pos}
-    assert all(pos >= 0 and pos <= 4095 for pos in pos_dict.values())
+    assert mock_motors.stubs[stub_name].called
+    assert pos_dict == {idx: pos}
 
 
 @pytest.mark.parametrize(
     "num_retry, num_invalid_try, pos",
     [
-        [1, 2, 1337],
+        [0, 2, 1337],
         [2, 3, 42],
         [3, 2, 4016],
         [2, 1, 999],
     ],
 )
-def test_read_num_retry(num_retry, num_invalid_try, pos):
-    mock_motors = MockMotors([1, 2, 3])
-    mock_motors.build_single_motor_stubs(
-        "Present_Position", return_value=pos, num_invalid_try=num_invalid_try
+def test_read_num_retry(num_retry, num_invalid_try, pos, dummy_motors):
+    mock_motors = MockMotors()
+    expected_position = {1: pos}
+    stub_name = mock_motors.build_sync_read_stub(
+        "Present_Position", expected_position, num_invalid_try=num_invalid_try
     )
     motors_bus = FeetechMotorsBus(
         port=mock_motors.port,
-        motors={
-            "dummy_1": (1, "sts3215"),
-            "dummy_2": (2, "sts3215"),
-            "dummy_3": (3, "sts3215"),
-        },
+        motors=dummy_motors,
     )
     motors_bus.connect()
 
     if num_retry >= num_invalid_try:
         pos_dict = motors_bus.read("Present_Position", 1, num_retry=num_retry)
-        assert pos_dict == {"dummy_1": pos}
-        assert all(pos >= 0 and pos <= 4095 for pos in pos_dict.values())
+        assert pos_dict == {1: pos}
     else:
         with pytest.raises(ConnectionError):
             _ = motors_bus.read("Present_Position", 1, num_retry=num_retry)
 
-    assert mock_motors.stubs["SyncRead_Present_Position_1"].calls == num_retry
+    expected_calls = min(1 + num_retry, 1 + num_invalid_try)
+    assert mock_motors.stubs[stub_name].calls == expected_calls

From 9e34c1d731edd689a3df4e405dc6b454ffafb9ca Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sat, 22 Mar 2025 01:24:48 +0100
Subject: [PATCH 084/171] Move feetech table & cleanup

---
 lerobot/common/motors/feetech/__init__.py |   7 +-
 lerobot/common/motors/feetech/feetech.py  | 100 ++--------------------
 lerobot/common/motors/feetech/tables.py   |  80 +++++++++++++++++
 tests/mocks/mock_feetech.py               |   2 +-
 4 files changed, 88 insertions(+), 101 deletions(-)
 create mode 100644 lerobot/common/motors/feetech/tables.py

diff --git a/lerobot/common/motors/feetech/__init__.py b/lerobot/common/motors/feetech/__init__.py
index 0134b92d..ae61d23b 100644
--- a/lerobot/common/motors/feetech/__init__.py
+++ b/lerobot/common/motors/feetech/__init__.py
@@ -1,8 +1,3 @@
 from .feetech import FeetechMotorsBus
 from .feetech_calibration import apply_feetech_offsets_from_calibration, run_full_arm_calibration
-
-__all__ = [
-    "FeetechMotorsBus",
-    "apply_feetech_offsets_from_calibration",
-    "run_full_arm_calibration",
-]
+from .tables import *
diff --git a/lerobot/common/motors/feetech/feetech.py b/lerobot/common/motors/feetech/feetech.py
index 5a315bf9..78fae13a 100644
--- a/lerobot/common/motors/feetech/feetech.py
+++ b/lerobot/common/motors/feetech/feetech.py
@@ -15,6 +15,12 @@
 from copy import deepcopy
 
 from ..motors_bus import MotorsBus
+from .tables import (
+    CALIBRATION_REQUIRED,
+    MODEL_BAUDRATE_TABLE,
+    MODEL_CONTROL_TABLE,
+    MODEL_RESOLUTION,
+)
 
 PROTOCOL_VERSION = 0
 BAUDRATE = 1_000_000
@@ -22,100 +28,6 @@ DEFAULT_TIMEOUT_MS = 1000
 
 MAX_ID_RANGE = 252
 
-# For joints in percentage (i.e. joints that move linearly like the prismatic joint of a gripper),
-# their nominal range is [0, 100] %. For instance, for Aloha gripper, 0% is fully
-# closed, and 100% is fully open. To account for slight calibration issue, we allow up to
-# [-10, 110] until an error is raised.
-LOWER_BOUND_LINEAR = -10
-UPPER_BOUND_LINEAR = 110
-
-HALF_TURN_DEGREE = 180
-
-# See this link for STS3215 Memory Table:
-# https://docs.google.com/spreadsheets/d/1GVs7W1VS1PqdhA1nW-abeyAHhTUxKUdR/edit?usp=sharing&ouid=116566590112741600240&rtpof=true&sd=true
-# data_name: (address, size_byte)
-SCS_SERIES_CONTROL_TABLE = {
-    "Model": (3, 2),
-    "ID": (5, 1),
-    "Baud_Rate": (6, 1),
-    "Return_Delay": (7, 1),
-    "Response_Status_Level": (8, 1),
-    "Min_Angle_Limit": (9, 2),
-    "Max_Angle_Limit": (11, 2),
-    "Max_Temperature_Limit": (13, 1),
-    "Max_Voltage_Limit": (14, 1),
-    "Min_Voltage_Limit": (15, 1),
-    "Max_Torque_Limit": (16, 2),
-    "Phase": (18, 1),
-    "Unloading_Condition": (19, 1),
-    "LED_Alarm_Condition": (20, 1),
-    "P_Coefficient": (21, 1),
-    "D_Coefficient": (22, 1),
-    "I_Coefficient": (23, 1),
-    "Minimum_Startup_Force": (24, 2),
-    "CW_Dead_Zone": (26, 1),
-    "CCW_Dead_Zone": (27, 1),
-    "Protection_Current": (28, 2),
-    "Angular_Resolution": (30, 1),
-    "Offset": (31, 2),
-    "Mode": (33, 1),
-    "Protective_Torque": (34, 1),
-    "Protection_Time": (35, 1),
-    "Overload_Torque": (36, 1),
-    "Speed_closed_loop_P_proportional_coefficient": (37, 1),
-    "Over_Current_Protection_Time": (38, 1),
-    "Velocity_closed_loop_I_integral_coefficient": (39, 1),
-    "Torque_Enable": (40, 1),
-    "Acceleration": (41, 1),
-    "Goal_Position": (42, 2),
-    "Goal_Time": (44, 2),
-    "Goal_Speed": (46, 2),
-    "Torque_Limit": (48, 2),
-    "Lock": (55, 1),
-    "Present_Position": (56, 2),
-    "Present_Speed": (58, 2),
-    "Present_Load": (60, 2),
-    "Present_Voltage": (62, 1),
-    "Present_Temperature": (63, 1),
-    "Status": (65, 1),
-    "Moving": (66, 1),
-    "Present_Current": (69, 2),
-    # Not in the Memory Table
-    "Maximum_Acceleration": (85, 2),
-}
-
-SCS_SERIES_BAUDRATE_TABLE = {
-    0: 1_000_000,
-    1: 500_000,
-    2: 250_000,
-    3: 128_000,
-    4: 115_200,
-    5: 57_600,
-    6: 38_400,
-    7: 19_200,
-}
-
-CALIBRATION_REQUIRED = ["Goal_Position", "Present_Position"]
-
-MODEL_CONTROL_TABLE = {
-    "scs_series": SCS_SERIES_CONTROL_TABLE,
-    "sts3215": SCS_SERIES_CONTROL_TABLE,
-}
-
-MODEL_RESOLUTION = {
-    "scs_series": 4096,
-    "sts3215": 4096,
-}
-
-MODEL_BAUDRATE_TABLE = {
-    "scs_series": SCS_SERIES_BAUDRATE_TABLE,
-    "sts3215": SCS_SERIES_BAUDRATE_TABLE,
-}
-
-# High number of retries is needed for feetech compared to dynamixel motors.
-NUM_READ_RETRY = 20
-NUM_WRITE_RETRY = 20
-
 
 class FeetechMotorsBus(MotorsBus):
     """
diff --git a/lerobot/common/motors/feetech/tables.py b/lerobot/common/motors/feetech/tables.py
new file mode 100644
index 00000000..5de95b61
--- /dev/null
+++ b/lerobot/common/motors/feetech/tables.py
@@ -0,0 +1,80 @@
+# See this link for STS3215 Memory Table:
+# https://docs.google.com/spreadsheets/d/1GVs7W1VS1PqdhA1nW-abeyAHhTUxKUdR/edit?usp=sharing&ouid=116566590112741600240&rtpof=true&sd=true
+# data_name: (address, size_byte)
+SCS_SERIES_CONTROL_TABLE = {
+    "Model": (3, 2),
+    "ID": (5, 1),
+    "Baud_Rate": (6, 1),
+    "Return_Delay": (7, 1),
+    "Response_Status_Level": (8, 1),
+    "Min_Angle_Limit": (9, 2),
+    "Max_Angle_Limit": (11, 2),
+    "Max_Temperature_Limit": (13, 1),
+    "Max_Voltage_Limit": (14, 1),
+    "Min_Voltage_Limit": (15, 1),
+    "Max_Torque_Limit": (16, 2),
+    "Phase": (18, 1),
+    "Unloading_Condition": (19, 1),
+    "LED_Alarm_Condition": (20, 1),
+    "P_Coefficient": (21, 1),
+    "D_Coefficient": (22, 1),
+    "I_Coefficient": (23, 1),
+    "Minimum_Startup_Force": (24, 2),
+    "CW_Dead_Zone": (26, 1),
+    "CCW_Dead_Zone": (27, 1),
+    "Protection_Current": (28, 2),
+    "Angular_Resolution": (30, 1),
+    "Offset": (31, 2),
+    "Mode": (33, 1),
+    "Protective_Torque": (34, 1),
+    "Protection_Time": (35, 1),
+    "Overload_Torque": (36, 1),
+    "Speed_closed_loop_P_proportional_coefficient": (37, 1),
+    "Over_Current_Protection_Time": (38, 1),
+    "Velocity_closed_loop_I_integral_coefficient": (39, 1),
+    "Torque_Enable": (40, 1),
+    "Acceleration": (41, 1),
+    "Goal_Position": (42, 2),
+    "Goal_Time": (44, 2),
+    "Goal_Speed": (46, 2),
+    "Torque_Limit": (48, 2),
+    "Lock": (55, 1),
+    "Present_Position": (56, 2),
+    "Present_Speed": (58, 2),
+    "Present_Load": (60, 2),
+    "Present_Voltage": (62, 1),
+    "Present_Temperature": (63, 1),
+    "Status": (65, 1),
+    "Moving": (66, 1),
+    "Present_Current": (69, 2),
+    # Not in the Memory Table
+    "Maximum_Acceleration": (85, 2),
+}
+
+SCS_SERIES_BAUDRATE_TABLE = {
+    0: 1_000_000,
+    1: 500_000,
+    2: 250_000,
+    3: 128_000,
+    4: 115_200,
+    5: 57_600,
+    6: 38_400,
+    7: 19_200,
+}
+
+MODEL_CONTROL_TABLE = {
+    "scs_series": SCS_SERIES_CONTROL_TABLE,
+    "sts3215": SCS_SERIES_CONTROL_TABLE,
+}
+
+MODEL_RESOLUTION = {
+    "scs_series": 4096,
+    "sts3215": 4096,
+}
+
+MODEL_BAUDRATE_TABLE = {
+    "scs_series": SCS_SERIES_BAUDRATE_TABLE,
+    "sts3215": SCS_SERIES_BAUDRATE_TABLE,
+}
+
+CALIBRATION_REQUIRED = ["Goal_Position", "Present_Position"]
diff --git a/tests/mocks/mock_feetech.py b/tests/mocks/mock_feetech.py
index e0a38042..7ff994ee 100644
--- a/tests/mocks/mock_feetech.py
+++ b/tests/mocks/mock_feetech.py
@@ -6,7 +6,7 @@ import scservo_sdk as scs
 import serial
 from mock_serial import MockSerial
 
-from lerobot.common.motors.feetech.feetech import SCS_SERIES_CONTROL_TABLE
+from lerobot.common.motors.feetech.tables import SCS_SERIES_CONTROL_TABLE
 
 # https://files.waveshare.com/upload/2/27/Communication_Protocol_User_Manual-EN%28191218-0923%29.pdf
 INSTRUCTION_TYPES = {

From 40675ec76c97c4b5ce49936284959175976deb2c Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sat, 22 Mar 2025 10:33:42 +0100
Subject: [PATCH 085/171] Add logger, rm logs

---
 lerobot/common/motors/motors_bus.py | 48 ++++++-----------------------
 1 file changed, 9 insertions(+), 39 deletions(-)

diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py
index 8343d922..5d4e654f 100644
--- a/lerobot/common/motors/motors_bus.py
+++ b/lerobot/common/motors/motors_bus.py
@@ -21,7 +21,7 @@
 
 import abc
 import json
-import time
+import logging
 from dataclasses import dataclass
 from enum import Enum
 from functools import cached_property
@@ -33,23 +33,13 @@ import serial
 from deepdiff import DeepDiff
 
 from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError
-from lerobot.common.utils.utils import capture_timestamp_utc
 
 NameOrID: TypeAlias = str | int
 Value: TypeAlias = int | float
 
 MAX_ID_RANGE = 252
 
-
-def get_group_sync_key(data_name: str, motor_ids: list[int]) -> str:
-    group_key = f"{data_name}_" + "_".join([str(idx) for idx in motor_ids])
-    return group_key
-
-
-def get_log_name(var_name: str, fn_name: str, data_name: str, motor_names: list[str]) -> str:
-    group_key = get_group_sync_key(data_name, motor_names)
-    log_name = f"{var_name}_{fn_name}_{group_key}"
-    return log_name
+logger = logging.getLogger(__name__)
 
 
 def assert_same_address(model_ctrl_table: dict[str, dict], motor_models: list[str], data_name: str) -> None:
@@ -268,7 +258,6 @@ class MotorsBus(abc.ABC):
         self.reader: GroupSyncRead
         self.writer: GroupSyncWrite
 
-        self.logs = {}  # TODO(aliberts): use subclass logger
         self.calibration = None
 
         self._id_to_model = {m.id: m.model for m in self.motors.values()}
@@ -363,10 +352,11 @@ class MotorsBus(abc.ABC):
 
     def ping(self, motor: NameOrID, num_retry: int = 0, raise_on_error: bool = False) -> int | None:
         idx = self.get_motor_id(motor)
-        for _ in range(1 + num_retry):
+        for n_try in range(1 + num_retry):
             model_number, comm, error = self.packet_handler.ping(self.port_handler, idx)
             if self._is_comm_success(comm):
                 return model_number
+            logger.debug(f"ping failed for {idx=}: {n_try=} got {comm=} {error=}")
 
         if raise_on_error:
             raise ConnectionError(f"Ping motor {motor} returned a {error} error code.")
@@ -463,8 +453,6 @@ class MotorsBus(abc.ABC):
                 f"{self.__class__.__name__}('{self.port}') is not connected. You need to run `{self.__class__.__name__}.connect()`."
             )
 
-        start_time = time.perf_counter()
-
         id_key_map: dict[int, NameOrID] = {}
         if motors is None:
             id_key_map = {m.id: name for name, m in self.motors.items()}
@@ -493,17 +481,7 @@ class MotorsBus(abc.ABC):
         if data_name in self.calibration_required and self.calibration is not None:
             ids_values = self.calibrate_values(ids_values)
 
-        keys_values = {id_key_map[idx]: val for idx, val in ids_values.items()}
-
-        # 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_ids)
-        self.logs[delta_ts_name] = time.perf_counter() - start_time
-
-        # log the utc time at which the data was received
-        ts_utc_name = get_log_name("timestamp_utc", "read", data_name, motor_ids)
-        self.logs[ts_utc_name] = capture_timestamp_utc()
-
-        return keys_values
+        return {id_key_map[idx]: val for idx, val in ids_values.items()}
 
     def _read(
         self, motor_ids: list[str], address: int, n_bytes: int, num_retry: int = 0
@@ -520,10 +498,11 @@ class MotorsBus(abc.ABC):
         for idx in motor_ids:
             self.reader.addParam(idx)
 
-        for _ in range(1 + num_retry):
+        for n_try in range(1 + num_retry):
             comm = self.reader.txRxPacket()
             if self._is_comm_success(comm):
                 break
+            logger.debug(f"ids={list(motor_ids)} @{address} ({n_bytes} bytes) {n_try=} got {comm=}")
 
         values = {idx: self.reader.getData(idx, address, n_bytes) for idx in motor_ids}
         return comm, values
@@ -543,8 +522,6 @@ class MotorsBus(abc.ABC):
                 f"{self.__class__.__name__}('{self.port}') is not connected. You need to run `{self.__class__.__name__}.connect()`."
             )
 
-        start_time = time.perf_counter()
-
         if isinstance(values, int):
             ids_values = {id_: values for id_ in self.ids}
         elif isinstance(values, dict):
@@ -569,14 +546,6 @@ class MotorsBus(abc.ABC):
                 f"{self.packet_handler.getTxRxResult(comm)}"
             )
 
-        # log the number of seconds it took to write the data to the motors
-        delta_ts_name = get_log_name("delta_timestamp_s", "write", data_name, list(ids_values))
-        self.logs[delta_ts_name] = time.perf_counter() - start_time
-
-        # log the utc time when the write has been completed
-        ts_utc_name = get_log_name("timestamp_utc", "write", data_name, list(ids_values))
-        self.logs[ts_utc_name] = capture_timestamp_utc()
-
     def _write(self, ids_values: dict[int, int], address: int, n_bytes: int, num_retry: int = 0) -> int:
         self.writer.clearParam()
         self.writer.start_address = address
@@ -586,10 +555,11 @@ class MotorsBus(abc.ABC):
             data = self.split_int_bytes(value, n_bytes)
             self.writer.addParam(idx, data)
 
-        for _ in range(1 + num_retry):
+        for n_try in range(1 + num_retry):
             comm = self.writer.txPacket()
             if self._is_comm_success(comm):
                 break
+            logger.debug(f"ids={list(ids_values)} @{address} ({n_bytes} bytes) {n_try=} got {comm=}")
 
         return comm
 

From f2ed2bfb2fb8646c0d60cee8dd73dec7705e33f0 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sat, 22 Mar 2025 11:11:39 +0100
Subject: [PATCH 086/171] Improve logging & typing

---
 lerobot/common/motors/motors_bus.py | 24 +++++++++++++-----------
 1 file changed, 13 insertions(+), 11 deletions(-)

diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py
index 5d4e654f..2a64a887 100644
--- a/lerobot/common/motors/motors_bus.py
+++ b/lerobot/common/motors/motors_bus.py
@@ -14,10 +14,10 @@
 # See the License for the specific language governing permissions and
 # limitations under the License.
 
-# TODO(aliberts): This noqa is for the PortHandler / PacketHandler Protocols
-# Add block noqa when feature below is available
-# https://github.com/astral-sh/ruff/issues/3711
 # ruff: noqa: N802
+# This noqa is for the Protocols classes: PortHandler, PacketHandler GroupSyncRead/Write
+# TODO(aliberts): Add block noqa when feature below is available
+# https://github.com/astral-sh/ruff/issues/3711
 
 import abc
 import json
@@ -325,13 +325,14 @@ class MotorsBus(abc.ABC):
             if not self.port_handler.openPort():
                 raise OSError(f"Failed to open port '{self.port}'.")
         except (FileNotFoundError, OSError, serial.SerialException) as e:
-            print(
+            logger.error(
                 f"\nCould not connect on port '{self.port}'. Make sure you are using the correct port."
                 "\nTry running `python lerobot/scripts/find_motors_bus_port.py`\n"
             )
             raise e
 
         self.set_timeout()
+        logger.debug(f"{self.__class__.__name__} connected.")
 
     def set_timeout(self, timeout_ms: int | None = None):
         timeout_ms = timeout_ms if timeout_ms is not None else self.default_timeout
@@ -347,7 +348,7 @@ class MotorsBus(abc.ABC):
             # TODO(aliberts): use ping instead
             return (self.ids == self.read("ID")).all()
         except ConnectionError as e:
-            print(e)
+            logger.error(e)
             return False
 
     def ping(self, motor: NameOrID, num_retry: int = 0, raise_on_error: bool = False) -> int | None:
@@ -369,7 +370,7 @@ class MotorsBus(abc.ABC):
     def set_baudrate(self, baudrate) -> None:
         present_bus_baudrate = self.port_handler.getBaudRate()
         if present_bus_baudrate != baudrate:
-            print(f"Setting bus baud rate to {baudrate}. Previously {present_bus_baudrate}.")
+            logger.info(f"Setting bus baud rate to {baudrate}. Previously {present_bus_baudrate}.")
             self.port_handler.setBaudRate(baudrate)
 
             if self.port_handler.getBaudRate() != baudrate:
@@ -440,11 +441,11 @@ class MotorsBus(abc.ABC):
             raise TypeError(f"'{motor}' should be int, str.")
 
     @overload
-    def read(self, data_name: str, motors: None = ...) -> dict[str, Value]: ...
+    def read(self, data_name: str, motors: None = ..., num_retry: int = ...) -> dict[str, Value]: ...
     @overload
-    def read(self, data_name: str, motors: NameOrID) -> dict[NameOrID, Value]: ...
-    @overload
-    def read(self, data_name: str, motors: list[NameOrID]) -> dict[NameOrID, Value]: ...
+    def read(
+        self, data_name: str, motors: NameOrID | list[NameOrID], num_retry: int = ...
+    ) -> dict[NameOrID, Value]: ...
     def read(
         self, data_name: str, motors: NameOrID | list[NameOrID] | None = None, num_retry: int = 0
     ) -> dict[NameOrID, Value]:
@@ -516,7 +517,7 @@ class MotorsBus(abc.ABC):
     #     for idx in motor_ids:
     #         value = self.reader.getData(idx, address, n_bytes)
 
-    def write(self, data_name: str, values: int | dict[NameOrID, int], num_retry: int = 0) -> None:
+    def write(self, data_name: str, values: Value | dict[NameOrID, Value], num_retry: int = 0) -> None:
         if not self.is_connected:
             raise DeviceNotConnectedError(
                 f"{self.__class__.__name__}('{self.port}') is not connected. You need to run `{self.__class__.__name__}.connect()`."
@@ -570,6 +571,7 @@ class MotorsBus(abc.ABC):
             )
 
         self.port_handler.closePort()
+        logger.debug(f"{self.__class__.__name__} disconnected.")
 
     def __del__(self):
         if self.is_connected:

From 8ca03a72558621cb63bc0d2c91b24e14dadf64a6 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sat, 22 Mar 2025 14:50:05 +0100
Subject: [PATCH 087/171] Add dxl write tests

---
 tests/mocks/mock_dynamixel.py  | 113 +++++++++++++++++++++++++++++++--
 tests/motors/test_dynamixel.py |  51 +++++++++++++++
 2 files changed, 159 insertions(+), 5 deletions(-)

diff --git a/tests/mocks/mock_dynamixel.py b/tests/mocks/mock_dynamixel.py
index 10f9b56f..2a1cf2b1 100644
--- a/tests/mocks/mock_dynamixel.py
+++ b/tests/mocks/mock_dynamixel.py
@@ -1,12 +1,14 @@
 import abc
 import random
+import threading
+import time
 from typing import Callable
 
 import dynamixel_sdk as dxl
 import serial
-from mock_serial import MockSerial
+from mock_serial.mock_serial import MockSerial, Stub
 
-from lerobot.common.motors.dynamixel import X_SERIES_CONTROL_TABLE
+from lerobot.common.motors.dynamixel import X_SERIES_CONTROL_TABLE, DynamixelMotorsBus
 
 # https://emanual.robotis.com/docs/en/dxl/crc/
 DXL_CRC_TABLE = [
@@ -245,6 +247,53 @@ class MockInstructionPacket(MockDynamixelPacketv2):
         length = len(dxl_ids) + 7
         return cls.build(dxl_id=dxl.BROADCAST_ID, params=params, length=length, instruct_type="Sync_Read")
 
+    @classmethod
+    def sync_write(
+        cls,
+        ids_values: dict[int],
+        start_address: int,
+        data_length: int,
+    ) -> bytes:
+        """
+        Builds a "Sync_Write" broadcast instruction.
+        (from https://emanual.robotis.com/docs/en/dxl/protocol2/#sync-write-0x83)
+
+        The parameters for Sync_Write (Protocol 2.0) are:
+            param[0]   = start_address L
+            param[1]   = start_address H
+            param[2]   = data_length L
+            param[3]   = data_length H
+            param[5]   = [1st motor] ID
+            param[5+1] = [1st motor] 1st Byte
+            param[5+2] = [1st motor] 2nd Byte
+            ...
+            param[5+X] = [1st motor] X-th Byte
+            param[6]   = [2nd motor] ID
+            param[6+1] = [2nd motor] 1st Byte
+            param[6+2] = [2nd motor] 2nd Byte
+            ...
+            param[6+X] = [2nd motor] X-th Byte
+
+        And 'length' = ((number_of_params * 1 + data_length) + 7), where:
+            +1 is for instruction byte,
+            +2 is for the address bytes,
+            +2 is for the length bytes,
+            +2 is for the CRC at the end.
+        """
+        data = []
+        for idx, value in ids_values.items():
+            split_value = DynamixelMotorsBus.split_int_bytes(value, data_length)
+            data += [idx, *split_value]
+        params = [
+            dxl.DXL_LOBYTE(start_address),
+            dxl.DXL_HIBYTE(start_address),
+            dxl.DXL_LOBYTE(data_length),
+            dxl.DXL_HIBYTE(data_length),
+            *data,
+        ]
+        length = len(ids_values) * (1 + data_length) + 7
+        return cls.build(dxl_id=dxl.BROADCAST_ID, params=params, length=length, instruct_type="Sync_Write")
+
 
 class MockStatusPacket(MockDynamixelPacketv2):
     """
@@ -337,13 +386,38 @@ class MockPortHandler(dxl.PortHandler):
         return True
 
 
+class WaitableStub(Stub):
+    """
+    In some situations, a test might be checking if a stub has been called before `MockSerial` thread had time
+    to read, match, and call the stub. In these situations, the test can fail randomly.
+
+    Use `wait_called()` or `wait_calls()` to block until the stub is called, avoiding race conditions.
+    """
+
+    def __init__(self, **kwargs):
+        super().__init__(**kwargs)
+        self._event = threading.Event()
+
+    def call(self):
+        self._event.set()
+        return super().call()
+
+    def wait_called(self, timeout: float = 1.0):
+        return self._event.wait(timeout)
+
+    def wait_calls(self, min_calls: int = 1, timeout: float = 1.0):
+        start = time.perf_counter()
+        while time.perf_counter() - start < timeout:
+            if self.calls >= min_calls:
+                return self.calls
+            time.sleep(0.005)
+        raise TimeoutError(f"Stub not called {min_calls} times within {timeout} seconds.")
+
+
 class MockMotors(MockSerial):
     """
     This class will simulate physical motors by responding with valid status packets upon receiving some
     instruction packets. It is meant to test MotorsBus classes.
-
-    'data_name' supported:
-        - Present_Position
     """
 
     ctrl_table = X_SERIES_CONTROL_TABLE
@@ -352,6 +426,15 @@ class MockMotors(MockSerial):
         super().__init__()
         self.open()
 
+    @property
+    def stubs(self) -> dict[str, WaitableStub]:
+        return super().stubs
+
+    def stub(self, *, name=None, **kwargs):
+        new_stub = WaitableStub(**kwargs)
+        self._MockSerial__stubs[name or new_stub.receive_bytes] = new_stub
+        return new_stub
+
     def build_broadcast_ping_stub(
         self, ids_models_firmwares: dict[int, list[int]] | None = None, num_invalid_try: int = 0
     ) -> str:
@@ -388,6 +471,10 @@ class MockMotors(MockSerial):
     def build_sync_read_stub(
         self, data_name: str, ids_values: dict[int, int] | None = None, num_invalid_try: int = 0
     ) -> str:
+        """
+        'data_name' supported:
+            - Present_Position
+        """
         address, length = self.ctrl_table[data_name]
         sync_read_request = MockInstructionPacket.sync_read(list(ids_values), address, length)
         if data_name != "Present_Position":
@@ -406,6 +493,22 @@ class MockMotors(MockSerial):
         )
         return stub_name
 
+    def build_sync_write_stub(
+        self, data_name: str, ids_values: dict[int, int] | None = None, num_invalid_try: int = 0
+    ) -> str:
+        address, length = self.ctrl_table[data_name]
+        sync_read_request = MockInstructionPacket.sync_write(ids_values, address, length)
+        # if data_name != "Goal_Position":
+        #     raise NotImplementedError
+
+        stub_name = f"Sync_Write_{data_name}_" + "_".join([str(idx) for idx in ids_values])
+        self.stub(
+            name=stub_name,
+            receive_bytes=sync_read_request,
+            send_fn=self._build_send_fn(b"", num_invalid_try),
+        )
+        return stub_name
+
     @staticmethod
     def _build_send_fn(packet: bytes, num_invalid_try: int = 0) -> Callable[[int], bytes]:
         def send_fn(_call_count: int) -> bytes:
diff --git a/tests/motors/test_dynamixel.py b/tests/motors/test_dynamixel.py
index 412a4a36..6d08ba00 100644
--- a/tests/motors/test_dynamixel.py
+++ b/tests/motors/test_dynamixel.py
@@ -233,3 +233,54 @@ def test_read_num_retry(num_retry, num_invalid_try, pos, dummy_motors):
 
     expected_calls = min(1 + num_retry, 1 + num_invalid_try)
     assert mock_motors.stubs[stub_name].calls == expected_calls
+
+
+@pytest.mark.parametrize(
+    "motors",
+    [
+        [1, 2, 3],
+        ["dummy_1", "dummy_2", "dummy_3"],
+        [1, "dummy_2", 3],
+    ],
+    ids=["by ids", "by names", "mixed"],
+)
+def test_write_all_motors(motors, dummy_motors):
+    mock_motors = MockMotors()
+    goal_positions = {
+        1: 1337,
+        2: 42,
+        3: 4016,
+    }
+    stub_name = mock_motors.build_sync_write_stub("Goal_Position", goal_positions)
+    motors_bus = DynamixelMotorsBus(
+        port=mock_motors.port,
+        motors=dummy_motors,
+    )
+    motors_bus.connect()
+
+    values = dict(zip(motors, goal_positions.values(), strict=True))
+    motors_bus.write("Goal_Position", values)
+
+    assert mock_motors.stubs[stub_name].wait_called()
+
+
+@pytest.mark.parametrize(
+    "data_name, value",
+    [
+        ["Torque_Enable", 0],
+        ["Torque_Enable", 1],
+    ],
+)
+def test_write_all_motors_single_value(data_name, value, dummy_motors):
+    mock_motors = MockMotors()
+    values = {m.id: value for m in dummy_motors.values()}
+    stub_name = mock_motors.build_sync_write_stub(data_name, values)
+    motors_bus = DynamixelMotorsBus(
+        port=mock_motors.port,
+        motors=dummy_motors,
+    )
+    motors_bus.connect()
+
+    motors_bus.write(data_name, value)
+
+    assert mock_motors.stubs[stub_name].wait_called()

From a4d487bc1dfecc480d676cb0082c72ff5fcb1ea1 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sat, 22 Mar 2025 16:52:42 +0100
Subject: [PATCH 088/171] Remove comment

---
 tests/mocks/mock_dynamixel.py | 3 ---
 1 file changed, 3 deletions(-)

diff --git a/tests/mocks/mock_dynamixel.py b/tests/mocks/mock_dynamixel.py
index 2a1cf2b1..be26eff5 100644
--- a/tests/mocks/mock_dynamixel.py
+++ b/tests/mocks/mock_dynamixel.py
@@ -498,9 +498,6 @@ class MockMotors(MockSerial):
     ) -> str:
         address, length = self.ctrl_table[data_name]
         sync_read_request = MockInstructionPacket.sync_write(ids_values, address, length)
-        # if data_name != "Goal_Position":
-        #     raise NotImplementedError
-
         stub_name = f"Sync_Write_{data_name}_" + "_".join([str(idx) for idx in ids_values])
         self.stub(
             name=stub_name,

From 0ccc957d5cc19b7b331cf588a10523faf0529f69 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sat, 22 Mar 2025 16:58:41 +0100
Subject: [PATCH 089/171] Fix imports

---
 .../motors/dynamixel/dynamixel_calibration.py | 31 ++++++++++++-------
 .../motors/feetech/feetech_calibration.py     | 19 ++++++------
 2 files changed, 30 insertions(+), 20 deletions(-)

diff --git a/lerobot/common/motors/dynamixel/dynamixel_calibration.py b/lerobot/common/motors/dynamixel/dynamixel_calibration.py
index 881435d1..fbae2e9a 100644
--- a/lerobot/common/motors/dynamixel/dynamixel_calibration.py
+++ b/lerobot/common/motors/dynamixel/dynamixel_calibration.py
@@ -18,9 +18,7 @@
 import numpy as np
 
 from ..motors_bus import CalibrationMode, MotorsBus, TorqueMode
-from .dynamixel import (
-    convert_degrees_to_steps,
-)
+from .tables import MODEL_RESOLUTION
 
 URL_TEMPLATE = (
     "https://raw.githubusercontent.com/huggingface/lerobot/main/media/{robot}/{arm}_{position}.webp"
@@ -47,6 +45,17 @@ def apply_drive_mode(position, drive_mode):
     return position
 
 
+def convert_degrees_to_steps(degrees: float | np.ndarray, models: str | list[str]) -> np.ndarray:
+    """This function converts the degree range to the step range for indicating motors rotation.
+    It assumes a motor achieves a full rotation by going from -180 degree position to +180.
+    The motor resolution (e.g. 4096) corresponds to the number of steps needed to achieve a full rotation.
+    """
+    resolutions = [MODEL_RESOLUTION[model] for model in models]
+    steps = degrees / 180 * np.array(resolutions) / 2
+    steps = steps.astype(int)
+    return steps
+
+
 def compute_nearest_rounded_position(position, models):
     delta_turn = convert_degrees_to_steps(ROTATED_POSITION_DEGREE, models)
     nearest_pos = np.round(position.astype(float) / delta_turn) * delta_turn
@@ -87,11 +96,11 @@ def run_arm_calibration(arm: MotorsBus, robot_type: str, arm_name: str, arm_type
     # 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)
+    zero_target_pos = convert_degrees_to_steps(ZERO_POSITION_DEGREE, arm.models)
 
     # Compute homing offset so that `present_position + homing_offset ~= target_position`.
     zero_pos = arm.read("Present_Position")
-    zero_nearest_pos = compute_nearest_rounded_position(zero_pos, arm.motor_models)
+    zero_nearest_pos = compute_nearest_rounded_position(zero_pos, arm.models)
     homing_offset = zero_target_pos - zero_nearest_pos
 
     # The rotated target position corresponds to a rotation of a quarter turn from the zero position.
@@ -105,7 +114,7 @@ def run_arm_calibration(arm: MotorsBus, robot_type: str, arm_name: str, arm_type
     print("See: " + URL_TEMPLATE.format(robot=robot_type, arm=arm_type, position="rotated"))
     input("Press Enter to continue...")
 
-    rotated_target_pos = convert_degrees_to_steps(ROTATED_POSITION_DEGREE, arm.motor_models)
+    rotated_target_pos = convert_degrees_to_steps(ROTATED_POSITION_DEGREE, arm.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).
@@ -114,7 +123,7 @@ def run_arm_calibration(arm: MotorsBus, robot_type: str, arm_name: str, arm_type
 
     # Re-compute homing offset to take into account drive mode
     rotated_drived_pos = apply_drive_mode(rotated_pos, drive_mode)
-    rotated_nearest_pos = compute_nearest_rounded_position(rotated_drived_pos, arm.motor_models)
+    rotated_nearest_pos = compute_nearest_rounded_position(rotated_drived_pos, arm.models)
     homing_offset = rotated_target_pos - rotated_nearest_pos
 
     print("\nMove arm to rest position")
@@ -123,12 +132,12 @@ def run_arm_calibration(arm: MotorsBus, robot_type: str, arm_name: str, arm_type
     print()
 
     # Joints with rotational motions are expressed in degrees in nominal range of [-180, 180]
-    calib_mode = [CalibrationMode.DEGREE.name] * len(arm.motor_names)
+    calib_mode = [CalibrationMode.DEGREE.name] * len(arm.names)
 
     # TODO(rcadene): make type of joints (DEGREE or LINEAR) configurable from yaml?
-    if robot_type in ["aloha"] and "gripper" in arm.motor_names:
+    if robot_type in ["aloha"] and "gripper" in arm.names:
         # Joints with linear motions (like gripper of Aloha) are expressed in nominal range of [0, 100]
-        calib_idx = arm.motor_names.index("gripper")
+        calib_idx = arm.names.index("gripper")
         calib_mode[calib_idx] = CalibrationMode.LINEAR.name
 
     calib_data = {
@@ -137,6 +146,6 @@ def run_arm_calibration(arm: MotorsBus, robot_type: str, arm_name: str, arm_type
         "start_pos": zero_pos.tolist(),
         "end_pos": rotated_pos.tolist(),
         "calib_mode": calib_mode,
-        "motor_names": arm.motor_names,
+        "motor_names": arm.names,
     }
     return calib_data
diff --git a/lerobot/common/motors/feetech/feetech_calibration.py b/lerobot/common/motors/feetech/feetech_calibration.py
index ad51f222..102b30be 100644
--- a/lerobot/common/motors/feetech/feetech_calibration.py
+++ b/lerobot/common/motors/feetech/feetech_calibration.py
@@ -18,7 +18,8 @@ from ..motors_bus import (
     MotorsBus,
     TorqueMode,
 )
-from .feetech import MODEL_RESOLUTION, FeetechMotorsBus
+from .feetech import FeetechMotorsBus
+from .tables import MODEL_RESOLUTION
 
 URL_TEMPLATE = (
     "https://raw.githubusercontent.com/huggingface/lerobot/main/media/{robot}/{arm}_{position}.webp"
@@ -34,7 +35,7 @@ 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
+        for name in arm.names
     ]
 
 
@@ -106,7 +107,7 @@ def single_motor_calibration(arm: MotorsBus, motor_id: int):
         "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],
+        "motor_name": arm.names[motor_id - 1],
     }
 
     return calib_dict
@@ -141,19 +142,19 @@ def run_full_arm_calibration(arm: MotorsBus, robot_type: str, arm_name: str, arm
     )  # TODO(pepijn): replace with new instruction homing pos (all motors in middle) in tutorial
     input("Press Enter to continue...")
 
-    start_positions = np.zeros(len(arm.motor_ids))
-    end_positions = np.zeros(len(arm.motor_ids))
-    encoder_offsets = np.zeros(len(arm.motor_ids))
+    start_positions = np.zeros(len(arm.ids))
+    end_positions = np.zeros(len(arm.ids))
+    encoder_offsets = np.zeros(len(arm.ids))
 
     modes = get_calibration_modes(arm)
 
-    for i, motor_id in enumerate(arm.motor_ids):
+    for i, motor_id in enumerate(arm.ids):
         if modes[i] == CalibrationMode.DEGREE.name:
             encoder_offsets[i] = calibrate_homing_motor(motor_id, arm)
             start_positions[i] = 0
             end_positions[i] = 0
 
-    for i, motor_id in enumerate(arm.motor_ids):
+    for i, motor_id in enumerate(arm.ids):
         if modes[i] == CalibrationMode.LINEAR.name:
             start_positions[i], end_positions[i] = calibrate_linear_motor(motor_id, arm)
             encoder_offsets[i] = 0
@@ -172,7 +173,7 @@ def run_full_arm_calibration(arm: MotorsBus, robot_type: str, arm_name: str, arm
         "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,
+        "motor_names": arm.names,
     }
     return calib_dict
 

From 1d3e1cbdbdba33e370ae66cd15bb33de0f185afa Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sat, 22 Mar 2025 17:02:01 +0100
Subject: [PATCH 090/171] Add feetech write tests

---
 tests/mocks/mock_feetech.py  | 105 ++++++++++++++++++++++++++++++++---
 tests/motors/test_feetech.py |  51 +++++++++++++++++
 2 files changed, 149 insertions(+), 7 deletions(-)

diff --git a/tests/mocks/mock_feetech.py b/tests/mocks/mock_feetech.py
index 7ff994ee..2a10e789 100644
--- a/tests/mocks/mock_feetech.py
+++ b/tests/mocks/mock_feetech.py
@@ -1,12 +1,14 @@
 import abc
 import random
+import threading
+import time
 from typing import Callable
 
 import scservo_sdk as scs
 import serial
-from mock_serial import MockSerial
+from mock_serial.mock_serial import MockSerial, Stub
 
-from lerobot.common.motors.feetech.tables import SCS_SERIES_CONTROL_TABLE
+from lerobot.common.motors.feetech import SCS_SERIES_CONTROL_TABLE, FeetechMotorsBus
 
 # https://files.waveshare.com/upload/2/27/Communication_Protocol_User_Manual-EN%28191218-0923%29.pdf
 INSTRUCTION_TYPES = {
@@ -100,12 +102,12 @@ class MockInstructionPacket(MockFeetechPacket):
         """
         Builds a "Sync_Read" broadcast instruction.
 
-        The parameters for Sync Read (Protocol 2.0) are:
+        The parameters for Sync Read are:
             param[0]   = start_address
             param[1]   = data_length
             param[2+]  = motor IDs to read from
 
-        And 'length' = (number_of_params + 7), where:
+        And 'length' = (number_of_params + 4), where:
             +1 is for instruction byte,
             +1 is for the address byte,
             +1 is for the length bytes,
@@ -115,6 +117,44 @@ class MockInstructionPacket(MockFeetechPacket):
         length = len(scs_ids) + 4
         return cls.build(scs_id=scs.BROADCAST_ID, params=params, length=length, instruct_type="Sync_Read")
 
+    @classmethod
+    def sync_write(
+        cls,
+        ids_values: dict[int],
+        start_address: int,
+        data_length: int,
+    ) -> bytes:
+        """
+        Builds a "Sync_Write" broadcast instruction.
+
+        The parameters for Sync_Write are:
+            param[0]   = start_address
+            param[1]   = data_length
+            param[2]   = [1st motor] ID
+            param[2+1] = [1st motor] 1st Byte
+            param[2+2] = [1st motor] 2nd Byte
+            ...
+            param[5+X] = [1st motor] X-th Byte
+            param[6]   = [2nd motor] ID
+            param[6+1] = [2nd motor] 1st Byte
+            param[6+2] = [2nd motor] 2nd Byte
+            ...
+            param[6+X] = [2nd motor] X-th Byte
+
+        And 'length' = ((number_of_params * 1 + data_length) + 4), where:
+            +1 is for instruction byte,
+            +1 is for the address byte,
+            +1 is for the length bytes,
+            +1 is for the checksum at the end.
+        """
+        data = []
+        for idx, value in ids_values.items():
+            split_value = FeetechMotorsBus.split_int_bytes(value, data_length)
+            data += [idx, *split_value]
+        params = [start_address, data_length, *data]
+        length = len(ids_values) * (1 + data_length) + 4
+        return cls.build(scs_id=scs.BROADCAST_ID, params=params, length=length, instruct_type="Sync_Write")
+
 
 class MockStatusPacket(MockFeetechPacket):
     """
@@ -205,13 +245,38 @@ class MockPortHandler(scs.PortHandler):
         return True
 
 
+class WaitableStub(Stub):
+    """
+    In some situations, a test might be checking if a stub has been called before `MockSerial` thread had time
+    to read, match, and call the stub. In these situations, the test can fail randomly.
+
+    Use `wait_called()` or `wait_calls()` to block until the stub is called, avoiding race conditions.
+    """
+
+    def __init__(self, **kwargs):
+        super().__init__(**kwargs)
+        self._event = threading.Event()
+
+    def call(self):
+        self._event.set()
+        return super().call()
+
+    def wait_called(self, timeout: float = 1.0):
+        return self._event.wait(timeout)
+
+    def wait_calls(self, min_calls: int = 1, timeout: float = 1.0):
+        start = time.perf_counter()
+        while time.perf_counter() - start < timeout:
+            if self.calls >= min_calls:
+                return self.calls
+            time.sleep(0.005)
+        raise TimeoutError(f"Stub not called {min_calls} times within {timeout} seconds.")
+
+
 class MockMotors(MockSerial):
     """
     This class will simulate physical motors by responding with valid status packets upon receiving some
     instruction packets. It is meant to test MotorsBus classes.
-
-    'data_name' supported:
-        - Present_Position
     """
 
     ctrl_table = SCS_SERIES_CONTROL_TABLE
@@ -220,6 +285,15 @@ class MockMotors(MockSerial):
         super().__init__()
         self.open()
 
+    @property
+    def stubs(self) -> dict[str, WaitableStub]:
+        return super().stubs
+
+    def stub(self, *, name=None, **kwargs):
+        new_stub = WaitableStub(**kwargs)
+        self._MockSerial__stubs[name or new_stub.receive_bytes] = new_stub
+        return new_stub
+
     def build_broadcast_ping_stub(
         self, ids_models_firmwares: dict[int, list[int]] | None = None, num_invalid_try: int = 0
     ) -> str:
@@ -256,6 +330,10 @@ class MockMotors(MockSerial):
     def build_sync_read_stub(
         self, data_name: str, ids_values: dict[int, int] | None = None, num_invalid_try: int = 0
     ) -> str:
+        """
+        'data_name' supported:
+            - Present_Position
+        """
         address, length = self.ctrl_table[data_name]
         sync_read_request = MockInstructionPacket.sync_read(list(ids_values), address, length)
         if data_name != "Present_Position":
@@ -274,6 +352,19 @@ class MockMotors(MockSerial):
         )
         return stub_name
 
+    def build_sync_write_stub(
+        self, data_name: str, ids_values: dict[int, int] | None = None, num_invalid_try: int = 0
+    ) -> str:
+        address, length = self.ctrl_table[data_name]
+        sync_read_request = MockInstructionPacket.sync_write(ids_values, address, length)
+        stub_name = f"Sync_Write_{data_name}_" + "_".join([str(idx) for idx in ids_values])
+        self.stub(
+            name=stub_name,
+            receive_bytes=sync_read_request,
+            send_fn=self._build_send_fn(b"", num_invalid_try),
+        )
+        return stub_name
+
     @staticmethod
     def _build_send_fn(packet: bytes, num_invalid_try: int = 0) -> Callable[[int], bytes]:
         def send_fn(_call_count: int) -> bytes:
diff --git a/tests/motors/test_feetech.py b/tests/motors/test_feetech.py
index d4a4397d..698e0adb 100644
--- a/tests/motors/test_feetech.py
+++ b/tests/motors/test_feetech.py
@@ -235,3 +235,54 @@ def test_read_num_retry(num_retry, num_invalid_try, pos, dummy_motors):
 
     expected_calls = min(1 + num_retry, 1 + num_invalid_try)
     assert mock_motors.stubs[stub_name].calls == expected_calls
+
+
+@pytest.mark.parametrize(
+    "motors",
+    [
+        [1, 2, 3],
+        ["dummy_1", "dummy_2", "dummy_3"],
+        [1, "dummy_2", 3],
+    ],
+    ids=["by ids", "by names", "mixed"],
+)
+def test_write_all_motors(motors, dummy_motors):
+    mock_motors = MockMotors()
+    goal_positions = {
+        1: 1337,
+        2: 42,
+        3: 4016,
+    }
+    stub_name = mock_motors.build_sync_write_stub("Goal_Position", goal_positions)
+    motors_bus = FeetechMotorsBus(
+        port=mock_motors.port,
+        motors=dummy_motors,
+    )
+    motors_bus.connect()
+
+    values = dict(zip(motors, goal_positions.values(), strict=True))
+    motors_bus.write("Goal_Position", values)
+
+    assert mock_motors.stubs[stub_name].wait_called()
+
+
+@pytest.mark.parametrize(
+    "data_name, value",
+    [
+        ["Torque_Enable", 0],
+        ["Torque_Enable", 1],
+    ],
+)
+def test_write_all_motors_single_value(data_name, value, dummy_motors):
+    mock_motors = MockMotors()
+    values = {m.id: value for m in dummy_motors.values()}
+    stub_name = mock_motors.build_sync_write_stub(data_name, values)
+    motors_bus = FeetechMotorsBus(
+        port=mock_motors.port,
+        motors=dummy_motors,
+    )
+    motors_bus.connect()
+
+    motors_bus.write(data_name, value)
+
+    assert mock_motors.stubs[stub_name].wait_called()

From 7d558d058ecb79bb5853f08cdeece12aa5d3ada7 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sat, 22 Mar 2025 17:03:18 +0100
Subject: [PATCH 091/171] Nit

---
 tests/mocks/mock_dynamixel.py | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/tests/mocks/mock_dynamixel.py b/tests/mocks/mock_dynamixel.py
index be26eff5..deb96ee7 100644
--- a/tests/mocks/mock_dynamixel.py
+++ b/tests/mocks/mock_dynamixel.py
@@ -346,7 +346,7 @@ class MockStatusPacket(MockDynamixelPacketv2):
         """Builds a 'Present_Position' status packet.
 
         Args:
-            dxl_id (int): Servo id
+            dxl_id (int): ID of the servo responding.
             pos (int | None, optional): Desired 'Present_Position' to be returned in the packet. If None, it
                 will use a random value in the min_max_range. Defaults to None.
             min_max_range (tuple, optional): Min/max range to generate the position values used for when 'pos'

From fedac994c371c5964640a5c77a3b069ed81ffbe9 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sat, 22 Mar 2025 18:16:13 +0100
Subject: [PATCH 092/171] Add autoclosing fixture

---
 tests/mocks/mock_dynamixel.py  |  1 -
 tests/mocks/mock_feetech.py    |  1 -
 tests/motors/test_dynamixel.py | 33 +++++++++++++++++----------------
 tests/motors/test_feetech.py   | 33 +++++++++++++++++----------------
 4 files changed, 34 insertions(+), 34 deletions(-)

diff --git a/tests/mocks/mock_dynamixel.py b/tests/mocks/mock_dynamixel.py
index deb96ee7..b75479d3 100644
--- a/tests/mocks/mock_dynamixel.py
+++ b/tests/mocks/mock_dynamixel.py
@@ -424,7 +424,6 @@ class MockMotors(MockSerial):
 
     def __init__(self):
         super().__init__()
-        self.open()
 
     @property
     def stubs(self) -> dict[str, WaitableStub]:
diff --git a/tests/mocks/mock_feetech.py b/tests/mocks/mock_feetech.py
index 2a10e789..44061094 100644
--- a/tests/mocks/mock_feetech.py
+++ b/tests/mocks/mock_feetech.py
@@ -283,7 +283,6 @@ class MockMotors(MockSerial):
 
     def __init__(self):
         super().__init__()
-        self.open()
 
     @property
     def stubs(self) -> dict[str, WaitableStub]:
diff --git a/tests/motors/test_dynamixel.py b/tests/motors/test_dynamixel.py
index 6d08ba00..2ea9827e 100644
--- a/tests/motors/test_dynamixel.py
+++ b/tests/motors/test_dynamixel.py
@@ -1,4 +1,5 @@
 import sys
+from typing import Generator
 from unittest.mock import patch
 
 import dynamixel_sdk as dxl
@@ -18,6 +19,14 @@ def patch_port_handler():
         yield
 
 
+@pytest.fixture
+def mock_motors() -> Generator[MockMotors, None, None]:
+    motors = MockMotors()
+    motors.open()
+    yield motors
+    motors.close()
+
+
 @pytest.fixture
 def dummy_motors() -> dict[str, Motor]:
     return {
@@ -91,8 +100,7 @@ def test_abc_implementation(dummy_motors):
         [3, 1120],
     ],
 )
-def test_ping(idx, model_nb, dummy_motors):
-    mock_motors = MockMotors()
+def test_ping(idx, model_nb, mock_motors, dummy_motors):
     mock_motors.build_ping_stub(idx, model_nb)
     motors_bus = DynamixelMotorsBus(
         port=mock_motors.port,
@@ -105,13 +113,12 @@ def test_ping(idx, model_nb, dummy_motors):
     assert ping_model_nb == model_nb
 
 
-def test_broadcast_ping(dummy_motors):
+def test_broadcast_ping(mock_motors, dummy_motors):
     expected_pings = {
         1: [1060, 50],
         2: [1120, 30],
         3: [1190, 10],
     }
-    mock_motors = MockMotors()
     mock_motors.build_broadcast_ping_stub(expected_pings)
     motors_bus = DynamixelMotorsBus(
         port=mock_motors.port,
@@ -134,8 +141,7 @@ def test_broadcast_ping(dummy_motors):
     ],
     ids=["None", "by ids", "by names", "mixed"],
 )
-def test_read_all_motors(motors, dummy_motors):
-    mock_motors = MockMotors()
+def test_read_all_motors(motors, mock_motors, dummy_motors):
     expected_positions = {
         1: 1337,
         2: 42,
@@ -163,8 +169,7 @@ def test_read_all_motors(motors, dummy_motors):
         [3, 4016],
     ],
 )
-def test_read_single_motor_by_name(idx, pos, dummy_motors):
-    mock_motors = MockMotors()
+def test_read_single_motor_by_name(idx, pos, mock_motors, dummy_motors):
     expected_position = {idx: pos}
     stub_name = mock_motors.build_sync_read_stub("Present_Position", expected_position)
     motors_bus = DynamixelMotorsBus(
@@ -187,8 +192,7 @@ def test_read_single_motor_by_name(idx, pos, dummy_motors):
         [3, 4016],
     ],
 )
-def test_read_single_motor_by_id(idx, pos, dummy_motors):
-    mock_motors = MockMotors()
+def test_read_single_motor_by_id(idx, pos, mock_motors, dummy_motors):
     expected_position = {idx: pos}
     stub_name = mock_motors.build_sync_read_stub("Present_Position", expected_position)
     motors_bus = DynamixelMotorsBus(
@@ -212,8 +216,7 @@ def test_read_single_motor_by_id(idx, pos, dummy_motors):
         [2, 1, 999],
     ],
 )
-def test_read_num_retry(num_retry, num_invalid_try, pos, dummy_motors):
-    mock_motors = MockMotors()
+def test_read_num_retry(num_retry, num_invalid_try, pos, mock_motors, dummy_motors):
     expected_position = {1: pos}
     stub_name = mock_motors.build_sync_read_stub(
         "Present_Position", expected_position, num_invalid_try=num_invalid_try
@@ -244,8 +247,7 @@ def test_read_num_retry(num_retry, num_invalid_try, pos, dummy_motors):
     ],
     ids=["by ids", "by names", "mixed"],
 )
-def test_write_all_motors(motors, dummy_motors):
-    mock_motors = MockMotors()
+def test_write_all_motors(motors, mock_motors, dummy_motors):
     goal_positions = {
         1: 1337,
         2: 42,
@@ -271,8 +273,7 @@ def test_write_all_motors(motors, dummy_motors):
         ["Torque_Enable", 1],
     ],
 )
-def test_write_all_motors_single_value(data_name, value, dummy_motors):
-    mock_motors = MockMotors()
+def test_write_all_motors_single_value(data_name, value, mock_motors, dummy_motors):
     values = {m.id: value for m in dummy_motors.values()}
     stub_name = mock_motors.build_sync_write_stub(data_name, values)
     motors_bus = DynamixelMotorsBus(
diff --git a/tests/motors/test_feetech.py b/tests/motors/test_feetech.py
index 698e0adb..168e1aaf 100644
--- a/tests/motors/test_feetech.py
+++ b/tests/motors/test_feetech.py
@@ -1,4 +1,5 @@
 import sys
+from typing import Generator
 from unittest.mock import patch
 
 import pytest
@@ -18,6 +19,14 @@ def patch_port_handler():
         yield
 
 
+@pytest.fixture
+def mock_motors() -> Generator[MockMotors, None, None]:
+    motors = MockMotors()
+    motors.open()
+    yield motors
+    motors.close()
+
+
 @pytest.fixture
 def dummy_motors() -> dict[str, Motor]:
     return {
@@ -92,8 +101,7 @@ def test_abc_implementation(dummy_motors):
         [3, 1120],
     ],
 )
-def test_ping(idx, model_nb, dummy_motors):
-    mock_motors = MockMotors()
+def test_ping(idx, model_nb, mock_motors, dummy_motors):
     mock_motors.build_ping_stub(idx, model_nb)
     motors_bus = FeetechMotorsBus(
         port=mock_motors.port,
@@ -107,13 +115,12 @@ def test_ping(idx, model_nb, dummy_motors):
 
 
 @pytest.mark.skip("TODO")
-def test_broadcast_ping(dummy_motors):
+def test_broadcast_ping(mock_motors, dummy_motors):
     expected_pings = {
         1: [1060, 50],
         2: [1120, 30],
         3: [1190, 10],
     }
-    mock_motors = MockMotors()
     mock_motors.build_broadcast_ping_stub(expected_pings)
     motors_bus = FeetechMotorsBus(
         port=mock_motors.port,
@@ -136,8 +143,7 @@ def test_broadcast_ping(dummy_motors):
     ],
     ids=["None", "by ids", "by names", "mixed"],
 )
-def test_read_all_motors(motors, dummy_motors):
-    mock_motors = MockMotors()
+def test_read_all_motors(motors, mock_motors, dummy_motors):
     expected_positions = {
         1: 1337,
         2: 42,
@@ -165,8 +171,7 @@ def test_read_all_motors(motors, dummy_motors):
         [3, 4016],
     ],
 )
-def test_read_single_motor_by_name(idx, pos, dummy_motors):
-    mock_motors = MockMotors()
+def test_read_single_motor_by_name(idx, pos, mock_motors, dummy_motors):
     expected_position = {idx: pos}
     stub_name = mock_motors.build_sync_read_stub("Present_Position", expected_position)
     motors_bus = FeetechMotorsBus(
@@ -189,8 +194,7 @@ def test_read_single_motor_by_name(idx, pos, dummy_motors):
         [3, 4016],
     ],
 )
-def test_read_single_motor_by_id(idx, pos, dummy_motors):
-    mock_motors = MockMotors()
+def test_read_single_motor_by_id(idx, pos, mock_motors, dummy_motors):
     expected_position = {idx: pos}
     stub_name = mock_motors.build_sync_read_stub("Present_Position", expected_position)
     motors_bus = FeetechMotorsBus(
@@ -214,8 +218,7 @@ def test_read_single_motor_by_id(idx, pos, dummy_motors):
         [2, 1, 999],
     ],
 )
-def test_read_num_retry(num_retry, num_invalid_try, pos, dummy_motors):
-    mock_motors = MockMotors()
+def test_read_num_retry(num_retry, num_invalid_try, pos, mock_motors, dummy_motors):
     expected_position = {1: pos}
     stub_name = mock_motors.build_sync_read_stub(
         "Present_Position", expected_position, num_invalid_try=num_invalid_try
@@ -246,8 +249,7 @@ def test_read_num_retry(num_retry, num_invalid_try, pos, dummy_motors):
     ],
     ids=["by ids", "by names", "mixed"],
 )
-def test_write_all_motors(motors, dummy_motors):
-    mock_motors = MockMotors()
+def test_write_all_motors(motors, mock_motors, dummy_motors):
     goal_positions = {
         1: 1337,
         2: 42,
@@ -273,8 +275,7 @@ def test_write_all_motors(motors, dummy_motors):
         ["Torque_Enable", 1],
     ],
 )
-def test_write_all_motors_single_value(data_name, value, dummy_motors):
-    mock_motors = MockMotors()
+def test_write_all_motors_single_value(data_name, value, mock_motors, dummy_motors):
     values = {m.id: value for m in dummy_motors.values()}
     stub_name = mock_motors.build_sync_write_stub(data_name, values)
     motors_bus = FeetechMotorsBus(

From c2e761437daab713b3a16946b2f62d9a316f6391 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sat, 22 Mar 2025 18:53:57 +0100
Subject: [PATCH 093/171] Assert ping stub called

---
 tests/motors/test_dynamixel.py | 6 ++++--
 tests/motors/test_feetech.py   | 6 ++++--
 2 files changed, 8 insertions(+), 4 deletions(-)

diff --git a/tests/motors/test_dynamixel.py b/tests/motors/test_dynamixel.py
index 2ea9827e..5f70ba6a 100644
--- a/tests/motors/test_dynamixel.py
+++ b/tests/motors/test_dynamixel.py
@@ -101,7 +101,7 @@ def test_abc_implementation(dummy_motors):
     ],
 )
 def test_ping(idx, model_nb, mock_motors, dummy_motors):
-    mock_motors.build_ping_stub(idx, model_nb)
+    stub_name = mock_motors.build_ping_stub(idx, model_nb)
     motors_bus = DynamixelMotorsBus(
         port=mock_motors.port,
         motors=dummy_motors,
@@ -111,6 +111,7 @@ def test_ping(idx, model_nb, mock_motors, dummy_motors):
     ping_model_nb = motors_bus.ping(idx)
 
     assert ping_model_nb == model_nb
+    assert mock_motors.stubs[stub_name].called
 
 
 def test_broadcast_ping(mock_motors, dummy_motors):
@@ -119,7 +120,7 @@ def test_broadcast_ping(mock_motors, dummy_motors):
         2: [1120, 30],
         3: [1190, 10],
     }
-    mock_motors.build_broadcast_ping_stub(expected_pings)
+    stub_name = mock_motors.build_broadcast_ping_stub(expected_pings)
     motors_bus = DynamixelMotorsBus(
         port=mock_motors.port,
         motors=dummy_motors,
@@ -129,6 +130,7 @@ def test_broadcast_ping(mock_motors, dummy_motors):
     ping_list = motors_bus.broadcast_ping()
 
     assert ping_list == expected_pings
+    assert mock_motors.stubs[stub_name].called
 
 
 @pytest.mark.parametrize(
diff --git a/tests/motors/test_feetech.py b/tests/motors/test_feetech.py
index 168e1aaf..e0d63c40 100644
--- a/tests/motors/test_feetech.py
+++ b/tests/motors/test_feetech.py
@@ -102,7 +102,7 @@ def test_abc_implementation(dummy_motors):
     ],
 )
 def test_ping(idx, model_nb, mock_motors, dummy_motors):
-    mock_motors.build_ping_stub(idx, model_nb)
+    stub_name = mock_motors.build_ping_stub(idx, model_nb)
     motors_bus = FeetechMotorsBus(
         port=mock_motors.port,
         motors=dummy_motors,
@@ -112,6 +112,7 @@ def test_ping(idx, model_nb, mock_motors, dummy_motors):
     ping_model_nb = motors_bus.ping(idx)
 
     assert ping_model_nb == model_nb
+    assert mock_motors.stubs[stub_name].called
 
 
 @pytest.mark.skip("TODO")
@@ -121,7 +122,7 @@ def test_broadcast_ping(mock_motors, dummy_motors):
         2: [1120, 30],
         3: [1190, 10],
     }
-    mock_motors.build_broadcast_ping_stub(expected_pings)
+    stub_name = mock_motors.build_broadcast_ping_stub(expected_pings)
     motors_bus = FeetechMotorsBus(
         port=mock_motors.port,
         motors=dummy_motors,
@@ -131,6 +132,7 @@ def test_broadcast_ping(mock_motors, dummy_motors):
     ping_list = motors_bus.broadcast_ping()
 
     assert ping_list == expected_pings
+    assert mock_motors.stubs[stub_name].called
 
 
 @pytest.mark.parametrize(

From e047074825eb6ab81e35dc48416ed96f53d40e3d Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sun, 23 Mar 2025 10:20:08 +0100
Subject: [PATCH 094/171] Add CalibrationMode

---
 lerobot/common/motors/motors_bus.py | 19 ++++++++++---------
 tests/motors/test_dynamixel.py      |  8 ++++----
 tests/motors/test_feetech.py        |  8 ++++----
 3 files changed, 18 insertions(+), 17 deletions(-)

diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py
index 2a64a887..6da8b36d 100644
--- a/lerobot/common/motors/motors_bus.py
+++ b/lerobot/common/motors/motors_bus.py
@@ -74,10 +74,17 @@ class DriveMode(Enum):
 
 
 class CalibrationMode(Enum):
-    # Joints with rotational motions are expressed in degrees in nominal range of [-180, 180]
     DEGREE = 0
-    # Joints with liner motions (like gripper of Aloha) are expressed in nominal range of [0, 100]
-    LINEAR = 1
+    RANGE_0_100 = 1
+    RANGE_M100_100 = 2
+    VELOCITY = 3
+
+
+@dataclass
+class Motor:
+    id: int
+    model: str
+    calibration: CalibrationMode
 
 
 class JointOutOfRangeError(Exception):
@@ -190,12 +197,6 @@ class GroupSyncWrite(Protocol):
     def txPacket(self): ...
 
 
-@dataclass
-class Motor:
-    id: int
-    model: str
-
-
 class MotorsBus(abc.ABC):
     """The main LeRobot class for implementing motors buses.
 
diff --git a/tests/motors/test_dynamixel.py b/tests/motors/test_dynamixel.py
index 5f70ba6a..688a7367 100644
--- a/tests/motors/test_dynamixel.py
+++ b/tests/motors/test_dynamixel.py
@@ -5,7 +5,7 @@ from unittest.mock import patch
 import dynamixel_sdk as dxl
 import pytest
 
-from lerobot.common.motors import Motor
+from lerobot.common.motors import CalibrationMode, Motor
 from lerobot.common.motors.dynamixel import DynamixelMotorsBus
 from tests.mocks.mock_dynamixel import MockMotors, MockPortHandler
 
@@ -30,9 +30,9 @@ def mock_motors() -> Generator[MockMotors, None, None]:
 @pytest.fixture
 def dummy_motors() -> dict[str, Motor]:
     return {
-        "dummy_1": Motor(id=1, model="xl430-w250"),
-        "dummy_2": Motor(id=2, model="xm540-w270"),
-        "dummy_3": Motor(id=3, model="xl330-m077"),
+        "dummy_1": Motor(1, "xl430-w250", CalibrationMode.RANGE_M100_100),
+        "dummy_2": Motor(2, "xm540-w270", CalibrationMode.RANGE_M100_100),
+        "dummy_3": Motor(3, "xl330-m077", CalibrationMode.RANGE_M100_100),
     }
 
 
diff --git a/tests/motors/test_feetech.py b/tests/motors/test_feetech.py
index e0d63c40..cb9dcda8 100644
--- a/tests/motors/test_feetech.py
+++ b/tests/motors/test_feetech.py
@@ -5,7 +5,7 @@ from unittest.mock import patch
 import pytest
 import scservo_sdk as scs
 
-from lerobot.common.motors import Motor
+from lerobot.common.motors import CalibrationMode, Motor
 from lerobot.common.motors.feetech import FeetechMotorsBus
 from tests.mocks.mock_feetech import MockMotors, MockPortHandler
 
@@ -30,9 +30,9 @@ def mock_motors() -> Generator[MockMotors, None, None]:
 @pytest.fixture
 def dummy_motors() -> dict[str, Motor]:
     return {
-        "dummy_1": Motor(id=1, model="sts3215"),
-        "dummy_2": Motor(id=2, model="sts3215"),
-        "dummy_3": Motor(id=3, model="sts3215"),
+        "dummy_1": Motor(1, "sts3215", CalibrationMode.RANGE_M100_100),
+        "dummy_2": Motor(2, "sts3215", CalibrationMode.RANGE_M100_100),
+        "dummy_3": Motor(3, "sts3215", CalibrationMode.RANGE_M100_100),
     }
 
 

From 1f1e1bcfe89938f8f2f3a13065f056f4afc01d99 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sun, 23 Mar 2025 11:08:20 +0100
Subject: [PATCH 095/171] Add Motor in dxl robots

---
 lerobot/common/motors/dynamixel/dynamixel.py  |  4 ++--
 lerobot/common/motors/feetech/feetech.py      |  4 ++--
 lerobot/common/robots/koch/robot_koch.py      | 14 ++++++-------
 .../robots/viperx/configuration_viperx.py     | 12 -----------
 lerobot/common/robots/viperx/robot_viperx.py  | 20 +++++++++----------
 .../common/teleoperators/koch/teleop_koch.py  | 14 ++++++-------
 .../widowx/configuration_widowx.py            | 11 ----------
 .../teleoperators/widowx/teleop_widowx.py     | 20 +++++++++----------
 8 files changed, 38 insertions(+), 61 deletions(-)

diff --git a/lerobot/common/motors/dynamixel/dynamixel.py b/lerobot/common/motors/dynamixel/dynamixel.py
index 8c5290b4..e988d3a0 100644
--- a/lerobot/common/motors/dynamixel/dynamixel.py
+++ b/lerobot/common/motors/dynamixel/dynamixel.py
@@ -20,7 +20,7 @@
 
 from copy import deepcopy
 
-from ..motors_bus import MotorsBus
+from ..motors_bus import Motor, MotorsBus
 from .tables import MODEL_BAUDRATE_TABLE, MODEL_CONTROL_TABLE, MODEL_RESOLUTION
 
 PROTOCOL_VERSION = 2.0
@@ -48,7 +48,7 @@ class DynamixelMotorsBus(MotorsBus):
     def __init__(
         self,
         port: str,
-        motors: dict[str, tuple[int, str]],
+        motors: dict[str, Motor],
     ):
         super().__init__(port, motors)
         import dynamixel_sdk as dxl
diff --git a/lerobot/common/motors/feetech/feetech.py b/lerobot/common/motors/feetech/feetech.py
index 78fae13a..3e8eb20a 100644
--- a/lerobot/common/motors/feetech/feetech.py
+++ b/lerobot/common/motors/feetech/feetech.py
@@ -14,7 +14,7 @@
 
 from copy import deepcopy
 
-from ..motors_bus import MotorsBus
+from ..motors_bus import Motor, MotorsBus
 from .tables import (
     CALIBRATION_REQUIRED,
     MODEL_BAUDRATE_TABLE,
@@ -44,7 +44,7 @@ class FeetechMotorsBus(MotorsBus):
     def __init__(
         self,
         port: str,
-        motors: dict[str, tuple[int, str]],
+        motors: dict[str, Motor],
     ):
         super().__init__(port, motors)
         import scservo_sdk as scs
diff --git a/lerobot/common/robots/koch/robot_koch.py b/lerobot/common/robots/koch/robot_koch.py
index ff2bdb65..1f57e6c3 100644
--- a/lerobot/common/robots/koch/robot_koch.py
+++ b/lerobot/common/robots/koch/robot_koch.py
@@ -23,7 +23,7 @@ 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 import TorqueMode
+from lerobot.common.motors import CalibrationMode, Motor, TorqueMode
 from lerobot.common.motors.dynamixel import (
     DynamixelMotorsBus,
     run_arm_calibration,
@@ -52,12 +52,12 @@ class KochRobot(Robot):
         self.arm = DynamixelMotorsBus(
             port=self.config.port,
             motors={
-                "shoulder_pan": (1, "xl430-w250"),
-                "shoulder_lift": (2, "xl430-w250"),
-                "elbow_flex": (3, "xl330-m288"),
-                "wrist_flex": (4, "xl330-m288"),
-                "wrist_roll": (5, "xl330-m288"),
-                "gripper": (6, "xl330-m288"),
+                "shoulder_pan": Motor(1, "xl430-w250", CalibrationMode.RANGE_M100_100),
+                "shoulder_lift": Motor(2, "xl430-w250", CalibrationMode.RANGE_M100_100),
+                "elbow_flex": Motor(3, "xl330-m288", CalibrationMode.RANGE_M100_100),
+                "wrist_flex": Motor(4, "xl330-m288", CalibrationMode.RANGE_M100_100),
+                "wrist_roll": Motor(5, "xl330-m288", CalibrationMode.RANGE_M100_100),
+                "gripper": Motor(6, "xl330-m288", CalibrationMode.RANGE_0_100),
             },
         )
         self.cameras = make_cameras_from_configs(config.cameras)
diff --git a/lerobot/common/robots/viperx/configuration_viperx.py b/lerobot/common/robots/viperx/configuration_viperx.py
index 44256889..186f0ad6 100644
--- a/lerobot/common/robots/viperx/configuration_viperx.py
+++ b/lerobot/common/robots/viperx/configuration_viperx.py
@@ -20,20 +20,8 @@ class ViperXRobotConfig(RobotConfig):
     # 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
index 7dbc8d34..e4b20094 100644
--- a/lerobot/common/robots/viperx/robot_viperx.py
+++ b/lerobot/common/robots/viperx/robot_viperx.py
@@ -13,7 +13,7 @@ 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 import TorqueMode
+from lerobot.common.motors import CalibrationMode, Motor, TorqueMode
 from lerobot.common.motors.dynamixel import (
     DynamixelMotorsBus,
     run_arm_calibration,
@@ -43,15 +43,15 @@ class ViperXRobot(Robot):
         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,
+                "waist": Motor(1, "xm540-w270", CalibrationMode.RANGE_M100_100),
+                "shoulder": Motor(2, "xm540-w270", CalibrationMode.RANGE_M100_100),
+                "shoulder_shadow": Motor(3, "xm540-w270", CalibrationMode.RANGE_M100_100),
+                "elbow": Motor(4, "xm540-w270", CalibrationMode.RANGE_M100_100),
+                "elbow_shadow": Motor(5, "xm540-w270", CalibrationMode.RANGE_M100_100),
+                "forearm_roll": Motor(6, "xm540-w270", CalibrationMode.RANGE_M100_100),
+                "wrist_angle": Motor(7, "xm540-w270", CalibrationMode.RANGE_M100_100),
+                "wrist_rotate": Motor(8, "xm430-w350", CalibrationMode.RANGE_M100_100),
+                "gripper": Motor(9, "xm430-w350", CalibrationMode.RANGE_0_100),
             },
         )
         self.cameras = make_cameras_from_configs(config.cameras)
diff --git a/lerobot/common/teleoperators/koch/teleop_koch.py b/lerobot/common/teleoperators/koch/teleop_koch.py
index b394019a..dfd7f67d 100644
--- a/lerobot/common/teleoperators/koch/teleop_koch.py
+++ b/lerobot/common/teleoperators/koch/teleop_koch.py
@@ -21,7 +21,7 @@ import time
 import numpy as np
 
 from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError
-from lerobot.common.motors import TorqueMode
+from lerobot.common.motors import CalibrationMode, Motor, TorqueMode
 from lerobot.common.motors.dynamixel import (
     DynamixelMotorsBus,
     run_arm_calibration,
@@ -49,12 +49,12 @@ class KochTeleop(Teleoperator):
         self.arm = DynamixelMotorsBus(
             port=self.config.port,
             motors={
-                "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"),
+                "shoulder_pan": Motor(1, "xl330-m077", CalibrationMode.RANGE_M100_100),
+                "shoulder_lift": Motor(2, "xl330-m077", CalibrationMode.RANGE_M100_100),
+                "elbow_flex": Motor(3, "xl330-m077", CalibrationMode.RANGE_M100_100),
+                "wrist_flex": Motor(4, "xl330-m077", CalibrationMode.RANGE_M100_100),
+                "wrist_roll": Motor(5, "xl330-m077", CalibrationMode.RANGE_M100_100),
+                "gripper": Motor(6, "xl330-m077", CalibrationMode.RANGE_0_100),
             },
         )
 
diff --git a/lerobot/common/teleoperators/widowx/configuration_widowx.py b/lerobot/common/teleoperators/widowx/configuration_widowx.py
index 133237e2..896405e9 100644
--- a/lerobot/common/teleoperators/widowx/configuration_widowx.py
+++ b/lerobot/common/teleoperators/widowx/configuration_widowx.py
@@ -36,14 +36,3 @@ class WidowXTeleopConfig(TeleoperatorConfig):
     # 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
index a661b003..702f8d44 100644
--- a/lerobot/common/teleoperators/widowx/teleop_widowx.py
+++ b/lerobot/common/teleoperators/widowx/teleop_widowx.py
@@ -21,7 +21,7 @@ import time
 import numpy as np
 
 from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError
-from lerobot.common.motors import TorqueMode
+from lerobot.common.motors import CalibrationMode, Motor, TorqueMode
 from lerobot.common.motors.dynamixel import (
     DynamixelMotorsBus,
     run_arm_calibration,
@@ -47,15 +47,15 @@ class WidowXTeleop(Teleoperator):
         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,
+                "waist": Motor(1, "xm430-w350", CalibrationMode.RANGE_M100_100),
+                "shoulder": Motor(2, "xm430-w350", CalibrationMode.RANGE_M100_100),
+                "shoulder_shadow": Motor(3, "xm430-w350", CalibrationMode.RANGE_M100_100),
+                "elbow": Motor(4, "xm430-w350", CalibrationMode.RANGE_M100_100),
+                "elbow_shadow": Motor(5, "xm430-w350", CalibrationMode.RANGE_M100_100),
+                "forearm_roll": Motor(6, "xm430-w350", CalibrationMode.RANGE_M100_100),
+                "wrist_angle": Motor(7, "xm430-w350", CalibrationMode.RANGE_M100_100),
+                "wrist_rotate": Motor(8, "xl430-w250", CalibrationMode.RANGE_M100_100),
+                "gripper": Motor(9, "xc430-w150", CalibrationMode.RANGE_0_100),
             },
         )
 

From a2f5c34625a88bddf71d3bcd073ae8e1fff24b83 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sun, 23 Mar 2025 11:55:39 +0100
Subject: [PATCH 096/171] Simplify split_int_bytes

---
 lerobot/common/motors/dynamixel/dynamixel.py | 9 ++-------
 lerobot/common/motors/feetech/feetech.py     | 9 ++-------
 2 files changed, 4 insertions(+), 14 deletions(-)

diff --git a/lerobot/common/motors/dynamixel/dynamixel.py b/lerobot/common/motors/dynamixel/dynamixel.py
index e988d3a0..7e6232e8 100644
--- a/lerobot/common/motors/dynamixel/dynamixel.py
+++ b/lerobot/common/motors/dynamixel/dynamixel.py
@@ -100,14 +100,9 @@ class DynamixelMotorsBus(MotorsBus):
         # Note: No need to convert back into unsigned int, since this byte preprocessing
         # already handles it for us.
         if n_bytes == 1:
-            data = [
-                dxl.DXL_LOBYTE(dxl.DXL_LOWORD(value)),
-            ]
+            data = [value]
         elif n_bytes == 2:
-            data = [
-                dxl.DXL_LOBYTE(dxl.DXL_LOWORD(value)),
-                dxl.DXL_HIBYTE(dxl.DXL_LOWORD(value)),
-            ]
+            data = [dxl.DXL_LOBYTE(value), dxl.DXL_HIBYTE(value)]
         elif n_bytes == 4:
             data = [
                 dxl.DXL_LOBYTE(dxl.DXL_LOWORD(value)),
diff --git a/lerobot/common/motors/feetech/feetech.py b/lerobot/common/motors/feetech/feetech.py
index 3e8eb20a..23ea9884 100644
--- a/lerobot/common/motors/feetech/feetech.py
+++ b/lerobot/common/motors/feetech/feetech.py
@@ -88,14 +88,9 @@ class FeetechMotorsBus(MotorsBus):
         # Note: No need to convert back into unsigned int, since this byte preprocessing
         # already handles it for us.
         if n_bytes == 1:
-            data = [
-                scs.SCS_LOBYTE(scs.SCS_LOWORD(value)),
-            ]
+            data = [value]
         elif n_bytes == 2:
-            data = [
-                scs.SCS_LOBYTE(scs.SCS_LOWORD(value)),
-                scs.SCS_HIBYTE(scs.SCS_LOWORD(value)),
-            ]
+            data = [scs.SCS_LOBYTE(value), scs.SCS_HIBYTE(value)]
         elif n_bytes == 4:
             data = [
                 scs.SCS_LOBYTE(scs.SCS_LOWORD(value)),

From 5a57e6f4a733cdccf64c2aa1da9effa2ddc1f7b4 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sun, 23 Mar 2025 13:25:45 +0100
Subject: [PATCH 097/171] Rename read/write -> sync_read/write, refactor, add
 write

---
 lerobot/common/motors/dynamixel/dynamixel.py |   7 +-
 lerobot/common/motors/feetech/feetech.py     |   7 +-
 lerobot/common/motors/motors_bus.py          | 152 +++++++++++++------
 tests/motors/test_dynamixel.py               |  14 +-
 tests/motors/test_feetech.py                 |  14 +-
 5 files changed, 126 insertions(+), 68 deletions(-)

diff --git a/lerobot/common/motors/dynamixel/dynamixel.py b/lerobot/common/motors/dynamixel/dynamixel.py
index 7e6232e8..b0c9844f 100644
--- a/lerobot/common/motors/dynamixel/dynamixel.py
+++ b/lerobot/common/motors/dynamixel/dynamixel.py
@@ -55,8 +55,8 @@ class DynamixelMotorsBus(MotorsBus):
 
         self.port_handler = dxl.PortHandler(self.port)
         self.packet_handler = dxl.PacketHandler(PROTOCOL_VERSION)
-        self.reader = dxl.GroupSyncRead(self.port_handler, self.packet_handler, 0, 0)
-        self.writer = dxl.GroupSyncWrite(self.port_handler, self.packet_handler, 0, 0)
+        self.sync_reader = dxl.GroupSyncRead(self.port_handler, self.packet_handler, 0, 0)
+        self.sync_writer = dxl.GroupSyncWrite(self.port_handler, self.packet_handler, 0, 0)
 
     def broadcast_ping(
         self, num_retry: int = 0, raise_on_error: bool = False
@@ -82,6 +82,9 @@ class DynamixelMotorsBus(MotorsBus):
 
         return comm == dxl.COMM_SUCCESS
 
+    def _is_error(self, error: int) -> bool:
+        return error != 0x00
+
     @staticmethod
     def split_int_bytes(value: int, n_bytes: int) -> list[int]:
         # Validate input
diff --git a/lerobot/common/motors/feetech/feetech.py b/lerobot/common/motors/feetech/feetech.py
index 23ea9884..5d1fa69e 100644
--- a/lerobot/common/motors/feetech/feetech.py
+++ b/lerobot/common/motors/feetech/feetech.py
@@ -51,8 +51,8 @@ class FeetechMotorsBus(MotorsBus):
 
         self.port_handler = scs.PortHandler(self.port)
         self.packet_handler = scs.PacketHandler(PROTOCOL_VERSION)
-        self.reader = scs.GroupSyncRead(self.port_handler, self.packet_handler, 0, 0)
-        self.writer = scs.GroupSyncWrite(self.port_handler, self.packet_handler, 0, 0)
+        self.sync_reader = scs.GroupSyncRead(self.port_handler, self.packet_handler, 0, 0)
+        self.sync_writer = scs.GroupSyncWrite(self.port_handler, self.packet_handler, 0, 0)
 
     def broadcast_ping(self, num_retry: int | None = None):
         raise NotImplementedError  # TODO
@@ -70,6 +70,9 @@ class FeetechMotorsBus(MotorsBus):
 
         return comm == scs.COMM_SUCCESS
 
+    def _is_error(self, error: int) -> bool:
+        return error != 0x00
+
     @staticmethod
     def split_int_bytes(value: int, n_bytes: int) -> list[int]:
         # Validate input
diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py
index 6da8b36d..4558d56c 100644
--- a/lerobot/common/motors/motors_bus.py
+++ b/lerobot/common/motors/motors_bus.py
@@ -256,8 +256,8 @@ class MotorsBus(abc.ABC):
 
         self.port_handler: PortHandler
         self.packet_handler: PacketHandler
-        self.reader: GroupSyncRead
-        self.writer: GroupSyncWrite
+        self.sync_reader: GroupSyncRead
+        self.sync_writer: GroupSyncWrite
 
         self.calibration = None
 
@@ -347,7 +347,7 @@ class MotorsBus(abc.ABC):
         """
         try:
             # TODO(aliberts): use ping instead
-            return (self.ids == self.read("ID")).all()
+            return (self.ids == self.sync_read("ID")).all()
         except ConnectionError as e:
             logger.error(e)
             return False
@@ -395,6 +395,10 @@ class MotorsBus(abc.ABC):
     def _is_comm_success(self, comm: int) -> bool:
         pass
 
+    @abc.abstractmethod
+    def _is_error(self, error: int) -> bool:
+        pass
+
     @staticmethod
     @abc.abstractmethod
     def split_int_bytes(value: int, n_bytes: int) -> list[int]:
@@ -442,12 +446,12 @@ class MotorsBus(abc.ABC):
             raise TypeError(f"'{motor}' should be int, str.")
 
     @overload
-    def read(self, data_name: str, motors: None = ..., num_retry: int = ...) -> dict[str, Value]: ...
+    def sync_read(self, data_name: str, motors: None = ..., num_retry: int = ...) -> dict[str, Value]: ...
     @overload
-    def read(
+    def sync_read(
         self, data_name: str, motors: NameOrID | list[NameOrID], num_retry: int = ...
     ) -> dict[NameOrID, Value]: ...
-    def read(
+    def sync_read(
         self, data_name: str, motors: NameOrID | list[NameOrID] | None = None, num_retry: int = 0
     ) -> dict[NameOrID, Value]:
         if not self.is_connected:
@@ -466,17 +470,11 @@ class MotorsBus(abc.ABC):
             raise TypeError(motors)
 
         motor_ids = list(id_key_map)
-        if self._has_different_ctrl_tables:
-            models = [self.id_to_model(idx) for idx in motor_ids]
-            assert_same_address(self.model_ctrl_table, models, data_name)
 
-        model = self.id_to_model(next(iter(motor_ids)))
-        addr, n_bytes = self.model_ctrl_table[model][data_name]
-
-        comm, ids_values = self._read(motor_ids, addr, n_bytes, num_retry)
+        comm, ids_values = self._sync_read(data_name, motor_ids, num_retry)
         if not self._is_comm_success(comm):
             raise ConnectionError(
-                f"Failed to read {data_name} on port {self.port} for ids {motor_ids}:"
+                f"Failed to sync read '{data_name}' on {motor_ids=} after {num_retry + 1} tries."
                 f"{self.packet_handler.getTxRxResult(comm)}"
             )
 
@@ -485,40 +483,50 @@ class MotorsBus(abc.ABC):
 
         return {id_key_map[idx]: val for idx, val in ids_values.items()}
 
-    def _read(
-        self, motor_ids: list[str], address: int, n_bytes: int, num_retry: int = 0
+    def _sync_read(
+        self, data_name: str, motor_ids: list[str], num_retry: int = 0
     ) -> tuple[int, dict[int, int]]:
-        self.reader.clearParam()
-        self.reader.start_address = address
-        self.reader.data_length = n_bytes
+        if self._has_different_ctrl_tables:
+            models = [self.id_to_model(idx) for idx in motor_ids]
+            assert_same_address(self.model_ctrl_table, models, data_name)
+
+        model = self.id_to_model(next(iter(motor_ids)))
+        addr, n_bytes = self.model_ctrl_table[model][data_name]
+        self._setup_sync_reader(motor_ids, addr, n_bytes)
 
         # FIXME(aliberts, pkooij): We should probably not have to do this.
         # Let's try to see if we can do with better comm status handling instead.
         # self.port_handler.ser.reset_output_buffer()
         # self.port_handler.ser.reset_input_buffer()
 
-        for idx in motor_ids:
-            self.reader.addParam(idx)
-
         for n_try in range(1 + num_retry):
-            comm = self.reader.txRxPacket()
+            comm = self.sync_reader.txRxPacket()
             if self._is_comm_success(comm):
                 break
-            logger.debug(f"ids={list(motor_ids)} @{address} ({n_bytes} bytes) {n_try=} got {comm=}")
+            logger.debug(f"Failed to sync read '{data_name}' ({addr=} {n_bytes=}) on {motor_ids=} ({n_try=})")
+            logger.debug(self.packet_handler.getRxPacketError(comm))
 
-        values = {idx: self.reader.getData(idx, address, n_bytes) for idx in motor_ids}
+        values = {idx: self.sync_reader.getData(idx, addr, n_bytes) for idx in motor_ids}
         return comm, values
 
-    # TODO(aliberts, pkooij): Implementing something like this could get much faster read times.
-    # Note: this could be at the cost of increase latency between the moment the data is produced by the
-    # motors and the moment it is used by a policy
+    def _setup_sync_reader(self, motor_ids: list[str], addr: int, n_bytes: int) -> None:
+        self.sync_reader.clearParam()
+        self.sync_reader.start_address = addr
+        self.sync_reader.data_length = n_bytes
+        for idx in motor_ids:
+            self.sync_reader.addParam(idx)
+
+    # TODO(aliberts, pkooij): Implementing something like this could get even much faster read times if need be.
+    # Would have to handle the logic of checking if a packet has been sent previously though but doable.
+    # This could be at the cost of increase latency between the moment the data is produced by the motors and
+    # the moment it is used by a policy.
     # def _async_read(self, motor_ids: list[str], address: int, n_bytes: int):
     #     self.reader.rxPacket()
     #     self.reader.txPacket()
     #     for idx in motor_ids:
     #         value = self.reader.getData(idx, address, n_bytes)
 
-    def write(self, data_name: str, values: Value | dict[NameOrID, Value], num_retry: int = 0) -> None:
+    def sync_write(self, data_name: str, values: Value | dict[NameOrID, Value], num_retry: int = 0) -> None:
         if not self.is_connected:
             raise DeviceNotConnectedError(
                 f"{self.__class__.__name__}('{self.port}') is not connected. You need to run `{self.__class__.__name__}.connect()`."
@@ -531,40 +539,84 @@ class MotorsBus(abc.ABC):
         else:
             raise ValueError(f"'values' is expected to be a single value or a dict. Got {values}")
 
+        if data_name in self.calibration_required and self.calibration is not None:
+            ids_values = self.uncalibrate_values(ids_values)
+
+        comm = self._sync_write(data_name, ids_values, num_retry)
+        if not self._is_comm_success(comm):
+            raise ConnectionError(
+                f"Failed to sync write '{data_name}' with {ids_values=} after {num_retry + 1} tries."
+                f"\n{self.packet_handler.getTxRxResult(comm)}"
+            )
+
+    def _sync_write(self, data_name: str, ids_values: dict[int, int], num_retry: int = 0) -> int:
         if self._has_different_ctrl_tables:
             models = [self.id_to_model(idx) for idx in ids_values]
             assert_same_address(self.model_ctrl_table, models, data_name)
 
-        if data_name in self.calibration_required and self.calibration is not None:
-            ids_values = self.uncalibrate_values(ids_values)
-
         model = self.id_to_model(next(iter(ids_values)))
         addr, n_bytes = self.model_ctrl_table[model][data_name]
-
-        comm = self._write(ids_values, addr, n_bytes, num_retry)
-        if not self._is_comm_success(comm):
-            raise ConnectionError(
-                f"Failed to write {data_name} on port {self.port} for ids {list(ids_values)}:"
-                f"{self.packet_handler.getTxRxResult(comm)}"
-            )
-
-    def _write(self, ids_values: dict[int, int], address: int, n_bytes: int, num_retry: int = 0) -> int:
-        self.writer.clearParam()
-        self.writer.start_address = address
-        self.writer.data_length = n_bytes
-
-        for idx, value in ids_values.items():
-            data = self.split_int_bytes(value, n_bytes)
-            self.writer.addParam(idx, data)
+        self._setup_sync_writer(ids_values, addr, n_bytes)
 
         for n_try in range(1 + num_retry):
-            comm = self.writer.txPacket()
+            comm = self.sync_writer.txPacket()
             if self._is_comm_success(comm):
                 break
-            logger.debug(f"ids={list(ids_values)} @{address} ({n_bytes} bytes) {n_try=} got {comm=}")
+            logger.debug(
+                f"Failed to sync write '{data_name}' ({addr=} {n_bytes=}) with {ids_values=} ({n_try=})"
+            )
+            logger.debug(self.packet_handler.getRxPacketError(comm))
 
         return comm
 
+    def _setup_sync_writer(self, ids_values: dict[int, int], addr: int, n_bytes: int) -> None:
+        self.sync_writer.clearParam()
+        self.sync_writer.start_address = addr
+        self.sync_writer.data_length = n_bytes
+        for idx, value in ids_values.items():
+            data = self.split_int_bytes(value, n_bytes)
+            self.sync_writer.addParam(idx, data)
+
+    def write(self, data_name: str, motor: NameOrID, value: Value, num_retry: int = 0) -> None:
+        if not self.is_connected:
+            raise DeviceNotConnectedError(
+                f"{self.__class__.__name__}('{self.port}') is not connected. You need to run `{self.__class__.__name__}.connect()`."
+            )
+
+        idx = self.get_motor_id(motor)
+
+        if data_name in self.calibration_required and self.calibration is not None:
+            id_value = self.uncalibrate_values({idx: value})
+            value = id_value[idx]
+
+        comm, error = self._write(data_name, idx, value, num_retry)
+        if not self._is_comm_success(comm):
+            raise ConnectionError(
+                f"Failed to write '{data_name}' on {idx=} with '{value}' after {num_retry + 1} tries."
+                f"\n{self.packet_handler.getTxRxResult(comm)}"
+            )
+        elif self._is_error(error):
+            raise RuntimeError(
+                f"Failed to write '{data_name}' on {idx=} with '{value}' after {num_retry + 1} tries."
+                f"\n{self.packet_handler.getRxPacketError(error)}"
+            )
+
+    def _write(self, data_name: str, motor_id: int, value: int, num_retry: int = 0) -> tuple[int, int]:
+        model = self.id_to_model(motor_id)
+        addr, n_bytes = self.model_ctrl_table[model][data_name]
+        data = self.split_int_bytes(value, n_bytes)
+
+        for n_try in range(1 + num_retry):
+            comm, error = self.packet_handler.writeTxRx(self.port_handler, motor_id, addr, n_bytes, data)
+            if self._is_comm_success(comm):
+                break
+            logger.debug(
+                f"Failed to write '{data_name}' ({addr=} {n_bytes=}) on {motor_id=} with '{value}' ({n_try=})"
+            )
+            logger.debug(self.packet_handler.getRxPacketError(comm))
+
+        return comm, error
+
     def disconnect(self) -> None:
         if not self.is_connected:
             raise DeviceNotConnectedError(
diff --git a/tests/motors/test_dynamixel.py b/tests/motors/test_dynamixel.py
index 688a7367..c189e243 100644
--- a/tests/motors/test_dynamixel.py
+++ b/tests/motors/test_dynamixel.py
@@ -156,7 +156,7 @@ def test_read_all_motors(motors, mock_motors, dummy_motors):
     )
     motors_bus.connect()
 
-    positions_read = motors_bus.read("Present_Position", motors=motors)
+    positions_read = motors_bus.sync_read("Present_Position", motors=motors)
 
     motors = ["dummy_1", "dummy_2", "dummy_3"] if motors is None else motors
     assert mock_motors.stubs[stub_name].called
@@ -180,7 +180,7 @@ def test_read_single_motor_by_name(idx, pos, mock_motors, dummy_motors):
     )
     motors_bus.connect()
 
-    pos_dict = motors_bus.read("Present_Position", f"dummy_{idx}")
+    pos_dict = motors_bus.sync_read("Present_Position", f"dummy_{idx}")
 
     assert mock_motors.stubs[stub_name].called
     assert pos_dict == {f"dummy_{idx}": pos}
@@ -203,7 +203,7 @@ def test_read_single_motor_by_id(idx, pos, mock_motors, dummy_motors):
     )
     motors_bus.connect()
 
-    pos_dict = motors_bus.read("Present_Position", idx)
+    pos_dict = motors_bus.sync_read("Present_Position", idx)
 
     assert mock_motors.stubs[stub_name].called
     assert pos_dict == {idx: pos}
@@ -230,11 +230,11 @@ def test_read_num_retry(num_retry, num_invalid_try, pos, mock_motors, dummy_moto
     motors_bus.connect()
 
     if num_retry >= num_invalid_try:
-        pos_dict = motors_bus.read("Present_Position", 1, num_retry=num_retry)
+        pos_dict = motors_bus.sync_read("Present_Position", 1, num_retry=num_retry)
         assert pos_dict == {1: pos}
     else:
         with pytest.raises(ConnectionError):
-            _ = motors_bus.read("Present_Position", 1, num_retry=num_retry)
+            _ = motors_bus.sync_read("Present_Position", 1, num_retry=num_retry)
 
     expected_calls = min(1 + num_retry, 1 + num_invalid_try)
     assert mock_motors.stubs[stub_name].calls == expected_calls
@@ -263,7 +263,7 @@ def test_write_all_motors(motors, mock_motors, dummy_motors):
     motors_bus.connect()
 
     values = dict(zip(motors, goal_positions.values(), strict=True))
-    motors_bus.write("Goal_Position", values)
+    motors_bus.sync_write("Goal_Position", values)
 
     assert mock_motors.stubs[stub_name].wait_called()
 
@@ -284,6 +284,6 @@ def test_write_all_motors_single_value(data_name, value, mock_motors, dummy_moto
     )
     motors_bus.connect()
 
-    motors_bus.write(data_name, value)
+    motors_bus.sync_write(data_name, value)
 
     assert mock_motors.stubs[stub_name].wait_called()
diff --git a/tests/motors/test_feetech.py b/tests/motors/test_feetech.py
index cb9dcda8..ac80f221 100644
--- a/tests/motors/test_feetech.py
+++ b/tests/motors/test_feetech.py
@@ -158,7 +158,7 @@ def test_read_all_motors(motors, mock_motors, dummy_motors):
     )
     motors_bus.connect()
 
-    positions_read = motors_bus.read("Present_Position", motors=motors)
+    positions_read = motors_bus.sync_read("Present_Position", motors=motors)
 
     motors = ["dummy_1", "dummy_2", "dummy_3"] if motors is None else motors
     assert mock_motors.stubs[stub_name].called
@@ -182,7 +182,7 @@ def test_read_single_motor_by_name(idx, pos, mock_motors, dummy_motors):
     )
     motors_bus.connect()
 
-    pos_dict = motors_bus.read("Present_Position", f"dummy_{idx}")
+    pos_dict = motors_bus.sync_read("Present_Position", f"dummy_{idx}")
 
     assert mock_motors.stubs[stub_name].called
     assert pos_dict == {f"dummy_{idx}": pos}
@@ -205,7 +205,7 @@ def test_read_single_motor_by_id(idx, pos, mock_motors, dummy_motors):
     )
     motors_bus.connect()
 
-    pos_dict = motors_bus.read("Present_Position", idx)
+    pos_dict = motors_bus.sync_read("Present_Position", idx)
 
     assert mock_motors.stubs[stub_name].called
     assert pos_dict == {idx: pos}
@@ -232,11 +232,11 @@ def test_read_num_retry(num_retry, num_invalid_try, pos, mock_motors, dummy_moto
     motors_bus.connect()
 
     if num_retry >= num_invalid_try:
-        pos_dict = motors_bus.read("Present_Position", 1, num_retry=num_retry)
+        pos_dict = motors_bus.sync_read("Present_Position", 1, num_retry=num_retry)
         assert pos_dict == {1: pos}
     else:
         with pytest.raises(ConnectionError):
-            _ = motors_bus.read("Present_Position", 1, num_retry=num_retry)
+            _ = motors_bus.sync_read("Present_Position", 1, num_retry=num_retry)
 
     expected_calls = min(1 + num_retry, 1 + num_invalid_try)
     assert mock_motors.stubs[stub_name].calls == expected_calls
@@ -265,7 +265,7 @@ def test_write_all_motors(motors, mock_motors, dummy_motors):
     motors_bus.connect()
 
     values = dict(zip(motors, goal_positions.values(), strict=True))
-    motors_bus.write("Goal_Position", values)
+    motors_bus.sync_write("Goal_Position", values)
 
     assert mock_motors.stubs[stub_name].wait_called()
 
@@ -286,6 +286,6 @@ def test_write_all_motors_single_value(data_name, value, mock_motors, dummy_moto
     )
     motors_bus.connect()
 
-    motors_bus.write(data_name, value)
+    motors_bus.sync_write(data_name, value)
 
     assert mock_motors.stubs[stub_name].wait_called()

From c9ca9e43162d3cb3619a380019b2db857bc922ee Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sun, 23 Mar 2025 13:32:08 +0100
Subject: [PATCH 098/171] Rename tests

---
 tests/motors/test_dynamixel.py | 12 ++++++------
 tests/motors/test_feetech.py   | 12 ++++++------
 2 files changed, 12 insertions(+), 12 deletions(-)

diff --git a/tests/motors/test_dynamixel.py b/tests/motors/test_dynamixel.py
index c189e243..271e494a 100644
--- a/tests/motors/test_dynamixel.py
+++ b/tests/motors/test_dynamixel.py
@@ -143,7 +143,7 @@ def test_broadcast_ping(mock_motors, dummy_motors):
     ],
     ids=["None", "by ids", "by names", "mixed"],
 )
-def test_read_all_motors(motors, mock_motors, dummy_motors):
+def test_sync_read_all_motors(motors, mock_motors, dummy_motors):
     expected_positions = {
         1: 1337,
         2: 42,
@@ -171,7 +171,7 @@ def test_read_all_motors(motors, mock_motors, dummy_motors):
         [3, 4016],
     ],
 )
-def test_read_single_motor_by_name(idx, pos, mock_motors, dummy_motors):
+def test_sync_read_single_motor_by_name(idx, pos, mock_motors, dummy_motors):
     expected_position = {idx: pos}
     stub_name = mock_motors.build_sync_read_stub("Present_Position", expected_position)
     motors_bus = DynamixelMotorsBus(
@@ -194,7 +194,7 @@ def test_read_single_motor_by_name(idx, pos, mock_motors, dummy_motors):
         [3, 4016],
     ],
 )
-def test_read_single_motor_by_id(idx, pos, mock_motors, dummy_motors):
+def test_sync_read_single_motor_by_id(idx, pos, mock_motors, dummy_motors):
     expected_position = {idx: pos}
     stub_name = mock_motors.build_sync_read_stub("Present_Position", expected_position)
     motors_bus = DynamixelMotorsBus(
@@ -218,7 +218,7 @@ def test_read_single_motor_by_id(idx, pos, mock_motors, dummy_motors):
         [2, 1, 999],
     ],
 )
-def test_read_num_retry(num_retry, num_invalid_try, pos, mock_motors, dummy_motors):
+def test_sync_read_num_retry(num_retry, num_invalid_try, pos, mock_motors, dummy_motors):
     expected_position = {1: pos}
     stub_name = mock_motors.build_sync_read_stub(
         "Present_Position", expected_position, num_invalid_try=num_invalid_try
@@ -249,7 +249,7 @@ def test_read_num_retry(num_retry, num_invalid_try, pos, mock_motors, dummy_moto
     ],
     ids=["by ids", "by names", "mixed"],
 )
-def test_write_all_motors(motors, mock_motors, dummy_motors):
+def test_sync_write_all_motors(motors, mock_motors, dummy_motors):
     goal_positions = {
         1: 1337,
         2: 42,
@@ -275,7 +275,7 @@ def test_write_all_motors(motors, mock_motors, dummy_motors):
         ["Torque_Enable", 1],
     ],
 )
-def test_write_all_motors_single_value(data_name, value, mock_motors, dummy_motors):
+def test_sync_write_all_motors_single_value(data_name, value, mock_motors, dummy_motors):
     values = {m.id: value for m in dummy_motors.values()}
     stub_name = mock_motors.build_sync_write_stub(data_name, values)
     motors_bus = DynamixelMotorsBus(
diff --git a/tests/motors/test_feetech.py b/tests/motors/test_feetech.py
index ac80f221..db2fa2a8 100644
--- a/tests/motors/test_feetech.py
+++ b/tests/motors/test_feetech.py
@@ -145,7 +145,7 @@ def test_broadcast_ping(mock_motors, dummy_motors):
     ],
     ids=["None", "by ids", "by names", "mixed"],
 )
-def test_read_all_motors(motors, mock_motors, dummy_motors):
+def test_sync_read_all_motors(motors, mock_motors, dummy_motors):
     expected_positions = {
         1: 1337,
         2: 42,
@@ -173,7 +173,7 @@ def test_read_all_motors(motors, mock_motors, dummy_motors):
         [3, 4016],
     ],
 )
-def test_read_single_motor_by_name(idx, pos, mock_motors, dummy_motors):
+def test_sync_read_single_motor_by_name(idx, pos, mock_motors, dummy_motors):
     expected_position = {idx: pos}
     stub_name = mock_motors.build_sync_read_stub("Present_Position", expected_position)
     motors_bus = FeetechMotorsBus(
@@ -196,7 +196,7 @@ def test_read_single_motor_by_name(idx, pos, mock_motors, dummy_motors):
         [3, 4016],
     ],
 )
-def test_read_single_motor_by_id(idx, pos, mock_motors, dummy_motors):
+def test_sync_read_single_motor_by_id(idx, pos, mock_motors, dummy_motors):
     expected_position = {idx: pos}
     stub_name = mock_motors.build_sync_read_stub("Present_Position", expected_position)
     motors_bus = FeetechMotorsBus(
@@ -220,7 +220,7 @@ def test_read_single_motor_by_id(idx, pos, mock_motors, dummy_motors):
         [2, 1, 999],
     ],
 )
-def test_read_num_retry(num_retry, num_invalid_try, pos, mock_motors, dummy_motors):
+def test_sync_read_num_retry(num_retry, num_invalid_try, pos, mock_motors, dummy_motors):
     expected_position = {1: pos}
     stub_name = mock_motors.build_sync_read_stub(
         "Present_Position", expected_position, num_invalid_try=num_invalid_try
@@ -251,7 +251,7 @@ def test_read_num_retry(num_retry, num_invalid_try, pos, mock_motors, dummy_moto
     ],
     ids=["by ids", "by names", "mixed"],
 )
-def test_write_all_motors(motors, mock_motors, dummy_motors):
+def test_sync_write_all_motors(motors, mock_motors, dummy_motors):
     goal_positions = {
         1: 1337,
         2: 42,
@@ -277,7 +277,7 @@ def test_write_all_motors(motors, mock_motors, dummy_motors):
         ["Torque_Enable", 1],
     ],
 )
-def test_write_all_motors_single_value(data_name, value, mock_motors, dummy_motors):
+def test_sync_write_all_motors_single_value(data_name, value, mock_motors, dummy_motors):
     values = {m.id: value for m in dummy_motors.values()}
     stub_name = mock_motors.build_sync_write_stub(data_name, values)
     motors_bus = FeetechMotorsBus(

From 9f46a3d8f9b5d6660ed217eb9427e4c81e99cfdd Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sun, 23 Mar 2025 16:11:24 +0100
Subject: [PATCH 099/171] Refactor dxl tests by functionality

---
 tests/motors/test_dynamixel.py | 262 +++++++++++++++++++++++----------
 1 file changed, 186 insertions(+), 76 deletions(-)

diff --git a/tests/motors/test_dynamixel.py b/tests/motors/test_dynamixel.py
index 271e494a..5b58f570 100644
--- a/tests/motors/test_dynamixel.py
+++ b/tests/motors/test_dynamixel.py
@@ -95,9 +95,9 @@ def test_abc_implementation(dummy_motors):
 @pytest.mark.parametrize(
     "idx, model_nb",
     [
-        [1, 1190],
-        [2, 1200],
-        [3, 1120],
+        (1, 1190),
+        (2, 1200),
+        (3, 1120),
     ],
 )
 def test_ping(idx, model_nb, mock_motors, dummy_motors):
@@ -133,22 +133,61 @@ def test_broadcast_ping(mock_motors, dummy_motors):
     assert mock_motors.stubs[stub_name].called
 
 
-@pytest.mark.parametrize(
-    "motors",
-    [
-        None,
-        [1, 2, 3],
-        ["dummy_1", "dummy_2", "dummy_3"],
-        [1, "dummy_2", 3],
-    ],
-    ids=["None", "by ids", "by names", "mixed"],
-)
-def test_sync_read_all_motors(motors, mock_motors, dummy_motors):
+def test_sync_read_none(mock_motors, dummy_motors):
     expected_positions = {
-        1: 1337,
-        2: 42,
-        3: 4016,
+        "dummy_1": 1337,
+        "dummy_2": 42,
+        "dummy_3": 4016,
     }
+    ids_values = dict(zip([1, 2, 3], expected_positions.values(), strict=True))
+    stub_name = mock_motors.build_sync_read_stub("Present_Position", ids_values)
+    motors_bus = DynamixelMotorsBus(
+        port=mock_motors.port,
+        motors=dummy_motors,
+    )
+    motors_bus.connect()
+
+    positions_read = motors_bus.sync_read("Present_Position")
+
+    assert mock_motors.stubs[stub_name].called
+    assert positions_read == expected_positions
+
+
+@pytest.mark.parametrize(
+    "dxl_id, position",
+    [
+        (1, 1337),
+        (2, 42),
+        (3, 4016),
+    ],
+)
+def test_sync_read_by_id(dxl_id, position, mock_motors, dummy_motors):
+    expected_position = {dxl_id: position}
+    stub_name = mock_motors.build_sync_read_stub("Present_Position", expected_position)
+    motors_bus = DynamixelMotorsBus(
+        port=mock_motors.port,
+        motors=dummy_motors,
+    )
+    motors_bus.connect()
+
+    positions_read = motors_bus.sync_read("Present_Position", dxl_id)
+
+    assert mock_motors.stubs[stub_name].called
+    assert positions_read == expected_position
+
+
+@pytest.mark.parametrize(
+    "ids, positions",
+    [
+        ([1],       [1337]),
+        ([1, 2],    [1337, 42]),
+        ([1, 2, 3], [1337, 42, 4016]),
+    ],
+    ids=["1 motor", "2 motors", "3 motors"],
+)  # fmt: skip
+def test_sync_read_by_ids(ids, positions, mock_motors, dummy_motors):
+    assert len(ids) == len(positions)
+    expected_positions = dict(zip(ids, positions, strict=True))
     stub_name = mock_motors.build_sync_read_stub("Present_Position", expected_positions)
     motors_bus = DynamixelMotorsBus(
         port=mock_motors.port,
@@ -156,66 +195,69 @@ def test_sync_read_all_motors(motors, mock_motors, dummy_motors):
     )
     motors_bus.connect()
 
-    positions_read = motors_bus.sync_read("Present_Position", motors=motors)
+    positions_read = motors_bus.sync_read("Present_Position", ids)
 
-    motors = ["dummy_1", "dummy_2", "dummy_3"] if motors is None else motors
     assert mock_motors.stubs[stub_name].called
-    assert positions_read == dict(zip(motors, expected_positions.values(), strict=True))
+    assert positions_read == expected_positions
 
 
 @pytest.mark.parametrize(
-    "idx, pos",
+    "id_, position",
     [
-        [1, 1337],
-        [2, 42],
-        [3, 4016],
+        (1, 1337),
+        (2, 42),
+        (3, 4016),
     ],
 )
-def test_sync_read_single_motor_by_name(idx, pos, mock_motors, dummy_motors):
-    expected_position = {idx: pos}
-    stub_name = mock_motors.build_sync_read_stub("Present_Position", expected_position)
+def test_sync_read_by_name(id_, position, mock_motors, dummy_motors):
+    expected_position = {f"dummy_{id_}": position}
+    stub_name = mock_motors.build_sync_read_stub("Present_Position", {id_: position})
     motors_bus = DynamixelMotorsBus(
         port=mock_motors.port,
         motors=dummy_motors,
     )
     motors_bus.connect()
 
-    pos_dict = motors_bus.sync_read("Present_Position", f"dummy_{idx}")
+    positions_read = motors_bus.sync_read("Present_Position", f"dummy_{id_}")
 
     assert mock_motors.stubs[stub_name].called
-    assert pos_dict == {f"dummy_{idx}": pos}
+    assert positions_read == expected_position
 
 
 @pytest.mark.parametrize(
-    "idx, pos",
+    "ids, positions",
     [
-        [1, 1337],
-        [2, 42],
-        [3, 4016],
+        ([1],       [1337]),
+        ([1, 2],    [1337, 42]),
+        ([1, 2, 3], [1337, 42, 4016]),
     ],
-)
-def test_sync_read_single_motor_by_id(idx, pos, mock_motors, dummy_motors):
-    expected_position = {idx: pos}
-    stub_name = mock_motors.build_sync_read_stub("Present_Position", expected_position)
+    ids=["1 motor", "2 motors", "3 motors"],
+)  # fmt: skip
+def test_sync_read_by_names(ids, positions, mock_motors, dummy_motors):
+    assert len(ids) == len(positions)
+    names = [f"dummy_{dxl_id}" for dxl_id in ids]
+    expected_positions = dict(zip(names, positions, strict=True))
+    ids_values = dict(zip(ids, positions, strict=True))
+    stub_name = mock_motors.build_sync_read_stub("Present_Position", ids_values)
     motors_bus = DynamixelMotorsBus(
         port=mock_motors.port,
         motors=dummy_motors,
     )
     motors_bus.connect()
 
-    pos_dict = motors_bus.sync_read("Present_Position", idx)
+    positions_read = motors_bus.sync_read("Present_Position", names)
 
     assert mock_motors.stubs[stub_name].called
-    assert pos_dict == {idx: pos}
+    assert positions_read == expected_positions
 
 
 @pytest.mark.parametrize(
     "num_retry, num_invalid_try, pos",
     [
-        [0, 2, 1337],
-        [2, 3, 42],
-        [3, 2, 4016],
-        [2, 1, 999],
+        (0, 2, 1337),
+        (2, 3, 42),
+        (3, 2, 4016),
+        (2, 1, 999),
     ],
 )
 def test_sync_read_num_retry(num_retry, num_invalid_try, pos, mock_motors, dummy_motors):
@@ -240,44 +282,18 @@ def test_sync_read_num_retry(num_retry, num_invalid_try, pos, mock_motors, dummy
     assert mock_motors.stubs[stub_name].calls == expected_calls
 
 
-@pytest.mark.parametrize(
-    "motors",
-    [
-        [1, 2, 3],
-        ["dummy_1", "dummy_2", "dummy_3"],
-        [1, "dummy_2", 3],
-    ],
-    ids=["by ids", "by names", "mixed"],
-)
-def test_sync_write_all_motors(motors, mock_motors, dummy_motors):
-    goal_positions = {
-        1: 1337,
-        2: 42,
-        3: 4016,
-    }
-    stub_name = mock_motors.build_sync_write_stub("Goal_Position", goal_positions)
-    motors_bus = DynamixelMotorsBus(
-        port=mock_motors.port,
-        motors=dummy_motors,
-    )
-    motors_bus.connect()
-
-    values = dict(zip(motors, goal_positions.values(), strict=True))
-    motors_bus.sync_write("Goal_Position", values)
-
-    assert mock_motors.stubs[stub_name].wait_called()
-
-
 @pytest.mark.parametrize(
     "data_name, value",
     [
-        ["Torque_Enable", 0],
-        ["Torque_Enable", 1],
+        ("Torque_Enable", 0),
+        ("Torque_Enable", 1),
+        ("Goal_Position", 1337),
+        ("Goal_Position", 42),
     ],
 )
-def test_sync_write_all_motors_single_value(data_name, value, mock_motors, dummy_motors):
-    values = {m.id: value for m in dummy_motors.values()}
-    stub_name = mock_motors.build_sync_write_stub(data_name, values)
+def test_sync_write_single_value(data_name, value, mock_motors, dummy_motors):
+    ids_values = {m.id: value for m in dummy_motors.values()}
+    stub_name = mock_motors.build_sync_write_stub(data_name, ids_values)
     motors_bus = DynamixelMotorsBus(
         port=mock_motors.port,
         motors=dummy_motors,
@@ -287,3 +303,97 @@ def test_sync_write_all_motors_single_value(data_name, value, mock_motors, dummy
     motors_bus.sync_write(data_name, value)
 
     assert mock_motors.stubs[stub_name].wait_called()
+
+
+@pytest.mark.parametrize(
+    "id_, position",
+    [
+        (1, 1337),
+        (2, 42),
+        (3, 4016),
+    ],
+)
+def test_sync_write_by_id(id_, position, mock_motors, dummy_motors):
+    value = {id_: position}
+    stub_name = mock_motors.build_sync_write_stub("Goal_Position", value)
+    motors_bus = DynamixelMotorsBus(
+        port=mock_motors.port,
+        motors=dummy_motors,
+    )
+    motors_bus.connect()
+
+    motors_bus.sync_write("Goal_Position", value)
+
+    assert mock_motors.stubs[stub_name].wait_called()
+
+
+@pytest.mark.parametrize(
+    "ids, positions",
+    [
+        ([1],       [1337]),
+        ([1, 2],    [1337, 42]),
+        ([1, 2, 3], [1337, 42, 4016]),
+    ],
+    ids=["1 motor", "2 motors", "3 motors"],
+)  # fmt: skip
+def test_sync_write_by_ids(ids, positions, mock_motors, dummy_motors):
+    assert len(ids) == len(positions)
+    values = dict(zip(ids, positions, strict=True))
+    stub_name = mock_motors.build_sync_write_stub("Goal_Position", values)
+    motors_bus = DynamixelMotorsBus(
+        port=mock_motors.port,
+        motors=dummy_motors,
+    )
+    motors_bus.connect()
+
+    motors_bus.sync_write("Goal_Position", values)
+
+    assert mock_motors.stubs[stub_name].wait_called()
+
+
+@pytest.mark.parametrize(
+    "id_, position",
+    [
+        (1, 1337),
+        (2, 42),
+        (3, 4016),
+    ],
+)
+def test_sync_write_by_name(id_, position, mock_motors, dummy_motors):
+    id_value = {id_: position}
+    stub_name = mock_motors.build_sync_write_stub("Goal_Position", id_value)
+    motors_bus = DynamixelMotorsBus(
+        port=mock_motors.port,
+        motors=dummy_motors,
+    )
+    motors_bus.connect()
+
+    write_value = {f"dummy_{id_}": position}
+    motors_bus.sync_write("Goal_Position", write_value)
+
+    assert mock_motors.stubs[stub_name].wait_called()
+
+
+@pytest.mark.parametrize(
+    "ids, positions",
+    [
+        ([1],       [1337]),
+        ([1, 2],    [1337, 42]),
+        ([1, 2, 3], [1337, 42, 4016]),
+    ],
+    ids=["1 motor", "2 motors", "3 motors"],
+)  # fmt: skip
+def test_sync_write_by_names(ids, positions, mock_motors, dummy_motors):
+    assert len(ids) == len(positions)
+    ids_values = dict(zip(ids, positions, strict=True))
+    stub_name = mock_motors.build_sync_write_stub("Goal_Position", ids_values)
+    motors_bus = DynamixelMotorsBus(
+        port=mock_motors.port,
+        motors=dummy_motors,
+    )
+    motors_bus.connect()
+
+    write_values = {f"dummy_{id_}": pos for id_, pos in ids_values.items()}
+    motors_bus.sync_write("Goal_Position", write_values)
+
+    assert mock_motors.stubs[stub_name].wait_called()

From 329d103453e3fe36d9cdbdc7e717cdd256f0429b Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sun, 23 Mar 2025 16:12:24 +0100
Subject: [PATCH 100/171] Add dxl write test

---
 tests/mocks/mock_dynamixel.py  | 54 +++++++++++++++++++++++++++++++---
 tests/motors/test_dynamixel.py | 44 +++++++++++++++++++++++++++
 2 files changed, 94 insertions(+), 4 deletions(-)

diff --git a/tests/mocks/mock_dynamixel.py b/tests/mocks/mock_dynamixel.py
index b75479d3..21668e17 100644
--- a/tests/mocks/mock_dynamixel.py
+++ b/tests/mocks/mock_dynamixel.py
@@ -294,6 +294,40 @@ class MockInstructionPacket(MockDynamixelPacketv2):
         length = len(ids_values) * (1 + data_length) + 7
         return cls.build(dxl_id=dxl.BROADCAST_ID, params=params, length=length, instruct_type="Sync_Write")
 
+    @classmethod
+    def write(
+        cls,
+        dxl_id: int,
+        value: int,
+        start_address: int,
+        data_length: int,
+    ) -> bytes:
+        """
+        Builds a "Write" instruction.
+        (from https://emanual.robotis.com/docs/en/dxl/protocol2/#write-0x03)
+
+        The parameters for Write (Protocol 2.0) are:
+            param[0]   = start_address L
+            param[1]   = start_address H
+            param[2]   = 1st Byte
+            param[3]   = 2nd Byte
+            ...
+            param[1+X] = X-th Byte
+
+        And 'length' = data_length + 5, where:
+            +1 is for instruction byte,
+            +2 is for the length bytes,
+            +2 is for the CRC at the end.
+        """
+        data = DynamixelMotorsBus.split_int_bytes(value, data_length)
+        params = [
+            dxl.DXL_LOBYTE(start_address),
+            dxl.DXL_HIBYTE(start_address),
+            *data,
+        ]
+        length = data_length + 5
+        return cls.build(dxl_id=dxl_id, params=params, length=length, instruct_type="Write")
+
 
 class MockStatusPacket(MockDynamixelPacketv2):
     """
@@ -458,7 +492,6 @@ class MockMotors(MockSerial):
         ping_request = MockInstructionPacket.ping(dxl_id)
         return_packet = MockStatusPacket.ping(dxl_id, model_nb, firm_ver)
         ping_response = self._build_send_fn(return_packet, num_invalid_try)
-
         stub_name = f"Ping_{dxl_id}"
         self.stub(
             name=stub_name,
@@ -474,16 +507,15 @@ class MockMotors(MockSerial):
         'data_name' supported:
             - Present_Position
         """
-        address, length = self.ctrl_table[data_name]
-        sync_read_request = MockInstructionPacket.sync_read(list(ids_values), address, length)
         if data_name != "Present_Position":
             raise NotImplementedError
 
+        address, length = self.ctrl_table[data_name]
+        sync_read_request = MockInstructionPacket.sync_read(list(ids_values), address, length)
         return_packets = b"".join(
             MockStatusPacket.present_position(idx, pos) for idx, pos in ids_values.items()
         )
         sync_read_response = self._build_send_fn(return_packets, num_invalid_try)
-
         stub_name = f"Sync_Read_{data_name}_" + "_".join([str(idx) for idx in ids_values])
         self.stub(
             name=stub_name,
@@ -505,6 +537,20 @@ class MockMotors(MockSerial):
         )
         return stub_name
 
+    def build_write_stub(
+        self, data_name: str, dxl_id: int, value: int, error: str = "Success", num_invalid_try: int = 0
+    ) -> str:
+        address, length = self.ctrl_table[data_name]
+        sync_read_request = MockInstructionPacket.write(dxl_id, value, address, length)
+        return_packet = MockStatusPacket.build(dxl_id, params=[], length=4, error=error)
+        stub_name = f"Write_{data_name}_{dxl_id}"
+        self.stub(
+            name=stub_name,
+            receive_bytes=sync_read_request,
+            send_fn=self._build_send_fn(return_packet, num_invalid_try),
+        )
+        return stub_name
+
     @staticmethod
     def _build_send_fn(packet: bytes, num_invalid_try: int = 0) -> Callable[[int], bytes]:
         def send_fn(_call_count: int) -> bytes:
diff --git a/tests/motors/test_dynamixel.py b/tests/motors/test_dynamixel.py
index 5b58f570..fee37b28 100644
--- a/tests/motors/test_dynamixel.py
+++ b/tests/motors/test_dynamixel.py
@@ -397,3 +397,47 @@ def test_sync_write_by_names(ids, positions, mock_motors, dummy_motors):
     motors_bus.sync_write("Goal_Position", write_values)
 
     assert mock_motors.stubs[stub_name].wait_called()
+
+
+@pytest.mark.parametrize(
+    "data_name, dxl_id, value",
+    [
+        ("Torque_Enable", 1, 0),
+        ("Torque_Enable", 1, 1),
+        ("Goal_Position", 2, 1337),
+        ("Goal_Position", 3, 42),
+    ],
+)
+def test_write_by_id(data_name, dxl_id, value, mock_motors, dummy_motors):
+    stub_name = mock_motors.build_write_stub(data_name, dxl_id, value)
+    motors_bus = DynamixelMotorsBus(
+        port=mock_motors.port,
+        motors=dummy_motors,
+    )
+    motors_bus.connect()
+
+    motors_bus.write(data_name, dxl_id, value)
+
+    assert mock_motors.stubs[stub_name].called
+
+
+@pytest.mark.parametrize(
+    "data_name, dxl_id, value",
+    [
+        ("Torque_Enable", 1, 0),
+        ("Torque_Enable", 1, 1),
+        ("Goal_Position", 2, 1337),
+        ("Goal_Position", 3, 42),
+    ],
+)
+def test_write_by_name(data_name, dxl_id, value, mock_motors, dummy_motors):
+    stub_name = mock_motors.build_write_stub(data_name, dxl_id, value)
+    motors_bus = DynamixelMotorsBus(
+        port=mock_motors.port,
+        motors=dummy_motors,
+    )
+    motors_bus.connect()
+
+    motors_bus.write(data_name, f"dummy_{dxl_id}", value)
+
+    assert mock_motors.stubs[stub_name].called

From d485dc1313e58a0409ca998b3898dcf5679876d5 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sun, 23 Mar 2025 16:15:53 +0100
Subject: [PATCH 101/171] Refactor _is_comm_success

---
 lerobot/common/motors/dynamixel/dynamixel.py | 5 ++---
 lerobot/common/motors/feetech/feetech.py     | 5 ++---
 2 files changed, 4 insertions(+), 6 deletions(-)

diff --git a/lerobot/common/motors/dynamixel/dynamixel.py b/lerobot/common/motors/dynamixel/dynamixel.py
index b0c9844f..5992ae56 100644
--- a/lerobot/common/motors/dynamixel/dynamixel.py
+++ b/lerobot/common/motors/dynamixel/dynamixel.py
@@ -57,6 +57,7 @@ class DynamixelMotorsBus(MotorsBus):
         self.packet_handler = dxl.PacketHandler(PROTOCOL_VERSION)
         self.sync_reader = dxl.GroupSyncRead(self.port_handler, self.packet_handler, 0, 0)
         self.sync_writer = dxl.GroupSyncWrite(self.port_handler, self.packet_handler, 0, 0)
+        self.__comm_success = dxl.COMM_SUCCESS
 
     def broadcast_ping(
         self, num_retry: int = 0, raise_on_error: bool = False
@@ -78,9 +79,7 @@ class DynamixelMotorsBus(MotorsBus):
         return ids_values
 
     def _is_comm_success(self, comm: int) -> bool:
-        import dynamixel_sdk as dxl
-
-        return comm == dxl.COMM_SUCCESS
+        return comm == self.__comm_success
 
     def _is_error(self, error: int) -> bool:
         return error != 0x00
diff --git a/lerobot/common/motors/feetech/feetech.py b/lerobot/common/motors/feetech/feetech.py
index 5d1fa69e..4c8dd4ed 100644
--- a/lerobot/common/motors/feetech/feetech.py
+++ b/lerobot/common/motors/feetech/feetech.py
@@ -53,6 +53,7 @@ class FeetechMotorsBus(MotorsBus):
         self.packet_handler = scs.PacketHandler(PROTOCOL_VERSION)
         self.sync_reader = scs.GroupSyncRead(self.port_handler, self.packet_handler, 0, 0)
         self.sync_writer = scs.GroupSyncWrite(self.port_handler, self.packet_handler, 0, 0)
+        self.__comm_success = scs.COMM_SUCCESS
 
     def broadcast_ping(self, num_retry: int | None = None):
         raise NotImplementedError  # TODO
@@ -66,9 +67,7 @@ class FeetechMotorsBus(MotorsBus):
         return ids_values
 
     def _is_comm_success(self, comm: int) -> bool:
-        import scservo_sdk as scs
-
-        return comm == scs.COMM_SUCCESS
+        return comm == self.__comm_success
 
     def _is_error(self, error: int) -> bool:
         return error != 0x00

From 3ceaee999df47f11e1c1a4192e935f339f75c549 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sun, 23 Mar 2025 16:25:12 +0100
Subject: [PATCH 102/171] Refactor feetech tests by functionality

---
 tests/motors/test_feetech.py | 262 +++++++++++++++++++++++++----------
 1 file changed, 186 insertions(+), 76 deletions(-)

diff --git a/tests/motors/test_feetech.py b/tests/motors/test_feetech.py
index db2fa2a8..7f917e92 100644
--- a/tests/motors/test_feetech.py
+++ b/tests/motors/test_feetech.py
@@ -96,9 +96,9 @@ def test_abc_implementation(dummy_motors):
 @pytest.mark.parametrize(
     "idx, model_nb",
     [
-        [1, 1190],
-        [2, 1200],
-        [3, 1120],
+        (1, 1190),
+        (2, 1200),
+        (3, 1120),
     ],
 )
 def test_ping(idx, model_nb, mock_motors, dummy_motors):
@@ -135,22 +135,61 @@ def test_broadcast_ping(mock_motors, dummy_motors):
     assert mock_motors.stubs[stub_name].called
 
 
-@pytest.mark.parametrize(
-    "motors",
-    [
-        None,
-        [1, 2, 3],
-        ["dummy_1", "dummy_2", "dummy_3"],
-        [1, "dummy_2", 3],
-    ],
-    ids=["None", "by ids", "by names", "mixed"],
-)
-def test_sync_read_all_motors(motors, mock_motors, dummy_motors):
+def test_sync_read_none(mock_motors, dummy_motors):
     expected_positions = {
-        1: 1337,
-        2: 42,
-        3: 4016,
+        "dummy_1": 1337,
+        "dummy_2": 42,
+        "dummy_3": 4016,
     }
+    ids_values = dict(zip([1, 2, 3], expected_positions.values(), strict=True))
+    stub_name = mock_motors.build_sync_read_stub("Present_Position", ids_values)
+    motors_bus = FeetechMotorsBus(
+        port=mock_motors.port,
+        motors=dummy_motors,
+    )
+    motors_bus.connect()
+
+    read_positions = motors_bus.sync_read("Present_Position")
+
+    assert mock_motors.stubs[stub_name].called
+    assert read_positions == expected_positions
+
+
+@pytest.mark.parametrize(
+    "id_, position",
+    [
+        (1, 1337),
+        (2, 42),
+        (3, 4016),
+    ],
+)
+def test_sync_read_by_id(id_, position, mock_motors, dummy_motors):
+    expected_position = {id_: position}
+    stub_name = mock_motors.build_sync_read_stub("Present_Position", expected_position)
+    motors_bus = FeetechMotorsBus(
+        port=mock_motors.port,
+        motors=dummy_motors,
+    )
+    motors_bus.connect()
+
+    read_position = motors_bus.sync_read("Present_Position", id_)
+
+    assert mock_motors.stubs[stub_name].called
+    assert read_position == expected_position
+
+
+@pytest.mark.parametrize(
+    "ids, positions",
+    [
+        ([1],       [1337]),
+        ([1, 2],    [1337, 42]),
+        ([1, 2, 3], [1337, 42, 4016]),
+    ],
+    ids=["1 motor", "2 motors", "3 motors"],
+)  # fmt: skip
+def test_sync_read_by_ids(ids, positions, mock_motors, dummy_motors):
+    assert len(ids) == len(positions)
+    expected_positions = dict(zip(ids, positions, strict=True))
     stub_name = mock_motors.build_sync_read_stub("Present_Position", expected_positions)
     motors_bus = FeetechMotorsBus(
         port=mock_motors.port,
@@ -158,66 +197,69 @@ def test_sync_read_all_motors(motors, mock_motors, dummy_motors):
     )
     motors_bus.connect()
 
-    positions_read = motors_bus.sync_read("Present_Position", motors=motors)
+    read_positions = motors_bus.sync_read("Present_Position", ids)
 
-    motors = ["dummy_1", "dummy_2", "dummy_3"] if motors is None else motors
     assert mock_motors.stubs[stub_name].called
-    assert positions_read == dict(zip(motors, expected_positions.values(), strict=True))
+    assert read_positions == expected_positions
 
 
 @pytest.mark.parametrize(
-    "idx, pos",
+    "id_, position",
     [
-        [1, 1337],
-        [2, 42],
-        [3, 4016],
+        (1, 1337),
+        (2, 42),
+        (3, 4016),
     ],
 )
-def test_sync_read_single_motor_by_name(idx, pos, mock_motors, dummy_motors):
-    expected_position = {idx: pos}
-    stub_name = mock_motors.build_sync_read_stub("Present_Position", expected_position)
+def test_sync_read_by_name(id_, position, mock_motors, dummy_motors):
+    expected_position = {f"dummy_{id_}": position}
+    stub_name = mock_motors.build_sync_read_stub("Present_Position", {id_: position})
     motors_bus = FeetechMotorsBus(
         port=mock_motors.port,
         motors=dummy_motors,
     )
     motors_bus.connect()
 
-    pos_dict = motors_bus.sync_read("Present_Position", f"dummy_{idx}")
+    read_position = motors_bus.sync_read("Present_Position", f"dummy_{id_}")
 
     assert mock_motors.stubs[stub_name].called
-    assert pos_dict == {f"dummy_{idx}": pos}
+    assert read_position == expected_position
 
 
 @pytest.mark.parametrize(
-    "idx, pos",
+    "ids, positions",
     [
-        [1, 1337],
-        [2, 42],
-        [3, 4016],
+        ([1],       [1337]),
+        ([1, 2],    [1337, 42]),
+        ([1, 2, 3], [1337, 42, 4016]),
     ],
-)
-def test_sync_read_single_motor_by_id(idx, pos, mock_motors, dummy_motors):
-    expected_position = {idx: pos}
-    stub_name = mock_motors.build_sync_read_stub("Present_Position", expected_position)
+    ids=["1 motor", "2 motors", "3 motors"],
+)  # fmt: skip
+def test_sync_read_by_names(ids, positions, mock_motors, dummy_motors):
+    assert len(ids) == len(positions)
+    names = [f"dummy_{dxl_id}" for dxl_id in ids]
+    expected_positions = dict(zip(names, positions, strict=True))
+    ids_values = dict(zip(ids, positions, strict=True))
+    stub_name = mock_motors.build_sync_read_stub("Present_Position", ids_values)
     motors_bus = FeetechMotorsBus(
         port=mock_motors.port,
         motors=dummy_motors,
     )
     motors_bus.connect()
 
-    pos_dict = motors_bus.sync_read("Present_Position", idx)
+    read_positions = motors_bus.sync_read("Present_Position", names)
 
     assert mock_motors.stubs[stub_name].called
-    assert pos_dict == {idx: pos}
+    assert read_positions == expected_positions
 
 
 @pytest.mark.parametrize(
     "num_retry, num_invalid_try, pos",
     [
-        [0, 2, 1337],
-        [2, 3, 42],
-        [3, 2, 4016],
-        [2, 1, 999],
+        (0, 2, 1337),
+        (2, 3, 42),
+        (3, 2, 4016),
+        (2, 1, 999),
     ],
 )
 def test_sync_read_num_retry(num_retry, num_invalid_try, pos, mock_motors, dummy_motors):
@@ -242,44 +284,18 @@ def test_sync_read_num_retry(num_retry, num_invalid_try, pos, mock_motors, dummy
     assert mock_motors.stubs[stub_name].calls == expected_calls
 
 
-@pytest.mark.parametrize(
-    "motors",
-    [
-        [1, 2, 3],
-        ["dummy_1", "dummy_2", "dummy_3"],
-        [1, "dummy_2", 3],
-    ],
-    ids=["by ids", "by names", "mixed"],
-)
-def test_sync_write_all_motors(motors, mock_motors, dummy_motors):
-    goal_positions = {
-        1: 1337,
-        2: 42,
-        3: 4016,
-    }
-    stub_name = mock_motors.build_sync_write_stub("Goal_Position", goal_positions)
-    motors_bus = FeetechMotorsBus(
-        port=mock_motors.port,
-        motors=dummy_motors,
-    )
-    motors_bus.connect()
-
-    values = dict(zip(motors, goal_positions.values(), strict=True))
-    motors_bus.sync_write("Goal_Position", values)
-
-    assert mock_motors.stubs[stub_name].wait_called()
-
-
 @pytest.mark.parametrize(
     "data_name, value",
     [
-        ["Torque_Enable", 0],
-        ["Torque_Enable", 1],
+        ("Torque_Enable", 0),
+        ("Torque_Enable", 1),
+        ("Goal_Position", 1337),
+        ("Goal_Position", 42),
     ],
 )
-def test_sync_write_all_motors_single_value(data_name, value, mock_motors, dummy_motors):
-    values = {m.id: value for m in dummy_motors.values()}
-    stub_name = mock_motors.build_sync_write_stub(data_name, values)
+def test_sync_write_single_value(data_name, value, mock_motors, dummy_motors):
+    ids_values = {m.id: value for m in dummy_motors.values()}
+    stub_name = mock_motors.build_sync_write_stub(data_name, ids_values)
     motors_bus = FeetechMotorsBus(
         port=mock_motors.port,
         motors=dummy_motors,
@@ -289,3 +305,97 @@ def test_sync_write_all_motors_single_value(data_name, value, mock_motors, dummy
     motors_bus.sync_write(data_name, value)
 
     assert mock_motors.stubs[stub_name].wait_called()
+
+
+@pytest.mark.parametrize(
+    "id_, position",
+    [
+        (1, 1337),
+        (2, 42),
+        (3, 4016),
+    ],
+)
+def test_sync_write_by_id(id_, position, mock_motors, dummy_motors):
+    value = {id_: position}
+    stub_name = mock_motors.build_sync_write_stub("Goal_Position", value)
+    motors_bus = FeetechMotorsBus(
+        port=mock_motors.port,
+        motors=dummy_motors,
+    )
+    motors_bus.connect()
+
+    motors_bus.sync_write("Goal_Position", value)
+
+    assert mock_motors.stubs[stub_name].wait_called()
+
+
+@pytest.mark.parametrize(
+    "ids, positions",
+    [
+        ([1],       [1337]),
+        ([1, 2],    [1337, 42]),
+        ([1, 2, 3], [1337, 42, 4016]),
+    ],
+    ids=["1 motor", "2 motors", "3 motors"],
+)  # fmt: skip
+def test_sync_write_by_ids(ids, positions, mock_motors, dummy_motors):
+    assert len(ids) == len(positions)
+    values = dict(zip(ids, positions, strict=True))
+    stub_name = mock_motors.build_sync_write_stub("Goal_Position", values)
+    motors_bus = FeetechMotorsBus(
+        port=mock_motors.port,
+        motors=dummy_motors,
+    )
+    motors_bus.connect()
+
+    motors_bus.sync_write("Goal_Position", values)
+
+    assert mock_motors.stubs[stub_name].wait_called()
+
+
+@pytest.mark.parametrize(
+    "id_, position",
+    [
+        (1, 1337),
+        (2, 42),
+        (3, 4016),
+    ],
+)
+def test_sync_write_by_name(id_, position, mock_motors, dummy_motors):
+    id_value = {id_: position}
+    stub_name = mock_motors.build_sync_write_stub("Goal_Position", id_value)
+    motors_bus = FeetechMotorsBus(
+        port=mock_motors.port,
+        motors=dummy_motors,
+    )
+    motors_bus.connect()
+
+    write_value = {f"dummy_{id_}": position}
+    motors_bus.sync_write("Goal_Position", write_value)
+
+    assert mock_motors.stubs[stub_name].wait_called()
+
+
+@pytest.mark.parametrize(
+    "ids, positions",
+    [
+        ([1],       [1337]),
+        ([1, 2],    [1337, 42]),
+        ([1, 2, 3], [1337, 42, 4016]),
+    ],
+    ids=["1 motor", "2 motors", "3 motors"],
+)  # fmt: skip
+def test_sync_write_by_names(ids, positions, mock_motors, dummy_motors):
+    assert len(ids) == len(positions)
+    ids_values = dict(zip(ids, positions, strict=True))
+    stub_name = mock_motors.build_sync_write_stub("Goal_Position", ids_values)
+    motors_bus = FeetechMotorsBus(
+        port=mock_motors.port,
+        motors=dummy_motors,
+    )
+    motors_bus.connect()
+
+    write_values = {f"dummy_{id_}": pos for id_, pos in ids_values.items()}
+    motors_bus.sync_write("Goal_Position", write_values)
+
+    assert mock_motors.stubs[stub_name].wait_called()

From a38bb15e79ff116537e5c14e46c20d9069ccbfaa Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sun, 23 Mar 2025 16:48:32 +0100
Subject: [PATCH 103/171] Add feetech write test

---
 tests/mocks/mock_feetech.py  | 49 +++++++++++++++++++++++++++++++++---
 tests/motors/test_feetech.py | 46 +++++++++++++++++++++++++++++++++
 2 files changed, 91 insertions(+), 4 deletions(-)

diff --git a/tests/mocks/mock_feetech.py b/tests/mocks/mock_feetech.py
index 44061094..f23dd6ee 100644
--- a/tests/mocks/mock_feetech.py
+++ b/tests/mocks/mock_feetech.py
@@ -155,6 +155,35 @@ class MockInstructionPacket(MockFeetechPacket):
         length = len(ids_values) * (1 + data_length) + 4
         return cls.build(scs_id=scs.BROADCAST_ID, params=params, length=length, instruct_type="Sync_Write")
 
+    @classmethod
+    def write(
+        cls,
+        scs_id: int,
+        value: int,
+        start_address: int,
+        data_length: int,
+    ) -> bytes:
+        """
+        Builds a "Write" instruction.
+
+        The parameters for Write (Protocol 2.0) are:
+            param[0]   = start_address L
+            param[1]   = start_address H
+            param[2]   = 1st Byte
+            param[3]   = 2nd Byte
+            ...
+            param[1+X] = X-th Byte
+
+        And 'length' = data_length + 5, where:
+            +1 is for instruction byte,
+            +2 is for the length bytes,
+            +2 is for the CRC at the end.
+        """
+        data = FeetechMotorsBus.split_int_bytes(value, data_length)
+        params = [start_address, *data]
+        length = data_length + 3
+        return cls.build(scs_id=scs_id, params=params, length=length, instruct_type="Write")
+
 
 class MockStatusPacket(MockFeetechPacket):
     """
@@ -317,7 +346,6 @@ class MockMotors(MockSerial):
         ping_request = MockInstructionPacket.ping(scs_id)
         return_packet = MockStatusPacket.ping(scs_id, model_nb, firm_ver)
         ping_response = self._build_send_fn(return_packet, num_invalid_try)
-
         stub_name = f"Ping_{scs_id}"
         self.stub(
             name=stub_name,
@@ -333,16 +361,15 @@ class MockMotors(MockSerial):
         'data_name' supported:
             - Present_Position
         """
-        address, length = self.ctrl_table[data_name]
-        sync_read_request = MockInstructionPacket.sync_read(list(ids_values), address, length)
         if data_name != "Present_Position":
             raise NotImplementedError
 
+        address, length = self.ctrl_table[data_name]
+        sync_read_request = MockInstructionPacket.sync_read(list(ids_values), address, length)
         return_packets = b"".join(
             MockStatusPacket.present_position(idx, pos) for idx, pos in ids_values.items()
         )
         sync_read_response = self._build_send_fn(return_packets, num_invalid_try)
-
         stub_name = f"Sync_Read_{data_name}_" + "_".join([str(idx) for idx in ids_values])
         self.stub(
             name=stub_name,
@@ -364,6 +391,20 @@ class MockMotors(MockSerial):
         )
         return stub_name
 
+    def build_write_stub(
+        self, data_name: str, scs_id: int, value: int, error: str = "Success", num_invalid_try: int = 0
+    ) -> str:
+        address, length = self.ctrl_table[data_name]
+        sync_read_request = MockInstructionPacket.write(scs_id, value, address, length)
+        return_packet = MockStatusPacket.build(scs_id, params=[], length=2, error=error)
+        stub_name = f"Write_{data_name}_{scs_id}"
+        self.stub(
+            name=stub_name,
+            receive_bytes=sync_read_request,
+            send_fn=self._build_send_fn(return_packet, num_invalid_try),
+        )
+        return stub_name
+
     @staticmethod
     def _build_send_fn(packet: bytes, num_invalid_try: int = 0) -> Callable[[int], bytes]:
         def send_fn(_call_count: int) -> bytes:
diff --git a/tests/motors/test_feetech.py b/tests/motors/test_feetech.py
index 7f917e92..8f3b4d04 100644
--- a/tests/motors/test_feetech.py
+++ b/tests/motors/test_feetech.py
@@ -399,3 +399,49 @@ def test_sync_write_by_names(ids, positions, mock_motors, dummy_motors):
     motors_bus.sync_write("Goal_Position", write_values)
 
     assert mock_motors.stubs[stub_name].wait_called()
+
+
+@pytest.mark.skip("TODO")
+@pytest.mark.parametrize(
+    "data_name, dxl_id, value",
+    [
+        ("Torque_Enable", 1, 0),
+        ("Torque_Enable", 1, 1),
+        ("Goal_Position", 2, 1337),
+        ("Goal_Position", 3, 42),
+    ],
+)
+def test_write_by_id(data_name, dxl_id, value, mock_motors, dummy_motors):
+    stub_name = mock_motors.build_write_stub(data_name, dxl_id, value)
+    motors_bus = FeetechMotorsBus(
+        port=mock_motors.port,
+        motors=dummy_motors,
+    )
+    motors_bus.connect()
+
+    motors_bus.write(data_name, dxl_id, value)
+
+    assert mock_motors.stubs[stub_name].called
+
+
+@pytest.mark.skip("TODO")
+@pytest.mark.parametrize(
+    "data_name, dxl_id, value",
+    [
+        ("Torque_Enable", 1, 0),
+        ("Torque_Enable", 1, 1),
+        ("Goal_Position", 2, 1337),
+        ("Goal_Position", 3, 42),
+    ],
+)
+def test_write_by_name(data_name, dxl_id, value, mock_motors, dummy_motors):
+    stub_name = mock_motors.build_write_stub(data_name, dxl_id, value)
+    motors_bus = FeetechMotorsBus(
+        port=mock_motors.port,
+        motors=dummy_motors,
+    )
+    motors_bus.connect()
+
+    motors_bus.write(data_name, f"dummy_{dxl_id}", value)
+
+    assert mock_motors.stubs[stub_name].called

From 57c97762e1ebb5081b877694847d0e8ff27f3dac Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sun, 23 Mar 2025 16:52:29 +0100
Subject: [PATCH 104/171] Simplify _is_comm_success & _is_error

---
 lerobot/common/motors/dynamixel/dynamixel.py | 9 ++-------
 lerobot/common/motors/feetech/feetech.py     | 9 ++-------
 lerobot/common/motors/motors_bus.py          | 8 ++++----
 3 files changed, 8 insertions(+), 18 deletions(-)

diff --git a/lerobot/common/motors/dynamixel/dynamixel.py b/lerobot/common/motors/dynamixel/dynamixel.py
index 5992ae56..3a3f5016 100644
--- a/lerobot/common/motors/dynamixel/dynamixel.py
+++ b/lerobot/common/motors/dynamixel/dynamixel.py
@@ -57,7 +57,8 @@ class DynamixelMotorsBus(MotorsBus):
         self.packet_handler = dxl.PacketHandler(PROTOCOL_VERSION)
         self.sync_reader = dxl.GroupSyncRead(self.port_handler, self.packet_handler, 0, 0)
         self.sync_writer = dxl.GroupSyncWrite(self.port_handler, self.packet_handler, 0, 0)
-        self.__comm_success = dxl.COMM_SUCCESS
+        self._comm_success = dxl.COMM_SUCCESS
+        self._error = 0x00
 
     def broadcast_ping(
         self, num_retry: int = 0, raise_on_error: bool = False
@@ -78,12 +79,6 @@ class DynamixelMotorsBus(MotorsBus):
         # TODO
         return ids_values
 
-    def _is_comm_success(self, comm: int) -> bool:
-        return comm == self.__comm_success
-
-    def _is_error(self, error: int) -> bool:
-        return error != 0x00
-
     @staticmethod
     def split_int_bytes(value: int, n_bytes: int) -> list[int]:
         # Validate input
diff --git a/lerobot/common/motors/feetech/feetech.py b/lerobot/common/motors/feetech/feetech.py
index 4c8dd4ed..74c114b3 100644
--- a/lerobot/common/motors/feetech/feetech.py
+++ b/lerobot/common/motors/feetech/feetech.py
@@ -53,7 +53,8 @@ class FeetechMotorsBus(MotorsBus):
         self.packet_handler = scs.PacketHandler(PROTOCOL_VERSION)
         self.sync_reader = scs.GroupSyncRead(self.port_handler, self.packet_handler, 0, 0)
         self.sync_writer = scs.GroupSyncWrite(self.port_handler, self.packet_handler, 0, 0)
-        self.__comm_success = scs.COMM_SUCCESS
+        self._comm_success = scs.COMM_SUCCESS
+        self._error = 0x00
 
     def broadcast_ping(self, num_retry: int | None = None):
         raise NotImplementedError  # TODO
@@ -66,12 +67,6 @@ class FeetechMotorsBus(MotorsBus):
         # TODO
         return ids_values
 
-    def _is_comm_success(self, comm: int) -> bool:
-        return comm == self.__comm_success
-
-    def _is_error(self, error: int) -> bool:
-        return error != 0x00
-
     @staticmethod
     def split_int_bytes(value: int, n_bytes: int) -> list[int]:
         # Validate input
diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py
index 4558d56c..249c66a8 100644
--- a/lerobot/common/motors/motors_bus.py
+++ b/lerobot/common/motors/motors_bus.py
@@ -258,6 +258,8 @@ class MotorsBus(abc.ABC):
         self.packet_handler: PacketHandler
         self.sync_reader: GroupSyncRead
         self.sync_writer: GroupSyncWrite
+        self._comm_success: int
+        self._error: int
 
         self.calibration = None
 
@@ -391,13 +393,11 @@ class MotorsBus(abc.ABC):
     def uncalibrate_values(self, ids_values: dict[int, float]) -> dict[int, int]:
         pass
 
-    @abc.abstractmethod
     def _is_comm_success(self, comm: int) -> bool:
-        pass
+        return comm == self._comm_success
 
-    @abc.abstractmethod
     def _is_error(self, error: int) -> bool:
-        pass
+        return error != self._error
 
     @staticmethod
     @abc.abstractmethod

From ff7cfdaf400fcb4058c85ffc2d3acc1d19e03af7 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sun, 23 Mar 2025 17:03:04 +0100
Subject: [PATCH 105/171] Move mock_serial patch to dedicated file

---
 tests/mocks/mock_dynamixel.py    | 34 +++----------------------------
 tests/mocks/mock_feetech.py      | 34 +++----------------------------
 tests/mocks/mock_serial_patch.py | 35 ++++++++++++++++++++++++++++++++
 3 files changed, 41 insertions(+), 62 deletions(-)
 create mode 100644 tests/mocks/mock_serial_patch.py

diff --git a/tests/mocks/mock_dynamixel.py b/tests/mocks/mock_dynamixel.py
index 21668e17..2f12283c 100644
--- a/tests/mocks/mock_dynamixel.py
+++ b/tests/mocks/mock_dynamixel.py
@@ -1,15 +1,15 @@
 import abc
 import random
-import threading
-import time
 from typing import Callable
 
 import dynamixel_sdk as dxl
 import serial
-from mock_serial.mock_serial import MockSerial, Stub
+from mock_serial.mock_serial import MockSerial
 
 from lerobot.common.motors.dynamixel import X_SERIES_CONTROL_TABLE, DynamixelMotorsBus
 
+from .mock_serial_patch import WaitableStub
+
 # https://emanual.robotis.com/docs/en/dxl/crc/
 DXL_CRC_TABLE = [
     0x0000, 0x8005, 0x800F, 0x000A, 0x801B, 0x001E, 0x0014, 0x8011,
@@ -420,34 +420,6 @@ class MockPortHandler(dxl.PortHandler):
         return True
 
 
-class WaitableStub(Stub):
-    """
-    In some situations, a test might be checking if a stub has been called before `MockSerial` thread had time
-    to read, match, and call the stub. In these situations, the test can fail randomly.
-
-    Use `wait_called()` or `wait_calls()` to block until the stub is called, avoiding race conditions.
-    """
-
-    def __init__(self, **kwargs):
-        super().__init__(**kwargs)
-        self._event = threading.Event()
-
-    def call(self):
-        self._event.set()
-        return super().call()
-
-    def wait_called(self, timeout: float = 1.0):
-        return self._event.wait(timeout)
-
-    def wait_calls(self, min_calls: int = 1, timeout: float = 1.0):
-        start = time.perf_counter()
-        while time.perf_counter() - start < timeout:
-            if self.calls >= min_calls:
-                return self.calls
-            time.sleep(0.005)
-        raise TimeoutError(f"Stub not called {min_calls} times within {timeout} seconds.")
-
-
 class MockMotors(MockSerial):
     """
     This class will simulate physical motors by responding with valid status packets upon receiving some
diff --git a/tests/mocks/mock_feetech.py b/tests/mocks/mock_feetech.py
index f23dd6ee..d685c970 100644
--- a/tests/mocks/mock_feetech.py
+++ b/tests/mocks/mock_feetech.py
@@ -1,15 +1,15 @@
 import abc
 import random
-import threading
-import time
 from typing import Callable
 
 import scservo_sdk as scs
 import serial
-from mock_serial.mock_serial import MockSerial, Stub
+from mock_serial import MockSerial
 
 from lerobot.common.motors.feetech import SCS_SERIES_CONTROL_TABLE, FeetechMotorsBus
 
+from .mock_serial_patch import WaitableStub
+
 # https://files.waveshare.com/upload/2/27/Communication_Protocol_User_Manual-EN%28191218-0923%29.pdf
 INSTRUCTION_TYPES = {
     "Ping": 0x01,	        # Checks whether the Packet has arrived at a device with the same ID as the specified packet ID
@@ -274,34 +274,6 @@ class MockPortHandler(scs.PortHandler):
         return True
 
 
-class WaitableStub(Stub):
-    """
-    In some situations, a test might be checking if a stub has been called before `MockSerial` thread had time
-    to read, match, and call the stub. In these situations, the test can fail randomly.
-
-    Use `wait_called()` or `wait_calls()` to block until the stub is called, avoiding race conditions.
-    """
-
-    def __init__(self, **kwargs):
-        super().__init__(**kwargs)
-        self._event = threading.Event()
-
-    def call(self):
-        self._event.set()
-        return super().call()
-
-    def wait_called(self, timeout: float = 1.0):
-        return self._event.wait(timeout)
-
-    def wait_calls(self, min_calls: int = 1, timeout: float = 1.0):
-        start = time.perf_counter()
-        while time.perf_counter() - start < timeout:
-            if self.calls >= min_calls:
-                return self.calls
-            time.sleep(0.005)
-        raise TimeoutError(f"Stub not called {min_calls} times within {timeout} seconds.")
-
-
 class MockMotors(MockSerial):
     """
     This class will simulate physical motors by responding with valid status packets upon receiving some
diff --git a/tests/mocks/mock_serial_patch.py b/tests/mocks/mock_serial_patch.py
new file mode 100644
index 00000000..e3992318
--- /dev/null
+++ b/tests/mocks/mock_serial_patch.py
@@ -0,0 +1,35 @@
+import threading
+import time
+
+from mock_serial.mock_serial import Stub
+
+
+class WaitableStub(Stub):
+    """
+    In some situations, a test might be checking if a stub has been called before `MockSerial` thread had time
+    to read, match, and call the stub. In these situations, the test can fail randomly.
+
+    Use `wait_called()` or `wait_calls()` to block until the stub is called, avoiding race conditions.
+
+    Proposed fix:
+    https://github.com/benthorner/mock_serial/pull/3
+    """
+
+    def __init__(self, **kwargs):
+        super().__init__(**kwargs)
+        self._event = threading.Event()
+
+    def call(self):
+        self._event.set()
+        return super().call()
+
+    def wait_called(self, timeout: float = 1.0):
+        return self._event.wait(timeout)
+
+    def wait_calls(self, min_calls: int = 1, timeout: float = 1.0):
+        start = time.perf_counter()
+        while time.perf_counter() - start < timeout:
+            if self.calls >= min_calls:
+                return self.calls
+            time.sleep(0.005)
+        raise TimeoutError(f"Stub not called {min_calls} times within {timeout} seconds.")

From 0ac026b52159e158cc76740878a2e3955de4dde5 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sun, 23 Mar 2025 17:04:30 +0100
Subject: [PATCH 106/171] Remove test skips & fix docstrings

---
 tests/mocks/mock_feetech.py  | 10 +++++-----
 tests/motors/test_feetech.py |  2 --
 2 files changed, 5 insertions(+), 7 deletions(-)

diff --git a/tests/mocks/mock_feetech.py b/tests/mocks/mock_feetech.py
index d685c970..8686e5af 100644
--- a/tests/mocks/mock_feetech.py
+++ b/tests/mocks/mock_feetech.py
@@ -166,7 +166,7 @@ class MockInstructionPacket(MockFeetechPacket):
         """
         Builds a "Write" instruction.
 
-        The parameters for Write (Protocol 2.0) are:
+        The parameters for Write are:
             param[0]   = start_address L
             param[1]   = start_address H
             param[2]   = 1st Byte
@@ -174,10 +174,10 @@ class MockInstructionPacket(MockFeetechPacket):
             ...
             param[1+X] = X-th Byte
 
-        And 'length' = data_length + 5, where:
+        And 'length' = data_length + 3, where:
             +1 is for instruction byte,
-            +2 is for the length bytes,
-            +2 is for the CRC at the end.
+            +1 is for the length bytes,
+            +1 is for the checksum at the end.
         """
         data = FeetechMotorsBus.split_int_bytes(value, data_length)
         params = [start_address, *data]
@@ -234,7 +234,7 @@ class MockStatusPacket(MockFeetechPacket):
         """Builds a 'Present_Position' status packet.
 
         Args:
-            scs_id (int): List of the servos ids
+            scs_id (int): List of the servos ids.
             pos (int | None, optional): Desired 'Present_Position' to be returned in the packet. If None, it
                 will use a random value in the min_max_range. Defaults to None.
             min_max_range (tuple, optional): Min/max range to generate the position values used for when 'pos'
diff --git a/tests/motors/test_feetech.py b/tests/motors/test_feetech.py
index 8f3b4d04..45ffd575 100644
--- a/tests/motors/test_feetech.py
+++ b/tests/motors/test_feetech.py
@@ -401,7 +401,6 @@ def test_sync_write_by_names(ids, positions, mock_motors, dummy_motors):
     assert mock_motors.stubs[stub_name].wait_called()
 
 
-@pytest.mark.skip("TODO")
 @pytest.mark.parametrize(
     "data_name, dxl_id, value",
     [
@@ -424,7 +423,6 @@ def test_write_by_id(data_name, dxl_id, value, mock_motors, dummy_motors):
     assert mock_motors.stubs[stub_name].called
 
 
-@pytest.mark.skip("TODO")
 @pytest.mark.parametrize(
     "data_name, dxl_id, value",
     [

From 97194bf7f3200e63f83fbd8e40226fa5a4ebab29 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sun, 23 Mar 2025 17:05:08 +0100
Subject: [PATCH 107/171] Nit

---
 tests/motors/test_dynamixel.py | 26 +++++++++++++-------------
 1 file changed, 13 insertions(+), 13 deletions(-)

diff --git a/tests/motors/test_dynamixel.py b/tests/motors/test_dynamixel.py
index fee37b28..278c24d2 100644
--- a/tests/motors/test_dynamixel.py
+++ b/tests/motors/test_dynamixel.py
@@ -147,22 +147,22 @@ def test_sync_read_none(mock_motors, dummy_motors):
     )
     motors_bus.connect()
 
-    positions_read = motors_bus.sync_read("Present_Position")
+    read_positions = motors_bus.sync_read("Present_Position")
 
     assert mock_motors.stubs[stub_name].called
-    assert positions_read == expected_positions
+    assert read_positions == expected_positions
 
 
 @pytest.mark.parametrize(
-    "dxl_id, position",
+    "id_, position",
     [
         (1, 1337),
         (2, 42),
         (3, 4016),
     ],
 )
-def test_sync_read_by_id(dxl_id, position, mock_motors, dummy_motors):
-    expected_position = {dxl_id: position}
+def test_sync_read_by_id(id_, position, mock_motors, dummy_motors):
+    expected_position = {id_: position}
     stub_name = mock_motors.build_sync_read_stub("Present_Position", expected_position)
     motors_bus = DynamixelMotorsBus(
         port=mock_motors.port,
@@ -170,10 +170,10 @@ def test_sync_read_by_id(dxl_id, position, mock_motors, dummy_motors):
     )
     motors_bus.connect()
 
-    positions_read = motors_bus.sync_read("Present_Position", dxl_id)
+    read_position = motors_bus.sync_read("Present_Position", id_)
 
     assert mock_motors.stubs[stub_name].called
-    assert positions_read == expected_position
+    assert read_position == expected_position
 
 
 @pytest.mark.parametrize(
@@ -195,10 +195,10 @@ def test_sync_read_by_ids(ids, positions, mock_motors, dummy_motors):
     )
     motors_bus.connect()
 
-    positions_read = motors_bus.sync_read("Present_Position", ids)
+    read_positions = motors_bus.sync_read("Present_Position", ids)
 
     assert mock_motors.stubs[stub_name].called
-    assert positions_read == expected_positions
+    assert read_positions == expected_positions
 
 
 @pytest.mark.parametrize(
@@ -218,10 +218,10 @@ def test_sync_read_by_name(id_, position, mock_motors, dummy_motors):
     )
     motors_bus.connect()
 
-    positions_read = motors_bus.sync_read("Present_Position", f"dummy_{id_}")
+    read_position = motors_bus.sync_read("Present_Position", f"dummy_{id_}")
 
     assert mock_motors.stubs[stub_name].called
-    assert positions_read == expected_position
+    assert read_position == expected_position
 
 
 @pytest.mark.parametrize(
@@ -245,10 +245,10 @@ def test_sync_read_by_names(ids, positions, mock_motors, dummy_motors):
     )
     motors_bus.connect()
 
-    positions_read = motors_bus.sync_read("Present_Position", names)
+    read_positions = motors_bus.sync_read("Present_Position", names)
 
     assert mock_motors.stubs[stub_name].called
-    assert positions_read == expected_positions
+    assert read_positions == expected_positions
 
 
 @pytest.mark.parametrize(

From 4273f1f384534fc91a0441be3fe309ee094bec0b Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sun, 23 Mar 2025 19:25:21 +0100
Subject: [PATCH 108/171] Add dxl operating modes

---
 lerobot/common/motors/dynamixel/__init__.py  |  2 +-
 lerobot/common/motors/dynamixel/dynamixel.py | 31 ++++++++++++++++++++
 lerobot/common/motors/dynamixel/tables.py    | 13 +++++++-
 3 files changed, 44 insertions(+), 2 deletions(-)

diff --git a/lerobot/common/motors/dynamixel/__init__.py b/lerobot/common/motors/dynamixel/__init__.py
index 1bd35361..14cbf8c1 100644
--- a/lerobot/common/motors/dynamixel/__init__.py
+++ b/lerobot/common/motors/dynamixel/__init__.py
@@ -1,3 +1,3 @@
-from .dynamixel import DynamixelMotorsBus
+from .dynamixel import DynamixelMotorsBus, OperatingMode
 from .dynamixel_calibration import run_arm_calibration
 from .tables import *
diff --git a/lerobot/common/motors/dynamixel/dynamixel.py b/lerobot/common/motors/dynamixel/dynamixel.py
index 3a3f5016..b2c9efbc 100644
--- a/lerobot/common/motors/dynamixel/dynamixel.py
+++ b/lerobot/common/motors/dynamixel/dynamixel.py
@@ -19,6 +19,7 @@
 # -> Need to check compatibility across models
 
 from copy import deepcopy
+from enum import Enum
 
 from ..motors_bus import Motor, MotorsBus
 from .tables import MODEL_BAUDRATE_TABLE, MODEL_CONTROL_TABLE, MODEL_RESOLUTION
@@ -32,6 +33,36 @@ CALIBRATION_REQUIRED = ["Goal_Position", "Present_Position"]
 CONVERT_UINT32_TO_INT32_REQUIRED = ["Goal_Position", "Present_Position"]
 
 
+class OperatingMode(Enum):
+    # DYNAMIXEL only controls current(torque) regardless of speed and position. This mode is ideal for a
+    # gripper or a system that only uses current(torque) control or a system that has additional
+    # velocity/position controllers.
+    Current = 0
+
+    # This mode controls velocity. This mode is identical to the Wheel Mode(endless) from existing DYNAMIXEL.
+    # This mode is ideal for wheel-type robots.
+    Velocity = 1
+
+    # This mode controls position. This mode is identical to the Joint Mode from existing DYNAMIXEL. Operating
+    # position range is limited by the Max Position Limit(48) and the Min Position Limit(52). This mode is
+    # ideal for articulated robots that each joint rotates less than 360 degrees.
+    Position = 3
+
+    # This mode controls position. This mode is identical to the Multi-turn Position Control from existing
+    # DYNAMIXEL. 512 turns are supported(-256[rev] ~ 256[rev]). This mode is ideal for multi-turn wrists or
+    # conveyer systems or a system that requires an additional reduction gear. Note that Max Position
+    # Limit(48), Min Position Limit(52) are not used on Extended Position Control Mode.
+    Extended_Position = 4
+
+    # This mode controls both position and current(torque). Up to 512 turns are supported (-256[rev] ~
+    # 256[rev]). This mode is ideal for a system that requires both position and current control such as
+    # articulated robots or grippers.
+    Current_Position = 5
+
+    # This mode directly controls PWM output. (Voltage Control Mode)
+    PWM = 16
+
+
 class DynamixelMotorsBus(MotorsBus):
     """
     The Dynamixel implementation for a MotorsBus. It relies on the python dynamixel sdk to communicate with
diff --git a/lerobot/common/motors/dynamixel/tables.py b/lerobot/common/motors/dynamixel/tables.py
index 06c5a0ad..4634d4a7 100644
--- a/lerobot/common/motors/dynamixel/tables.py
+++ b/lerobot/common/motors/dynamixel/tables.py
@@ -80,7 +80,7 @@ MODEL_RESOLUTION = {
 
 # {model: model_number}
 # https://emanual.robotis.com/docs/en/dxl/x/{MODEL}/#control-table-of-eeprom-area
-MODELS_TABLE = {
+MODEL_NUMBER = {
     "xl330-m077": 1190,
     "xl330-m288": 1200,
     "xl430-w250": 1060,
@@ -89,6 +89,17 @@ MODELS_TABLE = {
     "xc430-w150": 1070,
 }
 
+# {model: available_operating_modes}
+# https://emanual.robotis.com/docs/en/dxl/x/{MODEL}/#operating-mode11
+MODEL_OPERATING_MODES = {
+    "xl330-m077": [0, 1, 3, 4, 5, 16],
+    "xl330-m288": [0, 1, 3, 4, 5, 16],
+    "xl430-w250": [1, 3, 4, 16],
+    "xm430-w350": [0, 1, 3, 4, 5, 16],
+    "xm540-w270": [0, 1, 3, 4, 5, 16],
+    "xc430-w150": [1, 3, 4, 16],
+}
+
 MODEL_CONTROL_TABLE = {
     "x_series": X_SERIES_CONTROL_TABLE,
     "xl330-m077": X_SERIES_CONTROL_TABLE,

From 5b46dc0b6a031df25ea60bb45e8e4343f41b623f Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sun, 23 Mar 2025 19:26:10 +0100
Subject: [PATCH 109/171] Add is_connected in robots and teleops

---
 lerobot/common/robots/robot.py               | 4 ++++
 lerobot/common/teleoperators/teleoperator.py | 4 ++++
 2 files changed, 8 insertions(+)

diff --git a/lerobot/common/robots/robot.py b/lerobot/common/robots/robot.py
index 8b68c09f..a263a043 100644
--- a/lerobot/common/robots/robot.py
+++ b/lerobot/common/robots/robot.py
@@ -37,6 +37,10 @@ class Robot(abc.ABC):
     def camera_features(self) -> dict[str, dict]:
         pass
 
+    @abc.abstractproperty
+    def is_connected(self) -> bool:
+        pass
+
     @abc.abstractmethod
     def connect(self) -> None:
         """Connects to the robot."""
diff --git a/lerobot/common/teleoperators/teleoperator.py b/lerobot/common/teleoperators/teleoperator.py
index 3b60372e..743bd2c6 100644
--- a/lerobot/common/teleoperators/teleoperator.py
+++ b/lerobot/common/teleoperators/teleoperator.py
@@ -31,6 +31,10 @@ class Teleoperator(abc.ABC):
     def feedback_feature(self) -> dict:
         pass
 
+    @abc.abstractproperty
+    def is_connected(self) -> bool:
+        pass
+
     @abc.abstractmethod
     def connect(self) -> None:
         """Connects to the teleoperator."""

From 7152bc8aa71b9df0e5375474d59c070934e8e4a0 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sun, 23 Mar 2025 19:32:26 +0100
Subject: [PATCH 110/171] Update Koch

---
 lerobot/common/robots/koch/robot_koch.py      | 108 +++++++++---------
 .../common/teleoperators/koch/teleop_koch.py  |  78 +++++++------
 2 files changed, 93 insertions(+), 93 deletions(-)

diff --git a/lerobot/common/robots/koch/robot_koch.py b/lerobot/common/robots/koch/robot_koch.py
index 1f57e6c3..35cacdf9 100644
--- a/lerobot/common/robots/koch/robot_koch.py
+++ b/lerobot/common/robots/koch/robot_koch.py
@@ -17,8 +17,7 @@
 import json
 import logging
 import time
-
-import numpy as np
+from typing import Any
 
 from lerobot.common.cameras.utils import make_cameras_from_configs
 from lerobot.common.constants import OBS_IMAGES, OBS_STATE
@@ -26,6 +25,7 @@ from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnecte
 from lerobot.common.motors import CalibrationMode, Motor, TorqueMode
 from lerobot.common.motors.dynamixel import (
     DynamixelMotorsBus,
+    OperatingMode,
     run_arm_calibration,
 )
 
@@ -88,6 +88,44 @@ class KochRobot(Robot):
             }
         return cam_ft
 
+    def configure(self) -> None:
+        for name in self.arm.names:
+            # Torque must be deactivated to change values in the motors' EEPROM area
+            # We assume that at configuration time, arm is in a rest position,
+            # and torque can be safely disabled to run calibration.
+            self.arm.write("Torque_Enable", name, TorqueMode.DISABLED.value)
+            if name != "gripper":
+                # 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
+                self.arm.write("Operating_Mode", name, OperatingMode.Extended_Position.value)
+
+        # 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,
+        # its 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.
+        self.arm.write("Operating_Mode", "gripper", OperatingMode.Current_Position.value)
+
+        # 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", "elbow_flex", 1500)
+        self.arm.write("Position_I_Gain", "elbow_flex", 0)
+        self.arm.write("Position_D_Gain", "elbow_flex", 600)
+
+        for name in self.arm.names:
+            self.arm.write("Torque_Enable", name, TorqueMode.ENABLED.value)
+
+        logging.info("Torque enabled.")
+
+        # Move gripper to 45 degrees so that we can use it as a trigger.
+        self.arm.write("Goal_Position", "gripper", self.config.gripper_open_degree)
+
+    @property
+    def is_connected(self) -> bool:
+        return self.arm.is_connected  # TODO(aliberts): add cam.is_connected for cam in self.cameras
+
     def connect(self) -> None:
         if self.is_connected:
             raise DeviceAlreadyConnectedError(
@@ -96,40 +134,11 @@ class KochRobot(Robot):
 
         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()
-
-        # 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 Koch motors
-            self.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"
-        self.arm.write("Operating_Mode", 5, "gripper")
-
-        # 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)
+        self.configure()
+        # self.calibrate()  # TODO
 
         # Check arm can be read
-        self.arm.read("Present_Position")
+        self.arm.sync_read("Present_Position")
 
         # Connect the cameras
         for cam in self.cameras.values():
@@ -157,18 +166,12 @@ class KochRobot(Robot):
 
         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()`."
-            )
-
+    def get_observation(self) -> dict[str, Any]:
         obs_dict = {}
 
         # Read arm position
         before_read_t = time.perf_counter()
-        obs_dict[OBS_STATE] = self.arm.read("Present_Position")
+        obs_dict[OBS_STATE] = self.arm.sync_read("Present_Position")
         self.logs["read_pos_dt_s"] = time.perf_counter() - before_read_t
 
         # Capture images from cameras
@@ -180,7 +183,7 @@ class KochRobot(Robot):
 
         return obs_dict
 
-    def send_action(self, action: np.ndarray) -> np.ndarray:
+    def send_action(self, action: dict[str, float]) -> dict[str, float]:
         """Command arm to move to a target joint configuration.
 
         The relative action magnitude may be clipped depending on the configuration parameter
@@ -188,29 +191,22 @@ class KochRobot(Robot):
         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.
+            action (dict[str, float]): The goal positions for the motors.
 
         Returns:
-            np.ndarray: the action sent to the motors, potentially clipped.
+            dict[str, float]: 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)
+            present_pos = self.arm.sync_read("Present_Position")
+            goal_present_pos = {key: (g_pos, present_pos[key]) for key, g_pos in goal_pos.items()}
+            goal_pos = ensure_safe_goal_position(goal_present_pos, self.config.max_relative_target)
 
         # Send goal position to the arm
-        self.arm.write("Goal_Position", goal_pos.astype(np.int32))
+        self.arm.sync_write("Goal_Position", goal_pos)
 
         return goal_pos
 
diff --git a/lerobot/common/teleoperators/koch/teleop_koch.py b/lerobot/common/teleoperators/koch/teleop_koch.py
index dfd7f67d..842de99c 100644
--- a/lerobot/common/teleoperators/koch/teleop_koch.py
+++ b/lerobot/common/teleoperators/koch/teleop_koch.py
@@ -24,6 +24,7 @@ from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnecte
 from lerobot.common.motors import CalibrationMode, Motor, TorqueMode
 from lerobot.common.motors.dynamixel import (
     DynamixelMotorsBus,
+    OperatingMode,
     run_arm_calibration,
 )
 
@@ -58,7 +59,6 @@ class KochTeleop(Teleoperator):
             },
         )
 
-        self.is_connected = False
         self.logs = {}
 
     @property
@@ -73,6 +73,38 @@ class KochTeleop(Teleoperator):
     def feedback_feature(self) -> dict:
         return {}
 
+    def configure(self) -> None:
+        for name in self.arm.names:
+            # Torque must be deactivated to change values in the motors' EEPROM area
+            # We assume that at configuration time, arm is in a rest position,
+            # and torque can be safely disabled to run calibration.
+            self.arm.write("Torque_Enable", name, TorqueMode.DISABLED.value)
+            if name != "gripper":
+                # 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
+                self.arm.write("Operating_Mode", name, OperatingMode.Extended_Position.value)
+
+        # 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,
+        # its 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.
+        self.arm.write("Operating_Mode", "gripper", OperatingMode.Current_Position.value)
+
+        for name in self.arm.names:
+            self.arm.write("Torque_Enable", name, TorqueMode.ENABLED.value)
+
+        logging.info("Torque enabled.")
+
+        # Move gripper to 45 degrees so that we can use it as a trigger.
+        self.arm.write("Goal_Position", "gripper", self.config.gripper_open_degree)
+
+    @property
+    def is_connected(self) -> bool:
+        return self.arm.is_connected
+
     def connect(self) -> None:
         if self.is_connected:
             raise DeviceAlreadyConnectedError(
@@ -81,38 +113,11 @@ class KochTeleop(Teleoperator):
 
         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()
-
-        # 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 Koch motors
-            self.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"
-        self.arm.write("Operating_Mode", 5, "gripper")
-
-        # 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")
+        self.configure()
+        # self.calibrate()  # TODO
 
         # Check arm can be read
-        self.arm.read("Present_Position")
-
-        self.is_connected = True
+        self.arm.sync_read("Present_Position")
 
     def calibrate(self) -> None:
         """After calibration all motors function in human interpretable ranges.
@@ -134,18 +139,18 @@ class KochTeleop(Teleoperator):
 
         self.arm.set_calibration(calibration)
 
-    def get_action(self) -> np.ndarray:
+    def get_action(self) -> dict[str, float]:
         """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
+        start_time = time.perf_counter()
+        action = self.arm.sync_read("Present_Position")
+        self.logs["read_pos_dt_s"] = time.perf_counter() - start_time
 
         return action
 
     def send_feedback(self, feedback: np.ndarray) -> None:
         # TODO(rcadene, aliberts): Implement force feedback
-        pass
+        raise NotImplementedError
 
     def disconnect(self) -> None:
         if not self.is_connected:
@@ -154,4 +159,3 @@ class KochTeleop(Teleoperator):
             )
 
         self.arm.disconnect()
-        self.is_connected = False

From 25388d09475016a95f8a51478ee7413ec437e71f Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sun, 23 Mar 2025 19:41:46 +0100
Subject: [PATCH 111/171] Add feetech operating modes

---
 lerobot/common/motors/feetech/__init__.py |  2 +-
 lerobot/common/motors/feetech/feetech.py  | 15 +++++++++++++++
 2 files changed, 16 insertions(+), 1 deletion(-)

diff --git a/lerobot/common/motors/feetech/__init__.py b/lerobot/common/motors/feetech/__init__.py
index ae61d23b..1f110e40 100644
--- a/lerobot/common/motors/feetech/__init__.py
+++ b/lerobot/common/motors/feetech/__init__.py
@@ -1,3 +1,3 @@
-from .feetech import FeetechMotorsBus
+from .feetech import FeetechMotorsBus, OperatingMode
 from .feetech_calibration import apply_feetech_offsets_from_calibration, run_full_arm_calibration
 from .tables import *
diff --git a/lerobot/common/motors/feetech/feetech.py b/lerobot/common/motors/feetech/feetech.py
index 74c114b3..14aeb3df 100644
--- a/lerobot/common/motors/feetech/feetech.py
+++ b/lerobot/common/motors/feetech/feetech.py
@@ -13,6 +13,7 @@
 # limitations under the License.
 
 from copy import deepcopy
+from enum import Enum
 
 from ..motors_bus import Motor, MotorsBus
 from .tables import (
@@ -29,6 +30,20 @@ DEFAULT_TIMEOUT_MS = 1000
 MAX_ID_RANGE = 252
 
 
+class OperatingMode(Enum):
+    # position servo mode
+    POSITION = 0
+    # The motor is in constant speed mode, which is controlled by parameter 0x2e, and the highest bit 15 is
+    # the direction bit
+    VELOCITY = 1
+    # PWM open-loop speed regulation mode, with parameter 0x2c running time parameter control, bit11 as
+    # direction bit
+    PWM = 2
+    # In step servo mode, the number of step progress is represented by parameter 0x2a, and the highest bit 15
+    # is the direction bit
+    STEP = 3
+
+
 class FeetechMotorsBus(MotorsBus):
     """
     The FeetechMotorsBus class allows to efficiently read and write to the attached motors. It relies on the

From 7582a0a2b0b1a7ba008d80b2939f01bb878fa36a Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sun, 23 Mar 2025 19:42:21 +0100
Subject: [PATCH 112/171] Caps dxl OperatingMode

---
 lerobot/common/motors/dynamixel/dynamixel.py     | 10 +++++-----
 lerobot/common/robots/koch/robot_koch.py         |  4 ++--
 lerobot/common/teleoperators/koch/teleop_koch.py |  4 ++--
 3 files changed, 9 insertions(+), 9 deletions(-)

diff --git a/lerobot/common/motors/dynamixel/dynamixel.py b/lerobot/common/motors/dynamixel/dynamixel.py
index b2c9efbc..a9e00247 100644
--- a/lerobot/common/motors/dynamixel/dynamixel.py
+++ b/lerobot/common/motors/dynamixel/dynamixel.py
@@ -37,27 +37,27 @@ class OperatingMode(Enum):
     # DYNAMIXEL only controls current(torque) regardless of speed and position. This mode is ideal for a
     # gripper or a system that only uses current(torque) control or a system that has additional
     # velocity/position controllers.
-    Current = 0
+    CURRENT = 0
 
     # This mode controls velocity. This mode is identical to the Wheel Mode(endless) from existing DYNAMIXEL.
     # This mode is ideal for wheel-type robots.
-    Velocity = 1
+    VELOCITY = 1
 
     # This mode controls position. This mode is identical to the Joint Mode from existing DYNAMIXEL. Operating
     # position range is limited by the Max Position Limit(48) and the Min Position Limit(52). This mode is
     # ideal for articulated robots that each joint rotates less than 360 degrees.
-    Position = 3
+    POSITION = 3
 
     # This mode controls position. This mode is identical to the Multi-turn Position Control from existing
     # DYNAMIXEL. 512 turns are supported(-256[rev] ~ 256[rev]). This mode is ideal for multi-turn wrists or
     # conveyer systems or a system that requires an additional reduction gear. Note that Max Position
     # Limit(48), Min Position Limit(52) are not used on Extended Position Control Mode.
-    Extended_Position = 4
+    EXTENDED_POSITION = 4
 
     # This mode controls both position and current(torque). Up to 512 turns are supported (-256[rev] ~
     # 256[rev]). This mode is ideal for a system that requires both position and current control such as
     # articulated robots or grippers.
-    Current_Position = 5
+    CURRENT_POSITION = 5
 
     # This mode directly controls PWM output. (Voltage Control Mode)
     PWM = 16
diff --git a/lerobot/common/robots/koch/robot_koch.py b/lerobot/common/robots/koch/robot_koch.py
index 35cacdf9..3dd78519 100644
--- a/lerobot/common/robots/koch/robot_koch.py
+++ b/lerobot/common/robots/koch/robot_koch.py
@@ -99,14 +99,14 @@ class KochRobot(Robot):
                 # 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
-                self.arm.write("Operating_Mode", name, OperatingMode.Extended_Position.value)
+                self.arm.write("Operating_Mode", name, OperatingMode.EXTENDED_POSITION.value)
 
         # 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,
         # its 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.
-        self.arm.write("Operating_Mode", "gripper", OperatingMode.Current_Position.value)
+        self.arm.write("Operating_Mode", "gripper", OperatingMode.CURRENT_POSITION.value)
 
         # 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
diff --git a/lerobot/common/teleoperators/koch/teleop_koch.py b/lerobot/common/teleoperators/koch/teleop_koch.py
index 842de99c..25ae14e6 100644
--- a/lerobot/common/teleoperators/koch/teleop_koch.py
+++ b/lerobot/common/teleoperators/koch/teleop_koch.py
@@ -84,14 +84,14 @@ class KochTeleop(Teleoperator):
                 # 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
-                self.arm.write("Operating_Mode", name, OperatingMode.Extended_Position.value)
+                self.arm.write("Operating_Mode", name, OperatingMode.EXTENDED_POSITION.value)
 
         # 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,
         # its 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.
-        self.arm.write("Operating_Mode", "gripper", OperatingMode.Current_Position.value)
+        self.arm.write("Operating_Mode", "gripper", OperatingMode.CURRENT_POSITION.value)
 
         for name in self.arm.names:
             self.arm.write("Torque_Enable", name, TorqueMode.ENABLED.value)

From 039b437ef07554e2a9d0ee678b241b01a7f7d04f Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sun, 23 Mar 2025 19:43:58 +0100
Subject: [PATCH 113/171] Update ensure_safe_goal_position

---
 lerobot/common/robots/utils.py | 45 +++++++++++++++++++++++-----------
 1 file changed, 31 insertions(+), 14 deletions(-)

diff --git a/lerobot/common/robots/utils.py b/lerobot/common/robots/utils.py
index 12b9dac5..7e538376 100644
--- a/lerobot/common/robots/utils.py
+++ b/lerobot/common/robots/utils.py
@@ -1,8 +1,7 @@
 import logging
+from pprint import pformat
 from typing import Protocol
 
-import numpy as np
-
 from lerobot.common.robots import RobotConfig
 
 
@@ -81,20 +80,38 @@ def make_robot(robot_type: str, **kwargs) -> Robot:
 
 
 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
+    goal_present_pos: dict[str, tuple[float, float]], max_relative_target: float | dict[float]
+) -> dict[str, float]:
+    """Caps relative action target magnitude for safety."""
 
-    if not np.allclose(goal_pos, safe_goal_pos):
+    if isinstance(max_relative_target, float):
+        diff_cap = {key: max_relative_target for key in goal_present_pos}
+    elif isinstance(max_relative_target, dict):
+        if not set(goal_present_pos) == set(max_relative_target):
+            raise ValueError("max_relative_target keys must match those of goal_present_pos.")
+        diff_cap = max_relative_target
+    else:
+        raise TypeError(max_relative_target)
+
+    warnings_dict = {}
+    safe_goal_positions = {}
+    for key, (goal_pos, present_pos) in goal_present_pos.items():
+        diff = goal_pos - present_pos
+        max_diff = diff_cap[key]
+        safe_diff = min(diff, max_diff)
+        safe_diff = max(safe_diff, -max_diff)
+        safe_goal_pos = present_pos + safe_diff
+        safe_goal_positions[key] = safe_goal_pos
+        if abs(safe_goal_pos - goal_pos) > 1e-4:
+            warnings_dict[key] = {
+                "original goal_pos": goal_pos,
+                "safe goal_pos": safe_goal_pos,
+            }
+
+    if warnings_dict:
         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}"
+            f"{pformat(warnings_dict, indent=4)}"
         )
 
-    return safe_goal_pos
+    return safe_goal_positions

From 30fcd3d417bfdac820673c64ec302e2a89527d1a Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sun, 23 Mar 2025 20:15:47 +0100
Subject: [PATCH 114/171] Update so100

---
 lerobot/common/robots/so100/robot_so100.py    | 113 ++++++++----------
 .../teleoperators/so100/teleop_so100.py       |  61 +++++-----
 2 files changed, 81 insertions(+), 93 deletions(-)

diff --git a/lerobot/common/robots/so100/robot_so100.py b/lerobot/common/robots/so100/robot_so100.py
index 13229709..ccbe9dad 100644
--- a/lerobot/common/robots/so100/robot_so100.py
+++ b/lerobot/common/robots/so100/robot_so100.py
@@ -14,7 +14,6 @@
 # See the License for the specific language governing permissions and
 # limitations under the License.
 
-import json
 import logging
 import time
 
@@ -23,11 +22,11 @@ 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 import TorqueMode
+from lerobot.common.motors import CalibrationMode, Motor, TorqueMode
 from lerobot.common.motors.feetech import (
     FeetechMotorsBus,
+    OperatingMode,
     apply_feetech_offsets_from_calibration,
-    run_full_arm_calibration,
 )
 
 from ..robot import Robot
@@ -47,23 +46,21 @@ class SO100Robot(Robot):
         super().__init__(config)
         self.config = config
         self.robot_type = config.type
+        self.logs = {}
 
         self.arm = FeetechMotorsBus(
             port=self.config.port,
             motors={
-                "shoulder_pan": (1, "sts3215"),
-                "shoulder_lift": (2, "sts3215"),
-                "elbow_flex": (3, "sts3215"),
-                "wrist_flex": (4, "sts3215"),
-                "wrist_roll": (5, "sts3215"),
-                "gripper": (6, "sts3215"),
+                "shoulder_pan": Motor(1, "sts3215", CalibrationMode.RANGE_M100_100),
+                "shoulder_lift": Motor(2, "sts3215", CalibrationMode.RANGE_M100_100),
+                "elbow_flex": Motor(3, "sts3215", CalibrationMode.RANGE_M100_100),
+                "wrist_flex": Motor(4, "sts3215", CalibrationMode.RANGE_M100_100),
+                "wrist_roll": Motor(5, "sts3215", CalibrationMode.RANGE_M100_100),
+                "gripper": Motor(6, "sts3215", CalibrationMode.RANGE_0_100),
             },
         )
         self.cameras = make_cameras_from_configs(config.cameras)
 
-        self.is_connected = False
-        self.logs = {}
-
     @property
     def state_feature(self) -> dict:
         return {
@@ -87,6 +84,38 @@ class SO100Robot(Robot):
             }
         return cam_ft
 
+    def configure(self) -> None:
+        for name in self.arm.names:
+            # 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", name, TorqueMode.DISABLED.value)
+            self.arm.write("Mode", name, OperatingMode.POSITION.value)
+
+            # Set P_Coefficient to lower value to avoid shakiness (Default is 32)
+            self.arm.write("P_Coefficient", name, 16)
+            # Set I_Coefficient and D_Coefficient to default value 0 and 32
+            self.arm.write("I_Coefficient", name, 0)
+            self.arm.write("D_Coefficient", name, 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", name, 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", name, 254)
+            self.arm.write("Acceleration", name, 254)
+
+        self.calibrate()
+
+        for name in self.arm.names:
+            self.arm.write("Torque_Enable", name, TorqueMode.ENABLED.value)
+
+        logging.info("Torque activated.")
+
+    @property
+    def is_connected(self) -> bool:
+        # TODO(aliberts): add cam.is_connected for cam in self.cameras
+        return self.arm.is_connected
+
     def connect(self) -> None:
         if self.is_connected:
             raise DeviceAlreadyConnectedError(
@@ -95,59 +124,25 @@ class SO100Robot(Robot):
 
         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)
+        self.configure()
 
         # Check arm can be read
-        self.arm.read("Present_Position")
+        self.arm.sync_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].
-        """
-        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 '{self.calibration_fpath}'")
-            calibration = run_full_arm_calibration(self.arm, self.robot_type, self.name, "follower")
+        raise NotImplementedError
 
-            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)
+    def set_calibration(self) -> None:
+        if not self.calibration_fpath.exists():
+            logging.error("Calibration file not found. Please run calibration first")
+            raise FileNotFoundError(self.calibration_fpath)
 
-        self.arm.set_calibration(calibration)
-        apply_feetech_offsets_from_calibration(self.arm, calibration)
+        self.arm.set_calibration(self.calibration_fpath)
+        apply_feetech_offsets_from_calibration(self.arm, self.arm.calibration)
 
     def get_observation(self) -> dict[str, np.ndarray]:
         """The returned observations do not have a batch dimension."""
@@ -160,7 +155,7 @@ class SO100Robot(Robot):
 
         # Read arm position
         before_read_t = time.perf_counter()
-        obs_dict[OBS_STATE] = self.arm.read("Present_Position")
+        obs_dict[OBS_STATE] = self.arm.sync_read("Present_Position")
         self.logs["read_pos_dt_s"] = time.perf_counter() - before_read_t
 
         # Capture images from cameras
@@ -198,11 +193,11 @@ class SO100Robot(Robot):
         # 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")
+            present_pos = self.arm.sync_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))
+        self.arm.sync_write("Goal_Position", goal_pos.astype(np.int32))
 
         return goal_pos
 
@@ -219,5 +214,3 @@ class SO100Robot(Robot):
         self.arm.disconnect()
         for cam in self.cameras.values():
             cam.disconnect()
-
-        self.is_connected = False
diff --git a/lerobot/common/teleoperators/so100/teleop_so100.py b/lerobot/common/teleoperators/so100/teleop_so100.py
index 90af62a8..0e02b313 100644
--- a/lerobot/common/teleoperators/so100/teleop_so100.py
+++ b/lerobot/common/teleoperators/so100/teleop_so100.py
@@ -14,18 +14,16 @@
 # 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 import TorqueMode
+from lerobot.common.motors import CalibrationMode, Motor, TorqueMode
 from lerobot.common.motors.feetech import (
     FeetechMotorsBus,
     apply_feetech_offsets_from_calibration,
-    run_full_arm_calibration,
 )
 
 from ..teleoperator import Teleoperator
@@ -48,16 +46,15 @@ class SO100Teleop(Teleoperator):
         self.arm = FeetechMotorsBus(
             port=self.config.port,
             motors={
-                "shoulder_pan": (1, "sts3215"),
-                "shoulder_lift": (2, "sts3215"),
-                "elbow_flex": (3, "sts3215"),
-                "wrist_flex": (4, "sts3215"),
-                "wrist_roll": (5, "sts3215"),
-                "gripper": (6, "sts3215"),
+                "shoulder_pan": Motor(1, "sts3215", CalibrationMode.RANGE_M100_100),
+                "shoulder_lift": Motor(2, "sts3215", CalibrationMode.RANGE_M100_100),
+                "elbow_flex": Motor(3, "sts3215", CalibrationMode.RANGE_M100_100),
+                "wrist_flex": Motor(4, "sts3215", CalibrationMode.RANGE_M100_100),
+                "wrist_roll": Motor(5, "sts3215", CalibrationMode.RANGE_M100_100),
+                "gripper": Motor(6, "sts3215", CalibrationMode.RANGE_0_100),
             },
         )
 
-        self.is_connected = False
         self.logs = {}
 
     @property
@@ -72,6 +69,16 @@ class SO100Teleop(Teleoperator):
     def feedback_feature(self) -> dict:
         return {}
 
+    def configure(self) -> None:
+        # We assume that at connection time, arm is in a rest position,
+        # and torque can be safely disabled to run calibration.
+        for name in self.arm.names:
+            self.arm.write("Torque_Enable", name, TorqueMode.DISABLED.value)
+
+    @property
+    def is_connected(self) -> bool:
+        return self.arm.is_connected
+
     def connect(self) -> None:
         if self.is_connected:
             raise DeviceAlreadyConnectedError(
@@ -80,43 +87,32 @@ class SO100Teleop(Teleoperator):
 
         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.configure()
         self.calibrate()
 
         # Check arm can be read
-        self.arm.read("Present_Position")
-
-        self.is_connected = True
+        self.arm.sync_read("Present_Position")
 
     def calibrate(self) -> None:
+        raise NotImplementedError
+
+    def set_calibration(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].
         """
-        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 '{self.calibration_fpath}'")
-            calibration = run_full_arm_calibration(self.arm, self.robot_type, self.name, "leader")
+        if not self.calibration_fpath.exists():
+            logging.error("Calibration file not found. Please run calibration first")
+            raise FileNotFoundError(self.calibration_fpath)
 
-            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)
+        self.arm.set_calibration(self.calibration_fpath)
+        apply_feetech_offsets_from_calibration(self.arm, self.arm.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")
+        action = self.arm.sync_read("Present_Position")
         self.logs["read_pos_dt_s"] = time.perf_counter() - before_read_t
 
         return action
@@ -132,4 +128,3 @@ class SO100Teleop(Teleoperator):
             )
 
         self.arm.disconnect()
-        self.is_connected = False

From 39d8f458107e552d699228c68131a1836b4af63e Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Mon, 24 Mar 2025 11:57:12 +0100
Subject: [PATCH 115/171] Privatize methods & renames

---
 lerobot/common/motors/dynamixel/dynamixel.py |   8 +-
 lerobot/common/motors/feetech/feetech.py     |  15 +--
 lerobot/common/motors/motors_bus.py          | 102 ++++++++++---------
 tests/mocks/mock_dynamixel.py                |   4 +-
 tests/mocks/mock_feetech.py                  |   4 +-
 tests/motors/test_dynamixel.py               |  16 +--
 tests/motors/test_feetech.py                 |  16 +--
 7 files changed, 86 insertions(+), 79 deletions(-)

diff --git a/lerobot/common/motors/dynamixel/dynamixel.py b/lerobot/common/motors/dynamixel/dynamixel.py
index a9e00247..3a8a80be 100644
--- a/lerobot/common/motors/dynamixel/dynamixel.py
+++ b/lerobot/common/motors/dynamixel/dynamixel.py
@@ -89,7 +89,7 @@ class DynamixelMotorsBus(MotorsBus):
         self.sync_reader = dxl.GroupSyncRead(self.port_handler, self.packet_handler, 0, 0)
         self.sync_writer = dxl.GroupSyncWrite(self.port_handler, self.packet_handler, 0, 0)
         self._comm_success = dxl.COMM_SUCCESS
-        self._error = 0x00
+        self._no_error = 0x00
 
     def broadcast_ping(
         self, num_retry: int = 0, raise_on_error: bool = False
@@ -102,16 +102,16 @@ class DynamixelMotorsBus(MotorsBus):
         if raise_on_error:
             raise ConnectionError(f"Broadcast ping returned a {comm} comm error.")
 
-    def calibrate_values(self, ids_values: dict[int, int]) -> dict[int, float]:
+    def _calibrate_values(self, ids_values: dict[int, int]) -> dict[int, float]:
         # TODO
         return ids_values
 
-    def uncalibrate_values(self, ids_values: dict[int, float]) -> dict[int, int]:
+    def _uncalibrate_values(self, ids_values: dict[int, float]) -> dict[int, int]:
         # TODO
         return ids_values
 
     @staticmethod
-    def split_int_bytes(value: int, n_bytes: int) -> list[int]:
+    def _split_int_to_bytes(value: int, n_bytes: int) -> list[int]:
         # Validate input
         if value < 0:
             raise ValueError(f"Negative values are not allowed: {value}")
diff --git a/lerobot/common/motors/feetech/feetech.py b/lerobot/common/motors/feetech/feetech.py
index 14aeb3df..98144473 100644
--- a/lerobot/common/motors/feetech/feetech.py
+++ b/lerobot/common/motors/feetech/feetech.py
@@ -69,21 +69,24 @@ class FeetechMotorsBus(MotorsBus):
         self.sync_reader = scs.GroupSyncRead(self.port_handler, self.packet_handler, 0, 0)
         self.sync_writer = scs.GroupSyncWrite(self.port_handler, self.packet_handler, 0, 0)
         self._comm_success = scs.COMM_SUCCESS
-        self._error = 0x00
+        self._no_error = 0x00
 
-    def broadcast_ping(self, num_retry: int | None = None):
-        raise NotImplementedError  # TODO
+    def broadcast_ping(
+        self, num_retry: int = 0, raise_on_error: bool = False
+    ) -> dict[int, list[int, int]] | None:
+        # TODO
+        raise NotImplementedError
 
-    def calibrate_values(self, ids_values: dict[int, int]) -> dict[int, float]:
+    def _calibrate_values(self, ids_values: dict[int, int]) -> dict[int, float]:
         # TODO
         return ids_values
 
-    def uncalibrate_values(self, ids_values: dict[int, float]) -> dict[int, int]:
+    def _uncalibrate_values(self, ids_values: dict[int, float]) -> dict[int, int]:
         # TODO
         return ids_values
 
     @staticmethod
-    def split_int_bytes(value: int, n_bytes: int) -> list[int]:
+    def _split_int_to_bytes(value: int, n_bytes: int) -> list[int]:
         # Validate input
         if value < 0:
             raise ValueError(f"Negative values are not allowed: {value}")
diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py
index 249c66a8..0694b66a 100644
--- a/lerobot/common/motors/motors_bus.py
+++ b/lerobot/common/motors/motors_bus.py
@@ -259,7 +259,7 @@ class MotorsBus(abc.ABC):
         self.sync_reader: GroupSyncRead
         self.sync_writer: GroupSyncWrite
         self._comm_success: int
-        self._error: int
+        self._no_error: int
 
         self.calibration = None
 
@@ -285,12 +285,6 @@ class MotorsBus(abc.ABC):
         first_table = self.model_ctrl_table[self.models[0]]
         return any(DeepDiff(first_table, self.model_ctrl_table[model]) for model in self.models[1:])
 
-    def id_to_model(self, motor_id: int) -> str:
-        return self._id_to_model[motor_id]
-
-    def id_to_name(self, motor_id: int) -> str:
-        return self._id_to_name[motor_id]
-
     @cached_property
     def names(self) -> list[str]:
         return list(self.motors)
@@ -303,6 +297,20 @@ class MotorsBus(abc.ABC):
     def ids(self) -> list[int]:
         return [m.id for m in self.motors.values()]
 
+    def _id_to_model(self, motor_id: int) -> str:
+        return self._id_to_model[motor_id]
+
+    def _id_to_name(self, motor_id: int) -> str:
+        return self._id_to_name[motor_id]
+
+    def _get_motor_id(self, motor: NameOrID) -> int:
+        if isinstance(motor, str):
+            return self.motors[motor].id
+        elif isinstance(motor, int):
+            return motor
+        else:
+            raise TypeError(f"'{motor}' should be int, str.")
+
     def _validate_motors(self) -> None:
         # TODO(aliberts): improve error messages for this (display problematics values)
         if len(self.ids) != len(set(self.ids)):
@@ -314,6 +322,12 @@ class MotorsBus(abc.ABC):
         if any(model not in self.model_resolution_table for model in self.models):
             raise ValueError("Some motors models are not available.")
 
+    def _is_comm_success(self, comm: int) -> bool:
+        return comm == self._comm_success
+
+    def _is_error(self, error: int) -> bool:
+        return error != self._no_error
+
     @property
     def is_connected(self) -> bool:
         return self.port_handler.is_open
@@ -341,6 +355,18 @@ class MotorsBus(abc.ABC):
         timeout_ms = timeout_ms if timeout_ms is not None else self.default_timeout
         self.port_handler.setPacketTimeoutMillis(timeout_ms)
 
+    def get_baudrate(self) -> int:
+        return self.port_handler.getBaudRate()
+
+    def set_baudrate(self, baudrate: int) -> None:
+        present_bus_baudrate = self.port_handler.getBaudRate()
+        if present_bus_baudrate != baudrate:
+            logger.info(f"Setting bus baud rate to {baudrate}. Previously {present_bus_baudrate}.")
+            self.port_handler.setBaudRate(baudrate)
+
+            if self.port_handler.getBaudRate() != baudrate:
+                raise OSError("Failed to write bus baud rate.")
+
     @property
     def are_motors_configured(self) -> bool:
         """
@@ -355,7 +381,7 @@ class MotorsBus(abc.ABC):
             return False
 
     def ping(self, motor: NameOrID, num_retry: int = 0, raise_on_error: bool = False) -> int | None:
-        idx = self.get_motor_id(motor)
+        idx = self._get_motor_id(motor)
         for n_try in range(1 + num_retry):
             model_number, comm, error = self.packet_handler.ping(self.port_handler, idx)
             if self._is_comm_success(comm):
@@ -368,16 +394,8 @@ class MotorsBus(abc.ABC):
     @abc.abstractmethod
     def broadcast_ping(
         self, num_retry: int = 0, raise_on_error: bool = False
-    ) -> dict[int, list[int, int]] | None: ...
-
-    def set_baudrate(self, baudrate) -> None:
-        present_bus_baudrate = self.port_handler.getBaudRate()
-        if present_bus_baudrate != baudrate:
-            logger.info(f"Setting bus baud rate to {baudrate}. Previously {present_bus_baudrate}.")
-            self.port_handler.setBaudRate(baudrate)
-
-            if self.port_handler.getBaudRate() != baudrate:
-                raise OSError("Failed to write bus baud rate.")
+    ) -> dict[int, list[int, int]] | None:
+        pass
 
     def set_calibration(self, calibration_fpath: Path) -> None:
         with open(calibration_fpath) as f:
@@ -386,22 +404,16 @@ class MotorsBus(abc.ABC):
         self.calibration = {int(idx): val for idx, val in calibration.items()}
 
     @abc.abstractmethod
-    def calibrate_values(self, ids_values: dict[int, int]) -> dict[int, float]:
+    def _calibrate_values(self, ids_values: dict[int, int]) -> dict[int, float]:
         pass
 
     @abc.abstractmethod
-    def uncalibrate_values(self, ids_values: dict[int, float]) -> dict[int, int]:
+    def _uncalibrate_values(self, ids_values: dict[int, float]) -> dict[int, int]:
         pass
 
-    def _is_comm_success(self, comm: int) -> bool:
-        return comm == self._comm_success
-
-    def _is_error(self, error: int) -> bool:
-        return error != self._error
-
     @staticmethod
     @abc.abstractmethod
-    def split_int_bytes(value: int, n_bytes: int) -> list[int]:
+    def _split_int_to_bytes(value: int, n_bytes: int) -> list[int]:
         """
         Splits an unsigned integer into a list of bytes in little-endian order.
 
@@ -437,14 +449,6 @@ class MotorsBus(abc.ABC):
         """
         pass
 
-    def get_motor_id(self, motor: NameOrID) -> int:
-        if isinstance(motor, str):
-            return self.motors[motor].id
-        elif isinstance(motor, int):
-            return motor
-        else:
-            raise TypeError(f"'{motor}' should be int, str.")
-
     @overload
     def sync_read(self, data_name: str, motors: None = ..., num_retry: int = ...) -> dict[str, Value]: ...
     @overload
@@ -463,9 +467,9 @@ class MotorsBus(abc.ABC):
         if motors is None:
             id_key_map = {m.id: name for name, m in self.motors.items()}
         elif isinstance(motors, (str, int)):
-            id_key_map = {self.get_motor_id(motors): motors}
+            id_key_map = {self._get_motor_id(motors): motors}
         elif isinstance(motors, list):
-            id_key_map = {self.get_motor_id(m): m for m in motors}
+            id_key_map = {self._get_motor_id(m): m for m in motors}
         else:
             raise TypeError(motors)
 
@@ -479,7 +483,7 @@ class MotorsBus(abc.ABC):
             )
 
         if data_name in self.calibration_required and self.calibration is not None:
-            ids_values = self.calibrate_values(ids_values)
+            ids_values = self._calibrate_values(ids_values)
 
         return {id_key_map[idx]: val for idx, val in ids_values.items()}
 
@@ -487,10 +491,10 @@ class MotorsBus(abc.ABC):
         self, data_name: str, motor_ids: list[str], num_retry: int = 0
     ) -> tuple[int, dict[int, int]]:
         if self._has_different_ctrl_tables:
-            models = [self.id_to_model(idx) for idx in motor_ids]
+            models = [self._id_to_model(idx) for idx in motor_ids]
             assert_same_address(self.model_ctrl_table, models, data_name)
 
-        model = self.id_to_model(next(iter(motor_ids)))
+        model = self._id_to_model(next(iter(motor_ids)))
         addr, n_bytes = self.model_ctrl_table[model][data_name]
         self._setup_sync_reader(motor_ids, addr, n_bytes)
 
@@ -535,12 +539,12 @@ class MotorsBus(abc.ABC):
         if isinstance(values, int):
             ids_values = {id_: values for id_ in self.ids}
         elif isinstance(values, dict):
-            ids_values = {self.get_motor_id(motor): val for motor, val in values.items()}
+            ids_values = {self._get_motor_id(motor): val for motor, val in values.items()}
         else:
             raise ValueError(f"'values' is expected to be a single value or a dict. Got {values}")
 
         if data_name in self.calibration_required and self.calibration is not None:
-            ids_values = self.uncalibrate_values(ids_values)
+            ids_values = self._uncalibrate_values(ids_values)
 
         comm = self._sync_write(data_name, ids_values, num_retry)
         if not self._is_comm_success(comm):
@@ -551,10 +555,10 @@ class MotorsBus(abc.ABC):
 
     def _sync_write(self, data_name: str, ids_values: dict[int, int], num_retry: int = 0) -> int:
         if self._has_different_ctrl_tables:
-            models = [self.id_to_model(idx) for idx in ids_values]
+            models = [self._id_to_model(idx) for idx in ids_values]
             assert_same_address(self.model_ctrl_table, models, data_name)
 
-        model = self.id_to_model(next(iter(ids_values)))
+        model = self._id_to_model(next(iter(ids_values)))
         addr, n_bytes = self.model_ctrl_table[model][data_name]
         self._setup_sync_writer(ids_values, addr, n_bytes)
 
@@ -574,7 +578,7 @@ class MotorsBus(abc.ABC):
         self.sync_writer.start_address = addr
         self.sync_writer.data_length = n_bytes
         for idx, value in ids_values.items():
-            data = self.split_int_bytes(value, n_bytes)
+            data = self._split_int_to_bytes(value, n_bytes)
             self.sync_writer.addParam(idx, data)
 
     def write(self, data_name: str, motor: NameOrID, value: Value, num_retry: int = 0) -> None:
@@ -583,10 +587,10 @@ class MotorsBus(abc.ABC):
                 f"{self.__class__.__name__}('{self.port}') is not connected. You need to run `{self.__class__.__name__}.connect()`."
             )
 
-        idx = self.get_motor_id(motor)
+        idx = self._get_motor_id(motor)
 
         if data_name in self.calibration_required and self.calibration is not None:
-            id_value = self.uncalibrate_values({idx: value})
+            id_value = self._uncalibrate_values({idx: value})
             value = id_value[idx]
 
         comm, error = self._write(data_name, idx, value, num_retry)
@@ -602,9 +606,9 @@ class MotorsBus(abc.ABC):
             )
 
     def _write(self, data_name: str, motor_id: int, value: int, num_retry: int = 0) -> tuple[int, int]:
-        model = self.id_to_model(motor_id)
+        model = self._id_to_model(motor_id)
         addr, n_bytes = self.model_ctrl_table[model][data_name]
-        data = self.split_int_bytes(value, n_bytes)
+        data = self._split_int_to_bytes(value, n_bytes)
 
         for n_try in range(1 + num_retry):
             comm, error = self.packet_handler.writeTxRx(self.port_handler, motor_id, addr, n_bytes, data)
diff --git a/tests/mocks/mock_dynamixel.py b/tests/mocks/mock_dynamixel.py
index 2f12283c..a7bcf30d 100644
--- a/tests/mocks/mock_dynamixel.py
+++ b/tests/mocks/mock_dynamixel.py
@@ -282,7 +282,7 @@ class MockInstructionPacket(MockDynamixelPacketv2):
         """
         data = []
         for idx, value in ids_values.items():
-            split_value = DynamixelMotorsBus.split_int_bytes(value, data_length)
+            split_value = DynamixelMotorsBus._split_int_to_bytes(value, data_length)
             data += [idx, *split_value]
         params = [
             dxl.DXL_LOBYTE(start_address),
@@ -319,7 +319,7 @@ class MockInstructionPacket(MockDynamixelPacketv2):
             +2 is for the length bytes,
             +2 is for the CRC at the end.
         """
-        data = DynamixelMotorsBus.split_int_bytes(value, data_length)
+        data = DynamixelMotorsBus._split_int_to_bytes(value, data_length)
         params = [
             dxl.DXL_LOBYTE(start_address),
             dxl.DXL_HIBYTE(start_address),
diff --git a/tests/mocks/mock_feetech.py b/tests/mocks/mock_feetech.py
index 8686e5af..b1478a42 100644
--- a/tests/mocks/mock_feetech.py
+++ b/tests/mocks/mock_feetech.py
@@ -149,7 +149,7 @@ class MockInstructionPacket(MockFeetechPacket):
         """
         data = []
         for idx, value in ids_values.items():
-            split_value = FeetechMotorsBus.split_int_bytes(value, data_length)
+            split_value = FeetechMotorsBus._split_int_to_bytes(value, data_length)
             data += [idx, *split_value]
         params = [start_address, data_length, *data]
         length = len(ids_values) * (1 + data_length) + 4
@@ -179,7 +179,7 @@ class MockInstructionPacket(MockFeetechPacket):
             +1 is for the length bytes,
             +1 is for the checksum at the end.
         """
-        data = FeetechMotorsBus.split_int_bytes(value, data_length)
+        data = FeetechMotorsBus._split_int_to_bytes(value, data_length)
         params = [start_address, *data]
         length = data_length + 3
         return cls.build(scs_id=scs_id, params=params, length=length, instruct_type="Write")
diff --git a/tests/motors/test_dynamixel.py b/tests/motors/test_dynamixel.py
index 278c24d2..7fdd2618 100644
--- a/tests/motors/test_dynamixel.py
+++ b/tests/motors/test_dynamixel.py
@@ -67,24 +67,24 @@ def test_autouse_patch():
         "max four bytes",
     ],
 )  # fmt: skip
-def test_split_int_bytes(value, n_bytes, expected):
-    assert DynamixelMotorsBus.split_int_bytes(value, n_bytes) == expected
+def test_split_int_to_bytes(value, n_bytes, expected):
+    assert DynamixelMotorsBus._split_int_to_bytes(value, n_bytes) == expected
 
 
-def test_split_int_bytes_invalid_n_bytes():
+def test_split_int_to_bytes_invalid_n_bytes():
     with pytest.raises(NotImplementedError):
-        DynamixelMotorsBus.split_int_bytes(100, 3)
+        DynamixelMotorsBus._split_int_to_bytes(100, 3)
 
 
-def test_split_int_bytes_negative_numbers():
+def test_split_int_to_bytes_negative_numbers():
     with pytest.raises(ValueError):
-        neg = DynamixelMotorsBus.split_int_bytes(-1, 1)
+        neg = DynamixelMotorsBus._split_int_to_bytes(-1, 1)
         print(neg)
 
 
-def test_split_int_bytes_large_number():
+def test_split_int_to_bytes_large_number():
     with pytest.raises(ValueError):
-        DynamixelMotorsBus.split_int_bytes(2**32, 4)  # 4-byte max is 0xFFFFFFFF
+        DynamixelMotorsBus._split_int_to_bytes(2**32, 4)  # 4-byte max is 0xFFFFFFFF
 
 
 def test_abc_implementation(dummy_motors):
diff --git a/tests/motors/test_feetech.py b/tests/motors/test_feetech.py
index 45ffd575..1b50d045 100644
--- a/tests/motors/test_feetech.py
+++ b/tests/motors/test_feetech.py
@@ -67,24 +67,24 @@ def test_autouse_patch():
         "max four bytes",
     ],
 )  # fmt: skip
-def test_split_int_bytes(value, n_bytes, expected):
-    assert FeetechMotorsBus.split_int_bytes(value, n_bytes) == expected
+def test_split_int_to_bytes(value, n_bytes, expected):
+    assert FeetechMotorsBus._split_int_to_bytes(value, n_bytes) == expected
 
 
-def test_split_int_bytes_invalid_n_bytes():
+def test_split_int_to_bytes_invalid_n_bytes():
     with pytest.raises(NotImplementedError):
-        FeetechMotorsBus.split_int_bytes(100, 3)
+        FeetechMotorsBus._split_int_to_bytes(100, 3)
 
 
-def test_split_int_bytes_negative_numbers():
+def test_split_int_to_bytes_negative_numbers():
     with pytest.raises(ValueError):
-        neg = FeetechMotorsBus.split_int_bytes(-1, 1)
+        neg = FeetechMotorsBus._split_int_to_bytes(-1, 1)
         print(neg)
 
 
-def test_split_int_bytes_large_number():
+def test_split_int_to_bytes_large_number():
     with pytest.raises(ValueError):
-        FeetechMotorsBus.split_int_bytes(2**32, 4)  # 4-byte max is 0xFFFFFFFF
+        FeetechMotorsBus._split_int_to_bytes(2**32, 4)  # 4-byte max is 0xFFFFFFFF
 
 
 def test_abc_implementation(dummy_motors):

From 9832daf08dfd4db824afe9506ee2f5dcc7b3e606 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Mon, 24 Mar 2025 12:16:54 +0100
Subject: [PATCH 116/171] Fix dict

---
 lerobot/common/motors/motors_bus.py | 8 ++++----
 1 file changed, 4 insertions(+), 4 deletions(-)

diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py
index 0694b66a..8329c0a0 100644
--- a/lerobot/common/motors/motors_bus.py
+++ b/lerobot/common/motors/motors_bus.py
@@ -263,8 +263,8 @@ class MotorsBus(abc.ABC):
 
         self.calibration = None
 
-        self._id_to_model = {m.id: m.model for m in self.motors.values()}
-        self._id_to_name = {m.id: name for name, m in self.motors.items()}
+        self._id_to_model_dict = {m.id: m.model for m in self.motors.values()}
+        self._id_to_name_dict = {m.id: name for name, m in self.motors.items()}
 
     def __len__(self):
         return len(self.motors)
@@ -298,10 +298,10 @@ class MotorsBus(abc.ABC):
         return [m.id for m in self.motors.values()]
 
     def _id_to_model(self, motor_id: int) -> str:
-        return self._id_to_model[motor_id]
+        return self._id_to_model_dict[motor_id]
 
     def _id_to_name(self, motor_id: int) -> str:
-        return self._id_to_name[motor_id]
+        return self._id_to_name_dict[motor_id]
 
     def _get_motor_id(self, motor: NameOrID) -> int:
         if isinstance(motor, str):

From 8994252019cd7293f153882922a8f91e717de289 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Mon, 24 Mar 2025 12:19:03 +0100
Subject: [PATCH 117/171] Add _configure_motors & move ping methods

---
 lerobot/common/motors/dynamixel/dynamixel.py | 26 ++++++++------
 lerobot/common/motors/feetech/feetech.py     | 16 ++++++---
 lerobot/common/motors/motors_bus.py          | 38 +++++++++++---------
 3 files changed, 48 insertions(+), 32 deletions(-)

diff --git a/lerobot/common/motors/dynamixel/dynamixel.py b/lerobot/common/motors/dynamixel/dynamixel.py
index 3a8a80be..c26114ad 100644
--- a/lerobot/common/motors/dynamixel/dynamixel.py
+++ b/lerobot/common/motors/dynamixel/dynamixel.py
@@ -91,16 +91,11 @@ class DynamixelMotorsBus(MotorsBus):
         self._comm_success = dxl.COMM_SUCCESS
         self._no_error = 0x00
 
-    def broadcast_ping(
-        self, num_retry: int = 0, raise_on_error: bool = False
-    ) -> dict[int, list[int, int]] | None:
-        for _ in range(1 + num_retry):
-            data_list, comm = self.packet_handler.broadcastPing(self.port_handler)
-            if self._is_comm_success(comm):
-                return data_list
-
-        if raise_on_error:
-            raise ConnectionError(f"Broadcast ping returned a {comm} comm error.")
+    def _configure_motors(self) -> None:
+        # By default, Dynamixel motors have a 500µs delay response time (corresponding to a value of 250 on
+        # the 'Return_Delay_Time' address). We ensure this is reduced to the minimum of 2µs (value of 0).
+        for id_ in self.ids:
+            self.write("Return_Delay_Time", id_, 0)
 
     def _calibrate_values(self, ids_values: dict[int, int]) -> dict[int, float]:
         # TODO
@@ -139,3 +134,14 @@ class DynamixelMotorsBus(MotorsBus):
                 dxl.DXL_HIBYTE(dxl.DXL_HIWORD(value)),
             ]
         return data
+
+    def broadcast_ping(
+        self, num_retry: int = 0, raise_on_error: bool = False
+    ) -> dict[int, list[int, int]] | None:
+        for _ in range(1 + num_retry):
+            data_list, comm = self.packet_handler.broadcastPing(self.port_handler)
+            if self._is_comm_success(comm):
+                return data_list
+
+        if raise_on_error:
+            raise ConnectionError(f"Broadcast ping returned a {comm} comm error.")
diff --git a/lerobot/common/motors/feetech/feetech.py b/lerobot/common/motors/feetech/feetech.py
index 98144473..78c30045 100644
--- a/lerobot/common/motors/feetech/feetech.py
+++ b/lerobot/common/motors/feetech/feetech.py
@@ -71,11 +71,11 @@ class FeetechMotorsBus(MotorsBus):
         self._comm_success = scs.COMM_SUCCESS
         self._no_error = 0x00
 
-    def broadcast_ping(
-        self, num_retry: int = 0, raise_on_error: bool = False
-    ) -> dict[int, list[int, int]] | None:
-        # TODO
-        raise NotImplementedError
+    def _configure_motors(self) -> None:
+        # By default, Feetech motors have a 500µs delay response time (corresponding to a value of 250 on the
+        # 'Return_Delay' address). We ensure this is reduced to the minimum of 2µs (value of 0).
+        for id_ in self.ids:
+            self.write("Return_Delay", id_, 0)
 
     def _calibrate_values(self, ids_values: dict[int, int]) -> dict[int, float]:
         # TODO
@@ -114,3 +114,9 @@ class FeetechMotorsBus(MotorsBus):
                 scs.SCS_HIBYTE(scs.SCS_HIWORD(value)),
             ]
         return data
+
+    def broadcast_ping(
+        self, num_retry: int = 0, raise_on_error: bool = False
+    ) -> dict[int, list[int, int]] | None:
+        # TODO
+        raise NotImplementedError
diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py
index 8329c0a0..25b01c5d 100644
--- a/lerobot/common/motors/motors_bus.py
+++ b/lerobot/common/motors/motors_bus.py
@@ -351,6 +351,10 @@ class MotorsBus(abc.ABC):
         self.set_timeout()
         logger.debug(f"{self.__class__.__name__} connected.")
 
+    @abc.abstractmethod
+    def _configure_motors(self) -> None:
+        pass
+
     def set_timeout(self, timeout_ms: int | None = None):
         timeout_ms = timeout_ms if timeout_ms is not None else self.default_timeout
         self.port_handler.setPacketTimeoutMillis(timeout_ms)
@@ -380,23 +384,6 @@ class MotorsBus(abc.ABC):
             logger.error(e)
             return False
 
-    def ping(self, motor: NameOrID, num_retry: int = 0, raise_on_error: bool = False) -> int | None:
-        idx = self._get_motor_id(motor)
-        for n_try in range(1 + num_retry):
-            model_number, comm, error = self.packet_handler.ping(self.port_handler, idx)
-            if self._is_comm_success(comm):
-                return model_number
-            logger.debug(f"ping failed for {idx=}: {n_try=} got {comm=} {error=}")
-
-        if raise_on_error:
-            raise ConnectionError(f"Ping motor {motor} returned a {error} error code.")
-
-    @abc.abstractmethod
-    def broadcast_ping(
-        self, num_retry: int = 0, raise_on_error: bool = False
-    ) -> dict[int, list[int, int]] | None:
-        pass
-
     def set_calibration(self, calibration_fpath: Path) -> None:
         with open(calibration_fpath) as f:
             calibration = json.load(f)
@@ -449,6 +436,23 @@ class MotorsBus(abc.ABC):
         """
         pass
 
+    def ping(self, motor: NameOrID, num_retry: int = 0, raise_on_error: bool = False) -> int | None:
+        idx = self._get_motor_id(motor)
+        for n_try in range(1 + num_retry):
+            model_number, comm, error = self.packet_handler.ping(self.port_handler, idx)
+            if self._is_comm_success(comm):
+                return model_number
+            logger.debug(f"ping failed for {idx=}: {n_try=} got {comm=} {error=}")
+
+        if raise_on_error:
+            raise ConnectionError(f"Ping motor {motor} returned a {error} error code.")
+
+    @abc.abstractmethod
+    def broadcast_ping(
+        self, num_retry: int = 0, raise_on_error: bool = False
+    ) -> dict[int, list[int, int]] | None:
+        pass
+
     @overload
     def sync_read(self, data_name: str, motors: None = ..., num_retry: int = ...) -> dict[str, Value]: ...
     @overload

From 1de75c46c0ffecef82a241577e8cf4796aabe33e Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Mon, 24 Mar 2025 20:42:43 +0100
Subject: [PATCH 118/171] Return models (str) with pings

---
 lerobot/common/motors/dynamixel/dynamixel.py | 27 ++++++++++++------
 lerobot/common/motors/motors_bus.py          | 27 ++++++++++++++----
 tests/mocks/mock_dynamixel.py                |  9 ++----
 tests/motors/test_dynamixel.py               | 30 +++++++-------------
 4 files changed, 54 insertions(+), 39 deletions(-)

diff --git a/lerobot/common/motors/dynamixel/dynamixel.py b/lerobot/common/motors/dynamixel/dynamixel.py
index c26114ad..30b33896 100644
--- a/lerobot/common/motors/dynamixel/dynamixel.py
+++ b/lerobot/common/motors/dynamixel/dynamixel.py
@@ -18,20 +18,22 @@
 # https://emanual.robotis.com/docs/en/dxl/protocol2/#fast-sync-read-0x8a
 # -> Need to check compatibility across models
 
+import logging
 from copy import deepcopy
 from enum import Enum
 
 from ..motors_bus import Motor, MotorsBus
-from .tables import MODEL_BAUDRATE_TABLE, MODEL_CONTROL_TABLE, MODEL_RESOLUTION
+from .tables import MODEL_BAUDRATE_TABLE, MODEL_CONTROL_TABLE, MODEL_NUMBER, MODEL_RESOLUTION
 
 PROTOCOL_VERSION = 2.0
 BAUDRATE = 1_000_000
 DEFAULT_TIMEOUT_MS = 1000
-MAX_ID_RANGE = 252
 
 CALIBRATION_REQUIRED = ["Goal_Position", "Present_Position"]
 CONVERT_UINT32_TO_INT32_REQUIRED = ["Goal_Position", "Present_Position"]
 
+logger = logging.getLogger(__name__)
+
 
 class OperatingMode(Enum):
     # DYNAMIXEL only controls current(torque) regardless of speed and position. This mode is ideal for a
@@ -73,6 +75,7 @@ class DynamixelMotorsBus(MotorsBus):
     model_ctrl_table = deepcopy(MODEL_CONTROL_TABLE)
     model_resolution_table = deepcopy(MODEL_RESOLUTION)
     model_baudrate_table = deepcopy(MODEL_BAUDRATE_TABLE)
+    model_number_table = deepcopy(MODEL_NUMBER)
     calibration_required = deepcopy(CALIBRATION_REQUIRED)
     default_timeout = DEFAULT_TIMEOUT_MS
 
@@ -135,13 +138,19 @@ class DynamixelMotorsBus(MotorsBus):
             ]
         return data
 
-    def broadcast_ping(
-        self, num_retry: int = 0, raise_on_error: bool = False
-    ) -> dict[int, list[int, int]] | None:
-        for _ in range(1 + num_retry):
+    def broadcast_ping(self, num_retry: int = 0, raise_on_error: bool = False) -> dict[int, str] | None:
+        for n_try in range(1 + num_retry):
             data_list, comm = self.packet_handler.broadcastPing(self.port_handler)
             if self._is_comm_success(comm):
-                return data_list
+                break
+            logger.debug(f"Broadcast failed on port '{self.port}' ({n_try=})")
+            logger.debug(self.packet_handler.getRxPacketError(comm))
 
-        if raise_on_error:
-            raise ConnectionError(f"Broadcast ping returned a {comm} comm error.")
+        if not self._is_comm_success(comm):
+            if raise_on_error:
+                logger.error(self.packet_handler.getRxPacketError(comm))
+                raise ConnectionError
+
+            return data_list if data_list else None
+
+        return {id_: self._model_nb_to_model(data[0]) for id_, data in data_list.items()}
diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py
index 25b01c5d..a63393ec 100644
--- a/lerobot/common/motors/motors_bus.py
+++ b/lerobot/common/motors/motors_bus.py
@@ -242,6 +242,7 @@ class MotorsBus(abc.ABC):
     model_ctrl_table: dict[str, dict]
     model_resolution_table: dict[str, int]
     model_baudrate_table: dict[str, dict]
+    model_number_table: dict[str, int]
     calibration_required: list[str]
     default_timeout: int
 
@@ -265,6 +266,7 @@ class MotorsBus(abc.ABC):
 
         self._id_to_model_dict = {m.id: m.model for m in self.motors.values()}
         self._id_to_name_dict = {m.id: name for name, m in self.motors.items()}
+        self._model_nb_to_model_dict = {v: k for k, v in self.model_number_table.items()}
 
     def __len__(self):
         return len(self.motors)
@@ -297,6 +299,9 @@ class MotorsBus(abc.ABC):
     def ids(self) -> list[int]:
         return [m.id for m in self.motors.values()]
 
+    def _model_nb_to_model(self, motor_nb: int) -> str:
+        return self._model_nb_to_model_dict[motor_nb]
+
     def _id_to_model(self, motor_id: int) -> str:
         return self._id_to_model_dict[motor_id]
 
@@ -436,21 +441,33 @@ class MotorsBus(abc.ABC):
         """
         pass
 
-    def ping(self, motor: NameOrID, num_retry: int = 0, raise_on_error: bool = False) -> int | None:
+    def ping(self, motor: NameOrID, num_retry: int = 0, raise_on_error: bool = False) -> str | None:
         idx = self._get_motor_id(motor)
         for n_try in range(1 + num_retry):
             model_number, comm, error = self.packet_handler.ping(self.port_handler, idx)
             if self._is_comm_success(comm):
-                return model_number
+                break
             logger.debug(f"ping failed for {idx=}: {n_try=} got {comm=} {error=}")
 
-        if raise_on_error:
-            raise ConnectionError(f"Ping motor {motor} returned a {error} error code.")
+        if not self._is_comm_success(comm):
+            if raise_on_error:
+                logger.error(self.packet_handler.getRxPacketError(comm))
+                raise ConnectionError
+            else:
+                return
+        if self._is_error(error):
+            if raise_on_error:
+                logger.error(self.packet_handler.getTxRxResult(comm))
+                raise ConnectionError
+            else:
+                return
+
+        return self._model_nb_to_model(model_number)
 
     @abc.abstractmethod
     def broadcast_ping(
         self, num_retry: int = 0, raise_on_error: bool = False
-    ) -> dict[int, list[int, int]] | None:
+    ) -> dict[int, list[int, str]] | None:
         pass
 
     @overload
diff --git a/tests/mocks/mock_dynamixel.py b/tests/mocks/mock_dynamixel.py
index a7bcf30d..4159af3d 100644
--- a/tests/mocks/mock_dynamixel.py
+++ b/tests/mocks/mock_dynamixel.py
@@ -441,16 +441,13 @@ class MockMotors(MockSerial):
         return new_stub
 
     def build_broadcast_ping_stub(
-        self, ids_models_firmwares: dict[int, list[int]] | None = None, num_invalid_try: int = 0
+        self, ids_models: dict[int, list[int]] | None = None, num_invalid_try: int = 0
     ) -> str:
         ping_request = MockInstructionPacket.ping(dxl.BROADCAST_ID)
-        return_packets = b"".join(
-            MockStatusPacket.ping(idx, model, firm_ver)
-            for idx, (model, firm_ver) in ids_models_firmwares.items()
-        )
+        return_packets = b"".join(MockStatusPacket.ping(idx, model) for idx, model in ids_models.items())
         ping_response = self._build_send_fn(return_packets, num_invalid_try)
 
-        stub_name = "Ping_" + "_".join([str(idx) for idx in ids_models_firmwares])
+        stub_name = "Ping_" + "_".join([str(idx) for idx in ids_models])
         self.stub(
             name=stub_name,
             receive_bytes=ping_request,
diff --git a/tests/motors/test_dynamixel.py b/tests/motors/test_dynamixel.py
index 7fdd2618..73fb40aa 100644
--- a/tests/motors/test_dynamixel.py
+++ b/tests/motors/test_dynamixel.py
@@ -6,7 +6,7 @@ import dynamixel_sdk as dxl
 import pytest
 
 from lerobot.common.motors import CalibrationMode, Motor
-from lerobot.common.motors.dynamixel import DynamixelMotorsBus
+from lerobot.common.motors.dynamixel import MODEL_NUMBER, DynamixelMotorsBus
 from tests.mocks.mock_dynamixel import MockMotors, MockPortHandler
 
 
@@ -92,15 +92,10 @@ def test_abc_implementation(dummy_motors):
     DynamixelMotorsBus(port="/dev/dummy-port", motors=dummy_motors)
 
 
-@pytest.mark.parametrize(
-    "idx, model_nb",
-    [
-        (1, 1190),
-        (2, 1200),
-        (3, 1120),
-    ],
-)
-def test_ping(idx, model_nb, mock_motors, dummy_motors):
+@pytest.mark.parametrize("idx", [1, 2, 3])
+def test_ping(idx, mock_motors, dummy_motors):
+    expected_model = dummy_motors[f"dummy_{idx}"].model
+    model_nb = MODEL_NUMBER[expected_model]
     stub_name = mock_motors.build_ping_stub(idx, model_nb)
     motors_bus = DynamixelMotorsBus(
         port=mock_motors.port,
@@ -110,26 +105,23 @@ def test_ping(idx, model_nb, mock_motors, dummy_motors):
 
     ping_model_nb = motors_bus.ping(idx)
 
-    assert ping_model_nb == model_nb
+    assert ping_model_nb == expected_model
     assert mock_motors.stubs[stub_name].called
 
 
 def test_broadcast_ping(mock_motors, dummy_motors):
-    expected_pings = {
-        1: [1060, 50],
-        2: [1120, 30],
-        3: [1190, 10],
-    }
-    stub_name = mock_motors.build_broadcast_ping_stub(expected_pings)
+    expected_models = {m.id: m.model for m in dummy_motors.values()}
+    model_nbs = {id_: MODEL_NUMBER[model] for id_, model in expected_models.items()}
+    stub_name = mock_motors.build_broadcast_ping_stub(model_nbs)
     motors_bus = DynamixelMotorsBus(
         port=mock_motors.port,
         motors=dummy_motors,
     )
     motors_bus.connect()
 
-    ping_list = motors_bus.broadcast_ping()
+    ping_model_nbs = motors_bus.broadcast_ping()
 
-    assert ping_list == expected_pings
+    assert ping_model_nbs == expected_models
     assert mock_motors.stubs[stub_name].called
 
 

From 7c8ab8e2d6597a7d111974b1fe5befe0b6dbbb63 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Mon, 24 Mar 2025 20:46:36 +0100
Subject: [PATCH 119/171] Implement feetech broadcast ping

---
 lerobot/common/motors/feetech/feetech.py | 105 +++++++++++++++++++++--
 lerobot/common/motors/feetech/tables.py  |   8 +-
 tests/mocks/mock_feetech.py              |   9 +-
 tests/motors/test_feetech.py             |  30 +++----
 4 files changed, 120 insertions(+), 32 deletions(-)

diff --git a/lerobot/common/motors/feetech/feetech.py b/lerobot/common/motors/feetech/feetech.py
index 78c30045..849136a9 100644
--- a/lerobot/common/motors/feetech/feetech.py
+++ b/lerobot/common/motors/feetech/feetech.py
@@ -12,14 +12,17 @@
 # See the License for the specific language governing permissions and
 # limitations under the License.
 
+import logging
 from copy import deepcopy
 from enum import Enum
+from pprint import pformat
 
 from ..motors_bus import Motor, MotorsBus
 from .tables import (
     CALIBRATION_REQUIRED,
     MODEL_BAUDRATE_TABLE,
     MODEL_CONTROL_TABLE,
+    MODEL_NUMBER,
     MODEL_RESOLUTION,
 )
 
@@ -27,7 +30,7 @@ PROTOCOL_VERSION = 0
 BAUDRATE = 1_000_000
 DEFAULT_TIMEOUT_MS = 1000
 
-MAX_ID_RANGE = 252
+logger = logging.getLogger(__name__)
 
 
 class OperatingMode(Enum):
@@ -53,6 +56,7 @@ class FeetechMotorsBus(MotorsBus):
     model_ctrl_table = deepcopy(MODEL_CONTROL_TABLE)
     model_resolution_table = deepcopy(MODEL_RESOLUTION)
     model_baudrate_table = deepcopy(MODEL_BAUDRATE_TABLE)
+    model_number_table = deepcopy(MODEL_NUMBER)
     calibration_required = deepcopy(CALIBRATION_REQUIRED)
     default_timeout = DEFAULT_TIMEOUT_MS
 
@@ -115,8 +119,97 @@ class FeetechMotorsBus(MotorsBus):
             ]
         return data
 
-    def broadcast_ping(
-        self, num_retry: int = 0, raise_on_error: bool = False
-    ) -> dict[int, list[int, int]] | None:
-        # TODO
-        raise NotImplementedError
+    def _broadcast_ping(self) -> tuple[dict[int, int], int]:
+        import scservo_sdk as scs
+
+        data_list = {}
+
+        status_length = 6
+
+        rx_length = 0
+        wait_length = status_length * scs.MAX_ID
+
+        txpacket = [0] * 6
+
+        tx_time_per_byte = (1000.0 / self.port_handler.getBaudRate()) * 10.0
+
+        txpacket[scs.PKT_ID] = scs.BROADCAST_ID
+        txpacket[scs.PKT_LENGTH] = 2
+        txpacket[scs.PKT_INSTRUCTION] = scs.INST_PING
+
+        result = self.packet_handler.txPacket(self.port_handler, txpacket)
+        if result != scs.COMM_SUCCESS:
+            self.port_handler.is_using = False
+            return data_list, result
+
+        # set rx timeout
+        self.port_handler.setPacketTimeoutMillis((wait_length * tx_time_per_byte) + (3.0 * scs.MAX_ID) + 16.0)
+
+        rxpacket = []
+        while True:
+            rxpacket += self.port_handler.readPort(wait_length - rx_length)
+            rx_length = len(rxpacket)
+
+            if self.port_handler.isPacketTimeout():  # or rx_length >= wait_length
+                break
+
+        self.port_handler.is_using = False
+
+        if rx_length == 0:
+            return data_list, scs.COMM_RX_TIMEOUT
+
+        while True:
+            if rx_length < status_length:
+                return data_list, scs.COMM_RX_CORRUPT
+
+            # find packet header
+            for idx in range(0, (rx_length - 1)):
+                if (rxpacket[idx] == 0xFF) and (rxpacket[idx + 1] == 0xFF):
+                    break
+
+            if idx == 0:  # found at the beginning of the packet
+                # calculate checksum
+                checksum = 0
+                for idx in range(2, status_length - 1):  # except header & checksum
+                    checksum += rxpacket[idx]
+
+                checksum = scs.SCS_LOBYTE(~checksum)
+                if rxpacket[status_length - 1] == checksum:
+                    result = scs.COMM_SUCCESS
+                    data_list[rxpacket[scs.PKT_ID]] = rxpacket[scs.PKT_ERROR]
+
+                    del rxpacket[0:status_length]
+                    rx_length = rx_length - status_length
+
+                    if rx_length == 0:
+                        return data_list, result
+                else:
+                    result = scs.COMM_RX_CORRUPT
+                    # remove header (0xFF 0xFF)
+                    del rxpacket[0:2]
+                    rx_length = rx_length - 2
+            else:
+                # remove unnecessary packets
+                del rxpacket[0:idx]
+                rx_length = rx_length - idx
+
+    def broadcast_ping(self, num_retry: int = 0, raise_on_error: bool = False) -> dict[int, str] | None:
+        for n_try in range(1 + num_retry):
+            ids_status, comm = self._broadcast_ping()
+            if self._is_comm_success(comm):
+                break
+            logger.debug(f"Broadcast failed on port '{self.port}' ({n_try=})")
+            logger.debug(self.packet_handler.getRxPacketError(comm))
+
+        if not self._is_comm_success(comm):
+            if raise_on_error:
+                raise ConnectionError
+
+            return ids_status if ids_status else None
+
+        ids_errors = {id_: status for id_, status in ids_status.items() if self._is_error(status)}
+        if ids_errors:
+            display_dict = {id_: self.packet_handler.getRxPacketError(err) for id_, err in ids_errors.items()}
+            logger.error(f"Some motors found returned an error status:\n{pformat(display_dict, indent=4)}")
+        model_numbers = self.sync_read("Model_Number", list(ids_status), num_retry)
+        return {id_: self._model_nb_to_model(model_nb) for id_, model_nb in model_numbers.items()}
diff --git a/lerobot/common/motors/feetech/tables.py b/lerobot/common/motors/feetech/tables.py
index 5de95b61..7e7e7e9d 100644
--- a/lerobot/common/motors/feetech/tables.py
+++ b/lerobot/common/motors/feetech/tables.py
@@ -2,7 +2,8 @@
 # https://docs.google.com/spreadsheets/d/1GVs7W1VS1PqdhA1nW-abeyAHhTUxKUdR/edit?usp=sharing&ouid=116566590112741600240&rtpof=true&sd=true
 # data_name: (address, size_byte)
 SCS_SERIES_CONTROL_TABLE = {
-    "Model": (3, 2),
+    "Firmware_Version": (0, 2),
+    "Model_Number": (3, 2),
     "ID": (5, 1),
     "Baud_Rate": (6, 1),
     "Return_Delay": (7, 1),
@@ -72,6 +73,11 @@ MODEL_RESOLUTION = {
     "sts3215": 4096,
 }
 
+# {model: model_number}
+MODEL_NUMBER = {
+    "sts3215": 777,
+}
+
 MODEL_BAUDRATE_TABLE = {
     "scs_series": SCS_SERIES_BAUDRATE_TABLE,
     "sts3215": SCS_SERIES_BAUDRATE_TABLE,
diff --git a/tests/mocks/mock_feetech.py b/tests/mocks/mock_feetech.py
index b1478a42..f938522e 100644
--- a/tests/mocks/mock_feetech.py
+++ b/tests/mocks/mock_feetech.py
@@ -295,16 +295,13 @@ class MockMotors(MockSerial):
         return new_stub
 
     def build_broadcast_ping_stub(
-        self, ids_models_firmwares: dict[int, list[int]] | None = None, num_invalid_try: int = 0
+        self, ids_models: dict[int, list[int]] | None = None, num_invalid_try: int = 0
     ) -> str:
         ping_request = MockInstructionPacket.ping(scs.BROADCAST_ID)
-        return_packets = b"".join(
-            MockStatusPacket.ping(idx, model, firm_ver)
-            for idx, (model, firm_ver) in ids_models_firmwares.items()
-        )
+        return_packets = b"".join(MockStatusPacket.ping(idx, model) for idx, model in ids_models.items())
         ping_response = self._build_send_fn(return_packets, num_invalid_try)
 
-        stub_name = "Ping_" + "_".join([str(idx) for idx in ids_models_firmwares])
+        stub_name = "Ping_" + "_".join([str(idx) for idx in ids_models])
         self.stub(
             name=stub_name,
             receive_bytes=ping_request,
diff --git a/tests/motors/test_feetech.py b/tests/motors/test_feetech.py
index 1b50d045..994e6944 100644
--- a/tests/motors/test_feetech.py
+++ b/tests/motors/test_feetech.py
@@ -6,7 +6,7 @@ import pytest
 import scservo_sdk as scs
 
 from lerobot.common.motors import CalibrationMode, Motor
-from lerobot.common.motors.feetech import FeetechMotorsBus
+from lerobot.common.motors.feetech import MODEL_NUMBER, FeetechMotorsBus
 from tests.mocks.mock_feetech import MockMotors, MockPortHandler
 
 
@@ -93,15 +93,10 @@ def test_abc_implementation(dummy_motors):
 
 
 @pytest.mark.skip("TODO")
-@pytest.mark.parametrize(
-    "idx, model_nb",
-    [
-        (1, 1190),
-        (2, 1200),
-        (3, 1120),
-    ],
-)
-def test_ping(idx, model_nb, mock_motors, dummy_motors):
+@pytest.mark.parametrize("idx", [1, 2, 3])
+def test_ping(idx, mock_motors, dummy_motors):
+    expected_model = dummy_motors[f"dummy_{idx}"].model
+    model_nb = MODEL_NUMBER[expected_model]
     stub_name = mock_motors.build_ping_stub(idx, model_nb)
     motors_bus = FeetechMotorsBus(
         port=mock_motors.port,
@@ -111,27 +106,24 @@ def test_ping(idx, model_nb, mock_motors, dummy_motors):
 
     ping_model_nb = motors_bus.ping(idx)
 
-    assert ping_model_nb == model_nb
+    assert ping_model_nb == expected_model
     assert mock_motors.stubs[stub_name].called
 
 
 @pytest.mark.skip("TODO")
 def test_broadcast_ping(mock_motors, dummy_motors):
-    expected_pings = {
-        1: [1060, 50],
-        2: [1120, 30],
-        3: [1190, 10],
-    }
-    stub_name = mock_motors.build_broadcast_ping_stub(expected_pings)
+    expected_models = {m.id: m.model for m in dummy_motors.values()}
+    model_nbs = {id_: MODEL_NUMBER[model] for id_, model in expected_models.items()}
+    stub_name = mock_motors.build_broadcast_ping_stub(model_nbs)
     motors_bus = FeetechMotorsBus(
         port=mock_motors.port,
         motors=dummy_motors,
     )
     motors_bus.connect()
 
-    ping_list = motors_bus.broadcast_ping()
+    ping_model_nbs = motors_bus.broadcast_ping()
 
-    assert ping_list == expected_pings
+    assert ping_model_nbs == expected_models
     assert mock_motors.stubs[stub_name].called
 
 

From c6212d585de741539040d064e533d6ead509ae8a Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Mon, 24 Mar 2025 20:56:58 +0100
Subject: [PATCH 120/171] Add raw_values option

---
 lerobot/common/motors/motors_bus.py | 30 +++++++++++++++++++++--------
 1 file changed, 22 insertions(+), 8 deletions(-)

diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py
index a63393ec..19af9a5d 100644
--- a/lerobot/common/motors/motors_bus.py
+++ b/lerobot/common/motors/motors_bus.py
@@ -471,13 +471,19 @@ class MotorsBus(abc.ABC):
         pass
 
     @overload
-    def sync_read(self, data_name: str, motors: None = ..., num_retry: int = ...) -> dict[str, Value]: ...
+    def sync_read(
+        self, data_name: str, motors: None = ..., raw_values: bool = ..., num_retry: int = ...
+    ) -> dict[str, Value]: ...
     @overload
     def sync_read(
-        self, data_name: str, motors: NameOrID | list[NameOrID], num_retry: int = ...
+        self, data_name: str, motors: NameOrID | list[NameOrID], raw_values: bool = ..., num_retry: int = ...
     ) -> dict[NameOrID, Value]: ...
     def sync_read(
-        self, data_name: str, motors: NameOrID | list[NameOrID] | None = None, num_retry: int = 0
+        self,
+        data_name: str,
+        motors: NameOrID | list[NameOrID] | None = None,
+        raw_values: bool = False,
+        num_retry: int = 0,
     ) -> dict[NameOrID, Value]:
         if not self.is_connected:
             raise DeviceNotConnectedError(
@@ -503,7 +509,7 @@ class MotorsBus(abc.ABC):
                 f"{self.packet_handler.getTxRxResult(comm)}"
             )
 
-        if data_name in self.calibration_required and self.calibration is not None:
+        if not raw_values and data_name in self.calibration_required and self.calibration is not None:
             ids_values = self._calibrate_values(ids_values)
 
         return {id_key_map[idx]: val for idx, val in ids_values.items()}
@@ -551,7 +557,13 @@ class MotorsBus(abc.ABC):
     #     for idx in motor_ids:
     #         value = self.reader.getData(idx, address, n_bytes)
 
-    def sync_write(self, data_name: str, values: Value | dict[NameOrID, Value], num_retry: int = 0) -> None:
+    def sync_write(
+        self,
+        data_name: str,
+        values: Value | dict[NameOrID, Value],
+        raw_values: bool = False,
+        num_retry: int = 0,
+    ) -> None:
         if not self.is_connected:
             raise DeviceNotConnectedError(
                 f"{self.__class__.__name__}('{self.port}') is not connected. You need to run `{self.__class__.__name__}.connect()`."
@@ -564,7 +576,7 @@ class MotorsBus(abc.ABC):
         else:
             raise ValueError(f"'values' is expected to be a single value or a dict. Got {values}")
 
-        if data_name in self.calibration_required and self.calibration is not None:
+        if not raw_values and data_name in self.calibration_required and self.calibration is not None:
             ids_values = self._uncalibrate_values(ids_values)
 
         comm = self._sync_write(data_name, ids_values, num_retry)
@@ -602,7 +614,9 @@ class MotorsBus(abc.ABC):
             data = self._split_int_to_bytes(value, n_bytes)
             self.sync_writer.addParam(idx, data)
 
-    def write(self, data_name: str, motor: NameOrID, value: Value, num_retry: int = 0) -> None:
+    def write(
+        self, data_name: str, motor: NameOrID, value: Value, raw_value: bool = False, num_retry: int = 0
+    ) -> None:
         if not self.is_connected:
             raise DeviceNotConnectedError(
                 f"{self.__class__.__name__}('{self.port}') is not connected. You need to run `{self.__class__.__name__}.connect()`."
@@ -610,7 +624,7 @@ class MotorsBus(abc.ABC):
 
         idx = self._get_motor_id(motor)
 
-        if data_name in self.calibration_required and self.calibration is not None:
+        if not raw_value and data_name in self.calibration_required and self.calibration is not None:
             id_value = self._uncalibrate_values({idx: value})
             value = id_value[idx]
 

From 0c1d4cb3239ddf580c528d04da570b1b068c5ccc Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Mon, 24 Mar 2025 20:58:56 +0100
Subject: [PATCH 121/171] Rename idx -> id_

---
 lerobot/common/motors/feetech/feetech.py | 14 ++++-----
 lerobot/common/motors/motors_bus.py      | 40 ++++++++++++------------
 2 files changed, 27 insertions(+), 27 deletions(-)

diff --git a/lerobot/common/motors/feetech/feetech.py b/lerobot/common/motors/feetech/feetech.py
index 849136a9..45fcff89 100644
--- a/lerobot/common/motors/feetech/feetech.py
+++ b/lerobot/common/motors/feetech/feetech.py
@@ -163,15 +163,15 @@ class FeetechMotorsBus(MotorsBus):
                 return data_list, scs.COMM_RX_CORRUPT
 
             # find packet header
-            for idx in range(0, (rx_length - 1)):
-                if (rxpacket[idx] == 0xFF) and (rxpacket[idx + 1] == 0xFF):
+            for id_ in range(0, (rx_length - 1)):
+                if (rxpacket[id_] == 0xFF) and (rxpacket[id_ + 1] == 0xFF):
                     break
 
-            if idx == 0:  # found at the beginning of the packet
+            if id_ == 0:  # found at the beginning of the packet
                 # calculate checksum
                 checksum = 0
-                for idx in range(2, status_length - 1):  # except header & checksum
-                    checksum += rxpacket[idx]
+                for id_ in range(2, status_length - 1):  # except header & checksum
+                    checksum += rxpacket[id_]
 
                 checksum = scs.SCS_LOBYTE(~checksum)
                 if rxpacket[status_length - 1] == checksum:
@@ -190,8 +190,8 @@ class FeetechMotorsBus(MotorsBus):
                     rx_length = rx_length - 2
             else:
                 # remove unnecessary packets
-                del rxpacket[0:idx]
-                rx_length = rx_length - idx
+                del rxpacket[0:id_]
+                rx_length = rx_length - id_
 
     def broadcast_ping(self, num_retry: int = 0, raise_on_error: bool = False) -> dict[int, str] | None:
         for n_try in range(1 + num_retry):
diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py
index 19af9a5d..7946ac44 100644
--- a/lerobot/common/motors/motors_bus.py
+++ b/lerobot/common/motors/motors_bus.py
@@ -393,7 +393,7 @@ class MotorsBus(abc.ABC):
         with open(calibration_fpath) as f:
             calibration = json.load(f)
 
-        self.calibration = {int(idx): val for idx, val in calibration.items()}
+        self.calibration = {int(id_): val for id_, val in calibration.items()}
 
     @abc.abstractmethod
     def _calibrate_values(self, ids_values: dict[int, int]) -> dict[int, float]:
@@ -442,12 +442,12 @@ class MotorsBus(abc.ABC):
         pass
 
     def ping(self, motor: NameOrID, num_retry: int = 0, raise_on_error: bool = False) -> str | None:
-        idx = self._get_motor_id(motor)
+        id_ = self._get_motor_id(motor)
         for n_try in range(1 + num_retry):
-            model_number, comm, error = self.packet_handler.ping(self.port_handler, idx)
+            model_number, comm, error = self.packet_handler.ping(self.port_handler, id_)
             if self._is_comm_success(comm):
                 break
-            logger.debug(f"ping failed for {idx=}: {n_try=} got {comm=} {error=}")
+            logger.debug(f"ping failed for {id_=}: {n_try=} got {comm=} {error=}")
 
         if not self._is_comm_success(comm):
             if raise_on_error:
@@ -512,13 +512,13 @@ class MotorsBus(abc.ABC):
         if not raw_values and data_name in self.calibration_required and self.calibration is not None:
             ids_values = self._calibrate_values(ids_values)
 
-        return {id_key_map[idx]: val for idx, val in ids_values.items()}
+        return {id_key_map[id_]: val for id_, val in ids_values.items()}
 
     def _sync_read(
         self, data_name: str, motor_ids: list[str], num_retry: int = 0
     ) -> tuple[int, dict[int, int]]:
         if self._has_different_ctrl_tables:
-            models = [self._id_to_model(idx) for idx in motor_ids]
+            models = [self._id_to_model(id_) for id_ in motor_ids]
             assert_same_address(self.model_ctrl_table, models, data_name)
 
         model = self._id_to_model(next(iter(motor_ids)))
@@ -537,15 +537,15 @@ class MotorsBus(abc.ABC):
             logger.debug(f"Failed to sync read '{data_name}' ({addr=} {n_bytes=}) on {motor_ids=} ({n_try=})")
             logger.debug(self.packet_handler.getRxPacketError(comm))
 
-        values = {idx: self.sync_reader.getData(idx, addr, n_bytes) for idx in motor_ids}
+        values = {id_: self.sync_reader.getData(id_, addr, n_bytes) for id_ in motor_ids}
         return comm, values
 
     def _setup_sync_reader(self, motor_ids: list[str], addr: int, n_bytes: int) -> None:
         self.sync_reader.clearParam()
         self.sync_reader.start_address = addr
         self.sync_reader.data_length = n_bytes
-        for idx in motor_ids:
-            self.sync_reader.addParam(idx)
+        for id_ in motor_ids:
+            self.sync_reader.addParam(id_)
 
     # TODO(aliberts, pkooij): Implementing something like this could get even much faster read times if need be.
     # Would have to handle the logic of checking if a packet has been sent previously though but doable.
@@ -554,8 +554,8 @@ class MotorsBus(abc.ABC):
     # def _async_read(self, motor_ids: list[str], address: int, n_bytes: int):
     #     self.reader.rxPacket()
     #     self.reader.txPacket()
-    #     for idx in motor_ids:
-    #         value = self.reader.getData(idx, address, n_bytes)
+    #     for id_ in motor_ids:
+    #         value = self.reader.getData(id_, address, n_bytes)
 
     def sync_write(
         self,
@@ -588,7 +588,7 @@ class MotorsBus(abc.ABC):
 
     def _sync_write(self, data_name: str, ids_values: dict[int, int], num_retry: int = 0) -> int:
         if self._has_different_ctrl_tables:
-            models = [self._id_to_model(idx) for idx in ids_values]
+            models = [self._id_to_model(id_) for id_ in ids_values]
             assert_same_address(self.model_ctrl_table, models, data_name)
 
         model = self._id_to_model(next(iter(ids_values)))
@@ -610,9 +610,9 @@ class MotorsBus(abc.ABC):
         self.sync_writer.clearParam()
         self.sync_writer.start_address = addr
         self.sync_writer.data_length = n_bytes
-        for idx, value in ids_values.items():
+        for id_, value in ids_values.items():
             data = self._split_int_to_bytes(value, n_bytes)
-            self.sync_writer.addParam(idx, data)
+            self.sync_writer.addParam(id_, data)
 
     def write(
         self, data_name: str, motor: NameOrID, value: Value, raw_value: bool = False, num_retry: int = 0
@@ -622,21 +622,21 @@ class MotorsBus(abc.ABC):
                 f"{self.__class__.__name__}('{self.port}') is not connected. You need to run `{self.__class__.__name__}.connect()`."
             )
 
-        idx = self._get_motor_id(motor)
+        id_ = self._get_motor_id(motor)
 
         if not raw_value and data_name in self.calibration_required and self.calibration is not None:
-            id_value = self._uncalibrate_values({idx: value})
-            value = id_value[idx]
+            id_value = self._uncalibrate_values({id_: value})
+            value = id_value[id_]
 
-        comm, error = self._write(data_name, idx, value, num_retry)
+        comm, error = self._write(data_name, id_, value, num_retry)
         if not self._is_comm_success(comm):
             raise ConnectionError(
-                f"Failed to write '{data_name}' on {idx=} with '{value}' after {num_retry + 1} tries."
+                f"Failed to write '{data_name}' on {id_=} with '{value}' after {num_retry + 1} tries."
                 f"\n{self.packet_handler.getTxRxResult(comm)}"
             )
         elif self._is_error(error):
             raise RuntimeError(
-                f"Failed to write '{data_name}' on {idx=} with '{value}' after {num_retry + 1} tries."
+                f"Failed to write '{data_name}' on {id_=} with '{value}' after {num_retry + 1} tries."
                 f"\n{self.packet_handler.getRxPacketError(error)}"
             )
 

From 7a75bb9f61ed3b30457051f8e01f93c198f22679 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Mon, 24 Mar 2025 21:13:26 +0100
Subject: [PATCH 122/171] Improve errors

---
 lerobot/common/motors/dynamixel/dynamixel.py | 3 +--
 lerobot/common/motors/feetech/feetech.py     | 2 +-
 lerobot/common/motors/motors_bus.py          | 6 ++----
 3 files changed, 4 insertions(+), 7 deletions(-)

diff --git a/lerobot/common/motors/dynamixel/dynamixel.py b/lerobot/common/motors/dynamixel/dynamixel.py
index 30b33896..affe774b 100644
--- a/lerobot/common/motors/dynamixel/dynamixel.py
+++ b/lerobot/common/motors/dynamixel/dynamixel.py
@@ -148,8 +148,7 @@ class DynamixelMotorsBus(MotorsBus):
 
         if not self._is_comm_success(comm):
             if raise_on_error:
-                logger.error(self.packet_handler.getRxPacketError(comm))
-                raise ConnectionError
+                raise ConnectionError(self.packet_handler.getRxPacketError(comm))
 
             return data_list if data_list else None
 
diff --git a/lerobot/common/motors/feetech/feetech.py b/lerobot/common/motors/feetech/feetech.py
index 45fcff89..67f56efd 100644
--- a/lerobot/common/motors/feetech/feetech.py
+++ b/lerobot/common/motors/feetech/feetech.py
@@ -203,7 +203,7 @@ class FeetechMotorsBus(MotorsBus):
 
         if not self._is_comm_success(comm):
             if raise_on_error:
-                raise ConnectionError
+                raise ConnectionError(self.packet_handler.getRxPacketError(comm))
 
             return ids_status if ids_status else None
 
diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py
index 7946ac44..224726e7 100644
--- a/lerobot/common/motors/motors_bus.py
+++ b/lerobot/common/motors/motors_bus.py
@@ -451,14 +451,12 @@ class MotorsBus(abc.ABC):
 
         if not self._is_comm_success(comm):
             if raise_on_error:
-                logger.error(self.packet_handler.getRxPacketError(comm))
-                raise ConnectionError
+                raise ConnectionError(self.packet_handler.getRxPacketError(comm))
             else:
                 return
         if self._is_error(error):
             if raise_on_error:
-                logger.error(self.packet_handler.getTxRxResult(comm))
-                raise ConnectionError
+                raise RuntimeError(self.packet_handler.getTxRxResult(comm))
             else:
                 return
 

From 4293b6a4fbd67d84813971ac36b43fa2fda1febe Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Tue, 25 Mar 2025 07:26:34 +0100
Subject: [PATCH 123/171] Fix feetech ping tests

---
 tests/mocks/mock_feetech.py  | 111 ++++++++++++++++++++++++++---------
 tests/motors/test_feetech.py |  15 +++--
 2 files changed, 93 insertions(+), 33 deletions(-)

diff --git a/tests/mocks/mock_feetech.py b/tests/mocks/mock_feetech.py
index f938522e..fc5422ed 100644
--- a/tests/mocks/mock_feetech.py
+++ b/tests/mocks/mock_feetech.py
@@ -89,8 +89,31 @@ class MockInstructionPacket(MockFeetechPacket):
 
         No parameters required.
         """
-        params, length = [], 2
-        return cls.build(scs_id=scs_id, params=params, length=length, instruct_type="Ping")
+        return cls.build(scs_id=scs_id, params=[], length=2, instruct_type="Ping")
+
+    @classmethod
+    def read(
+        cls,
+        scs_id: int,
+        start_address: int,
+        data_length: int,
+    ) -> bytes:
+        """
+        Builds a "Read" instruction.
+
+        The parameters for Read are:
+            param[0]   = start_address
+            param[1]   = data_length
+
+        And 'length' = 4, where:
+            +1 is for instruction byte,
+            +1 is for the address byte,
+            +1 is for the length bytes,
+            +1 is for the checksum at the end.
+        """
+        params = [start_address, data_length]
+        length = 4
+        return cls.build(scs_id=scs_id, params=params, length=length, instruct_type="Read")
 
     @classmethod
     def sync_read(
@@ -211,23 +234,17 @@ class MockStatusPacket(MockFeetechPacket):
         ]  # fmt: skip
 
     @classmethod
-    def ping(cls, scs_id: int, model_nb: int = 1190, firm_ver: int = 50) -> bytes:
+    def ping(cls, scs_id: int, error: str = "Success") -> bytes:
         """Builds a 'Ping' status packet.
 
         Args:
             scs_id (int): ID of the servo responding.
-            model_nb (int, optional): Desired 'model number' to be returned in the packet. Defaults to 1190
-                which corresponds to a XL330-M077-T.
-            firm_ver (int, optional): Desired 'firmware version' to be returned in the packet.
-                Defaults to 50.
+            error (str, optional): Error to be returned. Defaults to "Success".
 
         Returns:
             bytes: The raw 'Ping' status packet ready to be sent through serial.
         """
-        # raise NotImplementedError
-        params = [scs.SCS_LOBYTE(model_nb), scs.SCS_HIBYTE(model_nb), firm_ver]
-        length = 2
-        return cls.build(scs_id, params=params, length=length)
+        return cls.build(scs_id, params=[], length=2, error=error)
 
     @classmethod
     def present_position(cls, scs_id: int, pos: int | None = None, min_max_range: tuple = (0, 4095)) -> bytes:
@@ -248,6 +265,24 @@ class MockStatusPacket(MockFeetechPacket):
         length = 4
         return cls.build(scs_id, params=params, length=length)
 
+    @classmethod
+    def model_number(cls, scs_id: int, model_nb: int | None = None) -> bytes:
+        """Builds a 'Present_Position' status packet.
+
+        Args:
+            scs_id (int): List of the servos ids.
+            pos (int | None, optional): Desired 'Present_Position' to be returned in the packet. If None, it
+                will use a random value in the min_max_range. Defaults to None.
+            min_max_range (tuple, optional): Min/max range to generate the position values used for when 'pos'
+                is None. Note that the bounds are included in the range. Defaults to (0, 4095).
+
+        Returns:
+            bytes: The raw 'Present_Position' status packet ready to be sent through serial.
+        """
+        params = [scs.SCS_LOBYTE(model_nb), scs.SCS_HIBYTE(model_nb)]
+        length = 4
+        return cls.build(scs_id, params=params, length=length)
+
 
 class MockPortHandler(scs.PortHandler):
     """
@@ -294,14 +329,11 @@ class MockMotors(MockSerial):
         self._MockSerial__stubs[name or new_stub.receive_bytes] = new_stub
         return new_stub
 
-    def build_broadcast_ping_stub(
-        self, ids_models: dict[int, list[int]] | None = None, num_invalid_try: int = 0
-    ) -> str:
+    def build_broadcast_ping_stub(self, ids: list[int] | None = None, num_invalid_try: int = 0) -> str:
         ping_request = MockInstructionPacket.ping(scs.BROADCAST_ID)
-        return_packets = b"".join(MockStatusPacket.ping(idx, model) for idx, model in ids_models.items())
+        return_packets = b"".join(MockStatusPacket.ping(idx) for idx in ids)
         ping_response = self._build_send_fn(return_packets, num_invalid_try)
-
-        stub_name = "Ping_" + "_".join([str(idx) for idx in ids_models])
+        stub_name = "Ping_" + "_".join([str(idx) for idx in ids])
         self.stub(
             name=stub_name,
             receive_bytes=ping_request,
@@ -309,11 +341,9 @@ class MockMotors(MockSerial):
         )
         return stub_name
 
-    def build_ping_stub(
-        self, scs_id: int, model_nb: int, firm_ver: int = 50, num_invalid_try: int = 0
-    ) -> str:
+    def build_ping_stub(self, scs_id: int, num_invalid_try: int = 0) -> str:
         ping_request = MockInstructionPacket.ping(scs_id)
-        return_packet = MockStatusPacket.ping(scs_id, model_nb, firm_ver)
+        return_packet = MockStatusPacket.ping(scs_id)
         ping_response = self._build_send_fn(return_packet, num_invalid_try)
         stub_name = f"Ping_{scs_id}"
         self.stub(
@@ -323,21 +353,48 @@ class MockMotors(MockSerial):
         )
         return stub_name
 
+    def build_read_stub(
+        self, data_name: str, scs_id: int, value: int | None = None, num_invalid_try: int = 0
+    ) -> str:
+        """
+        'data_name' supported:
+            - Model_Number
+        """
+        if data_name != "Model_Number":
+            raise NotImplementedError
+        address, length = self.ctrl_table[data_name]
+        read_request = MockInstructionPacket.read(scs_id, address, length)
+        return_packet = MockStatusPacket.model_number(scs_id, value)
+        read_response = self._build_send_fn(return_packet, num_invalid_try)
+        stub_name = f"Read_{data_name}_{scs_id}"
+        self.stub(
+            name=stub_name,
+            receive_bytes=read_request,
+            send_fn=read_response,
+        )
+        return stub_name
+
     def build_sync_read_stub(
         self, data_name: str, ids_values: dict[int, int] | None = None, num_invalid_try: int = 0
     ) -> str:
         """
         'data_name' supported:
             - Present_Position
+            - Model_Number
         """
-        if data_name != "Present_Position":
-            raise NotImplementedError
-
         address, length = self.ctrl_table[data_name]
         sync_read_request = MockInstructionPacket.sync_read(list(ids_values), address, length)
-        return_packets = b"".join(
-            MockStatusPacket.present_position(idx, pos) for idx, pos in ids_values.items()
-        )
+        if data_name == "Present_Position":
+            return_packets = b"".join(
+                MockStatusPacket.present_position(idx, pos) for idx, pos in ids_values.items()
+            )
+        elif data_name == "Model_Number":
+            return_packets = b"".join(
+                MockStatusPacket.model_number(idx, model_nb) for idx, model_nb in ids_values.items()
+            )
+        else:
+            raise NotImplementedError
+
         sync_read_response = self._build_send_fn(return_packets, num_invalid_try)
         stub_name = f"Sync_Read_{data_name}_" + "_".join([str(idx) for idx in ids_values])
         self.stub(
diff --git a/tests/motors/test_feetech.py b/tests/motors/test_feetech.py
index 994e6944..bed0957f 100644
--- a/tests/motors/test_feetech.py
+++ b/tests/motors/test_feetech.py
@@ -92,12 +92,13 @@ def test_abc_implementation(dummy_motors):
     FeetechMotorsBus(port="/dev/dummy-port", motors=dummy_motors)
 
 
-@pytest.mark.skip("TODO")
+# @pytest.mark.skip("TODO")
 @pytest.mark.parametrize("idx", [1, 2, 3])
 def test_ping(idx, mock_motors, dummy_motors):
     expected_model = dummy_motors[f"dummy_{idx}"].model
     model_nb = MODEL_NUMBER[expected_model]
-    stub_name = mock_motors.build_ping_stub(idx, model_nb)
+    ping_stub = mock_motors.build_ping_stub(idx)
+    mobel_nb_stub = mock_motors.build_read_stub("Model_Number", idx, model_nb)
     motors_bus = FeetechMotorsBus(
         port=mock_motors.port,
         motors=dummy_motors,
@@ -107,14 +108,15 @@ def test_ping(idx, mock_motors, dummy_motors):
     ping_model_nb = motors_bus.ping(idx)
 
     assert ping_model_nb == expected_model
-    assert mock_motors.stubs[stub_name].called
+    assert mock_motors.stubs[ping_stub].called
+    assert mock_motors.stubs[mobel_nb_stub].called
 
 
-@pytest.mark.skip("TODO")
 def test_broadcast_ping(mock_motors, dummy_motors):
     expected_models = {m.id: m.model for m in dummy_motors.values()}
     model_nbs = {id_: MODEL_NUMBER[model] for id_, model in expected_models.items()}
-    stub_name = mock_motors.build_broadcast_ping_stub(model_nbs)
+    ping_stub = mock_motors.build_broadcast_ping_stub(list(model_nbs))
+    mobel_nb_stub = mock_motors.build_sync_read_stub("Model_Number", model_nbs)
     motors_bus = FeetechMotorsBus(
         port=mock_motors.port,
         motors=dummy_motors,
@@ -124,7 +126,8 @@ def test_broadcast_ping(mock_motors, dummy_motors):
     ping_model_nbs = motors_bus.broadcast_ping()
 
     assert ping_model_nbs == expected_models
-    assert mock_motors.stubs[stub_name].called
+    assert mock_motors.stubs[ping_stub].called
+    assert mock_motors.stubs[mobel_nb_stub].called
 
 
 def test_sync_read_none(mock_motors, dummy_motors):

From cf963eb1b0fbc929b765ee75b1aba2df19188d31 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Tue, 25 Mar 2025 11:12:26 +0100
Subject: [PATCH 124/171] Ensure motors exist at connection time

---
 lerobot/common/motors/dynamixel/dynamixel.py |  4 +-
 lerobot/common/motors/feetech/feetech.py     | 14 ++-
 lerobot/common/motors/motors_bus.py          | 95 ++++++++++++++------
 3 files changed, 80 insertions(+), 33 deletions(-)

diff --git a/lerobot/common/motors/dynamixel/dynamixel.py b/lerobot/common/motors/dynamixel/dynamixel.py
index affe774b..11094f60 100644
--- a/lerobot/common/motors/dynamixel/dynamixel.py
+++ b/lerobot/common/motors/dynamixel/dynamixel.py
@@ -138,7 +138,7 @@ class DynamixelMotorsBus(MotorsBus):
             ]
         return data
 
-    def broadcast_ping(self, num_retry: int = 0, raise_on_error: bool = False) -> dict[int, str] | None:
+    def broadcast_ping(self, num_retry: int = 0, raise_on_error: bool = False) -> dict[int, int] | None:
         for n_try in range(1 + num_retry):
             data_list, comm = self.packet_handler.broadcastPing(self.port_handler)
             if self._is_comm_success(comm):
@@ -152,4 +152,4 @@ class DynamixelMotorsBus(MotorsBus):
 
             return data_list if data_list else None
 
-        return {id_: self._model_nb_to_model(data[0]) for id_, data in data_list.items()}
+        return {id_: data[0] for id_, data in data_list.items()}
diff --git a/lerobot/common/motors/feetech/feetech.py b/lerobot/common/motors/feetech/feetech.py
index 67f56efd..188350af 100644
--- a/lerobot/common/motors/feetech/feetech.py
+++ b/lerobot/common/motors/feetech/feetech.py
@@ -193,7 +193,7 @@ class FeetechMotorsBus(MotorsBus):
                 del rxpacket[0:id_]
                 rx_length = rx_length - id_
 
-    def broadcast_ping(self, num_retry: int = 0, raise_on_error: bool = False) -> dict[int, str] | None:
+    def broadcast_ping(self, num_retry: int = 0, raise_on_error: bool = False) -> dict[int, int] | None:
         for n_try in range(1 + num_retry):
             ids_status, comm = self._broadcast_ping()
             if self._is_comm_success(comm):
@@ -211,5 +211,13 @@ class FeetechMotorsBus(MotorsBus):
         if ids_errors:
             display_dict = {id_: self.packet_handler.getRxPacketError(err) for id_, err in ids_errors.items()}
             logger.error(f"Some motors found returned an error status:\n{pformat(display_dict, indent=4)}")
-        model_numbers = self.sync_read("Model_Number", list(ids_status), num_retry)
-        return {id_: self._model_nb_to_model(model_nb) for id_, model_nb in model_numbers.items()}
+        comm, model_numbers = self._sync_read(
+            "Model_Number", list(ids_status), model="scs_series", num_retry=num_retry
+        )
+        if not self._is_comm_success(comm):
+            if raise_on_error:
+                raise ConnectionError(self.packet_handler.getRxPacketError(comm))
+
+            return model_numbers if model_numbers else None
+
+        return model_numbers
diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py
index 224726e7..37b1fd77 100644
--- a/lerobot/common/motors/motors_bus.py
+++ b/lerobot/common/motors/motors_bus.py
@@ -42,11 +42,27 @@ MAX_ID_RANGE = 252
 logger = logging.getLogger(__name__)
 
 
+def get_ctrl_table(model_ctrl_table: dict[str, dict], model: str) -> dict[str, tuple[int, int]]:
+    try:
+        return model_ctrl_table[model]
+    except KeyError:
+        raise KeyError(f"Control table for {model=} not found.") from None
+
+
+def get_address(model_ctrl_table: dict[str, dict], model: str, data_name: str) -> tuple[int, int]:
+    ctrl_table = get_ctrl_table(model_ctrl_table, model)
+    try:
+        addr, bytes = ctrl_table[data_name]
+        return addr, bytes
+    except KeyError:
+        raise KeyError(f"Address for '{data_name}' not found in {model} control table.") from None
+
+
 def assert_same_address(model_ctrl_table: dict[str, dict], motor_models: list[str], data_name: str) -> None:
     all_addr = []
     all_bytes = []
     for model in motor_models:
-        addr, bytes = model_ctrl_table[model][data_name]
+        addr, bytes = get_address(model_ctrl_table, model, data_name)
         all_addr.append(addr)
         all_bytes.append(bytes)
 
@@ -275,7 +291,7 @@ class MotorsBus(abc.ABC):
         return (
             f"{self.__class__.__name__}(\n"
             f"    Port: '{self.port}',\n"
-            f"    Motors: \n{pformat(self.motors, indent=8)},\n"
+            f"    Motors: \n{pformat(self.motors, indent=8, sort_dicts=False)},\n"
             ")',\n"
         )
 
@@ -285,7 +301,9 @@ class MotorsBus(abc.ABC):
             return False
 
         first_table = self.model_ctrl_table[self.models[0]]
-        return any(DeepDiff(first_table, self.model_ctrl_table[model]) for model in self.models[1:])
+        return any(
+            DeepDiff(first_table, get_ctrl_table(self.model_ctrl_table, model)) for model in self.models[1:]
+        )
 
     @cached_property
     def names(self) -> list[str]:
@@ -317,15 +335,12 @@ class MotorsBus(abc.ABC):
             raise TypeError(f"'{motor}' should be int, str.")
 
     def _validate_motors(self) -> None:
-        # TODO(aliberts): improve error messages for this (display problematics values)
         if len(self.ids) != len(set(self.ids)):
-            raise ValueError("Some motors have the same id.")
+            raise ValueError(f"Some motors have the same id!\n{self}")
 
-        if len(self.names) != len(set(self.names)):
-            raise ValueError("Some motors have the same name.")
-
-        if any(model not in self.model_resolution_table for model in self.models):
-            raise ValueError("Some motors models are not available.")
+        # Ensure ctrl table available for all models
+        for model in self.models:
+            get_ctrl_table(self.model_ctrl_table, model)
 
     def _is_comm_success(self, comm: int) -> bool:
         return comm == self._comm_success
@@ -333,11 +348,30 @@ class MotorsBus(abc.ABC):
     def _is_error(self, error: int) -> bool:
         return error != self._no_error
 
+    def _assert_motors_exist(self) -> None:
+        found_models = self.broadcast_ping()
+        expected_models = {m.id: self.model_number_table[m.model] for m in self.motors.values()}
+        if not set(found_models) == set(self.ids):
+            raise RuntimeError(
+                f"{self.__class__.__name__} is supposed to have these motors: ({{id: model_nb}})"
+                f"\n{pformat(expected_models, indent=4, sort_dicts=False)}\n"
+                f"But it found these motors on port '{self.port}':"
+                f"\n{pformat(found_models, indent=4, sort_dicts=False)}\n"
+            )
+
+        for id_, model in expected_models.items():
+            if found_models[id_] != model:
+                raise RuntimeError(
+                    f"Motor '{self._id_to_name(id_)}' (id={id_}) is supposed to be of model_number={model} "
+                    f"('{self._id_to_model(id_)}') but a model_number={found_models[id_]} "
+                    "was found instead for that id."
+                )
+
     @property
     def is_connected(self) -> bool:
         return self.port_handler.is_open
 
-    def connect(self) -> None:
+    def connect(self, assert_motors_exist: bool = True) -> None:
         if self.is_connected:
             raise DeviceAlreadyConnectedError(
                 f"{self.__class__.__name__}('{self.port}') is already connected. Do not call `{self.__class__.__name__}.connect()` twice."
@@ -346,6 +380,8 @@ class MotorsBus(abc.ABC):
         try:
             if not self.port_handler.openPort():
                 raise OSError(f"Failed to open port '{self.port}'.")
+            elif assert_motors_exist:
+                self._assert_motors_exist()
         except (FileNotFoundError, OSError, serial.SerialException) as e:
             logger.error(
                 f"\nCould not connect on port '{self.port}'. Make sure you are using the correct port."
@@ -441,7 +477,7 @@ class MotorsBus(abc.ABC):
         """
         pass
 
-    def ping(self, motor: NameOrID, num_retry: int = 0, raise_on_error: bool = False) -> str | None:
+    def ping(self, motor: NameOrID, num_retry: int = 0, raise_on_error: bool = False) -> int | None:
         id_ = self._get_motor_id(motor)
         for n_try in range(1 + num_retry):
             model_number, comm, error = self.packet_handler.ping(self.port_handler, id_)
@@ -460,7 +496,7 @@ class MotorsBus(abc.ABC):
             else:
                 return
 
-        return self._model_nb_to_model(model_number)
+        return model_number
 
     @abc.abstractmethod
     def broadcast_ping(
@@ -470,16 +506,22 @@ class MotorsBus(abc.ABC):
 
     @overload
     def sync_read(
-        self, data_name: str, motors: None = ..., raw_values: bool = ..., num_retry: int = ...
+        self, data_name: str, motors: None = ..., *, raw_values: bool = ..., num_retry: int = ...
     ) -> dict[str, Value]: ...
     @overload
     def sync_read(
-        self, data_name: str, motors: NameOrID | list[NameOrID], raw_values: bool = ..., num_retry: int = ...
+        self,
+        data_name: str,
+        motors: NameOrID | list[NameOrID],
+        *,
+        raw_values: bool = ...,
+        num_retry: int = ...,
     ) -> dict[NameOrID, Value]: ...
     def sync_read(
         self,
         data_name: str,
         motors: NameOrID | list[NameOrID] | None = None,
+        *,
         raw_values: bool = False,
         num_retry: int = 0,
     ) -> dict[NameOrID, Value]:
@@ -500,7 +542,7 @@ class MotorsBus(abc.ABC):
 
         motor_ids = list(id_key_map)
 
-        comm, ids_values = self._sync_read(data_name, motor_ids, num_retry)
+        comm, ids_values = self._sync_read(data_name, motor_ids, num_retry=num_retry)
         if not self._is_comm_success(comm):
             raise ConnectionError(
                 f"Failed to sync read '{data_name}' on {motor_ids=} after {num_retry + 1} tries."
@@ -513,14 +555,14 @@ class MotorsBus(abc.ABC):
         return {id_key_map[id_]: val for id_, val in ids_values.items()}
 
     def _sync_read(
-        self, data_name: str, motor_ids: list[str], num_retry: int = 0
+        self, data_name: str, motor_ids: list[str], model: str | None = None, num_retry: int = 0
     ) -> tuple[int, dict[int, int]]:
         if self._has_different_ctrl_tables:
             models = [self._id_to_model(id_) for id_ in motor_ids]
             assert_same_address(self.model_ctrl_table, models, data_name)
 
-        model = self._id_to_model(next(iter(motor_ids)))
-        addr, n_bytes = self.model_ctrl_table[model][data_name]
+        model = self._id_to_model(next(iter(motor_ids))) if model is None else model
+        addr, n_bytes = get_address(self.model_ctrl_table, model, data_name)
         self._setup_sync_reader(motor_ids, addr, n_bytes)
 
         # FIXME(aliberts, pkooij): We should probably not have to do this.
@@ -559,6 +601,7 @@ class MotorsBus(abc.ABC):
         self,
         data_name: str,
         values: Value | dict[NameOrID, Value],
+        *,
         raw_values: bool = False,
         num_retry: int = 0,
     ) -> None:
@@ -577,7 +620,7 @@ class MotorsBus(abc.ABC):
         if not raw_values and data_name in self.calibration_required and self.calibration is not None:
             ids_values = self._uncalibrate_values(ids_values)
 
-        comm = self._sync_write(data_name, ids_values, num_retry)
+        comm = self._sync_write(data_name, ids_values, num_retry=num_retry)
         if not self._is_comm_success(comm):
             raise ConnectionError(
                 f"Failed to sync write '{data_name}' with {ids_values=} after {num_retry + 1} tries."
@@ -590,7 +633,7 @@ class MotorsBus(abc.ABC):
             assert_same_address(self.model_ctrl_table, models, data_name)
 
         model = self._id_to_model(next(iter(ids_values)))
-        addr, n_bytes = self.model_ctrl_table[model][data_name]
+        addr, n_bytes = get_address(self.model_ctrl_table, model, data_name)
         self._setup_sync_writer(ids_values, addr, n_bytes)
 
         for n_try in range(1 + num_retry):
@@ -613,7 +656,7 @@ class MotorsBus(abc.ABC):
             self.sync_writer.addParam(id_, data)
 
     def write(
-        self, data_name: str, motor: NameOrID, value: Value, raw_value: bool = False, num_retry: int = 0
+        self, data_name: str, motor: NameOrID, value: Value, *, raw_value: bool = False, num_retry: int = 0
     ) -> None:
         if not self.is_connected:
             raise DeviceNotConnectedError(
@@ -626,7 +669,7 @@ class MotorsBus(abc.ABC):
             id_value = self._uncalibrate_values({id_: value})
             value = id_value[id_]
 
-        comm, error = self._write(data_name, id_, value, num_retry)
+        comm, error = self._write(data_name, id_, value, num_retry=num_retry)
         if not self._is_comm_success(comm):
             raise ConnectionError(
                 f"Failed to write '{data_name}' on {id_=} with '{value}' after {num_retry + 1} tries."
@@ -640,7 +683,7 @@ class MotorsBus(abc.ABC):
 
     def _write(self, data_name: str, motor_id: int, value: int, num_retry: int = 0) -> tuple[int, int]:
         model = self._id_to_model(motor_id)
-        addr, n_bytes = self.model_ctrl_table[model][data_name]
+        addr, n_bytes = get_address(self.model_ctrl_table, model, data_name)
         data = self._split_int_to_bytes(value, n_bytes)
 
         for n_try in range(1 + num_retry):
@@ -662,7 +705,3 @@ class MotorsBus(abc.ABC):
 
         self.port_handler.closePort()
         logger.debug(f"{self.__class__.__name__} disconnected.")
-
-    def __del__(self):
-        if self.is_connected:
-            self.disconnect()

From c237d1379efdda28387fa97cfcbaef36344368bc Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Tue, 25 Mar 2025 11:12:52 +0100
Subject: [PATCH 125/171] Update tests

---
 tests/motors/test_dynamixel.py | 45 ++++++++++++++++----------------
 tests/motors/test_feetech.py   | 47 +++++++++++++++++-----------------
 2 files changed, 45 insertions(+), 47 deletions(-)

diff --git a/tests/motors/test_dynamixel.py b/tests/motors/test_dynamixel.py
index 73fb40aa..d2a0d086 100644
--- a/tests/motors/test_dynamixel.py
+++ b/tests/motors/test_dynamixel.py
@@ -94,34 +94,33 @@ def test_abc_implementation(dummy_motors):
 
 @pytest.mark.parametrize("idx", [1, 2, 3])
 def test_ping(idx, mock_motors, dummy_motors):
-    expected_model = dummy_motors[f"dummy_{idx}"].model
-    model_nb = MODEL_NUMBER[expected_model]
-    stub_name = mock_motors.build_ping_stub(idx, model_nb)
+    expected_model_nb = MODEL_NUMBER[dummy_motors[f"dummy_{idx}"].model]
+    stub_name = mock_motors.build_ping_stub(idx, expected_model_nb)
     motors_bus = DynamixelMotorsBus(
         port=mock_motors.port,
         motors=dummy_motors,
     )
-    motors_bus.connect()
+    motors_bus.connect(assert_motors_exist=False)
 
     ping_model_nb = motors_bus.ping(idx)
 
-    assert ping_model_nb == expected_model
+    assert ping_model_nb == expected_model_nb
     assert mock_motors.stubs[stub_name].called
 
 
 def test_broadcast_ping(mock_motors, dummy_motors):
-    expected_models = {m.id: m.model for m in dummy_motors.values()}
-    model_nbs = {id_: MODEL_NUMBER[model] for id_, model in expected_models.items()}
-    stub_name = mock_motors.build_broadcast_ping_stub(model_nbs)
+    models = {m.id: m.model for m in dummy_motors.values()}
+    expected_model_nbs = {id_: MODEL_NUMBER[model] for id_, model in models.items()}
+    stub_name = mock_motors.build_broadcast_ping_stub(expected_model_nbs)
     motors_bus = DynamixelMotorsBus(
         port=mock_motors.port,
         motors=dummy_motors,
     )
-    motors_bus.connect()
+    motors_bus.connect(assert_motors_exist=False)
 
     ping_model_nbs = motors_bus.broadcast_ping()
 
-    assert ping_model_nbs == expected_models
+    assert ping_model_nbs == expected_model_nbs
     assert mock_motors.stubs[stub_name].called
 
 
@@ -137,7 +136,7 @@ def test_sync_read_none(mock_motors, dummy_motors):
         port=mock_motors.port,
         motors=dummy_motors,
     )
-    motors_bus.connect()
+    motors_bus.connect(assert_motors_exist=False)
 
     read_positions = motors_bus.sync_read("Present_Position")
 
@@ -160,7 +159,7 @@ def test_sync_read_by_id(id_, position, mock_motors, dummy_motors):
         port=mock_motors.port,
         motors=dummy_motors,
     )
-    motors_bus.connect()
+    motors_bus.connect(assert_motors_exist=False)
 
     read_position = motors_bus.sync_read("Present_Position", id_)
 
@@ -185,7 +184,7 @@ def test_sync_read_by_ids(ids, positions, mock_motors, dummy_motors):
         port=mock_motors.port,
         motors=dummy_motors,
     )
-    motors_bus.connect()
+    motors_bus.connect(assert_motors_exist=False)
 
     read_positions = motors_bus.sync_read("Present_Position", ids)
 
@@ -208,7 +207,7 @@ def test_sync_read_by_name(id_, position, mock_motors, dummy_motors):
         port=mock_motors.port,
         motors=dummy_motors,
     )
-    motors_bus.connect()
+    motors_bus.connect(assert_motors_exist=False)
 
     read_position = motors_bus.sync_read("Present_Position", f"dummy_{id_}")
 
@@ -235,7 +234,7 @@ def test_sync_read_by_names(ids, positions, mock_motors, dummy_motors):
         port=mock_motors.port,
         motors=dummy_motors,
     )
-    motors_bus.connect()
+    motors_bus.connect(assert_motors_exist=False)
 
     read_positions = motors_bus.sync_read("Present_Position", names)
 
@@ -261,7 +260,7 @@ def test_sync_read_num_retry(num_retry, num_invalid_try, pos, mock_motors, dummy
         port=mock_motors.port,
         motors=dummy_motors,
     )
-    motors_bus.connect()
+    motors_bus.connect(assert_motors_exist=False)
 
     if num_retry >= num_invalid_try:
         pos_dict = motors_bus.sync_read("Present_Position", 1, num_retry=num_retry)
@@ -290,7 +289,7 @@ def test_sync_write_single_value(data_name, value, mock_motors, dummy_motors):
         port=mock_motors.port,
         motors=dummy_motors,
     )
-    motors_bus.connect()
+    motors_bus.connect(assert_motors_exist=False)
 
     motors_bus.sync_write(data_name, value)
 
@@ -312,7 +311,7 @@ def test_sync_write_by_id(id_, position, mock_motors, dummy_motors):
         port=mock_motors.port,
         motors=dummy_motors,
     )
-    motors_bus.connect()
+    motors_bus.connect(assert_motors_exist=False)
 
     motors_bus.sync_write("Goal_Position", value)
 
@@ -336,7 +335,7 @@ def test_sync_write_by_ids(ids, positions, mock_motors, dummy_motors):
         port=mock_motors.port,
         motors=dummy_motors,
     )
-    motors_bus.connect()
+    motors_bus.connect(assert_motors_exist=False)
 
     motors_bus.sync_write("Goal_Position", values)
 
@@ -358,7 +357,7 @@ def test_sync_write_by_name(id_, position, mock_motors, dummy_motors):
         port=mock_motors.port,
         motors=dummy_motors,
     )
-    motors_bus.connect()
+    motors_bus.connect(assert_motors_exist=False)
 
     write_value = {f"dummy_{id_}": position}
     motors_bus.sync_write("Goal_Position", write_value)
@@ -383,7 +382,7 @@ def test_sync_write_by_names(ids, positions, mock_motors, dummy_motors):
         port=mock_motors.port,
         motors=dummy_motors,
     )
-    motors_bus.connect()
+    motors_bus.connect(assert_motors_exist=False)
 
     write_values = {f"dummy_{id_}": pos for id_, pos in ids_values.items()}
     motors_bus.sync_write("Goal_Position", write_values)
@@ -406,7 +405,7 @@ def test_write_by_id(data_name, dxl_id, value, mock_motors, dummy_motors):
         port=mock_motors.port,
         motors=dummy_motors,
     )
-    motors_bus.connect()
+    motors_bus.connect(assert_motors_exist=False)
 
     motors_bus.write(data_name, dxl_id, value)
 
@@ -428,7 +427,7 @@ def test_write_by_name(data_name, dxl_id, value, mock_motors, dummy_motors):
         port=mock_motors.port,
         motors=dummy_motors,
     )
-    motors_bus.connect()
+    motors_bus.connect(assert_motors_exist=False)
 
     motors_bus.write(data_name, f"dummy_{dxl_id}", value)
 
diff --git a/tests/motors/test_feetech.py b/tests/motors/test_feetech.py
index bed0957f..1dc3d217 100644
--- a/tests/motors/test_feetech.py
+++ b/tests/motors/test_feetech.py
@@ -95,37 +95,36 @@ def test_abc_implementation(dummy_motors):
 # @pytest.mark.skip("TODO")
 @pytest.mark.parametrize("idx", [1, 2, 3])
 def test_ping(idx, mock_motors, dummy_motors):
-    expected_model = dummy_motors[f"dummy_{idx}"].model
-    model_nb = MODEL_NUMBER[expected_model]
+    expected_model_nb = MODEL_NUMBER[dummy_motors[f"dummy_{idx}"].model]
     ping_stub = mock_motors.build_ping_stub(idx)
-    mobel_nb_stub = mock_motors.build_read_stub("Model_Number", idx, model_nb)
+    mobel_nb_stub = mock_motors.build_read_stub("Model_Number", idx, expected_model_nb)
     motors_bus = FeetechMotorsBus(
         port=mock_motors.port,
         motors=dummy_motors,
     )
-    motors_bus.connect()
+    motors_bus.connect(assert_motors_exist=False)
 
     ping_model_nb = motors_bus.ping(idx)
 
-    assert ping_model_nb == expected_model
+    assert ping_model_nb == expected_model_nb
     assert mock_motors.stubs[ping_stub].called
     assert mock_motors.stubs[mobel_nb_stub].called
 
 
 def test_broadcast_ping(mock_motors, dummy_motors):
-    expected_models = {m.id: m.model for m in dummy_motors.values()}
-    model_nbs = {id_: MODEL_NUMBER[model] for id_, model in expected_models.items()}
-    ping_stub = mock_motors.build_broadcast_ping_stub(list(model_nbs))
-    mobel_nb_stub = mock_motors.build_sync_read_stub("Model_Number", model_nbs)
+    models = {m.id: m.model for m in dummy_motors.values()}
+    expected_model_nbs = {id_: MODEL_NUMBER[model] for id_, model in models.items()}
+    ping_stub = mock_motors.build_broadcast_ping_stub(list(models))
+    mobel_nb_stub = mock_motors.build_sync_read_stub("Model_Number", expected_model_nbs)
     motors_bus = FeetechMotorsBus(
         port=mock_motors.port,
         motors=dummy_motors,
     )
-    motors_bus.connect()
+    motors_bus.connect(assert_motors_exist=False)
 
     ping_model_nbs = motors_bus.broadcast_ping()
 
-    assert ping_model_nbs == expected_models
+    assert ping_model_nbs == expected_model_nbs
     assert mock_motors.stubs[ping_stub].called
     assert mock_motors.stubs[mobel_nb_stub].called
 
@@ -142,7 +141,7 @@ def test_sync_read_none(mock_motors, dummy_motors):
         port=mock_motors.port,
         motors=dummy_motors,
     )
-    motors_bus.connect()
+    motors_bus.connect(assert_motors_exist=False)
 
     read_positions = motors_bus.sync_read("Present_Position")
 
@@ -165,7 +164,7 @@ def test_sync_read_by_id(id_, position, mock_motors, dummy_motors):
         port=mock_motors.port,
         motors=dummy_motors,
     )
-    motors_bus.connect()
+    motors_bus.connect(assert_motors_exist=False)
 
     read_position = motors_bus.sync_read("Present_Position", id_)
 
@@ -190,7 +189,7 @@ def test_sync_read_by_ids(ids, positions, mock_motors, dummy_motors):
         port=mock_motors.port,
         motors=dummy_motors,
     )
-    motors_bus.connect()
+    motors_bus.connect(assert_motors_exist=False)
 
     read_positions = motors_bus.sync_read("Present_Position", ids)
 
@@ -213,7 +212,7 @@ def test_sync_read_by_name(id_, position, mock_motors, dummy_motors):
         port=mock_motors.port,
         motors=dummy_motors,
     )
-    motors_bus.connect()
+    motors_bus.connect(assert_motors_exist=False)
 
     read_position = motors_bus.sync_read("Present_Position", f"dummy_{id_}")
 
@@ -240,7 +239,7 @@ def test_sync_read_by_names(ids, positions, mock_motors, dummy_motors):
         port=mock_motors.port,
         motors=dummy_motors,
     )
-    motors_bus.connect()
+    motors_bus.connect(assert_motors_exist=False)
 
     read_positions = motors_bus.sync_read("Present_Position", names)
 
@@ -266,7 +265,7 @@ def test_sync_read_num_retry(num_retry, num_invalid_try, pos, mock_motors, dummy
         port=mock_motors.port,
         motors=dummy_motors,
     )
-    motors_bus.connect()
+    motors_bus.connect(assert_motors_exist=False)
 
     if num_retry >= num_invalid_try:
         pos_dict = motors_bus.sync_read("Present_Position", 1, num_retry=num_retry)
@@ -295,7 +294,7 @@ def test_sync_write_single_value(data_name, value, mock_motors, dummy_motors):
         port=mock_motors.port,
         motors=dummy_motors,
     )
-    motors_bus.connect()
+    motors_bus.connect(assert_motors_exist=False)
 
     motors_bus.sync_write(data_name, value)
 
@@ -317,7 +316,7 @@ def test_sync_write_by_id(id_, position, mock_motors, dummy_motors):
         port=mock_motors.port,
         motors=dummy_motors,
     )
-    motors_bus.connect()
+    motors_bus.connect(assert_motors_exist=False)
 
     motors_bus.sync_write("Goal_Position", value)
 
@@ -341,7 +340,7 @@ def test_sync_write_by_ids(ids, positions, mock_motors, dummy_motors):
         port=mock_motors.port,
         motors=dummy_motors,
     )
-    motors_bus.connect()
+    motors_bus.connect(assert_motors_exist=False)
 
     motors_bus.sync_write("Goal_Position", values)
 
@@ -363,7 +362,7 @@ def test_sync_write_by_name(id_, position, mock_motors, dummy_motors):
         port=mock_motors.port,
         motors=dummy_motors,
     )
-    motors_bus.connect()
+    motors_bus.connect(assert_motors_exist=False)
 
     write_value = {f"dummy_{id_}": position}
     motors_bus.sync_write("Goal_Position", write_value)
@@ -388,7 +387,7 @@ def test_sync_write_by_names(ids, positions, mock_motors, dummy_motors):
         port=mock_motors.port,
         motors=dummy_motors,
     )
-    motors_bus.connect()
+    motors_bus.connect(assert_motors_exist=False)
 
     write_values = {f"dummy_{id_}": pos for id_, pos in ids_values.items()}
     motors_bus.sync_write("Goal_Position", write_values)
@@ -411,7 +410,7 @@ def test_write_by_id(data_name, dxl_id, value, mock_motors, dummy_motors):
         port=mock_motors.port,
         motors=dummy_motors,
     )
-    motors_bus.connect()
+    motors_bus.connect(assert_motors_exist=False)
 
     motors_bus.write(data_name, dxl_id, value)
 
@@ -433,7 +432,7 @@ def test_write_by_name(data_name, dxl_id, value, mock_motors, dummy_motors):
         port=mock_motors.port,
         motors=dummy_motors,
     )
-    motors_bus.connect()
+    motors_bus.connect(assert_motors_exist=False)
 
     motors_bus.write(data_name, f"dummy_{dxl_id}", value)
 

From b71ac342142c8c99bab9b4662d22ea7c12f9815e Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Tue, 25 Mar 2025 12:11:56 +0100
Subject: [PATCH 126/171] Add test_motors_bus

---
 lerobot/common/motors/motors_bus.py | 21 ++++---
 tests/motors/test_motors_bus.py     | 87 +++++++++++++++++++++++++++++
 2 files changed, 97 insertions(+), 11 deletions(-)
 create mode 100644 tests/motors/test_motors_bus.py

diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py
index 37b1fd77..d5265d8c 100644
--- a/lerobot/common/motors/motors_bus.py
+++ b/lerobot/common/motors/motors_bus.py
@@ -43,19 +43,18 @@ logger = logging.getLogger(__name__)
 
 
 def get_ctrl_table(model_ctrl_table: dict[str, dict], model: str) -> dict[str, tuple[int, int]]:
-    try:
-        return model_ctrl_table[model]
-    except KeyError:
-        raise KeyError(f"Control table for {model=} not found.") from None
+    ctrl_table = model_ctrl_table.get(model)
+    if ctrl_table is None:
+        raise KeyError(f"Control table for {model=} not found.")
+    return ctrl_table
 
 
 def get_address(model_ctrl_table: dict[str, dict], model: str, data_name: str) -> tuple[int, int]:
     ctrl_table = get_ctrl_table(model_ctrl_table, model)
-    try:
-        addr, bytes = ctrl_table[data_name]
-        return addr, bytes
-    except KeyError:
-        raise KeyError(f"Address for '{data_name}' not found in {model} control table.") from None
+    addr_bytes = ctrl_table.get(data_name)
+    if addr_bytes is None:
+        raise KeyError(f"Address for '{data_name}' not found in {model} control table.")
+    return addr_bytes
 
 
 def assert_same_address(model_ctrl_table: dict[str, dict], motor_models: list[str], data_name: str) -> None:
@@ -69,13 +68,13 @@ def assert_same_address(model_ctrl_table: dict[str, dict], motor_models: list[st
     if len(set(all_addr)) != 1:
         raise NotImplementedError(
             f"At least two motor models use a different address for `data_name`='{data_name}'"
-            f"({list(zip(motor_models, all_addr, strict=False))}). Contact a LeRobot maintainer."
+            f"({list(zip(motor_models, all_addr, strict=False))})."
         )
 
     if len(set(all_bytes)) != 1:
         raise NotImplementedError(
             f"At least two motor models use a different bytes representation for `data_name`='{data_name}'"
-            f"({list(zip(motor_models, all_bytes, strict=False))}). Contact a LeRobot maintainer."
+            f"({list(zip(motor_models, all_bytes, strict=False))})."
         )
 
 
diff --git a/tests/motors/test_motors_bus.py b/tests/motors/test_motors_bus.py
new file mode 100644
index 00000000..7463ae8c
--- /dev/null
+++ b/tests/motors/test_motors_bus.py
@@ -0,0 +1,87 @@
+import re
+
+import pytest
+
+from lerobot.common.motors.motors_bus import assert_same_address, get_address, get_ctrl_table
+
+# TODO(aliberts)
+# class DummyMotorsBus(MotorsBus):
+#     def __init__(self, port: str, motors: dict[str, Motor]):
+#         super().__init__(port, motors)
+
+
+@pytest.fixture
+def ctrl_table_1() -> dict:
+    return {
+        "Firmware_Version": (0, 1),
+        "Model_Number": (1, 2),
+        "Present_Position": (3, 4),
+        "Goal_Position": (7, 2),
+    }
+
+
+@pytest.fixture
+def ctrl_table_2() -> dict:
+    return {
+        "Model_Number": (0, 2),
+        "Firmware_Version": (2, 1),
+        "Present_Position": (3, 4),
+        "Goal_Position": (7, 4),
+        "Lock": (7, 4),
+    }
+
+
+@pytest.fixture
+def model_ctrl_table(ctrl_table_1, ctrl_table_2) -> dict:
+    return {
+        "model_1": ctrl_table_1,
+        "model_2": ctrl_table_2,
+    }
+
+
+def test_get_ctrl_table(model_ctrl_table, ctrl_table_1):
+    model = "model_1"
+    ctrl_table = get_ctrl_table(model_ctrl_table, model)
+    assert ctrl_table == ctrl_table_1
+
+
+def test_get_ctrl_table_error(model_ctrl_table):
+    model = "model_99"
+    with pytest.raises(KeyError, match=f"Control table for {model=} not found."):
+        get_ctrl_table(model_ctrl_table, model)
+
+
+def test_get_address(model_ctrl_table):
+    addr, n_bytes = get_address(model_ctrl_table, "model_1", "Firmware_Version")
+    assert addr == 0
+    assert n_bytes == 1
+
+
+def test_get_address_error(model_ctrl_table):
+    model = "model_1"
+    data_name = "Lock"
+    with pytest.raises(KeyError, match=f"Address for '{data_name}' not found in {model} control table."):
+        get_address(model_ctrl_table, "model_1", data_name)
+
+
+def test_assert_same_address(model_ctrl_table):
+    models = ["model_1", "model_2"]
+    assert_same_address(model_ctrl_table, models, "Present_Position")
+
+
+def test_assert_same_address_different_addresses(model_ctrl_table):
+    models = ["model_1", "model_2"]
+    with pytest.raises(
+        NotImplementedError,
+        match=re.escape("At least two motor models use a different address"),
+    ):
+        assert_same_address(model_ctrl_table, models, "Model_Number")
+
+
+def test_assert_same_address_different_bytes(model_ctrl_table):
+    models = ["model_1", "model_2"]
+    with pytest.raises(
+        NotImplementedError,
+        match=re.escape("At least two motor models use a different bytes representation"),
+    ):
+        assert_same_address(model_ctrl_table, models, "Goal_Position")

From dcbbeab80b190df5ffeebc7adee30f2d9cf7d3ce Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Tue, 25 Mar 2025 12:30:07 +0100
Subject: [PATCH 127/171] Move DriveMode & TorqueMode

---
 lerobot/common/motors/__init__.py            |  2 +-
 lerobot/common/motors/dynamixel/__init__.py  |  2 +-
 lerobot/common/motors/dynamixel/dynamixel.py | 10 ++++++++++
 lerobot/common/motors/feetech/__init__.py    |  2 +-
 lerobot/common/motors/feetech/feetech.py     | 10 ++++++++++
 lerobot/common/motors/motors_bus.py          | 10 ----------
 6 files changed, 23 insertions(+), 13 deletions(-)

diff --git a/lerobot/common/motors/__init__.py b/lerobot/common/motors/__init__.py
index 3261ae7e..75904fa8 100644
--- a/lerobot/common/motors/__init__.py
+++ b/lerobot/common/motors/__init__.py
@@ -1 +1 @@
-from .motors_bus import CalibrationMode, DriveMode, Motor, MotorsBus, TorqueMode
+from .motors_bus import CalibrationMode, Motor, MotorsBus
diff --git a/lerobot/common/motors/dynamixel/__init__.py b/lerobot/common/motors/dynamixel/__init__.py
index 14cbf8c1..e711c09b 100644
--- a/lerobot/common/motors/dynamixel/__init__.py
+++ b/lerobot/common/motors/dynamixel/__init__.py
@@ -1,3 +1,3 @@
-from .dynamixel import DynamixelMotorsBus, OperatingMode
+from .dynamixel import DriveMode, DynamixelMotorsBus, OperatingMode, TorqueMode
 from .dynamixel_calibration import run_arm_calibration
 from .tables import *
diff --git a/lerobot/common/motors/dynamixel/dynamixel.py b/lerobot/common/motors/dynamixel/dynamixel.py
index 11094f60..5db015ef 100644
--- a/lerobot/common/motors/dynamixel/dynamixel.py
+++ b/lerobot/common/motors/dynamixel/dynamixel.py
@@ -65,6 +65,16 @@ class OperatingMode(Enum):
     PWM = 16
 
 
+class DriveMode(Enum):
+    NON_INVERTED = 0
+    INVERTED = 1
+
+
+class TorqueMode(Enum):
+    ENABLED = 1
+    DISABLED = 0
+
+
 class DynamixelMotorsBus(MotorsBus):
     """
     The Dynamixel implementation for a MotorsBus. It relies on the python dynamixel sdk to communicate with
diff --git a/lerobot/common/motors/feetech/__init__.py b/lerobot/common/motors/feetech/__init__.py
index 1f110e40..dbe9a08d 100644
--- a/lerobot/common/motors/feetech/__init__.py
+++ b/lerobot/common/motors/feetech/__init__.py
@@ -1,3 +1,3 @@
-from .feetech import FeetechMotorsBus, OperatingMode
+from .feetech import DriveMode, FeetechMotorsBus, OperatingMode, TorqueMode
 from .feetech_calibration import apply_feetech_offsets_from_calibration, run_full_arm_calibration
 from .tables import *
diff --git a/lerobot/common/motors/feetech/feetech.py b/lerobot/common/motors/feetech/feetech.py
index 188350af..54f86824 100644
--- a/lerobot/common/motors/feetech/feetech.py
+++ b/lerobot/common/motors/feetech/feetech.py
@@ -47,6 +47,16 @@ class OperatingMode(Enum):
     STEP = 3
 
 
+class DriveMode(Enum):
+    NON_INVERTED = 0
+    INVERTED = 1
+
+
+class TorqueMode(Enum):
+    ENABLED = 1
+    DISABLED = 0
+
+
 class FeetechMotorsBus(MotorsBus):
     """
     The FeetechMotorsBus class allows to efficiently read and write to the attached motors. It relies on the
diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py
index d5265d8c..40cda4f6 100644
--- a/lerobot/common/motors/motors_bus.py
+++ b/lerobot/common/motors/motors_bus.py
@@ -78,16 +78,6 @@ def assert_same_address(model_ctrl_table: dict[str, dict], motor_models: list[st
         )
 
 
-class TorqueMode(Enum):
-    ENABLED = 1
-    DISABLED = 0
-
-
-class DriveMode(Enum):
-    NON_INVERTED = 0
-    INVERTED = 1
-
-
 class CalibrationMode(Enum):
     DEGREE = 0
     RANGE_0_100 = 1

From bb774e7acdb9e0fe2e744a3d5aff04f44828dd5e Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Tue, 25 Mar 2025 12:31:51 +0100
Subject: [PATCH 128/171] Update Koch imports

---
 lerobot/common/robots/koch/robot_koch.py         | 6 ++++--
 lerobot/common/teleoperators/koch/teleop_koch.py | 3 ++-
 2 files changed, 6 insertions(+), 3 deletions(-)

diff --git a/lerobot/common/robots/koch/robot_koch.py b/lerobot/common/robots/koch/robot_koch.py
index 3dd78519..90a63776 100644
--- a/lerobot/common/robots/koch/robot_koch.py
+++ b/lerobot/common/robots/koch/robot_koch.py
@@ -22,10 +22,11 @@ from typing import Any
 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 import CalibrationMode, Motor, TorqueMode
+from lerobot.common.motors import CalibrationMode, Motor
 from lerobot.common.motors.dynamixel import (
     DynamixelMotorsBus,
     OperatingMode,
+    TorqueMode,
     run_arm_calibration,
 )
 
@@ -124,7 +125,8 @@ class KochRobot(Robot):
 
     @property
     def is_connected(self) -> bool:
-        return self.arm.is_connected  # TODO(aliberts): add cam.is_connected for cam in self.cameras
+        # TODO(aliberts): add cam.is_connected for cam in self.cameras
+        return self.arm.is_connected
 
     def connect(self) -> None:
         if self.is_connected:
diff --git a/lerobot/common/teleoperators/koch/teleop_koch.py b/lerobot/common/teleoperators/koch/teleop_koch.py
index 25ae14e6..3d2bf54e 100644
--- a/lerobot/common/teleoperators/koch/teleop_koch.py
+++ b/lerobot/common/teleoperators/koch/teleop_koch.py
@@ -21,10 +21,11 @@ import time
 import numpy as np
 
 from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError
-from lerobot.common.motors import CalibrationMode, Motor, TorqueMode
+from lerobot.common.motors import CalibrationMode, Motor
 from lerobot.common.motors.dynamixel import (
     DynamixelMotorsBus,
     OperatingMode,
+    TorqueMode,
     run_arm_calibration,
 )
 

From 6ccf083127424cf7fbbdb0ed2321dd57528378d4 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Tue, 25 Mar 2025 12:32:38 +0100
Subject: [PATCH 129/171] Update so100 imports

---
 lerobot/common/robots/so100/robot_so100.py         | 3 ++-
 lerobot/common/teleoperators/so100/teleop_so100.py | 3 ++-
 2 files changed, 4 insertions(+), 2 deletions(-)

diff --git a/lerobot/common/robots/so100/robot_so100.py b/lerobot/common/robots/so100/robot_so100.py
index ccbe9dad..a0321477 100644
--- a/lerobot/common/robots/so100/robot_so100.py
+++ b/lerobot/common/robots/so100/robot_so100.py
@@ -22,10 +22,11 @@ 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 import CalibrationMode, Motor, TorqueMode
+from lerobot.common.motors import CalibrationMode, Motor
 from lerobot.common.motors.feetech import (
     FeetechMotorsBus,
     OperatingMode,
+    TorqueMode,
     apply_feetech_offsets_from_calibration,
 )
 
diff --git a/lerobot/common/teleoperators/so100/teleop_so100.py b/lerobot/common/teleoperators/so100/teleop_so100.py
index 0e02b313..ab0bf3c0 100644
--- a/lerobot/common/teleoperators/so100/teleop_so100.py
+++ b/lerobot/common/teleoperators/so100/teleop_so100.py
@@ -20,9 +20,10 @@ import time
 import numpy as np
 
 from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError
-from lerobot.common.motors import CalibrationMode, Motor, TorqueMode
+from lerobot.common.motors import CalibrationMode, Motor
 from lerobot.common.motors.feetech import (
     FeetechMotorsBus,
+    TorqueMode,
     apply_feetech_offsets_from_calibration,
 )
 

From 9644e2b0865d024c8cfc39674d23f8370e8198c2 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Tue, 25 Mar 2025 12:47:44 +0100
Subject: [PATCH 130/171] Fix visualize_motors_bus

---
 lerobot/common/debugging/motors_bus.py | 16 ++++++++++------
 1 file changed, 10 insertions(+), 6 deletions(-)

diff --git a/lerobot/common/debugging/motors_bus.py b/lerobot/common/debugging/motors_bus.py
index f41a454b..cdb7d574 100644
--- a/lerobot/common/debugging/motors_bus.py
+++ b/lerobot/common/debugging/motors_bus.py
@@ -31,22 +31,26 @@ def visualize_motors_bus(motors_bus: MotorsBus):
         motors_bus.connect()
 
     # Disable torque on all motors so you can move them freely by hand
-    values_dict = {idx: 0 for idx in motors_bus.motor_ids}
-    motors_bus.write("Torque_Enable", values_dict)
+    for id_ in motors_bus.ids:
+        motors_bus.write("Torque_Enable", id_, 0)
+
     print("Torque disabled on all joints.")
 
     try:
         print("\nPress Ctrl+C to quit.\n")
         while True:
             # Read *raw* positions (no calibration).
-            raw_positions = motors_bus.read("Present_Position")
+            start = time.perf_counter()
+            raw_positions = motors_bus.sync_read("Present_Position", raw_values=True)
+            read_s = time.perf_counter() - start
 
             # # Read *already-homed* positions
             # homed_positions = motor_bus.read("Present_Position")
 
+            print(f"read_s: {read_s * 1e3:.2f}ms ({1 / read_s:.0f} Hz)")
             for name, raw_ticks in raw_positions.items():
-                idx = motors_bus.motors[name][0]
-                model = motors_bus.motors[name][1]
+                idx = motors_bus.motors[name].id
+                model = motors_bus.motors[name].model
 
                 # homed_val = homed_positions[i]  # degrees or % if linear
 
@@ -70,7 +74,7 @@ def visualize_motors_bus(motors_bus: MotorsBus):
                     f"INV_TICKS={inv_ticks:4d} "
                 )
             print("----------------------------------------------------")
-            time.sleep(0.25)
+            # time.sleep(0.25)
     except KeyboardInterrupt:
         pass
     finally:

From af295fadb54dcd5b0601b716dd7bcf10be61b329 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Tue, 25 Mar 2025 12:48:58 +0100
Subject: [PATCH 131/171] Fix imports

---
 lerobot/common/motors/dynamixel/dynamixel_calibration.py | 3 ++-
 lerobot/common/motors/feetech/feetech_calibration.py     | 3 +--
 2 files changed, 3 insertions(+), 3 deletions(-)

diff --git a/lerobot/common/motors/dynamixel/dynamixel_calibration.py b/lerobot/common/motors/dynamixel/dynamixel_calibration.py
index fbae2e9a..d959aee5 100644
--- a/lerobot/common/motors/dynamixel/dynamixel_calibration.py
+++ b/lerobot/common/motors/dynamixel/dynamixel_calibration.py
@@ -17,7 +17,8 @@
 
 import numpy as np
 
-from ..motors_bus import CalibrationMode, MotorsBus, TorqueMode
+from ..motors_bus import CalibrationMode, MotorsBus
+from .dynamixel import TorqueMode
 from .tables import MODEL_RESOLUTION
 
 URL_TEMPLATE = (
diff --git a/lerobot/common/motors/feetech/feetech_calibration.py b/lerobot/common/motors/feetech/feetech_calibration.py
index 102b30be..098370d0 100644
--- a/lerobot/common/motors/feetech/feetech_calibration.py
+++ b/lerobot/common/motors/feetech/feetech_calibration.py
@@ -16,9 +16,8 @@ import numpy as np
 from ..motors_bus import (
     CalibrationMode,
     MotorsBus,
-    TorqueMode,
 )
-from .feetech import FeetechMotorsBus
+from .feetech import FeetechMotorsBus, TorqueMode
 from .tables import MODEL_RESOLUTION
 
 URL_TEMPLATE = (

From 7a3b424cd310652b1cd80a8ca8739fd6b29651c5 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Tue, 25 Mar 2025 14:13:55 +0100
Subject: [PATCH 132/171] Add calibration

---
 lerobot/common/motors/calibration.py | 10 ++++++++++
 1 file changed, 10 insertions(+)
 create mode 100644 lerobot/common/motors/calibration.py

diff --git a/lerobot/common/motors/calibration.py b/lerobot/common/motors/calibration.py
new file mode 100644
index 00000000..f503a972
--- /dev/null
+++ b/lerobot/common/motors/calibration.py
@@ -0,0 +1,10 @@
+from dataclasses import dataclass
+
+
+@dataclass
+class MotorCalibration:
+    name: str
+    drive_mode: int
+    homing_offset: int
+    range_min: int
+    range_max: int

From 222d6f104ea8ec3fabb2f2549494ab3c6df4b022 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Tue, 25 Mar 2025 14:20:12 +0100
Subject: [PATCH 133/171] Rename idx -> id_

---
 tests/mocks/mock_dynamixel.py  | 14 +++++++-------
 tests/mocks/mock_feetech.py    | 20 ++++++++++----------
 tests/motors/test_dynamixel.py | 10 +++++-----
 tests/motors/test_feetech.py   | 12 ++++++------
 4 files changed, 28 insertions(+), 28 deletions(-)

diff --git a/tests/mocks/mock_dynamixel.py b/tests/mocks/mock_dynamixel.py
index 4159af3d..92e47c59 100644
--- a/tests/mocks/mock_dynamixel.py
+++ b/tests/mocks/mock_dynamixel.py
@@ -281,9 +281,9 @@ class MockInstructionPacket(MockDynamixelPacketv2):
             +2 is for the CRC at the end.
         """
         data = []
-        for idx, value in ids_values.items():
+        for id_, value in ids_values.items():
             split_value = DynamixelMotorsBus._split_int_to_bytes(value, data_length)
-            data += [idx, *split_value]
+            data += [id_, *split_value]
         params = [
             dxl.DXL_LOBYTE(start_address),
             dxl.DXL_HIBYTE(start_address),
@@ -444,10 +444,10 @@ class MockMotors(MockSerial):
         self, ids_models: dict[int, list[int]] | None = None, num_invalid_try: int = 0
     ) -> str:
         ping_request = MockInstructionPacket.ping(dxl.BROADCAST_ID)
-        return_packets = b"".join(MockStatusPacket.ping(idx, model) for idx, model in ids_models.items())
+        return_packets = b"".join(MockStatusPacket.ping(id_, model) for id_, model in ids_models.items())
         ping_response = self._build_send_fn(return_packets, num_invalid_try)
 
-        stub_name = "Ping_" + "_".join([str(idx) for idx in ids_models])
+        stub_name = "Ping_" + "_".join([str(id_) for id_ in ids_models])
         self.stub(
             name=stub_name,
             receive_bytes=ping_request,
@@ -482,10 +482,10 @@ class MockMotors(MockSerial):
         address, length = self.ctrl_table[data_name]
         sync_read_request = MockInstructionPacket.sync_read(list(ids_values), address, length)
         return_packets = b"".join(
-            MockStatusPacket.present_position(idx, pos) for idx, pos in ids_values.items()
+            MockStatusPacket.present_position(id_, pos) for id_, pos in ids_values.items()
         )
         sync_read_response = self._build_send_fn(return_packets, num_invalid_try)
-        stub_name = f"Sync_Read_{data_name}_" + "_".join([str(idx) for idx in ids_values])
+        stub_name = f"Sync_Read_{data_name}_" + "_".join([str(id_) for id_ in ids_values])
         self.stub(
             name=stub_name,
             receive_bytes=sync_read_request,
@@ -498,7 +498,7 @@ class MockMotors(MockSerial):
     ) -> str:
         address, length = self.ctrl_table[data_name]
         sync_read_request = MockInstructionPacket.sync_write(ids_values, address, length)
-        stub_name = f"Sync_Write_{data_name}_" + "_".join([str(idx) for idx in ids_values])
+        stub_name = f"Sync_Write_{data_name}_" + "_".join([str(id_) for id_ in ids_values])
         self.stub(
             name=stub_name,
             receive_bytes=sync_read_request,
diff --git a/tests/mocks/mock_feetech.py b/tests/mocks/mock_feetech.py
index fc5422ed..c5fab0d9 100644
--- a/tests/mocks/mock_feetech.py
+++ b/tests/mocks/mock_feetech.py
@@ -46,8 +46,8 @@ class MockFeetechPacket(abc.ABC):
     @staticmethod
     def _add_checksum(packet: list[int]) -> list[int]:
         checksum = 0
-        for idx in range(2, len(packet) - 1):  # except header & checksum
-            checksum += packet[idx]
+        for id_ in range(2, len(packet) - 1):  # except header & checksum
+            checksum += packet[id_]
 
         packet[-1] = scs.SCS_LOBYTE(~checksum)
 
@@ -171,9 +171,9 @@ class MockInstructionPacket(MockFeetechPacket):
             +1 is for the checksum at the end.
         """
         data = []
-        for idx, value in ids_values.items():
+        for id_, value in ids_values.items():
             split_value = FeetechMotorsBus._split_int_to_bytes(value, data_length)
-            data += [idx, *split_value]
+            data += [id_, *split_value]
         params = [start_address, data_length, *data]
         length = len(ids_values) * (1 + data_length) + 4
         return cls.build(scs_id=scs.BROADCAST_ID, params=params, length=length, instruct_type="Sync_Write")
@@ -331,9 +331,9 @@ class MockMotors(MockSerial):
 
     def build_broadcast_ping_stub(self, ids: list[int] | None = None, num_invalid_try: int = 0) -> str:
         ping_request = MockInstructionPacket.ping(scs.BROADCAST_ID)
-        return_packets = b"".join(MockStatusPacket.ping(idx) for idx in ids)
+        return_packets = b"".join(MockStatusPacket.ping(id_) for id_ in ids)
         ping_response = self._build_send_fn(return_packets, num_invalid_try)
-        stub_name = "Ping_" + "_".join([str(idx) for idx in ids])
+        stub_name = "Ping_" + "_".join([str(id_) for id_ in ids])
         self.stub(
             name=stub_name,
             receive_bytes=ping_request,
@@ -386,17 +386,17 @@ class MockMotors(MockSerial):
         sync_read_request = MockInstructionPacket.sync_read(list(ids_values), address, length)
         if data_name == "Present_Position":
             return_packets = b"".join(
-                MockStatusPacket.present_position(idx, pos) for idx, pos in ids_values.items()
+                MockStatusPacket.present_position(id_, pos) for id_, pos in ids_values.items()
             )
         elif data_name == "Model_Number":
             return_packets = b"".join(
-                MockStatusPacket.model_number(idx, model_nb) for idx, model_nb in ids_values.items()
+                MockStatusPacket.model_number(id_, model_nb) for id_, model_nb in ids_values.items()
             )
         else:
             raise NotImplementedError
 
         sync_read_response = self._build_send_fn(return_packets, num_invalid_try)
-        stub_name = f"Sync_Read_{data_name}_" + "_".join([str(idx) for idx in ids_values])
+        stub_name = f"Sync_Read_{data_name}_" + "_".join([str(id_) for id_ in ids_values])
         self.stub(
             name=stub_name,
             receive_bytes=sync_read_request,
@@ -409,7 +409,7 @@ class MockMotors(MockSerial):
     ) -> str:
         address, length = self.ctrl_table[data_name]
         sync_read_request = MockInstructionPacket.sync_write(ids_values, address, length)
-        stub_name = f"Sync_Write_{data_name}_" + "_".join([str(idx) for idx in ids_values])
+        stub_name = f"Sync_Write_{data_name}_" + "_".join([str(id_) for id_ in ids_values])
         self.stub(
             name=stub_name,
             receive_bytes=sync_read_request,
diff --git a/tests/motors/test_dynamixel.py b/tests/motors/test_dynamixel.py
index d2a0d086..80f853d6 100644
--- a/tests/motors/test_dynamixel.py
+++ b/tests/motors/test_dynamixel.py
@@ -92,17 +92,17 @@ def test_abc_implementation(dummy_motors):
     DynamixelMotorsBus(port="/dev/dummy-port", motors=dummy_motors)
 
 
-@pytest.mark.parametrize("idx", [1, 2, 3])
-def test_ping(idx, mock_motors, dummy_motors):
-    expected_model_nb = MODEL_NUMBER[dummy_motors[f"dummy_{idx}"].model]
-    stub_name = mock_motors.build_ping_stub(idx, expected_model_nb)
+@pytest.mark.parametrize("id_", [1, 2, 3])
+def test_ping(id_, mock_motors, dummy_motors):
+    expected_model_nb = MODEL_NUMBER[dummy_motors[f"dummy_{id_}"].model]
+    stub_name = mock_motors.build_ping_stub(id_, expected_model_nb)
     motors_bus = DynamixelMotorsBus(
         port=mock_motors.port,
         motors=dummy_motors,
     )
     motors_bus.connect(assert_motors_exist=False)
 
-    ping_model_nb = motors_bus.ping(idx)
+    ping_model_nb = motors_bus.ping(id_)
 
     assert ping_model_nb == expected_model_nb
     assert mock_motors.stubs[stub_name].called
diff --git a/tests/motors/test_feetech.py b/tests/motors/test_feetech.py
index 1dc3d217..f65813c3 100644
--- a/tests/motors/test_feetech.py
+++ b/tests/motors/test_feetech.py
@@ -93,18 +93,18 @@ def test_abc_implementation(dummy_motors):
 
 
 # @pytest.mark.skip("TODO")
-@pytest.mark.parametrize("idx", [1, 2, 3])
-def test_ping(idx, mock_motors, dummy_motors):
-    expected_model_nb = MODEL_NUMBER[dummy_motors[f"dummy_{idx}"].model]
-    ping_stub = mock_motors.build_ping_stub(idx)
-    mobel_nb_stub = mock_motors.build_read_stub("Model_Number", idx, expected_model_nb)
+@pytest.mark.parametrize("id_", [1, 2, 3])
+def test_ping(id_, mock_motors, dummy_motors):
+    expected_model_nb = MODEL_NUMBER[dummy_motors[f"dummy_{id_}"].model]
+    ping_stub = mock_motors.build_ping_stub(id_)
+    mobel_nb_stub = mock_motors.build_read_stub("Model_Number", id_, expected_model_nb)
     motors_bus = FeetechMotorsBus(
         port=mock_motors.port,
         motors=dummy_motors,
     )
     motors_bus.connect(assert_motors_exist=False)
 
-    ping_model_nb = motors_bus.ping(idx)
+    ping_model_nb = motors_bus.ping(id_)
 
     assert ping_model_nb == expected_model_nb
     assert mock_motors.stubs[ping_stub].called

From a631e4c11c2a04904e833d3cf1b1cc039e516daa Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Tue, 25 Mar 2025 15:36:36 +0100
Subject: [PATCH 134/171] Rename idx -> id_

---
 lerobot/common/debugging/motors_bus.py | 6 +++---
 1 file changed, 3 insertions(+), 3 deletions(-)

diff --git a/lerobot/common/debugging/motors_bus.py b/lerobot/common/debugging/motors_bus.py
index cdb7d574..81b75bf2 100644
--- a/lerobot/common/debugging/motors_bus.py
+++ b/lerobot/common/debugging/motors_bus.py
@@ -49,20 +49,20 @@ def visualize_motors_bus(motors_bus: MotorsBus):
 
             print(f"read_s: {read_s * 1e3:.2f}ms ({1 / read_s:.0f} Hz)")
             for name, raw_ticks in raw_positions.items():
-                idx = motors_bus.motors[name].id
+                id_ = motors_bus.motors[name].id
                 model = motors_bus.motors[name].model
 
                 # 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, motors_bus, idx)
+                manual_adjusted = adjusted_to_homing_ticks(raw_ticks, model, motors_bus, id_)
                 # 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, motors_bus, idx)
+                inv_ticks = adjusted_to_motor_ticks(manual_ticks, model, motors_bus, id_)
 
                 print(
                     f"{name:15s} | "

From 2d3a5fb2be85e373aff728cd0f756dd2560ebbca Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Tue, 25 Mar 2025 15:37:18 +0100
Subject: [PATCH 135/171] (WIP) _async_read

---
 lerobot/common/motors/motors_bus.py | 10 +++++++---
 1 file changed, 7 insertions(+), 3 deletions(-)

diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py
index 40cda4f6..97d9884c 100644
--- a/lerobot/common/motors/motors_bus.py
+++ b/lerobot/common/motors/motors_bus.py
@@ -581,10 +581,14 @@ class MotorsBus(abc.ABC):
     # This could be at the cost of increase latency between the moment the data is produced by the motors and
     # the moment it is used by a policy.
     # def _async_read(self, motor_ids: list[str], address: int, n_bytes: int):
-    #     self.reader.rxPacket()
-    #     self.reader.txPacket()
+    #     if self.sync_reader.start_address != address or self.sync_reader.data_length != n_bytes or ...:
+    #         self._setup_sync_reader(motor_ids, address, n_bytes)
+    #     else:
+    #         self.sync_reader.rxPacket()
+    #         self.sync_reader.txPacket()
+
     #     for id_ in motor_ids:
-    #         value = self.reader.getData(id_, address, n_bytes)
+    #         value = self.sync_reader.getData(id_, address, n_bytes)
 
     def sync_write(
         self,

From 21c3ac42eecca067e36e478e7fa09666ac5fa668 Mon Sep 17 00:00:00 2001
From: Pepijn <138571049+pkooij@users.noreply.github.com>
Date: Tue, 25 Mar 2025 16:24:04 +0100
Subject: [PATCH 136/171] Add new calibration method for robot refactor (#896)

Co-authored-by: Simon Alibert <simon.alibert@huggingface.co>
---
 lerobot/common/motors/calibration.py          | 168 ++++++++++
 lerobot/common/motors/feetech/__init__.py     |   1 -
 .../motors/feetech/feetech_calibration.py     | 313 ------------------
 lerobot/common/motors/motors_bus.py           |   8 -
 lerobot/common/robots/koch/robot_koch.py      |   1 +
 lerobot/common/robots/manipulator.py          | 128 -------
 lerobot/common/robots/so100/robot_so100.py    |  37 ++-
 .../teleoperators/so100/teleop_so100.py       |  36 +-
 tests/motors/test_calibration.py              | 147 ++++++++
 9 files changed, 372 insertions(+), 467 deletions(-)
 delete mode 100644 lerobot/common/motors/feetech/feetech_calibration.py
 create mode 100644 tests/motors/test_calibration.py

diff --git a/lerobot/common/motors/calibration.py b/lerobot/common/motors/calibration.py
index f503a972..8329092f 100644
--- a/lerobot/common/motors/calibration.py
+++ b/lerobot/common/motors/calibration.py
@@ -1,4 +1,29 @@
+#!/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 select
+import sys
+import time
 from dataclasses import dataclass
+from pathlib import Path
+
+from .dynamixel.dynamixel import DynamixelMotorsBus
+from .feetech.feetech import FeetechMotorsBus
+from .motors_bus import MotorsBus
 
 
 @dataclass
@@ -8,3 +33,146 @@ class MotorCalibration:
     homing_offset: int
     range_min: int
     range_max: int
+
+
+def find_offset(motorbus: MotorsBus):
+    input("Move robot to the middle of its range of motion and press ENTER....")
+    for name in motorbus.names:
+        # Also reset to defaults
+        if isinstance(motorbus, FeetechMotorsBus):
+            motorbus.write("Offset", name, 0, raw_value=True)
+            motorbus.write("Min_Angle_Limit", name, 0, raw_value=True)
+            motorbus.write("Max_Angle_Limit", name, 4095, raw_value=True)
+        elif isinstance(motorbus, DynamixelMotorsBus):
+            motorbus.write("Homing_Offset", name, 0, raw_value=True)
+            motorbus.write("Min_Position_Limit", name, 0, raw_value=True)
+            motorbus.write("Max_Position_Limit", name, 4095, raw_value=True)
+        else:
+            raise ValueError("Motorbus instance is unknown")
+
+    middle_values = motorbus.sync_read("Present_Position", raw_values=True)
+
+    offsets = {}
+    for name, pos in middle_values.items():
+        offset = pos - 2047  # Center the middle reading at 2047.
+        MotorCalibration.set_offset(motorbus, offset, name)
+        offsets[name] = offset
+
+    return offsets
+
+
+def find_min_max(motorbus: MotorsBus):
+    print("Move all joints (except wrist_roll; id = 5) sequentially through their entire ranges of motion.")
+    print("Recording positions. Press ENTER to stop...")
+
+    recorded_data = {name: [] for name in motorbus.names}
+
+    while True:
+        positions = motorbus.sync_read("Present_Position", raw_values=True)
+        for name in motorbus.names:
+            recorded_data[name].append(positions[name])
+        time.sleep(0.01)
+
+        # Check if user pressed Enter
+        ready_to_read, _, _ = select.select([sys.stdin], [], [], 0)
+        if ready_to_read:
+            line = sys.stdin.readline()
+            if line.strip() == "":
+                break
+
+    min_max = {}
+    for name in motorbus.names:
+        motor_values = recorded_data[name]
+        raw_min = min(motor_values)
+        raw_max = max(motor_values)
+
+        if name == "wrist_roll":
+            physical_min = 0
+            physical_max = 4095
+        else:
+            physical_min = int(raw_min)
+            physical_max = int(raw_max)
+
+        MotorCalibration.set_min_max(motorbus, physical_min, physical_max, name)
+        min_max[name] = {"min": physical_min, "max": physical_max}
+
+    return min_max
+
+
+def set_calibration(motorbus: MotorsBus, calibration_fpath: Path) -> None:
+    with open(calibration_fpath) as f:
+        calibration = json.load(f)
+
+    motorbus.calibration = {int(id_): val for id_, val in calibration.items()}
+
+    for _, cal_data in motorbus.calibration.items():
+        name = cal_data.get("name")
+        if name not in motorbus.names:
+            print(f"Motor name '{name}' from calibration not found in arm names.")
+            continue
+
+        MotorCalibration.set_offset(motorbus, cal_data["homing_offset"], name)
+        MotorCalibration.set_min_max(motorbus, cal_data["min"], cal_data["max"], name)
+
+
+def set_offset(motorbus: MotorsBus, homing_offset: int, name: str):
+    homing_offset = int(homing_offset)
+
+    # Clamp to [-2047..+2047]
+    if homing_offset > 2047:
+        homing_offset = 2047
+        print(
+            f"Warning: '{homing_offset}' is getting clamped because its larger then 2047; This should not happen!"
+        )
+    elif homing_offset < -2047:
+        homing_offset = -2047
+        print(
+            f"Warning: '{homing_offset}' is getting clamped because its smaller then -2047; This should not happen!"
+        )
+
+    direction_bit = 1 if homing_offset < 0 else 0  # Determine the direction (sign) bit and magnitude
+    magnitude = abs(homing_offset)
+    servo_offset = (
+        direction_bit << 11
+    ) | magnitude  # Combine sign bit (bit 11) with the magnitude (bits 0..10)
+
+    if isinstance(motorbus, FeetechMotorsBus):
+        motorbus.write("Offset", name, servo_offset, raw_value=True)
+        read_offset = motorbus.sync_read("Offset", name, raw_values=True)
+    elif isinstance(motorbus, DynamixelMotorsBus):
+        motorbus.write("Homing_Offset", name, servo_offset, raw_value=True)
+        read_offset = motorbus.sync_read("Homing_Offset", name, raw_values=True)
+    else:
+        raise ValueError("Motorbus instance is unknown")
+
+    if read_offset[name] != servo_offset:
+        raise ValueError(
+            f"Offset not set correctly for motor '{name}'. read: {read_offset} does not equal {servo_offset}"
+        )
+
+
+def set_min_max(motorbus: MotorsBus, min: int, max: int, name: str):
+    if isinstance(motorbus, FeetechMotorsBus):
+        motorbus.write("Min_Angle_Limit", name, min, raw_value=True)
+        motorbus.write("Max_Angle_Limit", name, max, raw_value=True)
+
+        read_min = motorbus.sync_read("Min_Angle_Limit", name, raw_values=True)
+        read_max = motorbus.sync_read("Max_Angle_Limit", name, raw_values=True)
+    elif isinstance(motorbus, DynamixelMotorsBus):
+        motorbus.write("Min_Position_Limit", name, min, raw_value=True)
+        motorbus.write("Max_Position_Limit", name, max, raw_value=True)
+
+        read_min = motorbus.sync_read("Min_Position_Limit", name, raw_values=True)
+        read_max = motorbus.sync_read("Max_Position_Limit", name, raw_values=True)
+    else:
+        raise ValueError("Motorbus instance is unknown")
+
+    if read_min[name] != min:
+        raise ValueError(
+            f"Min is not set correctly for motor '{name}'. read: {read_min} does not equal {min}"
+        )
+
+    if read_max[name] != max:
+        raise ValueError(
+            f"Max is not set correctly for motor '{name}'. read: {read_max} does not equal {max}"
+        )
diff --git a/lerobot/common/motors/feetech/__init__.py b/lerobot/common/motors/feetech/__init__.py
index dbe9a08d..911d1d19 100644
--- a/lerobot/common/motors/feetech/__init__.py
+++ b/lerobot/common/motors/feetech/__init__.py
@@ -1,3 +1,2 @@
 from .feetech import DriveMode, FeetechMotorsBus, OperatingMode, TorqueMode
-from .feetech_calibration import apply_feetech_offsets_from_calibration, run_full_arm_calibration
 from .tables import *
diff --git a/lerobot/common/motors/feetech/feetech_calibration.py b/lerobot/common/motors/feetech/feetech_calibration.py
deleted file mode 100644
index 098370d0..00000000
--- a/lerobot/common/motors/feetech/feetech_calibration.py
+++ /dev/null
@@ -1,313 +0,0 @@
-# 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 numpy as np
-
-from ..motors_bus import (
-    CalibrationMode,
-    MotorsBus,
-)
-from .feetech import FeetechMotorsBus, TorqueMode
-from .tables import MODEL_RESOLUTION
-
-URL_TEMPLATE = (
-    "https://raw.githubusercontent.com/huggingface/lerobot/main/media/{robot}/{arm}_{position}.webp"
-)
-
-
-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.")
-
-
-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.names
-    ]
-
-
-def reset_offset(motor_id, motor_bus):
-    # Open the write lock, changes to EEPROM do NOT persist yet
-    motor_bus.write("Lock", 1)
-
-    # Set offset to 0
-    motor_name = motor_bus.motor_names[motor_id - 1]
-    motor_bus.write("Offset", 0, motor_names=[motor_name])
-
-    # Close the write lock, changes to EEPROM do persist
-    motor_bus.write("Lock", 0)
-
-    # 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
-
-
-def calibrate_homing_motor(motor_id, motor_bus):
-    reset_offset(motor_id, motor_bus)
-
-    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}")
-
-    return home_ticks
-
-
-def calibrate_linear_motor(motor_id, motor_bus):
-    motor_names = motor_bus.motor_names
-    motor_name = motor_names[motor_id - 1]
-
-    reset_offset(motor_id, motor_bus)
-
-    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}")
-
-    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}")
-
-    return start_pos, end_pos
-
-
-def single_motor_calibration(arm: MotorsBus, motor_id: int):
-    """Calibrates a single motor and returns its calibration data for updating the calibration file."""
-
-    disable_torque(arm)
-    print(f"\n--- Calibrating Motor {motor_id} ---")
-
-    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": 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.names[motor_id - 1],
-    }
-
-    return calib_dict
-
-
-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.
-
-    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.
-
-    **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.
-
-    **Example Usage:**
-    ```python
-    run_full_arm_calibration(arm, "so100", "left", "follower")
-    ```
-    """
-    disable_torque(arm)
-
-    print(f"\nRunning calibration of {robot_type} {arm_name} {arm_type}...")
-
-    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...")
-
-    start_positions = np.zeros(len(arm.ids))
-    end_positions = np.zeros(len(arm.ids))
-    encoder_offsets = np.zeros(len(arm.ids))
-
-    modes = get_calibration_modes(arm)
-
-    for i, motor_id in enumerate(arm.ids):
-        if modes[i] == CalibrationMode.DEGREE.name:
-            encoder_offsets[i] = calibrate_homing_motor(motor_id, arm)
-            start_positions[i] = 0
-            end_positions[i] = 0
-
-    for i, motor_id in enumerate(arm.ids):
-        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")
-    input("Press Enter to continue...")
-
-    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": 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.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.")
-
-
-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, motor_bus: MotorsBus, motor_id: int) -> int:
-    """
-    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 motor_bus.calibration is not None:
-        drive_mode = motor_bus.calibration["drive_mode"][motor_id - 1]
-
-    if drive_mode:
-        ticks *= -1
-
-    return ticks
-
-
-def adjusted_to_motor_ticks(adjusted_pos: int, model: str, motor_bus: MotorsBus, 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 motor_bus.calibration is not None:
-        drive_mode = motor_bus.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
diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py
index 40cda4f6..71d01e49 100644
--- a/lerobot/common/motors/motors_bus.py
+++ b/lerobot/common/motors/motors_bus.py
@@ -20,12 +20,10 @@
 # https://github.com/astral-sh/ruff/issues/3711
 
 import abc
-import json
 import logging
 from dataclasses import dataclass
 from enum import Enum
 from functools import cached_property
-from pathlib import Path
 from pprint import pformat
 from typing import Protocol, TypeAlias, overload
 
@@ -414,12 +412,6 @@ class MotorsBus(abc.ABC):
             logger.error(e)
             return False
 
-    def set_calibration(self, calibration_fpath: Path) -> None:
-        with open(calibration_fpath) as f:
-            calibration = json.load(f)
-
-        self.calibration = {int(id_): val for id_, val in calibration.items()}
-
     @abc.abstractmethod
     def _calibrate_values(self, ids_values: dict[int, int]) -> dict[int, float]:
         pass
diff --git a/lerobot/common/robots/koch/robot_koch.py b/lerobot/common/robots/koch/robot_koch.py
index 90a63776..fa1ee284 100644
--- a/lerobot/common/robots/koch/robot_koch.py
+++ b/lerobot/common/robots/koch/robot_koch.py
@@ -149,6 +149,7 @@ class KochRobot(Robot):
         self.is_connected = True
 
     def calibrate(self) -> None:
+        # TODO(pepijn): Do calibration in same way as so100
         """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].
diff --git a/lerobot/common/robots/manipulator.py b/lerobot/common/robots/manipulator.py
index 5bdddd03..c5507ecf 100644
--- a/lerobot/common/robots/manipulator.py
+++ b/lerobot/common/robots/manipulator.py
@@ -18,7 +18,6 @@ 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 time
 import warnings
 from dataclasses import dataclass, field
@@ -81,73 +80,6 @@ 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.
@@ -347,8 +279,6 @@ class ManipulatorRobot:
         for name in self.leader_arms:
             self.leader_arms[name].write("Torque_Enable", TorqueMode.DISABLED.value)
 
-        self.activate_calibration()
-
         # Set robot preset (e.g. torque in leader gripper for Koch v1.1)
         if self.robot_type in ["koch", "koch_bimanual"]:
             self.set_koch_robot_preset()
@@ -385,61 +315,6 @@ class ManipulatorRobot:
 
         self.is_connected = True
 
-    def activate_calibration(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].
-        """
-
-        def load_or_run_calibration_(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:
-                # TODO(rcadene): display a warning in __init__ if calibration file not available
-                print(f"Missing calibration file '{arm_calib_path}'")
-
-                if self.robot_type in ["koch", "koch_bimanual", "aloha"]:
-                    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.feetech_calibration import (
-                        run_full_arm_calibration,
-                    )
-
-                    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:
-                    json.dump(calibration, f)
-
-            return 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):
             from lerobot.common.motors.dynamixel.dynamixel import TorqueMode
@@ -540,9 +415,6 @@ class ManipulatorRobot:
             # Set I_Coefficient and D_Coefficient to default value 0 and 32
             self.follower_arms[name].write("I_Coefficient", 0)
             self.follower_arms[name].write("D_Coefficient", 32)
-            # Close the write lock so that Maximum_Acceleration gets written to EPROM address,
-            # which is mandatory for Maximum_Acceleration to take effect after rebooting.
-            self.follower_arms[name].write("Lock", 0)
             # Set Maximum_Acceleration to 254 to speedup acceleration and deceleration of
             # the motors. Note: this configuration is not in the official STS3215 Memory Table
             self.follower_arms[name].write("Maximum_Acceleration", 254)
diff --git a/lerobot/common/robots/so100/robot_so100.py b/lerobot/common/robots/so100/robot_so100.py
index a0321477..f05d7bef 100644
--- a/lerobot/common/robots/so100/robot_so100.py
+++ b/lerobot/common/robots/so100/robot_so100.py
@@ -14,6 +14,7 @@
 # See the License for the specific language governing permissions and
 # limitations under the License.
 
+import json
 import logging
 import time
 
@@ -23,11 +24,11 @@ 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 import CalibrationMode, Motor
+from lerobot.common.motors.calibration import find_min_max, find_offset, set_calibration
 from lerobot.common.motors.feetech import (
     FeetechMotorsBus,
     OperatingMode,
     TorqueMode,
-    apply_feetech_offsets_from_calibration,
 )
 
 from ..robot import Robot
@@ -97,15 +98,17 @@ class SO100Robot(Robot):
             # Set I_Coefficient and D_Coefficient to default value 0 and 32
             self.arm.write("I_Coefficient", name, 0)
             self.arm.write("D_Coefficient", name, 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", name, 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", name, 254)
             self.arm.write("Acceleration", name, 254)
 
-        self.calibrate()
+        if not self.calibration_fpath.exists():
+            print("Calibration file not found. Running calibration.")
+            self.calibrate()
+        else:
+            print("Calibration file found. Loading calibration data.")
+            set_calibration(self.arm, self.calibration_fpath)
 
         for name in self.arm.names:
             self.arm.write("Torque_Enable", name, TorqueMode.ENABLED.value)
@@ -135,15 +138,25 @@ class SO100Robot(Robot):
             cam.connect()
 
     def calibrate(self) -> None:
-        raise NotImplementedError
+        print(f"\nRunning calibration of {self.name} robot")
 
-    def set_calibration(self) -> None:
-        if not self.calibration_fpath.exists():
-            logging.error("Calibration file not found. Please run calibration first")
-            raise FileNotFoundError(self.calibration_fpath)
+        offsets = find_offset(self.arm)
+        min_max = find_min_max(self.arm)
 
-        self.arm.set_calibration(self.calibration_fpath)
-        apply_feetech_offsets_from_calibration(self.arm, self.arm.calibration)
+        calibration = {}
+        for name in self.arm.names:
+            motor_id = self.arm.motors[name].id
+            calibration[str(motor_id)] = {
+                "name": name,
+                "homing_offset": offsets.get(name, 0),
+                "drive_mode": 0,
+                "min": min_max[name]["min"],
+                "max": min_max[name]["max"],
+            }
+
+        with open(self.calibration_fpath, "w") as f:
+            json.dump(calibration, f, indent=4)
+        print("Calibration saved to", self.calibration_fpath)
 
     def get_observation(self) -> dict[str, np.ndarray]:
         """The returned observations do not have a batch dimension."""
diff --git a/lerobot/common/teleoperators/so100/teleop_so100.py b/lerobot/common/teleoperators/so100/teleop_so100.py
index ab0bf3c0..89524165 100644
--- a/lerobot/common/teleoperators/so100/teleop_so100.py
+++ b/lerobot/common/teleoperators/so100/teleop_so100.py
@@ -14,6 +14,7 @@
 # See the License for the specific language governing permissions and
 # limitations under the License.
 
+import json
 import logging
 import time
 
@@ -21,11 +22,11 @@ import numpy as np
 
 from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError
 from lerobot.common.motors import CalibrationMode, Motor
+from lerobot.common.motors.calibration import find_min_max, find_offset, set_calibration
 from lerobot.common.motors.feetech import (
     FeetechMotorsBus,
-    TorqueMode,
-    apply_feetech_offsets_from_calibration,
 )
+from lerobot.common.motors.feetech.feetech import TorqueMode
 
 from ..teleoperator import Teleoperator
 from .configuration_so100 import SO100TeleopConfig
@@ -71,6 +72,13 @@ class SO100Teleop(Teleoperator):
         return {}
 
     def configure(self) -> None:
+        if not self.calibration_fpath.exists():
+            print("Calibration file not found. Running calibration.")
+            self.calibrate()
+        else:
+            print("Calibration file found. Loading calibration data.")
+            set_calibration(self.arm, self.calibration_fpath)
+
         # We assume that at connection time, arm is in a rest position,
         # and torque can be safely disabled to run calibration.
         for name in self.arm.names:
@@ -89,13 +97,32 @@ class SO100Teleop(Teleoperator):
         logging.info("Connecting arm.")
         self.arm.connect()
         self.configure()
-        self.calibrate()
 
         # Check arm can be read
         self.arm.sync_read("Present_Position")
 
     def calibrate(self) -> None:
-        raise NotImplementedError
+        print(f"\nRunning calibration of {self.name} teleop")
+        for name in self.arm.names:
+            self.arm.write("Torque_Enable", name, TorqueMode.DISABLED.value)
+
+        offsets = find_offset(self.arm)
+        min_max = find_min_max(self.arm)
+
+        calibration = {}
+        for name in self.arm.names:
+            motor_id = self.arm.motors[name].id
+            calibration[str(motor_id)] = {
+                "name": name,
+                "homing_offset": offsets.get(name, 0),
+                "drive_mode": 0,
+                "min": min_max[name]["min"],
+                "max": min_max[name]["max"],
+            }
+
+        with open(self.calibration_fpath, "w") as f:
+            json.dump(calibration, f, indent=4)
+        print("Calibration saved to", self.calibration_fpath)
 
     def set_calibration(self) -> None:
         """After calibration all motors function in human interpretable ranges.
@@ -107,7 +134,6 @@ class SO100Teleop(Teleoperator):
             raise FileNotFoundError(self.calibration_fpath)
 
         self.arm.set_calibration(self.calibration_fpath)
-        apply_feetech_offsets_from_calibration(self.arm, self.arm.calibration)
 
     def get_action(self) -> np.ndarray:
         """The returned action does not have a batch dimension."""
diff --git a/tests/motors/test_calibration.py b/tests/motors/test_calibration.py
new file mode 100644
index 00000000..011174db
--- /dev/null
+++ b/tests/motors/test_calibration.py
@@ -0,0 +1,147 @@
+import sys
+from typing import Generator
+from unittest.mock import Mock, call, patch
+
+import pytest
+import scservo_sdk as scs
+
+from lerobot.common.motors import CalibrationMode, Motor
+from lerobot.common.motors.calibration import find_min_max, find_offset, set_min_max, set_offset
+from lerobot.common.motors.feetech import FeetechMotorsBus
+from tests.mocks.mock_feetech import MockMotors, MockPortHandler
+
+
+@pytest.fixture(autouse=True)
+def patch_port_handler():
+    if sys.platform == "darwin":
+        with patch.object(scs, "PortHandler", MockPortHandler):
+            yield
+    else:
+        yield
+
+
+@pytest.fixture
+def mock_motors() -> Generator[MockMotors, None, None]:
+    motors = MockMotors()
+    motors.open()
+    yield motors
+    motors.close()
+
+
+@pytest.fixture
+def dummy_motors() -> dict[str, Motor]:
+    return {
+        "dummy_1": Motor(1, "sts3215", CalibrationMode.RANGE_M100_100),
+        "wrist_roll": Motor(2, "sts3215", CalibrationMode.RANGE_M100_100),
+        "dummy_3": Motor(3, "sts3215", CalibrationMode.RANGE_M100_100),
+    }
+
+
+@pytest.fixture(autouse=True)
+def patch_broadcast_ping():
+    with patch.object(FeetechMotorsBus, "broadcast_ping", return_value={1: 777, 2: 777, 3: 777}):
+        yield
+
+
+@pytest.mark.skipif(sys.platform != "darwin", reason=f"No patching needed on {sys.platform=}")
+def test_autouse_patch():
+    """Ensures that the autouse fixture correctly patches scs.PortHandler with MockPortHandler."""
+    assert scs.PortHandler is MockPortHandler
+
+
+@pytest.mark.parametrize(
+    "motor_names, read_values",
+    [
+        (
+            ["dummy_1"],
+            [{"dummy_1": 3000}],
+        ),
+    ],
+    ids=["two-motors"],
+)
+def test_find_offset(mock_motors, dummy_motors, motor_names, read_values):
+    motors_bus = FeetechMotorsBus(
+        port=mock_motors.port,
+        motors=dummy_motors,
+    )
+    motors_bus.connect()
+
+    with (
+        patch("builtins.input", return_value=""),
+        patch("lerobot.common.motors.calibration.set_offset") as mock_set_offset,
+    ):
+        motors_bus.sync_read = Mock(side_effect=[{"dummy_1": 3000}])
+        motors_bus.motor_names = motor_names
+        motors_bus.write = Mock(return_value=None)
+
+        find_offset(motors_bus)
+        # Compute the expected offset: 3000 - 2047 = 953.
+        expected_calls = [call(motors_bus, 953, "dummy_1")]
+        mock_set_offset.assert_has_calls(expected_calls, any_order=False)
+
+
+def test_find_min_max(mock_motors, dummy_motors):
+    motors_bus = FeetechMotorsBus(
+        port=mock_motors.port,
+        motors=dummy_motors,
+    )
+    motors_bus.connect()
+    motors_bus.motor_names = list(dummy_motors.keys())
+    read_side_effect = [
+        {"dummy_1": 10, "wrist_roll": 20, "dummy_3": 30},  # For first sync_read call.
+        {"dummy_1": 4000, "wrist_roll": 2000, "dummy_3": 100},  # For second sync_read call.
+        {"dummy_1": 100, "wrist_roll": 4050, "dummy_3": 2010},  # For third sync_read call.
+    ]
+    motors_bus.sync_read = Mock(side_effect=read_side_effect)
+
+    select_returns = [
+        ([], [], []),  # First iteration: no input.
+        ([], [], []),  # Second iteration.
+        ([sys.stdin], [], []),  # Third iteration: simulate pressing ENTER.
+    ]
+    with (
+        patch("lerobot.common.motors.calibration.set_min_max") as mock_set_min_max,
+        patch("lerobot.common.motors.calibration.select.select", side_effect=select_returns),
+        patch("sys.stdin.readline", return_value="\n"),
+    ):
+        find_min_max(motors_bus)
+
+    mock_set_min_max.assert_any_call(motors_bus, 10, 4000, "dummy_1")
+    mock_set_min_max.assert_any_call(motors_bus, 0, 4095, "wrist_roll")  # wrist_roll is forced to [0,4095]
+    mock_set_min_max.assert_any_call(motors_bus, 30, 2010, "dummy_3")
+    assert mock_set_min_max.call_count == 3
+
+
+def test_set_offset_clamping(mock_motors, dummy_motors):
+    motors_bus = FeetechMotorsBus(
+        port=mock_motors.port,
+        motors=dummy_motors,
+    )
+    motors_bus.connect()
+    motors_bus.sync_read = Mock(return_value={"dummy_1": 2047})
+    motors_bus.write = Mock()
+    # A very large offset should be clamped to +2047.
+    set_offset(motors_bus, 9999, "dummy_1")
+    motors_bus.write.assert_any_call("Offset", "dummy_1", 2047, raw_value=True)
+
+
+def test_set_min_max(mock_motors, dummy_motors):
+    motors_bus = FeetechMotorsBus(
+        port=mock_motors.port,
+        motors=dummy_motors,
+    )
+    motors_bus.connect()
+
+    def _sync_read_side_effect(data_name, motors, *, raw_values=False):
+        if data_name == "Min_Angle_Limit":
+            return {"dummy_1": 100}
+        elif data_name == "Max_Angle_Limit":
+            return {"dummy_1": 3000}
+        return {}
+
+    motors_bus.sync_read = Mock(side_effect=_sync_read_side_effect)
+
+    motors_bus.write = Mock()
+    set_min_max(motors_bus, 100, 3000, "dummy_1")
+    motors_bus.write.assert_any_call("Min_Angle_Limit", "dummy_1", 100, raw_value=True)
+    motors_bus.write.assert_any_call("Max_Angle_Limit", "dummy_1", 3000, raw_value=True)

From faa476f0d21365d7626bc780c64ec18b10c629b6 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Tue, 25 Mar 2025 17:33:05 +0100
Subject: [PATCH 137/171] Remove deprecated scripts

---
 lerobot/common/debugging/__init__.py          |   3 -
 lerobot/common/debugging/motors_bus.py        |  86 --
 .../common/motors/dynamixel/dynamixel_old.py  | 895 ------------------
 3 files changed, 984 deletions(-)
 delete mode 100644 lerobot/common/debugging/__init__.py
 delete mode 100644 lerobot/common/debugging/motors_bus.py
 delete mode 100644 lerobot/common/motors/dynamixel/dynamixel_old.py

diff --git a/lerobot/common/debugging/__init__.py b/lerobot/common/debugging/__init__.py
deleted file mode 100644
index e137aa31..00000000
--- a/lerobot/common/debugging/__init__.py
+++ /dev/null
@@ -1,3 +0,0 @@
-from .motors_bus import visualize_motors_bus
-
-__all__ = ["visualize_motors_bus"]
diff --git a/lerobot/common/debugging/motors_bus.py b/lerobot/common/debugging/motors_bus.py
deleted file mode 100644
index 81b75bf2..00000000
--- a/lerobot/common/debugging/motors_bus.py
+++ /dev/null
@@ -1,86 +0,0 @@
-"""
-Usage example
-
-```python
-from lerobot.common.debugging.motors_bus import visualize_motors_bus
-from lerobot.common.robots.so100 import SO100Robot, SO100RobotConfig
-
-cfg = SO100RobotConfig(port="/dev/tty.usbmodem58760430541")
-so100 = SO100Robot(cfg)
-
-visualize_motors_bus(so100.arm)
-```
-"""
-
-import time
-
-from lerobot.common.motors import MotorsBus
-from lerobot.common.motors.feetech.feetech_calibration import (
-    adjusted_to_homing_ticks,
-    adjusted_to_motor_ticks,
-    convert_degrees_to_ticks,
-    convert_ticks_to_degrees,
-)
-
-
-def visualize_motors_bus(motors_bus: MotorsBus):
-    """
-    Reads each joint's (1) raw ticks, (2) homed ticks, (3) degrees, and (4) invert-adjusted ticks.
-    """
-    if not motors_bus.is_connected:
-        motors_bus.connect()
-
-    # Disable torque on all motors so you can move them freely by hand
-    for id_ in motors_bus.ids:
-        motors_bus.write("Torque_Enable", id_, 0)
-
-    print("Torque disabled on all joints.")
-
-    try:
-        print("\nPress Ctrl+C to quit.\n")
-        while True:
-            # Read *raw* positions (no calibration).
-            start = time.perf_counter()
-            raw_positions = motors_bus.sync_read("Present_Position", raw_values=True)
-            read_s = time.perf_counter() - start
-
-            # # Read *already-homed* positions
-            # homed_positions = motor_bus.read("Present_Position")
-
-            print(f"read_s: {read_s * 1e3:.2f}ms ({1 / read_s:.0f} Hz)")
-            for name, raw_ticks in raw_positions.items():
-                id_ = motors_bus.motors[name].id
-                model = motors_bus.motors[name].model
-
-                # 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, motors_bus, id_)
-                # 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, motors_bus, id_)
-
-                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...")
-        motors_bus.disconnect()
-
-
-if __name__ == "__main__":
-    visualize_motors_bus()
diff --git a/lerobot/common/motors/dynamixel/dynamixel_old.py b/lerobot/common/motors/dynamixel/dynamixel_old.py
deleted file mode 100644
index 55f6069b..00000000
--- a/lerobot/common/motors/dynamixel/dynamixel_old.py
+++ /dev/null
@@ -1,895 +0,0 @@
-# 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 enum
-import logging
-import math
-import time
-import traceback
-from copy import deepcopy
-
-import numpy as np
-import tqdm
-
-from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError
-from lerobot.common.utils.utils import capture_timestamp_utc
-
-PROTOCOL_VERSION = 2.0
-BAUDRATE = 1_000_000
-TIMEOUT_MS = 1000
-
-MAX_ID_RANGE = 252
-
-# The following bounds define the lower and upper joints range (after calibration).
-# For joints in degree (i.e. revolute joints), their nominal range is [-180, 180] degrees
-# which corresponds to a half rotation on the left and half rotation on the right.
-# Some joints might require higher range, so we allow up to [-270, 270] degrees until
-# an error is raised.
-LOWER_BOUND_DEGREE = -270
-UPPER_BOUND_DEGREE = 270
-# For joints in percentage (i.e. joints that move linearly like the prismatic joint of a gripper),
-# their nominal range is [0, 100] %. For instance, for Aloha gripper, 0% is fully
-# closed, and 100% is fully open. To account for slight calibration issue, we allow up to
-# [-10, 110] until an error is raised.
-LOWER_BOUND_LINEAR = -10
-UPPER_BOUND_LINEAR = 110
-
-HALF_TURN_DEGREE = 180
-
-# https://emanual.robotis.com/docs/en/dxl/x/xl330-m077
-# https://emanual.robotis.com/docs/en/dxl/x/xl330-m288
-# https://emanual.robotis.com/docs/en/dxl/x/xl430-w250
-# https://emanual.robotis.com/docs/en/dxl/x/xm430-w350
-# https://emanual.robotis.com/docs/en/dxl/x/xm540-w270
-# https://emanual.robotis.com/docs/en/dxl/x/xc430-w150
-
-# data_name: (address, size_byte)
-X_SERIES_CONTROL_TABLE = {
-    "Model_Number": (0, 2),
-    "Model_Information": (2, 4),
-    "Firmware_Version": (6, 1),
-    "ID": (7, 1),
-    "Baud_Rate": (8, 1),
-    "Return_Delay_Time": (9, 1),
-    "Drive_Mode": (10, 1),
-    "Operating_Mode": (11, 1),
-    "Secondary_ID": (12, 1),
-    "Protocol_Type": (13, 1),
-    "Homing_Offset": (20, 4),
-    "Moving_Threshold": (24, 4),
-    "Temperature_Limit": (31, 1),
-    "Max_Voltage_Limit": (32, 2),
-    "Min_Voltage_Limit": (34, 2),
-    "PWM_Limit": (36, 2),
-    "Current_Limit": (38, 2),
-    "Acceleration_Limit": (40, 4),
-    "Velocity_Limit": (44, 4),
-    "Max_Position_Limit": (48, 4),
-    "Min_Position_Limit": (52, 4),
-    "Shutdown": (63, 1),
-    "Torque_Enable": (64, 1),
-    "LED": (65, 1),
-    "Status_Return_Level": (68, 1),
-    "Registered_Instruction": (69, 1),
-    "Hardware_Error_Status": (70, 1),
-    "Velocity_I_Gain": (76, 2),
-    "Velocity_P_Gain": (78, 2),
-    "Position_D_Gain": (80, 2),
-    "Position_I_Gain": (82, 2),
-    "Position_P_Gain": (84, 2),
-    "Feedforward_2nd_Gain": (88, 2),
-    "Feedforward_1st_Gain": (90, 2),
-    "Bus_Watchdog": (98, 1),
-    "Goal_PWM": (100, 2),
-    "Goal_Current": (102, 2),
-    "Goal_Velocity": (104, 4),
-    "Profile_Acceleration": (108, 4),
-    "Profile_Velocity": (112, 4),
-    "Goal_Position": (116, 4),
-    "Realtime_Tick": (120, 2),
-    "Moving": (122, 1),
-    "Moving_Status": (123, 1),
-    "Present_PWM": (124, 2),
-    "Present_Current": (126, 2),
-    "Present_Velocity": (128, 4),
-    "Present_Position": (132, 4),
-    "Velocity_Trajectory": (136, 4),
-    "Position_Trajectory": (140, 4),
-    "Present_Input_Voltage": (144, 2),
-    "Present_Temperature": (146, 1),
-}
-
-X_SERIES_BAUDRATE_TABLE = {
-    0: 9_600,
-    1: 57_600,
-    2: 115_200,
-    3: 1_000_000,
-    4: 2_000_000,
-    5: 3_000_000,
-    6: 4_000_000,
-}
-
-CALIBRATION_REQUIRED = ["Goal_Position", "Present_Position"]
-CONVERT_UINT32_TO_INT32_REQUIRED = ["Goal_Position", "Present_Position"]
-
-MODEL_CONTROL_TABLE = {
-    "x_series": X_SERIES_CONTROL_TABLE,
-    "xl330-m077": X_SERIES_CONTROL_TABLE,
-    "xl330-m288": X_SERIES_CONTROL_TABLE,
-    "xl430-w250": X_SERIES_CONTROL_TABLE,
-    "xm430-w350": X_SERIES_CONTROL_TABLE,
-    "xm540-w270": X_SERIES_CONTROL_TABLE,
-    "xc430-w150": X_SERIES_CONTROL_TABLE,
-}
-
-MODEL_RESOLUTION = {
-    "x_series": 4096,
-    "xl330-m077": 4096,
-    "xl330-m288": 4096,
-    "xl430-w250": 4096,
-    "xm430-w350": 4096,
-    "xm540-w270": 4096,
-    "xc430-w150": 4096,
-}
-
-MODEL_BAUDRATE_TABLE = {
-    "x_series": X_SERIES_BAUDRATE_TABLE,
-    "xl330-m077": X_SERIES_BAUDRATE_TABLE,
-    "xl330-m288": X_SERIES_BAUDRATE_TABLE,
-    "xl430-w250": X_SERIES_BAUDRATE_TABLE,
-    "xm430-w350": X_SERIES_BAUDRATE_TABLE,
-    "xm540-w270": X_SERIES_BAUDRATE_TABLE,
-    "xc430-w150": X_SERIES_BAUDRATE_TABLE,
-}
-
-NUM_READ_RETRY = 10
-NUM_WRITE_RETRY = 10
-
-
-def convert_degrees_to_steps(degrees: float | np.ndarray, models: str | list[str]) -> np.ndarray:
-    """This function converts the degree range to the step range for indicating motors rotation.
-    It assumes a motor achieves a full rotation by going from -180 degree position to +180.
-    The motor resolution (e.g. 4096) corresponds to the number of steps needed to achieve a full rotation.
-    """
-    resolutions = [MODEL_RESOLUTION[model] for model in models]
-    steps = degrees / 180 * np.array(resolutions) / 2
-    steps = steps.astype(int)
-    return steps
-
-
-def convert_to_bytes(value, bytes, mock=False):
-    if mock:
-        return value
-
-    import dynamixel_sdk as dxl
-
-    # Note: No need to convert back into unsigned int, since this byte preprocessing
-    # already handles it for us.
-    if bytes == 1:
-        data = [
-            dxl.DXL_LOBYTE(dxl.DXL_LOWORD(value)),
-        ]
-    elif bytes == 2:
-        data = [
-            dxl.DXL_LOBYTE(dxl.DXL_LOWORD(value)),
-            dxl.DXL_HIBYTE(dxl.DXL_LOWORD(value)),
-        ]
-    elif bytes == 4:
-        data = [
-            dxl.DXL_LOBYTE(dxl.DXL_LOWORD(value)),
-            dxl.DXL_HIBYTE(dxl.DXL_LOWORD(value)),
-            dxl.DXL_LOBYTE(dxl.DXL_HIWORD(value)),
-            dxl.DXL_HIBYTE(dxl.DXL_HIWORD(value)),
-        ]
-    else:
-        raise NotImplementedError(
-            f"Value of the number of bytes to be sent is expected to be in [1, 2, 4], but "
-            f"{bytes} is provided instead."
-        )
-    return data
-
-
-def get_group_sync_key(data_name, motor_names):
-    group_key = f"{data_name}_" + "_".join(motor_names)
-    return group_key
-
-
-def get_result_name(fn_name, data_name, motor_names):
-    group_key = get_group_sync_key(data_name, motor_names)
-    rslt_name = f"{fn_name}_{group_key}"
-    return rslt_name
-
-
-def get_queue_name(fn_name, data_name, motor_names):
-    group_key = get_group_sync_key(data_name, motor_names)
-    queue_name = f"{fn_name}_{group_key}"
-    return queue_name
-
-
-def get_log_name(var_name, fn_name, data_name, motor_names):
-    group_key = get_group_sync_key(data_name, motor_names)
-    log_name = f"{var_name}_{fn_name}_{group_key}"
-    return log_name
-
-
-def assert_same_address(model_ctrl_table, motor_models, data_name):
-    all_addr = []
-    all_bytes = []
-    for model in motor_models:
-        addr, bytes = model_ctrl_table[model][data_name]
-        all_addr.append(addr)
-        all_bytes.append(bytes)
-
-    if len(set(all_addr)) != 1:
-        raise NotImplementedError(
-            f"At least two motor models use a different address for `data_name`='{data_name}' ({list(zip(motor_models, all_addr, strict=False))}). Contact a LeRobot maintainer."
-        )
-
-    if len(set(all_bytes)) != 1:
-        raise NotImplementedError(
-            f"At least two motor models use a different bytes representation for `data_name`='{data_name}' ({list(zip(motor_models, all_bytes, strict=False))}). Contact a LeRobot maintainer."
-        )
-
-
-class TorqueMode(enum.Enum):
-    ENABLED = 1
-    DISABLED = 0
-
-
-class DriveMode(enum.Enum):
-    NON_INVERTED = 0
-    INVERTED = 1
-
-
-class CalibrationMode(enum.Enum):
-    # Joints with rotational motions are expressed in degrees in nominal range of [-180, 180]
-    DEGREE = 0
-    # Joints with linear motions (like gripper of Aloha) are expressed in nominal range of [0, 100]
-    LINEAR = 1
-
-
-class JointOutOfRangeError(Exception):
-    def __init__(self, message="Joint is out of range"):
-        self.message = message
-        super().__init__(self.message)
-
-
-class DynamixelMotorsBus:
-    """
-    The DynamixelMotorsBus class allows to efficiently read and write to the attached motors. It relies on
-    the python dynamixel sdk to communicate with the motors. For more info, see the [Dynamixel SDK Documentation](https://emanual.robotis.com/docs/en/software/dynamixel/dynamixel_sdk/sample_code/python_read_write_protocol_2_0/#python-read-write-protocol-20).
-
-    A DynamixelMotorsBus instance requires a port (e.g. `DynamixelMotorsBus(port="/dev/tty.usbmodem575E0031751"`)).
-    To find the port, you can run our utility script:
-    ```bash
-    python lerobot/scripts/find_motors_bus_port.py
-    >>> Finding all available ports for the MotorBus.
-    >>> ['/dev/tty.usbmodem575E0032081', '/dev/tty.usbmodem575E0031751']
-    >>> Remove the usb cable from your DynamixelMotorsBus and press Enter when done.
-    >>> The port of this DynamixelMotorsBus is /dev/tty.usbmodem575E0031751.
-    >>> Reconnect the usb cable.
-    ```
-
-    Example of usage for 1 motor connected to the bus:
-    ```python
-    motor_name = "gripper"
-    motor_index = 6
-    motor_model = "xl330-m288"
-
-    motors_bus = DynamixelMotorsBus(
-        port="/dev/tty.usbmodem575E0031751",
-        motors={motor_name: (motor_index, motor_model)},
-    )
-    motors_bus.connect()
-
-    position = motors_bus.read("Present_Position")
-
-    # move from a few motor steps as an example
-    few_steps = 30
-    motors_bus.write("Goal_Position", position + few_steps)
-
-    # when done, consider disconnecting
-    motors_bus.disconnect()
-    ```
-    """
-
-    def __init__(
-        self,
-        port: str,
-        motors: dict[str, tuple[int, str]],
-        mock: bool = False,
-    ):
-        self.port = port
-        self.motors = motors
-        self.mock = mock
-
-        self.model_ctrl_table = deepcopy(MODEL_CONTROL_TABLE)
-        self.model_resolution = deepcopy(MODEL_RESOLUTION)
-
-        self.port_handler = None
-        self.packet_handler = None
-        self.calibration = None
-        self.is_connected = False
-        self.group_readers = {}
-        self.group_writers = {}
-        self.logs = {}
-
-    def connect(self):
-        if self.is_connected:
-            raise DeviceAlreadyConnectedError(
-                f"DynamixelMotorsBus({self.port}) is already connected. Do not call `motors_bus.connect()` twice."
-            )
-
-        if self.mock:
-            import tests.mock_dynamixel_sdk as dxl
-        else:
-            import dynamixel_sdk as dxl
-
-        self.port_handler = dxl.PortHandler(self.port)
-        self.packet_handler = dxl.PacketHandler(PROTOCOL_VERSION)
-
-        try:
-            if not self.port_handler.openPort():
-                raise OSError(f"Failed to open port '{self.port}'.")
-        except Exception:
-            traceback.print_exc()
-            print(
-                "\nTry running `python lerobot/scripts/find_motors_bus_port.py` to make sure you are using the correct port.\n"
-            )
-            raise
-
-        # Allow to read and write
-        self.is_connected = True
-
-        self.port_handler.setPacketTimeoutMillis(TIMEOUT_MS)
-
-    def reconnect(self):
-        if self.mock:
-            import tests.mock_dynamixel_sdk as dxl
-        else:
-            import dynamixel_sdk as dxl
-
-        self.port_handler = dxl.PortHandler(self.port)
-        self.packet_handler = dxl.PacketHandler(PROTOCOL_VERSION)
-
-        if not self.port_handler.openPort():
-            raise OSError(f"Failed to open port '{self.port}'.")
-
-        self.is_connected = True
-
-    def are_motors_configured(self):
-        # Only check the motor indices and not baudrate, since if the motor baudrates are incorrect,
-        # a ConnectionError will be raised anyway.
-        try:
-            return (self.motor_indices == self.read("ID")).all()
-        except ConnectionError as e:
-            print(e)
-            return False
-
-    def find_motor_indices(self, possible_ids=None, num_retry=2):
-        if possible_ids is None:
-            possible_ids = range(MAX_ID_RANGE)
-
-        indices = []
-        for idx in tqdm.tqdm(possible_ids):
-            try:
-                present_idx = self.read_with_motor_ids(self.motor_models, [idx], "ID", num_retry=num_retry)[0]
-            except ConnectionError:
-                continue
-
-            if idx != present_idx:
-                # sanity check
-                raise OSError(
-                    "Motor index used to communicate through the bus is not the same as the one present in the motor memory. The motor memory might be damaged."
-                )
-            indices.append(idx)
-
-        return indices
-
-    def set_bus_baudrate(self, baudrate):
-        present_bus_baudrate = self.port_handler.getBaudRate()
-        if present_bus_baudrate != baudrate:
-            print(f"Setting bus baud rate to {baudrate}. Previously {present_bus_baudrate}.")
-            self.port_handler.setBaudRate(baudrate)
-
-            if self.port_handler.getBaudRate() != baudrate:
-                raise OSError("Failed to write bus baud rate.")
-
-    @property
-    def motor_names(self) -> list[str]:
-        return list(self.motors.keys())
-
-    @property
-    def motor_models(self) -> list[str]:
-        return [model for _, model in self.motors.values()]
-
-    @property
-    def motor_indices(self) -> list[int]:
-        return [idx for idx, _ in self.motors.values()]
-
-    def set_calibration(self, calibration: dict[str, list]):
-        self.calibration = calibration
-
-    def apply_calibration_autocorrect(self, values: np.ndarray | list, motor_names: list[str] | None):
-        """This function applies the calibration, automatically detects out of range errors for motors values and attempts 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, dynamixel xl330-m077 have a resolution of 4096, and
-        at any position in their original range, let's say the position 56734, they complete a full rotation clockwise by moving to 60830,
-        or anticlockwise by moving to 52638. The position in the original range is arbitrary and might change a lot between each motor.
-        To harmonize between motors of the same model, different robots, or even models of different brands, we propose to work
-        in the centered nominal degree range ]-180, 180[.
-        """
-        if motor_names is None:
-            motor_names = self.motor_names
-
-        # Convert from unsigned int32 original range [0, 2**32] to signed float32 range
-        values = values.astype(np.float32)
-
-        for i, name in enumerate(motor_names):
-            calib_idx = self.calibration["motor_names"].index(name)
-            calib_mode = self.calibration["calib_mode"][calib_idx]
-
-            if CalibrationMode[calib_mode] == CalibrationMode.DEGREE:
-                drive_mode = self.calibration["drive_mode"][calib_idx]
-                homing_offset = self.calibration["homing_offset"][calib_idx]
-                _, model = self.motors[name]
-                resolution = self.model_resolution[model]
-
-                # Update direction of rotation of the motor to match between leader and follower.
-                # In fact, the motor of the leader for a given joint can be assembled in an
-                # opposite direction in term of rotation than the motor of the follower on the same joint.
-                if drive_mode:
-                    values[i] *= -1
-
-                # Convert from range [-2**31, 2**31] to
-                # nominal range [-resolution//2, resolution//2] (e.g. [-2048, 2048])
-                values[i] += homing_offset
-
-                # Convert from range [-resolution//2, resolution//2] to
-                # universal float32 centered degree range [-180, 180]
-                # (e.g. 2048 / (4096 // 2) * 180 = 180)
-                values[i] = values[i] / (resolution // 2) * HALF_TURN_DEGREE
-
-                if (values[i] < LOWER_BOUND_DEGREE) or (values[i] > UPPER_BOUND_DEGREE):
-                    raise JointOutOfRangeError(
-                        f"Wrong motor position range detected for {name}. "
-                        f"Expected to be in nominal range of [-{HALF_TURN_DEGREE}, {HALF_TURN_DEGREE}] degrees (a full rotation), "
-                        f"with a maximum range of [{LOWER_BOUND_DEGREE}, {UPPER_BOUND_DEGREE}] degrees to account for joints that can rotate a bit more, "
-                        f"but present value is {values[i]} degree. "
-                        "This might be due to a cable connection issue creating an artificial 360 degrees jump in motor values. "
-                        "You need to recalibrate by running: `python lerobot/scripts/control_robot.py calibrate`"
-                    )
-
-            elif CalibrationMode[calib_mode] == CalibrationMode.LINEAR:
-                start_pos = self.calibration["start_pos"][calib_idx]
-                end_pos = self.calibration["end_pos"][calib_idx]
-
-                # Rescale the present position to a nominal range [0, 100] %,
-                # useful for joints with linear motions like Aloha gripper
-                values[i] = (values[i] - start_pos) / (end_pos - start_pos) * 100
-
-                if (values[i] < LOWER_BOUND_LINEAR) or (values[i] > UPPER_BOUND_LINEAR):
-                    raise JointOutOfRangeError(
-                        f"Wrong motor position range detected for {name}. "
-                        f"Expected to be in nominal range of [0, 100] % (a full linear translation), "
-                        f"with a maximum range of [{LOWER_BOUND_LINEAR}, {UPPER_BOUND_LINEAR}] % to account for some imprecision during calibration, "
-                        f"but present value is {values[i]} %. "
-                        "This might be due to a cable connection issue creating an artificial jump in motor values. "
-                        "You need to recalibrate by running: `python lerobot/scripts/control_robot.py calibrate`"
-                    )
-
-        return values
-
-    def autocorrect_calibration(self, values: np.ndarray | list, motor_names: list[str] | None):
-        """This function automatically detects issues with values of motors after calibration, and correct for these issues.
-
-        Some motors might have values outside of expected maximum bounds after calibration.
-        For instance, for a joint in degree, its value can be outside [-270, 270] degrees, which is totally unexpected given
-        a nominal range of [-180, 180] degrees, which represents half a turn to the left or right starting from zero position.
-
-        Known issues:
-        #1: Motor value randomly shifts of a full turn, caused by hardware/connection errors.
-        #2: Motor internal homing offset is shifted by a full turn, caused by using default calibration (e.g Aloha).
-        #3: motor internal homing offset is shifted by 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]
-
-                # 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 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
-                # (- (resolution // 2) - values[i] - homing_offset) / resolution <= factor <= ((resolution // 2) - values[i] - homing_offset) / resolution
-                low_factor = (-(resolution // 2) - values[i] - homing_offset) / resolution
-                upp_factor = ((resolution // 2) - values[i] - homing_offset) / resolution
-
-            elif CalibrationMode[calib_mode] == CalibrationMode.LINEAR:
-                start_pos = self.calibration["start_pos"][calib_idx]
-                end_pos = self.calibration["end_pos"][calib_idx]
-
-                # Convert from initial range to range [0, 100] in %
-                calib_val = (values[i] - start_pos) / (end_pos - start_pos) * 100
-                in_range = (calib_val > LOWER_BOUND_LINEAR) and (calib_val < UPPER_BOUND_LINEAR)
-
-                # Solve this inequality to find the factor to shift the range into [0, 100] %
-                # values[i] = (values[i] - start_pos + resolution * factor) / (end_pos + resolution * factor - start_pos - resolution * factor) * 100
-                # values[i] = (values[i] - start_pos + resolution * factor) / (end_pos - start_pos) * 100
-                # 0 <= (values[i] - start_pos + resolution * factor) / (end_pos - start_pos) * 100 <= 100
-                # (start_pos - values[i]) / resolution <= factor <= (end_pos - values[i]) / resolution
-                low_factor = (start_pos - values[i]) / resolution
-                upp_factor = (end_pos - values[i]) / resolution
-
-            if not in_range:
-                # Get first integer between the two bounds
-                if low_factor < upp_factor:
-                    factor = math.ceil(low_factor)
-
-                    if factor > upp_factor:
-                        raise ValueError(f"No integer found between bounds [{low_factor=}, {upp_factor=}]")
-                else:
-                    factor = math.ceil(upp_factor)
-
-                    if factor > low_factor:
-                        raise ValueError(f"No integer found between bounds [{low_factor=}, {upp_factor=}]")
-
-                if CalibrationMode[calib_mode] == CalibrationMode.DEGREE:
-                    out_of_range_str = f"{LOWER_BOUND_DEGREE} < {calib_val} < {UPPER_BOUND_DEGREE} degrees"
-                    in_range_str = f"{LOWER_BOUND_DEGREE} < {calib_val} < {UPPER_BOUND_DEGREE} degrees"
-                elif CalibrationMode[calib_mode] == CalibrationMode.LINEAR:
-                    out_of_range_str = f"{LOWER_BOUND_LINEAR} < {calib_val} < {UPPER_BOUND_LINEAR} %"
-                    in_range_str = f"{LOWER_BOUND_LINEAR} < {calib_val} < {UPPER_BOUND_LINEAR} %"
-
-                logging.warning(
-                    f"Auto-correct calibration of motor '{name}' by shifting value by {abs(factor)} full turns, "
-                    f"from '{out_of_range_str}' to '{in_range_str}'."
-                )
-
-                # A full turn corresponds to 360 degrees but also to 4096 steps for a motor resolution of 4096.
-                self.calibration["homing_offset"][calib_idx] += resolution * factor
-
-    def revert_calibration(self, values: np.ndarray | list, motor_names: list[str] | None):
-        """Inverse of `apply_calibration`."""
-        if motor_names is None:
-            motor_names = self.motor_names
-
-        for i, name in enumerate(motor_names):
-            calib_idx = self.calibration["motor_names"].index(name)
-            calib_mode = self.calibration["calib_mode"][calib_idx]
-
-            if CalibrationMode[calib_mode] == CalibrationMode.DEGREE:
-                drive_mode = self.calibration["drive_mode"][calib_idx]
-                homing_offset = self.calibration["homing_offset"][calib_idx]
-                _, model = self.motors[name]
-                resolution = self.model_resolution[model]
-
-                # Convert from nominal 0-centered degree range [-180, 180] to
-                # 0-centered resolution range (e.g. [-2048, 2048] for resolution=4096)
-                values[i] = values[i] / HALF_TURN_DEGREE * (resolution // 2)
-
-                # 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
-
-            elif CalibrationMode[calib_mode] == CalibrationMode.LINEAR:
-                start_pos = self.calibration["start_pos"][calib_idx]
-                end_pos = self.calibration["end_pos"][calib_idx]
-
-                # Convert from nominal lnear range of [0, 100] % to
-                # actual motor range of values which can be arbitrary.
-                values[i] = values[i] / 100 * (end_pos - start_pos) + start_pos
-
-        values = np.round(values).astype(np.int32)
-        return values
-
-    def read_with_motor_ids(self, motor_models, motor_ids, data_name, num_retry=NUM_READ_RETRY):
-        if self.mock:
-            import tests.mock_dynamixel_sdk as dxl
-        else:
-            import dynamixel_sdk as dxl
-
-        return_list = True
-        if not isinstance(motor_ids, list):
-            return_list = False
-            motor_ids = [motor_ids]
-
-        assert_same_address(self.model_ctrl_table, self.motor_models, data_name)
-        addr, bytes = self.model_ctrl_table[motor_models[0]][data_name]
-        group = dxl.GroupSyncRead(self.port_handler, self.packet_handler, addr, bytes)
-        for idx in motor_ids:
-            group.addParam(idx)
-
-        for _ in range(num_retry):
-            comm = group.txRxPacket()
-            if comm == dxl.COMM_SUCCESS:
-                break
-
-        if comm != dxl.COMM_SUCCESS:
-            raise ConnectionError(
-                f"Read failed due to communication error on port {self.port_handler.port_name} for indices {motor_ids}: "
-                f"{self.packet_handler.getTxRxResult(comm)}"
-            )
-
-        values = []
-        for idx in motor_ids:
-            value = group.getData(idx, addr, bytes)
-            values.append(value)
-
-        if return_list:
-            return values
-        else:
-            return values[0]
-
-    def read(self, data_name, motor_names: str | list[str] | None = None):
-        if not self.is_connected:
-            raise DeviceNotConnectedError(
-                f"DynamixelMotorsBus({self.port}) is not connected. You need to run `motors_bus.connect()`."
-            )
-
-        start_time = time.perf_counter()
-
-        if self.mock:
-            import tests.mock_dynamixel_sdk as dxl
-        else:
-            import dynamixel_sdk as dxl
-
-        if motor_names is None:
-            motor_names = self.motor_names
-
-        if isinstance(motor_names, str):
-            motor_names = [motor_names]
-
-        motor_ids = []
-        models = []
-        for name in motor_names:
-            motor_idx, model = self.motors[name]
-            motor_ids.append(motor_idx)
-            models.append(model)
-
-        assert_same_address(self.model_ctrl_table, models, data_name)
-        addr, bytes = self.model_ctrl_table[model][data_name]
-        group_key = get_group_sync_key(data_name, motor_names)
-
-        if data_name not in self.group_readers:
-            # create new group reader
-            self.group_readers[group_key] = dxl.GroupSyncRead(
-                self.port_handler, self.packet_handler, addr, bytes
-            )
-            for idx in motor_ids:
-                self.group_readers[group_key].addParam(idx)
-
-        for _ in range(NUM_READ_RETRY):
-            comm = self.group_readers[group_key].txRxPacket()
-            if comm == dxl.COMM_SUCCESS:
-                break
-
-        if comm != dxl.COMM_SUCCESS:
-            raise ConnectionError(
-                f"Read failed due to communication error on port {self.port} for group_key {group_key}: "
-                f"{self.packet_handler.getTxRxResult(comm)}"
-            )
-
-        values = []
-        for idx in motor_ids:
-            value = self.group_readers[group_key].getData(idx, addr, bytes)
-            values.append(value)
-
-        values = np.array(values)
-
-        # Convert to signed int to use range [-2048, 2048] for our motor positions.
-        if data_name in CONVERT_UINT32_TO_INT32_REQUIRED:
-            values = values.astype(np.int32)
-
-        if data_name in CALIBRATION_REQUIRED and self.calibration is not None:
-            values = self.apply_calibration_autocorrect(values, motor_names)
-
-        # log the number of seconds it took to read the data from the motors
-        delta_ts_name = get_log_name("delta_timestamp_s", "read", data_name, motor_names)
-        self.logs[delta_ts_name] = time.perf_counter() - start_time
-
-        # log the utc time at which the data was received
-        ts_utc_name = get_log_name("timestamp_utc", "read", data_name, motor_names)
-        self.logs[ts_utc_name] = capture_timestamp_utc()
-
-        return values
-
-    def write_with_motor_ids(self, motor_models, motor_ids, data_name, values, num_retry=NUM_WRITE_RETRY):
-        if self.mock:
-            import tests.mock_dynamixel_sdk as dxl
-        else:
-            import dynamixel_sdk as dxl
-
-        if not isinstance(motor_ids, list):
-            motor_ids = [motor_ids]
-        if not isinstance(values, list):
-            values = [values]
-
-        assert_same_address(self.model_ctrl_table, motor_models, data_name)
-        addr, bytes = self.model_ctrl_table[motor_models[0]][data_name]
-        group = dxl.GroupSyncWrite(self.port_handler, self.packet_handler, addr, bytes)
-        for idx, value in zip(motor_ids, values, strict=True):
-            data = convert_to_bytes(value, bytes, self.mock)
-            group.addParam(idx, data)
-
-        for _ in range(num_retry):
-            comm = group.txPacket()
-            if comm == dxl.COMM_SUCCESS:
-                break
-
-        if comm != dxl.COMM_SUCCESS:
-            raise ConnectionError(
-                f"Write failed due to communication error on port {self.port_handler.port_name} for indices {motor_ids}: "
-                f"{self.packet_handler.getTxRxResult(comm)}"
-            )
-
-    def write(self, data_name, values: int | float | np.ndarray, motor_names: str | list[str] | None = None):
-        if not self.is_connected:
-            raise DeviceNotConnectedError(
-                f"DynamixelMotorsBus({self.port}) is not connected. You need to run `motors_bus.connect()`."
-            )
-
-        start_time = time.perf_counter()
-
-        if self.mock:
-            import tests.mock_dynamixel_sdk as dxl
-        else:
-            import dynamixel_sdk as dxl
-
-        if motor_names is None:
-            motor_names = self.motor_names
-
-        if isinstance(motor_names, str):
-            motor_names = [motor_names]
-
-        if isinstance(values, (int, float, np.integer)):
-            values = [int(values)] * len(motor_names)
-
-        values = np.array(values)
-
-        motor_ids = []
-        models = []
-        for name in motor_names:
-            motor_idx, model = self.motors[name]
-            motor_ids.append(motor_idx)
-            models.append(model)
-
-        if data_name in CALIBRATION_REQUIRED and self.calibration is not None:
-            values = self.revert_calibration(values, motor_names)
-
-        values = values.tolist()
-
-        assert_same_address(self.model_ctrl_table, models, data_name)
-        addr, bytes = self.model_ctrl_table[model][data_name]
-        group_key = get_group_sync_key(data_name, motor_names)
-
-        init_group = data_name not in self.group_readers
-        if init_group:
-            self.group_writers[group_key] = dxl.GroupSyncWrite(
-                self.port_handler, self.packet_handler, addr, bytes
-            )
-
-        for idx, value in zip(motor_ids, values, strict=True):
-            data = convert_to_bytes(value, bytes, self.mock)
-            if init_group:
-                self.group_writers[group_key].addParam(idx, data)
-            else:
-                self.group_writers[group_key].changeParam(idx, data)
-
-        comm = self.group_writers[group_key].txPacket()
-        if comm != dxl.COMM_SUCCESS:
-            raise ConnectionError(
-                f"Write failed due to communication error on port {self.port} for group_key {group_key}: "
-                f"{self.packet_handler.getTxRxResult(comm)}"
-            )
-
-        # log the number of seconds it took to write the data to the motors
-        delta_ts_name = get_log_name("delta_timestamp_s", "write", data_name, motor_names)
-        self.logs[delta_ts_name] = time.perf_counter() - start_time
-
-        # TODO(rcadene): should we log the time before sending the write command?
-        # log the utc time when the write has been completed
-        ts_utc_name = get_log_name("timestamp_utc", "write", data_name, motor_names)
-        self.logs[ts_utc_name] = capture_timestamp_utc()
-
-    def disconnect(self):
-        if not self.is_connected:
-            raise DeviceNotConnectedError(
-                f"DynamixelMotorsBus({self.port}) is not connected. Try running `motors_bus.connect()` first."
-            )
-
-        if self.port_handler is not None:
-            self.port_handler.closePort()
-            self.port_handler = None
-
-        self.packet_handler = None
-        self.group_readers = {}
-        self.group_writers = {}
-        self.is_connected = False
-
-    def __del__(self):
-        if getattr(self, "is_connected", False):
-            self.disconnect()
-
-
-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")

From 1f1a01a798f052deb0aaa0fa3364a766f9464008 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Tue, 25 Mar 2025 17:42:18 +0100
Subject: [PATCH 138/171] Rename CalibrationMode -> MotorNormMode

---
 lerobot/common/motors/__init__.py             |  2 +-
 .../motors/dynamixel/dynamixel_calibration.py |  6 +++---
 lerobot/common/motors/motors_bus.py           |  4 ++--
 lerobot/common/robots/koch/robot_koch.py      | 14 ++++++-------
 lerobot/common/robots/so100/robot_so100.py    | 14 ++++++-------
 lerobot/common/robots/viperx/robot_viperx.py  | 20 +++++++++----------
 .../common/teleoperators/koch/teleop_koch.py  | 14 ++++++-------
 .../teleoperators/so100/teleop_so100.py       | 14 ++++++-------
 .../teleoperators/widowx/teleop_widowx.py     | 20 +++++++++----------
 tests/motors/test_calibration.py              |  8 ++++----
 tests/motors/test_dynamixel.py                |  8 ++++----
 tests/motors/test_feetech.py                  |  8 ++++----
 12 files changed, 66 insertions(+), 66 deletions(-)

diff --git a/lerobot/common/motors/__init__.py b/lerobot/common/motors/__init__.py
index 75904fa8..852317ea 100644
--- a/lerobot/common/motors/__init__.py
+++ b/lerobot/common/motors/__init__.py
@@ -1 +1 @@
-from .motors_bus import CalibrationMode, Motor, MotorsBus
+from .motors_bus import Motor, MotorNormMode, MotorsBus
diff --git a/lerobot/common/motors/dynamixel/dynamixel_calibration.py b/lerobot/common/motors/dynamixel/dynamixel_calibration.py
index d959aee5..94151af2 100644
--- a/lerobot/common/motors/dynamixel/dynamixel_calibration.py
+++ b/lerobot/common/motors/dynamixel/dynamixel_calibration.py
@@ -17,7 +17,7 @@
 
 import numpy as np
 
-from ..motors_bus import CalibrationMode, MotorsBus
+from ..motors_bus import MotorNormMode, MotorsBus
 from .dynamixel import TorqueMode
 from .tables import MODEL_RESOLUTION
 
@@ -133,13 +133,13 @@ def run_arm_calibration(arm: MotorsBus, robot_type: str, arm_name: str, arm_type
     print()
 
     # Joints with rotational motions are expressed in degrees in nominal range of [-180, 180]
-    calib_mode = [CalibrationMode.DEGREE.name] * len(arm.names)
+    calib_mode = [MotorNormMode.DEGREE.name] * len(arm.names)
 
     # TODO(rcadene): make type of joints (DEGREE or LINEAR) configurable from yaml?
     if robot_type in ["aloha"] and "gripper" in arm.names:
         # Joints with linear motions (like gripper of Aloha) are expressed in nominal range of [0, 100]
         calib_idx = arm.names.index("gripper")
-        calib_mode[calib_idx] = CalibrationMode.LINEAR.name
+        calib_mode[calib_idx] = MotorNormMode.LINEAR.name
 
     calib_data = {
         "homing_offset": homing_offset.tolist(),
diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py
index 57c49b7d..1d9e1af1 100644
--- a/lerobot/common/motors/motors_bus.py
+++ b/lerobot/common/motors/motors_bus.py
@@ -76,7 +76,7 @@ def assert_same_address(model_ctrl_table: dict[str, dict], motor_models: list[st
         )
 
 
-class CalibrationMode(Enum):
+class MotorNormMode(Enum):
     DEGREE = 0
     RANGE_0_100 = 1
     RANGE_M100_100 = 2
@@ -87,7 +87,7 @@ class CalibrationMode(Enum):
 class Motor:
     id: int
     model: str
-    calibration: CalibrationMode
+    norm_mode: MotorNormMode
 
 
 class JointOutOfRangeError(Exception):
diff --git a/lerobot/common/robots/koch/robot_koch.py b/lerobot/common/robots/koch/robot_koch.py
index fa1ee284..06e21b1c 100644
--- a/lerobot/common/robots/koch/robot_koch.py
+++ b/lerobot/common/robots/koch/robot_koch.py
@@ -22,7 +22,7 @@ from typing import Any
 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 import CalibrationMode, Motor
+from lerobot.common.motors import Motor, MotorNormMode
 from lerobot.common.motors.dynamixel import (
     DynamixelMotorsBus,
     OperatingMode,
@@ -53,12 +53,12 @@ class KochRobot(Robot):
         self.arm = DynamixelMotorsBus(
             port=self.config.port,
             motors={
-                "shoulder_pan": Motor(1, "xl430-w250", CalibrationMode.RANGE_M100_100),
-                "shoulder_lift": Motor(2, "xl430-w250", CalibrationMode.RANGE_M100_100),
-                "elbow_flex": Motor(3, "xl330-m288", CalibrationMode.RANGE_M100_100),
-                "wrist_flex": Motor(4, "xl330-m288", CalibrationMode.RANGE_M100_100),
-                "wrist_roll": Motor(5, "xl330-m288", CalibrationMode.RANGE_M100_100),
-                "gripper": Motor(6, "xl330-m288", CalibrationMode.RANGE_0_100),
+                "shoulder_pan": Motor(1, "xl430-w250", MotorNormMode.RANGE_M100_100),
+                "shoulder_lift": Motor(2, "xl430-w250", MotorNormMode.RANGE_M100_100),
+                "elbow_flex": Motor(3, "xl330-m288", MotorNormMode.RANGE_M100_100),
+                "wrist_flex": Motor(4, "xl330-m288", MotorNormMode.RANGE_M100_100),
+                "wrist_roll": Motor(5, "xl330-m288", MotorNormMode.RANGE_M100_100),
+                "gripper": Motor(6, "xl330-m288", MotorNormMode.RANGE_0_100),
             },
         )
         self.cameras = make_cameras_from_configs(config.cameras)
diff --git a/lerobot/common/robots/so100/robot_so100.py b/lerobot/common/robots/so100/robot_so100.py
index f05d7bef..00432d4b 100644
--- a/lerobot/common/robots/so100/robot_so100.py
+++ b/lerobot/common/robots/so100/robot_so100.py
@@ -23,7 +23,7 @@ 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 import CalibrationMode, Motor
+from lerobot.common.motors import Motor, MotorNormMode
 from lerobot.common.motors.calibration import find_min_max, find_offset, set_calibration
 from lerobot.common.motors.feetech import (
     FeetechMotorsBus,
@@ -53,12 +53,12 @@ class SO100Robot(Robot):
         self.arm = FeetechMotorsBus(
             port=self.config.port,
             motors={
-                "shoulder_pan": Motor(1, "sts3215", CalibrationMode.RANGE_M100_100),
-                "shoulder_lift": Motor(2, "sts3215", CalibrationMode.RANGE_M100_100),
-                "elbow_flex": Motor(3, "sts3215", CalibrationMode.RANGE_M100_100),
-                "wrist_flex": Motor(4, "sts3215", CalibrationMode.RANGE_M100_100),
-                "wrist_roll": Motor(5, "sts3215", CalibrationMode.RANGE_M100_100),
-                "gripper": Motor(6, "sts3215", CalibrationMode.RANGE_0_100),
+                "shoulder_pan": Motor(1, "sts3215", MotorNormMode.RANGE_M100_100),
+                "shoulder_lift": Motor(2, "sts3215", MotorNormMode.RANGE_M100_100),
+                "elbow_flex": Motor(3, "sts3215", MotorNormMode.RANGE_M100_100),
+                "wrist_flex": Motor(4, "sts3215", MotorNormMode.RANGE_M100_100),
+                "wrist_roll": Motor(5, "sts3215", MotorNormMode.RANGE_M100_100),
+                "gripper": Motor(6, "sts3215", MotorNormMode.RANGE_0_100),
             },
         )
         self.cameras = make_cameras_from_configs(config.cameras)
diff --git a/lerobot/common/robots/viperx/robot_viperx.py b/lerobot/common/robots/viperx/robot_viperx.py
index e4b20094..5471a312 100644
--- a/lerobot/common/robots/viperx/robot_viperx.py
+++ b/lerobot/common/robots/viperx/robot_viperx.py
@@ -13,7 +13,7 @@ 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 import CalibrationMode, Motor, TorqueMode
+from lerobot.common.motors import Motor, MotorNormMode, TorqueMode
 from lerobot.common.motors.dynamixel import (
     DynamixelMotorsBus,
     run_arm_calibration,
@@ -43,15 +43,15 @@ class ViperXRobot(Robot):
         self.arm = DynamixelMotorsBus(
             port=self.config.port,
             motors={
-                "waist": Motor(1, "xm540-w270", CalibrationMode.RANGE_M100_100),
-                "shoulder": Motor(2, "xm540-w270", CalibrationMode.RANGE_M100_100),
-                "shoulder_shadow": Motor(3, "xm540-w270", CalibrationMode.RANGE_M100_100),
-                "elbow": Motor(4, "xm540-w270", CalibrationMode.RANGE_M100_100),
-                "elbow_shadow": Motor(5, "xm540-w270", CalibrationMode.RANGE_M100_100),
-                "forearm_roll": Motor(6, "xm540-w270", CalibrationMode.RANGE_M100_100),
-                "wrist_angle": Motor(7, "xm540-w270", CalibrationMode.RANGE_M100_100),
-                "wrist_rotate": Motor(8, "xm430-w350", CalibrationMode.RANGE_M100_100),
-                "gripper": Motor(9, "xm430-w350", CalibrationMode.RANGE_0_100),
+                "waist": Motor(1, "xm540-w270", MotorNormMode.RANGE_M100_100),
+                "shoulder": Motor(2, "xm540-w270", MotorNormMode.RANGE_M100_100),
+                "shoulder_shadow": Motor(3, "xm540-w270", MotorNormMode.RANGE_M100_100),
+                "elbow": Motor(4, "xm540-w270", MotorNormMode.RANGE_M100_100),
+                "elbow_shadow": Motor(5, "xm540-w270", MotorNormMode.RANGE_M100_100),
+                "forearm_roll": Motor(6, "xm540-w270", MotorNormMode.RANGE_M100_100),
+                "wrist_angle": Motor(7, "xm540-w270", MotorNormMode.RANGE_M100_100),
+                "wrist_rotate": Motor(8, "xm430-w350", MotorNormMode.RANGE_M100_100),
+                "gripper": Motor(9, "xm430-w350", MotorNormMode.RANGE_0_100),
             },
         )
         self.cameras = make_cameras_from_configs(config.cameras)
diff --git a/lerobot/common/teleoperators/koch/teleop_koch.py b/lerobot/common/teleoperators/koch/teleop_koch.py
index 3d2bf54e..1b1506bd 100644
--- a/lerobot/common/teleoperators/koch/teleop_koch.py
+++ b/lerobot/common/teleoperators/koch/teleop_koch.py
@@ -21,7 +21,7 @@ import time
 import numpy as np
 
 from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError
-from lerobot.common.motors import CalibrationMode, Motor
+from lerobot.common.motors import Motor, MotorNormMode
 from lerobot.common.motors.dynamixel import (
     DynamixelMotorsBus,
     OperatingMode,
@@ -51,12 +51,12 @@ class KochTeleop(Teleoperator):
         self.arm = DynamixelMotorsBus(
             port=self.config.port,
             motors={
-                "shoulder_pan": Motor(1, "xl330-m077", CalibrationMode.RANGE_M100_100),
-                "shoulder_lift": Motor(2, "xl330-m077", CalibrationMode.RANGE_M100_100),
-                "elbow_flex": Motor(3, "xl330-m077", CalibrationMode.RANGE_M100_100),
-                "wrist_flex": Motor(4, "xl330-m077", CalibrationMode.RANGE_M100_100),
-                "wrist_roll": Motor(5, "xl330-m077", CalibrationMode.RANGE_M100_100),
-                "gripper": Motor(6, "xl330-m077", CalibrationMode.RANGE_0_100),
+                "shoulder_pan": Motor(1, "xl330-m077", MotorNormMode.RANGE_M100_100),
+                "shoulder_lift": Motor(2, "xl330-m077", MotorNormMode.RANGE_M100_100),
+                "elbow_flex": Motor(3, "xl330-m077", MotorNormMode.RANGE_M100_100),
+                "wrist_flex": Motor(4, "xl330-m077", MotorNormMode.RANGE_M100_100),
+                "wrist_roll": Motor(5, "xl330-m077", MotorNormMode.RANGE_M100_100),
+                "gripper": Motor(6, "xl330-m077", MotorNormMode.RANGE_0_100),
             },
         )
 
diff --git a/lerobot/common/teleoperators/so100/teleop_so100.py b/lerobot/common/teleoperators/so100/teleop_so100.py
index 89524165..2190321c 100644
--- a/lerobot/common/teleoperators/so100/teleop_so100.py
+++ b/lerobot/common/teleoperators/so100/teleop_so100.py
@@ -21,7 +21,7 @@ import time
 import numpy as np
 
 from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError
-from lerobot.common.motors import CalibrationMode, Motor
+from lerobot.common.motors import Motor, MotorNormMode
 from lerobot.common.motors.calibration import find_min_max, find_offset, set_calibration
 from lerobot.common.motors.feetech import (
     FeetechMotorsBus,
@@ -48,12 +48,12 @@ class SO100Teleop(Teleoperator):
         self.arm = FeetechMotorsBus(
             port=self.config.port,
             motors={
-                "shoulder_pan": Motor(1, "sts3215", CalibrationMode.RANGE_M100_100),
-                "shoulder_lift": Motor(2, "sts3215", CalibrationMode.RANGE_M100_100),
-                "elbow_flex": Motor(3, "sts3215", CalibrationMode.RANGE_M100_100),
-                "wrist_flex": Motor(4, "sts3215", CalibrationMode.RANGE_M100_100),
-                "wrist_roll": Motor(5, "sts3215", CalibrationMode.RANGE_M100_100),
-                "gripper": Motor(6, "sts3215", CalibrationMode.RANGE_0_100),
+                "shoulder_pan": Motor(1, "sts3215", MotorNormMode.RANGE_M100_100),
+                "shoulder_lift": Motor(2, "sts3215", MotorNormMode.RANGE_M100_100),
+                "elbow_flex": Motor(3, "sts3215", MotorNormMode.RANGE_M100_100),
+                "wrist_flex": Motor(4, "sts3215", MotorNormMode.RANGE_M100_100),
+                "wrist_roll": Motor(5, "sts3215", MotorNormMode.RANGE_M100_100),
+                "gripper": Motor(6, "sts3215", MotorNormMode.RANGE_0_100),
             },
         )
 
diff --git a/lerobot/common/teleoperators/widowx/teleop_widowx.py b/lerobot/common/teleoperators/widowx/teleop_widowx.py
index 702f8d44..c1aca4a9 100644
--- a/lerobot/common/teleoperators/widowx/teleop_widowx.py
+++ b/lerobot/common/teleoperators/widowx/teleop_widowx.py
@@ -21,7 +21,7 @@ import time
 import numpy as np
 
 from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError
-from lerobot.common.motors import CalibrationMode, Motor, TorqueMode
+from lerobot.common.motors import Motor, MotorNormMode, TorqueMode
 from lerobot.common.motors.dynamixel import (
     DynamixelMotorsBus,
     run_arm_calibration,
@@ -47,15 +47,15 @@ class WidowXTeleop(Teleoperator):
         self.arm = DynamixelMotorsBus(
             port=self.config.port,
             motors={
-                "waist": Motor(1, "xm430-w350", CalibrationMode.RANGE_M100_100),
-                "shoulder": Motor(2, "xm430-w350", CalibrationMode.RANGE_M100_100),
-                "shoulder_shadow": Motor(3, "xm430-w350", CalibrationMode.RANGE_M100_100),
-                "elbow": Motor(4, "xm430-w350", CalibrationMode.RANGE_M100_100),
-                "elbow_shadow": Motor(5, "xm430-w350", CalibrationMode.RANGE_M100_100),
-                "forearm_roll": Motor(6, "xm430-w350", CalibrationMode.RANGE_M100_100),
-                "wrist_angle": Motor(7, "xm430-w350", CalibrationMode.RANGE_M100_100),
-                "wrist_rotate": Motor(8, "xl430-w250", CalibrationMode.RANGE_M100_100),
-                "gripper": Motor(9, "xc430-w150", CalibrationMode.RANGE_0_100),
+                "waist": Motor(1, "xm430-w350", MotorNormMode.RANGE_M100_100),
+                "shoulder": Motor(2, "xm430-w350", MotorNormMode.RANGE_M100_100),
+                "shoulder_shadow": Motor(3, "xm430-w350", MotorNormMode.RANGE_M100_100),
+                "elbow": Motor(4, "xm430-w350", MotorNormMode.RANGE_M100_100),
+                "elbow_shadow": Motor(5, "xm430-w350", MotorNormMode.RANGE_M100_100),
+                "forearm_roll": Motor(6, "xm430-w350", MotorNormMode.RANGE_M100_100),
+                "wrist_angle": Motor(7, "xm430-w350", MotorNormMode.RANGE_M100_100),
+                "wrist_rotate": Motor(8, "xl430-w250", MotorNormMode.RANGE_M100_100),
+                "gripper": Motor(9, "xc430-w150", MotorNormMode.RANGE_0_100),
             },
         )
 
diff --git a/tests/motors/test_calibration.py b/tests/motors/test_calibration.py
index 011174db..2ea66e96 100644
--- a/tests/motors/test_calibration.py
+++ b/tests/motors/test_calibration.py
@@ -5,7 +5,7 @@ from unittest.mock import Mock, call, patch
 import pytest
 import scservo_sdk as scs
 
-from lerobot.common.motors import CalibrationMode, Motor
+from lerobot.common.motors import Motor, MotorNormMode
 from lerobot.common.motors.calibration import find_min_max, find_offset, set_min_max, set_offset
 from lerobot.common.motors.feetech import FeetechMotorsBus
 from tests.mocks.mock_feetech import MockMotors, MockPortHandler
@@ -31,9 +31,9 @@ def mock_motors() -> Generator[MockMotors, None, None]:
 @pytest.fixture
 def dummy_motors() -> dict[str, Motor]:
     return {
-        "dummy_1": Motor(1, "sts3215", CalibrationMode.RANGE_M100_100),
-        "wrist_roll": Motor(2, "sts3215", CalibrationMode.RANGE_M100_100),
-        "dummy_3": Motor(3, "sts3215", CalibrationMode.RANGE_M100_100),
+        "dummy_1": Motor(1, "sts3215", MotorNormMode.RANGE_M100_100),
+        "wrist_roll": Motor(2, "sts3215", MotorNormMode.RANGE_M100_100),
+        "dummy_3": Motor(3, "sts3215", MotorNormMode.RANGE_M100_100),
     }
 
 
diff --git a/tests/motors/test_dynamixel.py b/tests/motors/test_dynamixel.py
index 80f853d6..4f3165e7 100644
--- a/tests/motors/test_dynamixel.py
+++ b/tests/motors/test_dynamixel.py
@@ -5,7 +5,7 @@ from unittest.mock import patch
 import dynamixel_sdk as dxl
 import pytest
 
-from lerobot.common.motors import CalibrationMode, Motor
+from lerobot.common.motors import Motor, MotorNormMode
 from lerobot.common.motors.dynamixel import MODEL_NUMBER, DynamixelMotorsBus
 from tests.mocks.mock_dynamixel import MockMotors, MockPortHandler
 
@@ -30,9 +30,9 @@ def mock_motors() -> Generator[MockMotors, None, None]:
 @pytest.fixture
 def dummy_motors() -> dict[str, Motor]:
     return {
-        "dummy_1": Motor(1, "xl430-w250", CalibrationMode.RANGE_M100_100),
-        "dummy_2": Motor(2, "xm540-w270", CalibrationMode.RANGE_M100_100),
-        "dummy_3": Motor(3, "xl330-m077", CalibrationMode.RANGE_M100_100),
+        "dummy_1": Motor(1, "xl430-w250", MotorNormMode.RANGE_M100_100),
+        "dummy_2": Motor(2, "xm540-w270", MotorNormMode.RANGE_M100_100),
+        "dummy_3": Motor(3, "xl330-m077", MotorNormMode.RANGE_M100_100),
     }
 
 
diff --git a/tests/motors/test_feetech.py b/tests/motors/test_feetech.py
index f65813c3..fcc73780 100644
--- a/tests/motors/test_feetech.py
+++ b/tests/motors/test_feetech.py
@@ -5,7 +5,7 @@ from unittest.mock import patch
 import pytest
 import scservo_sdk as scs
 
-from lerobot.common.motors import CalibrationMode, Motor
+from lerobot.common.motors import Motor, MotorNormMode
 from lerobot.common.motors.feetech import MODEL_NUMBER, FeetechMotorsBus
 from tests.mocks.mock_feetech import MockMotors, MockPortHandler
 
@@ -30,9 +30,9 @@ def mock_motors() -> Generator[MockMotors, None, None]:
 @pytest.fixture
 def dummy_motors() -> dict[str, Motor]:
     return {
-        "dummy_1": Motor(1, "sts3215", CalibrationMode.RANGE_M100_100),
-        "dummy_2": Motor(2, "sts3215", CalibrationMode.RANGE_M100_100),
-        "dummy_3": Motor(3, "sts3215", CalibrationMode.RANGE_M100_100),
+        "dummy_1": Motor(1, "sts3215", MotorNormMode.RANGE_M100_100),
+        "dummy_2": Motor(2, "sts3215", MotorNormMode.RANGE_M100_100),
+        "dummy_3": Motor(3, "sts3215", MotorNormMode.RANGE_M100_100),
     }
 
 

From 2292b514aa59d3e83627f6bced3405a636cd2607 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Tue, 25 Mar 2025 17:58:54 +0100
Subject: [PATCH 139/171] Fix calibration functions

---
 lerobot/common/motors/calibration.py | 8 ++++----
 1 file changed, 4 insertions(+), 4 deletions(-)

diff --git a/lerobot/common/motors/calibration.py b/lerobot/common/motors/calibration.py
index 8329092f..3fbed56d 100644
--- a/lerobot/common/motors/calibration.py
+++ b/lerobot/common/motors/calibration.py
@@ -55,7 +55,7 @@ def find_offset(motorbus: MotorsBus):
     offsets = {}
     for name, pos in middle_values.items():
         offset = pos - 2047  # Center the middle reading at 2047.
-        MotorCalibration.set_offset(motorbus, offset, name)
+        set_offset(motorbus, offset, name)
         offsets[name] = offset
 
     return offsets
@@ -93,7 +93,7 @@ def find_min_max(motorbus: MotorsBus):
             physical_min = int(raw_min)
             physical_max = int(raw_max)
 
-        MotorCalibration.set_min_max(motorbus, physical_min, physical_max, name)
+        set_min_max(motorbus, physical_min, physical_max, name)
         min_max[name] = {"min": physical_min, "max": physical_max}
 
     return min_max
@@ -111,8 +111,8 @@ def set_calibration(motorbus: MotorsBus, calibration_fpath: Path) -> None:
             print(f"Motor name '{name}' from calibration not found in arm names.")
             continue
 
-        MotorCalibration.set_offset(motorbus, cal_data["homing_offset"], name)
-        MotorCalibration.set_min_max(motorbus, cal_data["min"], cal_data["max"], name)
+        set_offset(motorbus, cal_data["homing_offset"], name)
+        set_min_max(motorbus, cal_data["min"], cal_data["max"], name)
 
 
 def set_offset(motorbus: MotorsBus, homing_offset: int, name: str):

From 051a52a4cef809b17a9775b6a160bda43ebb612e Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Tue, 25 Mar 2025 21:32:30 +0100
Subject: [PATCH 140/171] Remove todo

---
 tests/motors/test_feetech.py | 1 -
 1 file changed, 1 deletion(-)

diff --git a/tests/motors/test_feetech.py b/tests/motors/test_feetech.py
index fcc73780..0154621a 100644
--- a/tests/motors/test_feetech.py
+++ b/tests/motors/test_feetech.py
@@ -92,7 +92,6 @@ def test_abc_implementation(dummy_motors):
     FeetechMotorsBus(port="/dev/dummy-port", motors=dummy_motors)
 
 
-# @pytest.mark.skip("TODO")
 @pytest.mark.parametrize("id_", [1, 2, 3])
 def test_ping(id_, mock_motors, dummy_motors):
     expected_model_nb = MODEL_NUMBER[dummy_motors[f"dummy_{id_}"].model]

From 50963fcf1352b4af597822ea0eb36dab9cd89153 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sun, 30 Mar 2025 15:32:25 +0200
Subject: [PATCH 141/171] Add scan_port utility

---
 lerobot/common/motors/dynamixel/tables.py | 20 ++++++++++++++++++++
 lerobot/common/motors/feetech/tables.py   | 14 +++++++++++++-
 lerobot/common/motors/motors_bus.py       | 21 +++++++++++++++++++++
 3 files changed, 54 insertions(+), 1 deletion(-)

diff --git a/lerobot/common/motors/dynamixel/tables.py b/lerobot/common/motors/dynamixel/tables.py
index 4634d4a7..5589b224 100644
--- a/lerobot/common/motors/dynamixel/tables.py
+++ b/lerobot/common/motors/dynamixel/tables.py
@@ -119,3 +119,23 @@ MODEL_BAUDRATE_TABLE = {
     "xm540-w270": X_SERIES_BAUDRATE_TABLE,
     "xc430-w150": X_SERIES_BAUDRATE_TABLE,
 }
+
+AVAILABLE_BAUDRATES = [
+    9600,
+    19200,
+    38400,
+    57600,
+    115200,
+    230400,
+    460800,
+    500000,
+    576000,
+    921600,
+    1000000,
+    1152000,
+    2000000,
+    2500000,
+    3000000,
+    3500000,
+    4000000,
+]
diff --git a/lerobot/common/motors/feetech/tables.py b/lerobot/common/motors/feetech/tables.py
index 7e7e7e9d..a947611d 100644
--- a/lerobot/common/motors/feetech/tables.py
+++ b/lerobot/common/motors/feetech/tables.py
@@ -83,4 +83,16 @@ MODEL_BAUDRATE_TABLE = {
     "sts3215": SCS_SERIES_BAUDRATE_TABLE,
 }
 
-CALIBRATION_REQUIRED = ["Goal_Position", "Present_Position"]
+AVAILABLE_BAUDRATES = [
+    4800,
+    9600,
+    14400,
+    19200,
+    38400,
+    57600,
+    115200,
+    128000,
+    250000,
+    500000,
+    1000000,
+]
diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py
index 1d9e1af1..1dde8e77 100644
--- a/lerobot/common/motors/motors_bus.py
+++ b/lerobot/common/motors/motors_bus.py
@@ -29,6 +29,7 @@ from typing import Protocol, TypeAlias, overload
 
 import serial
 from deepdiff import DeepDiff
+from tqdm import tqdm
 
 from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError
 
@@ -379,6 +380,26 @@ class MotorsBus(abc.ABC):
         self.set_timeout()
         logger.debug(f"{self.__class__.__name__} connected.")
 
+    @classmethod
+    def scan_port(cls, port: str) -> dict[int, list[int]]:
+        bus = cls(port, {})
+        try:
+            bus.port_handler.openPort()
+        except (FileNotFoundError, OSError, serial.SerialException) as e:
+            raise ConnectionError(
+                f"Could not connect to port '{port}'. Make sure you are using the correct port."
+                "\nTry running `python lerobot/scripts/find_motors_bus_port.py`\n"
+            ) from e
+        baudrate_ids = {}
+        for baudrate in tqdm(bus.available_baudrates, desc="Scanning port"):
+            bus.set_baudrate(baudrate)
+            ids_models = bus.broadcast_ping()
+            if ids_models:
+                tqdm.write(f"Motors found for {baudrate=}: {pformat(ids_models, indent=4)}")
+                baudrate_ids[baudrate] = list(ids_models)
+
+        return baudrate_ids
+
     @abc.abstractmethod
     def _configure_motors(self) -> None:
         pass

From d6007c6e7d2c4ded400bd320fac52d078719a3b4 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Sun, 30 Mar 2025 15:41:39 +0200
Subject: [PATCH 142/171] Add calibration utilities

---
 lerobot/common/motors/dynamixel/dynamixel.py |  75 +++++++--
 lerobot/common/motors/feetech/feetech.py     |  72 +++++++--
 lerobot/common/motors/feetech/tables.py      |  18 ++-
 lerobot/common/motors/motors_bus.py          | 160 ++++++++++++++++---
 lerobot/common/utils/utils.py                |   6 +
 5 files changed, 277 insertions(+), 54 deletions(-)

diff --git a/lerobot/common/motors/dynamixel/dynamixel.py b/lerobot/common/motors/dynamixel/dynamixel.py
index 5db015ef..f7e4569c 100644
--- a/lerobot/common/motors/dynamixel/dynamixel.py
+++ b/lerobot/common/motors/dynamixel/dynamixel.py
@@ -22,19 +22,50 @@ import logging
 from copy import deepcopy
 from enum import Enum
 
-from ..motors_bus import Motor, MotorsBus
-from .tables import MODEL_BAUDRATE_TABLE, MODEL_CONTROL_TABLE, MODEL_NUMBER, MODEL_RESOLUTION
+from ..motors_bus import Motor, MotorsBus, NameOrID, Value
+from .tables import (
+    AVAILABLE_BAUDRATES,
+    MODEL_BAUDRATE_TABLE,
+    MODEL_CONTROL_TABLE,
+    MODEL_NUMBER,
+    MODEL_RESOLUTION,
+)
 
 PROTOCOL_VERSION = 2.0
 BAUDRATE = 1_000_000
 DEFAULT_TIMEOUT_MS = 1000
 
-CALIBRATION_REQUIRED = ["Goal_Position", "Present_Position"]
+NORMALIZATION_REQUIRED = ["Goal_Position", "Present_Position"]
 CONVERT_UINT32_TO_INT32_REQUIRED = ["Goal_Position", "Present_Position"]
 
 logger = logging.getLogger(__name__)
 
 
+def encode_twos_complement(value: int, n_bytes: int):
+    if value >= 0:
+        return value
+
+    bit_width = n_bytes * 8
+    min_val = -(1 << (bit_width - 1))
+    max_val = (1 << (bit_width - 1)) - 1
+
+    if not (min_val <= value <= max_val):
+        raise ValueError(
+            f"Value {value} out of range for {n_bytes}-byte two's complement: [{min_val}, {max_val}]"
+        )
+
+    return (1 << bit_width) + value
+
+
+def decode_twos_complement(value: int, n_bytes: int) -> int:
+    # https://en.wikipedia.org/wiki/Two%27s_complement
+    bits = n_bytes * 8
+    sign_bit = 1 << (bits - 1)
+    if value & sign_bit:
+        value -= 1 << bits
+    return value
+
+
 class OperatingMode(Enum):
     # DYNAMIXEL only controls current(torque) regardless of speed and position. This mode is ideal for a
     # gripper or a system that only uses current(torque) control or a system that has additional
@@ -82,12 +113,13 @@ class DynamixelMotorsBus(MotorsBus):
     https://emanual.robotis.com/docs/en/software/dynamixel/dynamixel_sdk/sample_code/python_read_write_protocol_2_0/#python-read-write-protocol-20
     """
 
-    model_ctrl_table = deepcopy(MODEL_CONTROL_TABLE)
-    model_resolution_table = deepcopy(MODEL_RESOLUTION)
-    model_baudrate_table = deepcopy(MODEL_BAUDRATE_TABLE)
-    model_number_table = deepcopy(MODEL_NUMBER)
-    calibration_required = deepcopy(CALIBRATION_REQUIRED)
+    available_baudrates = deepcopy(AVAILABLE_BAUDRATES)
     default_timeout = DEFAULT_TIMEOUT_MS
+    model_baudrate_table = deepcopy(MODEL_BAUDRATE_TABLE)
+    model_ctrl_table = deepcopy(MODEL_CONTROL_TABLE)
+    model_number_table = deepcopy(MODEL_NUMBER)
+    model_resolution_table = deepcopy(MODEL_RESOLUTION)
+    normalization_required = deepcopy(NORMALIZATION_REQUIRED)
 
     def __init__(
         self,
@@ -110,14 +142,33 @@ class DynamixelMotorsBus(MotorsBus):
         for id_ in self.ids:
             self.write("Return_Delay_Time", id_, 0)
 
-    def _calibrate_values(self, ids_values: dict[int, int]) -> dict[int, float]:
+    def _get_half_turn_homings(self, positions: dict[NameOrID, Value]) -> dict[NameOrID, Value]:
+        """
+        On Dynamixel Motors:
+        Present_Position = Actual_Position + Homing_Offset
+        """
+        half_turn_homings = {}
+        for motor, pos in positions.items():
+            model = self._get_motor_model(motor)
+            max_res = self.model_resolution_table[model] - 1
+            half_turn_homings[motor] = int(max_res / 2) - pos
+
+        return half_turn_homings
+
+    def _normalize(self, ids_values: dict[int, int]) -> dict[int, float]:
         # TODO
         return ids_values
 
-    def _uncalibrate_values(self, ids_values: dict[int, float]) -> dict[int, int]:
+    def _unnormalize(self, ids_values: dict[int, float]) -> dict[int, int]:
         # TODO
         return ids_values
 
+    def _encode_value(self, value: int, data_name: str | None = None, n_bytes: int | None = None) -> int:
+        return encode_twos_complement(value, n_bytes)
+
+    def _decode_value(self, value: int, data_name: str | None = None, n_bytes: int | None = None) -> int:
+        return decode_twos_complement(value, n_bytes)
+
     @staticmethod
     def _split_int_to_bytes(value: int, n_bytes: int) -> list[int]:
         # Validate input
@@ -154,11 +205,11 @@ class DynamixelMotorsBus(MotorsBus):
             if self._is_comm_success(comm):
                 break
             logger.debug(f"Broadcast failed on port '{self.port}' ({n_try=})")
-            logger.debug(self.packet_handler.getRxPacketError(comm))
+            logger.debug(self.packet_handler.getTxRxResult(comm))
 
         if not self._is_comm_success(comm):
             if raise_on_error:
-                raise ConnectionError(self.packet_handler.getRxPacketError(comm))
+                raise ConnectionError(self.packet_handler.getTxRxResult(comm))
 
             return data_list if data_list else None
 
diff --git a/lerobot/common/motors/feetech/feetech.py b/lerobot/common/motors/feetech/feetech.py
index 54f86824..6eb37314 100644
--- a/lerobot/common/motors/feetech/feetech.py
+++ b/lerobot/common/motors/feetech/feetech.py
@@ -17,13 +17,15 @@ from copy import deepcopy
 from enum import Enum
 from pprint import pformat
 
-from ..motors_bus import Motor, MotorsBus
+from ..motors_bus import Motor, MotorsBus, NameOrID, Value
 from .tables import (
-    CALIBRATION_REQUIRED,
+    AVAILABLE_BAUDRATES,
+    ENCODINGS,
     MODEL_BAUDRATE_TABLE,
     MODEL_CONTROL_TABLE,
     MODEL_NUMBER,
     MODEL_RESOLUTION,
+    NORMALIZATION_REQUIRED,
 )
 
 PROTOCOL_VERSION = 0
@@ -33,6 +35,29 @@ DEFAULT_TIMEOUT_MS = 1000
 logger = logging.getLogger(__name__)
 
 
+def encode_sign_magnitude(value: int, sign_bit_index: int):
+    """
+    https://en.wikipedia.org/wiki/Signed_number_representations#Sign%E2%80%93magnitude
+    """
+    max_magnitude = (1 << sign_bit_index) - 1
+    magnitude = abs(value)
+    if magnitude > max_magnitude:
+        raise ValueError(f"Magnitude {magnitude} exceeds {max_magnitude} (max for {sign_bit_index=})")
+
+    direction_bit = 1 if value < 0 else 0
+    return (direction_bit << sign_bit_index) | magnitude
+
+
+def decode_sign_magnitude(encoded_value: int, sign_bit_index: int):
+    """
+    https://en.wikipedia.org/wiki/Signed_number_representations#Sign%E2%80%93magnitude
+    """
+    direction_bit = (encoded_value >> sign_bit_index) & 1
+    magnitude_mask = (1 << sign_bit_index) - 1
+    magnitude = encoded_value & magnitude_mask
+    return -magnitude if direction_bit else magnitude
+
+
 class OperatingMode(Enum):
     # position servo mode
     POSITION = 0
@@ -63,12 +88,16 @@ class FeetechMotorsBus(MotorsBus):
     python feetech sdk to communicate with the motors, which is itself based on the dynamixel sdk.
     """
 
-    model_ctrl_table = deepcopy(MODEL_CONTROL_TABLE)
-    model_resolution_table = deepcopy(MODEL_RESOLUTION)
-    model_baudrate_table = deepcopy(MODEL_BAUDRATE_TABLE)
-    model_number_table = deepcopy(MODEL_NUMBER)
-    calibration_required = deepcopy(CALIBRATION_REQUIRED)
+    available_baudrates = deepcopy(AVAILABLE_BAUDRATES)
     default_timeout = DEFAULT_TIMEOUT_MS
+    model_baudrate_table = deepcopy(MODEL_BAUDRATE_TABLE)
+    model_ctrl_table = deepcopy(MODEL_CONTROL_TABLE)
+    model_number_table = deepcopy(MODEL_NUMBER)
+    model_resolution_table = deepcopy(MODEL_RESOLUTION)
+    normalization_required = deepcopy(NORMALIZATION_REQUIRED)
+
+    # Feetech specific
+    encodings = deepcopy(ENCODINGS)
 
     def __init__(
         self,
@@ -89,16 +118,37 @@ class FeetechMotorsBus(MotorsBus):
         # By default, Feetech motors have a 500µs delay response time (corresponding to a value of 250 on the
         # 'Return_Delay' address). We ensure this is reduced to the minimum of 2µs (value of 0).
         for id_ in self.ids:
-            self.write("Return_Delay", id_, 0)
+            self.write("Return_Delay_Time", id_, 0)
 
-    def _calibrate_values(self, ids_values: dict[int, int]) -> dict[int, float]:
+    def _get_half_turn_homings(self, positions: dict[NameOrID, Value]) -> dict[NameOrID, Value]:
+        """
+        On Feetech Motors:
+        Present_Position = Actual_Position - Homing_Offset
+        """
+        half_turn_homings = {}
+        for motor, pos in positions.items():
+            model = self._get_motor_model(motor)
+            max_res = self.model_resolution_table[model] - 1
+            half_turn_homings[motor] = pos - int(max_res / 2)
+
+        return half_turn_homings
+
+    def _normalize(self, data_name: str, ids_values: dict[int, int]) -> dict[int, float]:
         # TODO
         return ids_values
 
-    def _uncalibrate_values(self, ids_values: dict[int, float]) -> dict[int, int]:
+    def _unnormalize(self, data_name: str, ids_values: dict[int, float]) -> dict[int, int]:
         # TODO
         return ids_values
 
+    def _encode_value(self, value: int, data_name: str | None = None, n_bytes: int | None = None) -> int:
+        sign_bit = self.encodings.get(data_name)
+        return encode_sign_magnitude(value, sign_bit) if sign_bit is not None else value
+
+    def _decode_value(self, value: int, data_name: str | None = None, n_bytes: int | None = None) -> int:
+        sign_bit = self.encodings.get(data_name)
+        return decode_sign_magnitude(value, sign_bit) if sign_bit is not None else value
+
     @staticmethod
     def _split_int_to_bytes(value: int, n_bytes: int) -> list[int]:
         # Validate input
@@ -114,8 +164,6 @@ class FeetechMotorsBus(MotorsBus):
 
         import scservo_sdk as scs
 
-        # Note: No need to convert back into unsigned int, since this byte preprocessing
-        # already handles it for us.
         if n_bytes == 1:
             data = [value]
         elif n_bytes == 2:
diff --git a/lerobot/common/motors/feetech/tables.py b/lerobot/common/motors/feetech/tables.py
index a947611d..0ea0962b 100644
--- a/lerobot/common/motors/feetech/tables.py
+++ b/lerobot/common/motors/feetech/tables.py
@@ -6,10 +6,10 @@ SCS_SERIES_CONTROL_TABLE = {
     "Model_Number": (3, 2),
     "ID": (5, 1),
     "Baud_Rate": (6, 1),
-    "Return_Delay": (7, 1),
+    "Return_Delay_Time": (7, 1),
     "Response_Status_Level": (8, 1),
-    "Min_Angle_Limit": (9, 2),
-    "Max_Angle_Limit": (11, 2),
+    "Min_Position_Limit": (9, 2),
+    "Max_Position_Limit": (11, 2),
     "Max_Temperature_Limit": (13, 1),
     "Max_Voltage_Limit": (14, 1),
     "Min_Voltage_Limit": (15, 1),
@@ -25,8 +25,8 @@ SCS_SERIES_CONTROL_TABLE = {
     "CCW_Dead_Zone": (27, 1),
     "Protection_Current": (28, 2),
     "Angular_Resolution": (30, 1),
-    "Offset": (31, 2),
-    "Mode": (33, 1),
+    "Homing_Offset": (31, 2),
+    "Operating_Mode": (33, 1),
     "Protective_Torque": (34, 1),
     "Protection_Time": (35, 1),
     "Overload_Torque": (36, 1),
@@ -83,6 +83,14 @@ MODEL_BAUDRATE_TABLE = {
     "sts3215": SCS_SERIES_BAUDRATE_TABLE,
 }
 
+NORMALIZATION_REQUIRED = ["Goal_Position", "Present_Position"]
+
+# Sign-Magnitude encoding bits
+ENCODINGS = {
+    "Homing_Offset": 11,
+    "Goal_Speed": 15,
+}
+
 AVAILABLE_BAUDRATES = [
     4800,
     9600,
diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py
index 1dde8e77..7389f88a 100644
--- a/lerobot/common/motors/motors_bus.py
+++ b/lerobot/common/motors/motors_bus.py
@@ -32,6 +32,7 @@ from deepdiff import DeepDiff
 from tqdm import tqdm
 
 from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError
+from lerobot.common.utils.utils import _enter_pressed
 
 NameOrID: TypeAlias = str | int
 Value: TypeAlias = int | float
@@ -243,12 +244,13 @@ class MotorsBus(abc.ABC):
     ```
     """
 
-    model_ctrl_table: dict[str, dict]
-    model_resolution_table: dict[str, int]
-    model_baudrate_table: dict[str, dict]
-    model_number_table: dict[str, int]
-    calibration_required: list[str]
+    available_baudrates: list[int]
     default_timeout: int
+    model_baudrate_table: dict[str, dict]
+    model_ctrl_table: dict[str, dict]
+    model_number_table: dict[str, int]
+    model_resolution_table: dict[str, int]
+    normalization_required: list[str]
 
     def __init__(
         self,
@@ -257,7 +259,6 @@ class MotorsBus(abc.ABC):
     ):
         self.port = port
         self.motors = motors
-        self._validate_motors()
 
         self.port_handler: PortHandler
         self.packet_handler: PacketHandler
@@ -322,6 +323,14 @@ class MotorsBus(abc.ABC):
         else:
             raise TypeError(f"'{motor}' should be int, str.")
 
+    def _get_motor_model(self, motor: NameOrID) -> int:
+        if isinstance(motor, str):
+            return self.motors[motor].model
+        elif isinstance(motor, int):
+            return self._id_to_model_dict[motor]
+        else:
+            raise TypeError(f"'{motor}' should be int, str.")
+
     def _validate_motors(self) -> None:
         if len(self.ids) != len(set(self.ids)):
             raise ValueError(f"Some motors have the same id!\n{self}")
@@ -337,9 +346,10 @@ class MotorsBus(abc.ABC):
         return error != self._no_error
 
     def _assert_motors_exist(self) -> None:
+        # TODO(aliberts): collect all wrong ids/models and display them at once
         found_models = self.broadcast_ping()
         expected_models = {m.id: self.model_number_table[m.model] for m in self.motors.values()}
-        if not set(found_models) == set(self.ids):
+        if not found_models or set(found_models) != set(self.ids):
             raise RuntimeError(
                 f"{self.__class__.__name__} is supposed to have these motors: ({{id: model_nb}})"
                 f"\n{pformat(expected_models, indent=4, sort_dicts=False)}\n"
@@ -371,11 +381,10 @@ class MotorsBus(abc.ABC):
             elif assert_motors_exist:
                 self._assert_motors_exist()
         except (FileNotFoundError, OSError, serial.SerialException) as e:
-            logger.error(
+            raise ConnectionError(
                 f"\nCould not connect on port '{self.port}'. Make sure you are using the correct port."
                 "\nTry running `python lerobot/scripts/find_motors_bus_port.py`\n"
-            )
-            raise e
+            ) from e
 
         self.set_timeout()
         logger.debug(f"{self.__class__.__name__} connected.")
@@ -433,12 +442,107 @@ class MotorsBus(abc.ABC):
             logger.error(e)
             return False
 
+    def set_half_turn_homings(self, motors: NameOrID | list[NameOrID] | None = None) -> dict[NameOrID, Value]:
+        """This assumes motors present positions are roughly in the middle of their desired range"""
+        if motors is None:
+            motors = self.names
+        elif isinstance(motors, (str, int)):
+            motors = [motors]
+        else:
+            raise TypeError(motors)
+
+        # Step 1: Set homing and min max to 0
+        self.reset_homing_ranges(motors)
+
+        # Step 2: Read Present_Position which will be Actual_Position since
+        # Present_Position = Actual_Position ± Homing_Offset (1)
+        # and Homing_Offset = 0 from step 1
+        actual_positions = self.sync_read("Present_Position", motors, normalize=True)
+
+        # Step 3: We want to set the Homing_Offset such that the current Present_Position to be half range of
+        # 1 revolution.
+        # For instance, if 1 revolution corresponds to 4095 (4096 steps), this means we want the current
+        # Present_Position to be 2047. In that example:
+        # Present_Position = 2047 (2)
+        # Actual_Position = X (read in step 2)
+        # from (1) and (2):
+        # => Homing_Offset = ±(X - 2048)
+        homing_offsets = self._get_half_turn_homings(actual_positions)
+
+        for motor, offset in homing_offsets.items():
+            self.write("Homing_Offset", motor, offset, normalize=False)
+
+        return homing_offsets
+
+    def reset_homing_ranges(self, motors: NameOrID | list[NameOrID] | None = None) -> None:
+        if motors is None:
+            motors = self.names
+        elif isinstance(motors, (str, int)):
+            motors = [motors]
+        else:
+            raise TypeError(motors)
+
+        for motor in motors:
+            model = self._get_motor_model(motor)
+            max_res = self.model_resolution_table[model] - 1
+            self.write("Homing_Offset", motor, 0, normalize=False)
+            self.write("Min_Position_Limit", motor, 0, normalize=False)
+            self.write("Max_Position_Limit", motor, max_res, normalize=False)
+
+    def register_ranges_of_motion(
+        self, motors: NameOrID | list[NameOrID] | None = None
+    ) -> dict[NameOrID, dict[str, Value]]:
+        """
+        This assumes that the homing offsets have been set such that all possible values in the range of
+        motion are positive and that the zero is not crossed. To that end, `set_half_turn_homings` should
+        typically be called prior to this.
+        """
+        if motors is None:
+            motors = self.names
+        elif isinstance(motors, (str, int)):
+            motors = [motors]
+        else:
+            raise TypeError(motors)
+
+        start_positions = self.sync_read("Present_Position", motors, normalize=False)
+        mins = start_positions.copy()
+        maxes = start_positions.copy()
+        while True:
+            positions = self.sync_read("Present_Position", motors, normalize=False)
+            mins = {motor: min(positions[motor], min_) for motor, min_ in mins.items()}
+            maxes = {motor: max(positions[motor], max_) for motor, max_ in maxes.items()}
+
+            if _enter_pressed():
+                break
+
+        for motor in motors:
+            self.write("Min_Position_Limit", motor, mins[motor], normalize=False)
+            self.write("Max_Position_Limit", motor, maxes[motor], normalize=False)
+
+        return {motor: {"min": mins[motor], "max": maxes[motor]} for motor in motors}
+
     @abc.abstractmethod
-    def _calibrate_values(self, ids_values: dict[int, int]) -> dict[int, float]:
+    def _get_half_turn_homings(self, positions: dict[NameOrID, Value]) -> dict[NameOrID, Value]:
         pass
 
     @abc.abstractmethod
-    def _uncalibrate_values(self, ids_values: dict[int, float]) -> dict[int, int]:
+    def _normalize(self, data_name: str, ids_values: dict[int, int]) -> dict[int, float]:
+        pass
+
+    @abc.abstractmethod
+    def _unnormalize(self, data_name: str, ids_values: dict[int, float]) -> dict[int, int]:
+        pass
+
+    @abc.abstractmethod
+    def _encode_value(
+        self, value: int, data_name: str | None = None, n_bytes: int | None = None
+    ) -> dict[int, int]:
+        pass
+
+    @abc.abstractmethod
+    def _decode_value(
+        self, value: int, data_name: str | None = None, n_bytes: int | None = None
+    ) -> dict[int, int]:
         pass
 
     @staticmethod
@@ -508,7 +612,7 @@ class MotorsBus(abc.ABC):
 
     @overload
     def sync_read(
-        self, data_name: str, motors: None = ..., *, raw_values: bool = ..., num_retry: int = ...
+        self, data_name: str, motors: None = ..., *, normalize: bool = ..., num_retry: int = ...
     ) -> dict[str, Value]: ...
     @overload
     def sync_read(
@@ -516,7 +620,7 @@ class MotorsBus(abc.ABC):
         data_name: str,
         motors: NameOrID | list[NameOrID],
         *,
-        raw_values: bool = ...,
+        normalize: bool = ...,
         num_retry: int = ...,
     ) -> dict[NameOrID, Value]: ...
     def sync_read(
@@ -524,7 +628,7 @@ class MotorsBus(abc.ABC):
         data_name: str,
         motors: NameOrID | list[NameOrID] | None = None,
         *,
-        raw_values: bool = False,
+        normalize: bool = True,
         num_retry: int = 0,
     ) -> dict[NameOrID, Value]:
         if not self.is_connected:
@@ -551,8 +655,8 @@ class MotorsBus(abc.ABC):
                 f"{self.packet_handler.getTxRxResult(comm)}"
             )
 
-        if not raw_values and data_name in self.calibration_required and self.calibration is not None:
-            ids_values = self._calibrate_values(ids_values)
+        if normalize and data_name in self.normalization_required and self.calibration is not None:
+            ids_values = self._normalize(ids_values)
 
         return {id_key_map[id_]: val for id_, val in ids_values.items()}
 
@@ -579,7 +683,11 @@ class MotorsBus(abc.ABC):
             logger.debug(f"Failed to sync read '{data_name}' ({addr=} {n_bytes=}) on {motor_ids=} ({n_try=})")
             logger.debug(self.packet_handler.getRxPacketError(comm))
 
-        values = {id_: self.sync_reader.getData(id_, addr, n_bytes) for id_ in motor_ids}
+        values = {}
+        for id_ in motor_ids:
+            val = self.sync_reader.getData(id_, addr, n_bytes)
+            values[id_] = self._decode_value(val, data_name, n_bytes)
+
         return comm, values
 
     def _setup_sync_reader(self, motor_ids: list[str], addr: int, n_bytes: int) -> None:
@@ -608,7 +716,7 @@ class MotorsBus(abc.ABC):
         data_name: str,
         values: Value | dict[NameOrID, Value],
         *,
-        raw_values: bool = False,
+        normalize: bool = True,
         num_retry: int = 0,
     ) -> None:
         if not self.is_connected:
@@ -621,10 +729,10 @@ class MotorsBus(abc.ABC):
         elif isinstance(values, dict):
             ids_values = {self._get_motor_id(motor): val for motor, val in values.items()}
         else:
-            raise ValueError(f"'values' is expected to be a single value or a dict. Got {values}")
+            raise TypeError(f"'values' is expected to be a single value or a dict. Got {values}")
 
-        if not raw_values and data_name in self.calibration_required and self.calibration is not None:
-            ids_values = self._uncalibrate_values(ids_values)
+        if normalize and data_name in self.normalization_required and self.calibration is not None:
+            ids_values = self._unnormalize(ids_values)
 
         comm = self._sync_write(data_name, ids_values, num_retry=num_retry)
         if not self._is_comm_success(comm):
@@ -640,6 +748,7 @@ class MotorsBus(abc.ABC):
 
         model = self._id_to_model(next(iter(ids_values)))
         addr, n_bytes = get_address(self.model_ctrl_table, model, data_name)
+        ids_values = {id_: self._encode_value(value, data_name, n_bytes) for id_, value in ids_values.items()}
         self._setup_sync_writer(ids_values, addr, n_bytes)
 
         for n_try in range(1 + num_retry):
@@ -662,7 +771,7 @@ class MotorsBus(abc.ABC):
             self.sync_writer.addParam(id_, data)
 
     def write(
-        self, data_name: str, motor: NameOrID, value: Value, *, raw_value: bool = False, num_retry: int = 0
+        self, data_name: str, motor: NameOrID, value: Value, *, normalize: bool = True, num_retry: int = 0
     ) -> None:
         if not self.is_connected:
             raise DeviceNotConnectedError(
@@ -671,8 +780,8 @@ class MotorsBus(abc.ABC):
 
         id_ = self._get_motor_id(motor)
 
-        if not raw_value and data_name in self.calibration_required and self.calibration is not None:
-            id_value = self._uncalibrate_values({id_: value})
+        if normalize and data_name in self.normalization_required and self.calibration is not None:
+            id_value = self._unnormalize({id_: value})
             value = id_value[id_]
 
         comm, error = self._write(data_name, id_, value, num_retry=num_retry)
@@ -690,6 +799,7 @@ class MotorsBus(abc.ABC):
     def _write(self, data_name: str, motor_id: int, value: int, num_retry: int = 0) -> tuple[int, int]:
         model = self._id_to_model(motor_id)
         addr, n_bytes = get_address(self.model_ctrl_table, model, data_name)
+        value = self._encode_value(value, data_name, n_bytes)
         data = self._split_int_to_bytes(value, n_bytes)
 
         for n_try in range(1 + num_retry):
diff --git a/lerobot/common/utils/utils.py b/lerobot/common/utils/utils.py
index 563a7b81..9440d1d2 100644
--- a/lerobot/common/utils/utils.py
+++ b/lerobot/common/utils/utils.py
@@ -17,7 +17,9 @@ import logging
 import os
 import os.path as osp
 import platform
+import select
 import subprocess
+import sys
 from copy import copy
 from datetime import datetime, timezone
 from pathlib import Path
@@ -228,3 +230,7 @@ def is_valid_numpy_dtype_string(dtype_str: str) -> bool:
     except TypeError:
         # If a TypeError is raised, the string is not a valid dtype
         return False
+
+
+def _enter_pressed() -> bool:
+    return select.select([sys.stdin], [], [], 0)[0] and sys.stdin.readline().strip() == ""

From 8503e8e1660d1a3cb6a932aab9d5b5e38ee2442b Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Mon, 31 Mar 2025 00:35:31 +0200
Subject: [PATCH 143/171] Move encoding functions to encoding_utils

---
 lerobot/common/motors/dynamixel/dynamixel.py | 27 +---------
 lerobot/common/motors/feetech/feetech.py     | 25 +---------
 lerobot/common/utils/encoding_utils.py       | 52 ++++++++++++++++++++
 3 files changed, 56 insertions(+), 48 deletions(-)
 create mode 100644 lerobot/common/utils/encoding_utils.py

diff --git a/lerobot/common/motors/dynamixel/dynamixel.py b/lerobot/common/motors/dynamixel/dynamixel.py
index f7e4569c..e6d6808c 100644
--- a/lerobot/common/motors/dynamixel/dynamixel.py
+++ b/lerobot/common/motors/dynamixel/dynamixel.py
@@ -22,6 +22,8 @@ import logging
 from copy import deepcopy
 from enum import Enum
 
+from lerobot.common.utils.encoding_utils import decode_twos_complement, encode_twos_complement
+
 from ..motors_bus import Motor, MotorsBus, NameOrID, Value
 from .tables import (
     AVAILABLE_BAUDRATES,
@@ -41,31 +43,6 @@ CONVERT_UINT32_TO_INT32_REQUIRED = ["Goal_Position", "Present_Position"]
 logger = logging.getLogger(__name__)
 
 
-def encode_twos_complement(value: int, n_bytes: int):
-    if value >= 0:
-        return value
-
-    bit_width = n_bytes * 8
-    min_val = -(1 << (bit_width - 1))
-    max_val = (1 << (bit_width - 1)) - 1
-
-    if not (min_val <= value <= max_val):
-        raise ValueError(
-            f"Value {value} out of range for {n_bytes}-byte two's complement: [{min_val}, {max_val}]"
-        )
-
-    return (1 << bit_width) + value
-
-
-def decode_twos_complement(value: int, n_bytes: int) -> int:
-    # https://en.wikipedia.org/wiki/Two%27s_complement
-    bits = n_bytes * 8
-    sign_bit = 1 << (bits - 1)
-    if value & sign_bit:
-        value -= 1 << bits
-    return value
-
-
 class OperatingMode(Enum):
     # DYNAMIXEL only controls current(torque) regardless of speed and position. This mode is ideal for a
     # gripper or a system that only uses current(torque) control or a system that has additional
diff --git a/lerobot/common/motors/feetech/feetech.py b/lerobot/common/motors/feetech/feetech.py
index 6eb37314..c0bd41fd 100644
--- a/lerobot/common/motors/feetech/feetech.py
+++ b/lerobot/common/motors/feetech/feetech.py
@@ -17,6 +17,8 @@ from copy import deepcopy
 from enum import Enum
 from pprint import pformat
 
+from lerobot.common.utils.encoding_utils import decode_sign_magnitude, encode_sign_magnitude
+
 from ..motors_bus import Motor, MotorsBus, NameOrID, Value
 from .tables import (
     AVAILABLE_BAUDRATES,
@@ -35,29 +37,6 @@ DEFAULT_TIMEOUT_MS = 1000
 logger = logging.getLogger(__name__)
 
 
-def encode_sign_magnitude(value: int, sign_bit_index: int):
-    """
-    https://en.wikipedia.org/wiki/Signed_number_representations#Sign%E2%80%93magnitude
-    """
-    max_magnitude = (1 << sign_bit_index) - 1
-    magnitude = abs(value)
-    if magnitude > max_magnitude:
-        raise ValueError(f"Magnitude {magnitude} exceeds {max_magnitude} (max for {sign_bit_index=})")
-
-    direction_bit = 1 if value < 0 else 0
-    return (direction_bit << sign_bit_index) | magnitude
-
-
-def decode_sign_magnitude(encoded_value: int, sign_bit_index: int):
-    """
-    https://en.wikipedia.org/wiki/Signed_number_representations#Sign%E2%80%93magnitude
-    """
-    direction_bit = (encoded_value >> sign_bit_index) & 1
-    magnitude_mask = (1 << sign_bit_index) - 1
-    magnitude = encoded_value & magnitude_mask
-    return -magnitude if direction_bit else magnitude
-
-
 class OperatingMode(Enum):
     # position servo mode
     POSITION = 0
diff --git a/lerobot/common/utils/encoding_utils.py b/lerobot/common/utils/encoding_utils.py
new file mode 100644
index 00000000..5f09297b
--- /dev/null
+++ b/lerobot/common/utils/encoding_utils.py
@@ -0,0 +1,52 @@
+def encode_sign_magnitude(value: int, sign_bit_index: int):
+    """
+    https://en.wikipedia.org/wiki/Signed_number_representations#Sign%E2%80%93magnitude
+    """
+    max_magnitude = (1 << sign_bit_index) - 1
+    magnitude = abs(value)
+    if magnitude > max_magnitude:
+        raise ValueError(f"Magnitude {magnitude} exceeds {max_magnitude} (max for {sign_bit_index=})")
+
+    direction_bit = 1 if value < 0 else 0
+    return (direction_bit << sign_bit_index) | magnitude
+
+
+def decode_sign_magnitude(encoded_value: int, sign_bit_index: int):
+    """
+    https://en.wikipedia.org/wiki/Signed_number_representations#Sign%E2%80%93magnitude
+    """
+    direction_bit = (encoded_value >> sign_bit_index) & 1
+    magnitude_mask = (1 << sign_bit_index) - 1
+    magnitude = encoded_value & magnitude_mask
+    return -magnitude if direction_bit else magnitude
+
+
+def encode_twos_complement(value: int, n_bytes: int):
+    """
+    https://en.wikipedia.org/wiki/Signed_number_representations#Two%27s_complement
+    """
+
+    bit_width = n_bytes * 8
+    min_val = -(1 << (bit_width - 1))
+    max_val = (1 << (bit_width - 1)) - 1
+
+    if not (min_val <= value <= max_val):
+        raise ValueError(
+            f"Value {value} out of range for {n_bytes}-byte two's complement: [{min_val}, {max_val}]"
+        )
+
+    if value >= 0:
+        return value
+
+    return (1 << bit_width) + value
+
+
+def decode_twos_complement(value: int, n_bytes: int) -> int:
+    """
+    https://en.wikipedia.org/wiki/Signed_number_representations#Two%27s_complement
+    """
+    bits = n_bytes * 8
+    sign_bit = 1 << (bits - 1)
+    if value & sign_bit:
+        value -= 1 << bits
+    return value

From 02803f545dd86618f67b109a9bff7121a6757895 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Mon, 31 Mar 2025 00:37:28 +0200
Subject: [PATCH 144/171] Add test_encoding_utils

---
 tests/utils/test_encoding_utils.py | 155 +++++++++++++++++++++++++++++
 1 file changed, 155 insertions(+)
 create mode 100644 tests/utils/test_encoding_utils.py

diff --git a/tests/utils/test_encoding_utils.py b/tests/utils/test_encoding_utils.py
new file mode 100644
index 00000000..5edfd177
--- /dev/null
+++ b/tests/utils/test_encoding_utils.py
@@ -0,0 +1,155 @@
+import pytest
+
+from lerobot.common.utils.encoding_utils import (
+    decode_sign_magnitude,
+    decode_twos_complement,
+    encode_sign_magnitude,
+    encode_twos_complement,
+)
+
+
+@pytest.mark.parametrize(
+    "value, sign_bit_index, expected",
+    [
+        (5, 4, 5),
+        (0, 4, 0),
+        (7, 3, 7),
+        (-1, 4, 17),
+        (-8, 4, 24),
+        (-3, 3, 11),
+    ],
+)
+def test_encode_sign_magnitude(value, sign_bit_index, expected):
+    assert encode_sign_magnitude(value, sign_bit_index) == expected
+
+
+@pytest.mark.parametrize(
+    "encoded, sign_bit_index, expected",
+    [
+        (5, 4, 5),
+        (0, 4, 0),
+        (7, 3, 7),
+        (17, 4, -1),
+        (24, 4, -8),
+        (11, 3, -3),
+    ],
+)
+def test_decode_sign_magnitude(encoded, sign_bit_index, expected):
+    assert decode_sign_magnitude(encoded, sign_bit_index) == expected
+
+
+@pytest.mark.parametrize(
+    "encoded, sign_bit_index",
+    [
+        (16, 4),
+        (-9, 3),
+    ],
+)
+def test_encode_raises_on_overflow(encoded, sign_bit_index):
+    with pytest.raises(ValueError):
+        encode_sign_magnitude(encoded, sign_bit_index)
+
+
+def test_encode_decode_sign_magnitude():
+    for sign_bit_index in range(2, 6):
+        max_val = (1 << sign_bit_index) - 1
+        for value in range(-max_val, max_val + 1):
+            encoded = encode_sign_magnitude(value, sign_bit_index)
+            decoded = decode_sign_magnitude(encoded, sign_bit_index)
+            assert decoded == value, f"Failed at value={value}, index={sign_bit_index}"
+
+
+@pytest.mark.parametrize(
+    "value, n_bytes, expected",
+    [
+        (0, 1, 0),
+        (5, 1, 5),
+        (-1, 1, 255),
+        (-128, 1, 128),
+        (-2, 1, 254),
+        (127, 1, 127),
+        (0, 2, 0),
+        (5, 2, 5),
+        (-1, 2, 65_535),
+        (-32_768, 2, 32_768),
+        (-2, 2, 65_534),
+        (32_767, 2, 32_767),
+        (0, 4, 0),
+        (5, 4, 5),
+        (-1, 4, 4_294_967_295),
+        (-2_147_483_648, 4, 2_147_483_648),
+        (-2, 4, 4_294_967_294),
+        (2_147_483_647, 4, 2_147_483_647),
+    ],
+)
+def test_encode_twos_complement(value, n_bytes, expected):
+    assert encode_twos_complement(value, n_bytes) == expected
+
+
+@pytest.mark.parametrize(
+    "value, n_bytes, expected",
+    [
+        (0, 1, 0),
+        (5, 1, 5),
+        (255, 1, -1),
+        (128, 1, -128),
+        (254, 1, -2),
+        (127, 1, 127),
+        (0, 2, 0),
+        (5, 2, 5),
+        (65_535, 2, -1),
+        (32_768, 2, -32_768),
+        (65_534, 2, -2),
+        (32_767, 2, 32_767),
+        (0, 4, 0),
+        (5, 4, 5),
+        (4_294_967_295, 4, -1),
+        (2_147_483_648, 4, -2_147_483_648),
+        (4_294_967_294, 4, -2),
+        (2_147_483_647, 4, 2_147_483_647),
+    ],
+)
+def test_decode_twos_complement(value, n_bytes, expected):
+    assert decode_twos_complement(value, n_bytes) == expected
+
+
+@pytest.mark.parametrize(
+    "value, n_bytes",
+    [
+        (-129, 1),
+        (128, 1),
+        (-32_769, 2),
+        (32_768, 2),
+        (-2_147_483_649, 4),
+        (2_147_483_648, 4),
+    ],
+)
+def test_encode_twos_complement_out_of_range(value, n_bytes):
+    with pytest.raises(ValueError):
+        encode_twos_complement(value, n_bytes)
+
+
+@pytest.mark.parametrize(
+    "value, n_bytes",
+    [
+        (-128, 1),
+        (-1, 1),
+        (0, 1),
+        (1, 1),
+        (127, 1),
+        (-32_768, 2),
+        (-1, 2),
+        (0, 2),
+        (1, 2),
+        (32_767, 2),
+        (-2_147_483_648, 4),
+        (-1, 4),
+        (0, 4),
+        (1, 4),
+        (2_147_483_647, 4),
+    ],
+)
+def test_twos_complement_roundtrip(value, n_bytes):
+    encoded = encode_twos_complement(value, n_bytes)
+    decoded = decode_twos_complement(encoded, n_bytes)
+    assert decoded == value, f"Failed at value={value}, n_bytes={n_bytes}"

From e096754d14a97bbb56e9e678259e8b4996ba4ca9 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Mon, 31 Mar 2025 00:41:25 +0200
Subject: [PATCH 145/171] Rename test

---
 tests/utils/test_encoding_utils.py | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/tests/utils/test_encoding_utils.py b/tests/utils/test_encoding_utils.py
index 5edfd177..c21c8081 100644
--- a/tests/utils/test_encoding_utils.py
+++ b/tests/utils/test_encoding_utils.py
@@ -149,7 +149,7 @@ def test_encode_twos_complement_out_of_range(value, n_bytes):
         (2_147_483_647, 4),
     ],
 )
-def test_twos_complement_roundtrip(value, n_bytes):
+def test_encode_decode_twos_complement(value, n_bytes):
     encoded = encode_twos_complement(value, n_bytes)
     decoded = decode_twos_complement(encoded, n_bytes)
     assert decoded == value, f"Failed at value={value}, n_bytes={n_bytes}"

From 6bfcc18e731f262c6866112172c3f35c56ddd155 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Mon, 31 Mar 2025 18:14:11 +0200
Subject: [PATCH 146/171] Add more calibration utilities

---
 lerobot/common/motors/__init__.py            |  2 +-
 lerobot/common/motors/dynamixel/dynamixel.py |  8 --
 lerobot/common/motors/feetech/feetech.py     |  8 --
 lerobot/common/motors/motors_bus.py          | 96 +++++++++++++++-----
 4 files changed, 72 insertions(+), 42 deletions(-)

diff --git a/lerobot/common/motors/__init__.py b/lerobot/common/motors/__init__.py
index 852317ea..dfbfbaee 100644
--- a/lerobot/common/motors/__init__.py
+++ b/lerobot/common/motors/__init__.py
@@ -1 +1 @@
-from .motors_bus import Motor, MotorNormMode, MotorsBus
+from .motors_bus import Motor, MotorCalibration, MotorNormMode, MotorsBus
diff --git a/lerobot/common/motors/dynamixel/dynamixel.py b/lerobot/common/motors/dynamixel/dynamixel.py
index e6d6808c..bae0f977 100644
--- a/lerobot/common/motors/dynamixel/dynamixel.py
+++ b/lerobot/common/motors/dynamixel/dynamixel.py
@@ -132,14 +132,6 @@ class DynamixelMotorsBus(MotorsBus):
 
         return half_turn_homings
 
-    def _normalize(self, ids_values: dict[int, int]) -> dict[int, float]:
-        # TODO
-        return ids_values
-
-    def _unnormalize(self, ids_values: dict[int, float]) -> dict[int, int]:
-        # TODO
-        return ids_values
-
     def _encode_value(self, value: int, data_name: str | None = None, n_bytes: int | None = None) -> int:
         return encode_twos_complement(value, n_bytes)
 
diff --git a/lerobot/common/motors/feetech/feetech.py b/lerobot/common/motors/feetech/feetech.py
index c0bd41fd..dc5de28d 100644
--- a/lerobot/common/motors/feetech/feetech.py
+++ b/lerobot/common/motors/feetech/feetech.py
@@ -112,14 +112,6 @@ class FeetechMotorsBus(MotorsBus):
 
         return half_turn_homings
 
-    def _normalize(self, data_name: str, ids_values: dict[int, int]) -> dict[int, float]:
-        # TODO
-        return ids_values
-
-    def _unnormalize(self, data_name: str, ids_values: dict[int, float]) -> dict[int, int]:
-        # TODO
-        return ids_values
-
     def _encode_value(self, value: int, data_name: str | None = None, n_bytes: int | None = None) -> int:
         sign_bit = self.encodings.get(data_name)
         return encode_sign_magnitude(value, sign_bit) if sign_bit is not None else value
diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py
index 7389f88a..29903be8 100644
--- a/lerobot/common/motors/motors_bus.py
+++ b/lerobot/common/motors/motors_bus.py
@@ -85,6 +85,15 @@ class MotorNormMode(Enum):
     VELOCITY = 3
 
 
+@dataclass
+class MotorCalibration:
+    id: int
+    drive_mode: int
+    homing_offset: int
+    range_min: int
+    range_max: int
+
+
 @dataclass
 class Motor:
     id: int
@@ -267,7 +276,7 @@ class MotorsBus(abc.ABC):
         self._comm_success: int
         self._no_error: int
 
-        self.calibration = None
+        self.calibration: dict[str, MotorCalibration] = {}
 
         self._id_to_model_dict = {m.id: m.model for m in self.motors.values()}
         self._id_to_name_dict = {m.id: name for name, m in self.motors.items()}
@@ -387,6 +396,7 @@ class MotorsBus(abc.ABC):
             ) from e
 
         self.set_timeout()
+        self.calibration = self.get_calibration()
         logger.debug(f"{self.__class__.__name__} connected.")
 
     @classmethod
@@ -429,19 +439,6 @@ class MotorsBus(abc.ABC):
             if self.port_handler.getBaudRate() != baudrate:
                 raise OSError("Failed to write bus baud rate.")
 
-    @property
-    def are_motors_configured(self) -> bool:
-        """
-        Only check the motor indices and not baudrate, since if the motor baudrates are incorrect, a
-        ConnectionError will be raised anyway.
-        """
-        try:
-            # TODO(aliberts): use ping instead
-            return (self.ids == self.sync_read("ID")).all()
-        except ConnectionError as e:
-            logger.error(e)
-            return False
-
     def set_half_turn_homings(self, motors: NameOrID | list[NameOrID] | None = None) -> dict[NameOrID, Value]:
         """This assumes motors present positions are roughly in the middle of their desired range"""
         if motors is None:
@@ -457,7 +454,7 @@ class MotorsBus(abc.ABC):
         # Step 2: Read Present_Position which will be Actual_Position since
         # Present_Position = Actual_Position ± Homing_Offset (1)
         # and Homing_Offset = 0 from step 1
-        actual_positions = self.sync_read("Present_Position", motors, normalize=True)
+        actual_positions = self.sync_read("Present_Position", motors, normalize=False)
 
         # Step 3: We want to set the Homing_Offset such that the current Present_Position to be half range of
         # 1 revolution.
@@ -479,7 +476,7 @@ class MotorsBus(abc.ABC):
             motors = self.names
         elif isinstance(motors, (str, int)):
             motors = [motors]
-        else:
+        elif not isinstance(motors, list):
             raise TypeError(motors)
 
         for motor in motors:
@@ -501,7 +498,7 @@ class MotorsBus(abc.ABC):
             motors = self.names
         elif isinstance(motors, (str, int)):
             motors = [motors]
-        else:
+        elif not isinstance(motors, list):
             raise TypeError(motors)
 
         start_positions = self.sync_read("Present_Position", motors, normalize=False)
@@ -521,17 +518,66 @@ class MotorsBus(abc.ABC):
 
         return {motor: {"min": mins[motor], "max": maxes[motor]} for motor in motors}
 
+    def get_calibration(self) -> dict[str, MotorCalibration]:
+        offsets = self.sync_read("Homing_Offset", normalize=False)
+        mins = self.sync_read("Min_Position_Limit", normalize=False)
+        maxes = self.sync_read("Max_Position_Limit", normalize=False)
+
+        try:
+            drive_modes = self.sync_read("Drive_Mode", normalize=False)
+        except KeyError:
+            drive_modes = {name: 0 for name in self.names}
+
+        calibration = {}
+        for name, motor in self.motors.items():
+            calibration[name] = MotorCalibration(
+                id=motor.id,
+                drive_mode=drive_modes[name],
+                homing_offset=offsets[name],
+                range_min=mins[name],
+                range_max=maxes[name],
+            )
+
+        return calibration
+
     @abc.abstractmethod
     def _get_half_turn_homings(self, positions: dict[NameOrID, Value]) -> dict[NameOrID, Value]:
         pass
 
-    @abc.abstractmethod
     def _normalize(self, data_name: str, ids_values: dict[int, int]) -> dict[int, float]:
-        pass
+        normalized_values = {}
+        for id_, val in ids_values.items():
+            name = self._id_to_name(id_)
+            min_ = self.calibration[name].range_min
+            max_ = self.calibration[name].range_max
+            bounded_val = min(max_, max(min_, val))
+            if self.motors[name].norm_mode is MotorNormMode.RANGE_M100_100:
+                normalized_values[id_] = (((bounded_val - min_) / (max_ - min_)) * 200) - 100
+            elif self.motors[name].norm_mode is MotorNormMode.RANGE_0_100:
+                normalized_values[id_] = ((bounded_val - min_) / (max_ - min_)) * 100
+            else:
+                # TODO(alibers): velocity and degree modes
+                raise NotImplementedError
+
+        return normalized_values
 
-    @abc.abstractmethod
     def _unnormalize(self, data_name: str, ids_values: dict[int, float]) -> dict[int, int]:
-        pass
+        unnormalized_values = {}
+        for id_, val in ids_values.items():
+            name = self._id_to_name(id_)
+            min_ = self.calibration[name].range_min
+            max_ = self.calibration[name].range_max
+            if self.motors[name].norm_mode is MotorNormMode.RANGE_M100_100:
+                bounded_val = min(100.0, max(-100.0, val))
+                unnormalized_values[id_] = int(((bounded_val + 100) / 200) * (max_ - min_) + min_)
+            elif self.motors[name].norm_mode is MotorNormMode.RANGE_0_100:
+                bounded_val = min(100.0, max(0.0, val))
+                unnormalized_values[id_] = int((bounded_val / 100) * (max_ - min_) + min_)
+            else:
+                # TODO(alibers): velocity and degree modes
+                raise NotImplementedError
+
+        return unnormalized_values
 
     @abc.abstractmethod
     def _encode_value(
@@ -655,8 +701,8 @@ class MotorsBus(abc.ABC):
                 f"{self.packet_handler.getTxRxResult(comm)}"
             )
 
-        if normalize and data_name in self.normalization_required and self.calibration is not None:
-            ids_values = self._normalize(ids_values)
+        if normalize and data_name in self.normalization_required:
+            ids_values = self._normalize(data_name, ids_values)
 
         return {id_key_map[id_]: val for id_, val in ids_values.items()}
 
@@ -732,7 +778,7 @@ class MotorsBus(abc.ABC):
             raise TypeError(f"'values' is expected to be a single value or a dict. Got {values}")
 
         if normalize and data_name in self.normalization_required and self.calibration is not None:
-            ids_values = self._unnormalize(ids_values)
+            ids_values = self._unnormalize(data_name, ids_values)
 
         comm = self._sync_write(data_name, ids_values, num_retry=num_retry)
         if not self._is_comm_success(comm):
@@ -781,7 +827,7 @@ class MotorsBus(abc.ABC):
         id_ = self._get_motor_id(motor)
 
         if normalize and data_name in self.normalization_required and self.calibration is not None:
-            id_value = self._unnormalize({id_: value})
+            id_value = self._unnormalize(data_name, {id_: value})
             value = id_value[id_]
 
         comm, error = self._write(data_name, id_, value, num_retry=num_retry)

From 8cc0232e73a11efeba25fdba59abccee8a4a17e5 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Mon, 31 Mar 2025 18:14:57 +0200
Subject: [PATCH 147/171] Format baudrate tables

---
 lerobot/common/motors/dynamixel/tables.py | 34 +++++++++++------------
 lerobot/common/motors/feetech/tables.py   | 22 +++++++--------
 2 files changed, 28 insertions(+), 28 deletions(-)

diff --git a/lerobot/common/motors/dynamixel/tables.py b/lerobot/common/motors/dynamixel/tables.py
index 5589b224..525404bf 100644
--- a/lerobot/common/motors/dynamixel/tables.py
+++ b/lerobot/common/motors/dynamixel/tables.py
@@ -121,21 +121,21 @@ MODEL_BAUDRATE_TABLE = {
 }
 
 AVAILABLE_BAUDRATES = [
-    9600,
-    19200,
-    38400,
-    57600,
-    115200,
-    230400,
-    460800,
-    500000,
-    576000,
-    921600,
-    1000000,
-    1152000,
-    2000000,
-    2500000,
-    3000000,
-    3500000,
-    4000000,
+    9_600,
+    19_200,
+    38_400,
+    57_600,
+    115_200,
+    230_400,
+    460_800,
+    500_000,
+    576_000,
+    921_600,
+    1_000_000,
+    1_152_000,
+    2_000_000,
+    2_500_000,
+    3_000_000,
+    3_500_000,
+    4_000_000,
 ]
diff --git a/lerobot/common/motors/feetech/tables.py b/lerobot/common/motors/feetech/tables.py
index 0ea0962b..a1220ac8 100644
--- a/lerobot/common/motors/feetech/tables.py
+++ b/lerobot/common/motors/feetech/tables.py
@@ -92,15 +92,15 @@ ENCODINGS = {
 }
 
 AVAILABLE_BAUDRATES = [
-    4800,
-    9600,
-    14400,
-    19200,
-    38400,
-    57600,
-    115200,
-    128000,
-    250000,
-    500000,
-    1000000,
+    4_800,
+    9_600,
+    14_400,
+    19_200,
+    38_400,
+    57_600,
+    115_200,
+    128_000,
+    250_000,
+    500_000,
+    1_000_000,
 ]

From 201311503ffe96b25792e2593ba7f12b588d6801 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Mon, 31 Mar 2025 18:16:42 +0200
Subject: [PATCH 148/171] Implement SO-100 leader calibration

---
 .../teleoperators/so100/teleop_so100.py       | 91 +++++++++----------
 lerobot/common/teleoperators/teleoperator.py  | 29 +++++-
 2 files changed, 66 insertions(+), 54 deletions(-)

diff --git a/lerobot/common/teleoperators/so100/teleop_so100.py b/lerobot/common/teleoperators/so100/teleop_so100.py
index 2190321c..75e56d15 100644
--- a/lerobot/common/teleoperators/so100/teleop_so100.py
+++ b/lerobot/common/teleoperators/so100/teleop_so100.py
@@ -14,19 +14,16 @@
 # 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 import Motor, MotorNormMode
-from lerobot.common.motors.calibration import find_min_max, find_offset, set_calibration
+from lerobot.common.motors import Motor, MotorCalibration, MotorNormMode
 from lerobot.common.motors.feetech import (
     FeetechMotorsBus,
+    OperatingMode,
+    TorqueMode,
 )
-from lerobot.common.motors.feetech.feetech import TorqueMode
 
 from ..teleoperator import Teleoperator
 from .configuration_so100 import SO100TeleopConfig
@@ -71,19 +68,6 @@ class SO100Teleop(Teleoperator):
     def feedback_feature(self) -> dict:
         return {}
 
-    def configure(self) -> None:
-        if not self.calibration_fpath.exists():
-            print("Calibration file not found. Running calibration.")
-            self.calibrate()
-        else:
-            print("Calibration file found. Loading calibration data.")
-            set_calibration(self.arm, self.calibration_fpath)
-
-        # We assume that at connection time, arm is in a rest position,
-        # and torque can be safely disabled to run calibration.
-        for name in self.arm.names:
-            self.arm.write("Torque_Enable", name, TorqueMode.DISABLED.value)
-
     @property
     def is_connected(self) -> bool:
         return self.arm.is_connected
@@ -96,46 +80,53 @@ class SO100Teleop(Teleoperator):
 
         logging.info("Connecting arm.")
         self.arm.connect()
+        if not self.is_calibrated:
+            self.calibrate()
+
         self.configure()
 
-        # Check arm can be read
-        self.arm.sync_read("Present_Position")
-
-    def calibrate(self) -> None:
-        print(f"\nRunning calibration of {self.name} teleop")
+    def configure(self) -> None:
+        # We assume that at connection time, arm is in a rest position,
+        # and torque can be safely disabled to run calibration.
         for name in self.arm.names:
             self.arm.write("Torque_Enable", name, TorqueMode.DISABLED.value)
 
-        offsets = find_offset(self.arm)
-        min_max = find_min_max(self.arm)
+    @property
+    def is_calibrated(self) -> bool:
+        motors_calibration = self.arm.get_calibration()
+        return motors_calibration == self.calibration
 
-        calibration = {}
+    def calibrate(self) -> None:
+        print(f"\nRunning calibration of {self.id} SO-100 teleop")
         for name in self.arm.names:
-            motor_id = self.arm.motors[name].id
-            calibration[str(motor_id)] = {
-                "name": name,
-                "homing_offset": offsets.get(name, 0),
-                "drive_mode": 0,
-                "min": min_max[name]["min"],
-                "max": min_max[name]["max"],
-            }
+            self.arm.write("Torque_Enable", name, TorqueMode.DISABLED.value)
+            self.arm.write("Operating_Mode", name, OperatingMode.POSITION.value)
 
-        with open(self.calibration_fpath, "w") as f:
-            json.dump(calibration, f, indent=4)
+        input("Move robot to the middle of its range of motion and press ENTER....")
+        homing_offsets = self.arm.set_half_turn_homings()
+
+        print(
+            "Move all joints except 'wrist_roll' (id=5) sequentially through their entire ranges of motion."
+        )
+        print("Recording positions. Press ENTER to stop...")
+        auto_range_motors = [name for name in self.arm.names if name != "wrist_roll"]
+        ranges = self.arm.register_ranges_of_motion(auto_range_motors)
+        ranges["wrist_roll"] = {"min": 0, "max": 4095}
+
+        self.calibration = {}
+        for name, motor in self.arm.motors.items():
+            self.calibration[name] = MotorCalibration(
+                id=motor.id,
+                drive_mode=0,
+                homing_offset=homing_offsets[name],
+                range_min=ranges[name]["min"],
+                range_max=ranges[name]["max"],
+            )
+
+        self._save_calibration()
         print("Calibration saved to", self.calibration_fpath)
 
-    def set_calibration(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].
-        """
-        if not self.calibration_fpath.exists():
-            logging.error("Calibration file not found. Please run calibration first")
-            raise FileNotFoundError(self.calibration_fpath)
-
-        self.arm.set_calibration(self.calibration_fpath)
-
-    def get_action(self) -> np.ndarray:
+    def get_action(self) -> dict[str, float]:
         """The returned action does not have a batch dimension."""
         # Read arm position
         before_read_t = time.perf_counter()
@@ -144,7 +135,7 @@ class SO100Teleop(Teleoperator):
 
         return action
 
-    def send_feedback(self, feedback: np.ndarray) -> None:
+    def send_feedback(self, feedback: dict[str, float]) -> None:
         # TODO(rcadene, aliberts): Implement force feedback
         pass
 
diff --git a/lerobot/common/teleoperators/teleoperator.py b/lerobot/common/teleoperators/teleoperator.py
index 743bd2c6..7267f27a 100644
--- a/lerobot/common/teleoperators/teleoperator.py
+++ b/lerobot/common/teleoperators/teleoperator.py
@@ -1,7 +1,11 @@
 import abc
+from pathlib import Path
 from typing import Any
 
+import draccus
+
 from lerobot.common.constants import HF_LEROBOT_CALIBRATION, TELEOPERATORS
+from lerobot.common.motors.motors_bus import MotorCalibration
 
 from .config import TeleoperatorConfig
 
@@ -22,6 +26,9 @@ class Teleoperator(abc.ABC):
         )
         self.calibration_dir.mkdir(parents=True, exist_ok=True)
         self.calibration_fpath = self.calibration_dir / f"{self.id}.json"
+        self.calibration: dict[str, MotorCalibration] = {}
+        if self.calibration_fpath.is_file():
+            self._load_calibration()
 
     @abc.abstractproperty
     def action_feature(self) -> dict:
@@ -40,11 +47,29 @@ class Teleoperator(abc.ABC):
         """Connects to the teleoperator."""
         pass
 
+    @abc.abstractmethod
+    def configure(self) -> None:
+        pass
+
+    @abc.abstractproperty
+    def is_calibrated(self) -> bool:
+        pass
+
     @abc.abstractmethod
     def calibrate(self) -> None:
         """Calibrates the teleoperator."""
         pass
 
+    def _load_calibration(self, fpath: Path | None = None) -> None:
+        fpath = self.calibration_fpath if fpath is None else fpath
+        with open(fpath) as f, draccus.config_type("json"):
+            self.calibration = draccus.load(dict[str, MotorCalibration], f)
+
+    def _save_calibration(self, fpath: Path | None = None) -> None:
+        fpath = self.calibration_fpath if fpath is None else fpath
+        with open(fpath, "w") as f, draccus.config_type("json"):
+            draccus.dump(self.calibration, f, indent=4)
+
     @abc.abstractmethod
     def get_action(self) -> dict[str, Any]:
         """Gets the action to send to a teleoperator."""
@@ -59,7 +84,3 @@ class Teleoperator(abc.ABC):
     def disconnect(self) -> None:
         """Disconnects from the teleoperator."""
         pass
-
-    def __del__(self):
-        if getattr(self, "is_connected", False):
-            self.disconnect()

From bc765f9e95786fcbb76dafe3bfc7ebd745e58d39 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Mon, 31 Mar 2025 18:17:20 +0200
Subject: [PATCH 149/171] Implement SO-100 follower calibration

---
 lerobot/common/robots/robot.py             |  29 ++++-
 lerobot/common/robots/so100/robot_so100.py | 123 +++++++++++----------
 2 files changed, 87 insertions(+), 65 deletions(-)

diff --git a/lerobot/common/robots/robot.py b/lerobot/common/robots/robot.py
index a263a043..7ae67ba5 100644
--- a/lerobot/common/robots/robot.py
+++ b/lerobot/common/robots/robot.py
@@ -1,7 +1,11 @@
 import abc
+from pathlib import Path
 from typing import Any
 
+import draccus
+
 from lerobot.common.constants import HF_LEROBOT_CALIBRATION, ROBOTS
+from lerobot.common.motors import MotorCalibration
 
 from .config import RobotConfig
 
@@ -23,6 +27,9 @@ class Robot(abc.ABC):
         )
         self.calibration_dir.mkdir(parents=True, exist_ok=True)
         self.calibration_fpath = self.calibration_dir / f"{self.id}.json"
+        self.calibration: dict[str, MotorCalibration] = {}
+        if self.calibration_fpath.is_file():
+            self._load_calibration()
 
     # TODO(aliberts): create a proper Feature class for this that links with datasets
     @abc.abstractproperty
@@ -46,11 +53,29 @@ class Robot(abc.ABC):
         """Connects to the robot."""
         pass
 
+    @abc.abstractmethod
+    def configure(self) -> None:
+        pass
+
+    @abc.abstractproperty
+    def is_calibrated(self) -> bool:
+        pass
+
     @abc.abstractmethod
     def calibrate(self) -> None:
         """Calibrates the robot."""
         pass
 
+    def _load_calibration(self, fpath: Path | None = None) -> None:
+        fpath = self.calibration_fpath if fpath is None else fpath
+        with open(fpath) as f, draccus.config_type("json"):
+            self.calibration = draccus.load(dict[str, MotorCalibration], f)
+
+    def _save_calibration(self, fpath: Path | None = None) -> None:
+        fpath = self.calibration_fpath if fpath is None else fpath
+        with open(fpath, "w") as f, draccus.config_type("json"):
+            draccus.dump(self.calibration, f, indent=4)
+
     @abc.abstractmethod
     def get_observation(self) -> dict[str, Any]:
         """Gets observation from the robot."""
@@ -65,7 +90,3 @@ class Robot(abc.ABC):
     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/so100/robot_so100.py b/lerobot/common/robots/so100/robot_so100.py
index 00432d4b..78273723 100644
--- a/lerobot/common/robots/so100/robot_so100.py
+++ b/lerobot/common/robots/so100/robot_so100.py
@@ -14,17 +14,14 @@
 # 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 typing import Any
 
 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 import Motor, MotorNormMode
-from lerobot.common.motors.calibration import find_min_max, find_offset, set_calibration
+from lerobot.common.motors import Motor, MotorCalibration, MotorNormMode
 from lerobot.common.motors.feetech import (
     FeetechMotorsBus,
     OperatingMode,
@@ -86,35 +83,6 @@ class SO100Robot(Robot):
             }
         return cam_ft
 
-    def configure(self) -> None:
-        for name in self.arm.names:
-            # 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", name, TorqueMode.DISABLED.value)
-            self.arm.write("Mode", name, OperatingMode.POSITION.value)
-
-            # Set P_Coefficient to lower value to avoid shakiness (Default is 32)
-            self.arm.write("P_Coefficient", name, 16)
-            # Set I_Coefficient and D_Coefficient to default value 0 and 32
-            self.arm.write("I_Coefficient", name, 0)
-            self.arm.write("D_Coefficient", name, 32)
-            # 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", name, 254)
-            self.arm.write("Acceleration", name, 254)
-
-        if not self.calibration_fpath.exists():
-            print("Calibration file not found. Running calibration.")
-            self.calibrate()
-        else:
-            print("Calibration file found. Loading calibration data.")
-            set_calibration(self.arm, self.calibration_fpath)
-
-        for name in self.arm.names:
-            self.arm.write("Torque_Enable", name, TorqueMode.ENABLED.value)
-
-        logging.info("Torque activated.")
-
     @property
     def is_connected(self) -> bool:
         # TODO(aliberts): add cam.is_connected for cam in self.cameras
@@ -128,37 +96,73 @@ class SO100Robot(Robot):
 
         logging.info("Connecting arm.")
         self.arm.connect()
-        self.configure()
+        if not self.is_calibrated:
+            self.calibrate()
 
-        # Check arm can be read
-        self.arm.sync_read("Present_Position")
+        self.configure()
 
         # Connect the cameras
         for cam in self.cameras.values():
             cam.connect()
 
-    def calibrate(self) -> None:
-        print(f"\nRunning calibration of {self.name} robot")
-
-        offsets = find_offset(self.arm)
-        min_max = find_min_max(self.arm)
-
-        calibration = {}
+    def configure(self) -> None:
         for name in self.arm.names:
-            motor_id = self.arm.motors[name].id
-            calibration[str(motor_id)] = {
-                "name": name,
-                "homing_offset": offsets.get(name, 0),
-                "drive_mode": 0,
-                "min": min_max[name]["min"],
-                "max": min_max[name]["max"],
-            }
+            # 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", name, TorqueMode.DISABLED.value)
+            self.arm.write("Operating_Mode", name, OperatingMode.POSITION.value)
 
-        with open(self.calibration_fpath, "w") as f:
-            json.dump(calibration, f, indent=4)
+            # Set P_Coefficient to lower value to avoid shakiness (Default is 32)
+            self.arm.write("P_Coefficient", name, 16)
+            # Set I_Coefficient and D_Coefficient to default value 0 and 32
+            self.arm.write("I_Coefficient", name, 0)
+            self.arm.write("D_Coefficient", name, 32)
+            # 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", name, 254)
+            self.arm.write("Acceleration", name, 254)
+
+        for name in self.arm.names:
+            self.arm.write("Torque_Enable", name, TorqueMode.ENABLED.value)
+
+        logging.info("Torque activated.")
+
+    @property
+    def is_calibrated(self) -> bool:
+        motors_calibration = self.arm.get_calibration()
+        return motors_calibration == self.calibration
+
+    def calibrate(self) -> None:
+        print(f"\nRunning calibration of {self.id} SO-100 robot")
+        for name in self.arm.names:
+            self.arm.write("Torque_Enable", name, TorqueMode.DISABLED.value)
+            self.arm.write("Operating_Mode", name, OperatingMode.POSITION.value)
+
+        input("Move robot to the middle of its range of motion and press ENTER....")
+        homing_offsets = self.arm.set_half_turn_homings()
+
+        print(
+            "Move all joints except 'wrist_roll' (id=5) sequentially through their entire ranges of motion."
+        )
+        print("Recording positions. Press ENTER to stop...")
+        auto_range_motors = [name for name in self.arm.names if name != "wrist_roll"]
+        ranges = self.arm.register_ranges_of_motion(auto_range_motors)
+        ranges["wrist_roll"] = {"min": 0, "max": 4095}
+
+        self.calibration = {}
+        for name, motor in self.arm.motors.items():
+            self.calibration[name] = MotorCalibration(
+                id=motor.id,
+                drive_mode=0,
+                homing_offset=homing_offsets[name],
+                range_min=ranges[name]["min"],
+                range_max=ranges[name]["max"],
+            )
+
+        self._save_calibration()
         print("Calibration saved to", self.calibration_fpath)
 
-    def get_observation(self) -> dict[str, np.ndarray]:
+    def get_observation(self) -> dict[str, Any]:
         """The returned observations do not have a batch dimension."""
         if not self.is_connected:
             raise DeviceNotConnectedError(
@@ -181,21 +185,18 @@ class SO100Robot(Robot):
 
         return obs_dict
 
-    def send_action(self, action: np.ndarray) -> np.ndarray:
+    def send_action(self, action: dict[str, Any]) -> dict[str, Any]:
         """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.
+            the action sent to the motors, potentially clipped.
         """
         if not self.is_connected:
             raise DeviceNotConnectedError(
@@ -211,7 +212,7 @@ class SO100Robot(Robot):
             goal_pos = ensure_safe_goal_position(goal_pos, present_pos, self.config.max_relative_target)
 
         # Send goal position to the arm
-        self.arm.sync_write("Goal_Position", goal_pos.astype(np.int32))
+        self.arm.sync_write("Goal_Position", goal_pos)
 
         return goal_pos
 

From 79293800f184381f47f07946f5717c64660d7d07 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Mon, 31 Mar 2025 18:18:27 +0200
Subject: [PATCH 150/171] Implement Koch calibration

---
 lerobot/common/robots/koch/robot_koch.py      | 103 +++++++++---------
 .../teleoperators/koch/configuration_koch.py  |   6 +-
 .../common/teleoperators/koch/teleop_koch.py  | 103 ++++++++++--------
 3 files changed, 114 insertions(+), 98 deletions(-)

diff --git a/lerobot/common/robots/koch/robot_koch.py b/lerobot/common/robots/koch/robot_koch.py
index 06e21b1c..e05280e6 100644
--- a/lerobot/common/robots/koch/robot_koch.py
+++ b/lerobot/common/robots/koch/robot_koch.py
@@ -14,7 +14,6 @@
 # See the License for the specific language governing permissions and
 # limitations under the License.
 
-import json
 import logging
 import time
 from typing import Any
@@ -22,12 +21,11 @@ from typing import Any
 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 import Motor, MotorNormMode
+from lerobot.common.motors import Motor, MotorCalibration, MotorNormMode
 from lerobot.common.motors.dynamixel import (
     DynamixelMotorsBus,
     OperatingMode,
     TorqueMode,
-    run_arm_calibration,
 )
 
 from ..robot import Robot
@@ -63,7 +61,6 @@ class KochRobot(Robot):
         )
         self.cameras = make_cameras_from_configs(config.cameras)
 
-        self.is_connected = False
         self.logs = {}
 
     @property
@@ -89,6 +86,28 @@ class KochRobot(Robot):
             }
         return cam_ft
 
+    @property
+    def is_connected(self) -> bool:
+        # TODO(aliberts): add cam.is_connected for cam in self.cameras
+        return self.arm.is_connected
+
+    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()
+        if not self.is_calibrated:
+            self.calibrate()
+
+        self.configure()
+
+        # Connect the cameras
+        for cam in self.cameras.values():
+            cam.connect()
+
     def configure(self) -> None:
         for name in self.arm.names:
             # Torque must be deactivated to change values in the motors' EEPROM area
@@ -120,54 +139,42 @@ class KochRobot(Robot):
 
         logging.info("Torque enabled.")
 
-        # Move gripper to 45 degrees so that we can use it as a trigger.
-        self.arm.write("Goal_Position", "gripper", self.config.gripper_open_degree)
-
     @property
-    def is_connected(self) -> bool:
-        # TODO(aliberts): add cam.is_connected for cam in self.cameras
-        return self.arm.is_connected
-
-    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()
-        self.configure()
-        # self.calibrate()  # TODO
-
-        # Check arm can be read
-        self.arm.sync_read("Present_Position")
-
-        # Connect the cameras
-        for cam in self.cameras.values():
-            cam.connect()
-
-        self.is_connected = True
+    def is_calibrated(self) -> bool:
+        motors_calibration = self.arm.get_calibration()
+        return motors_calibration == self.calibration
 
     def calibrate(self) -> None:
-        # TODO(pepijn): Do calibration in same way as so100
-        """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].
-        """
-        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 '{self.calibration_fpath}'")
-            calibration = run_arm_calibration(self.arm, self.robot_type, self.name, "follower")
+        print(f"\nRunning calibration of {self.id} Koch robot")
+        for name in self.arm.names:
+            self.arm.write("Torque_Enable", name, TorqueMode.DISABLED.value)
+            self.arm.write("Operating_Mode", name, OperatingMode.EXTENDED_POSITION.value)
 
-            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)
+        input("Move robot to the middle of its range of motion and press ENTER....")
+        homing_offsets = self.arm.set_half_turn_homings()
 
-        self.arm.set_calibration(calibration)
+        fixed_range = ["shoulder_pan", "wrist_roll"]
+        auto_range_motors = [name for name in self.arm.names if name not in fixed_range]
+        print(
+            "Move all joints except 'wrist_roll' (id=5) sequentially through their entire ranges of motion."
+        )
+        print("Recording positions. Press ENTER to stop...")
+        ranges = self.arm.register_ranges_of_motion(auto_range_motors)
+        for name in fixed_range:
+            ranges[name] = {"min": 0, "max": 4095}
+
+        self.calibration = {}
+        for name, motor in self.arm.motors.items():
+            self.calibration[name] = MotorCalibration(
+                id=motor.id,
+                drive_mode=0,
+                homing_offset=homing_offsets[name],
+                range_min=ranges[name]["min"],
+                range_max=ranges[name]["max"],
+            )
+
+        self._save_calibration()
+        print("Calibration saved to", self.calibration_fpath)
 
     def get_observation(self) -> dict[str, Any]:
         obs_dict = {}
@@ -226,5 +233,3 @@ class KochRobot(Robot):
         self.arm.disconnect()
         for cam in self.cameras.values():
             cam.disconnect()
-
-        self.is_connected = False
diff --git a/lerobot/common/teleoperators/koch/configuration_koch.py b/lerobot/common/teleoperators/koch/configuration_koch.py
index 2c6a2969..cf95f547 100644
--- a/lerobot/common/teleoperators/koch/configuration_koch.py
+++ b/lerobot/common/teleoperators/koch/configuration_koch.py
@@ -25,6 +25,6 @@ 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
+    # Sets the arm in torque mode with the gripper motor set to this value. This makes it possible to squeeze
+    # the gripper and have it spring back to an open position on its own.
+    gripper_open_pos: float = 50.0
diff --git a/lerobot/common/teleoperators/koch/teleop_koch.py b/lerobot/common/teleoperators/koch/teleop_koch.py
index 1b1506bd..1d49ea10 100644
--- a/lerobot/common/teleoperators/koch/teleop_koch.py
+++ b/lerobot/common/teleoperators/koch/teleop_koch.py
@@ -14,19 +14,16 @@
 # 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 import Motor, MotorNormMode
+from lerobot.common.motors import Motor, MotorCalibration, MotorNormMode
 from lerobot.common.motors.dynamixel import (
+    DriveMode,
     DynamixelMotorsBus,
     OperatingMode,
     TorqueMode,
-    run_arm_calibration,
 )
 
 from ..teleoperator import Teleoperator
@@ -74,6 +71,23 @@ class KochTeleop(Teleoperator):
     def feedback_feature(self) -> dict:
         return {}
 
+    @property
+    def is_connected(self) -> bool:
+        return self.arm.is_connected
+
+    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()
+        if not self.is_calibrated:
+            self.calibrate()
+
+        self.configure()
+
     def configure(self) -> None:
         for name in self.arm.names:
             # Torque must be deactivated to change values in the motors' EEPROM area
@@ -93,52 +107,49 @@ class KochTeleop(Teleoperator):
         # 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.
         self.arm.write("Operating_Mode", "gripper", OperatingMode.CURRENT_POSITION.value)
-
-        for name in self.arm.names:
-            self.arm.write("Torque_Enable", name, TorqueMode.ENABLED.value)
-
-        logging.info("Torque enabled.")
-
-        # Move gripper to 45 degrees so that we can use it as a trigger.
-        self.arm.write("Goal_Position", "gripper", self.config.gripper_open_degree)
+        # Set gripper's goal pos in current position mode so that we can use it as a trigger.
+        self.arm.write("Torque_Enable", "gripper", TorqueMode.ENABLED.value)
+        self.arm.write("Goal_Position", "gripper", self.config.gripper_open_pos)
 
     @property
-    def is_connected(self) -> bool:
-        return self.arm.is_connected
-
-    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()
-        self.configure()
-        # self.calibrate()  # TODO
-
-        # Check arm can be read
-        self.arm.sync_read("Present_Position")
+    def is_calibrated(self) -> bool:
+        motors_calibration = self.arm.get_calibration()
+        return motors_calibration == self.calibration
 
     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].
-        """
-        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 '{self.calibration_fpath}'")
-            calibration = run_arm_calibration(self.arm, self.robot_type, self.name, "leader")
+        print(f"\nRunning calibration of {self.id} Koch teleop")
+        for name in self.arm.names:
+            self.arm.write("Torque_Enable", name, TorqueMode.DISABLED.value)
+            self.arm.write("Operating_Mode", name, OperatingMode.EXTENDED_POSITION.value)
 
-            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.write("Drive_Mode", "elbow_flex", DriveMode.INVERTED.value)
+        drive_modes = {name: 1 if name == "elbow_flex" else 0 for name in self.arm.names}
 
-        self.arm.set_calibration(calibration)
+        input("Move robot to the middle of its range of motion and press ENTER....")
+        homing_offsets = self.arm.set_half_turn_homings()
+
+        fixed_range = ["shoulder_pan", "wrist_roll"]
+        auto_range_motors = [name for name in self.arm.names if name not in fixed_range]
+        print(
+            "Move all joints except 'wrist_roll' (id=5) sequentially through their entire ranges of motion."
+        )
+        print("Recording positions. Press ENTER to stop...")
+        ranges = self.arm.register_ranges_of_motion(auto_range_motors)
+        for name in fixed_range:
+            ranges[name] = {"min": 0, "max": 4095}
+
+        self.calibration = {}
+        for name, motor in self.arm.motors.items():
+            self.calibration[name] = MotorCalibration(
+                id=motor.id,
+                drive_mode=drive_modes[name],
+                homing_offset=homing_offsets[name],
+                range_min=ranges[name]["min"],
+                range_max=ranges[name]["max"],
+            )
+
+        self._save_calibration()
+        print("Calibration saved to", self.calibration_fpath)
 
     def get_action(self) -> dict[str, float]:
         """The returned action does not have a batch dimension."""
@@ -149,7 +160,7 @@ class KochTeleop(Teleoperator):
 
         return action
 
-    def send_feedback(self, feedback: np.ndarray) -> None:
+    def send_feedback(self, feedback: dict[str, float]) -> None:
         # TODO(rcadene, aliberts): Implement force feedback
         raise NotImplementedError
 

From 65569ba90edf2902c188eaa83c75b9863e7b8a81 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Mon, 31 Mar 2025 18:40:23 +0200
Subject: [PATCH 151/171] Add test_scan_port (TODO)

---
 tests/motors/test_feetech.py | 17 +++++++++++++++++
 1 file changed, 17 insertions(+)

diff --git a/tests/motors/test_feetech.py b/tests/motors/test_feetech.py
index 0154621a..9a606b27 100644
--- a/tests/motors/test_feetech.py
+++ b/tests/motors/test_feetech.py
@@ -92,6 +92,23 @@ def test_abc_implementation(dummy_motors):
     FeetechMotorsBus(port="/dev/dummy-port", motors=dummy_motors)
 
 
+@pytest.mark.skip("TODO")
+def test_scan_port(mock_motors):
+    expected = {
+        9_600: {1: 777},
+        57_600: {2: 777},
+        500_000: {237: 777},
+    }
+    expected_model_nbs = {id_: model for d in expected.values() for id_, model in d.items()}
+    ping_stub = mock_motors.build_broadcast_ping_stub(list(expected_model_nbs))
+    mobel_nb_stub = mock_motors.build_sync_read_stub("Model_Number", expected_model_nbs)
+    found = FeetechMotorsBus.scan_port(mock_motors.port)
+
+    assert found == expected
+    assert mock_motors.stubs[ping_stub].called
+    assert mock_motors.stubs[mobel_nb_stub].called
+
+
 @pytest.mark.parametrize("id_", [1, 2, 3])
 def test_ping(id_, mock_motors, dummy_motors):
     expected_model_nb = MODEL_NUMBER[dummy_motors[f"dummy_{id_}"].model]

From 1ebd81552c5cda6710075b0c10db410ea485838e Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Wed, 2 Apr 2025 22:27:49 +0200
Subject: [PATCH 152/171] Fix calibration

---
 lerobot/common/motors/dynamixel/dynamixel.py |  27 ++-
 lerobot/common/motors/feetech/feetech.py     |  17 +-
 lerobot/common/motors/motors_bus.py          | 186 ++++++++++++-------
 lerobot/common/utils/utils.py                |   7 +-
 4 files changed, 154 insertions(+), 83 deletions(-)

diff --git a/lerobot/common/motors/dynamixel/dynamixel.py b/lerobot/common/motors/dynamixel/dynamixel.py
index bae0f977..2abce818 100644
--- a/lerobot/common/motors/dynamixel/dynamixel.py
+++ b/lerobot/common/motors/dynamixel/dynamixel.py
@@ -24,7 +24,7 @@ from enum import Enum
 
 from lerobot.common.utils.encoding_utils import decode_twos_complement, encode_twos_complement
 
-from ..motors_bus import Motor, MotorsBus, NameOrID, Value
+from ..motors_bus import Motor, MotorCalibration, MotorsBus, NameOrID, Value
 from .tables import (
     AVAILABLE_BAUDRATES,
     MODEL_BAUDRATE_TABLE,
@@ -102,8 +102,9 @@ class DynamixelMotorsBus(MotorsBus):
         self,
         port: str,
         motors: dict[str, Motor],
+        calibration: dict[str, MotorCalibration] | None = None,
     ):
-        super().__init__(port, motors)
+        super().__init__(port, motors, calibration)
         import dynamixel_sdk as dxl
 
         self.port_handler = dxl.PortHandler(self.port)
@@ -113,12 +114,26 @@ class DynamixelMotorsBus(MotorsBus):
         self._comm_success = dxl.COMM_SUCCESS
         self._no_error = 0x00
 
-    def _configure_motors(self) -> None:
+    def configure_motors(self) -> None:
         # By default, Dynamixel motors have a 500µs delay response time (corresponding to a value of 250 on
         # the 'Return_Delay_Time' address). We ensure this is reduced to the minimum of 2µs (value of 0).
         for id_ in self.ids:
             self.write("Return_Delay_Time", id_, 0)
 
+    def _disable_torque(self, motors: list[NameOrID]) -> None:
+        for motor in motors:
+            self.write("Torque_Enable", motor, TorqueMode.DISABLED.value)
+
+    def _enable_torque(self, motors: list[NameOrID]) -> None:
+        for motor in motors:
+            self.write("Torque_Enable", motor, TorqueMode.ENABLED.value)
+
+    def _encode_value(self, value: int, data_name: str | None = None, n_bytes: int | None = None) -> int:
+        return encode_twos_complement(value, n_bytes)
+
+    def _decode_value(self, value: int, data_name: str | None = None, n_bytes: int | None = None) -> int:
+        return decode_twos_complement(value, n_bytes)
+
     def _get_half_turn_homings(self, positions: dict[NameOrID, Value]) -> dict[NameOrID, Value]:
         """
         On Dynamixel Motors:
@@ -132,12 +147,6 @@ class DynamixelMotorsBus(MotorsBus):
 
         return half_turn_homings
 
-    def _encode_value(self, value: int, data_name: str | None = None, n_bytes: int | None = None) -> int:
-        return encode_twos_complement(value, n_bytes)
-
-    def _decode_value(self, value: int, data_name: str | None = None, n_bytes: int | None = None) -> int:
-        return decode_twos_complement(value, n_bytes)
-
     @staticmethod
     def _split_int_to_bytes(value: int, n_bytes: int) -> list[int]:
         # Validate input
diff --git a/lerobot/common/motors/feetech/feetech.py b/lerobot/common/motors/feetech/feetech.py
index dc5de28d..4f49f870 100644
--- a/lerobot/common/motors/feetech/feetech.py
+++ b/lerobot/common/motors/feetech/feetech.py
@@ -19,7 +19,7 @@ from pprint import pformat
 
 from lerobot.common.utils.encoding_utils import decode_sign_magnitude, encode_sign_magnitude
 
-from ..motors_bus import Motor, MotorsBus, NameOrID, Value
+from ..motors_bus import Motor, MotorCalibration, MotorsBus, NameOrID, Value
 from .tables import (
     AVAILABLE_BAUDRATES,
     ENCODINGS,
@@ -82,8 +82,9 @@ class FeetechMotorsBus(MotorsBus):
         self,
         port: str,
         motors: dict[str, Motor],
+        calibration: dict[str, MotorCalibration] | None = None,
     ):
-        super().__init__(port, motors)
+        super().__init__(port, motors, calibration)
         import scservo_sdk as scs
 
         self.port_handler = scs.PortHandler(self.port)
@@ -93,7 +94,7 @@ class FeetechMotorsBus(MotorsBus):
         self._comm_success = scs.COMM_SUCCESS
         self._no_error = 0x00
 
-    def _configure_motors(self) -> None:
+    def configure_motors(self) -> None:
         # By default, Feetech motors have a 500µs delay response time (corresponding to a value of 250 on the
         # 'Return_Delay' address). We ensure this is reduced to the minimum of 2µs (value of 0).
         for id_ in self.ids:
@@ -112,6 +113,16 @@ class FeetechMotorsBus(MotorsBus):
 
         return half_turn_homings
 
+    def _disable_torque(self, motors: list[NameOrID]) -> None:
+        for motor in motors:
+            self.write("Torque_Enable", motor, TorqueMode.DISABLED.value)
+            self.write("Lock", motor, 0)
+
+    def _enable_torque(self, motors: list[NameOrID]) -> None:
+        for motor in motors:
+            self.write("Torque_Enable", motor, TorqueMode.ENABLED.value)
+            self.write("Lock", motor, 1)
+
     def _encode_value(self, value: int, data_name: str | None = None, n_bytes: int | None = None) -> int:
         sign_bit = self.encodings.get(data_name)
         return encode_sign_magnitude(value, sign_bit) if sign_bit is not None else value
diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py
index 29903be8..dc97d686 100644
--- a/lerobot/common/motors/motors_bus.py
+++ b/lerobot/common/motors/motors_bus.py
@@ -32,7 +32,7 @@ from deepdiff import DeepDiff
 from tqdm import tqdm
 
 from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError
-from lerobot.common.utils.utils import _enter_pressed
+from lerobot.common.utils.utils import enter_pressed, move_cursor_up
 
 NameOrID: TypeAlias = str | int
 Value: TypeAlias = int | float
@@ -265,9 +265,11 @@ class MotorsBus(abc.ABC):
         self,
         port: str,
         motors: dict[str, Motor],
+        calibration: dict[str, MotorCalibration] | None = None,
     ):
         self.port = port
         self.motors = motors
+        self.calibration = calibration if calibration else {}
 
         self.port_handler: PortHandler
         self.packet_handler: PacketHandler
@@ -276,8 +278,6 @@ class MotorsBus(abc.ABC):
         self._comm_success: int
         self._no_error: int
 
-        self.calibration: dict[str, MotorCalibration] = {}
-
         self._id_to_model_dict = {m.id: m.model for m in self.motors.values()}
         self._id_to_name_dict = {m.id: name for name, m in self.motors.items()}
         self._model_nb_to_model_dict = {v: k for k, v in self.model_number_table.items()}
@@ -396,7 +396,6 @@ class MotorsBus(abc.ABC):
             ) from e
 
         self.set_timeout()
-        self.calibration = self.get_calibration()
         logger.debug(f"{self.__class__.__name__} connected.")
 
     @classmethod
@@ -420,7 +419,37 @@ class MotorsBus(abc.ABC):
         return baudrate_ids
 
     @abc.abstractmethod
-    def _configure_motors(self) -> None:
+    def configure_motors(self) -> None:
+        pass
+
+    def disable_torque(self, motors: NameOrID | list[NameOrID] | None = None) -> None:
+        pass
+        if motors is None:
+            motors = self.names
+        elif isinstance(motors, (str, int)):
+            motors = [motors]
+        elif not isinstance(motors, list):
+            raise TypeError(motors)
+
+        self._disable_torque(motors)
+
+    def enable_torque(self, motors: NameOrID | list[NameOrID] | None = None) -> None:
+        pass
+        if motors is None:
+            motors = self.names
+        elif isinstance(motors, (str, int)):
+            motors = [motors]
+        elif not isinstance(motors, list):
+            raise TypeError(motors)
+
+        self._enable_torque(motors)
+
+    @abc.abstractmethod
+    def _enable_torque(self, motors: list[NameOrID]) -> None:
+        pass
+
+    @abc.abstractmethod
+    def _disable_torque(self, motors: list[NameOrID]) -> None:
         pass
 
     def set_timeout(self, timeout_ms: int | None = None):
@@ -439,39 +468,7 @@ class MotorsBus(abc.ABC):
             if self.port_handler.getBaudRate() != baudrate:
                 raise OSError("Failed to write bus baud rate.")
 
-    def set_half_turn_homings(self, motors: NameOrID | list[NameOrID] | None = None) -> dict[NameOrID, Value]:
-        """This assumes motors present positions are roughly in the middle of their desired range"""
-        if motors is None:
-            motors = self.names
-        elif isinstance(motors, (str, int)):
-            motors = [motors]
-        else:
-            raise TypeError(motors)
-
-        # Step 1: Set homing and min max to 0
-        self.reset_homing_ranges(motors)
-
-        # Step 2: Read Present_Position which will be Actual_Position since
-        # Present_Position = Actual_Position ± Homing_Offset (1)
-        # and Homing_Offset = 0 from step 1
-        actual_positions = self.sync_read("Present_Position", motors, normalize=False)
-
-        # Step 3: We want to set the Homing_Offset such that the current Present_Position to be half range of
-        # 1 revolution.
-        # For instance, if 1 revolution corresponds to 4095 (4096 steps), this means we want the current
-        # Present_Position to be 2047. In that example:
-        # Present_Position = 2047 (2)
-        # Actual_Position = X (read in step 2)
-        # from (1) and (2):
-        # => Homing_Offset = ±(X - 2048)
-        homing_offsets = self._get_half_turn_homings(actual_positions)
-
-        for motor, offset in homing_offsets.items():
-            self.write("Homing_Offset", motor, offset, normalize=False)
-
-        return homing_offsets
-
-    def reset_homing_ranges(self, motors: NameOrID | list[NameOrID] | None = None) -> None:
+    def reset_calibration(self, motors: NameOrID | list[NameOrID] | None = None) -> None:
         if motors is None:
             motors = self.names
         elif isinstance(motors, (str, int)):
@@ -486,39 +483,11 @@ class MotorsBus(abc.ABC):
             self.write("Min_Position_Limit", motor, 0, normalize=False)
             self.write("Max_Position_Limit", motor, max_res, normalize=False)
 
-    def register_ranges_of_motion(
-        self, motors: NameOrID | list[NameOrID] | None = None
-    ) -> dict[NameOrID, dict[str, Value]]:
-        """
-        This assumes that the homing offsets have been set such that all possible values in the range of
-        motion are positive and that the zero is not crossed. To that end, `set_half_turn_homings` should
-        typically be called prior to this.
-        """
-        if motors is None:
-            motors = self.names
-        elif isinstance(motors, (str, int)):
-            motors = [motors]
-        elif not isinstance(motors, list):
-            raise TypeError(motors)
+    @property
+    def is_calibrated(self) -> bool:
+        return self.calibration == self.read_calibration()
 
-        start_positions = self.sync_read("Present_Position", motors, normalize=False)
-        mins = start_positions.copy()
-        maxes = start_positions.copy()
-        while True:
-            positions = self.sync_read("Present_Position", motors, normalize=False)
-            mins = {motor: min(positions[motor], min_) for motor, min_ in mins.items()}
-            maxes = {motor: max(positions[motor], max_) for motor, max_ in maxes.items()}
-
-            if _enter_pressed():
-                break
-
-        for motor in motors:
-            self.write("Min_Position_Limit", motor, mins[motor], normalize=False)
-            self.write("Max_Position_Limit", motor, maxes[motor], normalize=False)
-
-        return {motor: {"min": mins[motor], "max": maxes[motor]} for motor in motors}
-
-    def get_calibration(self) -> dict[str, MotorCalibration]:
+    def read_calibration(self) -> dict[str, MotorCalibration]:
         offsets = self.sync_read("Homing_Offset", normalize=False)
         mins = self.sync_read("Min_Position_Limit", normalize=False)
         maxes = self.sync_read("Max_Position_Limit", normalize=False)
@@ -540,6 +509,83 @@ class MotorsBus(abc.ABC):
 
         return calibration
 
+    def write_calibration(self, calibration_dict: dict[str, MotorCalibration]) -> None:
+        for motor, calibration in calibration_dict.items():
+            self.write("Homing_Offset", motor, calibration.homing_offset)
+            self.write("Min_Position_Limit", motor, calibration.range_min)
+            self.write("Max_Position_Limit", motor, calibration.range_max)
+
+        self.calibration = calibration_dict
+
+    def set_half_turn_homings(self, motors: NameOrID | list[NameOrID] | None = None) -> dict[NameOrID, Value]:
+        """This assumes motors present positions are roughly in the middle of their desired range"""
+        if motors is None:
+            motors = self.names
+        elif isinstance(motors, (str, int)):
+            motors = [motors]
+        else:
+            raise TypeError(motors)
+
+        # Step 1: Set homing and min max to 0
+        self.reset_calibration(motors)
+
+        # Step 2: Read Present_Position which will be Actual_Position since
+        # Present_Position = Actual_Position ± Homing_Offset (1)
+        # and Homing_Offset = 0 from step 1
+        actual_positions = self.sync_read("Present_Position", motors, normalize=False)
+
+        # Step 3: We want to set the Homing_Offset such that the current Present_Position to be half range of
+        # 1 revolution.
+        # For instance, if 1 revolution corresponds to 4095 (4096 steps), this means we want the current
+        # Present_Position to be 2047. In that example:
+        # Present_Position = 2047 (2)
+        # Actual_Position = X (read in step 2)
+        # from (1) and (2):
+        # => Homing_Offset = ±(X - 2048)
+        homing_offsets = self._get_half_turn_homings(actual_positions)
+        for motor, offset in homing_offsets.items():
+            self.write("Homing_Offset", motor, offset)
+
+        return homing_offsets
+
+    def record_ranges_of_motion(
+        self, motors: NameOrID | list[NameOrID] | None = None, display_values: bool = True
+    ) -> tuple[dict[NameOrID, Value], dict[NameOrID, Value]]:
+        """
+        This assumes that the homing offsets have been set such that all possible values in the range of
+        motion are positive and that the zero is not crossed. To that end, `set_half_turn_homings` should
+        typically be called prior to this.
+        """
+        if motors is None:
+            motors = self.names
+        elif isinstance(motors, (str, int)):
+            motors = [motors]
+        elif not isinstance(motors, list):
+            raise TypeError(motors)
+
+        start_positions = self.sync_read("Present_Position", motors, normalize=False)
+        mins = start_positions.copy()
+        maxes = start_positions.copy()
+        while True:
+            positions = self.sync_read("Present_Position", motors, normalize=False)
+            mins = {motor: min(positions[motor], min_) for motor, min_ in mins.items()}
+            maxes = {motor: max(positions[motor], max_) for motor, max_ in maxes.items()}
+
+            if display_values:
+                print("\n-------------------------------------------")
+                print(f"{'NAME':<15} | {'MIN':>6} | {'POS':>6} | {'MAX':>6}")
+                for name in motors:
+                    print(f"{name:<15} | {mins[name]:>6} | {positions[name]:>6} | {maxes[name]:>6}")
+
+            if enter_pressed():
+                break
+
+            if display_values:
+                # Move cursor up to overwrite the previous output
+                move_cursor_up(len(motors) + 3)
+
+        return mins, maxes
+
     @abc.abstractmethod
     def _get_half_turn_homings(self, positions: dict[NameOrID, Value]) -> dict[NameOrID, Value]:
         pass
diff --git a/lerobot/common/utils/utils.py b/lerobot/common/utils/utils.py
index 9440d1d2..756ad9f0 100644
--- a/lerobot/common/utils/utils.py
+++ b/lerobot/common/utils/utils.py
@@ -232,5 +232,10 @@ def is_valid_numpy_dtype_string(dtype_str: str) -> bool:
         return False
 
 
-def _enter_pressed() -> bool:
+def enter_pressed() -> bool:
     return select.select([sys.stdin], [], [], 0)[0] and sys.stdin.readline().strip() == ""
+
+
+def move_cursor_up(lines):
+    """Move the cursor up by a specified number of lines."""
+    print(f"\033[{lines}A", end="")

From e55d2ffe5063a61eaae6744b20e7a1134928f234 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Wed, 2 Apr 2025 22:31:45 +0200
Subject: [PATCH 153/171] Hack feetech firmware bug

---
 lerobot/common/motors/dynamixel/dynamixel.py | 19 ++++++++++-
 lerobot/common/motors/feetech/feetech.py     | 35 +++++++++++++++++++-
 lerobot/common/motors/feetech/tables.py      |  2 ++
 lerobot/common/motors/motors_bus.py          | 24 +++++---------
 4 files changed, 62 insertions(+), 18 deletions(-)

diff --git a/lerobot/common/motors/dynamixel/dynamixel.py b/lerobot/common/motors/dynamixel/dynamixel.py
index 2abce818..719e80c7 100644
--- a/lerobot/common/motors/dynamixel/dynamixel.py
+++ b/lerobot/common/motors/dynamixel/dynamixel.py
@@ -24,7 +24,7 @@ from enum import Enum
 
 from lerobot.common.utils.encoding_utils import decode_twos_complement, encode_twos_complement
 
-from ..motors_bus import Motor, MotorCalibration, MotorsBus, NameOrID, Value
+from ..motors_bus import Motor, MotorCalibration, MotorsBus, NameOrID, Value, get_address
 from .tables import (
     AVAILABLE_BAUDRATES,
     MODEL_BAUDRATE_TABLE,
@@ -192,3 +192,20 @@ class DynamixelMotorsBus(MotorsBus):
             return data_list if data_list else None
 
         return {id_: data[0] for id_, data in data_list.items()}
+
+    def _write(self, data_name: str, motor_id: int, value: int, num_retry: int = 0) -> tuple[int, int]:
+        model = self._id_to_model(motor_id)
+        addr, n_bytes = get_address(self.model_ctrl_table, model, data_name)
+        value = self._encode_value(value, data_name, n_bytes)
+        data = self._split_int_to_bytes(value, n_bytes)
+
+        for n_try in range(1 + num_retry):
+            comm, error = self.packet_handler.writeTxRx(self.port_handler, motor_id, addr, n_bytes, data)
+            if self._is_comm_success(comm):
+                break
+            logger.debug(
+                f"Failed to write '{data_name}' ({addr=} {n_bytes=}) on {motor_id=} with '{value}' ({n_try=})"
+            )
+            logger.debug(self.packet_handler.getRxPacketError(comm))
+
+        return comm, error
diff --git a/lerobot/common/motors/feetech/feetech.py b/lerobot/common/motors/feetech/feetech.py
index 4f49f870..0f73a54b 100644
--- a/lerobot/common/motors/feetech/feetech.py
+++ b/lerobot/common/motors/feetech/feetech.py
@@ -19,7 +19,7 @@ from pprint import pformat
 
 from lerobot.common.utils.encoding_utils import decode_sign_magnitude, encode_sign_magnitude
 
-from ..motors_bus import Motor, MotorCalibration, MotorsBus, NameOrID, Value
+from ..motors_bus import Motor, MotorCalibration, MotorsBus, NameOrID, Value, get_address
 from .tables import (
     AVAILABLE_BAUDRATES,
     ENCODINGS,
@@ -261,3 +261,36 @@ class FeetechMotorsBus(MotorsBus):
             return model_numbers if model_numbers else None
 
         return model_numbers
+
+    def _is_eprom(self, address: int) -> bool:
+        """
+        HACK: because of https://gitee.com/ftservo/SCServoSDK/issues/IBY2S6
+        When writing to EPROM on for Feetech motors with Lock=0, we need to:
+            - 1. write several times
+            - 2. reset serial's buffer
+        """
+        return address < 40
+
+    def _write(self, data_name: str, motor_id: int, value: int, num_retry: int = 0) -> tuple[int, int]:
+        model = self._id_to_model(motor_id)
+        addr, n_bytes = get_address(self.model_ctrl_table, model, data_name)
+        value = self._encode_value(value, data_name, n_bytes)
+        data = self._split_int_to_bytes(value, n_bytes)
+
+        if self._is_eprom(addr):  # HACK
+            num_retry = max(num_retry, 5)
+
+        for n_try in range(1 + num_retry):
+            comm, error = self.packet_handler.writeTxRx(self.port_handler, motor_id, addr, n_bytes, data)
+            if self._is_comm_success(comm):
+                break
+            logger.debug(
+                f"Failed to write '{data_name}' ({addr=} {n_bytes=}) on {motor_id=} with '{value}' ({n_try=})"
+            )
+            logger.debug(self.packet_handler.getRxPacketError(comm))
+
+        if self._is_eprom(addr):  # HACK
+            self.port_handler.ser.reset_output_buffer()
+            self.port_handler.ser.reset_input_buffer()
+
+        return comm, error
diff --git a/lerobot/common/motors/feetech/tables.py b/lerobot/common/motors/feetech/tables.py
index a1220ac8..5df1ea59 100644
--- a/lerobot/common/motors/feetech/tables.py
+++ b/lerobot/common/motors/feetech/tables.py
@@ -2,6 +2,7 @@
 # https://docs.google.com/spreadsheets/d/1GVs7W1VS1PqdhA1nW-abeyAHhTUxKUdR/edit?usp=sharing&ouid=116566590112741600240&rtpof=true&sd=true
 # data_name: (address, size_byte)
 SCS_SERIES_CONTROL_TABLE = {
+    # EPROM
     "Firmware_Version": (0, 2),
     "Model_Number": (3, 2),
     "ID": (5, 1),
@@ -33,6 +34,7 @@ SCS_SERIES_CONTROL_TABLE = {
     "Speed_closed_loop_P_proportional_coefficient": (37, 1),
     "Over_Current_Protection_Time": (38, 1),
     "Velocity_closed_loop_I_integral_coefficient": (39, 1),
+    # SRAM
     "Torque_Enable": (40, 1),
     "Acceleration": (41, 1),
     "Goal_Position": (42, 2),
diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py
index dc97d686..cbe119d5 100644
--- a/lerobot/common/motors/motors_bus.py
+++ b/lerobot/common/motors/motors_bus.py
@@ -888,28 +888,20 @@ class MotorsBus(abc.ABC):
                 f"\n{self.packet_handler.getRxPacketError(error)}"
             )
 
+    @abc.abstractmethod
     def _write(self, data_name: str, motor_id: int, value: int, num_retry: int = 0) -> tuple[int, int]:
-        model = self._id_to_model(motor_id)
-        addr, n_bytes = get_address(self.model_ctrl_table, model, data_name)
-        value = self._encode_value(value, data_name, n_bytes)
-        data = self._split_int_to_bytes(value, n_bytes)
+        pass
 
-        for n_try in range(1 + num_retry):
-            comm, error = self.packet_handler.writeTxRx(self.port_handler, motor_id, addr, n_bytes, data)
-            if self._is_comm_success(comm):
-                break
-            logger.debug(
-                f"Failed to write '{data_name}' ({addr=} {n_bytes=}) on {motor_id=} with '{value}' ({n_try=})"
-            )
-            logger.debug(self.packet_handler.getRxPacketError(comm))
-
-        return comm, error
-
-    def disconnect(self) -> None:
+    def disconnect(self, disable_torque: bool = True) -> None:
         if not self.is_connected:
             raise DeviceNotConnectedError(
                 f"{self.__class__.__name__}('{self.port}') is not connected. Try running `{self.__class__.__name__}.connect()` first."
             )
 
+        if disable_torque:
+            self.port_handler.clearPort()
+            self.port_handler.is_using = False
+            self.disable_torque()
+
         self.port_handler.closePort()
         logger.debug(f"{self.__class__.__name__} disconnected.")

From 854b78975a7230fb6e34545ea584356a7f17b4a6 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Wed, 2 Apr 2025 22:31:53 +0200
Subject: [PATCH 154/171] Update tests

---
 tests/motors/test_dynamixel.py | 28 ++++++++++++++--------------
 tests/motors/test_feetech.py   | 28 ++++++++++++++--------------
 2 files changed, 28 insertions(+), 28 deletions(-)

diff --git a/tests/motors/test_dynamixel.py b/tests/motors/test_dynamixel.py
index 4f3165e7..b2483f5b 100644
--- a/tests/motors/test_dynamixel.py
+++ b/tests/motors/test_dynamixel.py
@@ -138,7 +138,7 @@ def test_sync_read_none(mock_motors, dummy_motors):
     )
     motors_bus.connect(assert_motors_exist=False)
 
-    read_positions = motors_bus.sync_read("Present_Position")
+    read_positions = motors_bus.sync_read("Present_Position", normalize=False)
 
     assert mock_motors.stubs[stub_name].called
     assert read_positions == expected_positions
@@ -161,7 +161,7 @@ def test_sync_read_by_id(id_, position, mock_motors, dummy_motors):
     )
     motors_bus.connect(assert_motors_exist=False)
 
-    read_position = motors_bus.sync_read("Present_Position", id_)
+    read_position = motors_bus.sync_read("Present_Position", id_, normalize=False)
 
     assert mock_motors.stubs[stub_name].called
     assert read_position == expected_position
@@ -186,7 +186,7 @@ def test_sync_read_by_ids(ids, positions, mock_motors, dummy_motors):
     )
     motors_bus.connect(assert_motors_exist=False)
 
-    read_positions = motors_bus.sync_read("Present_Position", ids)
+    read_positions = motors_bus.sync_read("Present_Position", ids, normalize=False)
 
     assert mock_motors.stubs[stub_name].called
     assert read_positions == expected_positions
@@ -209,7 +209,7 @@ def test_sync_read_by_name(id_, position, mock_motors, dummy_motors):
     )
     motors_bus.connect(assert_motors_exist=False)
 
-    read_position = motors_bus.sync_read("Present_Position", f"dummy_{id_}")
+    read_position = motors_bus.sync_read("Present_Position", f"dummy_{id_}", normalize=False)
 
     assert mock_motors.stubs[stub_name].called
     assert read_position == expected_position
@@ -236,7 +236,7 @@ def test_sync_read_by_names(ids, positions, mock_motors, dummy_motors):
     )
     motors_bus.connect(assert_motors_exist=False)
 
-    read_positions = motors_bus.sync_read("Present_Position", names)
+    read_positions = motors_bus.sync_read("Present_Position", names, normalize=False)
 
     assert mock_motors.stubs[stub_name].called
     assert read_positions == expected_positions
@@ -263,11 +263,11 @@ def test_sync_read_num_retry(num_retry, num_invalid_try, pos, mock_motors, dummy
     motors_bus.connect(assert_motors_exist=False)
 
     if num_retry >= num_invalid_try:
-        pos_dict = motors_bus.sync_read("Present_Position", 1, num_retry=num_retry)
+        pos_dict = motors_bus.sync_read("Present_Position", 1, normalize=False, num_retry=num_retry)
         assert pos_dict == {1: pos}
     else:
         with pytest.raises(ConnectionError):
-            _ = motors_bus.sync_read("Present_Position", 1, num_retry=num_retry)
+            _ = motors_bus.sync_read("Present_Position", 1, normalize=False, num_retry=num_retry)
 
     expected_calls = min(1 + num_retry, 1 + num_invalid_try)
     assert mock_motors.stubs[stub_name].calls == expected_calls
@@ -291,7 +291,7 @@ def test_sync_write_single_value(data_name, value, mock_motors, dummy_motors):
     )
     motors_bus.connect(assert_motors_exist=False)
 
-    motors_bus.sync_write(data_name, value)
+    motors_bus.sync_write(data_name, value, normalize=False)
 
     assert mock_motors.stubs[stub_name].wait_called()
 
@@ -313,7 +313,7 @@ def test_sync_write_by_id(id_, position, mock_motors, dummy_motors):
     )
     motors_bus.connect(assert_motors_exist=False)
 
-    motors_bus.sync_write("Goal_Position", value)
+    motors_bus.sync_write("Goal_Position", value, normalize=False)
 
     assert mock_motors.stubs[stub_name].wait_called()
 
@@ -337,7 +337,7 @@ def test_sync_write_by_ids(ids, positions, mock_motors, dummy_motors):
     )
     motors_bus.connect(assert_motors_exist=False)
 
-    motors_bus.sync_write("Goal_Position", values)
+    motors_bus.sync_write("Goal_Position", values, normalize=False)
 
     assert mock_motors.stubs[stub_name].wait_called()
 
@@ -360,7 +360,7 @@ def test_sync_write_by_name(id_, position, mock_motors, dummy_motors):
     motors_bus.connect(assert_motors_exist=False)
 
     write_value = {f"dummy_{id_}": position}
-    motors_bus.sync_write("Goal_Position", write_value)
+    motors_bus.sync_write("Goal_Position", write_value, normalize=False)
 
     assert mock_motors.stubs[stub_name].wait_called()
 
@@ -385,7 +385,7 @@ def test_sync_write_by_names(ids, positions, mock_motors, dummy_motors):
     motors_bus.connect(assert_motors_exist=False)
 
     write_values = {f"dummy_{id_}": pos for id_, pos in ids_values.items()}
-    motors_bus.sync_write("Goal_Position", write_values)
+    motors_bus.sync_write("Goal_Position", write_values, normalize=False)
 
     assert mock_motors.stubs[stub_name].wait_called()
 
@@ -407,7 +407,7 @@ def test_write_by_id(data_name, dxl_id, value, mock_motors, dummy_motors):
     )
     motors_bus.connect(assert_motors_exist=False)
 
-    motors_bus.write(data_name, dxl_id, value)
+    motors_bus.write(data_name, dxl_id, value, normalize=False)
 
     assert mock_motors.stubs[stub_name].called
 
@@ -429,6 +429,6 @@ def test_write_by_name(data_name, dxl_id, value, mock_motors, dummy_motors):
     )
     motors_bus.connect(assert_motors_exist=False)
 
-    motors_bus.write(data_name, f"dummy_{dxl_id}", value)
+    motors_bus.write(data_name, f"dummy_{dxl_id}", value, normalize=False)
 
     assert mock_motors.stubs[stub_name].called
diff --git a/tests/motors/test_feetech.py b/tests/motors/test_feetech.py
index 9a606b27..023ce332 100644
--- a/tests/motors/test_feetech.py
+++ b/tests/motors/test_feetech.py
@@ -159,7 +159,7 @@ def test_sync_read_none(mock_motors, dummy_motors):
     )
     motors_bus.connect(assert_motors_exist=False)
 
-    read_positions = motors_bus.sync_read("Present_Position")
+    read_positions = motors_bus.sync_read("Present_Position", normalize=False)
 
     assert mock_motors.stubs[stub_name].called
     assert read_positions == expected_positions
@@ -182,7 +182,7 @@ def test_sync_read_by_id(id_, position, mock_motors, dummy_motors):
     )
     motors_bus.connect(assert_motors_exist=False)
 
-    read_position = motors_bus.sync_read("Present_Position", id_)
+    read_position = motors_bus.sync_read("Present_Position", id_, normalize=False)
 
     assert mock_motors.stubs[stub_name].called
     assert read_position == expected_position
@@ -207,7 +207,7 @@ def test_sync_read_by_ids(ids, positions, mock_motors, dummy_motors):
     )
     motors_bus.connect(assert_motors_exist=False)
 
-    read_positions = motors_bus.sync_read("Present_Position", ids)
+    read_positions = motors_bus.sync_read("Present_Position", ids, normalize=False)
 
     assert mock_motors.stubs[stub_name].called
     assert read_positions == expected_positions
@@ -230,7 +230,7 @@ def test_sync_read_by_name(id_, position, mock_motors, dummy_motors):
     )
     motors_bus.connect(assert_motors_exist=False)
 
-    read_position = motors_bus.sync_read("Present_Position", f"dummy_{id_}")
+    read_position = motors_bus.sync_read("Present_Position", f"dummy_{id_}", normalize=False)
 
     assert mock_motors.stubs[stub_name].called
     assert read_position == expected_position
@@ -257,7 +257,7 @@ def test_sync_read_by_names(ids, positions, mock_motors, dummy_motors):
     )
     motors_bus.connect(assert_motors_exist=False)
 
-    read_positions = motors_bus.sync_read("Present_Position", names)
+    read_positions = motors_bus.sync_read("Present_Position", names, normalize=False)
 
     assert mock_motors.stubs[stub_name].called
     assert read_positions == expected_positions
@@ -284,11 +284,11 @@ def test_sync_read_num_retry(num_retry, num_invalid_try, pos, mock_motors, dummy
     motors_bus.connect(assert_motors_exist=False)
 
     if num_retry >= num_invalid_try:
-        pos_dict = motors_bus.sync_read("Present_Position", 1, num_retry=num_retry)
+        pos_dict = motors_bus.sync_read("Present_Position", 1, normalize=False, num_retry=num_retry)
         assert pos_dict == {1: pos}
     else:
         with pytest.raises(ConnectionError):
-            _ = motors_bus.sync_read("Present_Position", 1, num_retry=num_retry)
+            _ = motors_bus.sync_read("Present_Position", 1, normalize=False, num_retry=num_retry)
 
     expected_calls = min(1 + num_retry, 1 + num_invalid_try)
     assert mock_motors.stubs[stub_name].calls == expected_calls
@@ -312,7 +312,7 @@ def test_sync_write_single_value(data_name, value, mock_motors, dummy_motors):
     )
     motors_bus.connect(assert_motors_exist=False)
 
-    motors_bus.sync_write(data_name, value)
+    motors_bus.sync_write(data_name, value, normalize=False)
 
     assert mock_motors.stubs[stub_name].wait_called()
 
@@ -334,7 +334,7 @@ def test_sync_write_by_id(id_, position, mock_motors, dummy_motors):
     )
     motors_bus.connect(assert_motors_exist=False)
 
-    motors_bus.sync_write("Goal_Position", value)
+    motors_bus.sync_write("Goal_Position", value, normalize=False)
 
     assert mock_motors.stubs[stub_name].wait_called()
 
@@ -358,7 +358,7 @@ def test_sync_write_by_ids(ids, positions, mock_motors, dummy_motors):
     )
     motors_bus.connect(assert_motors_exist=False)
 
-    motors_bus.sync_write("Goal_Position", values)
+    motors_bus.sync_write("Goal_Position", values, normalize=False)
 
     assert mock_motors.stubs[stub_name].wait_called()
 
@@ -381,7 +381,7 @@ def test_sync_write_by_name(id_, position, mock_motors, dummy_motors):
     motors_bus.connect(assert_motors_exist=False)
 
     write_value = {f"dummy_{id_}": position}
-    motors_bus.sync_write("Goal_Position", write_value)
+    motors_bus.sync_write("Goal_Position", write_value, normalize=False)
 
     assert mock_motors.stubs[stub_name].wait_called()
 
@@ -406,7 +406,7 @@ def test_sync_write_by_names(ids, positions, mock_motors, dummy_motors):
     motors_bus.connect(assert_motors_exist=False)
 
     write_values = {f"dummy_{id_}": pos for id_, pos in ids_values.items()}
-    motors_bus.sync_write("Goal_Position", write_values)
+    motors_bus.sync_write("Goal_Position", write_values, normalize=False)
 
     assert mock_motors.stubs[stub_name].wait_called()
 
@@ -428,7 +428,7 @@ def test_write_by_id(data_name, dxl_id, value, mock_motors, dummy_motors):
     )
     motors_bus.connect(assert_motors_exist=False)
 
-    motors_bus.write(data_name, dxl_id, value)
+    motors_bus.write(data_name, dxl_id, value, normalize=False)
 
     assert mock_motors.stubs[stub_name].called
 
@@ -450,6 +450,6 @@ def test_write_by_name(data_name, dxl_id, value, mock_motors, dummy_motors):
     )
     motors_bus.connect(assert_motors_exist=False)
 
-    motors_bus.write(data_name, f"dummy_{dxl_id}", value)
+    motors_bus.write(data_name, f"dummy_{dxl_id}", value, normalize=False)
 
     assert mock_motors.stubs[stub_name].called

From eeb8490016263eecf1ba1f9bfc38d2652f541463 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Wed, 2 Apr 2025 22:33:48 +0200
Subject: [PATCH 155/171] Update Koch & SO-100

---
 .../common/robots/koch/configuration_koch.py  |   2 +
 lerobot/common/robots/koch/robot_koch.py      | 146 +++++++++---------
 lerobot/common/robots/robot.py                |  11 +-
 .../robots/so100/configuration_so100.py       |   2 +
 lerobot/common/robots/so100/robot_so100.py    | 115 +++++++-------
 .../common/teleoperators/koch/teleop_koch.py  | 112 +++++++-------
 .../teleoperators/so100/teleop_so100.py       |  64 ++++----
 lerobot/common/teleoperators/teleoperator.py  |  11 +-
 8 files changed, 226 insertions(+), 237 deletions(-)

diff --git a/lerobot/common/robots/koch/configuration_koch.py b/lerobot/common/robots/koch/configuration_koch.py
index 1f465e94..a72bd05f 100644
--- a/lerobot/common/robots/koch/configuration_koch.py
+++ b/lerobot/common/robots/koch/configuration_koch.py
@@ -11,6 +11,8 @@ class KochRobotConfig(RobotConfig):
     # Port to connect to the robot
     port: str
 
+    disable_torque_on_disconnect: bool = True
+
     # `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/koch/robot_koch.py b/lerobot/common/robots/koch/robot_koch.py
index e05280e6..72724daf 100644
--- a/lerobot/common/robots/koch/robot_koch.py
+++ b/lerobot/common/robots/koch/robot_koch.py
@@ -25,13 +25,14 @@ from lerobot.common.motors import Motor, MotorCalibration, MotorNormMode
 from lerobot.common.motors.dynamixel import (
     DynamixelMotorsBus,
     OperatingMode,
-    TorqueMode,
 )
 
 from ..robot import Robot
 from ..utils import ensure_safe_goal_position
 from .configuration_koch import KochRobotConfig
 
+logger = logging.getLogger(__name__)
+
 
 class KochRobot(Robot):
     """
@@ -46,8 +47,6 @@ class KochRobot(Robot):
     def __init__(self, config: KochRobotConfig):
         super().__init__(config)
         self.config = config
-        self.robot_type = config.type
-
         self.arm = DynamixelMotorsBus(
             port=self.config.port,
             motors={
@@ -58,11 +57,10 @@ class KochRobot(Robot):
                 "wrist_roll": Motor(5, "xl330-m288", MotorNormMode.RANGE_M100_100),
                 "gripper": Motor(6, "xl330-m288", MotorNormMode.RANGE_0_100),
             },
+            calibration=self.calibration,
         )
         self.cameras = make_cameras_from_configs(config.cameras)
 
-        self.logs = {}
-
     @property
     def state_feature(self) -> dict:
         return {
@@ -92,33 +90,70 @@ class KochRobot(Robot):
         return self.arm.is_connected
 
     def connect(self) -> None:
+        """
+        We assume that at connection time, arm is in a rest position,
+        and torque can be safely disabled to run calibration.
+        """
         if self.is_connected:
-            raise DeviceAlreadyConnectedError(
-                "ManipulatorRobot is already connected. Do not run `robot.connect()` twice."
-            )
+            raise DeviceAlreadyConnectedError(f"{self} already connected")
 
-        logging.info("Connecting arm.")
         self.arm.connect()
         if not self.is_calibrated:
             self.calibrate()
 
-        self.configure()
-
-        # Connect the cameras
         for cam in self.cameras.values():
             cam.connect()
 
-    def configure(self) -> None:
+        self.configure()
+        logger.info(f"{self} connected.")
+
+    @property
+    def is_calibrated(self) -> bool:
+        return self.arm.is_calibrated
+
+    def calibrate(self) -> None:
+        logger.info(f"\nRunning calibration of {self}")
+        self.arm.disable_torque()
+        for name in self.arm.names:
+            self.arm.write("Operating_Mode", name, OperatingMode.EXTENDED_POSITION.value)
+
+        input("Move robot to the middle of its range of motion and press ENTER....")
+        homing_offsets = self.arm.set_half_turn_homings()
+
+        full_turn_motors = ["shoulder_pan", "wrist_roll"]
+        unknown_range_motors = [name for name in self.arm.names if name not in full_turn_motors]
+        logger.info(
+            f"Move all joints except {full_turn_motors} sequentially through their entire "
+            "ranges of motion.\nRecording positions. Press ENTER to stop..."
+        )
+        range_mins, range_maxes = self.arm.record_ranges_of_motion(unknown_range_motors)
+        for name in full_turn_motors:
+            range_mins[name] = 0
+            range_maxes[name] = 4095
+
+        self.calibration = {}
+        for name, motor in self.arm.motors.items():
+            self.calibration[name] = MotorCalibration(
+                id=motor.id,
+                drive_mode=0,
+                homing_offset=homing_offsets[name],
+                range_min=range_mins[name],
+                range_max=range_maxes[name],
+            )
+
+        self.arm.write_calibration(self.calibration)
+        self._save_calibration()
+        logger.info(f"Calibration saved to {self.calibration_fpath}")
+
+    def configure(self) -> None:
+        self.arm.disable_torque()
+        self.arm.configure_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
         for name in self.arm.names:
-            # Torque must be deactivated to change values in the motors' EEPROM area
-            # We assume that at configuration time, arm is in a rest position,
-            # and torque can be safely disabled to run calibration.
-            self.arm.write("Torque_Enable", name, TorqueMode.DISABLED.value)
             if name != "gripper":
-                # 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
                 self.arm.write("Operating_Mode", name, OperatingMode.EXTENDED_POSITION.value)
 
         # Use 'position control current based' for gripper to be limited by the limit of the current.
@@ -133,63 +168,26 @@ class KochRobot(Robot):
         self.arm.write("Position_P_Gain", "elbow_flex", 1500)
         self.arm.write("Position_I_Gain", "elbow_flex", 0)
         self.arm.write("Position_D_Gain", "elbow_flex", 600)
-
-        for name in self.arm.names:
-            self.arm.write("Torque_Enable", name, TorqueMode.ENABLED.value)
-
-        logging.info("Torque enabled.")
-
-    @property
-    def is_calibrated(self) -> bool:
-        motors_calibration = self.arm.get_calibration()
-        return motors_calibration == self.calibration
-
-    def calibrate(self) -> None:
-        print(f"\nRunning calibration of {self.id} Koch robot")
-        for name in self.arm.names:
-            self.arm.write("Torque_Enable", name, TorqueMode.DISABLED.value)
-            self.arm.write("Operating_Mode", name, OperatingMode.EXTENDED_POSITION.value)
-
-        input("Move robot to the middle of its range of motion and press ENTER....")
-        homing_offsets = self.arm.set_half_turn_homings()
-
-        fixed_range = ["shoulder_pan", "wrist_roll"]
-        auto_range_motors = [name for name in self.arm.names if name not in fixed_range]
-        print(
-            "Move all joints except 'wrist_roll' (id=5) sequentially through their entire ranges of motion."
-        )
-        print("Recording positions. Press ENTER to stop...")
-        ranges = self.arm.register_ranges_of_motion(auto_range_motors)
-        for name in fixed_range:
-            ranges[name] = {"min": 0, "max": 4095}
-
-        self.calibration = {}
-        for name, motor in self.arm.motors.items():
-            self.calibration[name] = MotorCalibration(
-                id=motor.id,
-                drive_mode=0,
-                homing_offset=homing_offsets[name],
-                range_min=ranges[name]["min"],
-                range_max=ranges[name]["max"],
-            )
-
-        self._save_calibration()
-        print("Calibration saved to", self.calibration_fpath)
+        self.arm.enable_torque()
 
     def get_observation(self) -> dict[str, Any]:
+        if not self.is_connected:
+            raise DeviceNotConnectedError(f"{self} is not connected.")
+
         obs_dict = {}
 
         # Read arm position
-        before_read_t = time.perf_counter()
+        start = time.perf_counter()
         obs_dict[OBS_STATE] = self.arm.sync_read("Present_Position")
-        self.logs["read_pos_dt_s"] = time.perf_counter() - before_read_t
+        dt_ms = (time.perf_counter() - start) * 1e3
+        logger.debug(f"{self} read state: {dt_ms:.1f}ms")
 
         # Capture images from cameras
         for cam_key, cam in self.cameras.items():
-            before_camread_t = time.perf_counter()
+            start = 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
+            dt_ms = (time.perf_counter() - start) * 1e3
+            logger.debug(f"{self} read {cam_key}: {dt_ms:.1f}ms")
 
         return obs_dict
 
@@ -206,6 +204,9 @@ class KochRobot(Robot):
         Returns:
             dict[str, float]: The action sent to the motors, potentially clipped.
         """
+        if not self.is_connected:
+            raise DeviceNotConnectedError(f"{self} is not connected.")
+
         goal_pos = action
 
         # Cap goal position when too far away from present position.
@@ -217,19 +218,16 @@ class KochRobot(Robot):
 
         # Send goal position to the arm
         self.arm.sync_write("Goal_Position", goal_pos)
-
         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()
+        self.arm.disconnect(self.config.disable_torque_on_disconnect)
         for cam in self.cameras.values():
             cam.disconnect()
+
+        logger.info(f"{self} disconnected.")
diff --git a/lerobot/common/robots/robot.py b/lerobot/common/robots/robot.py
index 7ae67ba5..a7ec4eda 100644
--- a/lerobot/common/robots/robot.py
+++ b/lerobot/common/robots/robot.py
@@ -31,6 +31,9 @@ class Robot(abc.ABC):
         if self.calibration_fpath.is_file():
             self._load_calibration()
 
+    def __str__(self) -> str:
+        return f"{self.id} {self.__class__.__name__}"
+
     # TODO(aliberts): create a proper Feature class for this that links with datasets
     @abc.abstractproperty
     def state_feature(self) -> dict:
@@ -53,10 +56,6 @@ class Robot(abc.ABC):
         """Connects to the robot."""
         pass
 
-    @abc.abstractmethod
-    def configure(self) -> None:
-        pass
-
     @abc.abstractproperty
     def is_calibrated(self) -> bool:
         pass
@@ -76,6 +75,10 @@ class Robot(abc.ABC):
         with open(fpath, "w") as f, draccus.config_type("json"):
             draccus.dump(self.calibration, f, indent=4)
 
+    @abc.abstractmethod
+    def configure(self) -> None:
+        pass
+
     @abc.abstractmethod
     def get_observation(self) -> dict[str, Any]:
         """Gets observation from the robot."""
diff --git a/lerobot/common/robots/so100/configuration_so100.py b/lerobot/common/robots/so100/configuration_so100.py
index 969f8060..e6cb9c75 100644
--- a/lerobot/common/robots/so100/configuration_so100.py
+++ b/lerobot/common/robots/so100/configuration_so100.py
@@ -11,6 +11,8 @@ class SO100RobotConfig(RobotConfig):
     # Port to connect to the robot
     port: str
 
+    disable_torque_on_disconnect: bool = True
+
     # `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/so100/robot_so100.py b/lerobot/common/robots/so100/robot_so100.py
index 78273723..e7222a9d 100644
--- a/lerobot/common/robots/so100/robot_so100.py
+++ b/lerobot/common/robots/so100/robot_so100.py
@@ -25,13 +25,14 @@ from lerobot.common.motors import Motor, MotorCalibration, MotorNormMode
 from lerobot.common.motors.feetech import (
     FeetechMotorsBus,
     OperatingMode,
-    TorqueMode,
 )
 
 from ..robot import Robot
 from ..utils import ensure_safe_goal_position
 from .configuration_so100 import SO100RobotConfig
 
+logger = logging.getLogger(__name__)
+
 
 class SO100Robot(Robot):
     """
@@ -44,9 +45,6 @@ class SO100Robot(Robot):
     def __init__(self, config: SO100RobotConfig):
         super().__init__(config)
         self.config = config
-        self.robot_type = config.type
-        self.logs = {}
-
         self.arm = FeetechMotorsBus(
             port=self.config.port,
             motors={
@@ -89,65 +87,46 @@ class SO100Robot(Robot):
         return self.arm.is_connected
 
     def connect(self) -> None:
+        """
+        We assume that at connection time, arm is in a rest position,
+        and torque can be safely disabled to run calibration.
+        """
         if self.is_connected:
-            raise DeviceAlreadyConnectedError(
-                "ManipulatorRobot is already connected. Do not run `robot.connect()` twice."
-            )
+            raise DeviceAlreadyConnectedError(f"{self} already connected")
 
-        logging.info("Connecting arm.")
         self.arm.connect()
         if not self.is_calibrated:
             self.calibrate()
 
-        self.configure()
-
         # Connect the cameras
         for cam in self.cameras.values():
             cam.connect()
 
-    def configure(self) -> None:
-        for name in self.arm.names:
-            # 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", name, TorqueMode.DISABLED.value)
-            self.arm.write("Operating_Mode", name, OperatingMode.POSITION.value)
-
-            # Set P_Coefficient to lower value to avoid shakiness (Default is 32)
-            self.arm.write("P_Coefficient", name, 16)
-            # Set I_Coefficient and D_Coefficient to default value 0 and 32
-            self.arm.write("I_Coefficient", name, 0)
-            self.arm.write("D_Coefficient", name, 32)
-            # 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", name, 254)
-            self.arm.write("Acceleration", name, 254)
-
-        for name in self.arm.names:
-            self.arm.write("Torque_Enable", name, TorqueMode.ENABLED.value)
-
-        logging.info("Torque activated.")
+        self.configure()
+        logger.info(f"{self} connected.")
 
     @property
     def is_calibrated(self) -> bool:
-        motors_calibration = self.arm.get_calibration()
-        return motors_calibration == self.calibration
+        return self.arm.is_calibrated
 
     def calibrate(self) -> None:
-        print(f"\nRunning calibration of {self.id} SO-100 robot")
+        logger.info(f"\nRunning calibration of {self}")
+        self.arm.disable_torque()
         for name in self.arm.names:
-            self.arm.write("Torque_Enable", name, TorqueMode.DISABLED.value)
             self.arm.write("Operating_Mode", name, OperatingMode.POSITION.value)
 
         input("Move robot to the middle of its range of motion and press ENTER....")
         homing_offsets = self.arm.set_half_turn_homings()
 
-        print(
-            "Move all joints except 'wrist_roll' (id=5) sequentially through their entire ranges of motion."
+        full_turn_motor = "wrist_roll"
+        unknown_range_motors = [name for name in self.arm.names if name != full_turn_motor]
+        logger.info(
+            f"Move all joints except '{full_turn_motor}' sequentially through their "
+            "entire ranges of motion.\nRecording positions. Press ENTER to stop..."
         )
-        print("Recording positions. Press ENTER to stop...")
-        auto_range_motors = [name for name in self.arm.names if name != "wrist_roll"]
-        ranges = self.arm.register_ranges_of_motion(auto_range_motors)
-        ranges["wrist_roll"] = {"min": 0, "max": 4095}
+        range_mins, range_maxes = self.arm.record_ranges_of_motion(unknown_range_motors)
+        range_mins[full_turn_motor] = 0
+        range_maxes[full_turn_motor] = 4095
 
         self.calibration = {}
         for name, motor in self.arm.motors.items():
@@ -155,33 +134,49 @@ class SO100Robot(Robot):
                 id=motor.id,
                 drive_mode=0,
                 homing_offset=homing_offsets[name],
-                range_min=ranges[name]["min"],
-                range_max=ranges[name]["max"],
+                range_min=range_mins[name],
+                range_max=range_maxes[name],
             )
 
+        self.arm.write_calibration(self.calibration)
         self._save_calibration()
         print("Calibration saved to", self.calibration_fpath)
 
+    def configure(self) -> None:
+        self.arm.disable_torque()
+        self.arm.configure_motors()
+        for name in self.arm.names:
+            self.arm.write("Operating_Mode", name, OperatingMode.POSITION.value)
+            # Set P_Coefficient to lower value to avoid shakiness (Default is 32)
+            self.arm.write("P_Coefficient", name, 16)
+            # Set I_Coefficient and D_Coefficient to default value 0 and 32
+            self.arm.write("I_Coefficient", name, 0)
+            self.arm.write("D_Coefficient", name, 32)
+            # Set Maximum_Acceleration to 254 to speedup acceleration and deceleration of
+            # the motors. Note: this address is not in the official STS3215 Memory Table
+            self.arm.write("Maximum_Acceleration", name, 254)
+            self.arm.write("Acceleration", name, 254)
+
+        self.arm.enable_torque()
+
     def get_observation(self) -> dict[str, Any]:
-        """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()`."
-            )
+            raise DeviceNotConnectedError(f"{self} is not connected.")
 
         obs_dict = {}
 
         # Read arm position
-        before_read_t = time.perf_counter()
+        start = time.perf_counter()
         obs_dict[OBS_STATE] = self.arm.sync_read("Present_Position")
-        self.logs["read_pos_dt_s"] = time.perf_counter() - before_read_t
+        dt_ms = (time.perf_counter() - start) * 1e3
+        logger.debug(f"{self} read state: {dt_ms:.1f}ms")
 
         # Capture images from cameras
         for cam_key, cam in self.cameras.items():
-            before_camread_t = time.perf_counter()
+            start = 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
+            dt_ms = (time.perf_counter() - start) * 1e3
+            logger.debug(f"{self} read {cam_key}: {dt_ms:.1f}ms")
 
         return obs_dict
 
@@ -199,9 +194,7 @@ class SO100Robot(Robot):
             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()`."
-            )
+            raise DeviceNotConnectedError(f"{self} is not connected.")
 
         goal_pos = action
 
@@ -209,23 +202,21 @@ class SO100Robot(Robot):
         # /!\ Slower fps expected due to reading from the follower.
         if self.config.max_relative_target is not None:
             present_pos = self.arm.sync_read("Present_Position")
-            goal_pos = ensure_safe_goal_position(goal_pos, present_pos, self.config.max_relative_target)
+            goal_present_pos = {key: (g_pos, present_pos[key]) for key, g_pos in goal_pos.items()}
+            goal_pos = ensure_safe_goal_position(goal_present_pos, self.config.max_relative_target)
 
         # Send goal position to the arm
         self.arm.sync_write("Goal_Position", goal_pos)
-
         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()
+        self.arm.disconnect(self.config.disable_torque_on_disconnect)
         for cam in self.cameras.values():
             cam.disconnect()
+
+        logger.info(f"{self} disconnected.")
diff --git a/lerobot/common/teleoperators/koch/teleop_koch.py b/lerobot/common/teleoperators/koch/teleop_koch.py
index 1d49ea10..e0cfc89e 100644
--- a/lerobot/common/teleoperators/koch/teleop_koch.py
+++ b/lerobot/common/teleoperators/koch/teleop_koch.py
@@ -23,12 +23,13 @@ from lerobot.common.motors.dynamixel import (
     DriveMode,
     DynamixelMotorsBus,
     OperatingMode,
-    TorqueMode,
 )
 
 from ..teleoperator import Teleoperator
 from .configuration_koch import KochTeleopConfig
 
+logger = logging.getLogger(__name__)
+
 
 class KochTeleop(Teleoperator):
     """
@@ -43,8 +44,6 @@ class KochTeleop(Teleoperator):
     def __init__(self, config: KochTeleopConfig):
         super().__init__(config)
         self.config = config
-        self.robot_type = config.type
-
         self.arm = DynamixelMotorsBus(
             port=self.config.port,
             motors={
@@ -55,10 +54,9 @@ class KochTeleop(Teleoperator):
                 "wrist_roll": Motor(5, "xl330-m077", MotorNormMode.RANGE_M100_100),
                 "gripper": Motor(6, "xl330-m077", MotorNormMode.RANGE_0_100),
             },
+            calibration=self.calibration,
         )
 
-        self.logs = {}
-
     @property
     def action_feature(self) -> dict:
         return {
@@ -77,23 +75,60 @@ class KochTeleop(Teleoperator):
 
     def connect(self) -> None:
         if self.is_connected:
-            raise DeviceAlreadyConnectedError(
-                "ManipulatorRobot is already connected. Do not run `robot.connect()` twice."
-            )
+            raise DeviceAlreadyConnectedError(f"{self} already connected")
 
-        logging.info("Connecting arm.")
         self.arm.connect()
         if not self.is_calibrated:
             self.calibrate()
 
         self.configure()
+        logger.info(f"{self} connected.")
+
+    @property
+    def is_calibrated(self) -> bool:
+        return self.arm.is_calibrated
+
+    def calibrate(self) -> None:
+        logger.info(f"\nRunning calibration of {self}")
+        self.arm.disable_torque()
+        for name in self.arm.names:
+            self.arm.write("Operating_Mode", name, OperatingMode.EXTENDED_POSITION.value)
+
+        self.arm.write("Drive_Mode", "elbow_flex", DriveMode.INVERTED.value)
+        drive_modes = {name: 1 if name == "elbow_flex" else 0 for name in self.arm.names}
+
+        input("Move robot to the middle of its range of motion and press ENTER....")
+        homing_offsets = self.arm.set_half_turn_homings()
+
+        full_turn_motors = ["shoulder_pan", "wrist_roll"]
+        unknown_range_motors = [name for name in self.arm.names if name not in full_turn_motors]
+        logger.info(
+            f"Move all joints except {full_turn_motors} sequentially through their "
+            "entire ranges of motion.\nRecording positions. Press ENTER to stop..."
+        )
+        range_mins, range_maxes = self.arm.record_ranges_of_motion(unknown_range_motors)
+        for name in full_turn_motors:
+            range_mins[name] = 0
+            range_maxes[name] = 4095
+
+        self.calibration = {}
+        for name, motor in self.arm.motors.items():
+            self.calibration[name] = MotorCalibration(
+                id=motor.id,
+                drive_mode=drive_modes[name],
+                homing_offset=homing_offsets[name],
+                range_min=range_mins[name],
+                range_max=range_maxes[name],
+            )
+
+        self.arm.write_calibration(self.calibration)
+        self._save_calibration()
+        logger.info(f"Calibration saved to {self.calibration_fpath}")
 
     def configure(self) -> None:
+        self.arm.disable_torque()
+        self.arm.configure_motors()
         for name in self.arm.names:
-            # Torque must be deactivated to change values in the motors' EEPROM area
-            # We assume that at configuration time, arm is in a rest position,
-            # and torque can be safely disabled to run calibration.
-            self.arm.write("Torque_Enable", name, TorqueMode.DISABLED.value)
             if name != "gripper":
                 # 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
@@ -108,56 +143,14 @@ class KochTeleop(Teleoperator):
         # to make it move, and it will move back to its original target position when we release the force.
         self.arm.write("Operating_Mode", "gripper", OperatingMode.CURRENT_POSITION.value)
         # Set gripper's goal pos in current position mode so that we can use it as a trigger.
-        self.arm.write("Torque_Enable", "gripper", TorqueMode.ENABLED.value)
+        self.arm.enable_torque("gripper")
         self.arm.write("Goal_Position", "gripper", self.config.gripper_open_pos)
 
-    @property
-    def is_calibrated(self) -> bool:
-        motors_calibration = self.arm.get_calibration()
-        return motors_calibration == self.calibration
-
-    def calibrate(self) -> None:
-        print(f"\nRunning calibration of {self.id} Koch teleop")
-        for name in self.arm.names:
-            self.arm.write("Torque_Enable", name, TorqueMode.DISABLED.value)
-            self.arm.write("Operating_Mode", name, OperatingMode.EXTENDED_POSITION.value)
-
-        self.arm.write("Drive_Mode", "elbow_flex", DriveMode.INVERTED.value)
-        drive_modes = {name: 1 if name == "elbow_flex" else 0 for name in self.arm.names}
-
-        input("Move robot to the middle of its range of motion and press ENTER....")
-        homing_offsets = self.arm.set_half_turn_homings()
-
-        fixed_range = ["shoulder_pan", "wrist_roll"]
-        auto_range_motors = [name for name in self.arm.names if name not in fixed_range]
-        print(
-            "Move all joints except 'wrist_roll' (id=5) sequentially through their entire ranges of motion."
-        )
-        print("Recording positions. Press ENTER to stop...")
-        ranges = self.arm.register_ranges_of_motion(auto_range_motors)
-        for name in fixed_range:
-            ranges[name] = {"min": 0, "max": 4095}
-
-        self.calibration = {}
-        for name, motor in self.arm.motors.items():
-            self.calibration[name] = MotorCalibration(
-                id=motor.id,
-                drive_mode=drive_modes[name],
-                homing_offset=homing_offsets[name],
-                range_min=ranges[name]["min"],
-                range_max=ranges[name]["max"],
-            )
-
-        self._save_calibration()
-        print("Calibration saved to", self.calibration_fpath)
-
     def get_action(self) -> dict[str, float]:
-        """The returned action does not have a batch dimension."""
-        # Read arm position
-        start_time = time.perf_counter()
+        start = time.perf_counter()
         action = self.arm.sync_read("Present_Position")
-        self.logs["read_pos_dt_s"] = time.perf_counter() - start_time
-
+        dt_ms = (time.perf_counter() - start) * 1e3
+        logger.debug(f"{self} read action: {dt_ms:.1f}ms")
         return action
 
     def send_feedback(self, feedback: dict[str, float]) -> None:
@@ -171,3 +164,4 @@ class KochTeleop(Teleoperator):
             )
 
         self.arm.disconnect()
+        logger.info(f"{self} disconnected.")
diff --git a/lerobot/common/teleoperators/so100/teleop_so100.py b/lerobot/common/teleoperators/so100/teleop_so100.py
index 75e56d15..e42c48d3 100644
--- a/lerobot/common/teleoperators/so100/teleop_so100.py
+++ b/lerobot/common/teleoperators/so100/teleop_so100.py
@@ -22,12 +22,13 @@ from lerobot.common.motors import Motor, MotorCalibration, MotorNormMode
 from lerobot.common.motors.feetech import (
     FeetechMotorsBus,
     OperatingMode,
-    TorqueMode,
 )
 
 from ..teleoperator import Teleoperator
 from .configuration_so100 import SO100TeleopConfig
 
+logger = logging.getLogger(__name__)
+
 
 class SO100Teleop(Teleoperator):
     """
@@ -40,8 +41,6 @@ class SO100Teleop(Teleoperator):
     def __init__(self, config: SO100TeleopConfig):
         super().__init__(config)
         self.config = config
-        self.robot_type = config.type
-
         self.arm = FeetechMotorsBus(
             port=self.config.port,
             motors={
@@ -54,8 +53,6 @@ class SO100Teleop(Teleoperator):
             },
         )
 
-        self.logs = {}
-
     @property
     def action_feature(self) -> dict:
         return {
@@ -74,44 +71,37 @@ class SO100Teleop(Teleoperator):
 
     def connect(self) -> None:
         if self.is_connected:
-            raise DeviceAlreadyConnectedError(
-                "ManipulatorRobot is already connected. Do not run `robot.connect()` twice."
-            )
+            raise DeviceAlreadyConnectedError(f"{self} already connected")
 
-        logging.info("Connecting arm.")
         self.arm.connect()
         if not self.is_calibrated:
             self.calibrate()
 
         self.configure()
-
-    def configure(self) -> None:
-        # We assume that at connection time, arm is in a rest position,
-        # and torque can be safely disabled to run calibration.
-        for name in self.arm.names:
-            self.arm.write("Torque_Enable", name, TorqueMode.DISABLED.value)
+        logger.info(f"{self} connected.")
 
     @property
     def is_calibrated(self) -> bool:
-        motors_calibration = self.arm.get_calibration()
-        return motors_calibration == self.calibration
+        return self.arm.is_calibrated
 
     def calibrate(self) -> None:
-        print(f"\nRunning calibration of {self.id} SO-100 teleop")
+        logger.info(f"\nRunning calibration of {self}")
+        self.arm.disable_torque()
         for name in self.arm.names:
-            self.arm.write("Torque_Enable", name, TorqueMode.DISABLED.value)
             self.arm.write("Operating_Mode", name, OperatingMode.POSITION.value)
 
         input("Move robot to the middle of its range of motion and press ENTER....")
         homing_offsets = self.arm.set_half_turn_homings()
 
-        print(
-            "Move all joints except 'wrist_roll' (id=5) sequentially through their entire ranges of motion."
+        full_turn_motor = "wrist_roll"
+        unknown_range_motors = [name for name in self.arm.names if name != full_turn_motor]
+        logger.info(
+            f"Move all joints except '{full_turn_motor}' sequentially through their "
+            "entire ranges of motion.\nRecording positions. Press ENTER to stop..."
         )
-        print("Recording positions. Press ENTER to stop...")
-        auto_range_motors = [name for name in self.arm.names if name != "wrist_roll"]
-        ranges = self.arm.register_ranges_of_motion(auto_range_motors)
-        ranges["wrist_roll"] = {"min": 0, "max": 4095}
+        range_mins, range_maxes = self.arm.record_ranges_of_motion(unknown_range_motors)
+        range_mins[full_turn_motor] = 0
+        range_maxes[full_turn_motor] = 4095
 
         self.calibration = {}
         for name, motor in self.arm.motors.items():
@@ -119,25 +109,30 @@ class SO100Teleop(Teleoperator):
                 id=motor.id,
                 drive_mode=0,
                 homing_offset=homing_offsets[name],
-                range_min=ranges[name]["min"],
-                range_max=ranges[name]["max"],
+                range_min=range_mins[name],
+                range_max=range_maxes[name],
             )
 
+        self.arm.write_calibration(self.calibration)
         self._save_calibration()
-        print("Calibration saved to", self.calibration_fpath)
+        logger.info(f"Calibration saved to {self.calibration_fpath}")
+
+    def configure(self) -> None:
+        self.arm.disable_torque()
+        self.arm.configure_motors()
+        for name in self.arm.names:
+            self.arm.write("Operating_Mode", name, OperatingMode.POSITION.value)
 
     def get_action(self) -> dict[str, float]:
-        """The returned action does not have a batch dimension."""
-        # Read arm position
-        before_read_t = time.perf_counter()
+        start = time.perf_counter()
         action = self.arm.sync_read("Present_Position")
-        self.logs["read_pos_dt_s"] = time.perf_counter() - before_read_t
-
+        dt_ms = (time.perf_counter() - start) * 1e3
+        logger.debug(f"{self} read action: {dt_ms:.1f}ms")
         return action
 
     def send_feedback(self, feedback: dict[str, float]) -> None:
         # TODO(rcadene, aliberts): Implement force feedback
-        pass
+        raise NotImplementedError
 
     def disconnect(self) -> None:
         if not self.is_connected:
@@ -146,3 +141,4 @@ class SO100Teleop(Teleoperator):
             )
 
         self.arm.disconnect()
+        logger.info(f"{self} disconnected.")
diff --git a/lerobot/common/teleoperators/teleoperator.py b/lerobot/common/teleoperators/teleoperator.py
index 7267f27a..d6285f5c 100644
--- a/lerobot/common/teleoperators/teleoperator.py
+++ b/lerobot/common/teleoperators/teleoperator.py
@@ -30,6 +30,9 @@ class Teleoperator(abc.ABC):
         if self.calibration_fpath.is_file():
             self._load_calibration()
 
+    def __str__(self) -> str:
+        return f"{self.id} {self.__class__.__name__}"
+
     @abc.abstractproperty
     def action_feature(self) -> dict:
         pass
@@ -47,10 +50,6 @@ class Teleoperator(abc.ABC):
         """Connects to the teleoperator."""
         pass
 
-    @abc.abstractmethod
-    def configure(self) -> None:
-        pass
-
     @abc.abstractproperty
     def is_calibrated(self) -> bool:
         pass
@@ -70,6 +69,10 @@ class Teleoperator(abc.ABC):
         with open(fpath, "w") as f, draccus.config_type("json"):
             draccus.dump(self.calibration, f, indent=4)
 
+    @abc.abstractmethod
+    def configure(self) -> None:
+        pass
+
     @abc.abstractmethod
     def get_action(self) -> dict[str, Any]:
         """Gets the action to send to a teleoperator."""

From c0570b30030a02f8559bd9ecdd06fccfbf9fac1e Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Wed, 2 Apr 2025 22:40:00 +0200
Subject: [PATCH 156/171] Improve format

---
 lerobot/common/motors/motors_bus.py | 42 ++++++++++++++++-------------
 1 file changed, 23 insertions(+), 19 deletions(-)

diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py
index cbe119d5..799d959c 100644
--- a/lerobot/common/motors/motors_bus.py
+++ b/lerobot/common/motors/motors_bus.py
@@ -518,7 +518,25 @@ class MotorsBus(abc.ABC):
         self.calibration = calibration_dict
 
     def set_half_turn_homings(self, motors: NameOrID | list[NameOrID] | None = None) -> dict[NameOrID, Value]:
-        """This assumes motors present positions are roughly in the middle of their desired range"""
+        """
+        This assumes motors present positions are roughly in the middle of their desired range
+
+        Step 1: Set homing and min max to 0
+
+        Step 2: Read Present_Position which will be Actual_Position since
+        Present_Position = Actual_Position ± Homing_Offset (1)
+        and Homing_Offset = 0 from step 1
+
+        Step 3: We want to set the Homing_Offset such that the current Present_Position to be half range of 1
+        revolution. For instance, if 1 revolution corresponds to 4095 (4096 steps), this means we want the
+        current Present_Position to be 2047.
+
+        In that example:
+        Present_Position = 2047 (2)
+        Actual_Position = X (read in step 2)
+        from (1) and (2):
+        => Homing_Offset = ±(X - 2048)
+        """
         if motors is None:
             motors = self.names
         elif isinstance(motors, (str, int)):
@@ -526,28 +544,18 @@ class MotorsBus(abc.ABC):
         else:
             raise TypeError(motors)
 
-        # Step 1: Set homing and min max to 0
         self.reset_calibration(motors)
-
-        # Step 2: Read Present_Position which will be Actual_Position since
-        # Present_Position = Actual_Position ± Homing_Offset (1)
-        # and Homing_Offset = 0 from step 1
         actual_positions = self.sync_read("Present_Position", motors, normalize=False)
-
-        # Step 3: We want to set the Homing_Offset such that the current Present_Position to be half range of
-        # 1 revolution.
-        # For instance, if 1 revolution corresponds to 4095 (4096 steps), this means we want the current
-        # Present_Position to be 2047. In that example:
-        # Present_Position = 2047 (2)
-        # Actual_Position = X (read in step 2)
-        # from (1) and (2):
-        # => Homing_Offset = ±(X - 2048)
         homing_offsets = self._get_half_turn_homings(actual_positions)
         for motor, offset in homing_offsets.items():
             self.write("Homing_Offset", motor, offset)
 
         return homing_offsets
 
+    @abc.abstractmethod
+    def _get_half_turn_homings(self, positions: dict[NameOrID, Value]) -> dict[NameOrID, Value]:
+        pass
+
     def record_ranges_of_motion(
         self, motors: NameOrID | list[NameOrID] | None = None, display_values: bool = True
     ) -> tuple[dict[NameOrID, Value], dict[NameOrID, Value]]:
@@ -586,10 +594,6 @@ class MotorsBus(abc.ABC):
 
         return mins, maxes
 
-    @abc.abstractmethod
-    def _get_half_turn_homings(self, positions: dict[NameOrID, Value]) -> dict[NameOrID, Value]:
-        pass
-
     def _normalize(self, data_name: str, ids_values: dict[int, int]) -> dict[int, float]:
         normalized_values = {}
         for id_, val in ids_values.items():

From 28cd3a6f3aaa74184cd7239d626f87f88b768cbd Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Thu, 3 Apr 2025 08:14:35 +0200
Subject: [PATCH 157/171] Rename SO-100 classes

---
 lerobot/common/robots/so100/__init__.py            |  6 ++----
 ...iguration_so100.py => config_so100_follower.py} |  6 +++---
 .../so100/{robot_so100.py => so100_follower.py}    | 14 ++++++--------
 lerobot/common/robots/utils.py                     |  6 +++---
 lerobot/common/teleoperators/so100/__init__.py     |  6 ++----
 ...nfiguration_so100.py => config_so100_leader.py} |  6 +++---
 .../so100/{teleop_so100.py => so100_leader.py}     | 14 ++++++--------
 7 files changed, 25 insertions(+), 33 deletions(-)
 rename lerobot/common/robots/so100/{configuration_so100.py => config_so100_follower.py} (83%)
 rename lerobot/common/robots/so100/{robot_so100.py => so100_follower.py} (95%)
 rename lerobot/common/teleoperators/so100/{configuration_so100.py => config_so100_leader.py} (84%)
 rename lerobot/common/teleoperators/so100/{teleop_so100.py => so100_leader.py} (92%)

diff --git a/lerobot/common/robots/so100/__init__.py b/lerobot/common/robots/so100/__init__.py
index 81b064c4..087fd645 100644
--- a/lerobot/common/robots/so100/__init__.py
+++ b/lerobot/common/robots/so100/__init__.py
@@ -1,4 +1,2 @@
-from .configuration_so100 import SO100RobotConfig
-from .robot_so100 import SO100Robot
-
-__all__ = ["SO100RobotConfig", "SO100Robot"]
+from .config_so100_follower import SO100FollowerConfig
+from .so100_follower import SO100Follower
diff --git a/lerobot/common/robots/so100/configuration_so100.py b/lerobot/common/robots/so100/config_so100_follower.py
similarity index 83%
rename from lerobot/common/robots/so100/configuration_so100.py
rename to lerobot/common/robots/so100/config_so100_follower.py
index e6cb9c75..fc432222 100644
--- a/lerobot/common/robots/so100/configuration_so100.py
+++ b/lerobot/common/robots/so100/config_so100_follower.py
@@ -5,10 +5,10 @@ from lerobot.common.cameras import CameraConfig
 from ..config import RobotConfig
 
 
-@RobotConfig.register_subclass("so100")
+@RobotConfig.register_subclass("so100_follower")
 @dataclass
-class SO100RobotConfig(RobotConfig):
-    # Port to connect to the robot
+class SO100FollowerConfig(RobotConfig):
+    # Port to connect to the arm
     port: str
 
     disable_torque_on_disconnect: bool = True
diff --git a/lerobot/common/robots/so100/robot_so100.py b/lerobot/common/robots/so100/so100_follower.py
similarity index 95%
rename from lerobot/common/robots/so100/robot_so100.py
rename to lerobot/common/robots/so100/so100_follower.py
index e7222a9d..13c5739b 100644
--- a/lerobot/common/robots/so100/robot_so100.py
+++ b/lerobot/common/robots/so100/so100_follower.py
@@ -29,20 +29,20 @@ from lerobot.common.motors.feetech import (
 
 from ..robot import Robot
 from ..utils import ensure_safe_goal_position
-from .configuration_so100 import SO100RobotConfig
+from .config_so100_follower import SO100FollowerConfig
 
 logger = logging.getLogger(__name__)
 
 
-class SO100Robot(Robot):
+class SO100Follower(Robot):
     """
     [SO-100 Follower Arm](https://github.com/TheRobotStudio/SO-ARM100) designed by TheRobotStudio
     """
 
-    config_class = SO100RobotConfig
-    name = "so100"
+    config_class = SO100FollowerConfig
+    name = "so100_follower"
 
-    def __init__(self, config: SO100RobotConfig):
+    def __init__(self, config: SO100FollowerConfig):
         super().__init__(config)
         self.config = config
         self.arm = FeetechMotorsBus(
@@ -211,9 +211,7 @@ class SO100Robot(Robot):
 
     def disconnect(self):
         if not self.is_connected:
-            raise DeviceNotConnectedError(
-                "ManipulatorRobot is not connected. You need to run `robot.connect()` before disconnecting."
-            )
+            raise DeviceNotConnectedError(f"{self} is not connected.")
 
         self.arm.disconnect(self.config.disable_torque_on_disconnect)
         for cam in self.cameras.values():
diff --git a/lerobot/common/robots/utils.py b/lerobot/common/robots/utils.py
index 7e538376..c8a06b67 100644
--- a/lerobot/common/robots/utils.py
+++ b/lerobot/common/robots/utils.py
@@ -40,10 +40,10 @@ def make_robot_config(robot_type: str, **kwargs) -> RobotConfig:
         from .moss.configuration_moss import MossRobotConfig
 
         return MossRobotConfig(**kwargs)
-    elif robot_type == "so100":
-        from .so100.configuration_so100 import SO100RobotConfig
+    elif robot_type == "so100_leader":
+        from .so100.config_so100_follower import SO100FollowerConfig
 
-        return SO100RobotConfig(**kwargs)
+        return SO100FollowerConfig(**kwargs)
     elif robot_type == "stretch":
         from .stretch3.configuration_stretch3 import Stretch3RobotConfig
 
diff --git a/lerobot/common/teleoperators/so100/__init__.py b/lerobot/common/teleoperators/so100/__init__.py
index a319b5bc..63c877e6 100644
--- a/lerobot/common/teleoperators/so100/__init__.py
+++ b/lerobot/common/teleoperators/so100/__init__.py
@@ -1,4 +1,2 @@
-from .configuration_so100 import SO100TeleopConfig
-from .teleop_so100 import SO100Teleop
-
-__all__ = ["SO100TeleopConfig", "SO100Teleop"]
+from .config_so100_leader import SO100LeaderConfig
+from .so100_leader import SO100Leader
diff --git a/lerobot/common/teleoperators/so100/configuration_so100.py b/lerobot/common/teleoperators/so100/config_so100_leader.py
similarity index 84%
rename from lerobot/common/teleoperators/so100/configuration_so100.py
rename to lerobot/common/teleoperators/so100/config_so100_leader.py
index a6a807e4..a97949b7 100644
--- a/lerobot/common/teleoperators/so100/configuration_so100.py
+++ b/lerobot/common/teleoperators/so100/config_so100_leader.py
@@ -19,8 +19,8 @@ from dataclasses import dataclass
 from ..config import TeleoperatorConfig
 
 
-@TeleoperatorConfig.register_subclass("so100")
+@TeleoperatorConfig.register_subclass("so100_leader")
 @dataclass
-class SO100TeleopConfig(TeleoperatorConfig):
-    # Port to connect to the teloperator
+class SO100LeaderConfig(TeleoperatorConfig):
+    # Port to connect to the arm
     port: str
diff --git a/lerobot/common/teleoperators/so100/teleop_so100.py b/lerobot/common/teleoperators/so100/so100_leader.py
similarity index 92%
rename from lerobot/common/teleoperators/so100/teleop_so100.py
rename to lerobot/common/teleoperators/so100/so100_leader.py
index e42c48d3..f8f7239e 100644
--- a/lerobot/common/teleoperators/so100/teleop_so100.py
+++ b/lerobot/common/teleoperators/so100/so100_leader.py
@@ -25,20 +25,20 @@ from lerobot.common.motors.feetech import (
 )
 
 from ..teleoperator import Teleoperator
-from .configuration_so100 import SO100TeleopConfig
+from .config_so100_leader import SO100LeaderConfig
 
 logger = logging.getLogger(__name__)
 
 
-class SO100Teleop(Teleoperator):
+class SO100Leader(Teleoperator):
     """
     [SO-100 Leader Arm](https://github.com/TheRobotStudio/SO-ARM100) designed by TheRobotStudio
     """
 
-    config_class = SO100TeleopConfig
-    name = "so100"
+    config_class = SO100LeaderConfig
+    name = "so100_leader"
 
-    def __init__(self, config: SO100TeleopConfig):
+    def __init__(self, config: SO100LeaderConfig):
         super().__init__(config)
         self.config = config
         self.arm = FeetechMotorsBus(
@@ -136,9 +136,7 @@ class SO100Teleop(Teleoperator):
 
     def disconnect(self) -> None:
         if not self.is_connected:
-            raise DeviceNotConnectedError(
-                "ManipulatorRobot is not connected. You need to run `robot.connect()` before disconnecting."
-            )
+            DeviceNotConnectedError(f"{self} is not connected.")
 
         self.arm.disconnect()
         logger.info(f"{self} disconnected.")

From 2971bdfed5dd8de72085d0f40fc361ad0e321721 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Thu, 3 Apr 2025 08:23:31 +0200
Subject: [PATCH 158/171] Rename Koch classes

---
 lerobot/common/robots/koch/__init__.py          |  6 ++----
 ...guration_koch.py => config_koch_follower.py} |  6 +++---
 .../koch/{robot_koch.py => koch_follower.py}    | 14 ++++++--------
 lerobot/common/robots/utils.py                  |  6 +++---
 lerobot/common/teleoperators/koch/__init__.py   |  6 ++----
 ...figuration_koch.py => config_koch_leader.py} |  6 +++---
 .../koch/{teleop_koch.py => koch_leader.py}     | 17 +++++++++--------
 7 files changed, 28 insertions(+), 33 deletions(-)
 rename lerobot/common/robots/koch/{configuration_koch.py => config_koch_follower.py} (83%)
 rename lerobot/common/robots/koch/{robot_koch.py => koch_follower.py} (96%)
 rename lerobot/common/teleoperators/koch/{configuration_koch.py => config_koch_leader.py} (87%)
 rename lerobot/common/teleoperators/koch/{teleop_koch.py => koch_leader.py} (94%)

diff --git a/lerobot/common/robots/koch/__init__.py b/lerobot/common/robots/koch/__init__.py
index dfbe6369..ae98a2c3 100644
--- a/lerobot/common/robots/koch/__init__.py
+++ b/lerobot/common/robots/koch/__init__.py
@@ -1,4 +1,2 @@
-from .configuration_koch import KochRobotConfig
-from .robot_koch import KochRobot
-
-__all__ = ["KochRobotConfig", "KochRobot"]
+from .config_koch_follower import KochFollowerConfig
+from .koch_follower import KochFollower
diff --git a/lerobot/common/robots/koch/configuration_koch.py b/lerobot/common/robots/koch/config_koch_follower.py
similarity index 83%
rename from lerobot/common/robots/koch/configuration_koch.py
rename to lerobot/common/robots/koch/config_koch_follower.py
index a72bd05f..c6cd9f31 100644
--- a/lerobot/common/robots/koch/configuration_koch.py
+++ b/lerobot/common/robots/koch/config_koch_follower.py
@@ -5,10 +5,10 @@ from lerobot.common.cameras import CameraConfig
 from ..config import RobotConfig
 
 
-@RobotConfig.register_subclass("koch")
+@RobotConfig.register_subclass("koch_follower")
 @dataclass
-class KochRobotConfig(RobotConfig):
-    # Port to connect to the robot
+class KochFollowerConfig(RobotConfig):
+    # Port to connect to the arm
     port: str
 
     disable_torque_on_disconnect: bool = True
diff --git a/lerobot/common/robots/koch/robot_koch.py b/lerobot/common/robots/koch/koch_follower.py
similarity index 96%
rename from lerobot/common/robots/koch/robot_koch.py
rename to lerobot/common/robots/koch/koch_follower.py
index 72724daf..fc94f0ea 100644
--- a/lerobot/common/robots/koch/robot_koch.py
+++ b/lerobot/common/robots/koch/koch_follower.py
@@ -29,22 +29,22 @@ from lerobot.common.motors.dynamixel import (
 
 from ..robot import Robot
 from ..utils import ensure_safe_goal_position
-from .configuration_koch import KochRobotConfig
+from .config_koch_follower import KochFollowerConfig
 
 logger = logging.getLogger(__name__)
 
 
-class KochRobot(Robot):
+class KochFollower(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"
+    config_class = KochFollowerConfig
+    name = "koch_follower"
 
-    def __init__(self, config: KochRobotConfig):
+    def __init__(self, config: KochFollowerConfig):
         super().__init__(config)
         self.config = config
         self.arm = DynamixelMotorsBus(
@@ -222,9 +222,7 @@ class KochRobot(Robot):
 
     def disconnect(self):
         if not self.is_connected:
-            raise DeviceNotConnectedError(
-                "ManipulatorRobot is not connected. You need to run `robot.connect()` before disconnecting."
-            )
+            raise DeviceNotConnectedError(f"{self} is not connected.")
 
         self.arm.disconnect(self.config.disable_torque_on_disconnect)
         for cam in self.cameras.values():
diff --git a/lerobot/common/robots/utils.py b/lerobot/common/robots/utils.py
index c8a06b67..9c0b28ac 100644
--- a/lerobot/common/robots/utils.py
+++ b/lerobot/common/robots/utils.py
@@ -30,10 +30,10 @@ def make_robot_config(robot_type: str, **kwargs) -> RobotConfig:
         from .aloha.configuration_aloha import AlohaRobotConfig
 
         return AlohaRobotConfig(**kwargs)
-    elif robot_type == "koch":
-        from .koch.configuration_koch import KochRobotConfig
+    elif robot_type == "koch_follower":
+        from .koch.config_koch_follower import KochFollowerConfig
 
-        return KochRobotConfig(**kwargs)
+        return KochFollowerConfig(**kwargs)
     # elif robot_type == "koch_bimanual":
     #     return KochBimanualRobotConfig(**kwargs)
     elif robot_type == "moss":
diff --git a/lerobot/common/teleoperators/koch/__init__.py b/lerobot/common/teleoperators/koch/__init__.py
index f86454d1..ad2d6a0e 100644
--- a/lerobot/common/teleoperators/koch/__init__.py
+++ b/lerobot/common/teleoperators/koch/__init__.py
@@ -1,4 +1,2 @@
-from .configuration_koch import KochTeleopConfig
-from .teleop_koch import KochTeleop
-
-__all__ = ["KochTeleopConfig", "KochTeleop"]
+from .config_koch_leader import KochLeaderConfig
+from .koch_leader import KochLeader
diff --git a/lerobot/common/teleoperators/koch/configuration_koch.py b/lerobot/common/teleoperators/koch/config_koch_leader.py
similarity index 87%
rename from lerobot/common/teleoperators/koch/configuration_koch.py
rename to lerobot/common/teleoperators/koch/config_koch_leader.py
index cf95f547..64aaae12 100644
--- a/lerobot/common/teleoperators/koch/configuration_koch.py
+++ b/lerobot/common/teleoperators/koch/config_koch_leader.py
@@ -19,10 +19,10 @@ from dataclasses import dataclass
 from ..config import TeleoperatorConfig
 
 
-@TeleoperatorConfig.register_subclass("koch")
+@TeleoperatorConfig.register_subclass("koch_leader")
 @dataclass
-class KochTeleopConfig(TeleoperatorConfig):
-    # Port to connect to the teloperator
+class KochLeaderConfig(TeleoperatorConfig):
+    # Port to connect to the arm
     port: str
 
     # Sets the arm in torque mode with the gripper motor set to this value. This makes it possible to squeeze
diff --git a/lerobot/common/teleoperators/koch/teleop_koch.py b/lerobot/common/teleoperators/koch/koch_leader.py
similarity index 94%
rename from lerobot/common/teleoperators/koch/teleop_koch.py
rename to lerobot/common/teleoperators/koch/koch_leader.py
index e0cfc89e..85cad16c 100644
--- a/lerobot/common/teleoperators/koch/teleop_koch.py
+++ b/lerobot/common/teleoperators/koch/koch_leader.py
@@ -26,22 +26,22 @@ from lerobot.common.motors.dynamixel import (
 )
 
 from ..teleoperator import Teleoperator
-from .configuration_koch import KochTeleopConfig
+from .config_koch_leader import KochLeaderConfig
 
 logger = logging.getLogger(__name__)
 
 
-class KochTeleop(Teleoperator):
+class KochLeader(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"
+    config_class = KochLeaderConfig
+    name = "koch_leader"
 
-    def __init__(self, config: KochTeleopConfig):
+    def __init__(self, config: KochLeaderConfig):
         super().__init__(config)
         self.config = config
         self.arm = DynamixelMotorsBus(
@@ -147,6 +147,9 @@ class KochTeleop(Teleoperator):
         self.arm.write("Goal_Position", "gripper", self.config.gripper_open_pos)
 
     def get_action(self) -> dict[str, float]:
+        if not self.is_connected:
+            raise DeviceNotConnectedError(f"{self} is not connected.")
+
         start = time.perf_counter()
         action = self.arm.sync_read("Present_Position")
         dt_ms = (time.perf_counter() - start) * 1e3
@@ -159,9 +162,7 @@ class KochTeleop(Teleoperator):
 
     def disconnect(self) -> None:
         if not self.is_connected:
-            raise DeviceNotConnectedError(
-                "ManipulatorRobot is not connected. You need to run `robot.connect()` before disconnecting."
-            )
+            raise DeviceNotConnectedError(f"{self} is not connected.")
 
         self.arm.disconnect()
         logger.info(f"{self} disconnected.")

From 078f59bfd159f915bf0abf6b33ba7b0483b4eced Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Thu, 3 Apr 2025 12:14:15 +0200
Subject: [PATCH 159/171] Add calibration tests

---
 tests/mocks/mock_dynamixel.py  | 38 ++++++++++++++
 tests/mocks/mock_feetech.py    | 38 ++++++++++++++
 tests/motors/test_dynamixel.py | 92 +++++++++++++++++++++++++++++++++-
 tests/motors/test_feetech.py   | 92 +++++++++++++++++++++++++++++++++-
 4 files changed, 258 insertions(+), 2 deletions(-)

diff --git a/tests/mocks/mock_dynamixel.py b/tests/mocks/mock_dynamixel.py
index 92e47c59..42fd85df 100644
--- a/tests/mocks/mock_dynamixel.py
+++ b/tests/mocks/mock_dynamixel.py
@@ -493,6 +493,37 @@ class MockMotors(MockSerial):
         )
         return stub_name
 
+    def build_sequential_sync_read_stub(
+        self, data_name: str, ids_values: dict[int, list[int]] | None = None
+    ) -> str:
+        """
+        'data_name' supported:
+            - Present_Position
+        """
+        sequence_length = len(next(iter(ids_values.values())))
+        assert all(len(positions) == sequence_length for positions in ids_values.values())
+        if data_name != "Present_Position":
+            raise NotImplementedError
+
+        address, length = self.ctrl_table[data_name]
+        sync_read_request = MockInstructionPacket.sync_read(list(ids_values), address, length)
+        sequential_packets = []
+        for count in range(sequence_length):
+            return_packets = b"".join(
+                MockStatusPacket.present_position(id_, positions[count])
+                for id_, positions in ids_values.items()
+            )
+            sequential_packets.append(return_packets)
+
+        sync_read_response = self._build_sequential_send_fn(sequential_packets)
+        stub_name = f"Seq_Sync_Read_{data_name}_" + "_".join([str(id_) for id_ in ids_values])
+        self.stub(
+            name=stub_name,
+            receive_bytes=sync_read_request,
+            send_fn=sync_read_response,
+        )
+        return stub_name
+
     def build_sync_write_stub(
         self, data_name: str, ids_values: dict[int, int] | None = None, num_invalid_try: int = 0
     ) -> str:
@@ -528,3 +559,10 @@ class MockMotors(MockSerial):
             return packet
 
         return send_fn
+
+    @staticmethod
+    def _build_sequential_send_fn(packets: list[bytes]) -> Callable[[int], bytes]:
+        def send_fn(_call_count: int) -> bytes:
+            return packets[_call_count - 1]
+
+        return send_fn
diff --git a/tests/mocks/mock_feetech.py b/tests/mocks/mock_feetech.py
index c5fab0d9..473433bf 100644
--- a/tests/mocks/mock_feetech.py
+++ b/tests/mocks/mock_feetech.py
@@ -404,6 +404,37 @@ class MockMotors(MockSerial):
         )
         return stub_name
 
+    def build_sequential_sync_read_stub(
+        self, data_name: str, ids_values: dict[int, list[int]] | None = None
+    ) -> str:
+        """
+        'data_name' supported:
+            - Present_Position
+        """
+        sequence_length = len(next(iter(ids_values.values())))
+        assert all(len(positions) == sequence_length for positions in ids_values.values())
+        if data_name != "Present_Position":
+            raise NotImplementedError
+
+        address, length = self.ctrl_table[data_name]
+        sync_read_request = MockInstructionPacket.sync_read(list(ids_values), address, length)
+        sequential_packets = []
+        for count in range(sequence_length):
+            return_packets = b"".join(
+                MockStatusPacket.present_position(id_, positions[count])
+                for id_, positions in ids_values.items()
+            )
+            sequential_packets.append(return_packets)
+
+        sync_read_response = self._build_sequential_send_fn(sequential_packets)
+        stub_name = f"Seq_Sync_Read_{data_name}_" + "_".join([str(id_) for id_ in ids_values])
+        self.stub(
+            name=stub_name,
+            receive_bytes=sync_read_request,
+            send_fn=sync_read_response,
+        )
+        return stub_name
+
     def build_sync_write_stub(
         self, data_name: str, ids_values: dict[int, int] | None = None, num_invalid_try: int = 0
     ) -> str:
@@ -439,3 +470,10 @@ class MockMotors(MockSerial):
             return packet
 
         return send_fn
+
+    @staticmethod
+    def _build_sequential_send_fn(packets: list[bytes]) -> Callable[[int], bytes]:
+        def send_fn(_call_count: int) -> bytes:
+            return packets[_call_count - 1]
+
+        return send_fn
diff --git a/tests/motors/test_dynamixel.py b/tests/motors/test_dynamixel.py
index b2483f5b..83fe23bc 100644
--- a/tests/motors/test_dynamixel.py
+++ b/tests/motors/test_dynamixel.py
@@ -1,12 +1,13 @@
 import sys
 from typing import Generator
-from unittest.mock import patch
+from unittest.mock import MagicMock, patch
 
 import dynamixel_sdk as dxl
 import pytest
 
 from lerobot.common.motors import Motor, MotorNormMode
 from lerobot.common.motors.dynamixel import MODEL_NUMBER, DynamixelMotorsBus
+from lerobot.common.utils.encoding_utils import encode_twos_complement
 from tests.mocks.mock_dynamixel import MockMotors, MockPortHandler
 
 
@@ -432,3 +433,92 @@ def test_write_by_name(data_name, dxl_id, value, mock_motors, dummy_motors):
     motors_bus.write(data_name, f"dummy_{dxl_id}", value, normalize=False)
 
     assert mock_motors.stubs[stub_name].called
+
+
+def test_reset_calibration(mock_motors, dummy_motors):
+    write_homing_stubs = []
+    write_mins_stubs = []
+    write_maxes_stubs = []
+    for motor in dummy_motors.values():
+        write_homing_stubs.append(mock_motors.build_write_stub("Homing_Offset", motor.id, 0))
+        write_mins_stubs.append(mock_motors.build_write_stub("Min_Position_Limit", motor.id, 0))
+        write_maxes_stubs.append(mock_motors.build_write_stub("Max_Position_Limit", motor.id, 4095))
+
+    motors_bus = DynamixelMotorsBus(
+        port=mock_motors.port,
+        motors=dummy_motors,
+    )
+    motors_bus.connect(assert_motors_exist=False)
+
+    motors_bus.reset_calibration()
+
+    assert all(mock_motors.stubs[stub].called for stub in write_homing_stubs)
+    assert all(mock_motors.stubs[stub].called for stub in write_mins_stubs)
+    assert all(mock_motors.stubs[stub].called for stub in write_maxes_stubs)
+
+
+def test_set_half_turn_homings(mock_motors, dummy_motors):
+    """
+    For this test, we assume that the homing offsets are already 0 such that
+    Present_Position == Actual_Position
+    """
+    current_positions = {
+        1: 1337,
+        2: 42,
+        3: 3672,
+    }
+    expected_homings = {
+        1: 710,  # 2047 - 1337
+        2: 2005,  # 2047 - 42
+        3: -1625,  # 2047 - 3672
+    }
+    read_pos_stub = mock_motors.build_sync_read_stub("Present_Position", current_positions)
+    write_homing_stubs = []
+    for id_, homing in expected_homings.items():
+        encoded_homing = encode_twos_complement(homing, 4)
+        stub = mock_motors.build_write_stub("Homing_Offset", id_, encoded_homing)
+        write_homing_stubs.append(stub)
+
+    motors_bus = DynamixelMotorsBus(
+        port=mock_motors.port,
+        motors=dummy_motors,
+    )
+    motors_bus.connect(assert_motors_exist=False)
+    motors_bus.reset_calibration = MagicMock()
+
+    motors_bus.set_half_turn_homings()
+
+    motors_bus.reset_calibration.assert_called_once()
+    assert mock_motors.stubs[read_pos_stub].called
+    assert all(mock_motors.stubs[stub].called for stub in write_homing_stubs)
+
+
+def test_record_ranges_of_motion(mock_motors, dummy_motors):
+    positions = {
+        1: [351, 42, 1337],
+        2: [28, 3600, 2444],
+        3: [4002, 2999, 146],
+    }
+    expected_mins = {
+        "dummy_1": 42,
+        "dummy_2": 28,
+        "dummy_3": 146,
+    }
+    expected_maxes = {
+        "dummy_1": 1337,
+        "dummy_2": 3600,
+        "dummy_3": 4002,
+    }
+    read_pos_stub = mock_motors.build_sequential_sync_read_stub("Present_Position", positions)
+    with patch("lerobot.common.motors.motors_bus.enter_pressed", side_effect=[False, True]):
+        motors_bus = DynamixelMotorsBus(
+            port=mock_motors.port,
+            motors=dummy_motors,
+        )
+        motors_bus.connect(assert_motors_exist=False)
+
+        mins, maxes = motors_bus.record_ranges_of_motion(display_values=False)
+
+    assert mock_motors.stubs[read_pos_stub].calls == 3
+    assert mins == expected_mins
+    assert maxes == expected_maxes
diff --git a/tests/motors/test_feetech.py b/tests/motors/test_feetech.py
index 023ce332..5a9298c2 100644
--- a/tests/motors/test_feetech.py
+++ b/tests/motors/test_feetech.py
@@ -1,12 +1,13 @@
 import sys
 from typing import Generator
-from unittest.mock import patch
+from unittest.mock import MagicMock, patch
 
 import pytest
 import scservo_sdk as scs
 
 from lerobot.common.motors import Motor, MotorNormMode
 from lerobot.common.motors.feetech import MODEL_NUMBER, FeetechMotorsBus
+from lerobot.common.utils.encoding_utils import encode_sign_magnitude
 from tests.mocks.mock_feetech import MockMotors, MockPortHandler
 
 
@@ -453,3 +454,92 @@ def test_write_by_name(data_name, dxl_id, value, mock_motors, dummy_motors):
     motors_bus.write(data_name, f"dummy_{dxl_id}", value, normalize=False)
 
     assert mock_motors.stubs[stub_name].called
+
+
+def test_reset_calibration(mock_motors, dummy_motors):
+    write_homing_stubs = []
+    write_mins_stubs = []
+    write_maxes_stubs = []
+    for motor in dummy_motors.values():
+        write_homing_stubs.append(mock_motors.build_write_stub("Homing_Offset", motor.id, 0))
+        write_mins_stubs.append(mock_motors.build_write_stub("Min_Position_Limit", motor.id, 0))
+        write_maxes_stubs.append(mock_motors.build_write_stub("Max_Position_Limit", motor.id, 4095))
+
+    motors_bus = FeetechMotorsBus(
+        port=mock_motors.port,
+        motors=dummy_motors,
+    )
+    motors_bus.connect(assert_motors_exist=False)
+
+    motors_bus.reset_calibration()
+
+    assert all(mock_motors.stubs[stub].called for stub in write_homing_stubs)
+    assert all(mock_motors.stubs[stub].called for stub in write_mins_stubs)
+    assert all(mock_motors.stubs[stub].called for stub in write_maxes_stubs)
+
+
+def test_set_half_turn_homings(mock_motors, dummy_motors):
+    """
+    For this test, we assume that the homing offsets are already 0 such that
+    Present_Position == Actual_Position
+    """
+    current_positions = {
+        1: 1337,
+        2: 42,
+        3: 3672,
+    }
+    expected_homings = {
+        1: -710,  # 1337 - 2047
+        2: -2005,  # 42 - 2047
+        3: 1625,  # 3672 - 2047
+    }
+    read_pos_stub = mock_motors.build_sync_read_stub("Present_Position", current_positions)
+    write_homing_stubs = []
+    for id_, homing in expected_homings.items():
+        encoded_homing = encode_sign_magnitude(homing, 11)
+        stub = mock_motors.build_write_stub("Homing_Offset", id_, encoded_homing)
+        write_homing_stubs.append(stub)
+
+    motors_bus = FeetechMotorsBus(
+        port=mock_motors.port,
+        motors=dummy_motors,
+    )
+    motors_bus.connect(assert_motors_exist=False)
+    motors_bus.reset_calibration = MagicMock()
+
+    motors_bus.set_half_turn_homings()
+
+    motors_bus.reset_calibration.assert_called_once()
+    assert mock_motors.stubs[read_pos_stub].called
+    assert all(mock_motors.stubs[stub].called for stub in write_homing_stubs)
+
+
+def test_record_ranges_of_motion(mock_motors, dummy_motors):
+    positions = {
+        1: [351, 42, 1337],
+        2: [28, 3600, 2444],
+        3: [4002, 2999, 146],
+    }
+    expected_mins = {
+        "dummy_1": 42,
+        "dummy_2": 28,
+        "dummy_3": 146,
+    }
+    expected_maxes = {
+        "dummy_1": 1337,
+        "dummy_2": 3600,
+        "dummy_3": 4002,
+    }
+    read_pos_stub = mock_motors.build_sequential_sync_read_stub("Present_Position", positions)
+    with patch("lerobot.common.motors.motors_bus.enter_pressed", side_effect=[False, True]):
+        motors_bus = FeetechMotorsBus(
+            port=mock_motors.port,
+            motors=dummy_motors,
+        )
+        motors_bus.connect(assert_motors_exist=False)
+
+        mins, maxes = motors_bus.record_ranges_of_motion(display_values=False)
+
+    assert mock_motors.stubs[read_pos_stub].calls == 3
+    assert mins == expected_mins
+    assert maxes == expected_maxes

From 57319062aaa759292a3ec8958ec8b5ae76462aff Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Thu, 3 Apr 2025 12:17:43 +0200
Subject: [PATCH 160/171] Remove old calibration tests

---
 tests/motors/test_calibration.py | 147 -------------------------------
 1 file changed, 147 deletions(-)
 delete mode 100644 tests/motors/test_calibration.py

diff --git a/tests/motors/test_calibration.py b/tests/motors/test_calibration.py
deleted file mode 100644
index 2ea66e96..00000000
--- a/tests/motors/test_calibration.py
+++ /dev/null
@@ -1,147 +0,0 @@
-import sys
-from typing import Generator
-from unittest.mock import Mock, call, patch
-
-import pytest
-import scservo_sdk as scs
-
-from lerobot.common.motors import Motor, MotorNormMode
-from lerobot.common.motors.calibration import find_min_max, find_offset, set_min_max, set_offset
-from lerobot.common.motors.feetech import FeetechMotorsBus
-from tests.mocks.mock_feetech import MockMotors, MockPortHandler
-
-
-@pytest.fixture(autouse=True)
-def patch_port_handler():
-    if sys.platform == "darwin":
-        with patch.object(scs, "PortHandler", MockPortHandler):
-            yield
-    else:
-        yield
-
-
-@pytest.fixture
-def mock_motors() -> Generator[MockMotors, None, None]:
-    motors = MockMotors()
-    motors.open()
-    yield motors
-    motors.close()
-
-
-@pytest.fixture
-def dummy_motors() -> dict[str, Motor]:
-    return {
-        "dummy_1": Motor(1, "sts3215", MotorNormMode.RANGE_M100_100),
-        "wrist_roll": Motor(2, "sts3215", MotorNormMode.RANGE_M100_100),
-        "dummy_3": Motor(3, "sts3215", MotorNormMode.RANGE_M100_100),
-    }
-
-
-@pytest.fixture(autouse=True)
-def patch_broadcast_ping():
-    with patch.object(FeetechMotorsBus, "broadcast_ping", return_value={1: 777, 2: 777, 3: 777}):
-        yield
-
-
-@pytest.mark.skipif(sys.platform != "darwin", reason=f"No patching needed on {sys.platform=}")
-def test_autouse_patch():
-    """Ensures that the autouse fixture correctly patches scs.PortHandler with MockPortHandler."""
-    assert scs.PortHandler is MockPortHandler
-
-
-@pytest.mark.parametrize(
-    "motor_names, read_values",
-    [
-        (
-            ["dummy_1"],
-            [{"dummy_1": 3000}],
-        ),
-    ],
-    ids=["two-motors"],
-)
-def test_find_offset(mock_motors, dummy_motors, motor_names, read_values):
-    motors_bus = FeetechMotorsBus(
-        port=mock_motors.port,
-        motors=dummy_motors,
-    )
-    motors_bus.connect()
-
-    with (
-        patch("builtins.input", return_value=""),
-        patch("lerobot.common.motors.calibration.set_offset") as mock_set_offset,
-    ):
-        motors_bus.sync_read = Mock(side_effect=[{"dummy_1": 3000}])
-        motors_bus.motor_names = motor_names
-        motors_bus.write = Mock(return_value=None)
-
-        find_offset(motors_bus)
-        # Compute the expected offset: 3000 - 2047 = 953.
-        expected_calls = [call(motors_bus, 953, "dummy_1")]
-        mock_set_offset.assert_has_calls(expected_calls, any_order=False)
-
-
-def test_find_min_max(mock_motors, dummy_motors):
-    motors_bus = FeetechMotorsBus(
-        port=mock_motors.port,
-        motors=dummy_motors,
-    )
-    motors_bus.connect()
-    motors_bus.motor_names = list(dummy_motors.keys())
-    read_side_effect = [
-        {"dummy_1": 10, "wrist_roll": 20, "dummy_3": 30},  # For first sync_read call.
-        {"dummy_1": 4000, "wrist_roll": 2000, "dummy_3": 100},  # For second sync_read call.
-        {"dummy_1": 100, "wrist_roll": 4050, "dummy_3": 2010},  # For third sync_read call.
-    ]
-    motors_bus.sync_read = Mock(side_effect=read_side_effect)
-
-    select_returns = [
-        ([], [], []),  # First iteration: no input.
-        ([], [], []),  # Second iteration.
-        ([sys.stdin], [], []),  # Third iteration: simulate pressing ENTER.
-    ]
-    with (
-        patch("lerobot.common.motors.calibration.set_min_max") as mock_set_min_max,
-        patch("lerobot.common.motors.calibration.select.select", side_effect=select_returns),
-        patch("sys.stdin.readline", return_value="\n"),
-    ):
-        find_min_max(motors_bus)
-
-    mock_set_min_max.assert_any_call(motors_bus, 10, 4000, "dummy_1")
-    mock_set_min_max.assert_any_call(motors_bus, 0, 4095, "wrist_roll")  # wrist_roll is forced to [0,4095]
-    mock_set_min_max.assert_any_call(motors_bus, 30, 2010, "dummy_3")
-    assert mock_set_min_max.call_count == 3
-
-
-def test_set_offset_clamping(mock_motors, dummy_motors):
-    motors_bus = FeetechMotorsBus(
-        port=mock_motors.port,
-        motors=dummy_motors,
-    )
-    motors_bus.connect()
-    motors_bus.sync_read = Mock(return_value={"dummy_1": 2047})
-    motors_bus.write = Mock()
-    # A very large offset should be clamped to +2047.
-    set_offset(motors_bus, 9999, "dummy_1")
-    motors_bus.write.assert_any_call("Offset", "dummy_1", 2047, raw_value=True)
-
-
-def test_set_min_max(mock_motors, dummy_motors):
-    motors_bus = FeetechMotorsBus(
-        port=mock_motors.port,
-        motors=dummy_motors,
-    )
-    motors_bus.connect()
-
-    def _sync_read_side_effect(data_name, motors, *, raw_values=False):
-        if data_name == "Min_Angle_Limit":
-            return {"dummy_1": 100}
-        elif data_name == "Max_Angle_Limit":
-            return {"dummy_1": 3000}
-        return {}
-
-    motors_bus.sync_read = Mock(side_effect=_sync_read_side_effect)
-
-    motors_bus.write = Mock()
-    set_min_max(motors_bus, 100, 3000, "dummy_1")
-    motors_bus.write.assert_any_call("Min_Angle_Limit", "dummy_1", 100, raw_value=True)
-    motors_bus.write.assert_any_call("Max_Angle_Limit", "dummy_1", 3000, raw_value=True)

From 46797259571a5a3971cf0f0e29c7d386ab1db223 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Thu, 3 Apr 2025 15:53:54 +0200
Subject: [PATCH 161/171] Revert feetech hack and monkeypatch instead

---
 lerobot/common/motors/dynamixel/dynamixel.py | 19 +------
 lerobot/common/motors/feetech/feetech.py     | 52 +++++++-------------
 lerobot/common/motors/motors_bus.py          | 49 +++++++++++-------
 tests/mocks/mock_feetech.py                  |  4 ++
 4 files changed, 55 insertions(+), 69 deletions(-)

diff --git a/lerobot/common/motors/dynamixel/dynamixel.py b/lerobot/common/motors/dynamixel/dynamixel.py
index 719e80c7..2abce818 100644
--- a/lerobot/common/motors/dynamixel/dynamixel.py
+++ b/lerobot/common/motors/dynamixel/dynamixel.py
@@ -24,7 +24,7 @@ from enum import Enum
 
 from lerobot.common.utils.encoding_utils import decode_twos_complement, encode_twos_complement
 
-from ..motors_bus import Motor, MotorCalibration, MotorsBus, NameOrID, Value, get_address
+from ..motors_bus import Motor, MotorCalibration, MotorsBus, NameOrID, Value
 from .tables import (
     AVAILABLE_BAUDRATES,
     MODEL_BAUDRATE_TABLE,
@@ -192,20 +192,3 @@ class DynamixelMotorsBus(MotorsBus):
             return data_list if data_list else None
 
         return {id_: data[0] for id_, data in data_list.items()}
-
-    def _write(self, data_name: str, motor_id: int, value: int, num_retry: int = 0) -> tuple[int, int]:
-        model = self._id_to_model(motor_id)
-        addr, n_bytes = get_address(self.model_ctrl_table, model, data_name)
-        value = self._encode_value(value, data_name, n_bytes)
-        data = self._split_int_to_bytes(value, n_bytes)
-
-        for n_try in range(1 + num_retry):
-            comm, error = self.packet_handler.writeTxRx(self.port_handler, motor_id, addr, n_bytes, data)
-            if self._is_comm_success(comm):
-                break
-            logger.debug(
-                f"Failed to write '{data_name}' ({addr=} {n_bytes=}) on {motor_id=} with '{value}' ({n_try=})"
-            )
-            logger.debug(self.packet_handler.getRxPacketError(comm))
-
-        return comm, error
diff --git a/lerobot/common/motors/feetech/feetech.py b/lerobot/common/motors/feetech/feetech.py
index 0f73a54b..f97a8a98 100644
--- a/lerobot/common/motors/feetech/feetech.py
+++ b/lerobot/common/motors/feetech/feetech.py
@@ -19,7 +19,7 @@ from pprint import pformat
 
 from lerobot.common.utils.encoding_utils import decode_sign_magnitude, encode_sign_magnitude
 
-from ..motors_bus import Motor, MotorCalibration, MotorsBus, NameOrID, Value, get_address
+from ..motors_bus import Motor, MotorCalibration, MotorsBus, NameOrID, Value
 from .tables import (
     AVAILABLE_BAUDRATES,
     ENCODINGS,
@@ -61,6 +61,19 @@ class TorqueMode(Enum):
     DISABLED = 0
 
 
+def patch_setPacketTimeout(self, packet_length):  # noqa: N802
+    """
+    HACK: This patches the PortHandler behavior to set the correct packet timeouts.
+
+    It fixes https://gitee.com/ftservo/SCServoSDK/issues/IBY2S6
+    The bug is fixed on the official Feetech SDK repo (https://gitee.com/ftservo/FTServo_Python)
+    but because that version is not published on PyPI, we rely on the (unofficial) on that is, which needs
+    patching.
+    """
+    self.packet_start_time = self.getCurrentTime()
+    self.packet_timeout = (self.tx_time_per_byte * packet_length) + (self.tx_time_per_byte * 3.0) + 50
+
+
 class FeetechMotorsBus(MotorsBus):
     """
     The FeetechMotorsBus class allows to efficiently read and write to the attached motors. It relies on the
@@ -88,6 +101,10 @@ class FeetechMotorsBus(MotorsBus):
         import scservo_sdk as scs
 
         self.port_handler = scs.PortHandler(self.port)
+        # HACK: monkeypatch
+        self.port_handler.setPacketTimeout = patch_setPacketTimeout.__get__(
+            self.port_handler, scs.PortHandler
+        )
         self.packet_handler = scs.PacketHandler(PROTOCOL_VERSION)
         self.sync_reader = scs.GroupSyncRead(self.port_handler, self.packet_handler, 0, 0)
         self.sync_writer = scs.GroupSyncWrite(self.port_handler, self.packet_handler, 0, 0)
@@ -261,36 +278,3 @@ class FeetechMotorsBus(MotorsBus):
             return model_numbers if model_numbers else None
 
         return model_numbers
-
-    def _is_eprom(self, address: int) -> bool:
-        """
-        HACK: because of https://gitee.com/ftservo/SCServoSDK/issues/IBY2S6
-        When writing to EPROM on for Feetech motors with Lock=0, we need to:
-            - 1. write several times
-            - 2. reset serial's buffer
-        """
-        return address < 40
-
-    def _write(self, data_name: str, motor_id: int, value: int, num_retry: int = 0) -> tuple[int, int]:
-        model = self._id_to_model(motor_id)
-        addr, n_bytes = get_address(self.model_ctrl_table, model, data_name)
-        value = self._encode_value(value, data_name, n_bytes)
-        data = self._split_int_to_bytes(value, n_bytes)
-
-        if self._is_eprom(addr):  # HACK
-            num_retry = max(num_retry, 5)
-
-        for n_try in range(1 + num_retry):
-            comm, error = self.packet_handler.writeTxRx(self.port_handler, motor_id, addr, n_bytes, data)
-            if self._is_comm_success(comm):
-                break
-            logger.debug(
-                f"Failed to write '{data_name}' ({addr=} {n_bytes=}) on {motor_id=} with '{value}' ({n_try=})"
-            )
-            logger.debug(self.packet_handler.getRxPacketError(comm))
-
-        if self._is_eprom(addr):  # HACK
-            self.port_handler.ser.reset_output_buffer()
-            self.port_handler.ser.reset_input_buffer()
-
-        return comm, error
diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py
index 799d959c..96cbb7c3 100644
--- a/lerobot/common/motors/motors_bus.py
+++ b/lerobot/common/motors/motors_bus.py
@@ -468,21 +468,6 @@ class MotorsBus(abc.ABC):
             if self.port_handler.getBaudRate() != baudrate:
                 raise OSError("Failed to write bus baud rate.")
 
-    def reset_calibration(self, motors: NameOrID | list[NameOrID] | None = None) -> None:
-        if motors is None:
-            motors = self.names
-        elif isinstance(motors, (str, int)):
-            motors = [motors]
-        elif not isinstance(motors, list):
-            raise TypeError(motors)
-
-        for motor in motors:
-            model = self._get_motor_model(motor)
-            max_res = self.model_resolution_table[model] - 1
-            self.write("Homing_Offset", motor, 0, normalize=False)
-            self.write("Min_Position_Limit", motor, 0, normalize=False)
-            self.write("Max_Position_Limit", motor, max_res, normalize=False)
-
     @property
     def is_calibrated(self) -> bool:
         return self.calibration == self.read_calibration()
@@ -517,6 +502,23 @@ class MotorsBus(abc.ABC):
 
         self.calibration = calibration_dict
 
+    def reset_calibration(self, motors: NameOrID | list[NameOrID] | None = None) -> None:
+        if motors is None:
+            motors = self.names
+        elif isinstance(motors, (str, int)):
+            motors = [motors]
+        elif not isinstance(motors, list):
+            raise TypeError(motors)
+
+        for motor in motors:
+            model = self._get_motor_model(motor)
+            max_res = self.model_resolution_table[model] - 1
+            self.write("Homing_Offset", motor, 0, normalize=False)
+            self.write("Min_Position_Limit", motor, 0, normalize=False)
+            self.write("Max_Position_Limit", motor, max_res, normalize=False)
+
+        self.calibration = {}
+
     def set_half_turn_homings(self, motors: NameOrID | list[NameOrID] | None = None) -> dict[NameOrID, Value]:
         """
         This assumes motors present positions are roughly in the middle of their desired range
@@ -892,9 +894,22 @@ class MotorsBus(abc.ABC):
                 f"\n{self.packet_handler.getRxPacketError(error)}"
             )
 
-    @abc.abstractmethod
     def _write(self, data_name: str, motor_id: int, value: int, num_retry: int = 0) -> tuple[int, int]:
-        pass
+        model = self._id_to_model(motor_id)
+        addr, n_bytes = get_address(self.model_ctrl_table, model, data_name)
+        value = self._encode_value(value, data_name, n_bytes)
+        data = self._split_int_to_bytes(value, n_bytes)
+
+        for n_try in range(1 + num_retry):
+            comm, error = self.packet_handler.writeTxRx(self.port_handler, motor_id, addr, n_bytes, data)
+            if self._is_comm_success(comm):
+                break
+            logger.debug(
+                f"Failed to write '{data_name}' ({addr=} {n_bytes=}) on {motor_id=} with '{value}' ({n_try=})"
+            )
+            logger.debug(self.packet_handler.getRxPacketError(comm))
+
+        return comm, error
 
     def disconnect(self, disable_torque: bool = True) -> None:
         if not self.is_connected:
diff --git a/tests/mocks/mock_feetech.py b/tests/mocks/mock_feetech.py
index 473433bf..291052ae 100644
--- a/tests/mocks/mock_feetech.py
+++ b/tests/mocks/mock_feetech.py
@@ -7,6 +7,7 @@ import serial
 from mock_serial import MockSerial
 
 from lerobot.common.motors.feetech import SCS_SERIES_CONTROL_TABLE, FeetechMotorsBus
+from lerobot.common.motors.feetech.feetech import patch_setPacketTimeout
 
 from .mock_serial_patch import WaitableStub
 
@@ -308,6 +309,9 @@ class MockPortHandler(scs.PortHandler):
 
         return True
 
+    def setPacketTimeout(self, packet_length):  # noqa: N802
+        return patch_setPacketTimeout(self, packet_length)
+
 
 class MockMotors(MockSerial):
     """

From 0dcb2caba8296d822f2a267ed1bcf7b16646c6c3 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Thu, 3 Apr 2025 16:43:23 +0200
Subject: [PATCH 162/171] Simplify motors mocks

---
 tests/mocks/mock_dynamixel.py | 56 ++++++++++-------------------
 tests/mocks/mock_feetech.py   | 66 ++++++-----------------------------
 2 files changed, 30 insertions(+), 92 deletions(-)

diff --git a/tests/mocks/mock_dynamixel.py b/tests/mocks/mock_dynamixel.py
index 42fd85df..0d100bb1 100644
--- a/tests/mocks/mock_dynamixel.py
+++ b/tests/mocks/mock_dynamixel.py
@@ -1,5 +1,4 @@
 import abc
-import random
 from typing import Callable
 
 import dynamixel_sdk as dxl
@@ -178,7 +177,7 @@ class MockInstructionPacket(MockDynamixelPacketv2):
     Helper class to build valid Dynamixel Protocol 2.0 Instruction Packets.
 
     Protocol 2.0 Instruction Packet structure
-    (from https://emanual.robotis.com/docs/en/dxl/protocol2/#instruction-packet)
+    https://emanual.robotis.com/docs/en/dxl/protocol2/#instruction-packet
 
     | Header              | Packet ID | Length      | Instruction | Params            | CRC         |
     | ------------------- | --------- | ----------- | ----------- | ----------------- | ----------- |
@@ -206,7 +205,7 @@ class MockInstructionPacket(MockDynamixelPacketv2):
     ) -> bytes:
         """
         Builds a "Ping" broadcast instruction.
-        (from https://emanual.robotis.com/docs/en/dxl/protocol2/#ping-0x01)
+        https://emanual.robotis.com/docs/en/dxl/protocol2/#ping-0x01
 
         No parameters required.
         """
@@ -222,7 +221,7 @@ class MockInstructionPacket(MockDynamixelPacketv2):
     ) -> bytes:
         """
         Builds a "Sync_Read" broadcast instruction.
-        (from https://emanual.robotis.com/docs/en/dxl/protocol2/#sync-read-0x82)
+        https://emanual.robotis.com/docs/en/dxl/protocol2/#sync-read-0x82
 
         The parameters for Sync_Read (Protocol 2.0) are:
             param[0]   = start_address L
@@ -256,7 +255,7 @@ class MockInstructionPacket(MockDynamixelPacketv2):
     ) -> bytes:
         """
         Builds a "Sync_Write" broadcast instruction.
-        (from https://emanual.robotis.com/docs/en/dxl/protocol2/#sync-write-0x83)
+        https://emanual.robotis.com/docs/en/dxl/protocol2/#sync-write-0x83
 
         The parameters for Sync_Write (Protocol 2.0) are:
             param[0]   = start_address L
@@ -304,7 +303,7 @@ class MockInstructionPacket(MockDynamixelPacketv2):
     ) -> bytes:
         """
         Builds a "Write" instruction.
-        (from https://emanual.robotis.com/docs/en/dxl/protocol2/#write-0x03)
+        https://emanual.robotis.com/docs/en/dxl/protocol2/#write-0x03
 
         The parameters for Write (Protocol 2.0) are:
             param[0]   = start_address L
@@ -334,7 +333,7 @@ class MockStatusPacket(MockDynamixelPacketv2):
     Helper class to build valid Dynamixel Protocol 2.0 Status Packets.
 
     Protocol 2.0 Status Packet structure
-    (from https://emanual.robotis.com/docs/en/dxl/protocol2/#status-packet)
+    https://emanual.robotis.com/docs/en/dxl/protocol2/#status-packet
 
     | Header              | Packet ID | Length      | Instruction | Error | Params            | CRC         |
     | ------------------- | --------- | ----------- | ----------- | ----- | ----------------- | ----------- |
@@ -357,8 +356,8 @@ class MockStatusPacket(MockDynamixelPacketv2):
 
     @classmethod
     def ping(cls, dxl_id: int, model_nb: int = 1190, firm_ver: int = 50) -> bytes:
-        """Builds a 'Ping' status packet.
-
+        """
+        Builds a 'Ping' status packet.
         https://emanual.robotis.com/docs/en/dxl/protocol2/#ping-0x01
 
         Args:
@@ -376,22 +375,22 @@ class MockStatusPacket(MockDynamixelPacketv2):
         return cls.build(dxl_id, params=params, length=length)
 
     @classmethod
-    def present_position(cls, dxl_id: int, pos: int | None = None, min_max_range: tuple = (0, 4095)) -> bytes:
-        """Builds a 'Present_Position' status packet.
+    def read(cls, dxl_id: int, value: int, param_length: int) -> bytes:
+        """
+        Builds a 'Read' status packet (also works for 'Sync Read')
+        https://emanual.robotis.com/docs/en/dxl/protocol2/#read-0x02
+        https://emanual.robotis.com/docs/en/dxl/protocol2/#sync-read-0x82
 
         Args:
             dxl_id (int): ID of the servo responding.
-            pos (int | None, optional): Desired 'Present_Position' to be returned in the packet. If None, it
-                will use a random value in the min_max_range. Defaults to None.
-            min_max_range (tuple, optional): Min/max range to generate the position values used for when 'pos'
-                is None. Note that the bounds are included in the range. Defaults to (0, 4095).
+            value (int): Desired value to be returned in the packet.
+            param_length (int): The address length as reported in the control table.
 
         Returns:
             bytes: The raw 'Present_Position' status packet ready to be sent through serial.
         """
-        pos = random.randint(*min_max_range) if pos is None else pos
-        params = [dxl.DXL_LOBYTE(pos), dxl.DXL_HIBYTE(pos), 0, 0]
-        length = 8
+        params = DynamixelMotorsBus._split_int_to_bytes(value, param_length)
+        length = param_length + 4
         return cls.build(dxl_id, params=params, length=length)
 
 
@@ -472,18 +471,9 @@ class MockMotors(MockSerial):
     def build_sync_read_stub(
         self, data_name: str, ids_values: dict[int, int] | None = None, num_invalid_try: int = 0
     ) -> str:
-        """
-        'data_name' supported:
-            - Present_Position
-        """
-        if data_name != "Present_Position":
-            raise NotImplementedError
-
         address, length = self.ctrl_table[data_name]
         sync_read_request = MockInstructionPacket.sync_read(list(ids_values), address, length)
-        return_packets = b"".join(
-            MockStatusPacket.present_position(id_, pos) for id_, pos in ids_values.items()
-        )
+        return_packets = b"".join(MockStatusPacket.read(id_, pos, length) for id_, pos in ids_values.items())
         sync_read_response = self._build_send_fn(return_packets, num_invalid_try)
         stub_name = f"Sync_Read_{data_name}_" + "_".join([str(id_) for id_ in ids_values])
         self.stub(
@@ -496,22 +486,14 @@ class MockMotors(MockSerial):
     def build_sequential_sync_read_stub(
         self, data_name: str, ids_values: dict[int, list[int]] | None = None
     ) -> str:
-        """
-        'data_name' supported:
-            - Present_Position
-        """
         sequence_length = len(next(iter(ids_values.values())))
         assert all(len(positions) == sequence_length for positions in ids_values.values())
-        if data_name != "Present_Position":
-            raise NotImplementedError
-
         address, length = self.ctrl_table[data_name]
         sync_read_request = MockInstructionPacket.sync_read(list(ids_values), address, length)
         sequential_packets = []
         for count in range(sequence_length):
             return_packets = b"".join(
-                MockStatusPacket.present_position(id_, positions[count])
-                for id_, positions in ids_values.items()
+                MockStatusPacket.read(id_, positions[count], length) for id_, positions in ids_values.items()
             )
             sequential_packets.append(return_packets)
 
diff --git a/tests/mocks/mock_feetech.py b/tests/mocks/mock_feetech.py
index 291052ae..1636c113 100644
--- a/tests/mocks/mock_feetech.py
+++ b/tests/mocks/mock_feetech.py
@@ -1,5 +1,4 @@
 import abc
-import random
 from typing import Callable
 
 import scservo_sdk as scs
@@ -248,40 +247,19 @@ class MockStatusPacket(MockFeetechPacket):
         return cls.build(scs_id, params=[], length=2, error=error)
 
     @classmethod
-    def present_position(cls, scs_id: int, pos: int | None = None, min_max_range: tuple = (0, 4095)) -> bytes:
-        """Builds a 'Present_Position' status packet.
+    def read(cls, scs_id: int, value: int, param_length: int) -> bytes:
+        """Builds a 'Read' status packet.
 
         Args:
-            scs_id (int): List of the servos ids.
-            pos (int | None, optional): Desired 'Present_Position' to be returned in the packet. If None, it
-                will use a random value in the min_max_range. Defaults to None.
-            min_max_range (tuple, optional): Min/max range to generate the position values used for when 'pos'
-                is None. Note that the bounds are included in the range. Defaults to (0, 4095).
+            scs_id (int): ID of the servo responding.
+            value (int): Desired value to be returned in the packet.
+            param_length (int): The address length as reported in the control table.
 
         Returns:
-            bytes: The raw 'Present_Position' status packet ready to be sent through serial.
+            bytes: The raw 'Sync Read' status packet ready to be sent through serial.
         """
-        pos = random.randint(*min_max_range) if pos is None else pos
-        params = [scs.SCS_LOBYTE(pos), scs.SCS_HIBYTE(pos)]
-        length = 4
-        return cls.build(scs_id, params=params, length=length)
-
-    @classmethod
-    def model_number(cls, scs_id: int, model_nb: int | None = None) -> bytes:
-        """Builds a 'Present_Position' status packet.
-
-        Args:
-            scs_id (int): List of the servos ids.
-            pos (int | None, optional): Desired 'Present_Position' to be returned in the packet. If None, it
-                will use a random value in the min_max_range. Defaults to None.
-            min_max_range (tuple, optional): Min/max range to generate the position values used for when 'pos'
-                is None. Note that the bounds are included in the range. Defaults to (0, 4095).
-
-        Returns:
-            bytes: The raw 'Present_Position' status packet ready to be sent through serial.
-        """
-        params = [scs.SCS_LOBYTE(model_nb), scs.SCS_HIBYTE(model_nb)]
-        length = 4
+        params = FeetechMotorsBus._split_int_to_bytes(value, param_length)
+        length = param_length + 2
         return cls.build(scs_id, params=params, length=length)
 
 
@@ -368,7 +346,7 @@ class MockMotors(MockSerial):
             raise NotImplementedError
         address, length = self.ctrl_table[data_name]
         read_request = MockInstructionPacket.read(scs_id, address, length)
-        return_packet = MockStatusPacket.model_number(scs_id, value)
+        return_packet = MockStatusPacket.read(scs_id, value, length)
         read_response = self._build_send_fn(return_packet, num_invalid_try)
         stub_name = f"Read_{data_name}_{scs_id}"
         self.stub(
@@ -381,23 +359,9 @@ class MockMotors(MockSerial):
     def build_sync_read_stub(
         self, data_name: str, ids_values: dict[int, int] | None = None, num_invalid_try: int = 0
     ) -> str:
-        """
-        'data_name' supported:
-            - Present_Position
-            - Model_Number
-        """
         address, length = self.ctrl_table[data_name]
         sync_read_request = MockInstructionPacket.sync_read(list(ids_values), address, length)
-        if data_name == "Present_Position":
-            return_packets = b"".join(
-                MockStatusPacket.present_position(id_, pos) for id_, pos in ids_values.items()
-            )
-        elif data_name == "Model_Number":
-            return_packets = b"".join(
-                MockStatusPacket.model_number(id_, model_nb) for id_, model_nb in ids_values.items()
-            )
-        else:
-            raise NotImplementedError
+        return_packets = b"".join(MockStatusPacket.read(id_, pos, length) for id_, pos in ids_values.items())
 
         sync_read_response = self._build_send_fn(return_packets, num_invalid_try)
         stub_name = f"Sync_Read_{data_name}_" + "_".join([str(id_) for id_ in ids_values])
@@ -411,22 +375,14 @@ class MockMotors(MockSerial):
     def build_sequential_sync_read_stub(
         self, data_name: str, ids_values: dict[int, list[int]] | None = None
     ) -> str:
-        """
-        'data_name' supported:
-            - Present_Position
-        """
         sequence_length = len(next(iter(ids_values.values())))
         assert all(len(positions) == sequence_length for positions in ids_values.values())
-        if data_name != "Present_Position":
-            raise NotImplementedError
-
         address, length = self.ctrl_table[data_name]
         sync_read_request = MockInstructionPacket.sync_read(list(ids_values), address, length)
         sequential_packets = []
         for count in range(sequence_length):
             return_packets = b"".join(
-                MockStatusPacket.present_position(id_, positions[count])
-                for id_, positions in ids_values.items()
+                MockStatusPacket.read(id_, positions[count], length) for id_, positions in ids_values.items()
             )
             sequential_packets.append(return_packets)
 

From e393af2d88e59fe5c3926eab83922178f02fc69b Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Thu, 3 Apr 2025 17:35:10 +0200
Subject: [PATCH 163/171] Add is_calibrated test

---
 tests/motors/test_dynamixel.py | 45 +++++++++++++++++++++++++++++++++-
 tests/motors/test_feetech.py   | 41 ++++++++++++++++++++++++++++++-
 2 files changed, 84 insertions(+), 2 deletions(-)

diff --git a/tests/motors/test_dynamixel.py b/tests/motors/test_dynamixel.py
index 83fe23bc..9ebbbacb 100644
--- a/tests/motors/test_dynamixel.py
+++ b/tests/motors/test_dynamixel.py
@@ -5,7 +5,7 @@ from unittest.mock import MagicMock, patch
 import dynamixel_sdk as dxl
 import pytest
 
-from lerobot.common.motors import Motor, MotorNormMode
+from lerobot.common.motors import Motor, MotorCalibration, MotorNormMode
 from lerobot.common.motors.dynamixel import MODEL_NUMBER, DynamixelMotorsBus
 from lerobot.common.utils.encoding_utils import encode_twos_complement
 from tests.mocks.mock_dynamixel import MockMotors, MockPortHandler
@@ -37,6 +37,24 @@ def dummy_motors() -> dict[str, Motor]:
     }
 
 
+@pytest.fixture
+def dummy_calibration(dummy_motors) -> dict[str, MotorCalibration]:
+    drive_modes = [0, 1, 0]
+    homings = [-709, -2006, 1624]
+    mins = [43, 27, 145]
+    maxes = [1335, 3608, 3999]
+    calibration = {}
+    for name, motor in dummy_motors.items():
+        calibration[name] = MotorCalibration(
+            id=motor.id,
+            drive_mode=drive_modes[motor.id - 1],
+            homing_offset=homings[motor.id - 1],
+            range_min=mins[motor.id - 1],
+            range_max=maxes[motor.id - 1],
+        )
+    return calibration
+
+
 @pytest.mark.skipif(sys.platform != "darwin", reason=f"No patching needed on {sys.platform=}")
 def test_autouse_patch():
     """Ensures that the autouse fixture correctly patches dxl.PortHandler with MockPortHandler."""
@@ -435,6 +453,31 @@ def test_write_by_name(data_name, dxl_id, value, mock_motors, dummy_motors):
     assert mock_motors.stubs[stub_name].called
 
 
+def test_is_calibrated(mock_motors, dummy_motors, dummy_calibration):
+    drive_modes = {m.id: m.drive_mode for m in dummy_calibration.values()}
+    encoded_homings = {m.id: encode_twos_complement(m.homing_offset, 4) for m in dummy_calibration.values()}
+    mins = {m.id: m.range_min for m in dummy_calibration.values()}
+    maxes = {m.id: m.range_max for m in dummy_calibration.values()}
+    drive_modes_stub = mock_motors.build_sync_read_stub("Drive_Mode", drive_modes)
+    offsets_stub = mock_motors.build_sync_read_stub("Homing_Offset", encoded_homings)
+    mins_stub = mock_motors.build_sync_read_stub("Min_Position_Limit", mins)
+    maxes_stub = mock_motors.build_sync_read_stub("Max_Position_Limit", maxes)
+    motors_bus = DynamixelMotorsBus(
+        port=mock_motors.port,
+        motors=dummy_motors,
+        calibration=dummy_calibration,
+    )
+    motors_bus.connect(assert_motors_exist=False)
+
+    is_calibrated = motors_bus.is_calibrated
+
+    assert is_calibrated
+    assert mock_motors.stubs[drive_modes_stub].called
+    assert mock_motors.stubs[offsets_stub].called
+    assert mock_motors.stubs[mins_stub].called
+    assert mock_motors.stubs[maxes_stub].called
+
+
 def test_reset_calibration(mock_motors, dummy_motors):
     write_homing_stubs = []
     write_mins_stubs = []
diff --git a/tests/motors/test_feetech.py b/tests/motors/test_feetech.py
index 5a9298c2..871f102e 100644
--- a/tests/motors/test_feetech.py
+++ b/tests/motors/test_feetech.py
@@ -5,7 +5,7 @@ from unittest.mock import MagicMock, patch
 import pytest
 import scservo_sdk as scs
 
-from lerobot.common.motors import Motor, MotorNormMode
+from lerobot.common.motors import Motor, MotorCalibration, MotorNormMode
 from lerobot.common.motors.feetech import MODEL_NUMBER, FeetechMotorsBus
 from lerobot.common.utils.encoding_utils import encode_sign_magnitude
 from tests.mocks.mock_feetech import MockMotors, MockPortHandler
@@ -37,6 +37,23 @@ def dummy_motors() -> dict[str, Motor]:
     }
 
 
+@pytest.fixture
+def dummy_calibration(dummy_motors) -> dict[str, MotorCalibration]:
+    homings = [-709, -2006, 1624]
+    mins = [43, 27, 145]
+    maxes = [1335, 3608, 3999]
+    calibration = {}
+    for name, motor in dummy_motors.items():
+        calibration[name] = MotorCalibration(
+            id=motor.id,
+            drive_mode=0,
+            homing_offset=homings[motor.id - 1],
+            range_min=mins[motor.id - 1],
+            range_max=maxes[motor.id - 1],
+        )
+    return calibration
+
+
 @pytest.mark.skipif(sys.platform != "darwin", reason=f"No patching needed on {sys.platform=}")
 def test_autouse_patch():
     """Ensures that the autouse fixture correctly patches scs.PortHandler with MockPortHandler."""
@@ -456,6 +473,28 @@ def test_write_by_name(data_name, dxl_id, value, mock_motors, dummy_motors):
     assert mock_motors.stubs[stub_name].called
 
 
+def test_is_calibrated(mock_motors, dummy_motors, dummy_calibration):
+    encoded_homings = {m.id: encode_sign_magnitude(m.homing_offset, 11) for m in dummy_calibration.values()}
+    mins = {m.id: m.range_min for m in dummy_calibration.values()}
+    maxes = {m.id: m.range_max for m in dummy_calibration.values()}
+    offsets_stub = mock_motors.build_sync_read_stub("Homing_Offset", encoded_homings)
+    mins_stub = mock_motors.build_sync_read_stub("Min_Position_Limit", mins)
+    maxes_stub = mock_motors.build_sync_read_stub("Max_Position_Limit", maxes)
+    motors_bus = FeetechMotorsBus(
+        port=mock_motors.port,
+        motors=dummy_motors,
+        calibration=dummy_calibration,
+    )
+    motors_bus.connect(assert_motors_exist=False)
+
+    is_calibrated = motors_bus.is_calibrated
+
+    assert is_calibrated
+    assert mock_motors.stubs[offsets_stub].called
+    assert mock_motors.stubs[mins_stub].called
+    assert mock_motors.stubs[maxes_stub].called
+
+
 def test_reset_calibration(mock_motors, dummy_motors):
     write_homing_stubs = []
     write_mins_stubs = []

From f7672e14c77f9c33cf21103ac788da81aa4eb0c0 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Thu, 3 Apr 2025 18:34:08 +0200
Subject: [PATCH 164/171] Update viperx & widowx

---
 .../robots/viperx/configuration_viperx.py     |   4 +
 lerobot/common/robots/viperx/robot_viperx.py  | 208 +++++++++---------
 .../widowx/configuration_widowx.py            |  15 +-
 .../teleoperators/widowx/teleop_widowx.py     | 140 ++++++------
 4 files changed, 173 insertions(+), 194 deletions(-)

diff --git a/lerobot/common/robots/viperx/configuration_viperx.py b/lerobot/common/robots/viperx/configuration_viperx.py
index 186f0ad6..e6c68b18 100644
--- a/lerobot/common/robots/viperx/configuration_viperx.py
+++ b/lerobot/common/robots/viperx/configuration_viperx.py
@@ -8,6 +8,10 @@ from ..config import RobotConfig
 @RobotConfig.register_subclass("viperx")
 @dataclass
 class ViperXRobotConfig(RobotConfig):
+    port: str  # Port to connect to the arm
+
+    disable_torque_on_disconnect: bool = True
+
     # /!\ 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
diff --git a/lerobot/common/robots/viperx/robot_viperx.py b/lerobot/common/robots/viperx/robot_viperx.py
index 5471a312..fc11b603 100644
--- a/lerobot/common/robots/viperx/robot_viperx.py
+++ b/lerobot/common/robots/viperx/robot_viperx.py
@@ -4,25 +4,25 @@ 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 typing import Any
 
 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 import Motor, MotorNormMode, TorqueMode
+from lerobot.common.motors import Motor, MotorCalibration, MotorNormMode
 from lerobot.common.motors.dynamixel import (
     DynamixelMotorsBus,
-    run_arm_calibration,
+    OperatingMode,
 )
 
 from ..robot import Robot
 from ..utils import ensure_safe_goal_position
 from .configuration_viperx import ViperXRobotConfig
 
+logger = logging.getLogger(__name__)
+
 
 class ViperXRobot(Robot):
     """
@@ -38,8 +38,6 @@ class ViperXRobot(Robot):
     ):
         super().__init__(config)
         self.config = config
-        self.robot_type = config.type
-
         self.arm = DynamixelMotorsBus(
             port=self.config.port,
             motors={
@@ -56,9 +54,6 @@ class ViperXRobot(Robot):
         )
         self.cameras = make_cameras_from_configs(config.cameras)
 
-        self.is_connected = False
-        self.logs = {}
-
     @property
     def state_feature(self) -> dict:
         return {
@@ -83,111 +78,119 @@ class ViperXRobot(Robot):
             }
         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")
+    @property
+    def is_connected(self) -> bool:
+        # TODO(aliberts): add cam.is_connected for cam in self.cameras
+        return self.arm.is_connected
 
-        elbow_idx = self.config.elbow[0]
-        self.arm.write("Secondary_ID", elbow_idx, "elbow_shadow")
-
-    def connect(self):
+    def connect(self) -> None:
+        """
+        We assume that at connection time, arm is in a rest position,
+        and torque can be safely disabled to run calibration.
+        """
         if self.is_connected:
-            raise DeviceAlreadyConnectedError(
-                "ManipulatorRobot is already connected. Do not run `robot.connect()` twice."
+            raise DeviceAlreadyConnectedError(f"{self} already connected")
+
+        self.arm.connect()
+        if not self.is_calibrated:
+            self.calibrate()
+
+        for cam in self.cameras.values():
+            cam.connect()
+
+        self.configure()
+        logger.info(f"{self} connected.")
+
+    @property
+    def is_calibrated(self) -> bool:
+        return self.arm.is_calibrated
+
+    def calibrate(self) -> None:
+        raise NotImplementedError  # TODO(aliberts): adapt code below (copied from koch
+        logger.info(f"\nRunning calibration of {self}")
+        self.arm.disable_torque()
+        for name in self.arm.names:
+            self.arm.write("Operating_Mode", name, OperatingMode.EXTENDED_POSITION.value)
+
+        input("Move robot to the middle of its range of motion and press ENTER....")
+        homing_offsets = self.arm.set_half_turn_homings()
+
+        full_turn_motors = ["shoulder_pan", "wrist_roll"]
+        unknown_range_motors = [name for name in self.arm.names if name not in full_turn_motors]
+        logger.info(
+            f"Move all joints except {full_turn_motors} sequentially through their entire "
+            "ranges of motion.\nRecording positions. Press ENTER to stop..."
+        )
+        range_mins, range_maxes = self.arm.record_ranges_of_motion(unknown_range_motors)
+        for name in full_turn_motors:
+            range_mins[name] = 0
+            range_maxes[name] = 4095
+
+        self.calibration = {}
+        for name, motor in self.arm.motors.items():
+            self.calibration[name] = MotorCalibration(
+                id=motor.id,
+                drive_mode=0,
+                homing_offset=homing_offsets[name],
+                range_min=range_mins[name],
+                range_max=range_maxes[name],
             )
 
-        logging.info("Connecting arm.")
-        self.arm.connect()
+        self.arm.write_calibration(self.calibration)
+        self._save_calibration()
+        logger.info(f"Calibration saved to {self.calibration_fpath}")
 
-        # 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()
+    def configure(self) -> None:
+        self.arm.disable_torque()
+        self.arm.configure_motors()
 
-        self._set_shadow_motors()
+        # 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.
+        self.arm.write("Secondary_ID", "shoulder_shadow", 2)
+        self.arm.write("Secondary_ID", "elbow_shadow", 4)
 
         # Set a velocity limit of 131 as advised by Trossen Robotics
+        # TODO(aliberts): remove as it's actually useless in position control
         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)
+        # 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
+        for name in self.arm.names:
+            if name != "gripper":
+                self.arm.write("Operating_Mode", name, OperatingMode.EXTENDED_POSITION.value)
 
         # 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")
+        # 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).
+        self.arm.write("Operating_Mode", "gripper", OperatingMode.CURRENT_POSITION.value)
+        self.arm.enable_torque()
 
-        # 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].
-        """
-        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 '{self.calibration_fpath}'")
-            calibration = run_arm_calibration(self.arm, self.robot_type, self.name, "follower")
-
-            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)
-
-    def get_observation(self) -> dict[str, np.ndarray]:
+    def get_observation(self) -> dict[str, Any]:
         """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()`."
-            )
+            raise DeviceNotConnectedError(f"{self} is not connected.")
 
         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
+        start = time.perf_counter()
+        obs_dict[OBS_STATE] = self.arm.sync_read("Present_Position")
+        dt_ms = (time.perf_counter() - start) * 1e3
+        logger.debug(f"{self} read state: {dt_ms:.1f}ms")
 
         # Capture images from cameras
         for cam_key, cam in self.cameras.items():
-            before_camread_t = time.perf_counter()
+            start = 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
+            dt_ms = (time.perf_counter() - start) * 1e3
+            logger.debug(f"{self} read {cam_key}: {dt_ms:.1f}ms")
 
         return obs_dict
 
-    def send_action(self, action: np.ndarray) -> np.ndarray:
+    def send_action(self, action: dict[str, float]) -> dict[str, float]:
         """Command arm to move to a target joint configuration.
 
         The relative action magnitude may be clipped depending on the configuration parameter
@@ -195,44 +198,33 @@ class ViperXRobot(Robot):
         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.
+            action (dict[str, float]): The goal positions for the motors.
 
         Returns:
-            np.ndarray: the action sent to the motors, potentially clipped.
+            dict[str, float]: 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()`."
-            )
+            raise DeviceNotConnectedError(f"{self} is not connected.")
 
         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)
+            present_pos = self.arm.sync_read("Present_Position")
+            goal_present_pos = {key: (g_pos, present_pos[key]) for key, g_pos in goal_pos.items()}
+            goal_pos = ensure_safe_goal_position(goal_present_pos, self.config.max_relative_target)
 
         # Send goal position to the arm
-        self.arm.write("Goal_Position", goal_pos.astype(np.int32))
-
+        self.arm.sync_write("Goal_Position", goal_pos)
         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."
-            )
+            raise DeviceNotConnectedError(f"{self} is not connected.")
 
-        self.arm.disconnect()
+        self.arm.disconnect(self.config.disable_torque_on_disconnect)
         for cam in self.cameras.values():
             cam.disconnect()
 
-        self.is_connected = False
+        logger.info(f"{self} disconnected.")
diff --git a/lerobot/common/teleoperators/widowx/configuration_widowx.py b/lerobot/common/teleoperators/widowx/configuration_widowx.py
index 896405e9..6aa5810b 100644
--- a/lerobot/common/teleoperators/widowx/configuration_widowx.py
+++ b/lerobot/common/teleoperators/widowx/configuration_widowx.py
@@ -22,17 +22,4 @@ 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
+    port: str  # Port to connect to the arm
diff --git a/lerobot/common/teleoperators/widowx/teleop_widowx.py b/lerobot/common/teleoperators/widowx/teleop_widowx.py
index c1aca4a9..b9997abb 100644
--- a/lerobot/common/teleoperators/widowx/teleop_widowx.py
+++ b/lerobot/common/teleoperators/widowx/teleop_widowx.py
@@ -14,22 +14,22 @@
 # 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 import Motor, MotorNormMode, TorqueMode
+from lerobot.common.motors import Motor, MotorCalibration, MotorNormMode
 from lerobot.common.motors.dynamixel import (
+    DriveMode,
     DynamixelMotorsBus,
-    run_arm_calibration,
+    OperatingMode,
 )
 
 from ..teleoperator import Teleoperator
 from .configuration_widowx import WidowXTeleopConfig
 
+logger = logging.getLogger(__name__)
+
 
 class WidowXTeleop(Teleoperator):
     """
@@ -42,8 +42,6 @@ class WidowXTeleop(Teleoperator):
     def __init__(self, config: WidowXTeleopConfig):
         super().__init__(config)
         self.config = config
-        self.robot_type = config.type
-
         self.arm = DynamixelMotorsBus(
             port=self.config.port,
             motors={
@@ -59,9 +57,6 @@ class WidowXTeleop(Teleoperator):
             },
         )
 
-        self.is_connected = False
-        self.logs = {}
-
     @property
     def action_feature(self) -> dict:
         return {
@@ -74,84 +69,85 @@ class WidowXTeleop(Teleoperator):
     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")
+    @property
+    def is_connected(self) -> bool:
+        return self.arm.is_connected
 
     def connect(self):
         if self.is_connected:
-            raise DeviceAlreadyConnectedError(
-                "ManipulatorRobot is already connected. Do not run `robot.connect()` twice."
-            )
+            raise DeviceAlreadyConnectedError(f"{self} already connected")
 
-        logging.info("Connecting arm.")
         self.arm.connect()
+        if not self.is_calibrated:
+            self.calibrate()
 
-        # 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
+        self.configure()
+        logger.info(f"{self} connected.")
 
     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].
-        """
-        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 '{self.calibration_fpath}'")
-            calibration = run_arm_calibration(self.arm, self.robot_type, self.name, "leader")
+        raise NotImplementedError  # TODO(aliberts): adapt code below (copied from koch)
+        logger.info(f"\nRunning calibration of {self}")
+        self.arm.disable_torque()
+        for name in self.arm.names:
+            self.arm.write("Operating_Mode", name, OperatingMode.EXTENDED_POSITION.value)
 
-            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.write("Drive_Mode", "elbow_flex", DriveMode.INVERTED.value)
+        drive_modes = {name: 1 if name == "elbow_flex" else 0 for name in self.arm.names}
 
-        self.arm.set_calibration(calibration)
+        input("Move robot to the middle of its range of motion and press ENTER....")
+        homing_offsets = self.arm.set_half_turn_homings()
 
-    def get_action(self) -> np.ndarray:
-        """The returned action does not have a batch dimension."""
-        # Read arm position
-        before_read_t = time.perf_counter()
+        full_turn_motors = ["shoulder_pan", "wrist_roll"]
+        unknown_range_motors = [name for name in self.arm.names if name not in full_turn_motors]
+        logger.info(
+            f"Move all joints except {full_turn_motors} sequentially through their "
+            "entire ranges of motion.\nRecording positions. Press ENTER to stop..."
+        )
+        range_mins, range_maxes = self.arm.record_ranges_of_motion(unknown_range_motors)
+        for name in full_turn_motors:
+            range_mins[name] = 0
+            range_maxes[name] = 4095
+
+        self.calibration = {}
+        for name, motor in self.arm.motors.items():
+            self.calibration[name] = MotorCalibration(
+                id=motor.id,
+                drive_mode=drive_modes[name],
+                homing_offset=homing_offsets[name],
+                range_min=range_mins[name],
+                range_max=range_maxes[name],
+            )
+
+        self.arm.write_calibration(self.calibration)
+        self._save_calibration()
+        logger.info(f"Calibration saved to {self.calibration_fpath}")
+
+    def configure(self) -> None:
+        self.arm.disable_torque()
+        self.arm.configure_motors()
+
+        # 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.
+        self.arm.write("Secondary_ID", "shoulder_shadow", 2)
+        self.arm.write("Secondary_ID", "elbow_shadow", 4)
+
+    def get_action(self) -> dict[str, float]:
+        if not self.is_connected:
+            raise DeviceNotConnectedError(f"{self} is not connected.")
+
+        start = time.perf_counter()
         action = self.arm.read("Present_Position")
-        self.logs["read_pos_dt_s"] = time.perf_counter() - before_read_t
-
+        dt_ms = (time.perf_counter() - start) * 1e3
+        logger.debug(f"{self} read action: {dt_ms:.1f}ms")
         return action
 
-    def send_feedback(self, feedback: np.ndarray) -> None:
-        # TODO(rcadene, aliberts): Implement force feedback
-        pass
+    def send_feedback(self, feedback: dict[str, float]) -> None:
+        raise NotImplementedError
 
     def disconnect(self) -> None:
         if not self.is_connected:
-            raise DeviceNotConnectedError(
-                "ManipulatorRobot is not connected. You need to run `robot.connect()` before disconnecting."
-            )
+            raise DeviceNotConnectedError(f"{self} is not connected.")
 
         self.arm.disconnect()
-        self.is_connected = False
+        logger.info(f"{self} disconnected.")

From 3848a8f9aa765ce73914e8511b4fd92b4ddbfac5 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Thu, 3 Apr 2025 18:37:21 +0200
Subject: [PATCH 165/171] Rename viperx & widowx

---
 lerobot/common/robots/viperx/__init__.py                  | 2 ++
 .../viperx/{configuration_viperx.py => config_viperx.py}  | 2 +-
 .../common/robots/viperx/{robot_viperx.py => viperx.py}   | 8 ++++----
 lerobot/common/teleoperators/widowx/__init__.py           | 6 ++----
 .../widowx/{configuration_widowx.py => config_widowx.py}  | 2 +-
 .../teleoperators/widowx/{teleop_widowx.py => widowx.py}  | 8 ++++----
 6 files changed, 14 insertions(+), 14 deletions(-)
 create mode 100644 lerobot/common/robots/viperx/__init__.py
 rename lerobot/common/robots/viperx/{configuration_viperx.py => config_viperx.py} (97%)
 rename lerobot/common/robots/viperx/{robot_viperx.py => viperx.py} (98%)
 rename lerobot/common/teleoperators/widowx/{configuration_widowx.py => config_widowx.py} (94%)
 rename lerobot/common/teleoperators/widowx/{teleop_widowx.py => widowx.py} (96%)

diff --git a/lerobot/common/robots/viperx/__init__.py b/lerobot/common/robots/viperx/__init__.py
new file mode 100644
index 00000000..522d02f1
--- /dev/null
+++ b/lerobot/common/robots/viperx/__init__.py
@@ -0,0 +1,2 @@
+from .config_viperx import ViperXConfig
+from .viperx import ViperX
diff --git a/lerobot/common/robots/viperx/configuration_viperx.py b/lerobot/common/robots/viperx/config_viperx.py
similarity index 97%
rename from lerobot/common/robots/viperx/configuration_viperx.py
rename to lerobot/common/robots/viperx/config_viperx.py
index e6c68b18..e135e278 100644
--- a/lerobot/common/robots/viperx/configuration_viperx.py
+++ b/lerobot/common/robots/viperx/config_viperx.py
@@ -7,7 +7,7 @@ from ..config import RobotConfig
 
 @RobotConfig.register_subclass("viperx")
 @dataclass
-class ViperXRobotConfig(RobotConfig):
+class ViperXConfig(RobotConfig):
     port: str  # Port to connect to the arm
 
     disable_torque_on_disconnect: bool = True
diff --git a/lerobot/common/robots/viperx/robot_viperx.py b/lerobot/common/robots/viperx/viperx.py
similarity index 98%
rename from lerobot/common/robots/viperx/robot_viperx.py
rename to lerobot/common/robots/viperx/viperx.py
index fc11b603..744fbc87 100644
--- a/lerobot/common/robots/viperx/robot_viperx.py
+++ b/lerobot/common/robots/viperx/viperx.py
@@ -19,22 +19,22 @@ from lerobot.common.motors.dynamixel import (
 
 from ..robot import Robot
 from ..utils import ensure_safe_goal_position
-from .configuration_viperx import ViperXRobotConfig
+from .config_viperx import ViperXConfig
 
 logger = logging.getLogger(__name__)
 
 
-class ViperXRobot(Robot):
+class ViperX(Robot):
     """
     [ViperX](https://www.trossenrobotics.com/viperx-300) developed by Trossen Robotics
     """
 
-    config_class = ViperXRobotConfig
+    config_class = ViperXConfig
     name = "viperx"
 
     def __init__(
         self,
-        config: ViperXRobotConfig,
+        config: ViperXConfig,
     ):
         super().__init__(config)
         self.config = config
diff --git a/lerobot/common/teleoperators/widowx/__init__.py b/lerobot/common/teleoperators/widowx/__init__.py
index c67f0625..122ee329 100644
--- a/lerobot/common/teleoperators/widowx/__init__.py
+++ b/lerobot/common/teleoperators/widowx/__init__.py
@@ -1,4 +1,2 @@
-from .configuration_widowx import WidowXTeleopConfig
-from .teleop_widowx import WidowXTeleop
-
-__all__ = ["WidowXTeleopConfig", "WidowXTeleop"]
+from .config_widowx import WidowXConfig
+from .widowx import WidowX
diff --git a/lerobot/common/teleoperators/widowx/configuration_widowx.py b/lerobot/common/teleoperators/widowx/config_widowx.py
similarity index 94%
rename from lerobot/common/teleoperators/widowx/configuration_widowx.py
rename to lerobot/common/teleoperators/widowx/config_widowx.py
index 6aa5810b..42fae12d 100644
--- a/lerobot/common/teleoperators/widowx/configuration_widowx.py
+++ b/lerobot/common/teleoperators/widowx/config_widowx.py
@@ -21,5 +21,5 @@ from ..config import TeleoperatorConfig
 
 @TeleoperatorConfig.register_subclass("widowx")
 @dataclass
-class WidowXTeleopConfig(TeleoperatorConfig):
+class WidowXConfig(TeleoperatorConfig):
     port: str  # Port to connect to the arm
diff --git a/lerobot/common/teleoperators/widowx/teleop_widowx.py b/lerobot/common/teleoperators/widowx/widowx.py
similarity index 96%
rename from lerobot/common/teleoperators/widowx/teleop_widowx.py
rename to lerobot/common/teleoperators/widowx/widowx.py
index b9997abb..8b452055 100644
--- a/lerobot/common/teleoperators/widowx/teleop_widowx.py
+++ b/lerobot/common/teleoperators/widowx/widowx.py
@@ -26,20 +26,20 @@ from lerobot.common.motors.dynamixel import (
 )
 
 from ..teleoperator import Teleoperator
-from .configuration_widowx import WidowXTeleopConfig
+from .config_widowx import WidowXConfig
 
 logger = logging.getLogger(__name__)
 
 
-class WidowXTeleop(Teleoperator):
+class WidowX(Teleoperator):
     """
     [WidowX](https://www.trossenrobotics.com/widowx-250) developed by Trossen Robotics
     """
 
-    config_class = WidowXTeleopConfig
+    config_class = WidowXConfig
     name = "widowx"
 
-    def __init__(self, config: WidowXTeleopConfig):
+    def __init__(self, config: WidowXConfig):
         super().__init__(config)
         self.config = config
         self.arm = DynamixelMotorsBus(

From 716029b1e3538d4712c0ae3ccf6b0b01210f9de8 Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Thu, 3 Apr 2025 18:42:39 +0200
Subject: [PATCH 166/171] Remove old calibration

---
 lerobot/common/motors/calibration.py | 178 ---------------------------
 1 file changed, 178 deletions(-)
 delete mode 100644 lerobot/common/motors/calibration.py

diff --git a/lerobot/common/motors/calibration.py b/lerobot/common/motors/calibration.py
deleted file mode 100644
index 3fbed56d..00000000
--- a/lerobot/common/motors/calibration.py
+++ /dev/null
@@ -1,178 +0,0 @@
-#!/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 select
-import sys
-import time
-from dataclasses import dataclass
-from pathlib import Path
-
-from .dynamixel.dynamixel import DynamixelMotorsBus
-from .feetech.feetech import FeetechMotorsBus
-from .motors_bus import MotorsBus
-
-
-@dataclass
-class MotorCalibration:
-    name: str
-    drive_mode: int
-    homing_offset: int
-    range_min: int
-    range_max: int
-
-
-def find_offset(motorbus: MotorsBus):
-    input("Move robot to the middle of its range of motion and press ENTER....")
-    for name in motorbus.names:
-        # Also reset to defaults
-        if isinstance(motorbus, FeetechMotorsBus):
-            motorbus.write("Offset", name, 0, raw_value=True)
-            motorbus.write("Min_Angle_Limit", name, 0, raw_value=True)
-            motorbus.write("Max_Angle_Limit", name, 4095, raw_value=True)
-        elif isinstance(motorbus, DynamixelMotorsBus):
-            motorbus.write("Homing_Offset", name, 0, raw_value=True)
-            motorbus.write("Min_Position_Limit", name, 0, raw_value=True)
-            motorbus.write("Max_Position_Limit", name, 4095, raw_value=True)
-        else:
-            raise ValueError("Motorbus instance is unknown")
-
-    middle_values = motorbus.sync_read("Present_Position", raw_values=True)
-
-    offsets = {}
-    for name, pos in middle_values.items():
-        offset = pos - 2047  # Center the middle reading at 2047.
-        set_offset(motorbus, offset, name)
-        offsets[name] = offset
-
-    return offsets
-
-
-def find_min_max(motorbus: MotorsBus):
-    print("Move all joints (except wrist_roll; id = 5) sequentially through their entire ranges of motion.")
-    print("Recording positions. Press ENTER to stop...")
-
-    recorded_data = {name: [] for name in motorbus.names}
-
-    while True:
-        positions = motorbus.sync_read("Present_Position", raw_values=True)
-        for name in motorbus.names:
-            recorded_data[name].append(positions[name])
-        time.sleep(0.01)
-
-        # Check if user pressed Enter
-        ready_to_read, _, _ = select.select([sys.stdin], [], [], 0)
-        if ready_to_read:
-            line = sys.stdin.readline()
-            if line.strip() == "":
-                break
-
-    min_max = {}
-    for name in motorbus.names:
-        motor_values = recorded_data[name]
-        raw_min = min(motor_values)
-        raw_max = max(motor_values)
-
-        if name == "wrist_roll":
-            physical_min = 0
-            physical_max = 4095
-        else:
-            physical_min = int(raw_min)
-            physical_max = int(raw_max)
-
-        set_min_max(motorbus, physical_min, physical_max, name)
-        min_max[name] = {"min": physical_min, "max": physical_max}
-
-    return min_max
-
-
-def set_calibration(motorbus: MotorsBus, calibration_fpath: Path) -> None:
-    with open(calibration_fpath) as f:
-        calibration = json.load(f)
-
-    motorbus.calibration = {int(id_): val for id_, val in calibration.items()}
-
-    for _, cal_data in motorbus.calibration.items():
-        name = cal_data.get("name")
-        if name not in motorbus.names:
-            print(f"Motor name '{name}' from calibration not found in arm names.")
-            continue
-
-        set_offset(motorbus, cal_data["homing_offset"], name)
-        set_min_max(motorbus, cal_data["min"], cal_data["max"], name)
-
-
-def set_offset(motorbus: MotorsBus, homing_offset: int, name: str):
-    homing_offset = int(homing_offset)
-
-    # Clamp to [-2047..+2047]
-    if homing_offset > 2047:
-        homing_offset = 2047
-        print(
-            f"Warning: '{homing_offset}' is getting clamped because its larger then 2047; This should not happen!"
-        )
-    elif homing_offset < -2047:
-        homing_offset = -2047
-        print(
-            f"Warning: '{homing_offset}' is getting clamped because its smaller then -2047; This should not happen!"
-        )
-
-    direction_bit = 1 if homing_offset < 0 else 0  # Determine the direction (sign) bit and magnitude
-    magnitude = abs(homing_offset)
-    servo_offset = (
-        direction_bit << 11
-    ) | magnitude  # Combine sign bit (bit 11) with the magnitude (bits 0..10)
-
-    if isinstance(motorbus, FeetechMotorsBus):
-        motorbus.write("Offset", name, servo_offset, raw_value=True)
-        read_offset = motorbus.sync_read("Offset", name, raw_values=True)
-    elif isinstance(motorbus, DynamixelMotorsBus):
-        motorbus.write("Homing_Offset", name, servo_offset, raw_value=True)
-        read_offset = motorbus.sync_read("Homing_Offset", name, raw_values=True)
-    else:
-        raise ValueError("Motorbus instance is unknown")
-
-    if read_offset[name] != servo_offset:
-        raise ValueError(
-            f"Offset not set correctly for motor '{name}'. read: {read_offset} does not equal {servo_offset}"
-        )
-
-
-def set_min_max(motorbus: MotorsBus, min: int, max: int, name: str):
-    if isinstance(motorbus, FeetechMotorsBus):
-        motorbus.write("Min_Angle_Limit", name, min, raw_value=True)
-        motorbus.write("Max_Angle_Limit", name, max, raw_value=True)
-
-        read_min = motorbus.sync_read("Min_Angle_Limit", name, raw_values=True)
-        read_max = motorbus.sync_read("Max_Angle_Limit", name, raw_values=True)
-    elif isinstance(motorbus, DynamixelMotorsBus):
-        motorbus.write("Min_Position_Limit", name, min, raw_value=True)
-        motorbus.write("Max_Position_Limit", name, max, raw_value=True)
-
-        read_min = motorbus.sync_read("Min_Position_Limit", name, raw_values=True)
-        read_max = motorbus.sync_read("Max_Position_Limit", name, raw_values=True)
-    else:
-        raise ValueError("Motorbus instance is unknown")
-
-    if read_min[name] != min:
-        raise ValueError(
-            f"Min is not set correctly for motor '{name}'. read: {read_min} does not equal {min}"
-        )
-
-    if read_max[name] != max:
-        raise ValueError(
-            f"Max is not set correctly for motor '{name}'. read: {read_max} does not equal {max}"
-        )

From 99c0938b42c4dbb3b3b750cde48b6d46e51c82a4 Mon Sep 17 00:00:00 2001
From: Steven Palma <imstevenpmwork@ieee.org>
Date: Fri, 4 Apr 2025 09:45:18 +0200
Subject: [PATCH 167/171] feat(teleop): thread-safe keyboard teleop
 implementation (#869)

Co-authored-by: Simon Alibert <75076266+aliberts@users.noreply.github.com>
---
 .../teleoperators/keyboard/teleop_keyboard.py | 35 +++++++++++++------
 .../keyboard/teleop_keyboard_app.py           | 28 +++++++++++++++
 2 files changed, 53 insertions(+), 10 deletions(-)
 create mode 100755 lerobot/common/teleoperators/keyboard/teleop_keyboard_app.py

diff --git a/lerobot/common/teleoperators/keyboard/teleop_keyboard.py b/lerobot/common/teleoperators/keyboard/teleop_keyboard.py
index a0f0ab21..65f1dff7 100644
--- a/lerobot/common/teleoperators/keyboard/teleop_keyboard.py
+++ b/lerobot/common/teleoperators/keyboard/teleop_keyboard.py
@@ -18,6 +18,7 @@ import logging
 import os
 import sys
 import time
+from queue import Queue
 
 import numpy as np
 
@@ -28,7 +29,6 @@ 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.")
@@ -56,7 +56,8 @@ class KeyboardTeleop(Teleoperator):
         self.config = config
         self.robot_type = config.type
 
-        self.pressed_keys = {}
+        self.event_queue = Queue()
+        self.current_pressed = {}
         self.listener = None
         self.is_connected = False
         self.logs = {}
@@ -97,23 +98,35 @@ class KeyboardTeleop(Teleoperator):
 
     def on_press(self, key):
         if hasattr(key, "char"):
-            self.pressed_keys[key.char] = True
+            self.event_queue.put((key.char, True))
 
     def on_release(self, key):
         if hasattr(key, "char"):
-            self.pressed_keys[key.char] = False
+            self.event_queue.put((key.char, False))
         if key == keyboard.Key.esc:
             logging.info("ESC pressed, disconnecting.")
             self.disconnect()
 
+    def _drain_pressed_keys(self):
+        while not self.event_queue.empty():
+            key_char, is_pressed = self.event_queue.get_nowait()
+            self.current_pressed[key_char] = is_pressed
+
     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}
+
+        if not self.is_connected:
+            raise DeviceNotConnectedError(
+                "KeyboardTeleop is not connected. You need to run `connect()` before `get_action()`."
+            )
+
+        self._drain_pressed_keys()
+
+        # Generate action based on current key states
+        action = {key for key, val in self.current_pressed.items() if val}
         self.logs["read_pos_dt_s"] = time.perf_counter() - before_read_t
 
-        return action
+        return np.array(list(action))
 
     def send_feedback(self, feedback: np.ndarray) -> None:
         pass
@@ -121,7 +134,9 @@ class KeyboardTeleop(Teleoperator):
     def disconnect(self) -> None:
         if not self.is_connected:
             raise DeviceNotConnectedError(
-                "ManipulatorRobot is not connected. You need to run `robot.connect()` before disconnecting."
+                "KeyboardTeleop is not connected. You need to run `robot.connect()` before `disconnect()`."
             )
-        self.listener.stop()
+        if self.listener is not None:
+            self.listener.stop()
+
         self.is_connected = False
diff --git a/lerobot/common/teleoperators/keyboard/teleop_keyboard_app.py b/lerobot/common/teleoperators/keyboard/teleop_keyboard_app.py
new file mode 100755
index 00000000..4f463814
--- /dev/null
+++ b/lerobot/common/teleoperators/keyboard/teleop_keyboard_app.py
@@ -0,0 +1,28 @@
+import logging
+import time
+
+from lerobot.common.teleoperators.keyboard import KeyboardTeleop, KeyboardTeleopConfig
+
+
+def main():
+    logging.info("Configuring Keyboard Teleop")
+    keyboard_config = KeyboardTeleopConfig()
+    keyboard = KeyboardTeleop(keyboard_config)
+
+    logging.info("Connecting Keyboard Teleop")
+    keyboard.connect()
+
+    logging.info("Starting Keyboard capture")
+    i = 0
+    while i < 20:
+        action = keyboard.get_action()
+        print("Captured keys: %s", action)
+        time.sleep(1)
+        i += 1
+
+    keyboard.disconnect()
+    logging.info("Finished LeKiwiRobot cleanly")
+
+
+if __name__ == "__main__":
+    main()

From e998dddcfa3339830348689c83a5976a9b8a6e7c Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Tue, 8 Apr 2025 10:46:29 +0200
Subject: [PATCH 168/171] Add support for feetech scs series + various fixes

---
 lerobot/common/motors/feetech/feetech.py | 114 ++++++++++-----
 lerobot/common/motors/feetech/tables.py  | 141 ++++++++++++++++---
 lerobot/common/motors/motors_bus.py      | 170 ++++++++++-------------
 tests/mocks/mock_feetech.py              |  10 +-
 tests/motors/test_feetech.py             | 163 ++--------------------
 5 files changed, 291 insertions(+), 307 deletions(-)

diff --git a/lerobot/common/motors/feetech/feetech.py b/lerobot/common/motors/feetech/feetech.py
index f97a8a98..064927b0 100644
--- a/lerobot/common/motors/feetech/feetech.py
+++ b/lerobot/common/motors/feetech/feetech.py
@@ -21,19 +21,22 @@ from lerobot.common.utils.encoding_utils import decode_sign_magnitude, encode_si
 
 from ..motors_bus import Motor, MotorCalibration, MotorsBus, NameOrID, Value
 from .tables import (
-    AVAILABLE_BAUDRATES,
-    ENCODINGS,
+    FIRMWARE_VERSION,
     MODEL_BAUDRATE_TABLE,
     MODEL_CONTROL_TABLE,
+    MODEL_ENCODING_TABLE,
     MODEL_NUMBER,
+    MODEL_NUMBER_TABLE,
     MODEL_RESOLUTION,
-    NORMALIZATION_REQUIRED,
+    SCAN_BAUDRATES,
 )
 
 PROTOCOL_VERSION = 0
 BAUDRATE = 1_000_000
 DEFAULT_TIMEOUT_MS = 1000
 
+NORMALIZED_DATA = ["Goal_Position", "Present_Position"]
+
 logger = logging.getLogger(__name__)
 
 
@@ -80,16 +83,14 @@ class FeetechMotorsBus(MotorsBus):
     python feetech sdk to communicate with the motors, which is itself based on the dynamixel sdk.
     """
 
-    available_baudrates = deepcopy(AVAILABLE_BAUDRATES)
+    available_baudrates = deepcopy(SCAN_BAUDRATES)
     default_timeout = DEFAULT_TIMEOUT_MS
     model_baudrate_table = deepcopy(MODEL_BAUDRATE_TABLE)
     model_ctrl_table = deepcopy(MODEL_CONTROL_TABLE)
-    model_number_table = deepcopy(MODEL_NUMBER)
+    model_encoding_table = deepcopy(MODEL_ENCODING_TABLE)
+    model_number_table = deepcopy(MODEL_NUMBER_TABLE)
     model_resolution_table = deepcopy(MODEL_RESOLUTION)
-    normalization_required = deepcopy(NORMALIZATION_REQUIRED)
-
-    # Feetech specific
-    encodings = deepcopy(ENCODINGS)
+    normalized_data = deepcopy(NORMALIZED_DATA)
 
     def __init__(
         self,
@@ -140,13 +141,25 @@ class FeetechMotorsBus(MotorsBus):
             self.write("Torque_Enable", motor, TorqueMode.ENABLED.value)
             self.write("Lock", motor, 1)
 
-    def _encode_value(self, value: int, data_name: str | None = None, n_bytes: int | None = None) -> int:
-        sign_bit = self.encodings.get(data_name)
-        return encode_sign_magnitude(value, sign_bit) if sign_bit is not None else value
+    def _encode_sign(self, data_name: str, ids_values: dict[int, int]) -> dict[int, int]:
+        for id_ in ids_values:
+            model = self._id_to_model(id_)
+            encoding_table = self.model_encoding_table.get(model)
+            if encoding_table and data_name in encoding_table:
+                sign_bit = encoding_table[data_name]
+                ids_values[id_] = encode_sign_magnitude(ids_values[id_], sign_bit)
 
-    def _decode_value(self, value: int, data_name: str | None = None, n_bytes: int | None = None) -> int:
-        sign_bit = self.encodings.get(data_name)
-        return decode_sign_magnitude(value, sign_bit) if sign_bit is not None else value
+        return ids_values
+
+    def _decode_sign(self, data_name: str, ids_values: dict[int, int]) -> dict[int, int]:
+        for id_ in ids_values:
+            model = self._id_to_model(id_)
+            encoding_table = self.model_encoding_table.get(model)
+            if encoding_table and data_name in encoding_table:
+                sign_bit = encoding_table[data_name]
+                ids_values[id_] = decode_sign_magnitude(ids_values[id_], sign_bit)
+
+        return ids_values
 
     @staticmethod
     def _split_int_to_bytes(value: int, n_bytes: int) -> list[int]:
@@ -220,15 +233,15 @@ class FeetechMotorsBus(MotorsBus):
                 return data_list, scs.COMM_RX_CORRUPT
 
             # find packet header
-            for id_ in range(0, (rx_length - 1)):
-                if (rxpacket[id_] == 0xFF) and (rxpacket[id_ + 1] == 0xFF):
+            for idx in range(0, (rx_length - 1)):
+                if (rxpacket[idx] == 0xFF) and (rxpacket[idx + 1] == 0xFF):
                     break
 
-            if id_ == 0:  # found at the beginning of the packet
+            if idx == 0:  # found at the beginning of the packet
                 # calculate checksum
                 checksum = 0
-                for id_ in range(2, status_length - 1):  # except header & checksum
-                    checksum += rxpacket[id_]
+                for idx in range(2, status_length - 1):  # except header & checksum
+                    checksum += rxpacket[idx]
 
                 checksum = scs.SCS_LOBYTE(~checksum)
                 if rxpacket[status_length - 1] == checksum:
@@ -247,34 +260,71 @@ class FeetechMotorsBus(MotorsBus):
                     rx_length = rx_length - 2
             else:
                 # remove unnecessary packets
-                del rxpacket[0:id_]
-                rx_length = rx_length - id_
+                del rxpacket[0:idx]
+                rx_length = rx_length - idx
 
     def broadcast_ping(self, num_retry: int = 0, raise_on_error: bool = False) -> dict[int, int] | None:
         for n_try in range(1 + num_retry):
             ids_status, comm = self._broadcast_ping()
             if self._is_comm_success(comm):
                 break
-            logger.debug(f"Broadcast failed on port '{self.port}' ({n_try=})")
-            logger.debug(self.packet_handler.getRxPacketError(comm))
+            logger.debug(f"Broadcast ping failed on port '{self.port}' ({n_try=})")
+            logger.debug(self.packet_handler.getTxRxResult(comm))
 
         if not self._is_comm_success(comm):
             if raise_on_error:
-                raise ConnectionError(self.packet_handler.getRxPacketError(comm))
-
-            return ids_status if ids_status else None
+                raise ConnectionError(self.packet_handler.getTxRxResult(comm))
+            return
 
         ids_errors = {id_: status for id_, status in ids_status.items() if self._is_error(status)}
         if ids_errors:
             display_dict = {id_: self.packet_handler.getRxPacketError(err) for id_, err in ids_errors.items()}
             logger.error(f"Some motors found returned an error status:\n{pformat(display_dict, indent=4)}")
-        comm, model_numbers = self._sync_read(
-            "Model_Number", list(ids_status), model="scs_series", num_retry=num_retry
-        )
+
+        return self._get_model_number(list(ids_status), raise_on_error)
+
+    def _get_firmware_version(self, motor_ids: list[int], raise_on_error: bool = False) -> dict[int, int]:
+        # comm, major = self._sync_read(*FIRMWARE_MAJOR_VERSION, motor_ids)
+        # if not self._is_comm_success(comm):
+        #     if raise_on_error:
+        #         raise ConnectionError(self.packet_handler.getTxRxResult(comm))
+        #     return
+
+        # comm, minor = self._sync_read(*FIRMWARE_MINOR_VERSION, motor_ids)
+        # if not self._is_comm_success(comm):
+        #     if raise_on_error:
+        #         raise ConnectionError(self.packet_handler.getTxRxResult(comm))
+        #     return
+
+        # return {id_: f"{major[id_]}.{minor[id_]}" for id_ in motor_ids}
+
+        comm, firmware_versions = self._sync_read(*FIRMWARE_VERSION, motor_ids)
         if not self._is_comm_success(comm):
             if raise_on_error:
-                raise ConnectionError(self.packet_handler.getRxPacketError(comm))
+                raise ConnectionError(self.packet_handler.getTxRxResult(comm))
+            return
 
-            return model_numbers if model_numbers else None
+        return firmware_versions
+
+    def _get_model_number(self, motor_ids: list[int], raise_on_error: bool = False) -> dict[int, int]:
+        # comm, major = self._sync_read(*MODEL_MAJOR_VERSION, motor_ids)
+        # if not self._is_comm_success(comm):
+        #     if raise_on_error:
+        #         raise ConnectionError(self.packet_handler.getTxRxResult(comm))
+        #     return
+
+        # comm, minor = self._sync_read(*MODEL_MINOR_VERSION, motor_ids)
+        # if not self._is_comm_success(comm):
+        #     if raise_on_error:
+        #         raise ConnectionError(self.packet_handler.getTxRxResult(comm))
+        #     return
+
+        # return {id_: f"{major[id_]}.{minor[id_]}" for id_ in motor_ids}
+
+        comm, model_numbers = self._sync_read(*MODEL_NUMBER, motor_ids)
+        if not self._is_comm_success(comm):
+            if raise_on_error:
+                raise ConnectionError(self.packet_handler.getTxRxResult(comm))
+            return
 
         return model_numbers
diff --git a/lerobot/common/motors/feetech/tables.py b/lerobot/common/motors/feetech/tables.py
index 5df1ea59..0fa2fa84 100644
--- a/lerobot/common/motors/feetech/tables.py
+++ b/lerobot/common/motors/feetech/tables.py
@@ -1,10 +1,22 @@
+FIRMWARE_MAJOR_VERSION = (0, 1)
+FIRMWARE_MINOR_VERSION = (1, 1)
+MODEL_MAJOR_VERSION = (3, 1)
+MODEL_MINOR_VERSION = (4, 1)
+
+FIRMWARE_VERSION = (0, 2)
+MODEL_NUMBER = (3, 2)
+
 # See this link for STS3215 Memory Table:
 # https://docs.google.com/spreadsheets/d/1GVs7W1VS1PqdhA1nW-abeyAHhTUxKUdR/edit?usp=sharing&ouid=116566590112741600240&rtpof=true&sd=true
 # data_name: (address, size_byte)
-SCS_SERIES_CONTROL_TABLE = {
+STS_SMS_SERIES_CONTROL_TABLE = {
     # EPROM
-    "Firmware_Version": (0, 2),
-    "Model_Number": (3, 2),
+    "Firmware_Version": FIRMWARE_VERSION,  # read-only
+    "Model_Number": MODEL_NUMBER,  # read-only
+    # "Firmware_Major_Version": FIRMWARE_MAJOR_VERSION,  # read-only
+    # "Firmware_Minor_Version": FIRMWARE_MINOR_VERSION,  # read-only
+    # "Model_Major_Version": MODEL_MAJOR_VERSION,  # read-only
+    # "Model_Minor_Version": MODEL_MINOR_VERSION,
     "ID": (5, 1),
     "Baud_Rate": (6, 1),
     "Return_Delay_Time": (7, 1),
@@ -42,18 +54,75 @@ SCS_SERIES_CONTROL_TABLE = {
     "Goal_Speed": (46, 2),
     "Torque_Limit": (48, 2),
     "Lock": (55, 1),
-    "Present_Position": (56, 2),
-    "Present_Speed": (58, 2),
-    "Present_Load": (60, 2),
-    "Present_Voltage": (62, 1),
-    "Present_Temperature": (63, 1),
-    "Status": (65, 1),
-    "Moving": (66, 1),
-    "Present_Current": (69, 2),
+    "Present_Position": (56, 2),  # read-only
+    "Present_Speed": (58, 2),  # read-only
+    "Present_Load": (60, 2),  # read-only
+    "Present_Voltage": (62, 1),  # read-only
+    "Present_Temperature": (63, 1),  # read-only
+    "Status": (65, 1),  # read-only
+    "Moving": (66, 1),  # read-only
+    "Present_Current": (69, 2),  # read-only
     # Not in the Memory Table
     "Maximum_Acceleration": (85, 2),
 }
 
+SCS_SERIES_CONTROL_TABLE = {
+    # EPROM
+    "Firmware_Version": FIRMWARE_VERSION,  # read-only
+    "Model_Number": MODEL_NUMBER,  # read-only
+    # "Firmware_Major_Version": FIRMWARE_MAJOR_VERSION,  # read-only
+    # "Firmware_Minor_Version": FIRMWARE_MINOR_VERSION,  # read-only
+    # "Model_Major_Version": MODEL_MAJOR_VERSION,  # read-only
+    # "Model_Minor_Version": MODEL_MINOR_VERSION,
+    "ID": (5, 1),
+    "Baud_Rate": (6, 1),
+    "Return_Delay": (7, 1),
+    "Response_Status_Level": (8, 1),
+    "Min_Position_Limit": (9, 2),
+    "Max_Position_Limit": (11, 2),
+    "Max_Temperature_Limit": (13, 1),
+    "Max_Voltage_Limit": (14, 1),
+    "Min_Voltage_Limit": (15, 1),
+    "Max_Torque_Limit": (16, 2),
+    "Phase": (18, 1),
+    "Unloading_Condition": (19, 1),
+    "LED_Alarm_Condition": (20, 1),
+    "P_Coefficient": (21, 1),
+    "D_Coefficient": (22, 1),
+    "I_Coefficient": (23, 1),
+    "Minimum_Startup_Force": (24, 2),
+    "CW_Dead_Zone": (26, 1),
+    "CCW_Dead_Zone": (27, 1),
+    "Protective_Torque": (37, 1),
+    "Protection_Time": (38, 1),
+    # SRAM
+    "Torque_Enable": (40, 1),
+    "Acceleration": (41, 1),
+    "Goal_Position": (42, 2),
+    "Running_Time": (44, 2),
+    "Goal_Speed": (46, 2),
+    "Lock": (48, 1),
+    "Present_Position": (56, 2),  # read-only
+    "Present_Speed": (58, 2),  # read-only
+    "Present_Load": (60, 2),  # read-only
+    "Present_Voltage": (62, 1),  # read-only
+    "Present_Temperature": (63, 1),  # read-only
+    "Sync_Write_Flag": (64, 1),  # read-only
+    "Status": (65, 1),  # read-only
+    "Moving": (66, 1),  # read-only
+}
+
+STS_SMS_SERIES_BAUDRATE_TABLE = {
+    0: 1_000_000,
+    1: 500_000,
+    2: 250_000,
+    3: 128_000,
+    4: 115_200,
+    5: 57_600,
+    6: 38_400,
+    7: 19_200,
+}
+
 SCS_SERIES_BAUDRATE_TABLE = {
     0: 1_000_000,
     1: 500_000,
@@ -66,34 +135,52 @@ SCS_SERIES_BAUDRATE_TABLE = {
 }
 
 MODEL_CONTROL_TABLE = {
+    "sts_series": STS_SMS_SERIES_CONTROL_TABLE,
     "scs_series": SCS_SERIES_CONTROL_TABLE,
-    "sts3215": SCS_SERIES_CONTROL_TABLE,
+    "sms_series": STS_SMS_SERIES_CONTROL_TABLE,
+    "sts3215": STS_SMS_SERIES_CONTROL_TABLE,
+    "sts3250": STS_SMS_SERIES_CONTROL_TABLE,
+    "scs0009": SCS_SERIES_CONTROL_TABLE,
+    "sm8512bl": STS_SMS_SERIES_CONTROL_TABLE,
 }
 
 MODEL_RESOLUTION = {
-    "scs_series": 4096,
+    "sts_series": 4096,
+    "sms_series": 4096,
+    "scs_series": 1024,
     "sts3215": 4096,
-}
-
-# {model: model_number}
-MODEL_NUMBER = {
-    "sts3215": 777,
+    "sts3250": 4096,
+    "sm8512bl": 4096,
+    "scs0009": 1024,
 }
 
 MODEL_BAUDRATE_TABLE = {
+    "sts_series": STS_SMS_SERIES_BAUDRATE_TABLE,
+    "sms_series": STS_SMS_SERIES_BAUDRATE_TABLE,
     "scs_series": SCS_SERIES_BAUDRATE_TABLE,
-    "sts3215": SCS_SERIES_BAUDRATE_TABLE,
+    "sm8512bl": STS_SMS_SERIES_BAUDRATE_TABLE,
+    "sts3215": STS_SMS_SERIES_BAUDRATE_TABLE,
+    "sts3250": STS_SMS_SERIES_BAUDRATE_TABLE,
+    "scs0009": SCS_SERIES_BAUDRATE_TABLE,
 }
 
-NORMALIZATION_REQUIRED = ["Goal_Position", "Present_Position"]
-
 # Sign-Magnitude encoding bits
-ENCODINGS = {
+STS_SMS_SERIES_ENCODINGS_TABLE = {
     "Homing_Offset": 11,
     "Goal_Speed": 15,
 }
 
-AVAILABLE_BAUDRATES = [
+MODEL_ENCODING_TABLE = {
+    "sts_series": STS_SMS_SERIES_ENCODINGS_TABLE,
+    "sms_series": STS_SMS_SERIES_ENCODINGS_TABLE,
+    "scs_series": {},
+    "sts3215": STS_SMS_SERIES_ENCODINGS_TABLE,
+    "sts3250": STS_SMS_SERIES_ENCODINGS_TABLE,
+    "sm8512bl": STS_SMS_SERIES_ENCODINGS_TABLE,
+    "scs0009": {},
+}
+
+SCAN_BAUDRATES = [
     4_800,
     9_600,
     14_400,
@@ -106,3 +193,11 @@ AVAILABLE_BAUDRATES = [
     500_000,
     1_000_000,
 ]
+
+# {model: model_number}  TODO
+MODEL_NUMBER_TABLE = {
+    "sts3215": 777,
+    "sts3250": None,
+    "sm8512bl": None,
+    "scs0009": None,
+}
diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py
index 96cbb7c3..03f54452 100644
--- a/lerobot/common/motors/motors_bus.py
+++ b/lerobot/common/motors/motors_bus.py
@@ -25,7 +25,7 @@ from dataclasses import dataclass
 from enum import Enum
 from functools import cached_property
 from pprint import pformat
-from typing import Protocol, TypeAlias, overload
+from typing import Protocol, TypeAlias
 
 import serial
 from deepdiff import DeepDiff
@@ -257,9 +257,10 @@ class MotorsBus(abc.ABC):
     default_timeout: int
     model_baudrate_table: dict[str, dict]
     model_ctrl_table: dict[str, dict]
+    model_encoding_table: dict[str, dict]
     model_number_table: dict[str, int]
     model_resolution_table: dict[str, int]
-    normalization_required: list[str]
+    normalized_data: list[str]
 
     def __init__(
         self,
@@ -340,6 +341,24 @@ class MotorsBus(abc.ABC):
         else:
             raise TypeError(f"'{motor}' should be int, str.")
 
+    def _get_names_list(self, motors: str | list[str] | None) -> list[str]:
+        if motors is None:
+            return self.names
+        elif isinstance(motors, str):
+            return [motors]
+        elif isinstance(motors, list):
+            return motors.copy()
+        else:
+            raise TypeError(motors)
+
+    def _get_ids_values_dict(self, values: Value | dict[str, Value] | None) -> list[str]:
+        if isinstance(values, (int, float)):
+            return {id_: values for id_ in self.ids}
+        elif isinstance(values, dict):
+            return {self.motors[motor].id: val for motor, val in values.items()}
+        else:
+            raise TypeError(f"'values' is expected to be a single value or a dict. Got {values}")
+
     def _validate_motors(self) -> None:
         if len(self.ids) != len(set(self.ids)):
             raise ValueError(f"Some motors have the same id!\n{self}")
@@ -632,15 +651,11 @@ class MotorsBus(abc.ABC):
         return unnormalized_values
 
     @abc.abstractmethod
-    def _encode_value(
-        self, value: int, data_name: str | None = None, n_bytes: int | None = None
-    ) -> dict[int, int]:
+    def _encode_sign(self, data_name: str, ids_values: dict[int, int]) -> dict[int, int]:
         pass
 
     @abc.abstractmethod
-    def _decode_value(
-        self, value: int, data_name: str | None = None, n_bytes: int | None = None
-    ) -> dict[int, int]:
+    def _decode_sign(self, data_name: str, ids_values: dict[int, int]) -> dict[int, int]:
         pass
 
     @staticmethod
@@ -691,7 +706,7 @@ class MotorsBus(abc.ABC):
 
         if not self._is_comm_success(comm):
             if raise_on_error:
-                raise ConnectionError(self.packet_handler.getRxPacketError(comm))
+                raise ConnectionError(self.packet_handler.getTxRxResult(comm))
             else:
                 return
         if self._is_error(error):
@@ -708,87 +723,60 @@ class MotorsBus(abc.ABC):
     ) -> dict[int, list[int, str]] | None:
         pass
 
-    @overload
-    def sync_read(
-        self, data_name: str, motors: None = ..., *, normalize: bool = ..., num_retry: int = ...
-    ) -> dict[str, Value]: ...
-    @overload
     def sync_read(
         self,
         data_name: str,
-        motors: NameOrID | list[NameOrID],
-        *,
-        normalize: bool = ...,
-        num_retry: int = ...,
-    ) -> dict[NameOrID, Value]: ...
-    def sync_read(
-        self,
-        data_name: str,
-        motors: NameOrID | list[NameOrID] | None = None,
+        motors: str | list[str] | None = None,
         *,
         normalize: bool = True,
         num_retry: int = 0,
-    ) -> dict[NameOrID, Value]:
+    ) -> dict[str, Value]:
         if not self.is_connected:
             raise DeviceNotConnectedError(
                 f"{self.__class__.__name__}('{self.port}') is not connected. You need to run `{self.__class__.__name__}.connect()`."
             )
 
-        id_key_map: dict[int, NameOrID] = {}
-        if motors is None:
-            id_key_map = {m.id: name for name, m in self.motors.items()}
-        elif isinstance(motors, (str, int)):
-            id_key_map = {self._get_motor_id(motors): motors}
-        elif isinstance(motors, list):
-            id_key_map = {self._get_motor_id(m): m for m in motors}
-        else:
-            raise TypeError(motors)
+        names = self._get_names_list(motors)
+        ids = [self.motors[name].id for name in names]
+        models = [self.motors[name].model for name in names]
 
-        motor_ids = list(id_key_map)
+        if self._has_different_ctrl_tables:
+            assert_same_address(self.model_ctrl_table, models, data_name)
 
-        comm, ids_values = self._sync_read(data_name, motor_ids, num_retry=num_retry)
+        model = next(iter(models))
+        addr, n_bytes = get_address(self.model_ctrl_table, model, data_name)
+
+        comm, ids_values = self._sync_read(addr, n_bytes, ids, num_retry=num_retry)
         if not self._is_comm_success(comm):
             raise ConnectionError(
-                f"Failed to sync read '{data_name}' on {motor_ids=} after {num_retry + 1} tries."
+                f"Failed to sync read '{data_name}' on {ids=} after {num_retry + 1} tries."
                 f"{self.packet_handler.getTxRxResult(comm)}"
             )
 
-        if normalize and data_name in self.normalization_required:
+        ids_values = self._decode_sign(data_name, ids_values)
+
+        if normalize and data_name in self.normalized_data:
             ids_values = self._normalize(data_name, ids_values)
 
-        return {id_key_map[id_]: val for id_, val in ids_values.items()}
+        return {self._id_to_name(id_): value for id_, value in ids_values.items()}
 
     def _sync_read(
-        self, data_name: str, motor_ids: list[str], model: str | None = None, num_retry: int = 0
+        self, addr: int, n_bytes: int, motor_ids: list[int], num_retry: int = 0
     ) -> tuple[int, dict[int, int]]:
-        if self._has_different_ctrl_tables:
-            models = [self._id_to_model(id_) for id_ in motor_ids]
-            assert_same_address(self.model_ctrl_table, models, data_name)
-
-        model = self._id_to_model(next(iter(motor_ids))) if model is None else model
-        addr, n_bytes = get_address(self.model_ctrl_table, model, data_name)
         self._setup_sync_reader(motor_ids, addr, n_bytes)
-
-        # FIXME(aliberts, pkooij): We should probably not have to do this.
-        # Let's try to see if we can do with better comm status handling instead.
-        # self.port_handler.ser.reset_output_buffer()
-        # self.port_handler.ser.reset_input_buffer()
-
         for n_try in range(1 + num_retry):
             comm = self.sync_reader.txRxPacket()
             if self._is_comm_success(comm):
                 break
-            logger.debug(f"Failed to sync read '{data_name}' ({addr=} {n_bytes=}) on {motor_ids=} ({n_try=})")
-            logger.debug(self.packet_handler.getRxPacketError(comm))
-
-        values = {}
-        for id_ in motor_ids:
-            val = self.sync_reader.getData(id_, addr, n_bytes)
-            values[id_] = self._decode_value(val, data_name, n_bytes)
+            logger.debug(
+                f"Failed to sync read @{addr=} ({n_bytes=}) on {motor_ids=} ({n_try=}): "
+                + self.packet_handler.getTxRxResult(comm)
+            )
 
+        values = {id_: self.sync_reader.getData(id_, addr, n_bytes) for id_ in motor_ids}
         return comm, values
 
-    def _setup_sync_reader(self, motor_ids: list[str], addr: int, n_bytes: int) -> None:
+    def _setup_sync_reader(self, motor_ids: list[int], addr: int, n_bytes: int) -> None:
         self.sync_reader.clearParam()
         self.sync_reader.start_address = addr
         self.sync_reader.data_length = n_bytes
@@ -799,7 +787,7 @@ class MotorsBus(abc.ABC):
     # Would have to handle the logic of checking if a packet has been sent previously though but doable.
     # This could be at the cost of increase latency between the moment the data is produced by the motors and
     # the moment it is used by a policy.
-    # def _async_read(self, motor_ids: list[str], address: int, n_bytes: int):
+    # def _async_read(self, motor_ids: list[int], address: int, n_bytes: int):
     #     if self.sync_reader.start_address != address or self.sync_reader.data_length != n_bytes or ...:
     #         self._setup_sync_reader(motor_ids, address, n_bytes)
     #     else:
@@ -812,7 +800,7 @@ class MotorsBus(abc.ABC):
     def sync_write(
         self,
         data_name: str,
-        values: Value | dict[NameOrID, Value],
+        values: Value | dict[str, Value],
         *,
         normalize: bool = True,
         num_retry: int = 0,
@@ -822,41 +810,36 @@ class MotorsBus(abc.ABC):
                 f"{self.__class__.__name__}('{self.port}') is not connected. You need to run `{self.__class__.__name__}.connect()`."
             )
 
-        if isinstance(values, int):
-            ids_values = {id_: values for id_ in self.ids}
-        elif isinstance(values, dict):
-            ids_values = {self._get_motor_id(motor): val for motor, val in values.items()}
-        else:
-            raise TypeError(f"'values' is expected to be a single value or a dict. Got {values}")
+        ids_values = self._get_ids_values_dict(values)
+        models = [self._id_to_model(id_) for id_ in ids_values]
+        if self._has_different_ctrl_tables:
+            assert_same_address(self.model_ctrl_table, models, data_name)
 
-        if normalize and data_name in self.normalization_required and self.calibration is not None:
+        model = next(iter(models))
+        addr, n_bytes = get_address(self.model_ctrl_table, model, data_name)
+
+        if normalize and data_name in self.normalized_data:
             ids_values = self._unnormalize(data_name, ids_values)
 
-        comm = self._sync_write(data_name, ids_values, num_retry=num_retry)
+        ids_values = self._encode_sign(data_name, ids_values)
+
+        comm = self._sync_write(addr, n_bytes, ids_values, num_retry=num_retry)
         if not self._is_comm_success(comm):
             raise ConnectionError(
                 f"Failed to sync write '{data_name}' with {ids_values=} after {num_retry + 1} tries."
                 f"\n{self.packet_handler.getTxRxResult(comm)}"
             )
 
-    def _sync_write(self, data_name: str, ids_values: dict[int, int], num_retry: int = 0) -> int:
-        if self._has_different_ctrl_tables:
-            models = [self._id_to_model(id_) for id_ in ids_values]
-            assert_same_address(self.model_ctrl_table, models, data_name)
-
-        model = self._id_to_model(next(iter(ids_values)))
-        addr, n_bytes = get_address(self.model_ctrl_table, model, data_name)
-        ids_values = {id_: self._encode_value(value, data_name, n_bytes) for id_, value in ids_values.items()}
+    def _sync_write(self, addr: int, n_bytes: int, ids_values: dict[int, int], num_retry: int = 0) -> int:
         self._setup_sync_writer(ids_values, addr, n_bytes)
-
         for n_try in range(1 + num_retry):
             comm = self.sync_writer.txPacket()
             if self._is_comm_success(comm):
                 break
             logger.debug(
-                f"Failed to sync write '{data_name}' ({addr=} {n_bytes=}) with {ids_values=} ({n_try=})"
+                f"Failed to sync write @{addr=} ({n_bytes=}) with {ids_values=} ({n_try=}): "
+                + self.packet_handler.getTxRxResult(comm)
             )
-            logger.debug(self.packet_handler.getRxPacketError(comm))
 
         return comm
 
@@ -869,20 +852,23 @@ class MotorsBus(abc.ABC):
             self.sync_writer.addParam(id_, data)
 
     def write(
-        self, data_name: str, motor: NameOrID, value: Value, *, normalize: bool = True, num_retry: int = 0
+        self, data_name: str, motor: str, value: Value, *, normalize: bool = True, num_retry: int = 0
     ) -> None:
         if not self.is_connected:
             raise DeviceNotConnectedError(
                 f"{self.__class__.__name__}('{self.port}') is not connected. You need to run `{self.__class__.__name__}.connect()`."
             )
 
-        id_ = self._get_motor_id(motor)
+        id_ = self.motors[motor].id
+        model = self.motors[motor].model
+        addr, n_bytes = get_address(self.model_ctrl_table, model, data_name)
 
-        if normalize and data_name in self.normalization_required and self.calibration is not None:
-            id_value = self._unnormalize(data_name, {id_: value})
-            value = id_value[id_]
+        if normalize and data_name in self.normalized_data:
+            value = self._unnormalize(data_name, {id_: value})[id_]
 
-        comm, error = self._write(data_name, id_, value, num_retry=num_retry)
+        value = self._encode_sign(data_name, {id_: value})[id_]
+
+        comm, error = self._write(addr, n_bytes, id_, value, num_retry=num_retry)
         if not self._is_comm_success(comm):
             raise ConnectionError(
                 f"Failed to write '{data_name}' on {id_=} with '{value}' after {num_retry + 1} tries."
@@ -894,20 +880,18 @@ class MotorsBus(abc.ABC):
                 f"\n{self.packet_handler.getRxPacketError(error)}"
             )
 
-    def _write(self, data_name: str, motor_id: int, value: int, num_retry: int = 0) -> tuple[int, int]:
-        model = self._id_to_model(motor_id)
-        addr, n_bytes = get_address(self.model_ctrl_table, model, data_name)
-        value = self._encode_value(value, data_name, n_bytes)
+    def _write(
+        self, addr: int, n_bytes: int, motor_id: int, value: int, num_retry: int = 0
+    ) -> tuple[int, int]:
         data = self._split_int_to_bytes(value, n_bytes)
-
         for n_try in range(1 + num_retry):
             comm, error = self.packet_handler.writeTxRx(self.port_handler, motor_id, addr, n_bytes, data)
             if self._is_comm_success(comm):
                 break
             logger.debug(
-                f"Failed to write '{data_name}' ({addr=} {n_bytes=}) on {motor_id=} with '{value}' ({n_try=})"
+                f"Failed to sync write @{addr=} ({n_bytes=}) on id={motor_id} with {value=} ({n_try=}): "
+                + self.packet_handler.getTxRxResult(comm)
             )
-            logger.debug(self.packet_handler.getRxPacketError(comm))
 
         return comm, error
 
diff --git a/tests/mocks/mock_feetech.py b/tests/mocks/mock_feetech.py
index 1636c113..56437b02 100644
--- a/tests/mocks/mock_feetech.py
+++ b/tests/mocks/mock_feetech.py
@@ -5,7 +5,7 @@ import scservo_sdk as scs
 import serial
 from mock_serial import MockSerial
 
-from lerobot.common.motors.feetech import SCS_SERIES_CONTROL_TABLE, FeetechMotorsBus
+from lerobot.common.motors.feetech import STS_SMS_SERIES_CONTROL_TABLE, FeetechMotorsBus
 from lerobot.common.motors.feetech.feetech import patch_setPacketTimeout
 
 from .mock_serial_patch import WaitableStub
@@ -297,7 +297,7 @@ class MockMotors(MockSerial):
     instruction packets. It is meant to test MotorsBus classes.
     """
 
-    ctrl_table = SCS_SERIES_CONTROL_TABLE
+    ctrl_table = STS_SMS_SERIES_CONTROL_TABLE
 
     def __init__(self):
         super().__init__()
@@ -338,12 +338,6 @@ class MockMotors(MockSerial):
     def build_read_stub(
         self, data_name: str, scs_id: int, value: int | None = None, num_invalid_try: int = 0
     ) -> str:
-        """
-        'data_name' supported:
-            - Model_Number
-        """
-        if data_name != "Model_Number":
-            raise NotImplementedError
         address, length = self.ctrl_table[data_name]
         read_request = MockInstructionPacket.read(scs_id, address, length)
         return_packet = MockStatusPacket.read(scs_id, value, length)
diff --git a/tests/motors/test_feetech.py b/tests/motors/test_feetech.py
index 871f102e..5372c37a 100644
--- a/tests/motors/test_feetech.py
+++ b/tests/motors/test_feetech.py
@@ -6,7 +6,7 @@ import pytest
 import scservo_sdk as scs
 
 from lerobot.common.motors import Motor, MotorCalibration, MotorNormMode
-from lerobot.common.motors.feetech import MODEL_NUMBER, FeetechMotorsBus
+from lerobot.common.motors.feetech import MODEL_NUMBER_TABLE, FeetechMotorsBus
 from lerobot.common.utils.encoding_utils import encode_sign_magnitude
 from tests.mocks.mock_feetech import MockMotors, MockPortHandler
 
@@ -129,7 +129,7 @@ def test_scan_port(mock_motors):
 
 @pytest.mark.parametrize("id_", [1, 2, 3])
 def test_ping(id_, mock_motors, dummy_motors):
-    expected_model_nb = MODEL_NUMBER[dummy_motors[f"dummy_{id_}"].model]
+    expected_model_nb = MODEL_NUMBER_TABLE[dummy_motors[f"dummy_{id_}"].model]
     ping_stub = mock_motors.build_ping_stub(id_)
     mobel_nb_stub = mock_motors.build_read_stub("Model_Number", id_, expected_model_nb)
     motors_bus = FeetechMotorsBus(
@@ -147,7 +147,7 @@ def test_ping(id_, mock_motors, dummy_motors):
 
 def test_broadcast_ping(mock_motors, dummy_motors):
     models = {m.id: m.model for m in dummy_motors.values()}
-    expected_model_nbs = {id_: MODEL_NUMBER[model] for id_, model in models.items()}
+    expected_model_nbs = {id_: MODEL_NUMBER_TABLE[model] for id_, model in models.items()}
     ping_stub = mock_motors.build_broadcast_ping_stub(list(models))
     mobel_nb_stub = mock_motors.build_sync_read_stub("Model_Number", expected_model_nbs)
     motors_bus = FeetechMotorsBus(
@@ -191,55 +191,7 @@ def test_sync_read_none(mock_motors, dummy_motors):
         (3, 4016),
     ],
 )
-def test_sync_read_by_id(id_, position, mock_motors, dummy_motors):
-    expected_position = {id_: position}
-    stub_name = mock_motors.build_sync_read_stub("Present_Position", expected_position)
-    motors_bus = FeetechMotorsBus(
-        port=mock_motors.port,
-        motors=dummy_motors,
-    )
-    motors_bus.connect(assert_motors_exist=False)
-
-    read_position = motors_bus.sync_read("Present_Position", id_, normalize=False)
-
-    assert mock_motors.stubs[stub_name].called
-    assert read_position == expected_position
-
-
-@pytest.mark.parametrize(
-    "ids, positions",
-    [
-        ([1],       [1337]),
-        ([1, 2],    [1337, 42]),
-        ([1, 2, 3], [1337, 42, 4016]),
-    ],
-    ids=["1 motor", "2 motors", "3 motors"],
-)  # fmt: skip
-def test_sync_read_by_ids(ids, positions, mock_motors, dummy_motors):
-    assert len(ids) == len(positions)
-    expected_positions = dict(zip(ids, positions, strict=True))
-    stub_name = mock_motors.build_sync_read_stub("Present_Position", expected_positions)
-    motors_bus = FeetechMotorsBus(
-        port=mock_motors.port,
-        motors=dummy_motors,
-    )
-    motors_bus.connect(assert_motors_exist=False)
-
-    read_positions = motors_bus.sync_read("Present_Position", ids, normalize=False)
-
-    assert mock_motors.stubs[stub_name].called
-    assert read_positions == expected_positions
-
-
-@pytest.mark.parametrize(
-    "id_, position",
-    [
-        (1, 1337),
-        (2, 42),
-        (3, 4016),
-    ],
-)
-def test_sync_read_by_name(id_, position, mock_motors, dummy_motors):
+def test_sync_read_single_value(id_, position, mock_motors, dummy_motors):
     expected_position = {f"dummy_{id_}": position}
     stub_name = mock_motors.build_sync_read_stub("Present_Position", {id_: position})
     motors_bus = FeetechMotorsBus(
@@ -263,7 +215,7 @@ def test_sync_read_by_name(id_, position, mock_motors, dummy_motors):
     ],
     ids=["1 motor", "2 motors", "3 motors"],
 )  # fmt: skip
-def test_sync_read_by_names(ids, positions, mock_motors, dummy_motors):
+def test_sync_read(ids, positions, mock_motors, dummy_motors):
     assert len(ids) == len(positions)
     names = [f"dummy_{dxl_id}" for dxl_id in ids]
     expected_positions = dict(zip(names, positions, strict=True))
@@ -291,9 +243,9 @@ def test_sync_read_by_names(ids, positions, mock_motors, dummy_motors):
     ],
 )
 def test_sync_read_num_retry(num_retry, num_invalid_try, pos, mock_motors, dummy_motors):
-    expected_position = {1: pos}
+    expected_position = {"dummy_1": pos}
     stub_name = mock_motors.build_sync_read_stub(
-        "Present_Position", expected_position, num_invalid_try=num_invalid_try
+        "Present_Position", {1: pos}, num_invalid_try=num_invalid_try
     )
     motors_bus = FeetechMotorsBus(
         port=mock_motors.port,
@@ -302,11 +254,11 @@ def test_sync_read_num_retry(num_retry, num_invalid_try, pos, mock_motors, dummy
     motors_bus.connect(assert_motors_exist=False)
 
     if num_retry >= num_invalid_try:
-        pos_dict = motors_bus.sync_read("Present_Position", 1, normalize=False, num_retry=num_retry)
-        assert pos_dict == {1: pos}
+        pos_dict = motors_bus.sync_read("Present_Position", "dummy_1", normalize=False, num_retry=num_retry)
+        assert pos_dict == expected_position
     else:
         with pytest.raises(ConnectionError):
-            _ = motors_bus.sync_read("Present_Position", 1, normalize=False, num_retry=num_retry)
+            _ = motors_bus.sync_read("Present_Position", "dummy_1", normalize=False, num_retry=num_retry)
 
     expected_calls = min(1 + num_retry, 1 + num_invalid_try)
     assert mock_motors.stubs[stub_name].calls == expected_calls
@@ -335,28 +287,6 @@ def test_sync_write_single_value(data_name, value, mock_motors, dummy_motors):
     assert mock_motors.stubs[stub_name].wait_called()
 
 
-@pytest.mark.parametrize(
-    "id_, position",
-    [
-        (1, 1337),
-        (2, 42),
-        (3, 4016),
-    ],
-)
-def test_sync_write_by_id(id_, position, mock_motors, dummy_motors):
-    value = {id_: position}
-    stub_name = mock_motors.build_sync_write_stub("Goal_Position", value)
-    motors_bus = FeetechMotorsBus(
-        port=mock_motors.port,
-        motors=dummy_motors,
-    )
-    motors_bus.connect(assert_motors_exist=False)
-
-    motors_bus.sync_write("Goal_Position", value, normalize=False)
-
-    assert mock_motors.stubs[stub_name].wait_called()
-
-
 @pytest.mark.parametrize(
     "ids, positions",
     [
@@ -366,54 +296,7 @@ def test_sync_write_by_id(id_, position, mock_motors, dummy_motors):
     ],
     ids=["1 motor", "2 motors", "3 motors"],
 )  # fmt: skip
-def test_sync_write_by_ids(ids, positions, mock_motors, dummy_motors):
-    assert len(ids) == len(positions)
-    values = dict(zip(ids, positions, strict=True))
-    stub_name = mock_motors.build_sync_write_stub("Goal_Position", values)
-    motors_bus = FeetechMotorsBus(
-        port=mock_motors.port,
-        motors=dummy_motors,
-    )
-    motors_bus.connect(assert_motors_exist=False)
-
-    motors_bus.sync_write("Goal_Position", values, normalize=False)
-
-    assert mock_motors.stubs[stub_name].wait_called()
-
-
-@pytest.mark.parametrize(
-    "id_, position",
-    [
-        (1, 1337),
-        (2, 42),
-        (3, 4016),
-    ],
-)
-def test_sync_write_by_name(id_, position, mock_motors, dummy_motors):
-    id_value = {id_: position}
-    stub_name = mock_motors.build_sync_write_stub("Goal_Position", id_value)
-    motors_bus = FeetechMotorsBus(
-        port=mock_motors.port,
-        motors=dummy_motors,
-    )
-    motors_bus.connect(assert_motors_exist=False)
-
-    write_value = {f"dummy_{id_}": position}
-    motors_bus.sync_write("Goal_Position", write_value, normalize=False)
-
-    assert mock_motors.stubs[stub_name].wait_called()
-
-
-@pytest.mark.parametrize(
-    "ids, positions",
-    [
-        ([1],       [1337]),
-        ([1, 2],    [1337, 42]),
-        ([1, 2, 3], [1337, 42, 4016]),
-    ],
-    ids=["1 motor", "2 motors", "3 motors"],
-)  # fmt: skip
-def test_sync_write_by_names(ids, positions, mock_motors, dummy_motors):
+def test_sync_write(ids, positions, mock_motors, dummy_motors):
     assert len(ids) == len(positions)
     ids_values = dict(zip(ids, positions, strict=True))
     stub_name = mock_motors.build_sync_write_stub("Goal_Position", ids_values)
@@ -438,29 +321,7 @@ def test_sync_write_by_names(ids, positions, mock_motors, dummy_motors):
         ("Goal_Position", 3, 42),
     ],
 )
-def test_write_by_id(data_name, dxl_id, value, mock_motors, dummy_motors):
-    stub_name = mock_motors.build_write_stub(data_name, dxl_id, value)
-    motors_bus = FeetechMotorsBus(
-        port=mock_motors.port,
-        motors=dummy_motors,
-    )
-    motors_bus.connect(assert_motors_exist=False)
-
-    motors_bus.write(data_name, dxl_id, value, normalize=False)
-
-    assert mock_motors.stubs[stub_name].called
-
-
-@pytest.mark.parametrize(
-    "data_name, dxl_id, value",
-    [
-        ("Torque_Enable", 1, 0),
-        ("Torque_Enable", 1, 1),
-        ("Goal_Position", 2, 1337),
-        ("Goal_Position", 3, 42),
-    ],
-)
-def test_write_by_name(data_name, dxl_id, value, mock_motors, dummy_motors):
+def test_write(data_name, dxl_id, value, mock_motors, dummy_motors):
     stub_name = mock_motors.build_write_stub(data_name, dxl_id, value)
     motors_bus = FeetechMotorsBus(
         port=mock_motors.port,

From 792c3d961d591c1f01d6a85cddf55ba3f0230e4b Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Tue, 8 Apr 2025 10:47:11 +0200
Subject: [PATCH 169/171] Update dynamixel with motors bus & tables changes

---
 lerobot/common/motors/dynamixel/dynamixel.py |  36 ++--
 lerobot/common/motors/dynamixel/tables.py    |  25 ++-
 tests/motors/test_dynamixel.py               | 163 ++-----------------
 3 files changed, 61 insertions(+), 163 deletions(-)

diff --git a/lerobot/common/motors/dynamixel/dynamixel.py b/lerobot/common/motors/dynamixel/dynamixel.py
index 2abce818..cb2d2829 100644
--- a/lerobot/common/motors/dynamixel/dynamixel.py
+++ b/lerobot/common/motors/dynamixel/dynamixel.py
@@ -29,7 +29,8 @@ from .tables import (
     AVAILABLE_BAUDRATES,
     MODEL_BAUDRATE_TABLE,
     MODEL_CONTROL_TABLE,
-    MODEL_NUMBER,
+    MODEL_ENCODING_TABLE,
+    MODEL_NUMBER_TABLE,
     MODEL_RESOLUTION,
 )
 
@@ -37,7 +38,7 @@ PROTOCOL_VERSION = 2.0
 BAUDRATE = 1_000_000
 DEFAULT_TIMEOUT_MS = 1000
 
-NORMALIZATION_REQUIRED = ["Goal_Position", "Present_Position"]
+NORMALIZED_DATA = ["Goal_Position", "Present_Position"]
 CONVERT_UINT32_TO_INT32_REQUIRED = ["Goal_Position", "Present_Position"]
 
 logger = logging.getLogger(__name__)
@@ -94,9 +95,10 @@ class DynamixelMotorsBus(MotorsBus):
     default_timeout = DEFAULT_TIMEOUT_MS
     model_baudrate_table = deepcopy(MODEL_BAUDRATE_TABLE)
     model_ctrl_table = deepcopy(MODEL_CONTROL_TABLE)
-    model_number_table = deepcopy(MODEL_NUMBER)
+    model_encoding_table = deepcopy(MODEL_ENCODING_TABLE)
+    model_number_table = deepcopy(MODEL_NUMBER_TABLE)
     model_resolution_table = deepcopy(MODEL_RESOLUTION)
-    normalization_required = deepcopy(NORMALIZATION_REQUIRED)
+    normalized_data = deepcopy(NORMALIZED_DATA)
 
     def __init__(
         self,
@@ -128,11 +130,25 @@ class DynamixelMotorsBus(MotorsBus):
         for motor in motors:
             self.write("Torque_Enable", motor, TorqueMode.ENABLED.value)
 
-    def _encode_value(self, value: int, data_name: str | None = None, n_bytes: int | None = None) -> int:
-        return encode_twos_complement(value, n_bytes)
+    def _encode_sign(self, data_name: str, ids_values: dict[int, int]) -> dict[int, int]:
+        for id_ in ids_values:
+            model = self._id_to_model(id_)
+            encoding_table = self.model_encoding_table.get(model)
+            if encoding_table and data_name in encoding_table:
+                n_bytes = encoding_table[data_name]
+                ids_values[id_] = encode_twos_complement(ids_values[id_], n_bytes)
 
-    def _decode_value(self, value: int, data_name: str | None = None, n_bytes: int | None = None) -> int:
-        return decode_twos_complement(value, n_bytes)
+        return ids_values
+
+    def _decode_sign(self, data_name: str, ids_values: dict[int, int]) -> dict[int, int]:
+        for id_ in ids_values:
+            model = self._id_to_model(id_)
+            encoding_table = self.model_encoding_table.get(model)
+            if encoding_table and data_name in encoding_table:
+                n_bytes = encoding_table[data_name]
+                ids_values[id_] = decode_twos_complement(ids_values[id_], n_bytes)
+
+        return ids_values
 
     def _get_half_turn_homings(self, positions: dict[NameOrID, Value]) -> dict[NameOrID, Value]:
         """
@@ -182,13 +198,13 @@ class DynamixelMotorsBus(MotorsBus):
             data_list, comm = self.packet_handler.broadcastPing(self.port_handler)
             if self._is_comm_success(comm):
                 break
-            logger.debug(f"Broadcast failed on port '{self.port}' ({n_try=})")
+            logger.debug(f"Broadcast ping failed on port '{self.port}' ({n_try=})")
             logger.debug(self.packet_handler.getTxRxResult(comm))
 
         if not self._is_comm_success(comm):
             if raise_on_error:
                 raise ConnectionError(self.packet_handler.getTxRxResult(comm))
 
-            return data_list if data_list else None
+            return
 
         return {id_: data[0] for id_, data in data_list.items()}
diff --git a/lerobot/common/motors/dynamixel/tables.py b/lerobot/common/motors/dynamixel/tables.py
index 525404bf..a9f6d9e7 100644
--- a/lerobot/common/motors/dynamixel/tables.py
+++ b/lerobot/common/motors/dynamixel/tables.py
@@ -1,4 +1,4 @@
-# data_name: (address, size_byte)
+# {data_name: (address, size_byte)}
 # https://emanual.robotis.com/docs/en/dxl/x/{MODEL}/#control-table
 X_SERIES_CONTROL_TABLE = {
     "Model_Number": (0, 2),
@@ -66,6 +66,27 @@ X_SERIES_BAUDRATE_TABLE = {
     6: 4_000_000,
 }
 
+# {data_name: size_byte}
+X_SERIES_ENCODINGS_TABLE = {
+    "Homing_Offset": X_SERIES_CONTROL_TABLE["Homing_Offset"][1],
+    "Goal_PWM": X_SERIES_CONTROL_TABLE["Goal_PWM"][1],
+    "Goal_Current": X_SERIES_CONTROL_TABLE["Goal_Current"][1],
+    "Goal_Velocity": X_SERIES_CONTROL_TABLE["Goal_Velocity"][1],
+    "Present_PWM": X_SERIES_CONTROL_TABLE["Present_PWM"][1],
+    "Present_Current": X_SERIES_CONTROL_TABLE["Present_Current"][1],
+    "Present_Velocity": X_SERIES_CONTROL_TABLE["Present_Velocity"][1],
+}
+
+MODEL_ENCODING_TABLE = {
+    "x_series": X_SERIES_ENCODINGS_TABLE,
+    "xl330-m077": X_SERIES_ENCODINGS_TABLE,
+    "xl330-m288": X_SERIES_ENCODINGS_TABLE,
+    "xl430-w250": X_SERIES_ENCODINGS_TABLE,
+    "xm430-w350": X_SERIES_ENCODINGS_TABLE,
+    "xm540-w270": X_SERIES_ENCODINGS_TABLE,
+    "xc430-w150": X_SERIES_ENCODINGS_TABLE,
+}
+
 # {model: model_resolution}
 # https://emanual.robotis.com/docs/en/dxl/x/{MODEL}/#specifications
 MODEL_RESOLUTION = {
@@ -80,7 +101,7 @@ MODEL_RESOLUTION = {
 
 # {model: model_number}
 # https://emanual.robotis.com/docs/en/dxl/x/{MODEL}/#control-table-of-eeprom-area
-MODEL_NUMBER = {
+MODEL_NUMBER_TABLE = {
     "xl330-m077": 1190,
     "xl330-m288": 1200,
     "xl430-w250": 1060,
diff --git a/tests/motors/test_dynamixel.py b/tests/motors/test_dynamixel.py
index 9ebbbacb..6fd0e3a7 100644
--- a/tests/motors/test_dynamixel.py
+++ b/tests/motors/test_dynamixel.py
@@ -6,7 +6,7 @@ import dynamixel_sdk as dxl
 import pytest
 
 from lerobot.common.motors import Motor, MotorCalibration, MotorNormMode
-from lerobot.common.motors.dynamixel import MODEL_NUMBER, DynamixelMotorsBus
+from lerobot.common.motors.dynamixel import MODEL_NUMBER_TABLE, DynamixelMotorsBus
 from lerobot.common.utils.encoding_utils import encode_twos_complement
 from tests.mocks.mock_dynamixel import MockMotors, MockPortHandler
 
@@ -113,7 +113,7 @@ def test_abc_implementation(dummy_motors):
 
 @pytest.mark.parametrize("id_", [1, 2, 3])
 def test_ping(id_, mock_motors, dummy_motors):
-    expected_model_nb = MODEL_NUMBER[dummy_motors[f"dummy_{id_}"].model]
+    expected_model_nb = MODEL_NUMBER_TABLE[dummy_motors[f"dummy_{id_}"].model]
     stub_name = mock_motors.build_ping_stub(id_, expected_model_nb)
     motors_bus = DynamixelMotorsBus(
         port=mock_motors.port,
@@ -129,7 +129,7 @@ def test_ping(id_, mock_motors, dummy_motors):
 
 def test_broadcast_ping(mock_motors, dummy_motors):
     models = {m.id: m.model for m in dummy_motors.values()}
-    expected_model_nbs = {id_: MODEL_NUMBER[model] for id_, model in models.items()}
+    expected_model_nbs = {id_: MODEL_NUMBER_TABLE[model] for id_, model in models.items()}
     stub_name = mock_motors.build_broadcast_ping_stub(expected_model_nbs)
     motors_bus = DynamixelMotorsBus(
         port=mock_motors.port,
@@ -171,55 +171,7 @@ def test_sync_read_none(mock_motors, dummy_motors):
         (3, 4016),
     ],
 )
-def test_sync_read_by_id(id_, position, mock_motors, dummy_motors):
-    expected_position = {id_: position}
-    stub_name = mock_motors.build_sync_read_stub("Present_Position", expected_position)
-    motors_bus = DynamixelMotorsBus(
-        port=mock_motors.port,
-        motors=dummy_motors,
-    )
-    motors_bus.connect(assert_motors_exist=False)
-
-    read_position = motors_bus.sync_read("Present_Position", id_, normalize=False)
-
-    assert mock_motors.stubs[stub_name].called
-    assert read_position == expected_position
-
-
-@pytest.mark.parametrize(
-    "ids, positions",
-    [
-        ([1],       [1337]),
-        ([1, 2],    [1337, 42]),
-        ([1, 2, 3], [1337, 42, 4016]),
-    ],
-    ids=["1 motor", "2 motors", "3 motors"],
-)  # fmt: skip
-def test_sync_read_by_ids(ids, positions, mock_motors, dummy_motors):
-    assert len(ids) == len(positions)
-    expected_positions = dict(zip(ids, positions, strict=True))
-    stub_name = mock_motors.build_sync_read_stub("Present_Position", expected_positions)
-    motors_bus = DynamixelMotorsBus(
-        port=mock_motors.port,
-        motors=dummy_motors,
-    )
-    motors_bus.connect(assert_motors_exist=False)
-
-    read_positions = motors_bus.sync_read("Present_Position", ids, normalize=False)
-
-    assert mock_motors.stubs[stub_name].called
-    assert read_positions == expected_positions
-
-
-@pytest.mark.parametrize(
-    "id_, position",
-    [
-        (1, 1337),
-        (2, 42),
-        (3, 4016),
-    ],
-)
-def test_sync_read_by_name(id_, position, mock_motors, dummy_motors):
+def test_sync_read_single_value(id_, position, mock_motors, dummy_motors):
     expected_position = {f"dummy_{id_}": position}
     stub_name = mock_motors.build_sync_read_stub("Present_Position", {id_: position})
     motors_bus = DynamixelMotorsBus(
@@ -243,7 +195,7 @@ def test_sync_read_by_name(id_, position, mock_motors, dummy_motors):
     ],
     ids=["1 motor", "2 motors", "3 motors"],
 )  # fmt: skip
-def test_sync_read_by_names(ids, positions, mock_motors, dummy_motors):
+def test_sync_read(ids, positions, mock_motors, dummy_motors):
     assert len(ids) == len(positions)
     names = [f"dummy_{dxl_id}" for dxl_id in ids]
     expected_positions = dict(zip(names, positions, strict=True))
@@ -271,9 +223,9 @@ def test_sync_read_by_names(ids, positions, mock_motors, dummy_motors):
     ],
 )
 def test_sync_read_num_retry(num_retry, num_invalid_try, pos, mock_motors, dummy_motors):
-    expected_position = {1: pos}
+    expected_position = {"dummy_1": pos}
     stub_name = mock_motors.build_sync_read_stub(
-        "Present_Position", expected_position, num_invalid_try=num_invalid_try
+        "Present_Position", {1: pos}, num_invalid_try=num_invalid_try
     )
     motors_bus = DynamixelMotorsBus(
         port=mock_motors.port,
@@ -282,11 +234,11 @@ def test_sync_read_num_retry(num_retry, num_invalid_try, pos, mock_motors, dummy
     motors_bus.connect(assert_motors_exist=False)
 
     if num_retry >= num_invalid_try:
-        pos_dict = motors_bus.sync_read("Present_Position", 1, normalize=False, num_retry=num_retry)
-        assert pos_dict == {1: pos}
+        pos_dict = motors_bus.sync_read("Present_Position", "dummy_1", normalize=False, num_retry=num_retry)
+        assert pos_dict == expected_position
     else:
         with pytest.raises(ConnectionError):
-            _ = motors_bus.sync_read("Present_Position", 1, normalize=False, num_retry=num_retry)
+            _ = motors_bus.sync_read("Present_Position", "dummy_1", normalize=False, num_retry=num_retry)
 
     expected_calls = min(1 + num_retry, 1 + num_invalid_try)
     assert mock_motors.stubs[stub_name].calls == expected_calls
@@ -315,28 +267,6 @@ def test_sync_write_single_value(data_name, value, mock_motors, dummy_motors):
     assert mock_motors.stubs[stub_name].wait_called()
 
 
-@pytest.mark.parametrize(
-    "id_, position",
-    [
-        (1, 1337),
-        (2, 42),
-        (3, 4016),
-    ],
-)
-def test_sync_write_by_id(id_, position, mock_motors, dummy_motors):
-    value = {id_: position}
-    stub_name = mock_motors.build_sync_write_stub("Goal_Position", value)
-    motors_bus = DynamixelMotorsBus(
-        port=mock_motors.port,
-        motors=dummy_motors,
-    )
-    motors_bus.connect(assert_motors_exist=False)
-
-    motors_bus.sync_write("Goal_Position", value, normalize=False)
-
-    assert mock_motors.stubs[stub_name].wait_called()
-
-
 @pytest.mark.parametrize(
     "ids, positions",
     [
@@ -346,54 +276,7 @@ def test_sync_write_by_id(id_, position, mock_motors, dummy_motors):
     ],
     ids=["1 motor", "2 motors", "3 motors"],
 )  # fmt: skip
-def test_sync_write_by_ids(ids, positions, mock_motors, dummy_motors):
-    assert len(ids) == len(positions)
-    values = dict(zip(ids, positions, strict=True))
-    stub_name = mock_motors.build_sync_write_stub("Goal_Position", values)
-    motors_bus = DynamixelMotorsBus(
-        port=mock_motors.port,
-        motors=dummy_motors,
-    )
-    motors_bus.connect(assert_motors_exist=False)
-
-    motors_bus.sync_write("Goal_Position", values, normalize=False)
-
-    assert mock_motors.stubs[stub_name].wait_called()
-
-
-@pytest.mark.parametrize(
-    "id_, position",
-    [
-        (1, 1337),
-        (2, 42),
-        (3, 4016),
-    ],
-)
-def test_sync_write_by_name(id_, position, mock_motors, dummy_motors):
-    id_value = {id_: position}
-    stub_name = mock_motors.build_sync_write_stub("Goal_Position", id_value)
-    motors_bus = DynamixelMotorsBus(
-        port=mock_motors.port,
-        motors=dummy_motors,
-    )
-    motors_bus.connect(assert_motors_exist=False)
-
-    write_value = {f"dummy_{id_}": position}
-    motors_bus.sync_write("Goal_Position", write_value, normalize=False)
-
-    assert mock_motors.stubs[stub_name].wait_called()
-
-
-@pytest.mark.parametrize(
-    "ids, positions",
-    [
-        ([1],       [1337]),
-        ([1, 2],    [1337, 42]),
-        ([1, 2, 3], [1337, 42, 4016]),
-    ],
-    ids=["1 motor", "2 motors", "3 motors"],
-)  # fmt: skip
-def test_sync_write_by_names(ids, positions, mock_motors, dummy_motors):
+def test_sync_write(ids, positions, mock_motors, dummy_motors):
     assert len(ids) == len(positions)
     ids_values = dict(zip(ids, positions, strict=True))
     stub_name = mock_motors.build_sync_write_stub("Goal_Position", ids_values)
@@ -418,29 +301,7 @@ def test_sync_write_by_names(ids, positions, mock_motors, dummy_motors):
         ("Goal_Position", 3, 42),
     ],
 )
-def test_write_by_id(data_name, dxl_id, value, mock_motors, dummy_motors):
-    stub_name = mock_motors.build_write_stub(data_name, dxl_id, value)
-    motors_bus = DynamixelMotorsBus(
-        port=mock_motors.port,
-        motors=dummy_motors,
-    )
-    motors_bus.connect(assert_motors_exist=False)
-
-    motors_bus.write(data_name, dxl_id, value, normalize=False)
-
-    assert mock_motors.stubs[stub_name].called
-
-
-@pytest.mark.parametrize(
-    "data_name, dxl_id, value",
-    [
-        ("Torque_Enable", 1, 0),
-        ("Torque_Enable", 1, 1),
-        ("Goal_Position", 2, 1337),
-        ("Goal_Position", 3, 42),
-    ],
-)
-def test_write_by_name(data_name, dxl_id, value, mock_motors, dummy_motors):
+def test_write(data_name, dxl_id, value, mock_motors, dummy_motors):
     stub_name = mock_motors.build_write_stub(data_name, dxl_id, value)
     motors_bus = DynamixelMotorsBus(
         port=mock_motors.port,

From 782dff1163d612345d999ffbb52d27d4479f615f Mon Sep 17 00:00:00 2001
From: "pre-commit-ci[bot]"
 <66853113+pre-commit-ci[bot]@users.noreply.github.com>
Date: Tue, 8 Apr 2025 08:48:17 +0000
Subject: [PATCH 170/171] [pre-commit.ci] auto fixes from pre-commit.com hooks

for more information, see https://pre-commit.ci
---
 lerobot/common/motors/motors_bus.py | 4 ++--
 lerobot/common/robots/utils.py      | 2 +-
 2 files changed, 3 insertions(+), 3 deletions(-)

diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py
index 03f54452..7b568a2f 100644
--- a/lerobot/common/motors/motors_bus.py
+++ b/lerobot/common/motors/motors_bus.py
@@ -353,7 +353,7 @@ class MotorsBus(abc.ABC):
 
     def _get_ids_values_dict(self, values: Value | dict[str, Value] | None) -> list[str]:
         if isinstance(values, (int, float)):
-            return {id_: values for id_ in self.ids}
+            return dict.fromkeys(self.ids, values)
         elif isinstance(values, dict):
             return {self.motors[motor].id: val for motor, val in values.items()}
         else:
@@ -499,7 +499,7 @@ class MotorsBus(abc.ABC):
         try:
             drive_modes = self.sync_read("Drive_Mode", normalize=False)
         except KeyError:
-            drive_modes = {name: 0 for name in self.names}
+            drive_modes = dict.fromkeys(self.names, 0)
 
         calibration = {}
         for name, motor in self.motors.items():
diff --git a/lerobot/common/robots/utils.py b/lerobot/common/robots/utils.py
index 9c0b28ac..19b7c1b9 100644
--- a/lerobot/common/robots/utils.py
+++ b/lerobot/common/robots/utils.py
@@ -85,7 +85,7 @@ def ensure_safe_goal_position(
     """Caps relative action target magnitude for safety."""
 
     if isinstance(max_relative_target, float):
-        diff_cap = {key: max_relative_target for key in goal_present_pos}
+        diff_cap = dict.fromkeys(goal_present_pos, max_relative_target)
     elif isinstance(max_relative_target, dict):
         if not set(goal_present_pos) == set(max_relative_target):
             raise ValueError("max_relative_target keys must match those of goal_present_pos.")

From 034171a89abd18e9a262c04f4f40c0b0eb04a5bd Mon Sep 17 00:00:00 2001
From: Simon Alibert <simon.alibert@huggingface.co>
Date: Wed, 9 Apr 2025 10:26:30 +0200
Subject: [PATCH 171/171] Add Feetech protocol version

---
 lerobot/common/motors/feetech/feetech.py | 5 +++--
 1 file changed, 3 insertions(+), 2 deletions(-)

diff --git a/lerobot/common/motors/feetech/feetech.py b/lerobot/common/motors/feetech/feetech.py
index 064927b0..35a8a715 100644
--- a/lerobot/common/motors/feetech/feetech.py
+++ b/lerobot/common/motors/feetech/feetech.py
@@ -31,7 +31,7 @@ from .tables import (
     SCAN_BAUDRATES,
 )
 
-PROTOCOL_VERSION = 0
+DEFAULT_PROTOCOL_VERSION = 0
 BAUDRATE = 1_000_000
 DEFAULT_TIMEOUT_MS = 1000
 
@@ -97,6 +97,7 @@ class FeetechMotorsBus(MotorsBus):
         port: str,
         motors: dict[str, Motor],
         calibration: dict[str, MotorCalibration] | None = None,
+        protocol_version: int = DEFAULT_PROTOCOL_VERSION,
     ):
         super().__init__(port, motors, calibration)
         import scservo_sdk as scs
@@ -106,7 +107,7 @@ class FeetechMotorsBus(MotorsBus):
         self.port_handler.setPacketTimeout = patch_setPacketTimeout.__get__(
             self.port_handler, scs.PortHandler
         )
-        self.packet_handler = scs.PacketHandler(PROTOCOL_VERSION)
+        self.packet_handler = scs.PacketHandler(protocol_version)
         self.sync_reader = scs.GroupSyncRead(self.port_handler, self.packet_handler, 0, 0)
         self.sync_writer = scs.GroupSyncWrite(self.port_handler, self.packet_handler, 0, 0)
         self._comm_success = scs.COMM_SUCCESS