From dc012a3c17255632f1411fed8838071c09f8d5ea Mon Sep 17 00:00:00 2001 From: Amal Nanavati Date: Tue, 27 Feb 2024 11:46:45 -0800 Subject: [PATCH 01/18] [WIP] FoodOnForkDetector class, dummy instantiation, and node are in place but untested --- .pylintrc | 1 + ada_feeding_msgs/CMakeLists.txt | 1 + ada_feeding_msgs/msg/FoodOnForkDetection.msg | 11 + .../ada_feeding_perception/face_detection.py | 8 +- .../food_on_fork_detection.py | 358 ++++++++++++++++++ .../food_on_fork_detectors.py | 184 +++++++++ .../ada_feeding_perception/helpers.py | 1 + .../config/food_on_fork_detection.yaml | 17 + ada_feeding_perception/setup.py | 1 + 9 files changed, 578 insertions(+), 4 deletions(-) create mode 100644 ada_feeding_msgs/msg/FoodOnForkDetection.msg create mode 100644 ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py create mode 100644 ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py create mode 100644 ada_feeding_perception/config/food_on_fork_detection.yaml diff --git a/.pylintrc b/.pylintrc index de98f856..844df96c 100644 --- a/.pylintrc +++ b/.pylintrc @@ -201,6 +201,7 @@ good-names=a, j, k, x, + X, y, z, u, diff --git a/ada_feeding_msgs/CMakeLists.txt b/ada_feeding_msgs/CMakeLists.txt index 8f8b6bd4..9447718d 100644 --- a/ada_feeding_msgs/CMakeLists.txt +++ b/ada_feeding_msgs/CMakeLists.txt @@ -19,6 +19,7 @@ find_package(rosidl_default_generators REQUIRED) rosidl_generate_interfaces(${PROJECT_NAME} "msg/AcquisitionSchema.msg" "msg/FaceDetection.msg" + "msg/FoodOnForkDetection.msg" "msg/Mask.msg" "action/AcquireFood.action" diff --git a/ada_feeding_msgs/msg/FoodOnForkDetection.msg b/ada_feeding_msgs/msg/FoodOnForkDetection.msg new file mode 100644 index 00000000..221f3ac7 --- /dev/null +++ b/ada_feeding_msgs/msg/FoodOnForkDetection.msg @@ -0,0 +1,11 @@ +# A message with the results of food on fork detection on a single frame. + +# The header for the image the detection corresponds to +std_msgs/Header header + +# A probability in [0,1] that indicates the likelihood that there is food on the +# fork in the image. Negative values indicate error. +float64 probability + +# If an error was encountered, this field will contain the error message. +string message diff --git a/ada_feeding_perception/ada_feeding_perception/face_detection.py b/ada_feeding_perception/ada_feeding_perception/face_detection.py index 5f822457..86f3f7f8 100755 --- a/ada_feeding_perception/ada_feeding_perception/face_detection.py +++ b/ada_feeding_perception/ada_feeding_perception/face_detection.py @@ -56,6 +56,8 @@ class FaceDetectionNode(Node): let the client decide which face to use. """ + # pylint: disable=duplicate-code + # Much of the logic of this node mirrors FoodOnForkDetection. This is fine. # pylint: disable=too-many-instance-attributes # Needed for multiple model loads, publisher, subscribers, and shared variables def __init__( @@ -305,10 +307,6 @@ def toggle_face_detection_callback( the face detection on or off depending on the request. """ - # pylint: disable=duplicate-code - # We follow similar logic in any service to toggle a node - # (e.g., face detection) - self.get_logger().info(f"Incoming service request. data: {request.data}") response.success = False response.message = f"Failed to set is_on to {request.data}" @@ -563,6 +561,7 @@ def get_mouth_depth( f"Corresponding RGB image message received at {rgb_msg.header.stamp}. " f"Time difference: {min_time_diff} seconds." ) + # TODO: This should use the ros_msg_to_cv2_image helper function image_depth = self.bridge.imgmsg_to_cv2( closest_depth_msg, desired_encoding="passthrough", @@ -651,6 +650,7 @@ def run(self) -> None: continue # Detect the largest face in the RGB image + # TODO: This should use the ros_msg_to_cv2_image helper function image_bgr = cv2.imdecode( np.frombuffer(rgb_msg.data, np.uint8), cv2.IMREAD_COLOR ) diff --git a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py new file mode 100644 index 00000000..6e2c39af --- /dev/null +++ b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py @@ -0,0 +1,358 @@ +""" +This module contains a ROS2 node that: (a) takes in parameters specifying a FoodOnFork +class to use and kwargs for the class's constructor; (b) exposes a ROS2 service to +toggle the perception algorithm on and off; and (c) when the perception algorithm is +on, subscribes to the depth image topic and publishes the confidence that there is food +on the fork. +""" +# Standard imports +import collections.abc +import os +import threading +from typing import Any, Dict, Tuple + +# Third-party imports +from cv_bridge import CvBridge +import numpy as np +from rcl_interfaces.msg import ParameterDescriptor, ParameterType +import rclpy +from rclpy.callback_groups import MutuallyExclusiveCallbackGroup +from rclpy.executors import MultiThreadedExecutor +from rclpy.node import Node +from sensor_msgs.msg import CameraInfo, Image +from std_srvs.srv import SetBool +from tf2_ros.buffer import Buffer +from tf2_ros.transform_listener import TransformListener + +# Local imports +from ada_feeding.helpers import import_from_string +from ada_feeding_msgs.msg import FoodOnForkDetection +from ada_feeding_perception.food_on_fork_detectors import FoodOnForkDetector +from ada_feeding_perception.helpers import ( + get_img_msg_type, + ros_msg_to_cv2_image, +) + + +class FoodOnForkDetectionNode(Node): + """ + A ROS2 node that takes in parameters specifying a FoodOnForkDetector class to use and + kwargs for the class's constructor, exposes a ROS2 service to toggle the perception + algorithm on and off, and when the perception algorithm is on, subscribes to the + depth image topic and publishes the confidence that there is food on the fork. + """ + + # pylint: disable=duplicate-code + # Much of the logic of this node mirrors FaceDetection. This is fine. + # pylint: disable=too-many-instance-attributes + # Needed for multiple publishers/subscribers, model parameters, etc. + def __init__(self): + """ + Initializes the FoodOnForkDetection. + """ + super().__init__("food_on_fork_detection") + + # Load the parameters + ( + model_class, + model_path, + model_dir, + model_kwargs, + self.rate_hz, + ) = self.read_params() + + # Construct the FoodOnForkDetector model + food_on_fork_class = import_from_string(model_class) + assert issubclass( + food_on_fork_class, FoodOnForkDetector + ), f"Model {model_class} must subclass FoodOnForkDetector" + self.model = food_on_fork_class(**model_kwargs) + if len(model_path) > 0: + self.model.load(os.path.join(model_dir, model_path)) + + # Create the TF buffer, in case the perception algorithm needs it + self.tf_buffer = Buffer() + self.tf_listener = TransformListener(self.tf_buffer, self) + self.model.tf_buffer = self.tf_buffer + + # Create the service to toggle the perception algorithm on and off + self.is_on = False + self.is_on_lock = threading.Lock() + self.srv = self.create_service( + SetBool, + "~/toggle_food_on_fork_detection", + self.toggle_food_on_fork_detection, + callback_group=MutuallyExclusiveCallbackGroup(), + ) + + # Create the publisher + self.pub = self.create_publisher( + FoodOnForkDetection, "~/food_on_fork_detection", 1 + ) + + # Create the CameraInfo subscribers + self.camera_info_sub = self.create_subscription( + CameraInfo, + "~/camera_info", + self.camera_info_callback, + 1, + callback_group=MutuallyExclusiveCallbackGroup(), + ) + + # Create the depth image subscriber + self.cv_bridge = CvBridge() + self.depth_img = None + self.depth_img_lock = threading.Lock() + aligned_depth_topic = "~/aligned_depth" + try: + aligned_depth_type = get_img_msg_type(aligned_depth_topic, self) + except ValueError as err: + self.get_logger().error( + f"Error getting type of depth image topic. Defaulting to Image. {err}" + ) + aligned_depth_type = Image + # Subscribe to the depth image + self.depth_subscription = self.create_subscription( + aligned_depth_type, + aligned_depth_topic, + self.depth_callback, + 1, + callback_group=MutuallyExclusiveCallbackGroup(), + ) + + def read_params(self) -> Tuple[str, str, str, Dict[str, Any], float]: + """ + Reads the parameters for the FoodOnForkDetection. + + Returns + ------- + model_class: The FoodOnFork class to use. Must be a subclass of FoodOnFork. + model_path: The path to the model file. This must be relative to the model_dir + parameter. Ignored if the empty string. + model_dir: The directory to load the model from. + model_kwargs: The keywords to pass to the FoodOnFork class's constructor. + rate_hz: The rate (Hz) at which to publish. + """ + # Read the model_class + model_class = self.declare_parameter( + "model_class", + descriptor=ParameterDescriptor( + name="model_class", + type=ParameterType.PARAMETER_STRING, + description=( + "The FoodOnFork class to use. Must be a subclass of FoodOnFork." + ), + read_only=True, + ), + ) + model_class = model_class.value + + # Read the model_path + model_path = self.declare_parameter( + "model_path", + descriptor=ParameterDescriptor( + name="model_path", + type=ParameterType.PARAMETER_STRING, + description=( + "The path to the model file. This must be relative to the " + "model_dir parameter. Ignored if the empty string." + ), + read_only=True, + ), + ) + model_path = model_path.value + + # Read the model_dir + model_dir = self.declare_parameter( + "model_dir", + descriptor=ParameterDescriptor( + name="model_dir", + type=ParameterType.PARAMETER_STRING, + description=("The directory to load the model from."), + read_only=True, + ), + ) + model_dir = model_dir.value + + # Read the model_kwargs + model_kwargs = {} + model_kws = self.declare_parameter( + "model_kws", + descriptor=ParameterDescriptor( + name="model_kws", + type=ParameterType.PARAMETER_STRING_ARRAY, + description=( + "The keywords to pass to the FoodOnFork class's constructor." + ), + read_only=True, + ), + ) + for kw in model_kws.value: + full_name = f"model_kwargs.{kw}" + arg = self.declare_parameter( + full_name, + descriptor=ParameterDescriptor( + name=kw, + description="Custom keyword argument for the model.", + dynamic_typing=True, + read_only=True, + ), + ) + if isinstance(arg, collections.abc.Sequence): + arg = list(arg.value) + else: + arg = arg.value + model_kwargs[kw] = arg + + # Get the rate at which to operate + rate_hz = self.declare_parameter( + "rate_hz", + 10.0, + descriptor=ParameterDescriptor( + name="rate_hz", + type=ParameterType.PARAMETER_DOUBLE, + description="The rate (Hz) at which to publish.", + read_only=True, + ), + ) + rate_hz = rate_hz.value + + return ( + model_class, + model_path, + model_dir, + model_kwargs, + rate_hz, + ) + + def toggle_food_on_fork_detection( + self, request: SetBool.Request, response: SetBool.Response + ) -> SetBool.Response: + """ + Toggles the perception algorithm on and off. + + Parameters + ---------- + request: The request to toggle the perception algorithm on and off. + response: The response to toggle the perception algorithm on and off. + + Returns + ------- + response: The response to toggle the perception algorithm on and off. + """ + + self.get_logger().info(f"Incoming service request. data: {request.data}") + response.success = False + response.message = f"Failed to set is_on to {request.data}" + with self.is_on_lock: + self.is_on = request.data + response.success = True + response.message = f"Successfully set is_on to {request.data}" + return response + + def camera_info_callback(self, msg: CameraInfo) -> None: + """ + Callback for the camera info. Note that we assume CameraInfo never + changes, and therefore destroy the subscriber after the first message. + + Parameters + ---------- + msg: The camera info message. + """ + if self.model.camera_info is None: + self.model.camera_info = msg + self.destroy_subscription(self.camera_info_sub) + + def depth_callback(self, msg: Image) -> None: + """ + Callback for the depth image. + + Parameters + ---------- + msg: The depth image message. + """ + with self.depth_img_lock: + self.depth_img = msg + + def run(self) -> None: + """ + Runs the FoodOnForkDetection. + """ + rate = self.create_rate(self.rate_hz) + while rclpy.ok(): + # Loop at the specified rate + rate.sleep() + + # Check if food on fork detection is on + with self.is_on_lock: + is_on = self.is_on + if not is_on: + continue + + # Create the FoodOnForkDetection message + food_on_fork_detection_msg = FoodOnForkDetection() + + # Get the latest depth image + with self.depth_img_lock: + depth_img_msg = self.depth_img + self.depth_img = None + if depth_img_msg is None: + continue + food_on_fork_detection_msg.header = depth_img_msg.header + + # Convert the depth image to a cv2 image + depth_img_cv2 = ros_msg_to_cv2_image(depth_img_msg, self.cv_bridge) + X = np.expand_dims(depth_img_cv2, axis=0) + + # Get the probability that there is food on the fork + try: + proba = self.model.predict_proba(X) + food_on_fork_detection_msg.probability = proba + except Exception as err: + # pylint: disable=broad-except + # This is necessary because we don't know what exceptions the model + # might raise. + + err_str = f"Error predicting food on fork: {err}" + self.get_logger().error(err_str) + food_on_fork_detection_msg.probability = -1.0 + food_on_fork_detection_msg.message = err_str + + # Publish the FoodOnForkDetection message + self.pub.publish(food_on_fork_detection_msg) + + +def main(args=None): + """ + Launch the ROS node and spin. + """ + rclpy.init(args=args) + + food_on_fork_detection = FoodOnForkDetectionNode() + executor = MultiThreadedExecutor(num_threads=4) + + # Spin in the background since detecting faces will block + # the main thread + spin_thread = threading.Thread( + target=rclpy.spin, + args=(food_on_fork_detection,), + kwargs={"executor": executor}, + daemon=True, + ) + spin_thread.start() + + # Run face detection + try: + food_on_fork_detection.run() + except KeyboardInterrupt: + pass + + # Terminate this node + food_on_fork_detection.destroy_node() + rclpy.shutdown() + # Join the spin thread (so it is spinning in the main thread) + spin_thread.join() + + +if __name__ == "__main__": + main() diff --git a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py new file mode 100644 index 00000000..258ecab6 --- /dev/null +++ b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py @@ -0,0 +1,184 @@ +""" +This file contains an abstract class, FoodOnForkDetector, that takes in a single depth +image and returns a confidence in [0,1] that there is food on the fork. +""" +# Standard imports +from abc import ABC, abstractmethod +from enum import Enum + +# Third-party imports +import numpy as np +import numpy.typing as npt +from sensor_msgs.msg import CameraInfo +from tf2_ros.buffer import Buffer + + +class FoodOnForkLabel(Enum): + """ + An enumeration of possible labels for food on the fork. + """ + + UNSURE = -1 + NO_FOOD = 0 + FOOD = 1 + + +class FoodOnForkDetector(ABC): + """ + An abstract class for any perception algorithm that takes in a single depth + image and returns a confidence in [0,1] that there is food on the fork. + """ + + def __init__(self) -> None: + """ + Initializes the perception algorithm. + """ + self.__camera_info = None + self.__tf_buffer = None + + @property + def camera_info(self) -> CameraInfo: + """ + The camera info for the depth image. + + Returns + ------- + camera_info: The camera info for the depth image. + """ + assert self.__camera_info is not None, "Camera Info has not been set." + return self.__camera_info + + @camera_info.setter + def camera_info(self, camera_info: CameraInfo) -> None: + """ + Sets the camera info for the depth image. + + Parameters + ---------- + camera_info: The camera info for the depth image. + """ + self.__camera_info = camera_info + + @property + def tf_buffer(self) -> Buffer: + """ + The tf buffer for the depth image. + + Returns + ------- + tf_buffer: The tf buffer for the depth image. + """ + assert self.__tf_buffer is not None, "TF Buffer has not been set." + return self.__tf_buffer + + @tf_buffer.setter + def tf_buffer(self, tf_buffer: Buffer) -> None: + """ + Sets the tf buffer for the depth image. + + Parameters + ---------- + tf_buffer: The tf buffer for the depth image. + """ + self.__tf_buffer = tf_buffer + + @abstractmethod + def fit(self, X: npt.NDArray, y: npt.NDArray[FoodOnForkLabel]) -> None: + """ + Trains the perception algorithm on a dataset of depth images and + corresponding labels. + + Parameters + ---------- + X: The depth images to train on. + y: The labels for the depth images. + """ + + @abstractmethod + def save(self, path: str) -> None: + """ + Saves the perception algorithm to a file. + + Parameters + ---------- + path: The path to save the perception algorithm to. + """ + + @abstractmethod + def load(self, path: str) -> None: + """ + Loads the perception algorithm from a file. + + Parameters + ---------- + path: The path to load the perception algorithm from. + """ + + @abstractmethod + def predict_proba(self, X: npt.NDArray) -> npt.NDArray[FoodOnForkLabel]: + """ + Predicts the probability that there is food on the fork for a set of + depth images. + + Parameters + ---------- + X: The depth images to predict on. + + Returns + ------- + y: The predicted probabilities that there is food on the fork. + """ + + def predict( + self, X: npt.NDArray, lower_thresh: float, upper_thresh: float + ) -> npt.NDArray[FoodOnForkLabel]: + """ + Predicts whether there is food on the fork for a set of depth images. + + Parameters + ---------- + X: The depth images to predict on. + lower_thresh: The lower threshold for food on the fork. + upper_thresh: The upper threshold for food on the fork. + + Returns + ------- + y: The predicted labels for whether there is food on the fork. + """ + proba = self.predict_proba(X) + return np.where( + proba < lower_thresh, + FoodOnForkLabel.NO_FOOD, + np.where( + proba > upper_thresh, FoodOnForkLabel.FOOD, FoodOnForkLabel.UNSURE + ), + ) + + +class FoodOnForkDummyDetector(FoodOnForkDetector): + """ + A dummy perception algorithm that always predicts the same probability. + """ + + def __init__(self, proba: float) -> None: + """ + Initializes the dummy perception algorithm. + + Parameters + ---------- + proba: The probability that the dummy algorithm should always predict. + """ + super().__init__() + self.proba = proba + + def fit(self, X: npt.NDArray, y: npt.NDArray[FoodOnForkLabel]) -> None: + pass + + def save(self, path: str) -> None: + pass + + def load(self, path: str) -> None: + pass + + def predict_proba(self, X: npt.NDArray) -> npt.NDArray[FoodOnForkLabel]: + return np.full(X.shape[0], self.proba) diff --git a/ada_feeding_perception/ada_feeding_perception/helpers.py b/ada_feeding_perception/ada_feeding_perception/helpers.py index c1a89226..1116a89e 100644 --- a/ada_feeding_perception/ada_feeding_perception/helpers.py +++ b/ada_feeding_perception/ada_feeding_perception/helpers.py @@ -44,6 +44,7 @@ def ros_msg_to_cv2_image( bridge = CvBridge() return bridge.imgmsg_to_cv2(msg, desired_encoding="passthrough") if isinstance(msg, CompressedImage): + # TODO: This shoudl use bridge as well return cv2.imdecode(np.frombuffer(msg.data, np.uint8), cv2.IMREAD_UNCHANGED) raise ValueError("msg must be a ROS Image or CompressedImage") diff --git a/ada_feeding_perception/config/food_on_fork_detection.yaml b/ada_feeding_perception/config/food_on_fork_detection.yaml new file mode 100644 index 00000000..ca6bff1d --- /dev/null +++ b/ada_feeding_perception/config/food_on_fork_detection.yaml @@ -0,0 +1,17 @@ +# NOTE: You have to change this node name if you change the node name in the launchfile. +food_on_fork_detection: + ros__parameters: + # The FoodOnFork class to use + model_class: "ada_feeding_perception.food_on_fork_detectors.FoodOnForkDummyDetector" + # The path to load the model from. Ignored if the empty string. + # Should be relative to ada_feeding_perception's share directory. + model_path: "" + # Keywords to pass to the FoodOnFork class's constructor + model_kws: + - proba + # Keyword arguments to pass to the FoodOnFork class's constructor + model_kwargs: + proba: 0.5 + + # The rate at which to detect and publish the confidence that there is food on the fork + rate_hz: 10.0 \ No newline at end of file diff --git a/ada_feeding_perception/setup.py b/ada_feeding_perception/setup.py index 8a002894..6ab82bb7 100644 --- a/ada_feeding_perception/setup.py +++ b/ada_feeding_perception/setup.py @@ -46,6 +46,7 @@ tests_require=["pytest"], entry_points={ "console_scripts": [ + "food_on_fork_detection = ada_feeding_perception.food_on_fork_detection:main", "republisher = ada_feeding_perception.republisher:main", "segment_from_point = ada_feeding_perception.segment_from_point:main", "test_segment_from_point = ada_feeding_perception.test_segment_from_point:main", From f356cceae1d9119871804b3296ea564a1556f974 Mon Sep 17 00:00:00 2001 From: Amal Nanavati Date: Tue, 27 Feb 2024 16:18:42 -0800 Subject: [PATCH 02/18] Tested dummy food on fork detector --- .../food_on_fork_detection.py | 2 +- .../food_on_fork_detectors.py | 11 +++---- .../launch/ada_feeding_perception.launch.py | 31 +++++++++++++++++++ 3 files changed, 37 insertions(+), 7 deletions(-) diff --git a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py index 6e2c39af..9f9662d0 100644 --- a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py +++ b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py @@ -306,7 +306,7 @@ def run(self) -> None: # Get the probability that there is food on the fork try: - proba = self.model.predict_proba(X) + proba = self.model.predict_proba(X)[0] food_on_fork_detection_msg.probability = proba except Exception as err: # pylint: disable=broad-except diff --git a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py index 258ecab6..06ce1573 100644 --- a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py +++ b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py @@ -5,6 +5,7 @@ # Standard imports from abc import ABC, abstractmethod from enum import Enum +from typing import Optional # Third-party imports import numpy as np @@ -37,15 +38,14 @@ def __init__(self) -> None: self.__tf_buffer = None @property - def camera_info(self) -> CameraInfo: + def camera_info(self) -> Optional[CameraInfo]: """ The camera info for the depth image. Returns ------- - camera_info: The camera info for the depth image. + camera_info: The camera info for the depth image, or None if not set. """ - assert self.__camera_info is not None, "Camera Info has not been set." return self.__camera_info @camera_info.setter @@ -60,15 +60,14 @@ def camera_info(self, camera_info: CameraInfo) -> None: self.__camera_info = camera_info @property - def tf_buffer(self) -> Buffer: + def tf_buffer(self) -> Optional[Buffer]: """ The tf buffer for the depth image. Returns ------- - tf_buffer: The tf buffer for the depth image. + tf_buffer: The tf buffer for the depth image, or None if not set. """ - assert self.__tf_buffer is not None, "TF Buffer has not been set." return self.__tf_buffer @tf_buffer.setter diff --git a/ada_feeding_perception/launch/ada_feeding_perception.launch.py b/ada_feeding_perception/launch/ada_feeding_perception.launch.py index 309240c1..86c99620 100755 --- a/ada_feeding_perception/launch/ada_feeding_perception.launch.py +++ b/ada_feeding_perception/launch/ada_feeding_perception.launch.py @@ -145,4 +145,35 @@ def generate_launch_description(): ) launch_description.add_action(face_detection) + # Load the food-on-fork detection node + food_on_fork_detection_config = os.path.join( + ada_feeding_perception_share_dir, "config", "food_on_fork_detection.yaml" + ) + food_on_fork_detection_params = {} + food_on_fork_detection_params["model_dir"] = ParameterValue( + os.path.join(ada_feeding_perception_share_dir, "model"), value_type=str + ) + food_on_fork_detection_remappings = [ + ("~/food_on_fork_detection", "/food_on_fork_detection"), + ("~/toggle_food_on_fork_detection", "/toggle_food_on_fork_detection"), + ( + "~/aligned_depth", + PythonExpression( + expression=[ + "'", + prefix, + "/camera/aligned_depth_to_color/image_raw'", + ] + ), + ), + ] + food_on_fork_detection = Node( + package="ada_feeding_perception", + name="food_on_fork_detection", + executable="food_on_fork_detection", + parameters=[food_on_fork_detection_config, food_on_fork_detection_params], + remappings=realsense_remappings + food_on_fork_detection_remappings, + ) + launch_description.add_action(food_on_fork_detection) + return launch_description From da2e2f54df7711e74dfc4c6c370d24bc4bce4d1e Mon Sep 17 00:00:00 2001 From: Amal Nanavati Date: Wed, 28 Feb 2024 10:43:48 -0800 Subject: [PATCH 03/18] Deleted mistakenly added fork handle masks --- .../model/fork_handle_mask.png | Bin 8256 -> 0 bytes .../model/fork_handle_mask_with_shadow.png | Bin 7919 -> 0 bytes 2 files changed, 0 insertions(+), 0 deletions(-) delete mode 100644 ada_feeding_perception/model/fork_handle_mask.png delete mode 100644 ada_feeding_perception/model/fork_handle_mask_with_shadow.png diff --git a/ada_feeding_perception/model/fork_handle_mask.png b/ada_feeding_perception/model/fork_handle_mask.png deleted file mode 100644 index 4728560597ff7406f2751a7d0240e5338cde45fc..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 8256 zcmeHLdpwkB`+sJLA&Qja${1Q(?VQJ9#%VI+R5`1Z(3p9K(J(TD8Kp)CNs3y#DIt}P zs?}->Ib@wWs1W588>N!a2?_5#RNKD4-F@Ho^SaCVKI*j zLE@HB_g2+k&?@hO5_d}t)U>x7dp}jsFI6=2ob}q6-$mZuce^wzTC7Uo-Om4hwQ#p| z`I$Dg)ZpL-&pSL5dR~xVacYpstG9lV<$B&p0)f$UgN8`{w zl$~}vJ(SZqJ6MJjZ}QbPdS|UnG!1#&27=qlV=&yE8H^9{fG7^e?y+|I#eMcRH?N$- za~4_7URUFu@$4{W_o{6eZ`1|5(=)!tk8Sx{)j4tJkNMI=M6@O0qgIkBiUYKBaht0UZ- zx>*q0?uBpkI~X)FG`4aqWvX{#RD(w)%V<^<({&Tuw-ZR|Rod!~B4nnB0i_4|11<0ZuPyP*eH1wzMR(GP?u&oT(tD@ zcZTWb7f$0TZ9@)hbm&Nxiw}#tZz>2oBRpsW=^R-0RKdbRzA7=b`1#A{nKui@S{n{@ z%p_+=?0P=8>MW?c7#^rEAD5*xwjdP8;s^p^oH#Tb6dnXw*^0wi?6t569S8^U!mKg< zMWq-tk7JElVd_F~31`5;Jg1ll*ek}>n;o;3P32&0ZIrFVGyo6^i&$uJC_hX{6I){@ zacSULwv5N1Cq+bStua0>?r4S}0!CAC6dVC-FXly&FgD6)s|XI4=E-z;4*|YeV}eDZ za2g&T9UYB}CgTJVL3kpSO2rdMcoGQ%LK1U4Bd(c)>Id|d-fqlv3 z(o{=%!Rw~JO?~C_CVL5up6m)5i#-*BkQD`UCjA6hQ(Np{R#*@W#>e}5{jkpagIXYP z$fmHF85?VE4mz7cGUZ^Yq(C;-)Pg{?u;3CcIA;HZE);M@(X0q~Q4rt}a0Tjfk}LE# zQz@MPduO79VOf3vV^|^)`x|4F_l)7+M~s(EjSnGP;r|aQR+9psj2WOewFbr)n1=X| zxFu~+Pw zj+muvhMCdc1wk`=oSBQf#Vvj9lBCqv`qhK|a@X_3>^t{@cZDWCP*0enw%VPw$iw|R zK`F%!)BvaylZtEsv#5)zMmzfNP;>~AM}z-h zsDVp93X($d5FJAP(e|G#|Hrld!iB%E^*6NsI@~|A^}o{k*9rL}4?kb)-%I{K+xmR1 zf4|T^we`Q!`n*>7;Njk{e|$KBZ9w>lQ)C6f@g{RLf%l!iOf~t#u~J3A>i;V=|eceYbrI zA}U?SS{%QMTzdIk^=k(O1d6_@E&Tey;j1%`ZFqhwc64jk5g{`-p!k?esblhy(WAqaN0zt+{sblvJ4{bfL84g6bH#4 zN^`Y@nO22-UdY6TWkCluYIi<=NtbPCD`bVQ&h`Ip+&n;hDo!+*L5E1EqWkafPbf`D zIOWkJE<@WNgpi!qNdE`PF}%~b9zV@pLpKM@fHE47(EfEf;pjHsGAMQFKIeUUi24C! zy%L)4fbZ0?LL`MNqj;V2YO)GXi7HNhy06)Gea{XpF_e9y4XIF*cFw@kczop9sihOP z;-_&hB9N#Q!}Yt;Q%8n(COB1P^9tJyoF96E*vC01kf5etO;r?13(`&-j- zBqU(*1*ZYuzx&A9OfCv^eD~F?uuOG1ZmpSoYFcs}qNd)yXtRyNqpq0yq=o+bW40-3 zgPxEml_ew;hrN|tj_zxm%aQ5LgN!hzg4#7zSFC;>C(EHfl29Ivit`-!dg|r-upzcd z-$5Gn2oU}Qu7!GO+E?mzp>HzsBCl~~TF4xkB~>rcRBQPT@N(31h<8^9(b8LaRD&*6 z@yi#AklN~XtQ(JmCBboua}&n|*X5xn7dy^GSDw{+)c3wVAI}%O?Z3p{tk{WgHk-kt+2kRljC$Ms6#{5>!!Ip^0o@}@ItR(?rweGpPBqt zU6=mL8ryu2>*eV8NgDd{Mp~Ar%F>-*ct3WNu}f{<*jTN{a9)3$Z%Cupx#W1?Fp4}< zP5S089OWl!Yf@`HTY62K7n{Vrv8!q=&P=xV^T|w!qbMXKanpp;FpNV93dy?XUSGL` zqDvF=Tg!7iY`IL2O|^E}YRmQo=wmN-@H>-wX|ZAaqMKLI%{}ZjkWEr4wG{QbMOJY3H`hX+1{0%IaAbK(^N94u{PH;CFgAjGd{wJTjJ0 zn5DDDtd}r&IC%exAe20s9+H)ND@%7u8u##LE7T0t8=8tgZ6$q=MJ=X`%( zboHC)j^vrg0@kWrn=oEq&#QYoY!nZQIDeltE<@AcMg|L2Kg6*VbMnuM)@vhB?gw|? z`;}qjzmkPIpZ(^}H{S;E6|db?TqL)@@#MZ?BldDD-Hed<@gXJg9r1ei60KXVP~5jq z+txZ!O7pL&aeVu(dia#wnE@QfdqzGc*1c#E#vj6nPUw7v?Om?BxqiHuj7XW+Xg!)} zyI^r|!)c83UMGbaM1^@>@@h_J5N!O;CViK|w(=r&zyBC}^iBMUj#r0SC-_^oGg&$3 zLhT_WRdjE@Mpq*|q_=s)DIM)?k!$)=K9=&ua+PtkAem`stjw;t9FYc5|oQ3NB= z*cngO?;YNf%=0V4(B2rV0d%|Xe>;;#^zRtnYS`JJeu))p>^w_9WV@~$0_DBixhGRg zugRK+8n#tlxPnOTeX=CtsZuHKOKD_=(03Zgi8_VSpzt&seA?M+9jD`IzQ z>LQ~aDZRVY671Kdib2uQjIWdR3?gURtU(3u+_(kP961#1msg<)b{-B!H#K_<-QK{U z?-Awd%(ZO7lH~&qn8!i$Od}r{4=UO>y?E7CcY&K`I9v}#);#h^?x4p|N^8k&|H4<6 zHoE4yvO0FEn`Yvi1mz50Gz<61Kl{4i0E$kB>`GKD43%%?o|ntIeiuU0=fy-tiUzLK zfo`tZSKhGpNb8PYRIdbGnx>Nad~=s3A=SQmyt;CC&|U4#$zUK!mG7P(Kl%91ggj%Q zRI3}LcduXgLCCII(qdAsgoe5oSC5-IlqsRz%ct+wpgV0pGHTE2Qn2h!(*Oq2ZLPHQ zM^*C~nE@%52>HcPSJoj>CozZ@*JY~1_RZUEX-QwfDOT2R0J5h|GxWqnbwL(T?feek zG{dF|_5HZ^N5%byGZ&#10Vmsa!@Beu z%9E5>881bFZ9YceK7)4S)^0+dwOW7K5V}@@U2}+EVjHvcU0|IZgI?vd{h1JnN_A;3 zpSG@Yt5Uo)sk!gaT!$J9;9Ikw_|b_=L05i>m#Q>BESu{wF|(u55j5w+!0wDIDb!h* zBJgtYWIZ@(qK5!YD$Rg_5EvlNjknErrFeuP) zp9l&wIK6AVfx27quoi>v@GN2=+hd~YbUcVLv_UvA#%@R#=pspWuAo&9-#cDNyC2G@ z$fM|qH`3`+@3&3&+ba!ZeRa5hkz!RqM=KvylLBV>+q_<>?v|rtgAvoUow_uX+;s}| z{q%gzapu6Hnl#0var?}~cw1W-g+QSpL$|`YH1yBKZ<7o?%K?EWNrM$2Nz+2wUhzeJ zb=7J-Np>G-{6_n$PYk^Caf${yy9Adx2_!(-(W(NI8D>cDOMRO*QE3L@35H-yR@fVD zua0#)YbM`Ke_853QBhq5T6eT5iMUj$0915)cZ1uG!piF^2{~t^zk_|UG-!@0auF_Zq!<@V)cufeWxbD{q6K*-%`4ss8_g{A3IKD zXoDJLlwHNcLFbtTkc! z1PFq(TwNSIAxK3AL5N34bs!H zMw;HAs~6fd&f{g%D(e(8cEpCMap~7@?tZUv6}MZAy3W*2z<68;<|g7G;v@ zILp;`@AAY$h5A!^h3@kzwO9E0?A}@=r-Je}aP93qTXUY^8g%gm!zYcCklW4-Q`nE@`Y;8Gm}jQiNg~NLiiZoINNU3fDqQ9 zU}I*?HZ|QU3*5Dq+UA<|;T7TANtl9lnkJTA4o50iTIFPu%70DNMm}m_kjaM0*F3^w z?%&L=EkP_hK3rn6Vm;wW=8f#}X}c-&u%#wex%=xDJeV{wb77Qc-|E7LThzZd$`EY- zz*u*<>Su2J5)rC)$r|Mi@81*?XVxdi|e*rMWzwG zPw64;Z~oX3^TzJ=M7;u9*FfXzALc!ZOI%p;+|M$;-o3uy_{yg!s(DLm@z2vrL`CC# z-6{9$7j5;+$L>pfZ}#D^n)HF)ivUW&FSH}tsBI?#1^y#YKf!bTvD#)#UeVCN;jIs~ zTWDfl_P3<%pzWf#puM~qi>WLj-;~J~25?Lx_#)7E5M*T&A!4#ZI8r!(6T}tJ&|M|v zXqd~Up;wR?IEKic6U=pq5_6VDE%9PSg|H}Ww2k!ys|YFp;B%x*ID*d;NT?Asv=WyJ z-YdjdG^{j{hS1R73=h~|DCWRKQ=%yj;~2pWBcQD(z*b^*Al1{s=_3TVqM?JOQV|u4 z4G#}D4L36tii5Ct3Wb8j5wHXT23TMukpd|*0wa(ZDwn8yug%VJvkC# zsF=lZ4C4r-#$Q4>yD~gJBPdD=;_^kxq5yfn3&v)BwiAVlc}g2L3(Mhg_yAM_^27hm zUdj#pjjZ40rqC$M`7#j@?lb=HtUuMRGzL}-2Gv2x3RMJkb)caY`BK?J7MD#`zQtLv zEzF5b3IWL)1zpMHeVLU4iVdL1EEbt;Mj>O! z1P&WR#F3a73WdnRumXu@6eixxf=C(7MsW^QTMt(nnqZ1kf-5B+Jf<{IDCX193?>V9 zU;3NIi_7OMl`<8q;ms))78d3N@PmlQ5zT)yTFwzmK*uRS@iuuLUArsPz_*~sc2MytdxUdsPg)0H^BbB1jky^@G zH+nUC$>S<#35JzZL1nT=OOP5He6ePL->3|%FR%@(m=xh z%h$)l_+N&A;jcl)#P3(SzS1=&2F7IkwY$F3H6{keWc;(Hlu&8 zZ5#wm-0A9I>lJbL)%_6OzR;N!Jr8g0;LqH)%Fabo_l9V){KDq%@&ze*&1_ra#dcM& z+yTMVdxD;;zhzM)RlcaSG#&NEk-P>@_^DH~`p(IewFC#%Ysdw=lXcM(PAn`i^jo|m zRm&;7_F3fqj*$7;razx1>2uX(^H5mL20|g%P zk&p~hgXoY71Ve~FQvVzAf8Fa(QuvctWB2+Kus>nr|K|1A2l7X$jNR++9sWPZ8oSru zZ?rFC{lC1%HVU6I9J|-p$4(Jz>|QXm8Tzwf{#3y~4fVef|HX#*54^_SrwXpe?lty4 zRdD^cyy(8Zk=IFEI8C*urv=5%LZeT0e&{qUkNpsSiexf>!-}^N+qY+i-0^z%tj@ZpZRz9PHd^`wz(jBBoszC(qgY|RVO*Ew^^!DK9ej7+-OS-s z*5NGOI&A@g2kK~Ry+XS>_f3~&pi_|5$SrEZrubkp6`A-$zx>6#!LDXPVQj(EbAEtU z`sOu}Pcj-yBPAzR=6$=v)HicrI9B{Rd1OG``$%tfdn z?^%P-5u}YwSE8mly9SR1CFr(nqxL@OTUf?Hf~)6s`PlOP15fH6w;2e`k-^p4Rh_EH z?Y&nR-IJYaTIb~CbWjsyLw<@dQ-Q;^03LZ`y zDSM`#0H}utJ%24@b2a_KPuhY(Ld7mv=M!HoF%G8pA!b+aq01^aX07i#)RI2O2Co*3 zbFQGDI^f=Yh`Y8cw=w^zn*w5X&%w4Srh{2mClOPP{b6#;ykY$p>3hnBAma^$Y3pwW zw$$t|jjDN7A636oOJ#bGeSxvRzx-m|i~ggV7EFyJ<&U&mD}a)$`$VtKmnXG2J|rTy zwj=d}gZqj?zll6MRJ^eDk!ADR#B)uM%GYlfs-)y9J z;oYTzSG`ULbNrTet`4McAJ7Ojpl7$w)2(;D!YGUJNoj7YzO{Xm7VNRKFWJVkyZ!nK z#~qydVb&g7H8?$D&~~kppoluLFf`fLW3WTyTp{aA=m{zB$=5HtcqGGPvAL|G(CgdD z_OhhL*bYp6R8xVL3Ie&k;m*lb2MP)rXhZ%f_3PuN`0Q}JI&P=F`uD9!{l=Q_IY( z(ZQX0u`T|((c-z=MBT|wY!XNldQ!$2qcp3a`k2H(Nlgw6NxFt{w}-jou@B(dpgbJsyy^m zc-zfvqd`72t7RV4qfyi#Uh7iPwUWHrcYYS4F<~;;=kh(DOYS zuHfG+xm=B^V9p^QoN21;r;W`I#_8s8eZ3m2X7KlQWR82h3e^bNT`{~>slAmLxja1O z&Bz59B?Gg05G`tdhVN~AtbSn)sINz3d)1yjcRCA$9_>A=nV?-RXoTYXRNbDQi~R0> z_b$pAXJt-=yL}Poq_rdsH8{xzo^yLR6#w>wL^J;W=~<~V+d;&WJ9qKq2Tg@{;KnQJ zs0oKXkLj!6OuHsp=?sKkGed^uA~wot!Tb@~^um{un5xKDZ5OwY8lHWHI;zSjeeW}~ z1Ju5Ql-bvmmzg$#AMWhl*Ph-RdPymmJ3igifR2izSJvUXV)9H1Z_w4?8;djC90w7T ze(vv9wPdCDhM1{be(2r?F=7mDmDc3Ba$!tng-)0q0$zGU@T(1w*om%j0s zZ9LK!vY2{pov6t|B{4a=V!TaucAH(1lCj3)S2oQQA{D(#cY6@^p=j63`QG5}{g~sU zv-QJ0+cf2BrRu2ZL-5%lRW~Q9UX~)UkGK2!1#X7|kWky!2FUJ!;p)`54O=tAs_J|C zZ%j#;k5g0*J?^bu6!#<7c}57zv1~~b1U{h}r|QZJdC*U_rSG(5rDqWvqil}yMr01r zFO%G>L+siI$a$d)?wdiDb~m4VB9Y@q6{>r=CmT{jtppcsLw z$btSxAmgKZ?1L~VI|uGBU8bPKmIqP--yU?Qrbjh57t7e3Vu@Ne0mc znl`@4+^l^;K;2vOPCI*DKJC0Y7)VujN(~O&+@^1BP>-AHv*Xf*eSSnu1oAp(Km(UE zd~?K~?K5Rlm>*C7ZSjuCNnmNolVpYo-GEyO& Date: Wed, 28 Feb 2024 12:09:40 -0800 Subject: [PATCH 04/18] [WIP] added and tested train-test script --- .pylintrc | 4 + .../food_on_fork_detection.py | 7 +- .../food_on_fork_detectors.py | 67 ++- .../food_on_fork_train_test.py | 450 ++++++++++++++++++ 4 files changed, 513 insertions(+), 15 deletions(-) create mode 100644 ada_feeding_perception/ada_feeding_perception/food_on_fork_train_test.py diff --git a/.pylintrc b/.pylintrc index 844df96c..0ef39e4f 100644 --- a/.pylintrc +++ b/.pylintrc @@ -197,9 +197,11 @@ good-names=a, b, c, d, + f, i, j, k, + n, x, X, y, @@ -216,6 +218,8 @@ good-names=a, kw, ns, Run, + train_X, + test_X, _ # Good variable names regexes, separated by a comma. If names match any regex, diff --git a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py index 9f9662d0..e65625b5 100644 --- a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py +++ b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py @@ -308,11 +308,10 @@ def run(self) -> None: try: proba = self.model.predict_proba(X)[0] food_on_fork_detection_msg.probability = proba + # pylint: disable=broad-except + # This is necessary because we don't know what exceptions the model + # might raise. except Exception as err: - # pylint: disable=broad-except - # This is necessary because we don't know what exceptions the model - # might raise. - err_str = f"Error predicting food on fork: {err}" self.get_logger().error(err_str) food_on_fork_detection_msg.probability = -1.0 diff --git a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py index 06ce1573..48628a07 100644 --- a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py +++ b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py @@ -5,11 +5,13 @@ # Standard imports from abc import ABC, abstractmethod from enum import Enum +import time from typing import Optional # Third-party imports import numpy as np import numpy.typing as npt +from overrides import override from sensor_msgs.msg import CameraInfo from tf2_ros.buffer import Buffer @@ -36,6 +38,7 @@ def __init__(self) -> None: """ self.__camera_info = None self.__tf_buffer = None + self.__seed = int(time.time() * 1000) @property def camera_info(self) -> Optional[CameraInfo]: @@ -81,6 +84,28 @@ def tf_buffer(self, tf_buffer: Buffer) -> None: """ self.__tf_buffer = tf_buffer + @property + def seed(self) -> int: + """ + The random seed to use in the detector. + + Returns + ------- + seed: The random seed to use in the detector. + """ + return self.__seed + + @seed.setter + def seed(self, seed: int) -> None: + """ + Sets the random seed to use in the detector. + + Parameters + ---------- + seed: The random seed to use in the detector. + """ + self.__seed = seed + @abstractmethod def fit(self, X: npt.NDArray, y: npt.NDArray[FoodOnForkLabel]) -> None: """ @@ -94,23 +119,30 @@ def fit(self, X: npt.NDArray, y: npt.NDArray[FoodOnForkLabel]) -> None: """ @abstractmethod - def save(self, path: str) -> None: + def save(self, path: str) -> str: """ - Saves the perception algorithm to a file. + Saves the model to a file. Parameters ---------- - path: The path to save the perception algorithm to. + path: The path to save the perception algorithm to. This file should not + have an extension; this function will add the appropriate extension. + + Returns + ------- + save_path: The path that the model was saved to. """ @abstractmethod def load(self, path: str) -> None: """ - Loads the perception algorithm from a file. + Loads the model a file. Parameters ---------- - path: The path to load the perception algorithm from. + path: The path to load the perception algorithm from. If the path does + not have an extension, this function will add the appropriate + extension. """ @abstractmethod @@ -129,7 +161,11 @@ def predict_proba(self, X: npt.NDArray) -> npt.NDArray[FoodOnForkLabel]: """ def predict( - self, X: npt.NDArray, lower_thresh: float, upper_thresh: float + self, + X: npt.NDArray, + lower_thresh: float, + upper_thresh: float, + proba: Optional[npt.NDArray] = None, ) -> npt.NDArray[FoodOnForkLabel]: """ Predicts whether there is food on the fork for a set of depth images. @@ -139,17 +175,22 @@ def predict( X: The depth images to predict on. lower_thresh: The lower threshold for food on the fork. upper_thresh: The upper threshold for food on the fork. + proba: The predicted probabilities that there is food on the fork. If + None, this function will call predict_proba to get the probabilities. Returns ------- y: The predicted labels for whether there is food on the fork. """ - proba = self.predict_proba(X) + if proba is None: + proba = self.predict_proba(X) return np.where( proba < lower_thresh, - FoodOnForkLabel.NO_FOOD, + FoodOnForkLabel.NO_FOOD.value, np.where( - proba > upper_thresh, FoodOnForkLabel.FOOD, FoodOnForkLabel.UNSURE + proba > upper_thresh, + FoodOnForkLabel.FOOD.value, + FoodOnForkLabel.UNSURE.value, ), ) @@ -170,14 +211,18 @@ def __init__(self, proba: float) -> None: super().__init__() self.proba = proba + @override def fit(self, X: npt.NDArray, y: npt.NDArray[FoodOnForkLabel]) -> None: pass - def save(self, path: str) -> None: - pass + @override + def save(self, path: str) -> str: + return "" + @override def load(self, path: str) -> None: pass + @override def predict_proba(self, X: npt.NDArray) -> npt.NDArray[FoodOnForkLabel]: return np.full(X.shape[0], self.proba) diff --git a/ada_feeding_perception/ada_feeding_perception/food_on_fork_train_test.py b/ada_feeding_perception/ada_feeding_perception/food_on_fork_train_test.py new file mode 100644 index 00000000..1f95ab54 --- /dev/null +++ b/ada_feeding_perception/ada_feeding_perception/food_on_fork_train_test.py @@ -0,0 +1,450 @@ +""" +This script takes in a variety of command line arguments and then trains and test a +FoodOnForkDetector as configured by the arguments. +""" + +# Standard Imports +import argparse +import json +import os +import textwrap +import time +from typing import Any, Dict, Tuple + +# Third-party imports +import cv2 +import numpy as np +import numpy.typing as npt +import pandas as pd +from sklearn.metrics import ( + accuracy_score, + confusion_matrix, + f1_score, + precision_score, + recall_score, +) +from sklearn.model_selection import train_test_split + +# Local imports +from ada_feeding.helpers import import_from_string +from ada_feeding_perception.food_on_fork_detectors import FoodOnForkDetector + + +def read_args() -> argparse.Namespace: + """ + Read the command line arguments. + + Returns + ------- + args: argparse.Namespace + The command line arguments. + """ + parser = argparse.ArgumentParser( + description=( + "Train and test one or more FoodOnForkDetectors on an offline dataset." + ) + ) + + # Configure the models + parser.add_argument( + "--model-classes", + help=( + "A JSON-encoded string where keys are an arbitrary model ID and " + "values are the class names to use for that model. e.g., " + '{"dummy_detector": "ada_feeding_perception.food_on_fork_detectors.FoodOnForkDummyDetector", ' + '"t_test_detector": "ada_feeding_perception.food_on_fork_detectors.FoodOnForkTTestDetector"}' + ), + required=True, + ) + parser.add_argument( + "--model-kwargs", + default="{}", + help=( + "A JSON-encoded string where keys are the model ID and values are " + "a dictionary of keyword arguments to pass to the model's constructor. e.g., " + '{"dummy_detector": {"proba": 0.1}}' + ), + ) + + # Configure the dataset + parser.add_argument( + "--data-dir", + default="../data/food_on_fork", + help=( + "The directory containing the training and testing data. The path should be " + "relative to **this file's** location. This directory should have two " + "subdirectories: 'food' and 'no_food', each containing either .png files " + "corresponding to depth images or ROS bag files with the topics specified " + "in command line arguments." + ), + ) + parser.add_argument( + "--data-type", + help=( + "The type of data to use. Either 'bag' or 'png'. If 'bag', the data " + "subdirectoryies should contain ROS bag files. If 'png', the data " + "subdirectories should contain .png files." + ), + choices=["bag", "png"], + required=True, + ) + parser.add_argument( + "--depth-topic", + default="/local/camera/aligned_depth_to_color/image_raw", + help=( + "The topic to use for depth images. This is only used if --data-type is " + "'bag'." + ), + ) + parser.add_argument( + "--camera-info-topic", + default="/local/camera/color/camera_info", + help=( + "The topic to use for camera info. This is only used if --data-type is " + "'bag'." + ), + ) + + # Configure the training and testing operations + parser.add_argument( + "--no-train", + default=False, + action="store_true", + help="If set, do not train the models and instead only test them.", + ) + parser.add_argument( + "--seed", + default=None, + help=( + "The random seed to use for the train-test split and in the detector. " + "If unspecified, the seed will be the current time." + ), + ) + parser.add_argument( + "--train-set-size", + default=0.8, + type=float, + help="The fraction of the dataset to use for training", + ) + parser.add_argument( + "--model-dir", + default="../model", + help=( + "The directory to save and load the trained model to/from. The path should be " + "relative to **this file's** location. " + ), + ) + parser.add_argument( + "--output-dir", + default="../model/results", + help=( + "The directory to save the train and test results to. The path should be " + "relative to **this file's** location. " + ), + ) + parser.add_argument( + "--lower-thresh", + default=0.5, + type=float, + help=( + "If the predicted probability of food on fork is <= this value, the " + "detector will predict that there is no food on the fork." + ), + ) + parser.add_argument( + "--upper-thresh", + default=0.5, + type=float, + help=( + "If the predicted probability of food on fork is > this value, the " + "detector will predict that there is food on the fork." + ), + ) + + return parser.parse_args() + + +def load_data( + data_dir: str, data_type: str, depth_topic: str, camera_info_topic: str +) -> Tuple[npt.NDArray, npt.NDArray]: + """ + Load the data specified in the command line arguments. + + Parameters + ---------- + data_dir: str + The directory containing the training and testing data. The path should be + relative to **this file's** location. This directory should have two + subdirectories: 'food' and 'no_food', each containing either .png files + corresponding to depth images or ROS bag files with the topics specified + in command line arguments. + data_type: str + The type of data to use. Either 'bag' or 'png'. If 'bag', the data + subdirectoryies should contain ROS bag files. If 'png', the data + subdirectories should contain .png files. + depth_topic: str + The topic to use for depth images. This is only used if --data-type is + 'bag'. + camera_info_topic: str + The topic to use for camera info. This is only used if --data-type is + 'bag'. + + Returns + ------- + X: npt.NDArray + The depth images to predict on. + y: npt.NDArray + The labels for whether there is food on the fork. + """ + absolute_data_dir = os.path.join(os.path.dirname(__file__), data_dir) + + X = [] + y = [] + if data_type == "bag": + raise NotImplementedError("Bag file loading not implemented yet.") + elif data_type == "png": + food_dir = os.path.join(absolute_data_dir, "food") + no_food_dir = os.path.join(absolute_data_dir, "no_food") + for data_path, label in [(food_dir, 1), (no_food_dir, 0)]: + print(f"Loading data from {data_path} with label {label}...", end="") + n = 0 + for filename in os.listdir(data_path): + if filename.endswith(".png"): + # Load the image + image = cv2.imread( + os.path.join(data_path, filename), cv2.IMREAD_UNCHANGED + ) + + # Add the image and label to the dataset + X.append(image) + y.append(label) + n += 1 + print(f"Loaded {n} images.") + else: + raise ValueError(f"Invalid data type: {data_type}. Must be 'bag' or 'png'.") + + return np.array(X), np.array(y) + + +def load_models( + model_classes: str, model_kwargs: str, seed: int +) -> Dict[str, FoodOnForkDetector]: + """ + Load the models specified in the command line arguments. + + Parameters + ---------- + model_classes: str + A JSON-encoded dictionary where keys are an arbitrary model ID and values + are the class names to use for that model. + model_kwargs: str + A JSON-encoded dictionary where keys are the model ID and values are a + dictionary of keyword arguments to pass to the model's constructor. + seed: int + The random seed to use in the detector. + + Returns + ------- + models: dict + A dictionary where keys are the model ID and values are the model instances. + """ + # Parse the JSON strings + model_classes = json.loads(model_classes) + model_kwargs = json.loads(model_kwargs) + + models = {} + for model_id, model_class in model_classes.items(): + # Load the class + model_class = import_from_string(model_class) + + # Get the kwargs + kwargs = model_kwargs.get(model_id, {}) + + # Create the model + models[model_id] = model_class(**kwargs) + models[model_id].seed = seed + + return models + + +def train_models( + models: Dict[str, Any], X: npt.NDArray, y: npt.NDArray, model_dir: str +) -> None: + """ + Train the models on the training data. + + Parameters + ---------- + models: dict + A dictionary where keys are the model ID and values are the model instances. + X: npt.NDArray + The depth images to train on. + y: npt.NDArray + The labels for the depth images. + model_dir: str + The directory to save the trained model to. The path should be + relative to **this file's** location. + """ + absolute_model_dir = os.path.join(os.path.dirname(__file__), model_dir) + + for model_id, model in models.items(): + print(f"Training model {model_id}...", end="") + model.fit(X, y) + save_path = model.save(os.path.join(absolute_model_dir, model_id)) + print(f"Done. Saved to '{save_path}'.") + + +def evaluate_models( + models: Dict[str, Any], + train_X: npt.NDArray, + test_X: npt.NDArray, + train_y: npt.NDArray, + test_y: npt.NDArray, + model_dir: str, + output_dir: str, + lower_thresh: float, + upper_thresh: float, +) -> None: + """ + Test the models on the testing data. + + Parameters + ---------- + models: dict + A dictionary where keys are the model ID and values are the model instances. + train_X, test_X: npt.NDArray + The depth images to test on. + train_y, test_Y: npt.NDArray + The labels for the depth images. + model_dir: str + The directory to load the trained model from. The path should be + relative to **this file's** location. + output_dir: str + The directory to save the train and test results to. The path should be + relative to **this file's** location. + lower_thresh: float + If the predicted probability of food on fork is <= this value, the + detector will predict that there is no food on the fork. + upper_thresh: float + If the predicted probability of food on fork is > this value, the + detector will predict that there is food on the fork. + """ + # pylint: disable=too-many-locals, too-many-arguments + # This function is meant to be flexible. + + absolute_model_dir = os.path.join(os.path.dirname(__file__), model_dir) + absolute_output_dir = os.path.join(os.path.dirname(__file__), output_dir) + + results_df = [] + results_df_columns = [ + "model_id", + "y_true", + "y_pred_proba", + "y_pred", + "seed", + "dataset", + ] + results_txt = "" + for model_id, model in models.items(): + # First, load the model + load_path = os.path.join(absolute_model_dir, model_id) + print(f"Loading model {model_id} from {load_path}...", end="") + model.load(load_path) + print("Done.") + results_txt += f"Model {model_id} from {load_path}:\n" + + for label, (X, y) in [ + ("train", (train_X, train_y)), + ("test", (test_X, test_y)), + ]: + print(f"Evaluating model {model_id} on {label} dataset...", end="") + y_pred_proba = model.predict_proba(X) + y_pred = model.predict(X, lower_thresh, upper_thresh, y_pred_proba) + for i in range(y_pred_proba.shape[0]): + results_df.append( + [model_id, y[i], y_pred_proba[i], y_pred[i], model.seed, label] + ) + print("Done.") + + # Compute the summary statistics + txt = textwrap.indent(f"Results on {label} dataset:\n", " " * 4) + results_txt += txt + print(txt, end="") + for metric in [ + accuracy_score, + confusion_matrix, + f1_score, + precision_score, + recall_score, + ]: + txt = textwrap.indent(f"{metric.__name__}:\n", " " * 8) + results_txt += txt + print(txt, end="") + val = metric(y, y_pred) + txt = textwrap.indent(f"{val}\n", " " * 12) + results_txt += txt + print(txt, end="") + + results_txt += "\n" + + # Save the results + results_df = pd.DataFrame(results_df, columns=results_df_columns) + results_df.to_csv( + os.path.join( + absolute_output_dir, f"{time.strftime('%Y_%m_%d_%H_%M_%S')}_results.csv" + ) + ) + with open( + os.path.join( + absolute_output_dir, f"{time.strftime('%Y_%m_%d_%H_%M_%S')}_results.txt" + ), + "w", + encoding="utf-8", + ) as f: + f.write(results_txt) + + +def main() -> None: + """ + Train and test a FoodOnForkDetector as configured by the command line arguments. + """ + # Load the arguments + args = read_args() + + # Load the dataset + X, y = load_data( + args.data_dir, args.data_type, args.depth_topic, args.camera_info_topic + ) + + # Do a train-test split of the dataset + if args.seed is None: + seed = int(time.time()) + else: + seed = args.seed + train_X, test_X, train_y, test_y = train_test_split( + X, y, train_size=args.train_set_size, random_state=seed + ) + + # Load the models + models = load_models(args.model_classes, args.model_kwargs, seed) + + # Train the model + if not args.no_train: + train_models(models, train_X, train_y, args.model_dir) + + # Evaluate the model + evaluate_models( + models, + train_X, + test_X, + train_y, + test_y, + args.model_dir, + args.output_dir, + args.lower_thresh, + args.upper_thresh, + ) + + +if __name__ == "__main__": + main() From 74ee8a81e9695113675293e78ded22ae631db5b9 Mon Sep 17 00:00:00 2001 From: Amal Nanavati Date: Thu, 29 Feb 2024 19:40:35 -0800 Subject: [PATCH 05/18] Added PointCloudTTestDetector and tested on offline data --- .pylintrc | 4 + .../food_on_fork_detectors.py | 313 +++++++++++++++++- .../food_on_fork_train_test.py | 36 +- .../config/food_on_fork_detection.yaml | 6 +- .../model/pointcloud_t_test_detector.npz | Bin 0 -> 210863 bytes 5 files changed, 337 insertions(+), 22 deletions(-) create mode 100644 ada_feeding_perception/model/pointcloud_t_test_detector.npz diff --git a/.pylintrc b/.pylintrc index 0ef39e4f..e140f0da 100644 --- a/.pylintrc +++ b/.pylintrc @@ -201,7 +201,9 @@ good-names=a, i, j, k, + m, n, + p, x, X, y, @@ -211,6 +213,8 @@ good-names=a, w, h, r, + S, + S_inv, rc, ax, ex, diff --git a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py index 48628a07..9f41149e 100644 --- a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py +++ b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py @@ -5,13 +5,15 @@ # Standard imports from abc import ABC, abstractmethod from enum import Enum +import os import time -from typing import Optional +from typing import Optional, Tuple # Third-party imports import numpy as np import numpy.typing as npt from overrides import override +import scipy from sensor_msgs.msg import CameraInfo from tf2_ros.buffer import Buffer @@ -21,9 +23,9 @@ class FoodOnForkLabel(Enum): An enumeration of possible labels for food on the fork. """ - UNSURE = -1 NO_FOOD = 0 FOOD = 1 + UNSURE = 2 class FoodOnForkDetector(ABC): @@ -32,13 +34,18 @@ class FoodOnForkDetector(ABC): image and returns a confidence in [0,1] that there is food on the fork. """ - def __init__(self) -> None: + def __init__(self, verbose: bool = False) -> None: """ Initializes the perception algorithm. + + Parameters + ---------- + verbose: Whether to print debug messages. """ self.__camera_info = None self.__tf_buffer = None self.__seed = int(time.time() * 1000) + self.verbose = verbose @property def camera_info(self) -> Optional[CameraInfo]: @@ -107,7 +114,7 @@ def seed(self, seed: int) -> None: self.__seed = seed @abstractmethod - def fit(self, X: npt.NDArray, y: npt.NDArray[FoodOnForkLabel]) -> None: + def fit(self, X: npt.NDArray, y: npt.NDArray[int]) -> None: """ Trains the perception algorithm on a dataset of depth images and corresponding labels. @@ -146,7 +153,7 @@ def load(self, path: str) -> None: """ @abstractmethod - def predict_proba(self, X: npt.NDArray) -> npt.NDArray[FoodOnForkLabel]: + def predict_proba(self, X: npt.NDArray) -> npt.NDArray: """ Predicts the probability that there is food on the fork for a set of depth images. @@ -166,7 +173,7 @@ def predict( lower_thresh: float, upper_thresh: float, proba: Optional[npt.NDArray] = None, - ) -> npt.NDArray[FoodOnForkLabel]: + ) -> npt.NDArray[int]: """ Predicts whether there is food on the fork for a set of depth images. @@ -200,19 +207,20 @@ class FoodOnForkDummyDetector(FoodOnForkDetector): A dummy perception algorithm that always predicts the same probability. """ - def __init__(self, proba: float) -> None: + def __init__(self, proba: float, verbose: bool = False) -> None: """ Initializes the dummy perception algorithm. Parameters ---------- proba: The probability that the dummy algorithm should always predict. + verbose: Whether to print debug messages. """ - super().__init__() + super().__init__(verbose) self.proba = proba @override - def fit(self, X: npt.NDArray, y: npt.NDArray[FoodOnForkLabel]) -> None: + def fit(self, X: npt.NDArray, y: npt.NDArray[int]) -> None: pass @override @@ -224,5 +232,290 @@ def load(self, path: str) -> None: pass @override - def predict_proba(self, X: npt.NDArray) -> npt.NDArray[FoodOnForkLabel]: + def predict_proba(self, X: npt.NDArray) -> npt.NDArray: return np.full(X.shape[0], self.proba) + + +class FoodOnForkPointCloudTTestDetector(FoodOnForkDetector): + """ + A food-on-fork detection algorithm that determines the probability that a + test image and the most similar no-FoF image from the training set are from + the same underlying distribution. The algorithm reasons about images as 3D + point clouds and uses a t-test to compare the distributions of the two + images. + """ + + # pylint: disable=too-many-instance-attributes + # Necessary for this class. + + def __init__( + self, + camera_matrix: npt.NDArray, + crop_top_left: Tuple[float, float] = (297, 248), + crop_bottom_right: Tuple[float, float] = (425, 332), + depth_min_mm: int = 310, + depth_max_mm: int = 370, + min_points: int = 40, + verbose: bool = False, + ) -> None: + """ + Initializes the food-on-fork detection algorithm. + + Parameters + ---------- + camera_matrix: The camera intrinsic matrix (K). + crop_top_left, crop_bottom_right: Specifies the subset of the depth image + to convert to a pointcloud. This is a rectanglar region around the fork. + depth_min_mm, depth_max_mm: The minimum and maximum depth values to + consider for the pointcloud. Points outside this range will be + ignored. + min_points: The minimum number of points in a pointcloud to consider it + for comparison. If a pointcloud has fewer points than this, it will + return a probability of nan (prediction of UNSURE). + verbose: Whether to print debug messages. + """ + # pylint: disable=too-many-arguments + # Necessary for this class. + super().__init__(verbose) + self.camera_matrix = camera_matrix + self.crop_top_left = crop_top_left + self.crop_bottom_right = crop_bottom_right + self.depth_min_mm = depth_min_mm + self.depth_max_mm = depth_max_mm + self.min_points = min_points + + self.no_fof_means = None + self.no_fof_covs = None + self.no_fof_ns = None + + def depth_to_pointcloud( + self, depth_image: npt.NDArray, is_cropped: bool = False + ) -> npt.NDArray: + """ + Converts a depth image to a point cloud. + + Parameters + ---------- + depth_image: The depth image to convert to a point cloud. + is_cropped: Whether the depth image has already been cropped to the + region of interest. + + Returns + ------- + pointcloud: The point cloud representation of the depth image. + """ + # Get the depth values + if is_cropped: + depth_values = depth_image + else: + depth_values = depth_image[ + int(self.crop_top_left[1]) : int(self.crop_bottom_right[1]), + int(self.crop_top_left[0]) : int(self.crop_bottom_right[0]), + ] + # Get the pixel coordinates + pixel_coords = np.mgrid[ + int(self.crop_top_left[1]) : int(self.crop_bottom_right[1]), + int(self.crop_top_left[0]) : int(self.crop_bottom_right[0]), + ] + # Mask out values outside the depth range + mask = (depth_values > self.depth_min_mm) & (depth_values < self.depth_max_mm) + depth_values = depth_values[mask] + pixel_coords = pixel_coords[:, mask] + # Convert mm to m + depth_values = np.divide(depth_values, 1000.0) + # Extract the values from the camera matrix + f_x = self.camera_matrix[0] + f_y = self.camera_matrix[4] + c_x = self.camera_matrix[2] + c_y = self.camera_matrix[5] + # Convert to 3D coordinates + pointcloud = np.zeros((depth_values.shape[0], 3)) + pointcloud[:, 0] = np.multiply( + pixel_coords[1] - c_x, np.divide(depth_values, f_x) + ) + pointcloud[:, 1] = np.multiply( + pixel_coords[0] - c_y, np.divide(depth_values, f_y) + ) + pointcloud[:, 2] = depth_values + return pointcloud + + def fit(self, X: npt.NDArray, y: npt.NDArray[int]) -> None: + """ + Converts all the no-FoF images to pointclouds. Gets the mean, covariance, + and num points within each pointcloud and stores them. + + Parameters + ---------- + X: The depth images to train on. + y: The labels for the depth images. + """ + # Get the most up-to-date camera info + if self.camera_info is not None: + self.camera_matrix = np.array(self.camera_info.K) + no_fof_imgs = X[y == FoodOnForkLabel.NO_FOOD.value] + # TODO: remove the `is_cropped` from below once we move to ROS bags as + # the training set. + no_fof_pointclouds = [ + self.depth_to_pointcloud(img, is_cropped=True) for img in no_fof_imgs + ] + self.no_fof_means = np.array([np.mean(pc, axis=0) for pc in no_fof_pointclouds]) + self.no_fof_covs = np.array( + [np.cov(pc, rowvar=False, bias=False) for pc in no_fof_pointclouds] + ) + self.no_fof_ns = np.array([pc.shape[0] for pc in no_fof_pointclouds]) + + @override + def save(self, path: str) -> str: + if ( + self.no_fof_means is None + or self.no_fof_covs is None + or self.no_fof_ns is None + ): + raise ValueError( + "The model has not been trained yet. Call fit before saving." + ) + # If the path has an extension, remove it. + path = os.path.splitext(path)[0] + np.savez_compressed( + path, + no_fof_means=self.no_fof_means, + no_fof_covs=self.no_fof_covs, + no_fof_ns=self.no_fof_ns, + ) + return path + ".npz" + + @override + def load(self, path: str) -> None: + prefix, ext = os.path.splitext(path) + if len(ext) == 0: + path = path + ".npz" + params = np.load(path) + self.no_fof_means = params["no_fof_means"] + self.no_fof_covs = params["no_fof_covs"] + self.no_fof_ns = params["no_fof_ns"] + + # pylint: disable=too--many-arguments, too-many-locals + # Necessary for this function. + @staticmethod + def hotellings_t_test( + samp1_means: npt.NDArray, + samp1_covs: npt.NDArray, + samp1_ns: npt.NDArray, + samp2_mean: npt.NDArray, + samp2_cov: npt.NDArray, + samp2_n: int, + ) -> npt.NDArray: + """ + Performs a Hotelling's T^2 test to compare the distributions of pairwise + samples where the underlying populations are assumed to be multivariate + Gaussian distributions with unequal covariances. Based on: + https://www.ncss.com/wp-content/themes/ncss/pdf/Procedures/NCSS/Hotellings_Two-Sample_T2.pdf + + Samp2 is expected to be a simple sample. Samp1 can be a list of m samples. + This function computes the p-value pairwise between samp2 and each sample + in samp1. + + Parameters + ---------- + samp1_means: The means of the m samples to compare samp2 with. Shape (m, k) + samp1_covs: The covariances of the m samples to compare samp2 with. Shape (m, k, k) + samp1_ns: The number of points in each of the m samples to compare samp2 with. Shape (m,) + samp2_mean: The mean of the sample to pairwise compare with each sample in samp1. Shape (k,) + samp2_cov: The covariance of the sample to pairwise compare with each sample in samp1. Shape (k, k) + samp2_n: The number of points in the sample to pairwise compare with each sample in samp1. + + Returns + ------- + ps: The p-values of the pairwise tests between samp1 and every sample in samp2. + """ + # Get sizes + m, k = samp1_means.shape + + # Calculate the S Matrix, of size (m,k,k) + samp1_covs_div_ns = samp1_covs / np.repeat( + samp1_ns, [k**2] * m, axis=0 + ).reshape((m, k, k)) + samp2_cov_div_n = samp2_cov / samp2_n + S = samp1_covs_div_ns + samp2_cov_div_n + + # Calculate the T^2 statistic, of size (m,) + means_diff = samp1_means - samp2_mean # (m,k) + S_inv = np.linalg.inv(S) # (m,k,k) + t_sq = np.einsum( + "ij,ij->i", means_diff, np.einsum("ijk,ik->ij", S_inv, means_diff) + ) # (m,) + + # Define custom ot product and trace functions for this matrix shape + def dot_mkk_mkk(a: npt.NDArray, b: npt.NDArray): + return np.einsum("ijk,ikl->ijl", a, b) + + def trace_mkk(a: npt.NDArray): + return np.einsum("ijj->i", a) + + # Calculate the degrees of freedom, of size (m,) + df1 = np.repeat(k, m) + df2 = np.divide( + trace_mkk(dot_mkk_mkk(S, S)) + trace_mkk(S) ** 2.0, + ( + ( + trace_mkk(dot_mkk_mkk(samp1_covs_div_ns, samp1_covs_div_ns)) + + trace_mkk(samp1_covs_div_ns) ** 2.0 + ) + / (samp1_ns - 1) + ) + + ( + ( + np.trace(np.dot(samp2_cov_div_n, samp2_cov_div_n)) + + np.trace(samp2_cov_div_n) ** 2.0 + ) + / (samp2_n - 1) + ), + ) + + # Calculate the corresponding F value + f_vals = np.multiply(np.divide(df2 - df1 + 1, df1 * df2), t_sq) + + # Calculate the p value + p = 1 - scipy.stats.f.cdf(f_vals, df1, df2 - df1 + 1) + + return p + + @override + def predict_proba(self, X: npt.NDArray) -> npt.NDArray: + if ( + self.no_fof_means is None + or self.no_fof_covs is None + or self.no_fof_ns is None + ): + raise ValueError( + "The model has not been trained yet. Call fit before predicting." + ) + # TODO: remove the `is_cropped` from below once we move to ROS bags as + # the training set. + pointclouds = [self.depth_to_pointcloud(img, is_cropped=True) for img in X] + probas = [] + n = len(pointclouds) + for i in range(len(pointclouds)): + if self.verbose: + print(f"Predicting on pointcloud {i+1}/{n}") + pointcloud = pointclouds[i] + m = pointcloud.shape[0] + if m < self.min_points: + probas.append(np.nan) + continue + # Calculate the T^2 statistic and p-value + ps = FoodOnForkPointCloudTTestDetector.hotellings_t_test( + self.no_fof_means, + self.no_fof_covs, + self.no_fof_ns, + np.mean(pointcloud, axis=0), + np.cov(pointcloud, rowvar=False, bias=False), + pointcloud.shape[0], + ) + p = np.max(ps) + # p is the probability that the null hypothesis is true, i.e. the + # probability that the pointcloud is from the same distribution as + # the no-FoF pointclouds. Hence, we take 1 - p. + probas.append(1.0 - p) + + return np.array(probas) diff --git a/ada_feeding_perception/ada_feeding_perception/food_on_fork_train_test.py b/ada_feeding_perception/ada_feeding_perception/food_on_fork_train_test.py index 1f95ab54..b10843b2 100644 --- a/ada_feeding_perception/ada_feeding_perception/food_on_fork_train_test.py +++ b/ada_feeding_perception/ada_feeding_perception/food_on_fork_train_test.py @@ -9,7 +9,7 @@ import os import textwrap import time -from typing import Any, Dict, Tuple +from typing import Any, Dict, Optional, Tuple # Third-party imports import cv2 @@ -19,15 +19,15 @@ from sklearn.metrics import ( accuracy_score, confusion_matrix, - f1_score, - precision_score, - recall_score, ) from sklearn.model_selection import train_test_split # Local imports from ada_feeding.helpers import import_from_string -from ada_feeding_perception.food_on_fork_detectors import FoodOnForkDetector +from ada_feeding_perception.food_on_fork_detectors import ( + FoodOnForkDetector, + FoodOnForkLabel, +) def read_args() -> argparse.Namespace: @@ -115,6 +115,7 @@ def read_args() -> argparse.Namespace: parser.add_argument( "--seed", default=None, + type=int, help=( "The random seed to use for the train-test split and in the detector. " "If unspecified, the seed will be the current time." @@ -160,6 +161,15 @@ def read_args() -> argparse.Namespace: "detector will predict that there is food on the fork." ), ) + parser.add_argument( + "--max-eval-n", + default=None, + type=int, + help=( + "The maximum number of evaluations to perform. If None, all evaluations " + "will be performed. Typically used when debugging a detector" + ), + ) return parser.parse_args() @@ -205,7 +215,10 @@ def load_data( elif data_type == "png": food_dir = os.path.join(absolute_data_dir, "food") no_food_dir = os.path.join(absolute_data_dir, "no_food") - for data_path, label in [(food_dir, 1), (no_food_dir, 0)]: + for data_path, label in [ + (food_dir, FoodOnForkLabel.FOOD.value), + (no_food_dir, FoodOnForkLabel.NO_FOOD.value), + ]: print(f"Loading data from {data_path} with label {label}...", end="") n = 0 for filename in os.listdir(data_path): @@ -304,6 +317,7 @@ def evaluate_models( output_dir: str, lower_thresh: float, upper_thresh: float, + max_eval_n: Optional[int] = None, ) -> None: """ Test the models on the testing data. @@ -328,6 +342,9 @@ def evaluate_models( upper_thresh: float If the predicted probability of food on fork is > this value, the detector will predict that there is food on the fork. + max_eval_n: int, optional + The maximum number of evaluations to perform. If None, all evaluations + will be performed. Typically used when debugging a detector. """ # pylint: disable=too-many-locals, too-many-arguments # This function is meant to be flexible. @@ -357,6 +374,9 @@ def evaluate_models( ("train", (train_X, train_y)), ("test", (test_X, test_y)), ]: + if max_eval_n is not None: + X = X[:max_eval_n] + y = y[:max_eval_n] print(f"Evaluating model {model_id} on {label} dataset...", end="") y_pred_proba = model.predict_proba(X) y_pred = model.predict(X, lower_thresh, upper_thresh, y_pred_proba) @@ -373,9 +393,6 @@ def evaluate_models( for metric in [ accuracy_score, confusion_matrix, - f1_score, - precision_score, - recall_score, ]: txt = textwrap.indent(f"{metric.__name__}:\n", " " * 8) results_txt += txt @@ -443,6 +460,7 @@ def main() -> None: args.output_dir, args.lower_thresh, args.upper_thresh, + args.max_eval_n, ) diff --git a/ada_feeding_perception/config/food_on_fork_detection.yaml b/ada_feeding_perception/config/food_on_fork_detection.yaml index ca6bff1d..68f32841 100644 --- a/ada_feeding_perception/config/food_on_fork_detection.yaml +++ b/ada_feeding_perception/config/food_on_fork_detection.yaml @@ -5,13 +5,13 @@ food_on_fork_detection: model_class: "ada_feeding_perception.food_on_fork_detectors.FoodOnForkDummyDetector" # The path to load the model from. Ignored if the empty string. # Should be relative to ada_feeding_perception's share directory. - model_path: "" + model_path: "model/pointcloud_t_test_detector.npz" # Keywords to pass to the FoodOnFork class's constructor model_kws: - - proba + - camera_matrix # Keyword arguments to pass to the FoodOnFork class's constructor model_kwargs: - proba: 0.5 + camera_matrix: [614.5933227539062, 0.0, 312.1358947753906, 0.0, 614.6914672851562, 223.70831298828125, 0.0, 0.0, 1.0] # The rate at which to detect and publish the confidence that there is food on the fork rate_hz: 10.0 \ No newline at end of file diff --git a/ada_feeding_perception/model/pointcloud_t_test_detector.npz b/ada_feeding_perception/model/pointcloud_t_test_detector.npz new file mode 100644 index 0000000000000000000000000000000000000000..a8b963a9cee4b6ad13c85e011c995db8d67bc181 GIT binary patch literal 210863 zcmV(!K;^$sO9KQH000080000X07kxCw5;|30H_K901yBa0B&zzW^ZO+ZDnC@b1rUh zc>w?r0H_K9000000Ic=^000000GyilKb8L*$Bnc|sVJ3El7=!$gj`ByG^rF3sXihz zWv>QhRK|VFI-HzyA3}@@OaCew{x>~l~b3N)4ZT2Coe5`!O7L#_1qOJC)e|K|323{=ip|CpSxW;=WK`n z-mI*)bC10A&MorNzS95Se~TYzm|Id)1c*03Pg-rqg2NsmG=(rW=tPjO?qv|LcDHKC z`upjydue^wcUv};NIa9<^M(WlLqH@YE(!Xr26jFz;Xu|lc5>|^682YaQeQC6g7zRg zOD8`zxNLYkvdWi&ZoYshv8fa=TIuiJqR9ov8u4i510?v4G~Alap+Jz$xqi2b4TD>D z)UL2ghX)UC)U2wYgDPdVDCjH~8cytf=A=o2<_^!AumB1U_e{C-zG1^#PrvoS zEb`f}i46yHGlR9AQ{dqJLfY=pI9T*DVfCyX7sfY9*(}-1gpk9QyuvFPko@`WWSkKP z`1P+D7%nAYDEi!@vilSW{Aeh>TFZvdPg646yeWt%xl29!k^=5`JD()zav?fbIo~&h zfIU&cJDq@cs?v!B6{`T_ZWar6Jd9Opxxt3edv{W9KO7M{9!d-@4DYW(_IxDgA+KO77j zz&>7=9F(hQA|doV+uJ6jZ zUSz_7lHS(p4IKmwzH&bn=+A-$Z%yPRu@0|a=?l5OAV4AaL4nK`3La^GPc-UaL$-G^}&0h4uFr`UC{?xt`qD%!2gG^BaEpvcX(Z;HJuN0;n~^ z8i(>(5W=AE`-0D3y0G$*TQURm^JCko9tJqb9KBt)f&+#&qRz0Kgwc*%nQjLbL}`WU zm*2(yo{xH?{SeO?Uzc#1mx9JjG2S^m&($wERZny%xM;9Kh>tH73IuphhH7&m{`jBK zqen?lvf13Q4f{Kk80KLf%7z@}a*eA$86cRblNs#7fPDq59$$41bg$X!ufK(a*!P?2 zPj|B5%(`-!bljsI?R`tu5$RBWGGXX>D;<^;-qbi^!G%nA_C#n54I=(5-NgBj0KS$d z5{r)F+-6U|$}MKXzBQb~8WbIrrw(|nIl=|=xlX5nOa_FlYMlyoro;JiR!g5X7X-Jg zvi~bWf}q~21CLI!Ag~F{_D8Z|(N6vFzt<>mTeMn`wjvcAy}W8YOt|n_Rjq5xi-bQf zKM2|fvLHKT_vM5THhgrk3SC*vgg4ff9!80H&I^rRqn2E-nr=29jwHY-V_&~*8xypf zj_=LxWrNJlKlF|?0&MLvz8=GV9k=SZ{ob1mwQp}7`u zd47h2Didz!T^>77&ww1afHF`*{Ykcd@@$-d|Dw~s4b-rJ`}$Cs~&ZxsnK(!w8q~@q(uS>exr? zda?2i6r6n9_;7w69UeHp&pd97bqJWAdw}{bVcKG;8?{Ye%uJv-fRX~S> z%9rHEP*)pL(?eg?6TniL6Jui?CjBoo>}q3!(Uk6N@O1)~*jToCF<9`hQZu>->o3FU zlb&}l9d0dKV$feo2bZMzYnC*gy03Fr5z!(8%>#Tq?nV)iRTr3GJx! zc|KA+4_KfsyH;Zx)^nHc{dwyGDNvU`HB~i0ht!q1m8!?NpgH^Do+Iwhk%uRookqCY3GvHl?}yi*36xYv%sm5-byNwE5?VZy?>`c|H^;$S@+ z+D&=uzWEZcUP&~-n$Chhn;#$B9E^RRNXiYjBf;abZDdn11xgjGUSdq-4(BX z2w&$+E`^=pg3|B>`{oD&4mn*~5wwGXP!Z$r*IL=IcuUW>?g<8T>`PdDbuL)+`OaalKMOC5uxKKQKvtj_xzeG-a_#SeC{z6_S7W%$*aa+c6EgHPP7o750 zm4Nz|1s@F^xiGWfQ|)0J8a$_&$6V7$09NIN&3kZ8+RSf(=nEz&&sJ|2CF#H)^i+E( z`ndQqS}Ffq0?6OHmBO$u1*b}e@1y=05D!(}_K?seKN9KiI}yxmes)Q=ap3RWbD!6l zFk$}4Go3L<23(f@JeRG{fkqwK@~$KT{?OaLJ?Ue?>kRs8S=3t%^2D_{e14RG*GSJC z6HL98=PRH;O8+VDa9B%%Y*r0~Ix7lzr^X;-c)V=HikEAoo6v!yq3AVSR zZp(|h51@|JhYD>o3t|B&74tm`ebb_{sWYI7fNFC#&)!WGi1{z<{mEv-lZkS^4SPsX zJb&0=8SZ^<8x{z8?EY`jjdffCVp8V9@3^k43>Y5&OjWu@n&5Vm$oXfD2Me z_qG+7k)XeLNV(951ulXmc|+KD!~C2I@$&@u&%IhE$Yz1WMxHk^sJAW4+~Ck<3Z_IY zq*A}9K;+_FwL;XTEo%y<2i+;CU-Xc_raJ{x2=5wQeJ;50HVC$J2vFgsCtPx3f$^31 zdMod+VQQ1p$=QV@m>9WSA9F^Xq&ysG5y;!ljSr(XlhCAeF>M?2k;>-iWgi;Ypzxsc zjXUlU&%rkJvcVLvHrcxKHtx|9g|mxiP=A(<_0+3hV1ey_#r&SgIikCkzVHkqVEfS( z$MTSKG8%UC*kWItF28CzBS6B}OU9dZUZG#ht1sAx_x-Aq{c8LV0ZrxpujCvlFl$;- z|E-Y?Uy{!DyYVu?XOZ?137j9tChxw>I6rS(Z~c6=feBia_CA$(2E5xgMRn+KpgdOZ zNUb{w$;KJ2eM}Z)hVzINp)S4Pf9XAwN5Hyk#yM`LEKt@zz^3qn2osGq(v7Vm0w zn9$J3n;Uta0WY3^*KnPSucHd#4(s3p@HP0Ws*3E|J6Qu+Dok^JQ%@W^< zeJGtuOWA{cDL7i{HbxSle!_3PAae5Nm0v^>kdvkQ&MBTkf4Or&?8uFhBydkyydwQI z2Y6pA&T?-NaO&zi(uB)|gzSxKzl-_Sr2^M!srVF4kF# zI)CL`4QFF36AG7YSn;qA_c8s*xh1&2D{n>2dG4cNK|s`nB+L<0pGI81)iEIN!PZ>0 z@igeHm6v&^$pQP*N7S@LNqA~|@$66J|DBy_3p}yEoohNHOi`~S_k~5qU`{!AS331H z>hK#LqgIz-3ib}!sC}(Wfe()rHD4kB)T?ZG^+1<|&ryr&@8zOD2jq<&MP9PY;IXT_ zln!p80lbv{mV^H z5@67Cq^baO)5SbLpHQrGc8s#fLd=!=A$K$eu+CL~MXs&I&!gWQ^4507T;_Z%wBaxd zu0Hflj>Y|5@j(2nyD0&FrCC=BR!~s9+4$rv`lHBhia8dG`gyMge$S_1mWM_YNBz`x zSkk-zxhT?S*@DpbOwiR>rci;;*I0i_rwIE}{PL;#JP z5WQE&f&-s6N}oi1p1Ndav*ZQ=y8PcgFW*TA6}zvQi!WgwF|5|SIf`|z)NW5rVnI-B zU$6>tl)ZNEp>*^$f%Q%5GekUz8&Xb(T~WX zwb@KK?NL;%fj)b=w4&{|4Hp(>{Zdj*Az^#T%*Yv>=kE!r*ENecF!{``+Yz~Ie@vT{ z=Q|eM?r~qj^}(F0GH00ei3vwn40j9$)1jr4S|x;>li%1rw*Ec=oqxAyIA^gSYe~tv zJ9r*H#Z4Or>}epARAsc8p8%hNX8pg|_pxKI7*&G=YG6u1BsgWcqkUZo2gJ7MW}U}+e!3N5 zcyuELnVFmZMxt->vGN84MrgoqaPewYSR$O`ciplLxx$5?-|rtkcbzehsu82$%uu0T zEY7VTWB>krf+WbLWt?9Ufjn|amFF?e)!u|FyltCESlDyANCERyJ-MIz~=o?p31{@f@Gk9DW7wL|7A8%9ipDj75i91Rbh{Jts`N*V&r`6F+PhIy^3d&_|KaLpen*BHR(l65U$ z8wb2{*4vLhBVeIr$@#OGyWiAUhYR6-MJCMyX51&s@~AU7G>7Cbf0GlFyw>cX411YsdDhy#%oPeLSAY zqrX)7#nmB)zhnLv%Bx1gzABsO7Mv@G->ZD*<6Koai{JQmoC5n{txIWdQ=q@{)y8w^ zkEOyhibZQ!U>z)(v?+rQ#+eUnZ(%Oj+4471p^taelXy z0;O%fDyEo&y2mS@rx_vCa^{sO?nuxb3PP3{y4Mb;fK;WD!%{si zB-!6~j;f@gKS{aMod}SxINN&@=dGkR8#F=*c+@vw`L>q{t6X@@`p_?4h`K9Y#?M_@ zN4|2fJ~XAd#OY=>R0u9@Fx2f^!$wbZT1kkC)BrQSWO%v%WmjPy2ZTjF4)QLfVB^k1e6%<^T#e|o(lX(~ zykCoDhIf--fAoGvsWk=D(g)TYM?b1QKEk>uPC}4u*t@_xs1K1ptA~&qb3zo4(Q)2J zum4tTK+dsSz$@|Z=ld(DI)3!U-%imJhL|^BE%WxU!u~E=x=URgbF0|>ZrvxCpAygB zb2CNXG`;40epZzU$6gelWG!UC4Xxw9pB?6a_$+;SE7o%~`Iute2n*hZ3Aglmv*D+^ z&Z+1fOjy(G-u_0N0SoO5`LproudkVH$Pgi+VYyDpbBcl!ytc3JVXir$&=l{?AizsX zU};@A3u+YSE}zAEu59ycUyQl?rrbuR*G?9c3-?|(jbg(>b6MIm%%|tI%z|zqkL}(r zb7ci`-I;`7o--HH!G7M7uU9_P;Y#6lBh#~7coMB`e5{Osx{M9#^2ozY^4qil;0RmzCH*kZ{>YW~$Gmf% zD->tb$%Gg0#g{P9U&?nCdB@075FI8pvT|7}!0k_bpB1@KcBgV~G7~vQ~$4?EFaL{M-}1V4;J2>w8G^K-^^(NG=mUmw|QQk8%_mkR{={ zvSg7L>dfrPjg_D3*l_BD(VAMU^9oJF@HzbX1rrgAhma3>wne4;b&+siwUtPE3v@RF6OR8z!?ImG_ z!R9sJ29iL)?9GLa7aZ8eqb_dgN)Ul6cE z@O4NZ>e!7PF7be$pL?>$@i5MRtbNTg(Pey-L^00 zb-*zaR+HX7udoi;!G6#AP=Crik{bij$M1i1tDiwG&RW$_!;3z?C3H`drv~cMka3j} z=DRI*n>;g-pGO0YuF^1fTv}(N714zLzBKvV$pAL&>=<~|BtwIPu`f-&x5q#%cW0N- zH7=AdyV>_ghk~MY#V1LE4t5c5BoolD*EaVQ4NVYmMn&A*4C}fq->q^z@>pj_)N`$J z0*o&{77SLPK-fU(t`GKQRC${x8@bE#)PlX*c`P`_3O?e7`oI6`+Fh^T5g`1v;Ov5L z$S1Vem1bUS@f?*oMbh2W1Vk#7(_fh%7iPCcHes27?3o*G-7%W z<{(;FvR4uQ`|i_0VJ`;QpWnvS+QES!k*d=HSQq=VUbQsL3u=1fvt;Vniqv)h5|PUXg*!`QD_|n zaIgG(58n4x_Ciy;?Ih$nUYnIFVu4+JBG}+Lt+{0sk2eAD*X1?DA%9vwUCcO+KGpnN zf@gID0UuZy{tIJSaOf=0$wt)Y+7*36_g@n5xcd2i9pqS9&(}RMmw zV|dI^Hw?BL34TT0*!gK^0~4RmSCn{Q^*si>{_6JQe0~~qn8}Im(&j(}?;b%udgr!z;@@J5vC*s*58yQ`>`)cOVoeeRUtv=^nWa`2Nc|>zI%Ee^2w>f;~Rr6r$gZ6 zmlZDMbWnMDF4ha{(^#ue)rom_{gy0?dB-TIy6T*lg!`g1m>)Re!~p5)vTw1uX)t%E za+0lux%F+lyv>Pp2;I7UeIM#@Qcz% zoR+d5DPZyTeClfCPu_zteH?kqGH%?pdnN^j^Jm{LR_DUem)eT&dq`NC=Wm=mmIRS= zVMNO-#kPHlvHIt-=n z*_bd)ht<;Bs;%fp0@vflmf5F+#v1Q4aXoYhj%+KPvf={MeSgNTv+2;DdhH`IK!=8x z5EqQk+0{LNRi`Ztj;$PbeZD*v91m&Fyufp+v%aie%0~m1N{GShukpYyGVXB_`##*A z`7?rt2H%&f^JX-}L&1n`IS2F3#0&AVQQY^U%cqvO;r@1x-gzH|`)eU>&p*b?1k&Wg zEp1;0%>UH#-0UE7^~%16ZjuSlY?pZaLf-Cpc`d{B7zcJwbe`@9ak*Ud+N zUDh4pLX~LvGNJiQ@O|xN_T?x8!p9r}%=9^+DEunJZ$NOdh+wu zYZVp!beNnNKBe@L4hNbImUv(tJUe3`ZqPv16<%4b@7$eq=CtC zr^j9~v5?-vFUWG`0$!T;_KoCu07+xuRFJ7b(f&e{<=ZqAa~9G((&YO4I7@1 z2!|BhC7|W|m&y7vCVYzg>bn>Bk>5y0pAYqD{N~Q%S99nPrI>HzjdlL@;4kfZC35NU zse_^)QlREkHmA~@3(qq{U2OFz`1Nv`^x^&#u-+ZLfHc58O%`&o$RD?OelCaIsVgfbt)9`M9<^di~Hr^ z{M0vx3A64SyRV$4gJr2aZzJ-sNNK;GKIR>ZiO&TYQmHVOa&yibb_i3Tgv)Yg9zh=rqNvIU>qxIk>(F0-&S8LA{*=Xux1Kvw_EzJ3ob*bJr4FJNN+ zT6KC^U~m$IA88abt>OSDYERNRArcb5h<|*Tf_iZF>2^QV;m~=-A1-zxpZm-;l%hWW zY_OX7gP%J@o}M_EM!G;tX{U}NK=56%T|JpX)yy<`(Sm{%I1Nm*k zWXW8w1`W~}voWE11Zc%PAx%)9ng1C&EvOmOo6OY#$`X{`p286Kbky+eMm=0O6y7TNOR&v7ou#T^oT_L~8dO5vyegfSrX z@=rCo4hIUvYu9b6C*Y1j=N6uD3jEU_J_$zt-+V`zYf(XhP*1nb!{#J#v)J8`RKNkX zx!25vJ4xs_IriC@V!?GEF^Q*`r~dOY`aXm|U-BkaY95|vC2y^FN*M?4E)3Zg{$D!W zeX~_VBcBedJSW`aP?w_U{O98EJ{KL5$(BSq96Nd`wdMpDKE$<7(9F}}>M6bP%04={ zm@KZ{f_s|9$jYDGN$u%5J&osUUguBR`=;={dd@)%s$~#cZ!1BQI2ZT=-1pc zi}i%jNA!*D1v=zO@OX6h*0pR3j>gD}4Prgh#n+y>l23x;vZKuNlSvS@)cWve^x?x- zDQI3gmFPd60+!M#kuOl6cMa?KiLwaDX=J_GjeJ|%UFNV9>(-t&U99I%f?lP_=CRil zRMnHdXo4`tN(L=@g$>?2BM$e03n|>J^y*iJxsu$UNWDo{o8KBj2Rp@wZI)oN3

f^oo%;MyRh+ks;)#)$N+gu8QB`Vz@xB$V9Ir;2Pe zQ+k;Y<1eHUgnb0@J%NEoF`p|+OT_q5Q0?}`v=DvvV8%}k0(FD&OL%i!00pWaMXSUA zeeW;PZv;f`777AnUU2ycG2JeKq4kDq18A51UQOxnTZUv#sU~?xTO#e7-6( z3clM)JGeEcK*;9m8+piM5giHImLCa_wtF!z33Jmo#>#9F^v&4LV(F8C_#C+~&fGN? z2)e7%tU}qan_sy-@+$$C^Rg4(V7=|le7)A;UMQS@teap(fimBwZ8Xf$_D_E;+4avK zUnXVkJWGM${r%3;$n$mz8us_FKH(n{HAor(E>cO3{fj9$X{q~N1o=GSLi|?K4+Olm zcT~&0K!KlBw=RL_nb$R6@9TaNDy|fNzKeRYPSrx<3g&uO3%^Uln`oeaIxNg*EdfmX zr+l)=)#D#qope#J*k{)M7l?KH5g_0ZgmvrtJD6D!NojT9_ta~X?lLC#s)C3fE#|7|1uTYM@7giA8ESYb}N^U;rba*77c8^rGG zIwgQ0Lp)y${ZY|C|Gmfy0$wc8S)3lgg78wa=y_QG%RY}|if@zfT6;`)Mj{#fJWJPn z%EFu#pzTqJIy^mB8sKlv0!^-=)ochGE~&dq*csBGi8!PXXcG&AKb+^j;Jwm*-#@g+ zoCF6hn|U97N-iSq_d}e|w{=%8{8~f8{42qMuD6g+56@R{#Qb~O#iGd5fP^Do9Deho zZvQD-tu%`|@Nxpux-JoLU{o#n`3juhTY?WiVXho%IN7>m9u0=iZHbTs%u|y1+2tDXO@UpN(XiY$9nFsDmyzA~1v0e$m~<%D@C1zRn)RtuwU?~tf`k`X~b zah7?e8s_C{$!|U?xbKJGEvWjAdPqweP>POb0e|8)&s;oz;>ngbCV2h=PfK3END2b& zsoozm&%Y)GUYpwwo4tp{y z*I*9y`(U_UU@`@Y$d2)2m>;jLACm1y{i#nk610<`VAcHUFC_Y1@refqE+B_+XCj7Y zJ6T|3P~E@Vn+*d4krz5V2{?8|>%IN}6Lu81FfwsYR+1I5(K47dzPT#azf2r6lNpe6`r+*6!Cp zfmvp@Oy6({+%Jo7J&n40bk)1#N4Ma-h0GT`(?Y@B$?%lyGB$*NOkbCbeSgGbv3z`j z32#cy3u|GW)zTN)?zJM})LSRt3W9<}pL_aZc&}Tw+boP`3FH{l3fDRo82%U)YW876 zg!`Afk6H*w^Zd~{fH|cgNAXHJa?y^8v4~?9sPo5;Ik>c^z=sNjR4ZLBe6xA`?4c7A zRQ9PBo%+gvL7;u=P)BZ;y|lz32j|B~Huqac5^%n*QmlA|`FB#$=p=^;?7t^Ygon|g zI!KR>LH=iWrW{;y}eJ`i)CJp1K;?U;iv_|6NT!~62=8CE8rkE|JFmQu z;e~w8xH~0A@?rA_tn9qFV@IOy01k1S2>p znPu~4v0vRorlc0~ztY$3Uh0^;iwz?0|NA?ii{00zEk+37`}SJkDEi~!(sJfI+zXc8 zf2&>_QgEnO#X`cD4&&JoVtlq-7!}*FJJc;55;nEWFMUr3&qbfix{)&#B^w%+<`YmS zpdYvD4HJAFbbqvAeID8_?n#zK-9GJIYWVmwS!p3)ho2Srsw4ao^`r~^z zjK&h=wA#&GtG;1BO3PH&??m5h*FGS2@-!FPA8oODUP1tm`r}VL=`2t)7zI1fVoPuW(OU&LGV zTQ9m|eM}C1+kwwnpKw0%WjzVg1M<37FOtBT^$N|uj%-?Rl~@iyKYw-4&c2Geu<%n zd?#StRsEkEF&FeY-rAp!KKR}3N=|162{gqcV;xe-knhUg>#s6tJBVP+PT=3w_4Qj4zu=Xmg~CO9mlV=j?k!;Jq{gzgAS26JW4>;TjLj zO;a|L<~qoM1J)%&@*xE5KDBT{<~tLv9L+NR_jl~tFAqvfPQhqJV-?-8*^iQ(T^uzlHgLP*6gZ64g`4C4QnQ# zoIT`eKXK(K#+(F#8B`0n52Iw#=Q5BPf+_Lw`59Z|#0s>R6W_4$>!1KPv=r`og zGwWXn3hFYULri2@xd$EQjzuMuqfV~u-Zz<>MS_3I+l#iC%ccU8xmq}fLG$I6UOyus zgg!Np`d>P%_Z1mybYO#+NkPc`E(Uzx=$LrKo&j+m+Q$#?3MIpI zSaW6mF8T9ZxITA>R(O>J1r3+}=fx~IX-IakF)xb=I_dzBQ2T+s=|e09+uAqmYewIE zx8zXBbS(knQCV$SNfc;V^*uJidHC;ItWN~`Y{~J}AG)xQ_bqL z{9+@CJSOD#>V78HS)8s@acCHj3O>CFy_D6ge~K+%MCuUvN*quL@}LWP=y| z^yVF_NyrIX)hhfLbI^15Q*x-EqZ1E828@{?IhvS84`9Fxc}E@hL)b_8&u=O*=iWXS zJ!)M;hZR=@qeIXa915gQe?cEr+H`T;yPFQbCTiujp1`_kStbf~5n$VRxT{Nvf+X>R z!2QV8heAcAi)@i6j)XlE#9aKV&EHl9eRG40mC?ss68bJV989cC0?O;R@D|KR@dx@G zMrRptT{Y~m#8C#^-}lF2#FzuWb!YR_Fee^3y`5gBOhNeIx|mJK=cd~WoQE)1Qubka zA;__MwqxTCk!)CgHoHIjBmu8I@8sQ`VZ!=lXEypG2R_=-AbC}sgoRc8FS=P2e7fW! z;Er|3o*M2LR-{45#SJfvGkIkIG;C2&q~u<>5v`!ap$2TI{4Nu)jx;mNaSzbyN-z&?wQrDP6!1-`aXg2P3;H1;5{Twz#k$cwr;PYiJ@cop+ddt7^p3SRa zLyflVW{;yZkQ=_^YtSAGMscq%HskZ}=|3|>9@CI{@!cKw!dlGWwUQ(5 z-I_L`o#Lqwov&SRUXu$6Ns+rA+fd+e#C-RMDmpApq*DtqN6YS*-QO}8w%HwZb(3lOn3yh!epo6Q8q9*fUL~Vv(AP{x zvYv$EoWJ{BG@+Ehf_r<0t(A}u$Knj~_uxIR_S}{Tj-`Y1$E13XV_awwD#+x=`N>dh z$uRV0!PYSQ-~;&cBH!w~xL*h$1~tacMX}(UZlU}U^pTV*vA{+i5*{wx?r;(H&HjLZ zfhp#)Eeg_k8KVRwXw-gX{$j!GS%rDF*V!Ptn_0FVb%tkKfz;MB>99(8>E%*)+`Gze zB@Rv$405h`8P87zwXJ_I>mg^FFH%`jXPpjSUFKT{3hA(R(e&tZ^rMQ1+l|C;0%nsN z9xuoHZqV_Yl|kPRJNWngXTNk9zwK=M3pwPy!;yLS&vGGJ`>^uRbpqDE3@w(#JRW*x z_D2AozrbkspEFBH=$(%HaovptC+kD(?4bCc!JyO6>GX6E4)9p%S{D+54 zK(Tk3&8c@x;HzEez7hH4RPqe5@C*TaemsB3i#pHRy7HVM&ga0LH^=|@(m*kRTD|8; zEYLFpY}Yt(Vep~pi%^^gwJgdj?idRuV~h>H;Jj^bIrKm>;Gs+68e|f{%D6n>=bR$z2r&(kd)?D>Gi+dk=ZOHdXYJCHmd&@*T6D|9-!^as1!+>{oRq9)uyE=)Rp< za9k%G4xzn5;qdcOVeQ@6pGgnHRW3u-U1K=*NB zks0>aHqpOF0`({FYJvWJoWtKWSq5#GBU0r)M%t-UaOG9Qop zgSnV%m=cTk&Di)LZ$g5Eq2S|IzFO&^IcOG@i288KeP?1@5EBZuYRu$sF`z)?qv8(} z4p;@UPG1(q`WcOjM^~T7n%O5+(5)61hRR`nq86ffaq_LVN2L?Ek+rA8u z;8Q$v=v;jg@S2piPnX~vZcDNi-9f;gM~ZvQL}@V4{lI)~t{o0X9GAN`kA!)%e*>d2 zcMM(MU?Pii9sK|L`_y3D}O zlgd|mnyM2J9(?z`K@|(wI_+hE`Y_P^NlM<8fP<-v_821PhDW4`EosF%*T2}6OJUwI z(3`t+BnhGg1U{{K!+{%`F?#a?Xb>zI_1O?LQ6O%lvq_0lVEvY_&E$d3oOFWPhO zw48hhh@Gm?jl^8?X~xy<8S=x+kBfB%FyDq{J8=0GQsD~SFWF)b7rcW;Y%@{_*n0Zd z=d;2TT(hf6i~09G`?EWY9hS&lXL4F?o>Fl7l)$pMDmD~vzbcpJ{f|!`i)|QS!X?hq zA{WeqRS7b`>f8uea;vAs5Bup>EGfDf^C|E4H*bhE64D%P>H{w(fpE&yJnc#jL}-RM z-a}s#dF3JMbb=N|E1_C z`bcnc8=L)%2IS?8?;&wX@FF}c^DFM}JAGc&9wrHV$_7Tx#YwQXWRJ)Ia#YTLYxKK# zQh<@jX|UBHAeWdmb9Lkb^K`3}P&xzjBFc`3_@;q!NU+T_oKMSWtC(FPOlUt|Ww}v@ z0edeeT`N@Kz`^0889oizms`D77IEpYwc%#ciHmFyzQeOHB8PYFtGD`CUEH#5Uu zEJ#>Xn|Nrlk^<{<8@4!Ozbdi@jNFY-zw%X-<6kmBvF+6Wj~)kTrY{d(^&+8Dd3Sx_ zT^0(CmZr+mYdb6 zld%1SP4gD?Wm%bF^9l63#Zrr2>_@)eeW}9LcP0fE_1dM?=%LTDMl$OUFyXn@g<&31 z2FPi2SIc3Yqm??;vxfR#E@CjOWkaUA48CWcg4FB;?$??4a;>L{1l&KZ-R{uD1ZSNDClQ>Vl!Ma-qF7Jw z!r)zxpRr)4pJez^)K8v%A$_+e$O+zi8GqJLpsH#zWs01cdh?mO1nP|1gy-c=m}kq? z)IUXI-Im2Y+vJl;z(C((Ic==7x~1^x#s9uv6WJUz{W2M}?JicFy%P@#k*^H4V%?VW zZR9RyOE`a}@gZ+~DlL-#3y!}{wH!b6L_G3RtAi5Fv?P0PnM zbPTv4ovxe|tw=)L(huQlGAKygV|cb5d6n{CRk)c(!ZW?Ky{yMcP}w!D*H_Mg9p_f> zReM2zp11{%Q703gz8uo=#y#y)I&9LJ@2-863voGCd=|Jz@4r6! zZ@drl$JUGvBL^};y6$AC z9zVc=%|BaS3bZ7HTDCw{ZA%OYejX*w-MJ9(-EedIBLeJyF-Dbpm>`ulqHyV-E)AyT z+A)$q^v0Fwd)W`++H-4%6{omhTD=|)l#@_CwfgJ9@FbYpuMUFDZC1zo@dlA_XYf%NzVqXCha2Iy~M$f~v@5bxy}4-RN+$a9(j9JJnu=(kb^HDY z{zY-{%-H15In*WNecJ}hE|Sobo6GwEdA>O@<8mzW;a3ki<$K8lNJXEnmg{Fhl>2MG z7<{kfSNY{5S15Su++qFkO$wAO>>hA9#08fRREN%60-_aC?lVhSApCyo@lqc)Y~25X zIqx6^vmovh$WDQK_dYcEAP;BvW{jHfGT{tt=PUJNzF6a$zke;tXfeGiQ^7c47yuQ?z(2nQNm+U`a zRf~C#Ua-u6I0Zg`UUVhP2={BO|9pZB3F1nUI*C~<_^wh}^)ClWxh|YkSwVuec7w=M z%z1oIa?`f``}=(Jl$|}d2}o;HysO7c0d?x*DT5B2&!47up4AY*&-q;~H^BrRsn~Nq z$UjWw?Qi~~pN4j4UHc-I4(xUL56@z5svaDgs5pjtJ5y+IhQWek$2Zarpx(YL4gGpg zg@lh%wYmmRSa8zyiREeR7c0AFmnP;Tjo+qXDaft0sST^;ao$87?Zmc*63{TSDra9U z6W(np@7>#{w3p1s+iNQ60D@6A{Y?<`K-du%?vR4altV| zfdkxMw#u!j!wL^at(ZeuR~aC2T4JAi}{b@lBUz7!lPR(rb`^O0lCVxRZX zG%))U%YRprfF_N=4K$o{<>%{r7d$1Q`i#y2XSF0)moPp826f{)U#k?YR+_jddqLtRq8+O&Kx1)uw zLFZBkJ>+56#-F>3k=wibpO`o}V7@m0(Nlx{Rk<8vWPXf-&X;S;+OQ5ac2<6w+Fba~ zbke%`m4x*o7q0w4F1o0eKM_#PftMTm+e>iX7A{Fx&n!uY`0O1`P3O_~2eaGO*OG9J z@@Ww;O9G8eVkyaW9N=BAw(?Ov0X3z+>;e{2@H&1Z=sV7#Rcr6L(0b%asf6Vg!z>_q zSy7$1?-msc8U;{)7`?=*RoM4yE#EHv`@31Wg4)T>G6D{R+Mi%?3jC%yhs1Gy%%|A7 z2SW(Zc{yhP=`#~NPA!g6M<1CL`r4S&!hlT{f9B?EF<`#S=U-B|?_x#2Pu)L4LXpAj zhkdA5pDVa->rltm3jMNIK;O(;aP*`LhY1!v#)r#LpL?`thVMRLz%IqvH*eJ#@Hn;A zsdEB|0cdB_$$T31vwodqqjIgck8kh+#7G%phyBmo2i#G?OKX zRF;w@k?nWpx_<9}uUyZ3pYuKEzCX8l7R+~>{fWO=2hAH|ZW~ZH+B?LYcLkAP7B%F0 z1ZY~i^8I3`8yIl^V~t-u z*8gWyt3>@u3iM8VG75_&A#UgU*j1+kpHQ zMP6^Kx1j))mDx5gl?gZKPY?61TNc_TW0~DRK(^eW)9a;4pw}h8+J<^kVIgX*b)EzX z#+RF^t%;EDsF*c=hzs&kud^l&5umT}Z$$DA6O3(-FIkK89_+WyT=N_S-t9_T?uh(D z3%8eTME*&ez5S@ilR*B=j^}YK-8giQ59S*4^Y-6VZ{z2#n~|TYW5TWxf9Iw<=(A!c z=!7H{$^#y!E+31Azi(5t+;M+juD4DU;!?o4&gPBH>UdDF{w%81$bs17qp!Uw6fk-b zlgklJfcvc%)5|k4=Sm9LX<|Kp4F_CbaF>LH!#DC9k@xr*7n__P5%7BdJEb?+pLz{G z%=x&UePI(C-avs&ZF?JPAPHZH8WRKLgv-HYI*F)<-3=iNZvSDxHVP|G6#eVNh_l6V z?*|iAOwtw|M7&Le;As!%MC9ZQsd#b2ZrtCL+H1@GNQfv}diEUF znWl0)B@**Kqdo1A|91u?*)PBK5_RCsX#6=XO$uCMSj(q9BO%)$vcngBxkUNfCNVP# zSey!!f6O3Z`tkbnN;pU9`wEtF(f8W}DwT|GlCbpQ&}0DmX%bARjvD$JSQHlg0abQtK4-S9(~11>Jl zzxtwXSC_}{6i|zY?`3xlD~oEk53(>Fu^Vx285(@0dzKK78kP>C^1DL=f7Nr2Ijh3mR{)g$#A!zGv=xpN0H8cr$vAjr+2?cqA%A zf&!Dw3#!UY5|%w(uOW>&dU@e&lVdIegf<^O^7SDdM%_|`mm6^4>61N%bJ*vZ-`{U< zE+^sFw@**>D%mj8ve+(6gaUl?Uz^@dWP(J8`G70Vk?O<#V@oa&@N{zZudv0~pX!%q zjIci&7f`C@3JFl)bF^<%Bw^sl_n*P2W7qy{?ca5T0!y0K9O7Iefjw#&n8CZR&A)D| z1?JX2Q*Sa%PO{*@=`)W9FXP-T99EoW5s-MuDZ6pgz%$(U&0SaR*Q!upQR0vD z6FApimn5pku|8UnUbgNJ=x|T)rJK~xWDqG;)R)10-5#(%yu6+OuTj^)$QA~C-Jg4B z?lT*<%0yZ{UWYn%yZFtTY9_2taFf$U-Ojysu*&5M6|x4z7l*n>!}^ui<5uE4uJZG| ze~ga;@vn_)btxoN+&8Ftj&t$Rq1b-{`DDvtwa5?8n9#CitM{59HfW^(-6)51)f?B- z8P`PvkqMu#&(X)fvY&YJa`b|ApEM6FBH{9juCipT+g()!yWKMc98Pk5d9Q^Dw3#$@ zFIGO9l1(R{ak~3Fcf*>5bHkBog}G2(`QL*25_fjGQAN z;IYKbz0XN_c~SU%Ebso=I~2`uDghB2ziqpK$G`GZ$m%|F)Vo5B5j73uw+qM5OrBsu zp~#t48ILe8|5>pn2Inq2$h2oiIRomw+73Hn-9GPYRnJc*fW>(qbZr|6mEOnydGoHX zzW%ShfmvXelEYF8bN~Osgx7zTWD}-|H1|G=sTsm8YART$B3J{ud?Duu-VjH zdk6O=IEteunM#K<&V+$iB^^$D)G<7)z=3B^Gecsq{*oJNj~pu`AzWC|P8a9S@8!2o zt6vkq>5Uj*%%HArlMwuh^*N)I*=yxR0Drwjs7(_C;-}4w)^(z899qz}68&=bIV+Lm z*+kg-C;vaXCKoQbcqaV5Pr&wtBevJs3}AUJFuaBPxL8El^i&(>*_MFk?`f!4@_$n+ zaGiTrdsS+$q=Med(ds=?aS(KV&t6G0F3eW>+U-X_wNj4mIq{qcx2yUr4x-;hmo4|G z93VjMpVg70ub7bU6n=6C<~~??-XVT31uA|?YVE-O96zkwznSMRUyC))qJMZDei`zr zga+FZL=E>LABKP5+igG)uqsJa$riafx$3QeG@e(_tE?4|&XCZ&DA=4{O@jm5H$VID zBo~y03Q9ks&W!E<8E{{mgbnTXPhGGNqim(!N;2u7)#D%Jsz!%p9Rll$nr=34*zeiNEoD*Sz@4AB=VJbWfP^jiG^IMde8MK`s=9SBM{bNrCGpZqBX9 zj)y^&Rr$Kb92i{NxHbuSuOw9M04t1y1vkT+{@`)^Pj~NbU=!f+H?Q>XBNDX7elJnS z{&_T^bc!G6mlGEqa0B`06Vq{r75@C>67eF@QxupmdOB?Qo(WIWAEohxuh}iA~3qIPCwL1tPm2F+ow!Y(5QjSmEX)O^Z|lqM8dlt;(2? zx-p=t8ujqk{rjt4`xCIq>y_GI7Xx-%zo7)7er7bztWiR}>bg{~c6%-Ah8|_!7}jlv zywBA}><4xB0ZyJ939~_;*8W3&DEww$a^oZFTP>j@)WrlJdXB{#oL^SkWagghEI2*c z>asV52LHa+`D!6Qr$#+J+1*74Wm<8j;Tk$jsE?%m+QWgvrCK&yeW;+7U|+8IFdE+c zX3Y*<<3h|v!yp|O7QD#H(Mx?#1IKcm)s~iAV5`~63>IR2C?R4tKjI-ZByAHEa$pH5 z*0~Mq{6=LFWorQmBj;;3i1NNSKV*IRqcR0L+F05LvCf@l9crCeXY%6-qafsjA%kA& z)?6mcO9`)CjqA@1Y?A4SN`T!587sYy#RBb2z=lF&F8tc2Es!9E$gGH^O zoRJv^Y!q(ox=#{Nf3UFZ*F7eDyK$%6iT4~fe(#Vwm_rRcn|GcqLhg#)A5O1e!-&7* zvMX30-N#o<4usQyt@$j@$C?X$M@)1^P>0)Y6l}V&kObRRk*5`Lu5%-lsvVK{;^gJM z<|VPA5>VRt zIF|#IE%yz6_dsKQB`+u!S*WZi3 z33zcfG|JPA2`A0!=-*L?=Xt!fGNhs3P0mZ|ME)$BpSE2U`IB9{^TG)FbxjP_Y&MF7 zE~_=im!l6R*|)cB$2_ZyC$~WgbI13cMIX?oTxU(5irpfCd~qRb@@patopka|K|S|b z^B{1AHwh=>X!&A8iEvEsXNQ>v7rJf+mmAno!D>FG-qjk{YZkS)+?@;a=l|kQOeY}i zcxCS0w@i><&91(Wd7-4}YD+%yu=mgNPpv|kFp{-qiw$x@MuFs96$95Znwg-AzL~r1 zR?b`t8_wA*Z5`M~0lg8kH&2i^HadyDdWwBMs1WNx!~PKp+mO?O`k?yheexFUAEk>O z4+op*!1S0N&J?GE^lQFbLoyr?W_X3l>XD$k`@!W!ku*p=Q{1J1b^dZQ;L7R`Gb{S)`*gt_zLG>}n72Y~kf&}{7=RyC| z=dcein47yN30@@xnK@$vxV{CJoCi2V;psA1a8q-E0} z^7YcZt@d2Ftz=aC-j@YGJ6ehtf1rW?BF#mec)mHCEq5DH5};13H2A-}vG8MT*_@sU z7urHTM!k+D;OYsFAkHraoIfDUcL;SmB#-)1Fr5Lm)jo_YoFlt`wl`?UTB8nNfj~kyaS$q#UEpPEAMgi)W z{_$yvdei}>2MJH&FptEJDE@#4OrV5so6E%d2=|s;);x-OD;M(U7W(oP^*x`4+u4wr zN_pLwh<(3Zp+QCxeK6)*x)t{AhGSdOe-zQ+z2V62g(5UqJn7-#eS`}pGYU6e2vEQ% z&9jYne}>tNP+sbLHZ-{(+Pxh8@%Y*;{BLS;UtBg?si8jm>prJf^1dfa&um@q*F1{(_P?{$5&9j8kU;x=^6617Ncd~M`i*rf(7sqNN@Iewgi0S3`+<9} zpNw+%P(FMkopPS$|&m!iWo>KmxNUF^O@JtM{F3*OcMQm-x*&`c77R zZqGZcf6}(g>JN92ptWQ4jI=uqmPsz$YKXeWda`4o*f9zeXua%RA;*F%eV=24-PvGm zdr9|JI|T&vW%t)zj0XvkRMD(T4t(EpEah1q0UGvae!&V7bk1p9OT>O?dwH}?(SZaF z?LedGFdF2%S9mCj{pohfjUk1cmU`fZn@Ru);tS@P@vf`qzL*WpWMKZP{4w(AQal{3 z@!>bD;=qChtl=L41e7H6)4p*T&@HmlP!+jLZK-3@gCqj#l%xXXrx~!BEz$k}_x;^( z>tGq=gk+^3W|HV5M`W87ig3P|S|HH82mNfc%~pa#gD}t-nnq6hBB6AygG+}U1=@}g zEIJ5twSE|@aDemcKlNAGw;e0~dv!aL2~~F&Ke&TDZ=&idCa{VE^*>Z+o$rzG(S13| zMGg^Pc63AQTLL0OO0RtsV}Zd3cF!(PHmv)=ywj3I0efpnV{_$rX#DYhdbELqeBiUz z!+-)W{wkMQ;9UH%q_?=#^7P8<-zm&}KNfZ?X(5N!=Ba$;Jx__XFi5)B9Ovgvy5lVN zn`X_Yqk8CrQH%DjR$oPeSb|lZToMh6`5ZQ9TX13J`(SHj+~0i*Tg)<=6Jf*MGc+sU zg7y3vuv$Wa#S@ltKFFC{@~p(YuphD&RiB$TGGL4KlLMw1G^nGPyxf4i5j5>X{47R} zRh-Psf5(LW73<1*_ZK{sY$=m!qr!$}C;jqs6v)~3x0B<@g+s!xM5i#_Lrqu@h4ObwfDx{%L- zp0STwvz{zy2=P3=AM?u{jiBH-D=vgqNSGXwqrkZxF1JQwnXuM`BB+M?P%hTyv<>@w zMS9r>Bb>kN;}M1dShpEl^Ns%uDIjZDp=Xf8gdQD7?GL#AW%3&9J023?`%7!R7w^8R zWB)y0i9VikMQ^^rO$z*S(ePUmgL%;P`Hp<#*xp-r%r4@-cPrdd)55yRuQ%!4h;@5w zrq1`Ri3;Lx51h0!$6VN&`p?pZ3wwlWCVBfs{D~S$S(pT4dmjAOQR6~_{k{+rSqcQ? zUA=9Id?;YtlN^gYcJ9-@$e{U5FuT&y9y*)|vBJeRS-8Jt(kz?Sc zf_cwRd;cOZGHgEu6zO}mUri=qev_8#MfBgh(+%5ostDL`?ea=FoC%L)=l!?nKJs=( zuSiP}3BST@v_^UpLF&IAr5WUenZXus6ZFlc4zBN#eMq1bBxldzJnnZJoBGNjz-iFA ztXGf(-{I`g-@NONbbMXpf)hYZ%xL}Gf%+;Y zGY*e$UtIrr*Ig>~th-DTtBeL)&Ba{WRW3LcYFGIpC%hYSe(~}H1GGaw7PdBIe;#_pg(4>Ba5)jmUDQM~+1HxCF_qFGJ{}QNm_ypg2$*+TbVt@RE{tgZaHrfLVSP{3+qo(l2o)CG zyNJ5C$8pJO?gs)c9yI-LGxESied@CRkRM1@m4+(xQx#=a69fCIvFNE8?|zDR!GbHa zx^ONAlzTR=B;jcCgPmKke*(PJ<-)AzFS3Y$^ zJuh?W{^)jzfaB%6Tx}~EptCG`M+Nc#zxzOwYbSD7tHjqqAN0o!H|GAKUY)!9%#V4H z0{K%RR|AvqbN~Nbvg03`e%sE{VX|*UaXddAmWynPDBs6{rB@P9?ZzA-{HCdDPdfvY zOJ48DKwiB&r6RC3hylj*1){@Qba?#uj7xzw2MiOYZwZ-F;KM${yQTHm&&1a$UcPuY zsJC1M^*Oy-z$R>tgzKLcKdOsj!{p#H57TA>?y+J6oJJYYX3}yt9(6l3xZ8=8#<}vk z-@VX^21j~7sr)#@1uOq^S>+uJ2)cM~OAGqci(Q2c?a2Ajb2?U=m8eilET8MY6$f8_ z*t^^~&4n;d-XN$pxSmfANatm1pecM|ty)?x+6{c{57iYo@ox5q;Ex{I|3@c61#7bO-U*O@gA zMn6hHu6uau!9MhH`*mspKTfbfGdJtkt8X;WjS*TGk9lg-AM^3X1K`>UfA5H-k@koRVSiHT>p5$?+mm}gRqbM5wl(xI8kgiAdF`n=~f28C`b z75+kiUQUg~ggq0MvHp{zhO;4jgP_~HCj@+-4iXPU|NZ-E?EFXULmBm-g=b`W&q)Zd zmW*b?_}%#b7GggLw{a>eVyF<$BROxR4#bjJb)Q0;f*IkEESsLcsN^ z^ggUl@Eh@+V?#Kne6C_f5hO$@x34L{c`PxN6%0tHgTQZ@&%eFsaP0Q?T-tsPT#ja& zn~o45x@l)*trzAOy^P+g4akRIn|sQyB0nf{zU4n8L37Mh`xojb87yBzwv%&*I@_L&yB&JZMs+=^^pa<=ajFz{K1il z9KKu4R9zV7@s{eXw{^-S6dTQd!h1e>$p&-!ZRDkg$J*~|ARoC@nI6l<_4j%Nl^MTF z0@6SFi{SPIP@iHb8XjhYX^3q{h6)8PoVr0dh7+_#!-HvNITBssw5#~kS9|S{3sYYw6ilSkLQwN3QuUrGWRbv!_P=NyzhP5V(iON&Nh`M{Xen zF7JDi9^l9VvB#(Og9{tHbdPUko5zD;N?gjwp%{qtfBATq4HxI8IinJ};h~V>adF=B zYQ*p6s=Q^x)%gW28_@53uO8}h`pSg4F$F@j{pyi`ymbl6UM$$V%Fol zIA=1-6dDG_bDXT?LlAD zG}LZO#oQ5{t-AWZn{2pOd40iDBmp7zVM;Ej$4h>w$FeamylPd+Q?h1(bi+p;UTIxsjR3s=+S!}@yzQ%>8 zNsFEY8<5bG*gSBWKM5|?EcRX4t7O&;=drG-;>P!UCKSzEtELmchORy4V1(zJ(igcR*_niI zt{sdS%zay*kycuh1bn)aX){^H1jW~WTY@mZtST|?TpmLJ^-``z?g-|LARkJQ5Bkw& zGJeX40!n|lhI>0maP8{?--wU3idy$&=}C4`1QJv;$+qmTUsloB7V_1!F(= zsfF?0Q}C^%EdF#U0cZG{s&tK+P`*#F+{`>89I;d~wo0I3XYcbyi-QfF*es`iw z%`W{D18#jh+cE4%11YOl`*hGB_0FBqzuiEBR@?_$6|^95oQ^vx~j zO!UqoFIEPQW!>sb1bfZKnXuhln4kYsH#iCXwQ*(kU>XfDTTMFmm8zt~>f?wB|j9I$Tdc^P(=^^UVw^G6ZAMZ@*r(3XaCPzOCf9 z*Y`aE^J{jc&YCm9d_eBmzc4nqZ}GB7UqZs!Bey7q{fXeN?kL_0c!Gw~Mu`rGQlS+Kg32Brso! zXoMptxc)U+#KfGXv3QgFa^y!!n$o%+^oy)THx0GNaNg;bYOz0=Q2E}GPaXSHbj+es z1bs6@q5bIgcO(?1umi`+kxLJz>m*(yAi`7fnNmFiT2zI$&_3b(4vop4FQC9rlak+i zgW@6Wzt(SssD}+-IwWHn2?)-A*~dYCJAOs{if$_#$`(04h(aE=T)AFd_5%|Pj`1lk z^JT-*m`xr79xQn9uslGvkp}*$SJ-{H@5NWSu0ARRT-fu(``KwGgg!~NEJR;^wej&T zfn?;dpLe=`NRTjIax(K1a(nM((L*bhC@@kIthEg})LZ02@h9ZTjru^vvD95Gf9RaLnw?f_jNbnka?&gZRME$uaKpp);KJ2B*wgpLGvc02b z*B&mM?IJd3VgLVhi@me}eP@%6pzYBhHWYZBkoLMrKx%tcA;*ykdt?Xfr!W^N3#Gi8 zz&W|zx$Xs>L4&x(%L+H0;KKNUe5tPy===TMT(=*4`C>8}Ohjy?gfLGTsFp%R zBL$Z9swHSXiwCaCvu8_6I53#>qip6l1@8S9V}29!ft~Nj^)ZJQpNekW$RuHZYAH1b^ViWB%MDH& zD6pzL>vG*CCbagio)qN${;~g-m-@0`Tv2U#2J#`FXyuR{_K%L#%Yc=)36PL@U9z6e z1g&u5@^aL3&+}2i%B2)|%x}itC>0NNw!RLjjT{J(ptr5PLjtEK!RoV~1I5If3VSRcsjdz4qFI7Gd0%-PeXrDI*{5 znXL#P!MqYvEazr|^%49xTe2>b0$#plW-gKOu*mGFLw-32j%w`eTfLKnA<;x-Hy;{w zv$Wnjpe{-Li#yL3O@%{Zi)ht-(I6PXD4|{E0=LihX#ZXkHf4I#r$cBkoo3+^VvIba zX{@m%lK_Rkt27TFhhJZ)e9-9u8&o7E0Ux*wgn)4w10K zOzu-@UPsgx1f6UcA3EuiC3>*Z!0NtE`Ar0-o`m2~3eAA#&c`jr=&j;*qxDdiew#-eTsHgU7ih zyKPrK>J|To9s7?m2~a&{G;)0n_H&~jOe4=rZwdL~1u52^F_S zZ^t~Q0TCduM&~3K)F;XW^6>K%o$@cdL_bm+ce?sij|+lFR?kljr9kcX#-AnENk|^5 z5s*V}uMfU29{r5~@07K4I&!a#u!vbRa+=zi2~`&6g@1Dyqp_V#Xh=@-Uxc}D;nI|@ ze=-!krDLkgEM2LPE@gXR|EFl!_(XB1 z9`;*#-NgJ5%$2sqpT(n*rxb_1ZO!obg{0 z;cm<=WlPkV$!Z1b!AL6XJtFM=DJ~ke$-lg`5cPJo=M#119_-JI)qdNqGC?N&DZT|ZMv0sFk`m-33@ zp)@O(-vxF4Zzo@+JwN*0Oz!T7i<3Zq=~2rya$M-LS){+LfB?dJl|a*L-u-2&U!*X9 zJ#6%^w{9f>R_BEWSu;VL52xwsfBl_uC-uK!yA71a=F^>ZA zFP1#GfH~LL(KMfT|C+>8xfB2FC~(gAYqoGQ6J#rhIBC>@zZDG^x{$+V+o>^!?;|HK z|8B#3UyN4r<+|=r5{5_mwiXU2g0Y!rODxv^Qzj>$wwVELLyupqyh?{tk_p@2@8dwT z;9e`yBq|)ZRM8nW8Vx7b82{nDcVn<$CT9iu*Xh&d2S-zoPr71^QmU~(yMM_obfSQ9 z_EvGbH%w@Mm|@Sm&U5qie_OVF!G6Bh7c`x~gokpc9eB^NS3jd%FDgidq{Z0{U*5&S zl~X>i8!%s6@6$-%L?=Kpd)zmB5#~6-rT!OCKPjiedh|3gA6{A~{JS<0_Wf4rSaOsL zD#zlAmB*2Xzjfs1VXn6xoLagb`*V+7;k$QxDBvrqz2f~V61v_B_xwSwt1EdsbP;p$ z)->0d3&<(otfQ~J#NU7LH-9i3`NXzV!JakDgv$qXuXiI~RhE9w;7$>s?Wb~8C5Qy) zt?RCo;+$?=i?eNmU5zJ+QeJ?F~CJ0D) zHK5RViwPRSLOm=dwfpMo?XB*!4YuN6`8=URW*3A0*7y*uN$Skatgss=AExs4zJsg6Gu| zyZ`#LF%rUaKL3#rNP@B}+i!^D9LYX8vNCER>fKel)&9P8kh$9!pQXyd`neVU)}X+y zdzPbam_J~<*a`>qFV=y`wl#_j_)l(8Yd3*8PqODhwE+hv9rYZR=n$}CZ_()xcP6NP z*!_{GZ?e8F@_8>v=&pF^@v)c&_hyXvb&!W!h>gF}IGA?^`sdHQcX|J@;r@<*E5n#CJPrt3_n?0bczQg@MBRveX{zV{ngPoN zkKCjM)1mmx%f%ngbHM+!Z0XAg7WkIY;>Fu(5EYu55O0or&Xm0z{z8Kh zX?s5pTP|$KQV^0FMO_tn*33A?gf|X-C(ItPf!X}ZO!yid-tiH8+sBe2YBE6dsT2o< zvj(2_R}wI~cWvs?R3>!ajWe}DU2?8??wOKJKvsRf(?&%S_#eCvT>pU$Uwlory1gJU z|Lo0UjbMLu-#Kf8`JI!ssx=$)h`jz4ruuRcuE#e}AE93Ptt>J;UW4oLx_#g$@4bf$ zmF0QQWAUx@59>9iz(ST!(^xVIlBR35-eDaKtrMST=un|#;|2fcp3$JarDn4f>VP22 zGAZ{21+w_EBF>_I_Axg6d>PD!vDVM24lx9*)HAcy`@?|w1$jvec-L=~oqQ2&OG2W- z;6Y`5zn$OvBp!DpD8&vcKl6tXkE)Lfjn(v~8^Yu$CFtKKmfF&8{_>W^wY3XmN z{E9zcD6S?m@tXiwL%~&3MkI(Wv!X{Jzlp{1(kyztQv zbvq*PLoOS2)$veIM+S5Z^2B;*?+?mAl zm1;bjde4RevTvX6OiO3NuXFRHt z{(bNEwdgGGzVpGdDSgxviod^0CxZ_8Gl?oAnsi|6eG|9e&4C|kwbzb5r^Ed63p1jl z$>6rPPe?$61N`dyR3wmBwTpA6?rx^QwHGpP$5GEy%7o401t?IeVbruAbJ<4Lk=u%x z7q0vpF;vBTB-5`k*7Ge9Is|ul|A!p1a`L~YbZ-jCNMyfIdB=qHeV%+H$fcgF-v(9; zmsZKy(i_El!JrfRuXrJqS$cFs1y_zdM2so?w%>Tw_5*7tpnRVg* zT0fqiE{RQm_osIbR~W`Zu!X5IKl-xV%FjEON>Cv089#qQJPCr7|6l@jg-*|V+YsjS^s+Vhdml2RTxb?|`IR?ZTHax7y z`C8E%nV^UIA5}jUD*ToSrtA#@RmjQq4il%6*qHCG*dDBzON4jr%XPEVxlpukT$mqy zDvmnwf`vIk+or{X_Z*>0BXti^9SThHJ%3uoWP<2~zr+Ok>H3rRHs8bk*V@Cg#+H+x@xtxntKJ(B_IzPp%8QY(TE~c4T4WTCAJ&x~}ojhxoZE z^XD~T&e}Bj=4}b;kAT;KpX-|l=wIf}Y(tLw-m~`KADmPE^D)jPSpPOXpG7g@On86c z=DsZKpM7nKPV(3%6KQf9Rj3cm^W3}R+SqV2-*fV%HuAxIXQQKIiSYKmM4b5^E-W23 z7d?gRD8A%oYVe*0`{fnR(l8f)Pj#c&Op%bjwEm~2P!im`vP^QH1{VqyM1=1kZ``eq zdR~A&@*=+_I2hO8PD{V!`GWwd7ftWmWJzeAyKis;`!i^b<=&bziIDZrk?&MI0cq5U z%{G|Fvp45<`Rt@Xz_Q>e@+}F6gtvQe%1~FwrW!vAFd#@*?}q0gI?PgRluM6sfO^$u z%eO27&J59nZhvI}%fV($A9WyvYkwqYBL#Z4J-=mfiUg_R;z3u`nPURmeLndR5No6O zPtb)4U*4wtutxtPg5DVawV=Sxjgq=4#h6RZEHv>%KBQL4ZKy;&-?H2#@}ve67JUCU zWP$rA`1{c2ie3WDEx3gET@oh4W)F+=a+bk0kLF`u5O(PZc1IxBAL=Gz66uu{=lg7+SWku=%Q%?}6=|J>=r z`Nx2a_H)PLv2JrCZdBnb1T-CQUAniQ0f#zI#5&`;sZ9Z5x2Z-e=Ghls!iJf==V9(Ol3#5~fExX|vv@B9lH5kFN8)<^ zo7bMz5I}{)SCxeh9wi_StW>-~$)r3ibV?9p8EH#mhga`T>2`dC!U3B-DB3 zWDWUdcM>+P(^UA~z=lUA7PF?PWA>JRrw+cyyjEXkEsJ^WeFJ?7@BUKj@JoA)`x1d+ zWBWi5`&Q^r&7md93_uDf=TD}=#>{0qZzI1+rZ2CT!#wpo#O&Mz=IG~9E0c@x`2KUc zrcM>e5xwmj_GL--u)Xu&F;9 zY_UE;_ZWGG*q>LG@`^4G5OBL!)pPVB=JdW}WzLOk_*gloSWrcQ9KzyBKP4W_{dVq> zDd)h`$xj*gkjL}_&A)_{V15}^y%15!2JT%(`blXD>^b+W=4UVyeA(++yyt$byYxnU zMKuMO!@-RflJO8M&{L@To&)L(!sdcp0zA5MRBZuYEL>7snEl{17d|c%*m>d^o@Z`H zx;`fnq|9IaFgN7F_=LUS=K$XO`!2P8!SmJP8~!Yf`LyEux2=zQv7Q2}^xrllLidH7 zVjtA)3tFjR{*Nf2vcM{9sxuyjejZ;_U&Mj244H``78L{sXMMw+pF!7(JlCA#Tv&7Y zfszL1vL;sLUC-+zEO)l*6U92)P8vD&wh-WV?67KL1QY5E1{Uk#d2KFYSw-fMaC6Z) zqfl-l9M0l@cMtcgWN)fx^J5CUeC4}@eVc^c(n>0J*q?GW^&S&eRA?Ii`j#&%4yGp4 zj)bD`)LJL(5L!b4^}w$E2cPkttF}xzrG|GM@5R|W$me++focI<&pcvGB@z2}$Cc8H zGKaC>0!1vxx=9H3>i3^CaG+?hB; zA*}PQ-(Mc)A?HNTO0lWPrNoUBcX-^@zpGfUOo9rIj|cjkN}|CcwJwEp<%00c_feWA z<^;>4k!nLaI3B2KanR$y&uBifAN}rV_{=p9@=VPIwW3_qy~-OMJCu-D&;LhGm(DTa zLvZMS0n0=Y3geescrn;-FO=st)h@pIh8~q%j9IDtu{`d&-2igUf%3qaJRl zyp_wgDoaivm z{DwioQ4UBxT9UI;lL8JdG|x#Y2?v*^JQS_wy|44%TSe6EgPn);D>0{BI5wBpg7fub zl}5nZ4-}BRx1puEDjxnx$b55t!+}mY$;aJ#6j-strj}92gvnXkb6nni1l5*Hss02Q z1UH>5t!?JS6?TJ;GEBBkzc<)2(F=LF2xRH>% zoo%d*a~JQYlz+MqebCW9Ls>KdWYY7<;am z7-jQ{fNi!JRpX-!5Su%?s0;PnQ>kG|8Tyw_=a!(m(+rT_AKUx_dC6$6jbTJ7739); zBetIwy5L%p||R=wCx-7p}2_(8uln&9z2T;BnI7lk!^eP&HZ8 z&#C7?s)_j3b3v%LL$Rs4*e6lx^CKm(Z%y)~rYjN&IDDu{fsOn&zFKvQH}+xc;UG)W z8|$OBxygGg34guSg+3zRI_7DPM~G6OcwXU^6Ih2~&g8Ka^l{%~Lyr3~uNB?*A$>u@pC9)VV6^I7-=JmrW zPH`djTSnd>>h`WzEgFAcV?QhDEOkbnx!JjUmysn4)+${x78$0&vC>+5E6lC8UIz@% zN3OGAMDr{1-ea?Fx412ym+!BJa~XDY*x@U|A6S$O1!bUWBF}*j>-JY{QlP@cKOf&e zcaDO&bEoSQkdw1NnD`o@cT++- zMX1ob<8}C3%Qz6!`!72eePnZmMsjr=`uC&#C(|~fep2;m8o2(refj%2s54iR!=+j4 zNf62`_w{OF!$a^lUzvmzn0#zjRCKhZVUxqIZc&zi@&vwz_#w_?fwBqO5t8CcRv-NoO zAOlu?Vnn%R(BQoBuKNPGFSc1Cl>BG{H1oKt5*L$D@U_f__k2k0s;l`7Tt8j@W7vrp zCS;aA+xh@?L%frwqTfY_$+eePHVZQ#LBaOW7OcOv=ZTB9aV#+Cv-n}tNP|1qt7AK{ z&IuX5?tBF1Dcu!c4}4-k5p8!M?|o`q+KF;!uDvb+R`pys_dJ~ghm9AhZ^L;XbsmU_tR-PzQjXdL_RnourJ4~L63)t;i{D>F zgL!Kgt#LYxKJvjLPi7Yh?so<6>Mlrvx6=zuCsCKY|6610@RI;O{yoYwAtc<*cHA9@ zepeG{`D7@TfIMHn4x<(ZP*#b`g@0y4a>{-8=bi+3$NgIK4>>dUO{nk(;b)S@CNO-;2B=sb6$g>iUj?4r))DFoX>(!z| z(B@Miwi+DRydpG*f%;}==9uI4g8^6LoB(e?kiVPFvEQ;ghUUFRpK?F?P@wBqBK#KZ zjdey|a^WAo{V5XnT~1)ZKM4|!3|QShk8?V2MRzCf{;cA+M2o~E1N`GkSGpn3R~NLc zN^!*8QTltAf;b6J&%%{As_MHtFrA@-sTFd=fOsu zyqmoD*a$y6ivH65X-ekk69QImiVh1HV1QHok=o^W{OkGOtK54b*Y|FH3IbbO#HUdwmwY)DbvBiNjmaG~ zS1}(+E^Z=Z(ZBd^#OTx@zkO{9F0f@GZ^{pZkl2UfFWUqT7Z4!2q-r3np9%lTc2Sdj z*&y;X;`tEzglnq)z`hC^JR4A$_v$PcCRYu+a-~rB9W%8(U(;aj_NT3HjJOc^@rxeQ z1?TI6s!k2&*1*%%RtK=(IBL;?{FuM=QwtX=vzf4b=dIAyH;}hw?UY0|QDJP~-D8Tf z1nB3??ef2hzPWI*rb004m4SujKRFWg{pC~qP*=Cj+#_ouNTBW6Wufvj5#&PZl#GB2 zF>5>dE$`tzM(eI}Vl%+4NZb1^er{nj`*I`l!;xz~2F_m?(7)_Vl^_0`Z)x=_?UfWb z>t38(ZAZeD?pe1k-upz17xg=14&rPoP~3#`*yJyJy(AG3&N@#Z=TT+Whe@m5R#YW!e6I~()Sq8CA)wk(L% zHqBFxqd}qc*bcjMy!V%R6dov{z@@Kd)gvkKptem(byXP$mc@?opWIBsj{U6t@7!rH zbU*r{l?~>gX{pKG$qDeJ?d*ZO*P=mO?^ww-FD~f!jk??BAy4LTj~qfifA)F1^I_bV z*lo1n9k+Pz*ZW;loI{5NcD;9&;yhORr|p@+9QW#${l6z(@zAa|vw2B12V(YHyQ{Au zVYKi0`IzoR2(O72G*iVK)O%B~_c#SawG9nwkPkQ6g-L%vKHL^-xLzIeb*l2sBjL+P zxW{+ccrWk%?x$CeTj2jwHU3b2yl8N-$s*%3_FLX`me3gLwz{{oqSI#vc*;lp3q($v za2*>IdCP#N=1al#t~5wZTdXmOJm22bRQ$e>3O-Gm&aFiR+)w`8J^wNnygX|A9MPw) zueDy&dmeq?XrlMxeKx41FQ0V8d0(M2?DWtDb;H)Pl=t519>Q5k1ox2X$l4 z)r;fg$%3U78960?Xt1Ycl>a#HqxHr>(^j z#}S>jc(}nP$`cAWAb2+H(xPP)7#mu7XCeV}S?n#Jcf9vCyu3V;C(D34?VF3X{!WHx zCV{oKv{sd&wYxgoJk;GnY}H?G9(;@?#z}I&dfT_r@lHL(;yZUpLozQ#G%3C zAo~t?+^;1RpBzuj3r7{zOqFpzr}9IuZ$}^blt zPyZ^W$Aw4!c~cRBm^(Tb^rT}y>->+UGmnSrkNP<6q=iyHX;E3Cvb9NZ5-L*Jl`Tt> zHl!#ayM*lS%{mO`4p~ap3JDbo(Tsh`79mTEP(5d!=ke#f=5^=Z^F8PDd4FcE`wf4j zy%_sB+&N+BvJ45k&rOXF$KzZJ1(`(S>x;)@-uWM3z*_lrE*c%_P*g6lOBi{taPVJ^ z&neWktfQavH>4n69)C2X!Ulr_|0!O;eqE=2>&DL-22>j@emjDCb$h(|R50rH;-!2) zKfPr__}96quO7{?Ing9XKa+&*;iExZafzUt;H-1CiUqgyR#vUXdTRS>{Amtg!eQC2 z8f9D;#|skhC`0n|1TdG zXzHKI0RG)^RWiu)CV4wqZ*d;uH)`C=LZ1J6h|zHz^PS$=*9}LpZ%5?%EqplN(@OG* zYu=$iMD*7c&i&yQ3ENkmt;HPl+D|hrjR~v|SD!z^{4#DZ=d%s-;~mB0k1bs>ufdmR zn=z-@SG^Q1K!1AEcf-(uSf#jQxC@5i&zjpchcm`eiBNSr#@a(!UPHP5)D4@W|00@ek7~FuaTi6eVrIiXFaNUCgj++r%Nyt*PwA5{7!U5rB;+FTC!S>~k z7XMhx%dR`G=^ajlJ??K?H`cIVxPG&&yfX>I;|-;*fykMezc+FF8AHPen!(k=Vj}T($fhrQ<7fx1@qb+|0i!LCIiwhine*@)8TaMpX2wD_gtjX z3q_8TFq32~!;7DL;JeafHS&MokNCo*Z6v%&+x0B-DihBCxFcDK{kbFX$==fNbeJ@1 zZVhNp137lej(vMrAdueaYgv&F^GlXI__`t;^pA`#CY4wavUGgqKIGU$QKjpSbmaDR zM;>vWuX0D~M$=Of5+thUwC%BPSFh;Ym5SGUX8SUesxa)&lN0L>4>3TZtLol!oL^(f zm?o!16pa5Vby<->2l1t@N7tCM;n?|~<@N0Z1hi5AR%bFndaCwE6VB-lt<)n1(*(?Z zZX8IqWy0*~(A2ehEIvvS`wDvDtGB}S% zxU%gI+@ryg-#c|9yJO(c*Y67iP*=B0e0R9;0CSdZP;W;Y1FDwKeR0C;x+qzG&t-iw z)ciUSf61GGgE?zvbM4r$m+R-T+Y%%k(!1ZDLgKoZ?R;K}>s#$^F3vMTfSA26HHo?; zu5N7?iPxLCV#SYJ3n+;H&XbeoM~Cs=7uJ{0AWzDRSo&Td!J#f~uMPTgEpJ0gHR{r* zf0LTRuSw|AoNPScmk8w!FYOB7u%OklEn+h*1r!S7Sk7H^@Y#JJe?prDlj8Y1-dWK= zKO%4U7T0)4r%lIXW3G=gxT|iA`nlV?kEl4zgk2w2x<8I=26rLDCs)>!a5=MMqvBmA zC~a-ZuElvQUZa;m7bQVvLmErl!Q-BnT87jDDYx@3gSFRH*EIJ{M9`) zxV&Mj(mL&U2-DGgdJy~n*WEQY=CTQx>Hf)>7p1^GQlM{VOEUyjTzl*wOTulvz&c-? zqjNl=DxBxps(as!f5q8Xag2M)C4mVgrk(%%FrSJj)ef(x7_e+-N$RQqtWVI+JiSw> z4|P1=&MwF~#TDMC8X3^cHeCD@*H`|1{gyY#hvk&>+obm|hF`RRcPQEPEnYGqN z{a!|FQ2V`3J?a$!1L6tRoyHW1N4O~0A}2HN->Z(p`I0=bps50NKE&69+>AQ&z1G!H z3OV0#JSp4u1rw^cRv(W>K0p2J;DtNrUz??vr*`C0u)!uczzcQQYL86LkOcv1f0cQq zpJJa=o=c@s|A#bMZB!4_z)HaU%)0&9`zN!80 zZU#^1rh`#F1SrWA4m(J2p2K5us2X+bOmtYXDEgyb=YJNz(I2f6rK{ee-k!d%^RYB??<3EogC7zJ$ajsB^6g;2 z=GsqVocremHaE+5f2V-l+^*XAHyQ5yH>E75#DXLR(?(Y>k1mszLI6VFldCJq(+7v z!1~w2m>U$vBu-jjKlko4dF+Jz@IKJ=g8N1a`a<*dj^R4Smib<-$Nm@GfA;5hZzgyM zGuk%bbuAsC9M?EeP%gP*AoFW7NIZ-?ntzJ(JCt_3Mm7Z#r*{S3{+0~q4VQ>+K|c-9 zxHcbjoCboX?NXPOSOo+7LyKseaSx5SQ_*` z;s!Nj_-kd2^QzdN^^<4F)1yqduT}TsFXo+!%)Le38o?rLb$h^YysrP zz{9M>uh~2lSSjDh(!|fL9sC_OA&6X39P^^6lnyZ|vF9gIS9i&ajHnbb;OceS$@LL* z=v4Fk+p5h5a#iHj>@=LO(G~+$aSDiv1v}sq_Gi`AhZCw4>R;>h^GrGf@3G9LokQM` zEl{mhN4^?3-CG~bguNFJ_>(w~a@t;uQEt?qn9H6ip%fhcdv;Qpb01v`6=k>vxpvp& z3zlv=ygQokSXq$;pHok8S;i7@Yx|{@%6R@>GpeF>I2Zi-wrfn^65yBerNY;Q0_BO~ zcoo!{W3O482aqf7)cn4a8Iu7&Mi*G=*)_v(MD6&{3hXN*iMgwBaquc*la)8>r{W{G zs5taH@xuw!4NWFA7TpS1hC09ZO^3Q6_CvW+LXuk<`q5#(hOM~n_uV~2ThPA_2he)I zBfl*=Fl7JMtr>nS7Zv%3e$wV^)C^5eM6G9bT?kYmBcK zlP`;f3rOe{4b}bSkqAOtyuZy>3@+;7y88!&HQ;p(~@q zHjd209O}Ynugf>hfcrIP4}QZwVFZ~tDD9(QMC3(VY%m?fBK~c3F=NAk&Z@t!Z=sKG zELc|mi3$EI?lU;gcM6%^>wNPJ4R}^+T2E6kQ2pEE@{608AFqy|8Ap9H-SPEH$U_P~ zN6&p;hrY9HrgME3gWk+8{XH9Elh)BSInh5R>i}ZSn}3soFm!fb6m6}0=^q~ z2tPs26z66Hjbfh%jV!H}c}T!oxAu+eh8fWGgZZ8F{mccQkD@+unByF}3k<&F`Ah_V zibG!gUT1S)3Uj;M!%HOzb`)6jZQfe=p&5St__ViuG#wU|dkhOzr-4VpJ-2+$z7n)- zdES>aC_JnxCxdz*D{%Mj$Q3sD@cd?5R+BI^=$ag0nFyW#U9@kg!*#iOL4!Mo0twry z&pQNDpu1mln6Z})N0fEDbS*PLbQ+;fbA%`$ekFZU(`zfxW#1K6O?dd`!AK6}P1-r*zq;L*|ScV}_#red9R zeg%-A?eK76ryB*nZ#=~wV*mWJ%KNsDPQc*@=^ke2%e;@R>0Wrf$BgZ3mUF&WxtVBq z{0jp-s^zRBux@ST))#Fb5g?~^%{cWJ14I=fiI3=m_AYwMDD)K#`8!`fkaX~pnb3NO z97{j&Vtain@=x$=eY-c#)7|YG6EFvLNFP))l_H@b>YSV0OXPu78<*0N!?*cmC8q2q z!7F0>NdX@UL=Syxc!cNqr!S~6{Z|s4+m>f`s4os|_Y58D z5u7IdRODZ>pd{O=r*H!W+b3kbk3C0UcowjDFP_h+ai2|FHwpDI+6t4Kk{~6FAQdm>f5g?IZqa& zuPHn|EjYpXKkjLdo-62^)8cP>?f<63xw^et-(}MwN&M^ZL12N`<$;rXV^9aI14LVp zi+=t)t?iDyL9O{CFk3`IZmP}7$jU@`@$snVgI6pNCcNzLdDCEfZ06&{pcrW8o?G_e zIvYOJe{KoCNdqbIlZtG2aT7Qg9Gpu14U9(AlO=E8DQ)Q$KQ!K<(DQ;>UN<90J# z-y5&5oe!=eAS|uB!36nQx9el1DfUUnpZocldr9~&ap?9?E)y1LN{UOMFIU9bocMNy z1XsenQ(_QgJ>%KRGSkjBQ-JERYjutKA?yAOG6)diWt zP1skSEt!9kwMckhG`prUm4drjeq45#BlcfO@OjNbt{X|?t;l17rPi6VpS_wP&r3Jg z)_{bN7YWP9e3|fD;)iJw_Jh}{>Z zhVh*y`X`Xb)@+skDfl}X_KehMPpGgVp4)~f$NKQ?t+sJN-FW+#hq{i(KfBT0;zkw$ zCmQ3@eU4&(X7||kp-gDmD}P z{^O6%K!4fbR{mjeCIQLMlFUOGOepB`_$iF%x#!qq!29%0nYc3y*>w%ijZ%&C@#O)n27n}?<4+n{9NDC!Cb2aB&2J7 zh>AC3g6s19)Ya&B%G3$_7m5s6nLcV8_B0(d{C|szB0pqiiG81`PX|Wj!}k}x(qT*U z?5|TtSx}SV(JC2=Tw0$vb^ci*T*|t!`CB;)4mu4R1{;xZ%24M+zzqtzdtNCvpzdXb z(%g;2(eDhU8y;PYhd}1R;0om159G;*i&0n0#h;W3FQFi>>#E-f_Vd}eF}u431ZWj8 zHts=wbLd!Ee}%K3=GNd;2Rwh{{=Hk_H4{em+5gPPK1mtn35uUdhi`5D z3n@@!M_mrZxtNHo+trP^+ULWAe-n#Sz)fJ}PtGAWtghpE`UtNp#*Oc=Kjy^#f2vCt zV*YjaEq$Ga{Jl2S&TYp`G91d1()U$hgTwil-$gjTHyFvZDjFT)|9f!t6!KxS8n5Id zCIKsrd+r=VzL?C{I_rfxZ}sim!`wZ{MW+)xb1$YtdF7UW{HWV}#TxE$mNfYIWL!>9 zHU@IMUK$<3JidF?WyMpK40t{IDpV75im%eOXg|*HkA)>%)HV_twcae&??)Y8`?$Fd z`%^(LCP1XUiAkKyC zre_vV4H^jW^4k5R8*k`IDeLQ;&%OU^!_1Iuqq7TIJ#OQ5h! z+Y}uPK7>=8{Wptbnx+D`5+L7Zm3F2#1B%^u8w46RgX?j6>J>ZWs}mbdjadxPvs-VF zi~SQpY2=JL(O}nab9bNN1lae_JYtnT8{`tcZ_P|Ve{9{iKF=Zv!jA;zmoZt8zj<#! z80s_apU9;d^v5jGrYINe&!+x6Pm2xF-?#KcY)9YeTUT=83;LW5EwkNHv{xL-)98hP^j&DQ9PYcR)I@>V|fr*IAj!hA3< z_wW10tig5p-mov_7Uomuq>Y2|IFBvMqo^Q761+F2IL;SPaJg@*Lka3bf%U_+-ZCVZ zpW`|uT7>l^Uyr5Y>tUS|SHFdmP(@Q59kxmYPv`WbQ`IccJIAX?6Qx1io4*&l{bFGE z`vd8PPRRLgLGM2I5s+1S%l=;j6ZVFPa*1G{mj??*Jg6X`$4NXt5p|xc*Is%7`fsIk zMY#d$Mo&9&b?7$(qOMzyYhit4E7jyW@i^OG9A2|9moT|+0nK38vhckK$ycPsvx`=DR1GHVZZ z#D3VLy{bOt6#+UrM<=*;Qy|Oh%LqC6 zpoxH*U+SMK`6)1X79E|2=ef^WMsEo%15lJ$U1fB5rY)DCV}*X5xkThn8v$NH@0RGE zXF`gh|AQ9%+&3CS=_2kl$eVj=u|GTphIBQX1aGk6U#G?M$lCGVU(OZp`Q&VPQ8j64M{*|r@qn16X# z3pP|D7nwZ^eXkNpL3zHh3TJ=41*@_hJuxRkoH{DBIGp-j;dJ=9#~C-=h+Vr2yn;1u-CAC685K= z%R%#Dmn2BIv?uoV%{Vy0RG6DU-`BkGX@!dl2?N6VPTHs^E(v+tYf(?G`wyL8R7HWK z^qWq(>14RMt^Y_r=IbN;tJ!aGjwXT>B&#AQ;Jf0=$9YZ{Z=_F$7wWmSgNvm@CY&Zd5m-f{bugnB9cdd}YbIouwXV7Hz1p+1y3kgm2F+g9| z=Ug$>TnD>GpDPh zCb=B_@#V$yTIg#+CK0!^$_e;f|K{xy1*~VU**e`%*tcHRX?FDlM1<3OqR@v0-=-DJ zI-(Bi7%e(zMxyV&ciffCglYE#r(ryffp>gY6ZVynyz^P3G$v@A+!Ov4U%x=(UOcZ$ zgL;c0-a@Y!kQB`Lpn!81arQx`m^2eQ)~jkioK1#++>6bDr`W(Nv9VN4hx43{&s?p) zk|A7G$x8${-!r?tl0iM$*)vuqjk#OPv~*&@HQi@(uQMUhzD;)&=SYQ~^0c84>mFM7M0)~rn49%Wiz6(!o8cw2XdMl{ z?e9VDbWx*y+wymzi|V~Zg6r#S=GyiOs&a^a@#F|4Pd zf?=8w^5;s`;s@2p16%&Gb9iI$b1f^4O3<(OFFWGXjP*IxL`-V5GC(?YVcJvVz4eD9 zt8U#TAj-0FY!mY5#{$F=E1-a)vL%e@2(1c zxOFZG5)Y0jIqJp1u{DJ!P4N9f`p)e?4w1lklk_wj>kw|*ywMSLoA}-MTb74}8o9Es zIyk2XycN%Nah_lIJTmz=u4CmW_aDz^6zr_nnBZ28{i)%?wT1J$Smb7XVNWJFPn*#* zunuOYG@QcoNZ7P@p%lM*5*Qm^*t|QJ1xEkLYL*|NK>KUKk}uuK5N+BqAdP*pHe~Wx zHrDfE&(-$weg+ulIG81MG{flP^Oeu|NubqT+fx6C3ASPjJ^`+a;KCN$W7sE;J6rE7 zXHjseV4t=Ua@V)ZWrBthB(QalW@uVaV7~T6$w$=NQ}fS5f+q>^o-Z^d6DX)NFn(u< z@821?ly4*I^X$$KTb@W$@S1B~>L}-X=DK(1ow$)3)UJ5Hb)rMB=QW}8#%$PTwpZ`A z7Y#l{>`*Q%jtAF{fusRFHhiuLsJN<^0iPOsOR@*(ki5z`mKSq+^!(e2ZH^>d)7u~$ zM_|6rIPv-u)^p3(g6}7$3Ai5JcvUKl36%;5JMQ6ioqVyJ>EK7e(xVCD(a2+`pT0Y= z0AF{m`fF;3=P&cCq~t_B`fSF3H#TA4cGd6V9;zduIHNjK?q4EkE&I96_c;sHUtQFj zp`)I}me_?YO#&@F1);fo7KDTjh3vw7)EWBMc5;9LbL^s_KbVh9*AD2)q90veKL3?M zU3y|WOQ&#NQj29>B)LiW)qh~Q_#FzoW>werp+8PPNSF|gqd-U7^qlZpI;0$al6eb# zyyvisSTyFNc`NE?!7V08$GUGX!@m8?AA6?*{as!2ZP-mmti!dHUVHF3Cbac3?ORD` zJ$`wa!+Q$!qOx+uE6_KK-?m9FBEhF*d)(Ah3L@U82DMwHPqEB^H1h^#Mk^go zf1TdBozwsM9%iF78f+Ak_Kg4+k z@tv7v=#OhUhet7wOh5S5)rQ>F{Ki9mEpp3doe-CQ)l4{(!hK*T)>+=YuU28h&Y*~u#|H^G`eF7|qYnkcV`@tt;&nL&XM2A^{gt|@Sjv-&IY`a& z?+vU^6qPozID`VB%RjlEjV8lci}vEzcpRsuXN#1E2~ep@6`FHr!mrrF-<~43+@4IE z_d>pU&g&U=?I8s{+iNE-p?;d2xpd@GbSfmdTJzu6Wx)I4Rp&6bWnqq2Vcotv0&vRYjE zC;IHBgNyZAQBR_V>ltThm>+9=UfKFLgQdgSg%PDB{0ZQ3eyx!R1!i5Psx>T_UVNAG zz1QR*!w`qAr0p-vu?G}V>Jq---Xj-hm*l*)2f9J zmDy13RM;ePn*y~vM2Hc-?(w&a+xjGaZd>i~#pWbf-t0L7ICu8-brP?!pL5G(4%@qv zP+t|1c@zC;!yZ@0OI)wD_BZ-UIeD-^TjKO{3JL|QnHtFRX)EQUrZ1DQ?*4$iQE&2Z6sDXi4Hm=Lhol-P!_ie1k?{a==!n^o`j_ZHVJijU6)92BLVCO*}sP$ zN**I&N%^7Hz+dPK_4P459?kINj@8pNl7O50|1j?KF=0eU(lHfz=JQK0>&Gc1c(}3N zi@i*Qk^?>x6Uc|TJ|}*j{6xTO#*wbq^GwJ-RxG85{XbgukHKY+T=meLH*h8y91gEP zF}0r!joTuA3F7;M-yc?ZhWcsqiS||>^^+E=9VGmS06m-hrv&EKpI0P%1Xx(NDCg!Z zSqesO3H{wQo($*G)B-;4WkXqOd(prf0``?E)J{uLkjhoA9*yfexAl~)dlmsgk~N#R zgfih;?4QTHn1ia$_=W#RC*bkw@T?MCuL|uyxzK_Pi(ZVYOen-2)~R`nsI%!S%}W>rdK` z+?$`=<|;JK0Q)S1kG;qt>Q3w%Yt=Kr{`YF_9mq3$HuuA8kXxqYogKuGXG9+CtDEXb zhAYdz-Yz|YoWCh!WAQo)7!%Ku`@SZ_o=~cs|1i#D#m=AEsH>MAKDzlIa=ZMr#-=$u z|N9f-)9Gg^a1#IX$r`ya_w((x{}k9D;WnG0dzqqcWdiM!< zHh*aADeSl5yIbycHwfMqZlps5 zU(&T&3pS{9xQcXPe$)@C_TGc}T1(w9S`oQL?fmG4&`{*4e8*jn@j6}=`3`XI>saSF z=u$tL4o&>JrNJfXpc0{Uj%x=C{ECmU0{pPA4D?&tFEPPPRis}CkMrQU(n9ha3HL;^ zKdU4%;cl)N`xfdza`Vpl9WfM`b<4&++m-^qoJ*57Apa<&h1yul&_Hup@PV<71dOOx z-ZDo2k{jrLJc!3Xm}(JPbdL$Zv=p?&>-AZbpzNkjz{-~D_hZP1%P$_UU~%^2D48fG zzY@@4CJ=7!PQmxfd~>OoFNWE!X;FU(=qHXm`sYbOK(b!NC7iEKCps1@qJJG@s#-a5 zerM+y-DAwz7cx6#u^@8ME2U>Aul+~C8sFn9SE9b%k-O&@*hfO!_8<+lrHL@htG&YD z6Z+2Ah#gmN;QJ!%ek}8+!{`(#$DKRb-`r?$iBkFH5cUYvreY;^T=06EM8~q{ z3CL))&D>GSgrUvy`{vMRw;mMJ#^irDFWh3oL`SS@b1U*>*Z#i;QMVZryOwhJ z`Pgj7i6@v7?XR2l5AIKb<#tbf3bRQ*UBLrVRz`Gyl?fP|rorBz~CfA|P({kIz{`6x2)KAM?id_tqr|JMfY4 zUwA}8-(3n)GQ9f2aD8p{#7BfmY2c+&{ceVffM&Np+Xt_*VN{M!%^m9_t7Z+sbxdg4 z6BXm@irnHld({?wfB7%r;!Rc*NV-;4O5kw{ilQ49<&se6Q*)+}OoaRG0%JQXSWsj# zdyQ)c1uuOIJ8IJDkXi#;zi{2xzL1>S{VfTKP zXQZ6bYHg`SI5*|A zIL`fYP9isU4d{{3-8LiSgZ^(m=KuT}p6A?0$z@KunA5-A_#TG*9^SrRah!8s)|(-J zgYyLVc7KdXM*ZnodO9HaEdK^HphBzUdJSUWR7$}D9Ve_$q}ikGVl-HOmfRI=5(EEjXnlGG>+@#m z`WAad#5oB4uswJcb*YIJ)A>RzeH z=hoZBOjv05Qy>`E-FK;gd)$%M=rU7bv7{!%L!%>K#3;B zw<1>v3!WdfKn~QJ(ACXC4$KNJ(|F2m^aVS<|FXWFV?wFklek%2cTcSp9`6k#uID#JP?jgnetuy5nr--JaY z2WFbh4GbaY2R3{6_F%t7vUygFu1EgSUKyqxM+e)JyFv`lv4Ig5;uVCsn~yyAsRFrn<&&gVO@A2PS~rYx!>;LElQQkW3X^a?Ntk3(uODx?)NC>fU zZ)wL|8QoeF*o-;OB&WGANScHr#>grf&1+P znH)S$rbwB83HAxk_~fi19!K9@ck@47FA*DI^?1x{uAZqgFXtIh`_>|a4>{AVN~wKk z2MK{8cBjq@C&8Oe*S|(jS>SB+pr>Dz1lw}{p{Exqcv)L$E=5uiwW;i@0Rgf+ca{=7lXsaW0}zas;4$AEF$U*zpR(fzO6Ua+9{D`Bq1 zq(HWQVYMK43LKmgDHG=Wf1-Aw&vl&)SbDnm@tbNo{9CkjFALZAZ}|AtPpEId&Ze_J zIZ&{#Onmwmes27Op4CrzNVxy`%Ke&8Oc>W6^mRpkxF9$!#=yC@aLEudNJx$fn`s1nr4fay4m&0|IW<)z&CQ+-iymE<(v~10h5J(e&o~Nl z<6eoia_&ptWZ;#H`SHTJ58Jr$x)zv-o!yAnb%slL|C?+A+#@0mb?u~JI8oqeB=+0l z4b~RhkVCjdt`|?|Fkw!*<;Vlh_lI{JyE}SN2in*gT$pS8a^Bu}iSPG5qwv=95Dn%U zHv}>a6TmtkO2E&A4X<;CWvccvpexEpWRY$)z&$<61gbDC8~bvJQG|s zp1!ijb!<1LH)@=TfRR04<18ej;Y*bVI@nyvB!)6r@8|HG9wH)+2bJ{&*6}@F;d0hNpLlwrT1859IW_! z_>Lyd?;!vFwtyuh9CI(}}a-IL+U3<74Z^MCPGqkvae<+MN6*+p8} z71`h-V=|qLzFc?ABS*uDf}>|xjY{}_)93(&je0Z~TlFZH zzbzUx9^EjJK#mI2$@yzTBj8PmA0ax)fV@?P>HlFqy`x2OCrD5*m|zm{Dx3~();^Q_ zblFh)ByVlNc^aG?yLP)%B?b;$;j5L$=~YKG3aZFmo_Y@ zj38i@?rN#ow+!&QF7o0{S2M&IH7WVtBOsb2GlZg;;DWJ6hO>{%{S!PLHwZ{gxiGAY z`n+{qOOzk=aNCR+dvh-V3w(GUZn%Is^hdLeVnj0>ifKtY@{|VhO7AY!TucBBNk^UM zI&AQnf2Aq>9l6fw?(IY!v+;7U*-}oxjw^X87MQ!u6}GL~f!uDDzVF2v z{R~L_RTiA_g$`EQ**fm1C#6~&GLE7zoKs(`qK5pF$X@W7v+oI?UFnQY9|0b!me(V9 zqs}}j9?tmG3`vp9PqksKejLHFebrHKQJgZk%CU$)BJs? zC)aPrm44hzLeS}lQ%a~aA%hpj3#*&q`!X(-RW-Qo+uk|0rZ8d0vV}qccpRE>k;*Dv z5^{g5cN}h{;6;G(`i$4ju#lD#UE@f>C86!y|F9qa@H&6XQ)i$%dN}*J z-^(RbZdnkpSjz4r<0TWgLXR7yA)h$1emFlUB7p3E7q%7q$M?{R8XL^TYV)fa9$}yK zCLPu|cZUg@L&fABtn<~4EbmgBcW>X-?Itx0u)fJ23q(FKS)Trprbxk^BW~&OsdUhF z-@QH@dCzQ%oZZQO0s=fY?>&Es0=H+1|8ah|wUM8DHFTPU$>Xg?0Z*8)Ua_s92z77s zi$A==niP~q4E^+~@Z)ST>!6;8vD>a%v(BEcw{@2=kiw z{KnZcgA5p!Gr8_{pAMm>RY`l$FFyWl_m4P9!U-|j?)s}Zzh||KVvwWE`?w?(&S!vo zXTy580y-r34Xg?<$3EO1{#hNlaaW&WR4w|Km7XX~4ePIP>vHm0^nKmfNWIB-iSTvo z%qPB=Ebx4*3W3*XU~Xf&n@ceUcx!_yMmfLZYntB_B_L>4>$frL>V+-m;}cN_xF+1C?(9M?o%x(u zhjXJI*vTD;ugi=EU)kJ1LfOC}H8_?CquOfGe`{E9=kWYCW0efBHmZ5Zxlifix<9VV zP#@y81^X6Vp`cQV;&*(X4BC4yI!9vOmrr*$vq#=IH(Yq+fDZ+ebvtz5Ah%b!n;4UL zp67j2&!q=bkox0#!e;c-^z|FYjyxh@x4d(-vM2>=i&=l1(Z^R04f);`BZ2j!(27n{ zFqFGxQVVs%meddQoMJ#(`rJ!@59FUPso)LRho*rORy)*5xOgFdR-gv+l>XXTPJT%` zzTc?qF9Y(EnolH!(qX6iV5i}E%=L>K-b?dh4r&S~L-F`2n%&zU;_>rOFL>26KmcR$ zo@Jc-Id`0XQFj^FcSXjLmm8B%cfKD{{M^O)|0zf7Z=C14Y|Fnb_7(Z0g4nni>;KMJ zzEBK($Na*!uS?HSutlI@-~N$gXf2-hFFDEv(M97nSvQcI{mX3EPb5RA{-&V2s2f7B z1gH~^$mi?Ie+;1xbe4G@3dMOJ63E(~ripwX>+;nxf`nb^ePflE*r-njRtVtwNlpCD z68J@jb8+dshYZ;8)XlVS@)`*%lNaWQWHDhc{nlcRe)=?Svs<0W0FwxrjzOMO*e)>9 z@#{1j#OL0=c(9&?zOcH)o=ggAvJ$TE#yV7{{CW8<7IQ?CBu^o(drtgDML$zE*#F+5 zkn$i2B(B)4{-hZX`T15JHOME&(^hx7XyAHrm1gbsrQmkRfX+3}ex|qcYnEZZHJ`tf zF^@Xjb3N@=cSSQa*By|mpHGKuQ7%V5?{rvRao^=D^2~_D>ix6R3;=vUgTK(8(9n>= z{BrS=j`TvDy9NUzBefO+co&;ps6_u4emc{u%DFG=YL@@wIILS}X_847@=@v!`8Ldh zy{-lQi)l3Y{igfk z`Et2j0M2#N>%yW8KN|cw)3IJK6@7bMZQmCB+|XZbVzc`(*OUqC*n$0_$e^HZ; z|ELNHBJxu<-82e#aurhNF%O$a~GH5v&JkdFHCm`>0|lxbZC1+2pMQ8)ot>y5;d+tl*VpNZU?G3IYHv9UCanDx-K)mfH5)2N+h5OfH{ilyP0&?KCALSpnVSaH}iSp%NM!}z(Po2Y%yG&2DI;(pT5bR^2 zD~0`|+Sye(iQN9|kk-N^Z5mkGDvt8`$3T+7^-&WiHiVn}am^_}|N7#ocyK=xY~4SW zbc8plVP6NH-!+(Ur;(>?a;n{+ECG%ZR zen}Du>phwb)VwKp`~T~;=hwvPtC-_h9lYX(m^*XV2$!;uTk`DY{>xlUf|cf6Z>v8O zzW@Kehf-2oPHGC%;BSkG*gyFgDBV>sRDwKH;+Wy%?n8r?jF7O&OUM`PF1fPUw_jcQ zzc?f3OI{3H>Vi4wUbQ%1C+Gi_%rXMIgh&`(cA|bHodVX+ zOp8qe;n!W#<(e$ytyHhMkEpjRLatD#>xp;k#ol1P5ZWWL|0rj_I&r~uCL?s)-i=;2Y`j6J$eYzZTmO$>;6(^9#Mh;rWgl&m|Egy_l9>();ebHp( zu1UhvT@B@KsQ27kVr=eV9h$mo%6aY+u)M_hNETPN6;`WQeSIXk6# zgAR_C+KZDgFKmC~Mw_oDK-gDj*-zwQqwW(vr;+Cu2dwVts3)K&VsdiInh7(%>wL;^ zPCu`D+Abf1eZJ*v^ekRi>&=xE=XscF|2#K4ej=nedcZ@_hr5R-`ZNML{ht4rFdEgi0iR3&I?v*7(e!6jJ{1~@I4 zey;c;9n=SB>IC<&phA*+T@L1{-48zTan~Y0s~kGKrh;?7mVDm)Mhg7rYGR%bB*O_2 z=@-FjY!I|xKB1sZLc*GL7GxCiHRrx87szP{{C!S%==m2DhIW4eG$vF$V)Yj>uePO#VR< zp1Tb?SKm&U%lcT#2$G}9Jz+=suY&a5DFZOW<38hl4`8DYK zE$%-Czj69%pVToEc@ng)D}|40;QaplL|ck_Tboh%$1oh{j%%6GzV8gsuUIel1NG<1 zg0WSc{l%W8QXhr7nXrLB$D$woD`j)t8Ey2Dk{;EIDyVz4EBElwkxNI0k_WC~9k#e% zw&}-t@pqa&x)Sqdg+#Ni&k8Q)2|&`8lq# z3iEES;)(l4IA7Ua*DOiS?{G?|B^;2e#lm}QlhIEt)|quf4gqQcN4M`q4j);&EqA?7 zGnBLMZ`s#E1Fdjf=Q`xUKFj3`tlar~)!+BM^j*qekFu(1*P%D7~ zCYQ%PC-jjUgIo+Z67y-FP$$X9d9DjxRQOXfM9y)^uCXS-@6T#k!+0hHHLxz5;<}H> z2)#{+qk+#NZJuMM1P~^5*DX-5h6mJif{jTywPREAcrFu^sr#EnIp5=XimlDlC6RMQ z9p|Gdu+z#`{fzx4ec;)G|7q#W!=ZZLFdkAAMJV5rrA4R+*+P#j5rv8-=BLr?|Xi95%4-i z+d)2w30l1UnMaT(t46%}?H&>^wk&M_DBjnuz)jP1?DxQ>VxJG&k~iL0`*=3^^9+<* z>2g2_={*YPe^20#bBe2w|8tH;1Y%zd{FS(O;Ry+H`;V*ZuE%`cD=Dz9g$ODKs9 z;P-7bcCfI&TnD4$bC3syI*9~hMGC?Os>EY)eT5Z@DmI4^pq%$E#1i#kp5(&wj@U2T z2Gryd+mTb9*q)Pv*+8RvuP)oqfpa^Iwwg+y?%9Ogxk{r!UD|}(BCO|)st+EFw~}z$ zP4}ub6H|0uxm0*E(HgiDko=I*2M$^;MBlG@>pW-g&xAD#!jp_J$LVjDf9p6zfapwk!p{3lxcGBV{^4*Iyk5U? z`!nPmD!p}94Re#HYtfc4?4y?fqtyF;?8oGYyz~|(*nacs6AD7UY7h0_-$%d~wWrUb zA2NZjy~SV$cfW?xu-TJD1}rUkyiVVd23L<3OLn3UzOl=<_Rc1uZNy=V;_nQ2e08&* zDss_`f!|zxGzsDpZ}V0DWx!~0vZ(wcHu!xn_2xKYKmS?P6O}@P&+0$aj$^)NX+GdN zj&(b&?>g`jxz2v(;ktv!nIc~_t7TV_5WQ|usPQQ#9Fp_-@Ef^t@Zoxe6k8IGKX!=v zj=bX>7vYy)%Yw9*Yp&CfHv}E%w=RZI(6oTLo%@{Fk~OBTO2}^qUA z(3dBpm=zo5lMrLiY*~DUg29Q@j{U7H82y$U6sk@DAOG;q z#VTo|`8W^dACj%z?^5u~cBqbtIxqfj%<=mPw z)@`{Yjs0cP=OEXHeHZe+!>;TL)-CwaWJt{Ken;Sw}{O?@%sdCVQV%^wy-5D=;9G|4x_0K$Gng)R2ijh$02 z0)iw=T=r`g#vGAwB(G%)`of94!oaCH zk_NhbwD+fRo?j-Ns*O0E1&xi>XYaKqLu6?1+G!sSq&B6EJ7YfL9Uh}vZ_?n+W^YH* z6?1pK=c;|kKc_g)gB`y!z^BcA7k7W9-QCAKBCn&K@7W&a`w{EmNR{p_oKIy3=^*g} z0)%?jw};|=J&irryAt((w?#C6k~0aZzaEEogi$bWuf;$!-k0X;$0u?W>CmGiF6-ET z2Wsa84%a9km%bWH2u~xyKI%bwA3Fn{<_rIAF2~PpW%}9_Nmv;@trKO-1bN$ha-4e} zOA}@D+>(I(3oXn>JehE~mH5SaMviTlu%>oJWwu0-Cx8b<5kXRx5$nQ;)nSYTF z9m@_pujR${T~OuGgWOU=2<~V*MnLX=iHa(fd5~h~wSUZw1<_@HY6de@Y>Gz$mc%QPjALzJ#1ciX8Vx}0xT3%BL(7^Fu<^OTZF#j znXptXJ|qtkrGr*`571!F)FOD}5e{f4BxN)(NswHTvVE&|2Jk;GPCe1Y28EzaRaY^e z`Z=Y`@|G~+{Izj+4*Kk|Pa9?Zg7YBegyZ8UKWN}o-0~_9Iee$k(NoKF2zZ_o73;Hs z0*$i;o3gkZczre(G7v+Ldh|Y~RM-I5jUsdRjCm_|#I;s(Q`!;{fv*kT_o$eFo z8@H06QF%P90CT8^i-9H|>R3%AbJg2LBorQ=GwSd~9|<1bUxW3Qw(?JBJo59##-oi7 zL@CgJIB?4n*FE^h#N~Du5`yQIYFxfefv=8uggaix^8?tQ49|oQ#W!-(CsTp$Ghcie z`bgXJ6+A_#*NjzGUfS4q^Z6e2gkwLtq*hmd$jbszn-{)o*Cj)juxFGi_E*9xiRY*E z2{^j^sOw}=9%T5bJo@53>@|O0b7xmJ_;o+lI*lB~3Ubxd&?3Rw zUgh8*>S2WxZnf=?g?vxbDO5$56p%#&a8Fn5f2jW5Ycra)Xt z@g{fQimrblN5hDOe8(d{)-X}u@|KJJzzNuLRLa=W6f?Go1cbA^>8j^Ci!ceKnMb7)%s_RK3xNWY!z z*NXN0Tq)me6uIlqC-2WiJ`}inDE36)JgaxRe5Ps$sQkM0{+%}DmU%hFddL+&^PA?K z)g|Cir06#lQ}oBxuhzw3j;s0cu6tl^%Ztf=B*C`nudxp8d;DDaTe4L*LrYY`ZFaZ^%F&#^Sm|#Dl^YJG3 z;|HGq-cg<;$f&*YnL%BZ+biFth&m9?H);DFIp9v0fAVAWO~t(%U%as9z_T|U!Um{& zdiL9|4|yfS!o~X!GtO|}Y;=h4okBX?axyDBaOV!Vd9l~sbYR1f`Cc!5%;Tx~=6qSP z=qF18mrSCLIb7Qksa~H2`x<3@nMVl7(El%Dg%=0vrk-z;L_S&CxoM4EZwBnNkl${E z+&f}@^Fj803N#}$`N=}`_hZLbSKD&nxK>v}0}b<0nUNYPiT%jQ$QZ=>G?fqNs}9Wq zo6MBro`GbTmtDFBi3=7sDbDBVV!&wV{2;La8W@CM+7O1^#gn+i>R>Se6G6tWzY$Eh z_w1@zCni$`%FJQb<<~q z?2f6mvFK|9L61As_EB*9Rb9CzuFJH;%(bLrB-}l`a^Lc73K~kU6!v31k3GBhdOC^# zksHKiPt;GLydFMl4))^)iRK~`5?*MIgvP{Cury?M?J3l^SLOMyq)~@s^KRvZZKj}9 zt8stB8y0ltTyv^hO~Q41k2?a%OgJ;HUTlf$?%0r>bL2=K)Snm&uEL!DGhw_S1AXB~ zNtJ{29TGfi2M$?1&48J>EBQspf$vV~ODTJqkA8@4z+rp*4j%613zbjTh8JrAfPkdB7je2Ml*eITmK*9Pp zdEK!)G`QE-a5@b0R8-jdu2RhD7xN2DMHoyVy`s)dVg2XEy&C>ENPuC;s-~SrOlbVN zet7o{7OXh`W3P8I0jg!d`J zOKhKKXa7!v4C_CheL*Vs0My`Cg8?Asha|s@0E#1sC0q zkE0$6%?bZ{T#tNcb>Ta82zBt1&c};Q*&yI((;5vN5VTq!#gBXwzPx_7;Y2p1<;)Cx z*2i_+ykATnb@lbx@Pe{y6ue6Kkt~G$wZW4eI$cPB&%H?BkX9xb<~+B46O7{-+wUIn zjesJtA|6NX^GKK5KU86zt1W(}{K}RAr9~T0_(sq{Z$MRg0CO2lN`LU+D-!e%tO*bf z%>a$r{wzt%amv$5j^lhJ+;5B?;-LP_w7R>u;omiO_%3!9xuS4yK+s+<3KUB^GuC7M zZ>oA6y9n#{pvFa`&)!T(u6e<7M}N8h5%oxU)f_D8@_D*^|Eu8 z4wkn&bkh&efhb?(q=I$j@9~B426K&S#L(*9I3M}xUl}j3FPsOTzaBYAg2Up%DAs)n zi2v^kmehJ?7F$U|{o9qJr4KT|JNuyU?kYBv@C?SrXA>ZBsdLBpUj}Fd-EmrneMcA1 z3toUeK3Tk5MCK9`ZhD!F(XkGl%K2`eGNK?WeB{ru582>7J>l zj-9rl!5=HWpQUOnxEt#m`?r9EjPYkOPPa0EFr41C@Hrb|{#>YZ>L$S4?o+h`t(&8tuW6RhW&^UlKd`dM&z-pgLf0{wYwz>Nlf4s^0PB3r)EA#-OIk$sE~|Dx2b zuj0DINVXXDqt5UoPVdXX^>tfmeg8J*5uWG})s9#KavU}Ze?c8St;M)qhPl<@uh5@B zA204LM@hzL5>655G>dy$)eQVOY0GXgmuT{58^kyD50@(X_U+ zBOC5~bc!#H;{$L&k6g%@cFaO2G}!L@_t5_BNH|?&DZ*ds{XJefd+j=T8yT z)pZ(6{}mDh^j?=#)Kj3qSRufy5y!KiUpagNxis*rThBuLyUm8i@12nc(poq|DMk!P zQ1N4rPtjrWQ@Pz0Z8qp!Oqa6XLqORLS1WQF*TtaeV|O6x6)1YdV2(SouSlxjo(VjA zn+#T7$Lq%nAMEMQ1iir5(;s+mgR?wS|CT)mvJ@9zF>FKbs*Q}iU!4JFU9t4gXKYw_ zfRV~vMnc}4%V>Ts1+Oz6lwZcWRqD@fojXB*tX>2=?j~}MrLuPBRTdml=-D}ELxE$U zM)%@h*{~sAWV5U;^3|`&JZaRQ3xR3zU)-7CT;F489EY4-kiTgZeQ0<%b>7OkY*6uV zjZ8D-K&XJ)@cncWjt0~bAf=GI0=EZr#O)8T)g-0L>BPQR1btZlHi^ar~lN0162}h`pm>p_pIM# zD4al^Y~AAyI6rZgP6;P){!g5?b=vou0n8hh95!G*gPYFTkWVCJmx{l9`6?YQ|9ZLW zNEaJAl_M;SfP@2EoOT%EeVsS{R?mGNBf?j(Wh?s2&VlimIAIE=wCD7dFekdEXb;a$ zV7}&We_C^$37_;?FLY3!&;GIRQBNg+rekU^>CA+n;OVHR$XCBJ7pgdgFhH*_PdUAW z4!fu7HZM14!`Zu~!^%&Q8;4v@-BZqk^}`BxN07Vx%~p?W!~1&Gzx?P5)a|Qv3sVA7 z=V=}?w$lFyxL^A;oO`a9-K6*f5A?O5MWx56g9Nl2&R?g~%Ya*>yRVF6&Xrwco%TT% zbC7ZOE(135fLQNohiVqA<Ll&IqBpnrLx1nBVxAQB^t@)pVOF*W{o%pIO3i_;qMZaO6zS`9=D$UJB>;4|DoRMrH;8)4pb znxgAf6L3%C*>b@@3|Pnbn8JN;+MD_O-zpRHzfct(8 z(+ZEea0+Sz{r`SLKT29+_;HzU9>mWXQ1xXr7^P2l{zl$gTU%eT&n^oReScn!zn=_+ z^%4)okq`B|7C43oVLw{r>Jt~3kl^vN${?3 z(M>7LFS2V-k(v1Y9<2>D?(-y#xmryYLztU*wBI$CB3E?gKc#Wc)s(!wAoV!~E*_Hn zmV?S=Lj12)@r}m7fU_QNPSKATT z&4R4E6OltYIB&N$-YS^MhUnD%HNJWr@M4cR-9e6gY`(Rk8u`cO7D#i?PflOH>FeMiS_2BeuG!DEg$7k$J36XR-=6Px5nGi)LVSGpEWJ4c^j;{OA3~m- zOG}FB}x)*9YL<}*Crow_hGqpY&SvQ3HsRcPY->kX0_li3+}!iGfm+wS1FiF z_b=!Eexf3grzLD;!MIESiT>lc+vC@6- z9ksuVA3b}L#}%)CT5G%D z)&S%;9)UyL+}d5(^LzOM5)LXXXGQe)e)1a7zeDdObpq3uv+vtZlBgEa>J1PrdZxS<8t zUB{|iS{T>;;jE}%F^TzWcfiqCmIN3ipZuDRdVVYa(u5c0cem3#_Sv7Zq1a0L&AOe~ zFZ_xEN6=?O{f_kxU7=vCLEbnO`|FHZdfMPi3T!`kw^%R9fkTg`?H}ym09&tS!iXY4 zpd(UD(e4gyVnPx%MCG$!LRNg6V4lE^L03 zenW`~CbJvDexYwZY_^QAIZT3Y=a72UO$xk>S3lwM?Ngd)(!UtwuE)9Y!RRl0s-+5# zVZYNCZ1c>uMg7#Mzo8vX0pCgoDODU#q|c5kM=S`)TDnPQRVWiIohoEDqkj!~pFCFE zPlrp_`#+VuyaR8I10{FZu)*9yQ)`WA7Cd#`wDqM(GB7JF#=J3K@A_~0yAk%$w{F)@ zQiDu*=sdQHjl9QDXH$mfv*6(uhIK`2GB^Y8ueH7$7`vwQLc5WGzP^yMwxm1=7d!v% z@i7*tN`1&s$|68F_t2K{pA7h7!@lQ(el)TDVuKLoyL-pyOzU4UfR^QN_XTxE^x66s z!k9VX-H0T5m`|10{`%$C-XSL_i{`-Lebk;d`k3Q?9O#_WzZ9E=IwCU;l{OT^by>4lVzU z`L0Fa)B66yS>Q%?zdZivHtdQ%ZB>arb)oV?xztk3P2qo|=bcBL*B$7V!M+=sTQ1JG zk%U}piP*|8Cb)TN-Rwi&Sk`(h|0i;9zI5({ZaWiFlvFc|E@EHIC9RI0#=awfxp>O&QYO}+ zxJZC%{xltiYU|6Qg6JT8r&79UE9RrDo$iIz47ebt=9J2$fnKWfVV?sWDB8Or=Gbil z7`n>0PtP!*&`0h!AI^W_Y^}bOVQU{m~ksxP(RJyNBO->Bw*vlu9l>Q6kHZQ z6IF?M|As1STOjJjk?xW|?XQ?nceh|kCXQ#%O0SsQJq+ma|319W0(G^K5*x8%!@c;m z(Y*W=L?)j6E|5ush-}f5kvMPhLSBkbbn>9sv2LFr*2&hx+ad-XI8gWBuuz~49TLu+ zuJx9ogZtF{jBA=~IK_F?C{s^DOUKwyd~F6SN*CMKRL%zDd-s%tBlB?lsXM$r)4;^m z>EAym@=$h94BL83ps@AH76m{BmaW|d@T?EaL<>xYSw$x zRGtLqKmWw$p}z=R95Hvqet(;*@LCn;GiTfJ*hA>Ui*oed=%UW_XD1|nLH=1K6Bslp zO+nyaHPaT%n`a0K5$^jPCgv%%xn5&}q8;y00P^ZF1L?WT$hTsO&N&P8Q0L{cHrr!; znw+q2yONs*6~-<>hUmlYrK=-{McP4c+WOAqArk06{3idMp&&h1<=Qe_uloi0fA6%T zznrO9ovxM%4GHl#gzmE;>EW}n#cm{A-PakoI2m)tzJrEe&|kLJUZU&!Qm`jJu||3% z8!m4;Av$WwfsSjey?I>(D0V!zH%Vkd2fzs^p`FhWeZ1f3ZA)2(nj&V zMDBlBEdPRnaq@V^rq9`Mk9GizEjUmjuV^)RlYsn1!@jrXQ?TSN=M49G$YmD&9>x;* z@8x_^hT$|gEOqSHs$(3GH`Oj>Vc)GuXHNXbN5MVsj(2PD`+ur0aJrGhzZB;5+(N!} z?b1844t+31@#VLL9mwI6_9`{^m|*p5v3|^D7V6DPfj93-?0-$;`w1B^rcLMR!u-Wk z5N^?YC<|7rgocwxlEGA|pxMNa1DZ6-+V?f~b57a@b8R}X*w>EM>agKIn=y-+k92U( zSpQcI^K7!qg3fs+Y`A~c`Si8HiBzT)TEd#}`wcVK?8 zTs8D4oCQaGm3#zFlkk&oE&USmRau?#s;^i-QD=%aseR4@Ro?aD)h-0IxwuGeK|K$* zIwZsiCLp2n=h5DiO!(*fR(vz++nc{aI!-Qmu;ps2_PHS%$iA~G&BeYTKa4G$xt<4Y za_4i8R?{Hkkv{*uqZ|k_{OV_IiCmO(qJ8;uCTQ?fP7Y(8|E+U89q640pDOB9s{Ya7 zn_fcfRTmDtvlcI@>c)Cb*Nkb8L@s^4px`FzHt#m(Dn(TiGVi=ObSwhvztU@`8tTbJ zl{HOF4eLNWWF?p9XC7J$m~+pmQ2VMCkNHdfL=rs<>z^k0bCE0ZiCRFS#VzD&vFzX1 zH+(}qh!%Nx1N)`@Riot9b^`oeW1E8mDVVl;KEd6mpFboYZiietanVt}lcYfE?UuXT zeZhGjTdpXTASbls(-);M;rGX)P3yS(T9ASU=(yc>}Vg z&_}lF>Q`UKe5^3B$`t2+8UL>Zji^^gx7z%>j&G6(o!)<?b0GcXoKLdD(Ky57_b_!;`)^13QE ze7Lf!dD||$zH2#sE%tkE+mqld>?7N4>5-HJ2~ID1`uF-#U~W>cR)&0=sCdVO#$Wb>9 z!;fbWaKpggm6V}?c{$`#MH}XhFQ#t%e+OtYNNdY8?N4eSYCP zYQjLiTnFb}pZMG#}?-3*q{Wm?FSCu1@1?7wX>8z{~{v ze!yCJfle0^X5Th^)4{xdJ>bSnhk-9z7uwVF$Gb~>kknke&X^R%-9%(Z z&o%!#ng@#v?n>?F&4sE|!Rf@q9H8$Kb68hJhx8{a6uvE`gIDA3#ES-Oc+V@RsG`7t zC;J4;S6IC>?!MYCkvD9tllj-4DWps>K#KSE?u+<& z#g0T_h36!MIV^o{&CG!Q+zorwF^@lb;ys*<UvUlL3&VY=SHH%~GA##~a8Ix6tr_al zxtrBB@Pz;&yCW+Hw^7h{-&bc0uODwSx;<_l3Ec+uZoG07?A`8jjUU%N@mz|6hX)C} zBxZsiW1S>HaAy(sxrkPgwO`&5;NYrd#m;5IS<}_IgQ%;CWzKb#TPWz+($|&{O@rA@ zje*o|4(y%egv4*cymoo(=f7A-7E7)(`(9$+QOkW&dLDE1z}Ju2hndhm{P`O9{qMVE zP6lYT5O8(tvsntcuHb;&a$X$I&AFpx!&uKBEL-c^urAb}R;zY;vEbj(;s(v-=u;0f zUY$jsvY&5KSc=y_Z?a9DyU)Gs(y1Z=3=X9SOhQ?hfpqadrCX-G8!SEONx) z-Zl>WUbDXY6zad!_c)){SSF-e$vc>%UvCQhdUh7Md}B+FQo8<0< zNr6m|>9S8XT&eQx8_W_NxT1*w%b%23OKPPZd|T{xcaOT69QCg6BnZa))5 zzM5awvLU|-bt$c>zx67UdtOv&JL;kS{g%xQw@Dzwz0E2yPtB!W{I&q~aM0jXzkeli z+S22K7P#(tbB})tqu$mF#WCtcNch7m-XtDQ!H$5V4~I|(H28LI8W$qr#(4E>2J+Q` zbBm07u&<{CHV+QS5wPd{MO_B^zT=If*%r9&3k526&O4b0DoicSWtBAW=DaAWN6wes z`T4gGUgvz^(KvPVeFd+AlTPUGmsgcMjLFS_B?Wc!sQan#`=;WdbmXY*vmei2m&t-t zS2Uw_`jWxk?qcUj?(c;3EOK2R0YCrvCEi|%`KZY~aS`^N;WP8}QS9qAb9xtdVckYY z9VlCeoTD7R@LwS2W!=X-JR?|FW^lmc7S8kYta1C%2Lw=NN$L}r*JK+u%B3Q=EVvt_ zB`izA+sT`|hjuc7XfB){OF%sjJ9AD#X*U<+;6vU5u#eLtzH{tIMJ4iVAO6mPd)D5X=xabnRzAlIH67 zn%Jk#SNLBq!t2PpE~D9FuIa8Yw_S_<_4|~*wv81De*dII2dkM7qG{L>9L9pi<1&vV zQMb1ZjhRhfHU<%3$A0QP?r{EE}t!RF0@`tKrZ#C18)#((>Db}#0sM{Dvd zTbZEWcAvjLGhY1ZdeSQU|=5Fc1P7+~=ihuDkrQ;77hH;H^+hV}h8hiNfzVOS5CiPC!l{! zum88moIwMNgAEFvwj5Y<#WT8i69p;`@%M8ia=_YU`0UhH4y^uEkZ*Jl^V*#A??-F~ zNbu%gWcRSZ=Vm$G{2l@Sof7qvlcnH8_|0Q~kc(z6)OlY#NP($Slj!wi8l=o|qPmfv z|IS4PD1{Sn@}avmuLuPxRws2-P~U>)lH|h!GGRfunRSPG8g%RZ9eacQ=qsLf*b&#a zCR)d2De~$J+v&tr^qn=Dx8{rl3QdElDl@>A#>3*?uCU-YIEVCbMSuJ6Hw`0mmrQRvql2B%ftO%kw- z8j{{|6?2-O51S>vmh;y|@MQj_nGm3#eCve5I~8J|Pd3jjOL$sUx%;w5o>%_$dV)H&0VTx!~QsRQybO>97WD=+4P-|M22 z-m~C;P)h>@6aWAK2mk;8Api??=FO}o0s#0P0{{;I6aa2-UuJJ+Ut@1}b1rUhc>w?r z0QepQ000000IVhg000000G!u(I8<-k`0+s!vXd?QPGnEgeMeuBkkV!kkx(QGiI9?| z&6-k4l1h>#>ls`2UG~Vn%f649$M3qH`#k^u=9+(A^Zx71%(>6!6J>nf$i$3_aGP*f z>WafHdk-m1VJR&~4XFddQjTsOo*uS0Y}`DqIQ+lQPuRNNa@hI&mXoc!!;YnuHB=5C z5LVfF%N!8CC;b2MVt8*|zM&0=K}O$)0!zCrY~gtHh05A8+%FM}~=z0dU)Fsn9I?6^M^jN(ZHAA8cjOL<@vQjaZP3Do z*>jh1Kpwqw19qN^;K#$=FH@byF=U}vzI)A9IH5;*#q39w1Ppa#ih{k4;p}fPq7lEY ztw;t#ZzwjeM4GT=%qwuxw->i()j|2>t}QVAedejRKMC*1j~6nZ+p?2EgK1i@xu`PS zpVnWNaArT;&&$yFaE6hHd{y>ZfVZJ2eCGG6u;LLt5q0Df($~zpxYxkN!N@;Z@yd`u zV`P_LAP6N#-9p{I(G!tl!X%~wW@RAX=XI;m&|O5-k@v>NU)gY60ZZ?$2{Zqqf(M_i z-6DlIVYi!vTW`_)0mvW5&n#yzZUeTO8$WmzD0oNCsJ8LnDki|g9ZCr%$JAig?pIaG z`(@#2ZT^klksL(i1-eexBWD$13#JlyMv0w>Ix;SE>WGL1~XGX*>m^{ zLGHat`e&QCaG&en)T-F63J0;$${IBpBI?LaQkhk$Zt76gO8bq5HW?ftlmt&C)MC`G z^V+`E9k|(ez8q^*CV|?c8 zwpbOevQ;2J(f-@JH47+sN50^4Jg{q(0+bVKBz<-bfz_3dZ}f`3VEg%~ZiKKF;||nG z>9~_J2C94`j6lX1-jTnL^fVUknE;-3VY{UFk%8@(UmQv9@mT6-|6Y2=THFC8_nS

keQK!(@FH}Yh_KX_^*TyF$awYq&2ivEmAH`ITUzf_7F1EmissnZ}~>zP-4 z(G1>^i%Ea{dxYme*`ax}bw)nO^W9~kFfJP;wbifMTwDamrKtxOKidjJ^MU z{`Iyk6>I}3#@MvOu_7?_LzKYk*A|Rd&-U)m`eA?^>GUcpIhF%ve;$3rkeQ2jWa*W| zUwt$fA?M=Ck4+K{Ph^4y0 zZSd{cy3ph{Cnfo925s_<24@wkS6=D0ssT+gZ`-rF`!(~aTU&U0A zHO}#`p7AJPOc!+JwaUOw{V1j>zgmi$b7p_|&ABO%t(q&=O# zWdI~MENgvTti^htri^)Fzj3q6FbL#E&w$Xgnl^v-&*L4L>v-`*_2MEp*Oqqq-a9hr zy)57R{zC*N{2aT--(87&pXEPR4s$Z#xtv;ak+O|<pmwOoV@gZ}+6pGl zvpW63?0W*(n$;%&GXGyp*8dDAlj?pv7R9{UmQ1@5o=yvpj#9I|B^l(t2+vk%1P$d+2@jGfdbJq(-GXJO8hlqjwhEAKm$-HX zT5-V1lg)fvG0k{K{yQ$Xa{es`%yC>hcjdofARH1Frpl0oQBluVrFEC$PC2k0vi*1x zu+ho7%6CrU9eLm>O+5M1G!T21Y5nB08npdmxhUf!3~LxH@11hnhnwm7<@OvJ6J`&r3ud znbB(HZ_ouA_(7=f6x$Oqs9HjM=Kkk(AbI6QuXV!!K%QPv!>*^YLzn5VR}QduW2htZ z-8;x;mPQBbtM|HzHVD8?voK-qgCrnYbNhVO#$OEibniEZ1L3St+@#ZJP$nNk9XVto zs0Jo>0vU8{+dx4cEm{}*)^jMw@eGg_wLgvpr7#G=|s;I-jSoO=3Gkh zp8;~t*PNe=3PZCyJ~^H9AFKLPSx8Y8pE(`@jJfJQjOr~3ePWX?8T^$@XL z(AmTH)Oy@72!L%$X_C?8u7;^B_a}xpe>`-m5m4@p?8HPHt$Y%4El-V8-Y9K!U zbc+m<4%UrKn7sj4TBw+Ob1QM53B9AHXhH=ItJ~}gmaH<~cjVT}+IT$~a@O3nv6+!GwehWU_8NQ5FVAkZMCgOoqRT`E4bbr;KRANiCByj<4D|7a6 zDjyB;v|eLf_2SS!`$*!EUQtbl;btx#VIF?Wh4WZ_b1?wjBDEDX64&!jSQqAlTh*e1 z&mC&deb_NE6`ybG{e$J~-u5XhKlZiqb$6%8*rv7fV53Aq5at9rZjD})d8k<0mg={m z`ZkH2SNSw47b=GzO+W=-9I$d~DXutPFHCp(=@m1Hn|w;ENq;43EFEC^bXmr^@ff4W zlAv-}JmMUlcF~jV8_J3I%aX+c{Lc0G$J$-8zcBcGo2={U?hk(s*(CCixiZ0 zw*6(U<2%z*O47nN!*Zq>n3A6~{6^XIVrw~(Qm^TeUZJ$bAYk#)dr)2p*pwXGLP6_u z-6OyUkCLmuG}oih=Xsp!=Jhf`8qVa^XONbUVDG?4T$9{E?L8@ULzl4H1rPOzD$d~j z_fGew1CZSzYh(dn$eZC4d$yd#%NuJa{$U*+x$~Cw$d^IG%HPMrILOp~qsRxvG=E|h zo*%7hvguIH1eWP>{dBR*os=}334WM%9hgqIAE>vwrFGHKb7a+aD_R6(&Xaahk}?S6 zo(W8&$k5(@!d1NP^-!|objJ_qqZ#fF^({4k8lA#j^WT)m3i49N=3k+420&Vm12!&o zU72JwGmnWws=rf$$L7;%@(N!5ZCZ}BF@nRC4$qC$GyA0+*H5Bi?r@L2@jDG`Tz|)^8&cXc#*VZX_TK%8V3r2^3OxkY~^NS9Tt^Bkn{1u-i zR9-&@>~(gyiIj#)kwWVr78ky#iiy%!R)TDnCrnRp!0x2XTmvtWT~PN5#88YhmP7WM zW1Zd6?GW=MOR8BJTq4Xj(B)WU?84ud4S!>43OmZ?Ziu2uJ$#e57selm zXS6Asd75+TClyu9QC`uA^)T;B6U6mm5D@1j*UF>xL@um)?7yP#A3qv;p6QM)Ru zX%fZkfUN}9hIT|9lj60{#R@s~m$=tdQ2>wgjE3j)Qt4>5Jz zIP#LcM6dFS2^zGm1(wB5`q%NcJ!e8&5uz0A(O`TWw~4**kvR0x*Wn5me#^5@7UZSh zD}*@MPz?{*&*d%Vgy=C#&QjU?5_KZIrff9}#d_@V=3+K~!KUrINwVc?m@uye$5dKh zJrGp#(%3Z()Dk~1%<#{6r7%17mu%;RPk-J>(28zCT#p0puowo9?sgqAxr&M( z`Iy{WpjM=)H)*OU6pdl%wAaASb4d#MDR8YTn=>jc&G2|)Sor?rY*DK0aT+cNLW{v# zJN_4`AhqY;ofW~{XnHx~E?p>r3=On9?rlHj?q|W9Zx<*XmOfB+tqywedCNbmMiRQa zn~z~f)opjeaOtq)KWrb8lktGsHgAGmVCvCl@Z@Mncfa9+tbbV^QgKW&^YD&ROl2C6GAyBTxIBQc{cN~ zzZ)a>fJsZ>sJ;+eeZeQ@pWcOk z{&yU*%D+v7@{)UpScljA=i!(DXJL}FADpGR(-CdQOO^x&&)bW{p9oEy3ryA&?|VrY zyd4g~?plRDK@R4p9Tj^7s7gnnt3QwZWXn$c*DcKDczW(rcy$HU{n?8Q2^Am4P?M0P zYptSKo-&5X8N16oX;7{{!6bi$F~U~@$|lPjHG?wb0@GJ+VE~2gM^toeDvEB-*-5tk z(U7uCwOgvqQhj~|KE6z_o-0oNz9D#-UK94wnXGZJli}4TtsFFL5Dv_b+oyD4 z{vsPTS_}5IFL`L{wNFUbHopDs7ow>C`dQI>u5EVq6h6p5;pdT2{qO-k)zh4{J?fEY zd{sYNGc_kn23D7y8d|hu`uaG$xu1I8%4+S@ThQN-r*a>Cx4Y%lNtr8 z;8jtFIr1~t)kyY$sH5adtc^dVUIEw>W?uBhW!9YZ9J!i)>bO1H@4AyzA_tDXTG2t5J z<#mwa3?#;RVL#LcC+vav=(@@-y~6|x9=)A}pB{Hc&nu2RFuy|*`L1GJ{cc|fm$jx2 z;^l9Gh?nlt68h2=Y8*LSQs#Q43q_{#ZtFE&a7ka!SV4 zNk}a-!snHr18~x2T?=Ccr2hM>N;6!#Br*v=)PK?)F742hUU9O2*t#l|r&7d{EWSr2LGFx&*-3!rTdQLeL9%wYX-w;>C$^PKEXx!dG-O7s#XZowY zxOXKpEZ`nx1|Xm3FUhp@#Yo2glBN|$-3UuNEpd4B-haNCcX!@X*5kJ%7;nzw6lA-m zULR&~umVt1#vyB}r&kK{+P30_mJ}6YA!F+5wIG)*NB99|;sbl@^ZWN5+9yk>?`pE( zo9&E2!E5|FQD)*GwcZn6H@3H49#7YWczTr;)ZG?J{?C4ueKB1XNJ!T-(BW6_Lp^8a zos@#uK0KpEi9!A^O|+D$2y6vkm4n>0pzoD47DjVsk>bsG-`BngG{APtt#ZM70ARMQ zYd-Y-VEWx(VpdsLGZkV0foN*w+qbkI1Z!^Abv+R2hum(@ZEHsBtb7U%tNsiM5D`38w4HA&Z5O*gJRgu#SAvwnT+*sz+ph0kgaSZ`p@YhID~9A4u$DI zl+pG^$I0H9s<+`CrtRKWXBf5So*(eKo~FUno52@E)qL9}UXd=^3oY3ZjlX{a!%TM5y6uu9KsFgw*5`F2>5muV<=z+lU4J2Mv@2oRR zGlUD8W~SdJ-S+TjF`8*7(N9~4p%SU-hoHDOBbiuT7Jiz)GYDng)&cE`(Y<0RFm*Lt z#M=KFx5bQ~jRJ-Ie)&JJA;A~cgbYG6rhCf7y4Saj(|6%^w;wRjURmS)@|Mk*B~=>g ztckD;pfGNAHMAnK%*=$DWVXUZTT|F2ek$2sIgaydAlv!jM!I_;K6~OL+Z_wW|Lmg9 zGowm_)UsE6b@h9P{*rYmT|CwwP;e5z+4G_qWkB+>cDHixe}l{pF%oJ?VPrE4SJN^J z5pWU($5|S9H^UlouEVmLfAy4EL`XD!OzJ>^8dDi`t?R#(m_%A3Dfv!Z+E+Tp2ZeGaO4<6wmr=5v<$S(AePPn}HqbxnAG zQx%x9aaK_}MKI+9hq?lmlU=)dot1uF{WCj^^hw^PNc|i6Pl?WF=$&8nHMr4@MT`x9Ig_L@G$>U z@sgj=9lhm6GVpg#WQ8CaS^G!>WB@%(}^_--)2PfUTg~)zh^xB&K*L_mum`?Uy3}u-T#>Sh<7qN zYkSflU_t!YBEFP>>Uj9!jxhmH1=Sf{{~Rv~$eoLMmdwOlNJlL9aN7c8k3xOp(N_*g zRo74P|HkP6cadAS0;WNcqqU`HE9FTP@e(=8-FVKi55&{0u>9p?DEpen>FvmXBM)~} z#IEiO0BEQBkP_4c)Z?9$!5t0h0$G1}3OL6x!o!43T@Ow9oDXZ%1qrLl#Nf-Iq+cBC zfx`2dqTq0dCJCkyj&*-nrxOd$E_N?$MSQ8Mc|E#x5xlVTFdBG*#5^i+;nvpyj2f?} zgQ3WzDEoNhM6Z)f99UoOBwoSuyclAZ>R%^jW&KsU^^9rqzajV?_0ck(#QFqX_8zV^ zYyM_$c8uS;_ga}e`cZc5W`Bdex8nedUr6wW>;IDN!dsbu%q59^81suqP?p&kxS+YT zizI+5n<&OD{4~oPkV!-}8wwk4#;oDd0a0(a=sNr~p|@34XBkPitHE zP7xJ{9D;jZtggd5=S-hS@UOi{M8e2lE?9_^HMT<|0?yx=$uj__MlT|^!$tbscp-Gi z--rwUtG!GF!;_|I&eNvt_wFCt&HoVcV)1Bue=?7hE4`}&{}U&&eU3^`K{(3oAJ-ru zn_9}yWA*px4a@iZ@*WFb+>2Dss+b1@jV({Nlk5@w|CY3DNoajXuChK#oeM{8_i1_z z8LxGFNJ#CPm-DnqWKImPjRyI{p4)8U<;$s6J7G#dE=e1JcD0uyB=a0_Vv_DbBZ6_2 znD=2j^RMr9x&2Okp@k7Diuq?Z&@V%NIMEUi*R%T=C9AU3wyu#5w*C~6*N%H64M>;b zH7Nco@+UBg$h=!Pwf#5^DrlwTK2PjZrIB9(Vu?6g~97&5_~+|XPs=} zjx3(3M4ug>yLInpF}O4Qqd;fegEASgE#zDK)5e-pM-9sJt8L2NPOV zKyu6!?O=mtp(Z&?K17az2~uwa>0}YV%HQ+3L*!BkC1em(orR;LmY2wNXs#I_Bbad7 z504N+f64Kd^m6|>+zTD(RYK}T_r$fQqfnx8GKKdP|Z2U*QuD1@{f2ALQ z7xcLUBbm{3{`c|tb?|g?vCB;MODCI+xbd+!vYNe~-*CPYTU&Ke>xRD^F2KuDOJZ+* z9rIFmXm&ODSW7@_5Sq7ODTJ8oU8*dZr^^Gi8E-6Y6B-W{m-tpiJ2hk}feCY|drMY^ z4x`WLfl^Iv_52Vhix(e_g4%5IgYl%NO}~2uv7U+Nwt)@iHX*#K{ZDz!mT8W1d=D_V z+X11xrT22ZlnKFHp37V42R_WQ;{|eEHR5E?q4(Uv+EnXtdTy@LMJ|L)rX|IKbjek$ zuWka(Vi%b7=fVNe2iQ}zb*wz0ZzU~KS~>goygYMX*Rx2^f%Z7*<=2*rzw0?7os`i_ zzR`wbco6y~dix`2F%X91wk2(CEz4o;gQfB>h)%rt-B+fXxiE(VMphr1xd31;hA{|B z8N-e@%qjSlO9F>UUh&IjX0A5rhh+p;P;M(TCvb&bCn@w9t`$L{JRq#w72ss;BhdCr zc=`uO6GIZ@3cPALH)3|&KE)3U#wi9eRbpxsa@NCoZpI_C`ux6(ecgcsOXpnKZ#}={ zuI;(8r`2`U%glK|gM41@rR$IR!n4etFB=zddH4oEJo8N@n3BX#*e%I*Ll+L{KCPcl zr?Qu+3Y6y6BOQVd6U1jWH?z#0qiO(Z24lL@9@rwR@!eY}>kAG|pf9eO#9!Pa>Cpu{Y`0Q|0TiWyaL%gnF$K91eW6$F_NP{T zSa-kRiRV#iS83+n4nEwspf;WeJOycQt6xBaC;-sBOrK&SE+o6)ln~AG>KI9}GJ;RE zSN{FpmfhL5H%!A*aw})J#hEZlp(6q6`q_hmE?Y5#S_6wE5UvkO_ZA{JkBonH0&b$v z2Z`Jdr#(2Z5?JfTXyfzw6xOxVeX;tbq=?%pRmi2Ce4r}>_&;1P?O4<7j~84LCWlC7 zotTDmm1QUv+2#*C~Oh0*z_Mc_D;}WDx812{T|Apz_wW;v4tMk_csnV zN+18{=*#^SpCA^!49q^a)T#S@ikxa3fei0-|Ltb$sx^ z+8PKTXCKl357MSq<9Hszs0_4zCI5?{1Ert4z|lBU-kT(xhQ0aM1Hv4OKG-H?iH1+O zId5;ZE7HS!g~}}Dmn0Rs7&_*5G$D+GTxWsz%%<7uPX66awR9^zZ>x-^p+YdU`-cKo zwGyB#ZGc}EAS&pU-5b;myi7lVs$(x}5ZYmrh6Jsm0z$jUy6J5`*LA3S;$r#D^1w6Q1ZdlAsCDdKwHnnCZ zPj*Lan7YULO(7;^ElS3Dgc|R<+#FYH%B%_qo%E2yR%&6|#^%npx-SmHg4cxWAptqU zRuQ+Lr^@a56Q>_WQ9+5ZY?aG=mXfvm!|QaIb82;!$f8qjauu5LSSm887?y?B!cLzI zv$gq-pOcaGU6-s7Swc;Tm1ml76p0<~(PoaZN#lcHPcPz{z+;{=IU>omJ~Rg zJ_~r7s0ZaasHq~}le=?NPWi!-`G_p5&ak5gxvYevP<#vm!;Xm1Vb#~t41u1WQmFat zevz9~W%awhNgJd-nJ4@W{sNzzq(&u~`LciO1>=KI&r`*%B=ZAZ4jsVE$ z_I2Nt)ui-D3Re_kIz;en%_4}!9VhLd`kH711)xknHTn(D-$aTt*+> zOkYf^IWy+NUZh6x8N&E5tc@fV)tH(_iMx?CgFtcJMrtAFf zjP8s8X4GfHOCXhKCsY^bC0XG%`YQJIT0*O6K<5h{sl)3?PUl zKog{IOcn#-U5+K(axm(BVgiMjvSRCAbz-U#aslgGZ zLbzNrCc`;EnrIjPJ8_;-3jHbI0`s(#_Uey=*KX+TSEr1<8Yhc8)Kmk}6_)a@Fk~1w zIko7?@Fpk-+Cv>RbojqqSrB^kcVbR_%wEmRR0#HwzVRc5+i?)oO{L4Ze%5avP%p4! z$AF-0kdmnjrUuMBl$pH)^?e>?fvdNu>n)zkU$mdxxJ8FqV2TOxr?hrcdcG6|JP^Zn z+Jif2?h=AM_Cm+jm{b;FMh^(tv9W|9P_uoXE=ARlUmPV@wd%_dJ-&llSO0458ZV8I zb#cZ3nyaEFZlho^AIdyxPETPv19HnpvF}g*)kp(f>t?~fg0S&M6I1T0_f8U|eaXFA zx@`dMCdbOU%}z6U|5bJ{lkLa4*KR$8+`wk{QqOzqOa~w@1Ip7T?=%?mC_!!Y04r7i zd42t20$t&8x|NMpZ17LhFhM5sgv zv*XwBzQAoT-fd2+VHpop7^PRVxhT z_6i}xV;N74GF<{R$tMgZ9xPp$^74TyaO()$9)zwyEN@oU<(J-|{O}6!RjmHYV~!r- zH(I>T@dN%J#(3H_oM9l(8^mav`DMb#QkVw=NWbNNcG%w%&$XmTYMwHdX0yLDw6b7h z*k4ka4qFN43w)08UE?vDguJZ(+!3TC88jgn+Mx3!du;i_Pp@E)>t2~( zFyn{igXI-3?0af56U)IP%O+KFV0eolT>uWA3A-FbpjAR#Q+#S%8-e%JEzQ754louW zf*PSlT!iFE++I{;sb}j{aW_3)^#I1NR8Ug5^dX>_D<`wSC{o?L5d#F)oMtQZ?{^KDj={qbco)%570R z-vQ*!;*ft-F%pNuQY5L>nv5{$26GD z!QrUP#sPaPU6j54T5=hy-=VqS;OR~9z24p8$sjM#2ioYLfzJuMVF-SDr6_T00FTe# z69l^uF>l2O^f!ATv9ttJBS1t6{ZeD~(}V7h^1r9vS(n*iC%vcrz?IL%j zpd~q>5Kdz4Yh6yysl=9!_c!SiG2m84LXK?EBW=(_SX$jtAp&4soMbVSCFQ_S zn;mbj3%unCw%`2e-nFXK{)mZdHO9EWY9_E95`1_`3|)G4#s$Q3-}ADZY_BaCvW6cK zpCi$NQ#QgK!ErEMkHw~t|`u#X@#TJqPE$+$}%K;23*6n4ZOaOOzbaK zfzZ_odbuka?J)Hxx8s9?GHm9XpqgCVXg=e|)!n78rH0GcECc7B3CALo+tKkHY#T~w z`mUuepU3N3B^6c_DPcV)LIWNw#T6OI%AiHy0FhB3*;=U(04kJ+#JpOcaO6g~^!~jR zWVfbzR;2~r9O%)5yzVNn`9Q|z4OHx>eb2Hb1QuFkQg?qpH>~dhew^H>U|0s1lYwF{ z(K>Tg7D-To3n=$bb{uE;ub`~pNIc1N_D;$*PrkTiwHWB&9d`K$dqi|s)6pm954Zxu z$2hY38n}n-#7H>NdzC)zcAkb#1t8Hz+J#bA@q;4d(ZSl}QX89NKv%rERpbofFo-dO zSiKdOA*3ik)=8{sNX*4%O5&T-R*?^W!|HTq?D+oo@7cL_QO$*^Bi8^tWpzs*j$g3e zz3JEI%f|yNqL#iF4($is$^dclc&aUed~t(>4A;WhU;P*t=;a-amvS|N2*5; zThq(mLqK+nKTMt4p4SRu-i+wxMIH|7@UuE`w}wdv4ndFQbkpv8b^9Ud!{)cVo+i2( zst$nI8*&?@OL1f3*(PcuJhQ|6Sh<_)R^2xf*Qpqo>epx`j(z3be|A9Ri#BXaQ4tRF z*h^_4$Lzl4G-j9_qgzcu%PCaxEq$sW!UlXuYQuE+Q32K;+#Y2}eRC;uUtw1gL`*$jVe6_NyAJGX8iuy+R~WzfpJSChT|3%%D4uzkzjGinS_~1BQ}rQ z;3&EumRD+K8d37j;prE@Uo$l?B<8_)v%C`PRowlQ8LCR zktU@&NVBPct|i-UXpaK>rQ`cuJ>&fA&Yqolz^peqxQedYSchxo@Ho5oql9LlI3N2k z4YY6ESiTQN8_1B4Ju{G1_(g zG&(vEDLcB-bV`H zbCla<%DV`(QtUr+7{?a(czLuFzW8_ZiHfAb%@U6H_})VLxU7Jd{# zystOyDS9DdnJ4ncK~?QnL4a;U_^S6oJMk7m3-zgYke5>+2oM zSoEFm+nPb*dk)MA+`C&A>$xY&dmdZgnABJD-E8XPg>A+z=fwTc{P*L4Tp# ztFvewkMV;;i`oRRF`E<{GbUCVjFUPhO}B4(dV}5eaB_t=_*qMT8%`$gG<*Je6QECn z$ehu})g8wIo*+YHh%~xL-K&4Fm&Zen_%n9v?duuChydva@xcXnSlHri?#N+#+I4o? zmr6bf@SHfx4wP)N*tpG~R|~JkVxi=csjG8;R`zj7+>DCCw>wu1?e{f_Au1~y*fu7R z1L-t}uWD*%`+32`cKQrs9&lm-wMWV3_lQhnOFI}19-J2y9uxTYotrB)Nt%ln7g-a4 zY7ocIpIz||Z;nYoh+Wkjq;+uWn^TOaptNur@fN8FO3^~R|Ky}9K9QMGWuICGjDohD zp0`Ix3Z-MT?T?Yy7coc0UqL@^^q8(JHKX3mNgO16559!lVgK}}pZi$x1p+DXr0D|g z8@X^w*l50Z%w!>mx${CFi+qzW7{x&-3p?Ew*J*lUSr99qEa18B)h=U+=Dlw&8iimB z1GqLUS3ZYN{l1ArkZG^YCmMOs*_ePxAK`Za=;lTbra`>yLm}{leDyGI8E@_FtR_db z1b#?=Q*)<;XM>n*(+s|I;x&YL58U^L^2avLh&a*$&GijHpUvl7OzHeX6+aNb^1xQW z*GXQYXic{QBXj>6^{Qag7cct$^CGg!Dk21Ku0>JUx=&fAn~qbB(y{?^v1SDW&XR76 zU}~|%@k>)$YTE6hN|++Z`)^It`A;h46RcHGQvi@&e71x2_B$LSi&@YS)RM>c?p%1^ zf3rjHxF(A!pvWP3cyIdKuLtHgj_%&d7_SCYW+Xr1RHps`qyTo`y9fptI&wnx?qrQP z*hVF_3;z??QNt~w*|}Ay4FURg3rj%1(fs8tjBYOnHDXp09EVyyU};dZi&7%B&7Ci; zqlU!;g07RJ(bOzgW_0nhh^r$4qGpl!@`tqYgf5)*K*+^B_py&E101##DmEUwlLXBLpj9|L#pOn@BaN zU(|7*iXRM!(so4xm98Brhy>glOF!~4LR?5t(+^%xw|WIktfxz`$ZiY~$Eb76Lnex$P@{5Qui-a~AT3+j|)0^ida#fc%tpR!7&Ns>t`3>s<2g3@cpV z+Gta^8u7qk_9a_d^^pyd$FO}~sA(nY$pK3jS_Te+Lvv5I!chT|EAsVkr6ml|!X%9b zv|M&d^X}^kx^yW|E{}^4K2PbZET3=S(KckFv}p8#3+q{MN{=)qh^VP$fJG4dWwJ%> zIb!Ry(@IGs+(qmj#^1EyR@5mp(%IkA8Bwyk&aInlG6#!>e%7PW7H*eV=Ve~Wiu;De ziP5swk@XO-6}aLd-Jg-v=iJvae!30OPm9El-E2tlb0m>o;3m@u^&YqqMv@1UQpz|r)6|?#90T)|-ch`( zQh9p+q75YKs?wAQh1bFiJ(pFG<`smxXy5Ur$O1r6_7O>Vz#M7&=Nc}qq@F*D7gRx?Dxm3Tx2DH82^I4-F+mh!&k+9yYxVe zi@~pIc~|}F%+Dv8KqQpi2Q*54hg0&ya6WE3B*7Wn_Yi0Tkhf33OeFu-UVQgKB6l$P z#PyRh&Xa3@s2>`F(p=w z$!BL`k)ZU@dyW<%OA@ygnQyYVm9ZFeBswVvMq!OVKl!5&WkL$*#AaxS0+LaQrzn7ulvwrn+ba=j6Hdu<M~9tHHz z4qDf1+5d_KdSxag^U%!!!_n-T*(_N#awI%bnHK@}c3ZWQ^{O98YR_vILj;UXtxdA} z*J~mg0ADV}Kck~t8M%ql8e{B-leQe2Ju-GJqh`(5{J2!YB7O?_J~%tJwPOl>BEBC_ zb_PD6|Be&6Lk|avdTwP#01zoX;5Glp2O6)9mev^$$Z6iqVezU=ZdDB2TYcHycmK~Z zJr%jY%HYlq_X>CzE74a8nOc0J^?H@s8ZipCQT?pn8c=1^s@+=JTl4P?Bf<3l2_D48 zPUgpQR8h|Ki7#)OVOoUuvpQUe{Tsq&GL%hi&a?xNa5%6yUmqybHVVW5ji~-aY-(S} zmiuv}g3=6ZEske?n40#x6FEG@ph$xW7ouL*_kHKV>WrQ5#ky^+`2VyZHu4m4M*pMRlH^DoQusz~ zS&QG^?NNZ$@^2NP_%#Vdx&9@vVDIT$C#56k>ECmn1(NTMK^u=tE^^K>ic*3PVeQnC zdYNmraBEcwG#cZ+Jrw0jw4WJk%VjLnH)6pYH-ADqlA2`9)a@{GSe}=vO(`h2({|G? z8F`3wOJh2+%al)9!cW!$(ehaU1F%YPMGJF(k8t>_-kj)%E!Ny>m8Gf`B#ivLF#UTW z%EwwOj<*IxL-tS#_d2)n+VkG?PWtCUFz4hU;Pp}5GRe7eoQ7i@)!9H6L0U!Ck%56K zNg}_HoSK3GB_SO{6$8J<3@qI6U^w>4>dn`&W#;br&8tTkpW;J^ceqpT@W?*eL)_mrp%B0y4S$J0YfZZl zw4NG(?^`vYT*{6L-MLgDt+1O0<~uRTK9Irn<7J0oi%(|h(SwG7{z=Fj5Q)qGD}H+$ zLMb4Yu2M6==j%BThKnz`d8l0>MNT*JCvPl?Mq^RfNTf`JgFG2^2`?V&V0{SAUsjmv zGe+QR>d7?~T?)>A7`<}Ew}l$@t`1d?KoHRenJVLwzN6&Do_QIaNjMM@-d?uiwcH7z zgbK&tfcBs9=GtfizSgwDc?3R17ZFF`Z4pg7{12Z z%H5~h&$e0$cRuG0PXZr@e=e~#uOi)?-h*4-D(+DLuDuwYnORvJ2o1(xIWdw0PE;%X z8NK$xw$IhTocyo|>2gF}V1(ZHDjvwR(e`n_U(h*woS#au|KteB@OEJ9kz>)yc=ao()Z6c_MkG$zL^edd z-3Bfqp97Ku2@S{2SXbmiyPsX1_pR3fHf8JAMM{FU5;!|qvdNA=BAu)L8S~;p zDz_=7;akumE(a}eio}0RSf^^4v5~*FeZfdk`9QGMc^9dH40l zytOmOswr05B2JGi+dW~7m369S0bA?|YkVg#DD*igf|zt(zcDp+^_OmT-jEkKWk$r; zDUY)=GA0Lhy_|2bTpF9fdRm|+DIS!HC9L@guDnFfHhmZ&9YWkk@E7&RDCv$5O^v7j2t0JX!G;F3D~0Kvlil^=6Er**c9p>=4(1 z%{!2_ABX5);80B$^!&4_#ME%7DEW!^wU^t@Ew>NbAvj!}zMfn@p`aJ5JZ{wcLW4)o zBDJvO_vw4Lo-Uc668yKuU(HT+QlNgdEPl+L2g-rcMWcKCp%Qz4Gx|8oPjCSnXtC^- zY8NL%4%Xb{%p{O6=M~yO6-_ow*P|Eco9pWk>ELFUuLPv93Y+6y)9BKDg4cCSP5Te< z)@0V#cKesK8l!nhn|?i-MDH$nPx=m?|i#CXh-4J)Ux|jJa`4yG^jhJ=d7t-2`Q9Fh<{i@}~9yF}b zOjER7#fCL~2T`gLF&FO8=DB!(Md1zY0_9};FLINBMS(CE_C#%o&e#L$<=!>2U-=Pn zBHrCa$kO1A;f;2VL(Eti`I^FtTr$>)FzFHMwp(%T9skLk6}tOlC*z*+%y@}5@I_z!E zz4Y(bj9T5)flSB)%`@GfBV^x5BqrQ{1H*VwL@KQ@ujms|EI*ru5aD}#xEa_PhDGNo zTkE*s4I-~Np(aG-u%9-PvDia^mjiYx$anj#ShwLU|0s4wGr_Dq(^Z+z!^ijZ@HW~B zq=a}avf~A8Ft5&i$YkNl+ORD1YpPf@IGwLbao~4osZ3D}D4Y_u zy@{DY^W3VdJ~qPm1VIBp<%@G2d?`^_?L}}V%|V($s2#}sd}MAEQN^T*t&n>GIqGUv zoU7%TD4ukPnv+@&Y~ED6AHHBH&w~n3y(3GeLX`0>yKm81>W%o(faS)V4WT2sVesyP z$BIpO!OrD$HVF7ZHa{8|<@oa0tI58VDhl9O#Df-3%}AUJev#*;c4CjEqWo3}RK(uyfY{fE z|Ezk3t862i4;Ar&J5f1qO|z}Cdu!F@2Q~$V$M4FQnfjoW%^86+l}yO@nQ|%_LQ5dr zRla-hZF`=7R&_1!waw**AC02htHTzrqt+a2=rIklg?)3fpkh*r@88CylIRcf>gvvHbHPFjw-|8WR=-(x-|t{JFF7uz6>$tQOzhvH92s z5YBTPwYRzNsXlt;Kux;578eE?kR`GR$P_XMm$986<}cEuBcfuPlOG(7*da?spl$+4 z&N?ht`2*?uXgrs>zc`8xj3T8}gU<2B>@dnQ{z-mpGB1G>8TK3**skx3nvV!-g34%7TqA~23eNq zT_fhh_SX=2Nx9uXzGcgCXCET)=*{lHK?4$2-ky?H#p)l1PTN#|w-$R>QcG$x4@g3U zw%@Y!;KKM%>YchzHcDKa2yT0jV`QG-DUPGNpGGL$c|jvB31$BcFm#FAoW zx3x_kkkaz3-ESr2g*>4~szZYon4R^1U+XO+G0Xk^`QO?`nBZ>?3B^hp=mPkF+>VVR zAjP-ke%nDVfKwQd%}HB|wY98>^+!;NKjqI-D?bcy?m+qMbdF=rso2kNlG@k1a2p8? zj@dk+x%69-%}XaMBa~z=CufHD9-_5tZ)lDu45{1q@j?^VpdWCaKf>1;>T-t!UF1rN z{cYBSmRH>Rp7h7rWV z1=p&=YCHte$bsSiD7pr=%DONbZ?4J4Oq^`HsU|nswrz8=J!!Hv*|u%lc75mj0rxp) z-+lIr^{%ycTLNu2@@a~T&Gr%0(0v+ldg1(#Uye{Fou?GQ*mpjdpXH%dBC*C!GGCrT z##=@|fPqJ-o|NJRy}%bVrHMYi$JP))2aJZ{71RS@Ji7vZ7(#LuROp9=u4LGDV2qbd zfk#^^_=dk+$+c7hPHj){nq2|I54FK-rBA6`J^;A7m>}g)Twm$3uQ(h$Wa-f76jq2AyO6M7j z4nxN?_b)zcVk;xm$PG}bT$<+_?6M?)1H|gXK9Vmtq?5;?Wv-S4IhL+%2F~legT}n+VhC>0fCU;)w$=O$^AgItJ?4PqZ#K6OPCM8X})$cE_-7~5veMA_k9OaN)Jddy`@MB?OeF+FmYFDI! zvir|BXkWy)2;C#_ZfPAkS**$>wMzM<{C>4+CnlpL8paUUuMol8Ko6nOd1pI5Rzm)| z@@W*B=H7^#9gR-5S)>eHCiY~vIY!Tsk5jht{=k-hda!hA5ylndcPq5dR^eCuheI9HCA4npT=|e2jd@* zWTV(*ED!m1$8|UHwfJK9m{Svjh#RHgL0x&vdTJNK^TYWhjmH|mIvr~lUiiEOM{v4) zF3fRL!RWZ@s8#K_CjQA}GH+O!3O4i!=tdZmu6t(qnRksOX@GL*L8L)?k<5h3tCOny z`wz4QH1!x4qT?=~)OZ>C3pL0g4#QSN)$wP&@&wr1Ws!T}K$ygT)~2I+S=MmJevf8r#|9Dn!HK|pybNr89B)+Rfd^KOZ2Ee~mNo{)0yn2iWRlL9tmu)h z@7VEC!*&r!6hUG`PSg-fX<{MYm*f0Y`;P#~6eptss}77ZW{KmA_bonOjBs4kCL@Xr zE*Tct&ENrTXwxZboGdPkFb^j@{W3t7P6L66uQ=o&MvovOOhoN}j_u>kH?u}w_aB1N z_|%|>_~Xn?QaHn|Do&yzL?<(@q9dR24i`YS6A_y%I-il~Av*#Etk%`UIqD?0L#Iii zet%AVRi1t}a?-lzX^D~kjFT5vp_=KiJ1OM;rx$M+=F1M7NEqF*%$^<|92BJf_L30u zn$qcgG&uoBqGv>5xFMS7U zXiyVf%}98Vr?$G_A`Fe3oAb=T+5Dn|Q%lmE{$XW45YyKD!3yC7Y=}_GQ2Dxu{ZW}k z8=s@Q2+VoU;%uxo9-gMnHP%uX{|*x5xH-6v@4n=FIqP<$yx%l=u9kJ-lnNDHgUG7J z38)(WA*&x0qR(z2w+2c`;uDrHjpL}CMSx?j9!!egChui=x<06~C2 zgxxy6zV}ve{uxNi@ZQng8)d%H-r!#XCw6R_K=^~DAktq;MCd)dAAC;V#egaI7&u52gU_9KYo z53$wf6@viv(uTUBLAO9UFo$KY z=n!lytYetCS z+bHAe1jhHe6_vG-B4VU9GMH?&vZL#&cIp-srVG8Nfk{le*yAkTv{Q_(Vv zR)%4;!Jcy~7AN-5_@5lFj~E=o7~4oa%LX}_vUmN!#rfpcTE$=vVbJ>93CkD@Q@HIl zvz&JqYLd5Zj=u@M7uzOML;v4zr%1?=sifj;bBsIwJ0rr&x$!JrDM>U889htKO}B2! zxTs{&5|9HAfms6xD@+4$^qk@y3E zPd0A+)H5mw$GRQ0yi*b4#_aCuWb|%)6`o~_>`STO`x3C!PZ)c7-fXHcA<XclOUx(ceX#rGd!=0_YEBak+F- z!&n6GV`Ht$PJ6rRJ)3_$PvK9sw1}3Llc7F}PIAnne@D;R>3*GhA4LZ!A4u7WL~5Ec z{*SAW8!NtFLXgr|O@(8U3=IAMEHw7H^lIOf)MML|4=1UZlz82f@b(j=^ zpBqN{u)jtJaKJMWw$yHu(6byvmyKYrX?3_Z@NqLiMqAS7*Nja7tat&n*#?32TCfrA zq$c0Qk{-Caeb(ns}R9-p)Apc6fH9gd)A6%Yek?`vA z)`mvC(tJ1k8Gn&&NPn5inu7&#rs~u=+{M8w26-!P27Gd+A(pYv(hmt&wobzM+Ur0IK1Z@X7 z$r_vw6n3qmR=Zi}nH#isSjOXx*s<$CL|`|>17N_1F5Sg$9zWmy($0U z%kHVq?~r`WekVy0NT31tRqbzw%hn?WU_|%r%Fg%!YBkOM@aqpMcw!j*-@Z#skz7PZ zW7bk?pr%zz@$G~5eOIBe+my)@fO0zGemDP<9>s`t{THD}5b}o$)r^hIg8mIpmVn{L zY*=fiW@Ku0C}P9eM5OI41u%BqJUmnWy@xf$^-XrPkXZ_CtteYxkZ#fC2T?x z4lrRWg0m}Wy>pt7`2TFD$6Y#nLt*R*4?lP@JZ~4|x=m`kHi8!0ywECLTn<_tpYhBi zafA2rpg*|%Y6(=D_VGzS#OI-}+F!b?wh#C*N?-ebxz*#1G7_S1?;Q8N2dLTwZ`6S! z8u@rEY63^ET=sT*XY8-vDa3POlqT$yBH3w?l`A>>-Lo9At_P3cMtbLKNFFWj9Y6fn zi+3?VA~S)$6j<@5q<5da^)>V-+>%3A&u*p=W%9>-O&zTV63O6I`I*3kc#zhGdE`R2 z#&vX?Uh|`4D;}!N=9Qtp0C~>ywdt=`agXXotnPCcCwRe$pgNCGf-w1-zo>1%B7LQ|3xoHwza!4!U=%xlTalGkAZiLbFh)jGn#^12mJwDD1*K%#_|FudD#N3XS&z#U&RGSwi+H)vI&xA$9Vq+p6^b_;EXi@qEd4op267Wj?bXg5)j55HT21UIW{ zC(!%n`|cYUfY#*Qo*Zs0v&Xq6C=SG*tZ*M>7WahnM{L&$1TdcvSQq?5j@J*@`cDBT zj#OU!Rd;{H1+wrujL-MY$L~x16@;?gFS41d%wkpp>v$NPhiH<1OmfD`B6wzQ;x5T% z9hB-~(33jAW$37d0hsO-$^G~6V+X;C_7i$MHYKO3YNLnjUC{I^e?-XuP2pc`PR_7D zN`mBPrm)Y=&B(4H?P^~S^#UENpOw3TnshAlSDEruJz_SRu6fZ7qJgTcG?9Q1>|1r`8T80Gfg0gYbXs*&yE%RATGw zpIwS#Q7@Op=QyF-Fao2K+SCbz^JJ}fZ1TX- z!zCwwW_<~+NcN3ZDuUnTe;i)q8JEX=An+itXI2Oa;&w1kT^Y>ML3&!DQDSM(z-hr9 zrC<@?H%yw^_&Dvx^z*uvINukp<>d9v%`cbI2oK_}eLCLUXV99)nnBifz&wQ775)HlxL#H1B6A{BcGO;9445%KWPgQB62jI z?n&2rf%8*=@ho@KCHr3m%o=~!z0v-tXO6`0U6+H?tWh*jOB40ywL+TYVl+g^8?Frq zB$ov6^i1X(VCTLwc{04ipPiqRt(l~4?Hp8KE(orCoN_P?bOMw8>t%xm5M;Mj(yjIg zys42?3@c#w3c4;?Ti<{&UeSEL1hF7EUVrI6DaGrSExW8pGa2*{gX^$p)MPKTiTq4Er1#GaSO!xnU31)1Ddo+f=+x5yRfnMoA_GqKoNn@ARdd5#@G90kdU zAm6GX!WLlCRC^MfA9@_2RK2^2m-iy0>?XJUT%{YpljG1=F8`Ma8;Un%ltb-#$yCPT3zW*{vVxp+lT=B|}OCr#eYsN4y9>jDL9C~-}aTV>A zn)RdEA(Yr5b$u6?Ul1l)+&bZm9xEU-Y7*ih#jE$7$)HlwF&GR}=0fo=I3YlYNf)9? z)slivVKZ_4M~Avq>_>yh|I43kQ_|Uj$Qpb|u7m8*y0s1YW)N*5Se*k{L>_%a>mDnv zQt4Y`v7HE7ZRp}P7ws>`-vBex=S3LgAHv!(@f!G>DV{nimk@?}^o{MVv5 z)L5EbWm&jOJsEZ7f z@A}ZhoT-^&=(8RhIN7>4g|Pdvd2^`>I8^}@w>d-Q%kNkJYVl`*n~Mg+E$8(=26@vcY|4H`6ZNSb)r8!d>>B#D}m&Yj3fW6$RyF!!c=2s|GWRI*NkF5UD?u zXwB}*nen_;l8Q-Lgn$FUrPrm8s6rXH+r)6mnCrJ*u@r{Yy!LLWeLfg>5;0i=vCdFX zG&MzDjNcD-WNU1>fP#On2><(Y{-)p=;wEtWDeITD+N@)#-+fr)wC=WXmUbK=)_g{W zlVFn>qoBm&FTmCjCzU)s?Bfu6XCTDM8kz-meieU`+=c(0K| zx1M3UK3MAmW$fGQW~emi*jKQ^Qs$RP16P$8<9ZSYU;aTA}l;sf!oG}LFpK_!?H%iX*2UxZ+Ama8^X0 zGcX3=0ro-m8wOvzekFRm968b-bhEu|`FY~n0IU^iEwd06ed~?8DC{vlgNK2Jt z@pc$Gc)T`6`$6CZDvI`G_#5=c8t}jN{Ok-xTobmN4f;fucney-MXdnO^}dFC+ zI0o5)>@LCxs+1|(pGQQvhpi`SY?}H-!xQSd2ihb&En3486fEDKwpJFl>u)(j z=ORb;tTAm?k+a7ovE8QZFt3jH1I4H>+k%?|fz$P43_51nQZN(_q>$B1Vz#2{w&g0% zwlKu10h^p*NBN0)=UvW+gymAmjAIQbCYHJW%G?pH62N*jo!$qJ#$Vx)4*JE2QJQ2W z4)M@4!p6!yqk5F*KW*8a?qkx-w*oL)2Ie`O@pl6G_JOzb`_^$sdA+&oTVXbroPXQV zZwvHmd5hd)9Ru_F_tSS&3u-z0NNW?*zk&M^feqHOIWcmS3=hu@Ic}t}sigp_hKvatv@_pqV zf`Poax579@0s2}O)&a-RM#ee9@;aN7BJk@1>@=5Uq*QZrzgdw-*|o+cOZqe`biwnm3fM11iBeG9ROt?^VJ z0{F;T$PN-Tu;Cc@0+t8M##r^vU)bqhEua^Y9i8O%{5P90WrIJwoP)qGEF)fVUNioO zK3LFM#>wGHX`7rr{SInS?M|kNZ8;*~&*XmTGffszto4gU<8dUL_(gl$yPR)uwUJJG zN-%XCYl5{}7SluClWqy?->5sr>8jZUz_kv@bJ;Mo9P*0vVoVvOs(_WR3GP;G#6U3W&l-JKfPbv=&zU1bECgmFU~}C+ScRo zxW&UfYCG!G;MIhVrGa<7`!L!MyqtueE7K+FlOLojU6PL03lRUyA6;NZm9v2Y#T1k94G%wCN>tcrjQDlmcTyM&zKSdtexofa9MXKPd z`WjDSQ}dWc%l_4Zu|Vsu^~D|$5D*wf_tE&hR#3_s#MHe!CSW?lmTL3r^zr9A>Qh=k?l{6VFQ$6nf5r0^#!(D{HGFGFps@~ur2$JOebx$QC~l^n ziERU4&%oG;`FI`}^H#LJ(e<|tkxbWdoh9&ta~t7$u(rfAcBUBPzg6Rsh;L4GV4c-; zaHZ^VdY%Iets62d-z+5 zAqWHS_};p20?BOJ*4bH;+~rk}@)H*Omk+kf=$G`olI5 zqD(nj{(S67Lqbc{)i|)@F&gyA?)r_=l=m)?=m6vwZ zLFjZDFUOoAF+s^ZCn`niMOB#3#MLg={6>!0=6LqcY$(r>AQd@_Qwk*z4{G-$x;vKT zK~1~STeb#kR9g**C#71n177b`#-@9Cc7qtmeRYY_evk<-FhmH_fTux(wy%E|6N1`l zyO!q*2Q$@&1hGQ3$^8IlF^4dV7-1@Ud6SBz!Cio!(pp!=CzTCce`3<4;b_nvh zSnvxJNMA#)3lpKac*fgy2VYaDC``9tvbd_td+RAk{hyoVy;73Z@hx3mN?QNn(B~U1 z7k5py$O%LBp~r(u_BvEZ+k@NdX&nZ?nS-tc0=_shFqJbqy=fQEa2!4E!!Nbh?aK)f zX7fJm#H?=Z30=(ggeAG;cKJcS8HF7lWS_AFx&y=pFo?4{q0MzY3RZpf?1At;#8qWX1ds^8$P=+DjGT%^#8yR+y zrVcaXOlE_KJ!k1v=D>T_3pTTK>;EulBgN+XF6nBx3~D_fH_~rplx_(88ybjS4Ntyo z+=r#TF~-Ly%<3T#570LZ8&Fl=i<+vU$QRpkS>~Y!W|HBX6B}-uYwW3 zHLYn2;sxZ8;4O=!+UOI>bECaJ<;->=y=BzuiJDvnf{-5w85(ji7xcL4DUc~=J?+Y- z)i4thj{W`)Zqs|j0FMV->K$QxL-FK}Gl>FJTEiY`zw{f13QK~VS} z$wl3Nzuf;j>H%z?h$$$e-<8r~bRO6E#wVr(JzmbzEb4UCde6x&H#$_-N(xX99|?^7 z;Qd{^Kecdx3f1@LjpqgF0PG^}TdyV}Y_w4`XP?)cVQ6o>b75OO|5IenRmG$&)X4xJlDf@F}8+AN(qJ8`N>c0Pqo}!d9OIWaK z>=_I^13#U8D2SO+2%_nEM}(hv?f^`|=J5k!ddVp|D8wEyElG|!Q9PZP|D5z`MYa>5 zi>dtN+vf28i@sJFMXWiQ8`v2WuxCq9Ik7hKZ0xEtz?KV%71~5mX zlAU2QW9lP0Pr{vFRS@oUQNdZVXMT;s!Ua3+0KZI5pYX@=cQ~~y;?^h1jl_PFw zjJBKK?8W&3ay=cN+)Ja?*2e=1rBT{Vo9`dxvKWSb_=^vjW>E&f(Jmj~$Rm1)Lj8D4 zzWP~`1iBb>CPz$MG|-B+knxp$-12$2S9)aNV!p}}I6T@G8sNDwty<^l{NpWc? zVYB{DPluYxhWw4yk2lv_W_U0a_Eoo_nu>-UFov4Zy8jtSF5pF5K9WcN6**<2FKWj2 z4bpXXG)5LP8q8=gg8LA&-FV0ZSN^M)-Ri}z^#Q{)nzS) zuE1QK2I4>v)9mX5eo(G2ixxYd0lvyAOi|lQuAlu!y=B^+c}eettBEKDF}7$qq$BKO zFZkMV5&l>g1W*9_ee{_H@Kg27GTmZCKB$&h9DUXV-mw>Go{%{`l(yJ$Slenm^zrQW zhF!`Y0f*t|`;_-xqK-Pf*sHOtQUCFGE@4XE#3!WIFH-IvWra|Uh>ns(t)pZ=CAn#h z;DJ{nKxh8g+Kl6}yV}B+EBK2V%btO!`<4sFqHN=){F#UMn16RaIpUol=v(t)*qa6v z66hZ^-p6JgU_lcJs|6z-{`2*RxDy}HOVL?|GKY%PcAIKjk^)|q1Vbl}h)T>dfI399 zC{Fls9IJK3JQ(tdntQ{S8n#8}Y(%@kedV%7tfbi{X&YB66gb(F`NY_M$^{@sy_}5exh9*4Jo7KMnX`drg0she>Puv4wkE-#;^^ zN^U!-wZ%tz7o+3y2-6LWgKN&rz7=*IX(+2stpLRB3{LM}6VRcb%)TnVPCpUJCHgJ> zSSwD1<*z88k3x7?+n^Wu^))Cn7S@<{Z61I#K+&jrT(CR~+#ge7w#7r(1Ye|M6J6Si zLwrenDs$3(&W$;d<(`NrUBx;?+m~=1{ihza+_+yFIvH(aamNOIOOd;(IzXL`y?@=; z_1+NR#dx@RXA{IBa^f-AJs!pZZd+&_Ke73wp&yr{_ND8^!Fa#Xv#lruX`6c-VN&VD ztfm{W{F>!MS|Y3}>SLM&Y^|8?e;AbB63c(L%}sn4gNSbLkl}1$KsePPlbWeGVcM&O zm)ajT;5S=*vELH0MiL}!o|ogG<4Xavgpi{@pf~Gs%7hWLX{C~G<~08h)xmM?#t$*= zSFm8rb5}a0*-w#u+LPh&h&hmC#*Vf`hFbO;Oy+Q1C z4unjAytd8G^BT7XJ@so1Prh9m5)Al|v*%f*7IL{f1wgw-aZ8K2I*wqYK8x~&z1uVgU znoc+B2JR}BS$pE{5Ej;AJY6qRuJ?u%>H_5odsjy)$;*z?0pciy+Zlc%wU4K^YJUgR zxz5UodVA~~m5+xJkBUI;xCEzo%AZ}=IVvi=z$wIjwDJwEzT86qH~SDs64H^*#6;9O zkWo5^Hiw-=-~kAAJrQu5;O{NczlS{tLf+P|18qbv5jmw2?%|~~fEyP~MmGyTPL_Fp z6P$WX+NB^z#=I|T)m6Y*Mk3#;yw8Sd-d-Fsw|-@QYCCvZknjf(hKj-w*-PnSFq>Tm z_BH`n_^P8nsFhVcR;i}D&3l@5*)#N8U+HDRah+*E?MFc1z_z}Un4cRDG!!0P7fj5?3)fvwOO(>DS09H8>8oPJBW&a3Noh0oW%IQyA$AKY^$FTf<$g7TeVVkO*v0%=rqlHRJR(JRFNueO73D*bzi<4zD5Te$xXeaF zqM?^iv;m%4v1L)+?KBt-WJ9PB30~ba ztQTFaLd2`H=mQjb99T2%M&Iijz)DT~cyY*!Cjj?h_;|6+=z?`S`)6Z8gcD|dr8bA~ z@rdx)zHuY5ggdAP zF4z(}U`EjIC4JvlWP$!5XttiU&zulrY@LDI^ABu=m39ab3vECW&#G4tn<=AFt|Ecv zrPOUVpDHNpMN0~hwcOTKMjx>qv? zT7=Nu@Hi*}KMK`HQps0?Q3kr>@}kr?{eB=nL!GN(qj3;F7;>-Vi zPBEq$FI3)rQw}+?P@`#ZEQ@4yRuhgjBV_It3uZPKi2#CnsKm|u&+Iba@ zk{GE0hOS$g`qMVj4|j0Y$2*B@X&m2iF|U-yj`GRwr4}RuZgagT-~bKqyUR)BKFHsl zL0UXte@2>73hJU#*jlKPCwJT`4Gg}YgDo3F2I#ORv zUA`~Ah9ln)m$fZzs)lFIMDBUnE<|fSpR@~nf55n+@~2rM_XAFz=NP{V$EE`K_5OX8 zNu>yhLjUnaXp5Wl$D=9eaap(N)=N5dXRlDGK8pDFX*N*Dw)yTn-507~v5#oH&uuU< z@^);(iVoD|rV7S~gr(>UyjKFnhQ(eGc@Jg3gjN z9gdHyOapGHDC(~ih|hzWBF-3;{7)ad{@yzGx&Ze}lahJmUjs`|@~=TC(T{QWsefLL zG6q~KW&et+PNw`b##1-1F74r$E{DM=@V>i=SE62S{82R5tKTRSrILqa_fX-IG>Q-j zWU&2UtcTm8Fb|vIYE}L!XO}aX4Z;P&X8olhl-#~$S4B}mFl)AgP&{w%%hNr|Qmm%k zeQP@PT1|9h=uHxwe7V@qsoFGv4uroed-LlJ>c~!wosqkfxDVrtjp8Py{sLbqxT|8x9}PI6BFMeT)XiS1 zY{H@7QzSOcpmJ*b`q-*;VWXjs>Qg}5Ev6q!X z0TZ2a(`9QxPK=)Uq#iZ8);wj23m=oi7cYTIZit+c5geG#3tRlnYDIFPt< zrTrB+T6;!7M{oo5!F3a7TrD-G0&PO7yH0HD;O5U56&0Tb-IBW9{mog%egwBy7=hEN zoMS)vUQQe;0FcWlrT%HpR^z0a^!A`8fl}4q`|Sx1VR-!Y&G$HPSm?H?d9#(u{IsmA zq(OWhS=$15NV}5j#Cxk5tcXLHpG+LGy4$~YtmkF zO%(#@J(?h6qoZ`tN4MVbg3Ba-KU2Ax&@rG}tU#2&!a z2j<aGmDGDq*X(o#=Mj9ym)}HD?&FyuVT;QknpYunhAL!i3Z+N>{KU8lS34`mZK#6m5N`%1^ULP-(qV!rQ#-9 z4zZfT0TW&KgM!V_@Nxs#-jfFfcKxz*wUcv0tA;x;1XDFikHSNV6>_{yfzP#o!`Ypq zx|TQ~&cQn4H7;d^hz*nrnf!%(C7jDMZ`jzt4sbzzsi;h4_Kbq{lVMyw`FWs($L2G6 zprxu)Gis7b#4YW0FSXa*Y&qa`mNK59$N%rw{5baN%r98CTGhVTTK|L*Y2cDG{ZR(! zdpcmmsn(lno~16OZNB744u>4ciTyt$B??#FAcJG+`B_OK{{D;UY2xIC^r0EmO8%kq z6Ergn)~uYZZo0-pMt^OEAa$bfjv z<4#tiT-xfqgkKWwp^6DTGk~*xsL;>+eN9C*aoJc@)ywy&+tnvyx852@Pkc-2e&|KvOIEEGPmHs!fYZA4NZG%Q| zQ+@ABP3s&0ux>PI{7b!?8iaEeT$~Ee!(E(i<8g$ZL6jiRGn~Q4Z8EsVv%V-X>;YUm|KZnz z;vN9e+;{o;#r4MoWaicUNNcB=-YVFwP*(1uUqnp-HDwj7>&`{R;hivC^*w~#e!Dpy zFkwVK)RvMnDbAVkH2rt;PDHZBxpT!vgWY<2qoX4sjCv98LEM_=jjlK55u=i~3-F_H zQ<3-Iym;V}>90;i&kOvqJB{x{#&sdHW>;*}m`ChFWe&3Db`1SoeY~h`C;tLp6wRN< zH=TWH$P`hXKJ~M2Jwx!;BHDS-TesE0megK|A}Ur6-Z%O|D3a&L6sOjnKr>SAH_$Y> zKJG_ub;_tMf*HNO*n*yw3sFV8*^1w+>lakM(rwXe@fX~dttLm&SfRp~#RB^YOIV)EpqKstD^B^V)Y~UI<6EB6d##PFovArlr z1~zr#SwbpI@VH9ooA+aoz3B&2q8^80pnMVrR$ohK5I3`nvHzDlA@rM@RL6}(JP0UR z!v(+XBDFQ2%DQlKxTZ(@fyS?(dn-m@;|Ndd18@4RRB*C`SFa@3IfRH{2nv)1en@D?C z+gKzEm8wIG_$)3*!3tqm=kVr6;K(0-TM`i>E%}N}-0MncfS;Txg7UbP*5X35m3hd0 z|N2*~a#1GJIqS(xRq*Xea5Vv-hC@df?89ai?%(!N4aQ-6jiqHbQfTMBzs4`qM8YsG zrRS+in{)7zdm*!~ho9fxY?gS-^WFvyTp}(TXz`(3)gqLk3t{ZVJJOQvFG)`sQ<+)! z>LW}7V1tu&p{t~R%l#!jNP$eRKCWZe{llx`cN~bG%dbe&MA}Gv5PLuS7kq#F{dO7q z)z2ThJm*Y`lox{b2Uo+sq3>8VV*to-Yjij6MR1pCEv_OY!CAaAI`DhNu&O=-#@2G+ zA97U>l`heSYPb3!b_nX`oES8gqjsh-}rJ_NKIRc!VmCuGp zNhJ*ZvRHCuOr7X=n^3d9WKU^3ea_K>9X|OACzB-x|@? z1;Wijers!A&5qhUh|sPNvzu^?wxiGb+hYz*D6rdB`jyJ2W`gqx>mKpdi~)<@Fym_` zRIA4fZ+lzP`rK82Qp3jx7guJLY_r5Q zhEkW~cj-}(m{G)p0Sf3)Cqo(ix+&{esSv)ch-srdX*o|B4u^&fUIvqV+mqn_NK4cB zDYrHi7v{th?LQM?8vhC=jvu8HKst{_6MIu`~JRec?vuauCsO z88f3QxG|C(gV0*iM5@@~UPygjZRMh3x9f%!FC9WdaKy;iyUk2?M>ik)s5sCLnLHA_6uUy3&EQg zpYR~zvu>Bd0}3%n?=wd6eGm(nih7Z719ojKlJARbDkIZ9UxyEJo?F#l2 zE-Op32!9|G8fh%E?F}J9_@g_G_^L3#-iF5M^K2R!Mrgpa$c>`}re4+&b1p<~MSETM z(I|2;!fS|J+`2EB32$OeZGS04ZXf3ME~NbNeaO1madIi1P4BPA(ngr+H;lPBLVD4b zR3c-4c&X0^)+{5xM&bq0^jQR04wDdt9RtV*UrW!FyT?kffCt@UncI>r8d zy2`mQc2B*c7?OHlKr7~}Ke`y4frzD3DIXH*eExcf5-urhMB~qW6Yb419h0}%H57fq zb_fen%TQHtFy&6XdKjhXGajkQ^x}N&sNl!;gq55Yqy7xgp&HOc{mfk%gIjzw*8NZEbYQBM?!u8Kbz8kLQ8 zzi%D%-z&4q9OphAt3Aw0fa4!?BV&;0Zc;I6eQm9F!yW%puYbk~;%1~>S7-mc7R z=nvlOfWD?2`EL3Sb&30xImo7{hjv*4*a}ayahQvtN`BRk&Uo#!{jC{{<3jaaw4ZAV zI9y9BNU^%5@Auv!Sbn{D+dOMDns7i%5dW<b$X=1@+t-ukPmRT?LmU zbwEnUhv?Tg)=pjM2YL%wPucRKoajI9Iv>!J+s5+yx2hvYIB-PXv(PRfYe2gjt@WTAC{sp*dDi&3&_N>z!%Su6&O9+=hcEG#-rUCd zz}D+l;U;cfJfryB%_5r?!0nL16e=#5L$B4#{Edh@AC4m!xjugM6%S z0rhVm^tccqF4NWfwPmVe(hS_>)eP~;z(1e?4jvmc#CrUWLDh7z-cmLZvg_VXGkNwYV@O_8K1~C&s_%4|l9{el--DOQXqiB*uy7Wv3LV@HftijwPZ6 z71fL_tQ|)cjL^`}ao0C0-lL!deh7P!$OOMn^zno}R&ykK;aNx&EUg@KpZ-wkR6XQt zH8~XlUW#-iD-mgLru(7fVFMx4Ne@j=_o7!*)-H8|frxiKsN%t;;wkVN({5}>c{72N z`eG=4F@HIK?pUz&zPjH7l8#DI-?{%J6XUJ^7P#UhhOkhtk?7rQVf(p z!uvOQkQaK71#TS1!Dkpq@J8xINO1Wq$~ww%ne^|NJa&_spz--b=*tB`E8tdA4xbb4 zMaKSf>bnW*zg9x_v-1n+v{P*5kj;J62q7BxiS2@=Z>M=MRBydoZL_?e>9(Xzq{Qn! zRLh6soJ(IuXP6wrpsHM*@u-heP?Pg~W&_(Qz_>bGr>{3o-o~zbeimt_hx0JECu1FB z%0lW!j0a+}$Li@hDeWdSGYjXtUQdsfA%QKY#e7-L5`h*;8eDg7GH)W~u^>R^qZfzi z42D13R=0i%Ih?<|{3a=X)lY$6(%6Qv*M1+?AS0`}B`6|X$jgBOtlP1X9?m9K4Fn^3 zAT}rR(p}s(a_!0&{Nt<_dt-CVvRYBP$kxk~7XrfjP?TY2&`$he`UEuzEgdv_na57| zehw`W7t*H63IBUI?GIgcLyEpHry7Y!9wInG5{j-dX{f!pO_s-?_M0094vmlO^6gI| z{}nZr&99Vj(9unZGC;&;_$LIl0{qN`SE#O%anQ}>IfGa3cPf1EqZ&LD0lj^)NO%%{%=;vcKJZtN_FrW_gwzUeI3j*&!{ z)MY|}cIOn%7j&0I-Jn}unDe@^YSY(qXV5FB^7^F}^ zyH}}s@A1eW9VvBEZE1fM79vbjUS0TDKH+UpT^U@UR3chv|Fd4MQUmd!O`!4i(T+l5 z**ua;vxe<=$t;jzAz<-MUR+0BHk-F51)aacd{R$sRCx35g7SmrJ}A`Yp}D%0)~_u@ z)T6UC`ODkm(u@!{FJVr!^kZ60!lXek_M}w}jr%N80Nip;PYJ=_Q|%%lDM7f0!~I(7h{V9diQ~)(R0&yXZ2@*FlAs2S=00Op0+b4 zP_x{Cbck{T;Sr})b|#zim!RM$+h;!PpLkIBdMFc9GeX;s3q9g?6i|*@Kh-WFJy9-( zsxE*UdE*GY7S&YL_-v(n?)LjZ^k{I<&!iNYw{GgQwyx8;&{OfQZb*{7{^?(9ao*XI zQm-F4Ft2qL%~C8pLiXDkM_Z4bu-%^yB1_mKHH#LQpH5e}AarByl3c7jAb{|2(KZRV zKydz`)oH2{3ee}WL5h(ag{65Qd{e$t@oSUnHyP#F#kBK|(eS_V00LonDf%nHtQiUa ze9@_Z04VmBu8G^13L~{9)yi0TxVLhC7CTOvtT(iyo*Zpm8p3(62}OCP@5I~jYp()Z zcK}>|ax|TK)%S1oHfs$R&mEw%SDJ}mX>nw3cmr{ooWnpcw++*9w~!y6I@7!Ca6s2? z8om#jwIqQV?Z=50YVEIHzhE?#)iCRQ*t+U$Z^-~sQnn0VtBOGt|C*EBm9-2x^7!W60fN@rT*dvE>e@1&zD+} z8x(s7=^Cy#A%uoQ9+prf1lFl#%;(goAA^MM0-Xi#Jtu4EwW;N~#yLob(HjC{j>&V~5P`!Jr$=#zn*sE=;{rZ=L2*-yS!T(Wo z6>L#0W93aW z)c{pDMs{aQnz1^fIu)LP8omd)?+NrVAhvT7_f)->Rd%|t#oJu)JDZrZ_U4iizF8gG zpKW2X91PiE1*rxTf{8>ic4D(?<+6HbI1yMs$kIYalk(=*c6aM3e;j^5O{lhuJcoHe zm!&ec9X;uK_S)X;5d;jRZZ@}cgz{)BLU+-6f{^8p!}F|DWgPuGubg_bMgC7{9JzfW zF@1*(1{=$=ijhpefuq8f?8CIy)i4E3idivj9l`uu?dS`yX zZZP733YeU}smNZel@&{}=)4(g0FFHc&Mr-7?k>lFGV8cR=7Bt=# z`&ww&vhH$QJUuWz*jMGMo-ZR|?(xLSP>f1gPA!UuRYe)77Ar4vFNvMU9%;CZYs-52Ox-4oM0!&zGj5?9TbfS8UVb-x_)KF~uL z1bb|JST4TMUwgaX-1GDGL2PT*x^&tg>02fiAkf@!?c+f@2&y?$UX!V=BV0=$!CsWJ zS0M;-k84<@98C_;FFMnFlcNv1dR~i@3p<3l?m{22=6~4VLa%3bn;5$WE@Ncfw0R<| zA@9dW_shO*K>vAaJDH_Jz2yQvqKJuoAFoVi{@n3+$9rVPYh6?J9%U|}R5?ot?RgBr zX@)uO{4ODQ{ae@O49gzy&yy%8m>;99#6g)4 zVL7@ODjmUt6Si4WdrRwycekZ~SyvN^2?`{GUMJm$6d%(8JO7^hYE!Bh^c16JCpF$2 zOmE5ass5Gguj17V2?YoZa{hGj@t-Ap&+Wtyy1F-*i(z5qIL0-9E|j?#8^-3^#Jpyv zlxyym#LrGsTz;DC81a=_LrJsV>SCw)<$DQz0G|Pl_*g&j_^-z{ySIi>PT)@@gZ-<+ z9UU$;aRYa_W}vP0qD)o+hnRQc!BG7K###bh8DSe^_ov>)S$m$2)&ZD`{ii8`GC~}* z>M{kyTppvvAqL)G2#JRFns%WwoB-6WQ>$10ti_1_?zNKm$+(>r!(3N^b2ur?a*EAA zT7*92{GoYQME^HW$BHLZi#LuD08(FAMZjI6ZPQ-A*>PkzVcsm1Mv~6I_aEsxN3=u` z+B63LS}imCvn4)?-No{SYb{}9HTw^v;89QO@li&3YPx|{^g!kJJpxB?Fqlnb*~vyQ z{fH$cigx(D>!+5AFd(;@2g#Y9(;>xA5vWr1v)BQX`Rts=i{}fI zl6$vrGLZH>3(rjJsA!V;=|AyFTqKc`)BD??iZMCX@Z3htK=1 z9X#~-7G;xn&J(k}x0^9$P%EWC-;qvc)^E~FeQZU$MHGo!KOJfx$DL`>PKM7Q%&TeD zpD+33pGTC<#t-p>^TZmShs*$oU*~)}Bbk8o zk4dxRQhgP&1A{}&FRXWX9PXh7`*mft5hXWm?FYz#J5SYrKM?_t)~)12WBZs=z@vcN zlXJOuV$BnvByn*E>qJg z9+iZSP%DS+5K#5cdR&T3afuO9VqJZ<-w7Kb_d3tmI0v|*q4K{M1Vz=sKQTgALoh(J zKOK0#3%^K_E8xjvc|*vwbxqFAA-c30TSwe}c0VHoug|03tK-Yz74m}X*-nq(?AA>q zSfKv6L_evMxYx#N7t=R+h1f+f7^UbH*1rIMg2#e!4VvePVe-5+qnPwPWIrsc*%dkw zOo>=B3S#sICVa{t;~KS7J>%!>dP;Privj&;JEx(kl4mt$<4nUs;M4o>Pvj zpPchP9b!ZDoln=pSd+H@-fgI2>m>m0sl1zY9$TOfu6_JkZ48=}r+oWQw{dpAf7hSa zt;V$hZf`Nw!u~KUHBc?MHNkie?P8eskm726?swoPO|<>|L^x(Ij-8Iz9_p5Q*`mAe zUOZwOjErq#o8mBS7z30w9Sbu3Ei4=HZPsrm};Tf^jG9)x6nl2dAgtFMx_sb6Z$--M1(&}i7&vTIdAO$ zt}vFdX}ae+N(J+io502JIQX~(k&ncn*STvRD#OO-aa}Jrcfn<}HzNQJnt?lu(et() z5XA@tr@(CtDu+49ZVXPX))HXoWr<6Ezpyb(I8wGytglqfWEn7S< zc8!DZiusTo-$K4{^NcqkEOSWzI6U*2&V!kVPM_=U&ug$%4W*@(maq{etg)4(P8dkmQI_YRT{>$% z69$r)1q!P?HgKEV{e=5Xn#(`IUR!lO=$s(u`=N~(qNBN&+O_*X2iXfq)Ynd+fsq+2 z(C#2e;Zpfcolw@C|C6p|5v_#fU{fla&8Nbu$uM!s1Ld}O!2asN;PSQ3$E<_2s(P!d zV|Zu!Imk zTzzF0!zJ&YH}ak&bl&YT2_34D6B2AmfCIww$pwMnGJ2Nhk<^9AKKt=zvvnQsQv308 zx9m|0=kC#*0zJ=0mn$&PlZb9QpGsqp7f zm)~X4%sN&;2NPuFBD7jf#iws;;`(e5L9M~VyH+q69cmpZ+0Y) zeecC}k-gnwQ6R^9ucGz?KxmBF-FC0dD#Anc`CWC54TG9vbVB@BqY%Q0wdQ_%GY?L!|ZSu&$Q?);SBIxgk=Z^7!c7Nss;6DC)<(_p08%Ael-l zPEnCk0L|(RKbyRDDPou59Qv9a=~4-%Y_1i$+&#|W@7E_5Ez#*OMn1Sh1A`Zvvc@^d zdqC-`7nU(w5r#eWJVFK&=}PRjd&v^j4@!J@(ac|$&}&vjytwsAKrnTBpncuC;1-%E zn?;`^H)E9W2BoC3w^JmmOhW7G<2S0GN<{M|sr$z2=~yX_2iWjenVMQF#Q+n?UPwgTq`}3*ozIM+K!$CuCFGT1B?^)DjE}c<{05hk$5B2ZclZ2m6-$oWNV(BlP>mz*M7t$@pL>ul!Qy4jd(xF*it8n&mZ>iH+ zo-$XL5p;?7o&m z#M*qw)foB?bfHIbg6!Pip#G^ImCC%G3<}6=9(^86HS>KMGcnc&)09$tqV7`-ax=GiOb5W$gZ}qZ4`E`M zEJKRbn?zJU;)OqjB9&CJXH{k>U6#FFo=ZxxxlveWe|gPs(`EtMG^PBD6PkGd%GhK~ zV`G~`UF%L91Qzjww~N1BYdTC*eX!%x6G|c}f;_PvLEF_eUIp;beOu!!=n30QY0aX-1o0%zJWg*oKD77nj$MrtiP0 zAR5jQxLg0J!fof<)V*vtL;HNyqRsrRAxO|^T&vUN5R=Pc^s|v{o*dDV?dYoJCvlwI zs0*+Y_J;wtT?IwK40a4Vt-CW(Z!4gD&JQt$GZbWixzgNejSYd@TOYz9ad z);5CKd+2+6dF6eNBKkc>=i3(eFR1lVx$SoSoSK~>=92;X=Nk2wo7lDGFF~9?7R48f zK~$pk`N7>DTm&4(w|jM zK`dY5^?}AYlGoavZk}pa?ryhIMgN%&vDviO}BYGvT%oCZ4Q|bIOH;1xns0m*azx>LA zi&{vkR3QkGORb1 zcO$Hr4nRVBN4KXQ)jY6zLXgekig5%E6JCo%9R+sQwGUBko8i6#MQW3KD5zR=uO-`` z=~V#*$weM9Lqj&=iW;l_$C4TGLyU5n{s^`Zg>^Zs**2@Q1S_Uo7gA9CZfarNYte3O zhdfpp@tZ*agwMKZ5t+oGqHk+R#gOjnx>LJeLNkeXi2d)%-FNVNLYwO4%OgD?&rOML zo1pCzzhap~{iYM7)Kt9wu#mcl#{pZ`*rM)QPT6XcC*oT;KkDS?&-K{ud&i|<>Ar1v zv8xEl3QcbK@VyO>$7hJU!#_{$bRR6l_Dk7+x`E}i8Wm|8mKl9iDzbJO7*J1rabyO_ zhhov=Q+PjSSJ5Qf-SA4$QC`C4Jwx}+wYpqSFBEdi)Aj4iWp-eSFtu=Hne69iA7&s4Z&3!b{W9HBvH8^--zoHd#$r>_`6Ph zZ%=Ale2c;L=u(vG@z?+4rv2MHd{3IgrsdMIm}GI6>z*a`u}a&Vb?IG zJ&0Kl;Lx4HHDBcX`MdEJLO%RU7@?{5wcJCK7r5ySsQFz5Q~@T+Beki7bcKE1+J5_Y z41$_{IHu2ANLbKwwryNYODx=N%d)B_&xo8jXn9G`C9#b3PkjjzvG$3*^#wb zc?!`dSqg&YRLQxLAl2Tc)Mg#LUrSiu)=f$@?(1=EvR)r?udDf-^6cDY0vnRWa_WLf zf;4Peg2n1KjbQLVmF;}%0uK=C8ebxXxI;l+*ej_Q(*^<6soy3W$`1u6snW%Hu^qH0|H|UW;QXEYJHE#pBP_QIaNvJO338v+{~`B}`fS1d zBw_UeGmt;C_#yQ-K2o+d@rkx+d>d^W z3;ScxercQ=fCSK=VJq7c9OeQVeAHT4dzwSTu@{L1X? z=s-$!logqp6evvof_RuDt8}Jzis+I+miVG)DHYgZjj^p}fw*Gzs zIN0{)m~}Rq7?{<%Y@bytEe4U~j;VitkH=+*-o2 z)WWk4MmExoob^nhe0spuBZ6wyHQps()|h}{neU1epg1tUT`DxsuKIDC~iDg+K*KQ{9M`t+1f-Gf^_AbQkdmF3G(XJ_j0WQ*m;oB$P zLq%_p=sViXh!WQE3;>O9iNX-G! zNT}y9_8JlTG_5zikux(?*$#&UaUl-oZP(ct2)}(g0^d7a@eMfU9_GcSU^M(+^!25u ziGoI+cp194iJE2?cA8IS3i2Kj4%+5M07@C!%e?w!Dn;&wn!z~-BNNSC0_2SHU{tnanOqFwe>1^bPQJwHeWKBnbjzzaQg`OXZ6nF zaT&?ldQ81#y(9``@4Fwj)%Vf(e`wl$ALHk`?eNsV?lDzKb3dgy0+ogI#(Dc#Lii zF&=s=P}f+;Ar|@~FFjEL6wgz}qpgKZhaI9I=W*agte^<<4ktk?nsB9V0jExBU>y9A z4peLY>-4uVTT&Yl0A3EL8JhEaLUPM~Ty%U2XHHH`nn0sYQ6ZJi8!2ytC#dr ze&`Gp@9tl6{hvoV^jkkNxY-H}LY&$~UpelEfOI!hXMS@EK8#dq$0K(xxaDnHFpy+=x8( z^B+K@GyuOL?>-w~MCH1E72~3^OYVQgF=v8HlOge@e;rmcc?Rp_JcyS(98s75oa9L=5AZ>fxWO7ei%oQ+GF+^%^C3ZJo`~ zAEEi4Z|3y+S|lCSC3c`NWw@KJDmu|KNB+?Gl#x7RtSBL`cS=xanH0FYDWS2pht?FV z&kYf*vLTEcgrd?9mR8lW$7&msgT`Q?9FZ!Tw{ zOoHHiy1hGsCJ%AoN_Z&2Yr4^$B`OugV(thYpeWz>(Q9x2Zf zezpJ1K`X!cdhP~I{RlWg?CzxsWx-*DebzObVDUBw|HL@=Yj^(PQG!7xE#~M>m+z7f zIW0UDYiv-)a-9@_9XYr=RA10M?M0p;o#@DMF*xy}7yn)R3r4+cp*XqGu)4iu?VZ?f z*q0nH>KA5A_q}Y&cVrwLM_V`hr_GZcUjrfzV{9Jb4#W$S9-FHT$6#7FZe+ACl3|j$ zyt;-wI>G>Y)%VRNBDRp~cEnA+CFcXy9mXa&H@^^fL*i4?4B{J19b=Yj^cxNGnD7f2 zd-5aTZ(hqfixy9Yc{~(_=eBV~@lEu{v%HM;WQCAPM4AG#mrnGtE}>YnJ$R=hx59@< zK=r3`jlVIz7bdsU%j{WKF5a^zm9f1#e7b#hVVeJnh$;-{YLVyN*TABj`Pa@)pqS(N zJwp9~k?YQjKZJY-uM;|VRNvekKr8W9+nV@pwT3CP^$Hw5pJqEa_h8V0h?h8VJIefIag0D@Q0>r zGc^H|hO{oVC#-;A2^L>}*zrWcfRN#;fhr?VkYh|3)QkowL^Tky#tZP8f0&A9O$-Z>u%-I^`ZD*0lBL z>!@Fg)8Rajk-vK%1H6heXECvIf6n`U?xDI)WpcY)V(@%x4r=17aJXpx6E+pwCU~Q` zLxuuP7F7G$+aB(>n8J;`Vq+ zeT3@i$Z-w9yBJ0qkch6xF%@&&EL+EwMMlzm`jS~WhElYO{BE@Ur1pWSie)vcBxobk z{L3685WsltF_p&+^5Nq;y7tkz*Yn)AcFWhZi=_OC^~c@wwa$|IKYdU2?b}MZP5Bcu z36Of#t?o^`nv2AIU#I=MS|spgYM1qri_80Lr);|3hH(q1ZhWye>Zau2t0pgq=)(T@ z{rK~~Lup`*Z8-G?WE)yAzU01Bn% zX0hR{P^`0G?vppHU_{xw@^1fBMd}5e^f~On}a^H&uZdES|JTLJ)RYj6RG!5`TvOHfMT@yizH{yWycHI%&8xo=K_0@Xb?S0{lLXb%H}1YQYAj^h>VQ66H|Zv zISyh%8h)F!uwS|h{NS7W_@S!hop;x^J7ZB0>cuqc{>6mBPAvH`knz~uJuUHtnKWkG zB1;k(+4alN;`PcSQ7o|4)$E%DQ(k?XgH2fYjUVge+Ct;)^72mfzLf$)U@!#nya-+- zlS=lFp5h;hrY**`l}KT|Nl?SvJ4~T{!Mf&CB)~D3`~)p$;kw|g;SYkmzLPs)MqV>W zd*X<)Jw6W~Wx@|LXUKDLvv_K_SBP!0sV4wXqMYR1T>qe{H!hcFjXBo}5fw^I&)=Y9 zwB-Mu)1egw*sL3n6LG{Ij}yJ!RrD!Runr+*|3~K?!d6>-9&y<$wjbLdeOsMB{Vh~k zbA*(@m?4^BZE}GMo_5h$Thimsu)hS+>iP%@2WV zhfY?nIi>7tx`bu~!^7_Zo;zzzZQHFBHQH(A8a*5mIOu+YJ!Ahyt!KXf%)s>{W`cA6 zMTg(=UG#$=*`u2&x%=MlX}|r*vXAkEV2dUdHk8dXg>_HEb7q62*~$lDP6;XoTlA)q zvWlGYI~MUV6MZ0V`{kPp6Xo*2SJ$l+OwEOE(Q8QvF!&N?g~3V`Q%fRTvwjIGFiBAS7 zdSy0<_MFf1wJ>^xtaQhqdidugEE+{2i&J2|tIE-_NpjV;pC3xf!#j4E$kE4ub2VAD zeyMw_oD5TMCS%69N!+r0e^@3<#1#IQa*Sy9-73uWR#cvq;4DF&BUhkKZ7yIRi6)Gm zt2_cYb_VmgO$I@~<=qY_` zs}UQ||9WrBWdT+1u7o>eJb&hfdW&C-(9&YlLWc^)J^IwvR%ILxX#IKpoQsBP61w^d zI1~F{VM_YRe#%<6xVxKbE82BsySH$h?lMZS^pgcLv=&HJDLgjR@Z-6#+aOjtZt$QU zbGP?b`Y-kpOWw9Q5_a4?@(`D~K1IpA))2p;1sfof)Vp%cqFyMVy8bX!eXSiVW~Wrj z+sOXQA;$hVb8%{rKIvS2LjWTfRGTu^)Cy1r{@?T#IR}VgBWPFgrHxi^mPg;K$>klwdC+cpL0fy)O`! zK|P^dJagwXgm!BQ9qfK~0L|KWpWfF$N1#ThK{+hT+G_S@M`m#czs3I$?UpN0hikt~ zh(Z2TiAY3w*~Y(Q1AG&?2c`{O)M;O?`XLVsc~V%!=r`?e?*Dqj0?*7j56%(lf=tdT z5A_iYdsR}(9aUKZ1)QY+<)i=OloxX!p6)M|MUT}ROXv8S9Qw<%n8z?52&=*L1*n0n zUsU=9j~xMs2V`K^Uv@D4_|XmcQ~&9EW1fm7&B$M?2{OI}MkzYI1qo0NVJ`)(@=q}A5R$T^4&(g?ZlPhU-UTU_86||+L zSK;3rWm&NaRv{j-NJ|#MP584II4)Y=iuvLqSIv9pGsv?tXSy-w^!(k4c`uK>wPBAY zz&Gj6beg*;Xi`NDM#9Q+phlXnb!3rhijfmvBx5UBzzwT^dKU3-Gcx z_AgU38tF(@an65M_|g6%tH%8lRi6rcy*jt8bP7h`aF3=LQ|2~YVj#YjV87x9Xe)4k zG_-FvM$9+0Jo-WpFU0-ra(?WMUPgm$dDiR{w(fp`fYaNJ5e3>R_}e`lczLyjH;L0^ zr18tF;7*Hq>{m{w24|Fy^k?K3p>uD~Q6RlH{nWb*$1O?<$jDb;Joi0?(@NikJred| zqaOz~B?KSL_*IwCol#B;^Hy_DZ)!Ugre;q}L2}=c_QNp63uT z$WiFjMo-Jmx}OKTJO&%5%&yPx*dL^m%AcUYajW2io^QWv z6a2NTt8g=oA*kLND44YCjva+vIX?xRy2)s`@?(%1JbgH^Z-*sVyBdiWg|uOnIkH-_ z6p&E%%;k!!Vlm;SpNaK(W&J(@SN9h)e;R%SQ;c=MtVUiL$LYjv{-H=ISSNF_blDRg z;kxvk=t~r4h@ot={xotnpvkI-b7DiYv4hcbWFT)~wUB6D7qQpI`XgyueZ-h8|NGru zKxhs~mz4BUHX`j=KN1Dt?Ln;|C`(*T&yXlTcgQ12k7VaSD*H7}_>dr;R`}+U3p(`n z7XluT+1dr|$N+CusH6&Gobz)$q2Nbd<0=$v-I(xN7Y#T_X2~F2j2Dd4$hkso%)g+T zjJr!^`+t6b@BijBTQFe8<8fjz-Tj9Puc5_@OK@L~C0(KL}1`32#h=yDT+r8F~WiS1lo73wqp!FEttFiIL1jv}WmC#bAUXaNV zf#r^oV;pj9_Q4be2m}Wf9avl1;=qhI-K^3)9q5IJ=GK@ckb;2Xz{bu*DI{tTS)1;u zy2-~hC};hz$gJ={f8Z|5v%Yj@?PjY6Ws8Okyl8nDHYXG)$^DuU$@l-53VW@!PfD(I z3+MI^Y|kJ4L5ei2J$<*}o6QKPpq^AAW}v$cC!)*~(E7lt-74S3EQ%Ie7|ZYRVYqK9 z(O7sbR8dO6dnFaDCl8}JXJZzGjM6)a8hBM}{=J1J?isafae@tHej!2mxay*okxQ7N zktQXi`+Asucm6b-`HHJ4s1<0 zen|er1 zJ3#-(4ClEn|MW~$BvEru<325yjuar^#N&OF1LkLfv3rJ1RZQEuO7tJAJz$iO^MoF2 zE&e#`2w4|F+E8Qne?L6qiVq-WSHY>=x$*p9+gifg3Qmq`$Zi^g`~mfr2N@I6nHNmm ze)gmNr;l*#n&=)~S8wt__l@#DW*P7rsm6sy-6y9k)aau2f!pO%l*oqO9LFJ6n?qlQ z4*Tkg$wpyQ@A21Z2ic#F`xRNrM+SfYYIVN_3n^R}6;xGfWs}uK(S*7y;SN78j!!-f zqlnE`NsR5zcLP8$Zt)A)dd?m(-&onO(2MEbOY-6Bp~C0y(&xFS!Le^=@c%S7$(pfY z77Ge=dwfuUxgmIGR#1(h9wu)bBv0C{iee%4EH840H+)UGrVRLDHU$JsmYBUQtyka8 zFX;a(Yll7zKQ)Wl^7%YM)0Z3t92$4gss9;;$F@$7?=BO(ZB7P8=gs%{0btPmK@i1x2+yim~cM}T%6}o%{ zpH8%&-d-~f5oVi#6Zi?RJZS=(nuQod~*z3 za>$AJ>y@REa#HuIDz3XyAKliM89J(`DlZ(Nzkcs){NKGdd(!P&KTFfw$~Qy_q6p6W znGSLO#~E|ap|*E`5mh6N@~FiB`W0tk!Sl~=cMKq@_(n2OO;!w}exA#vsP1`ml)v*@ zXoq{$UHzPA$_0$Y;e3(66GF&4ot#}98d?DW*B$GZoCLLWjl~p%`D*tF%BSxVHux0{ z&n|@|RQldSe1Ez-;PeK&iT$)>0WTgyi%*v%hfL^8)IcaJ09!&p_d)be_=l7$mbAvo z-h-A^dG&g7gvl(|OzcshL-p)&c;8re2?3{xDRMdvH*Acd!q2su31N%>`)y4>h8T}h z!qhumHe}@JVcCJheL#aDyIheJSvMOrQow?oCWF!QGVynKr9Q}FjGed5rJiK<#?$ID zLyd9C>6<&VVR9r;afavVwiLj$`9@J=$tMIGXj5hv-}~Mjc{|7Sz&f$xi}DO1HILh7GQ z_M9~KT&tX!o?A1%zZoUQMGMrCcA5{>Fd}w5F%VRh)1nSF37d%KH=rna{rECZNs2Jc z@dXZE7%qtY8awLP^n4RI_|m5zRX0y+-`luw!!vRp}C1;4g^;v_$w;y&hLwWm_f34NJ5+(Ki?G(*L=4FL5ku8Qk zG$?&s`dgLO-l6;}THtzJ<~41XjVs?R`i3&JtxB?$?%-4x{lT>uxL$Pc!`c)N_j<%_ zbC#ID6FbgyY+~b(hNOqW;Hv@g>V$nfBW+c!5g2x1J`&0*kQlSUAOY-#ELt zSO6_~4)jvhJL3_z46is&&IZI~NEqaJ!s2#+ADt>HAP_79@BTH_$8(`zGpyP+qb`W; zcnp6?49DZl^85igi9g5j;3XAF;!Rd^Vbe5k(bHjo*fmS~WaD%PK%P4Mzv<2~ z3Cxe-_REOZHE8?Rp8XX{{M9o>S@_C!r8Regn>FuQG{Z3(Zh#y)b$g1A^<= zAWM@!b+5^xuE;ndqSWl?S$H&kbg|dJ+T;3yO>kAVx}$D08bDzw>S}Z!ESPRBr^KA zI%nEw*uEmN^jK_4z}3ztB77{-3wp54YYU%SdF@qmqF;#53!F~vZO1PViqMMR!?V$i zeUZu$q*hKw5T#qIQhgZ*WHzrY(%v0Hs27II0>kg}kk)5Th3{T?|5j+doo8QVne2@n z)1Nht;yI{7QZTVMYLdRnHdSM^Cs)2=tG#-u2==mK7TH%$T_>K?73zisp__hy;kVPh z4zr|uKim+QF!Or}$a>YhhhvnRL#e)YKkBF`z+*8tMo=973NY=qwPIV_r>9Xq84+CP zi4U&pah(OHW|_<-WL{9dG)w8iLG-+hk)2<`(3<2ana4P>g7Go>;J8wFxL=Uv+23iaNsEjsUBvMAVvNo_RT%G zH_QMKYeZ1wnv^XbNTyplPn;kkO{l&`1|M;ANMj?}nB81L%-fq_ z?77}zZ|Th^3ABUx7xcMKaYTkNt+RFMHk30=u>6Q4Tut_Fe0lv>5b#NjOUu=v<8M8B zbhQO|%5pUx*~ZUxrth~Q#Wc?g-)O`pr~L{G{R{|Dknb;_LaKIRJ8W}3wxWd4jzBHE z{jce;h5d0;&xd;Amj_2UO@aco($>Kl$1LxrJ+}WXIH&@rkWKo_^FjA zRoFT5RtFmRhe_alNsdm$M8DE4Au>BmW^{sDKA;9Mv6SP^*Z0M6SWWnZtI39#GHMhu za0duNvu+EFyR(*3Db*nercTtcDQy8y8t@?pA_?kXR z_wHvO3_rD{WA?0_xJA();-`IkvOocjr#ol?WIStn@?7Th&dYJh<8eY&|DNbR0WL+D2~t`wnV=pzeB zyP<)%OCS+Gm+?&Gw7SNs_1j_s>Rqg31eQR}dh+9(Kr6C|h$2?*%-DPSZiTC9)2Lee zBawe`AW}r$sZ3^_J>nsdrW0Sk`BxvjC8WhDB{pohX+o|~Y5L-SY?L>>&n?j13Lu|e zv`u%Z&KLVYdxe0Ir~3%=9~@*N2;N(XgR!h3UlU%KZ%hnLDN3?Z{hi_2N&aV)g@7v=#)y85(On(7lVUo3wwRnJi(pp96FVQo#imZ}6s z3pi~nF3WzI)p8hvRF0zl!icxprtOw13u?h%fByPl!36R2g->5dCosrKcnUpy1dIvK z^w$PY-@7fgJ;!{nHp-)JfmF8@nj{N6Xy;vPA-T3}+VLjPB$d~9qL)G_5GKf>@^o)J zYzo`ruA8>=ezvF2T$jVF`Y*~7-r1hHPN*-V&N`!TAi_irXGy;uUBXw{4FXMmC+QS~ z&=3$>dsva7DU^lfe8zt(sNIHo(FQXxEBmmNq^3#zul6$cr2`G{f}jDH&P{^lVp$%k zm7G-YngLkqufI%dE{;7mi8ATo9*C`nCTx)r-XB&Z$OTIRZ?5hy?r#+;8`!lSe+@Se zaS&R@veIiuArjQikJ#Lt?Td_G$1p8@<5y5dct~MAQB?d_SrH39gKk$*&W_q#)r*=S zQZ-$}%NJL*Q0F)ficJ%gqy+gAS>ZR(Y(QfASG|>U3Bdgoa2@LS`5OiyimHt#LZQLI z;JT=`gEiE~jl6BCZSpf-8D*=gi!``6(TdYnUA|DkI`mMQ1JyAMKF5BaZ+F+sDpF+CdWO}Ry1=*^=2v>4H z%SelOalf88v-ep-4uXsr~00o>WMa_@yl!}2JJp8{T34&B!iKPD-nBWPS2;mrc z2>=yfPr+vcE8LK?MG7d3#2ar)9yhN{(MK#pvDY@+ zU=cnn`s9|>msNTP*#%onF3hP+q|gpg^e*YUpbYH0#0axZRJW?8T4i_nnq9SxgIsq? zL^kY0#L1Ev0G(|xm!sIFBlvn_WZ%5q!YOOq_Lb9S$Do)FEo#KVX z>rDbJPG+@x<{8}h2EIY}mV|CdX_vw#(9C0|Ph%`o+dJRl*5B71_i5`P@g1uTk>V-= z{UTd_{~Tfj;HR~*2KS%bgB5B%yNV>qW!dO^sXMg6w0DR-IV@Ivb?A))qxeq)6;tzd zx^9GL5In_|5i7Y*#w9$sI;I2k?XtD*%HEnzgyR~XozqKHox%&LUeNY&QWC&sTw3u7 zzLtm`f&vb*?Rk_YkLAK0M;Xffd_RucZ&Qt*y1j&Qa=B4`zVx?4Kv{o552w|!^}YnN zV$PY$nhKbxR#tIogyhw9T{f$ntp1hwRJp1`wZR&Ch#VKq2zEy*4zd&%o*uGm8E8Vr zo2wkP)_upOKZ>}BNQUR=x*UYnaJ=~;-hnIPn8ZiF@}BHF@km@vl7_b!@bw$szY#oa z=ksFVwFpS%o2YP_KTV68rh_lS%-PW{ES!9_Cu88L&8m2Oe2m zYVNcLnySJXC6?KKnla2ovOL`=#Ls<4+wyj2r7I2xgyJssuq8M4jO<6OB$gbBK?P>y z!3UjDVmr1O`>D-+Fs+eVDXpEElwIMDi>|nqK!MUtf$LuD*A$j2|A!&&QLg+xtQ34j zBQ%GuqtXXed{_>rk#4FR_1|(gvqbGPe{@1#8Gq5GHLwQ^yefyJ%D(?MyUJKW z^DnZ}bxuIh$%KHM)nu7FN4yu*iuTOWvMmF@!*ZG{=tB_T+(fpsVke&@{^0%3_`()u z`Tl@)!J3H6FyAm9{MhJ;R+Ht0ry)W~}Bt1!SH4wet z_9O3=L|oyuYDSF!3Nda`KAxX#&mYq_d`y&&xdjX|@@%~B`NIvobIkWz>fu(?Pq;W) zMq%jp{Ph-vpiz!hAO2Ip$DI3{o)GMsTU{$A$ioq9!dJK&X2-CN^GX79V~`y5k@471iM_ zcXk<16fbMsp^8&};eE${6kTIrU271Gtu|_GH@4kajcwbub;HJNY}<_+HnwdW@4WxH zxj5gqJ3Bi&i(VO>E$Fjy%j-D#ajof{AYx-)g*X-CIUI1f!+f}Q2S`N2@rrQ9be``)E=KXJtr z&XrVfz}b64`a6Yz2Qr@VOSp+kYf)b8;NBdGuO$E@iUZv~uzKe5YdBkGhGluUny*!M zqwViQBCqI3gSuclf;iBa+XA7ea-fMGr2fyr95ugKHWr7Wctz$r@6Wyo2{Tg(m3AZ_ zxpNO^;Ld=myq-oyd$2LksJ>zPNQMBMbJCL05B+b*K78$a2|1g{e{qgAvDA7Z5=*v4 z65XTf;>KM}inA}E*QG=@QBm%9K$X+)s#{)8f>)z;sLYeffj>P_%`g4eVdznC+Lt%5 zD9QXM1S;B`$557zH14$1MbiMLU`T&iUgTKzs-C)M$$=Po4wET&w_8ovr4rw>q-Q3~ zH)-8L^BfJDNll}Q;X80syJ<08>4-C6*22py!F{d0|594hlvrzuwOiOSmlb|n{rsbi zD)nke?C)~CFw+4DvkzY&+eRq+i5ug`$ZYGe`Jz}9kSZKu?cN!l%R2;&Q4lEcl0W_~HURxL}!?PZOJ)JTHkP4XFm(%F=by_b&G{B}hc zsP6*P6L=CNp~E2W6KhdliOc~ab({c~ZJWhbe@y1vezD<%IZ&53N7wnq%HhRKsWdAO zU}N`O;#bT1%7x4n#&FlEM+kPERpSqpJ5JSo`rJK>SN11|$DzV?szZs1!I@i&#}G)^ zZ$)?|wxPv+I!l2T=-4n3b%s&+GG!Em+5#CogA2j*o$DFh{^$7Cag2>te7#~n2sHB- zIgM8-%tj_|<WY%@UgRDfspa?Z>68GU)WQ08u+{;J;bB>Kyl-7=>j9I` zQr==r469k-Ov{yemMh)(n%k%9Dul@xbR=Sp| zTYp1~@^SLFsWO89a>2W>$4Bqm@E-bH^ofG;8S)j|_K9QxE}kkRKc%-Y!H9!zR~?rP z`k7rU{f+NcR6NRM*Y{;s)Oc+TiI15UNzsSHERph$dLUO|hWDRP_*?xU3hjHw7JCi+ zJ6f>37&JN{D$QM{Rfw{>ztAGn3sWWOId9fT>}()_Awj&JYn*%R*y|$-0rS{2L1=J{Hf9r z;$_h&bU$5}v}5)~^M=299GJdYQ@Vb2H{q|S-{=}_FbH4x@Lp7S1pndFTTZme_$RSN zLBm`Dr&*zLcR@QmTv&04u%*Qx@T_`how_*SU_<$F*zR`|m1uAv2bnK=SpnDAM!^30 zZUsAXjJI%%OsEIb?&fy*yAc>1Q5$bvCT-!k)LuqrzkRgoUl^Wrex|EudfvM~!mqnu z(h3JzbbD99Ll2=|Q4i7n&n+a!$#c@p1eMH=nU!{ulC^*+&NR)EyvDo-Xus_wlLEqEU!n!2aeEr7=LpW*eKisXQO6)r839-k+ z-}tKF`hP}xS^e=EL)mw^0Utcrbh+QZj`J!}s+9N9`;U3y#prBMLEdT9PL`?eqC2LG zFcP3x&7{{^XSiXOj(j+Rl&B$X$!*;h^mJfQzH7ey+58K3BT?|r_VpQR+vo3D*hF9~ z5J85{iE=u%%z{eDd9k|ZrUMi{a@5T`lzY2&C%kd7>g&wk3x+#ENn0v^NvbrJ0MxZt z_lYI)b!(-KE|cWaNgLuv_nG0vI=7@p7ooQ|+?3La_H*QS2_uX{YvS3QAjtJinr}Zcwd3{%Jc{Dk3ArYOc?I7QJqAGSE~lD8ZIx;hY>=aXTQN-63DK$=f92 z>q5QUab}W{p9chmDeRCazr1Cudf23hwV^vPY~Q~_eL7F*Nb0?d0iL8adAg)bvk)r} z`dN0I`H+av#w|Rq{=YS7`1%Tqzj|-A4DYc+Qno6aD&F(+{{Q2;vR4_3QW3Dp3dW<+ zB?d`Xq0k16_lv!b-uJ}Wnh&PD)HV$KmP89fLT#;?yW0g-b{XqGTrwzGxT|-Iyw-eY z>nwHK==O)t`iEzilAH-MV#RoO&vycC0P=G#u5$x=X*WsuLt@vydK!*37lZ$DXW}Vx zWk(q_VSY%tS80Jv&_~on=>(r(pGa`d+@!C zTz~w-`H(#BPLsMrWx$)W!%6hZKxLPU3BrZXb+?Rx|30j{N z6-Y#^XeE;nSn6&h6@?DtYsqn}OElO#$9_1WVH@UD1SP*`)%ZX`hr~^<+*>dA4DIMPsQ~jA$}Z^5 zs6fPid7jyUi%I*~5EVY>wYpt=wI*?i=Y0$8*@;(3?{mxU=g&QatL8RyZSpptLV6z= z?JhDvm`>SDdbxpwJYz!G7Fa@qlvmj2_65-oK4{%n0e=GJx`9y5=rsi>92n$0rs>X} z{XZ{<&K@2YDbt1soU^G&P~H|mXkK0>gv8O3--~P?lY{IY{P##TOh!t{qA@Z*mK^jT zu@H2?Q%#NoZaRDWIhfP(+Ea&EtyK-Zb(eS_4rn0B-;dVz6!L+Y&-Y>PvA<2e#7EuQ zuV;baOt%@k(lR0fbb<3Z2-#8bxXO4SFj_4AkJ`9^Z;|&bVyt=0wIq=malMBf zB^&SJK2WVXRC)Hn2K80N_Lra#6@kg2+`^0IZYY*+NYKY zC6Rz!7IIP%zu$`*x}?s?&ck+r11qO$?u5@p1yBH&O3!W*MhHIWAGl*4BCs6{XLYaC zS2;`f+1&Em1_Z!ZQttiU&!a88DZGn+-Y#ni6Q3T1j6`N&eI4_W+oCQ)?Ko&ZnyV^Gla` z)JoWaOkDxY$xV<=`c|uuURfde{{d>Et_Xk870E%PQ1qBukYH(3l@(sPlzh@<4y{!EXomu|g*Y?rXDD zf3;0MXOQ9_(%yxvIY7ecv#@v*zewuf5@t2TGY{L@NsoFFLrwf0pS!~(=%nuRTyI6O ziVdE2VtI;Si6@x1-UVLy=kGnfqqFrl`9F?eK9?iik8z&_*G~!$%70}bUPV5Pc4K(2_z?LcaBjQp&+Fy!Y@6nVT1C(6`|C!U8&Ov0utP;-$(s&9;&kHnRP25gPax zT+BQ`QNM@2!fRi|oR?0^r7fHo7lp}(z^{s->_-Xxz(pUfSR#A7##;&sS) z9xw})Pbd#;uE9|3A(?u%5)(X%WB7$r;!75T8s)^47F9>VHfbjiF97c0&B&)YpE*FF zS-0cOm^r|<<(uO0F=}e5!C$dMHnJ=PSFg^h-NFHB(n3{|@hpfSf*HMYRk;cnn(6D? zjkG3Az}Kw(lS1|w0rRg9qBhIN4Dr<-!;?=(ISaC`Ll5CWe}lV&bAtOnCeMeFLKeS{ zUxl4AHJmCVAJuhBTwf$}>EJ6Z`!u*i;ym}{w$+H9?&sBh^hZHy69Pe&65EHRF-kqa zLU-)E@VDHw;~i3q%a!*PC#}U^(T9G3PK%$}XI;%t2b0obr|Y8sOT)#*H=MR;T&6pa z<@<1pi$jAq$-SW=%{GotG%e0z)cf%9z)XQ6!j&w$n}T`C4(K~8Z};GM8qDM>gTO`c zbRT12q%z^zpcu}qFnJtnV6RCeZ z`=QU7@yt`<{gL{S)870TGE|Ad79)#5rSbz0k~9jx&g|E2D_Qi5>sS|KHk7`F>7t;0K4j53kwsyu_`s2f zz7t4+?4cRod8OdCVoTH#E-h0VkWpw7Z;i&GtMo3G(JlH}qN(6m4=FK9e1(O@HNRne z8>n8rb$qqkaO@?St+J@$1gu3l^`CF{x8NQ2S)zgeCj9jGV3s6bTRq{ZVY_HI8yYB@lv>NEb^;kHy`Q&Zu&*jg#rWak{tzbf$Mj|3xQ+ z@Z!8r7H<{;VfoM z0PvcY&c#^J*pz{pe-jk)v)+4?DY(nWXp_(c{gf)C+rDW(oyH7VJ#ty}crK6L^+8>X zaC8*ysW!_7jy*Q6$5oy~7h&JiwWz6~Z?aesAq+MeeRi-fiM@zH2dxDy#3}>F$@b&k zo^MPVHgZdRV6Yd^(Ki?Vun|z{AqJ&5snSuDFeh#QqwD(Sq$3bU_cGo9uo{!Y=I6 zJQ`QmV@PoVLcN>Y=?t`R+O@$yt7nEp9jg z%FHZ>2Ze@Wajr9|E(jLP9q*TlAFu)VRn}jc*`?7kCLWfDEM32rl37b;e^#DPLg=qo z&#n#3!fwQ9ZE*5D1RkkG@_GMh276Uip8Nj9f)aD#FhT7IR2Of)9|z~bIM&{E-4w_D zWrAD(eq~R)&2s)W+;nBED0yC52{y0aZKCQu!CyTYTyR`Vh(=;;XVb|BLzIPXnMf%z z)cD*KZ%#l6I>pX?nF+NAYg4mrx$Oc2U&5_+xW25w1sshFAa~@}62CimK&knPB7y5#VXbGp6nrAe&J|~d3{`v1+N1`W;gJN6B^P&nOLas~0 zX!~~*ar+C_<-tyzOw&?ZjS^9U3<^%<-g5+?z^za(o@nQ7%HyL~pmq;Na_QPX&SVe* z=T3J-X2|ykt9Pta*ugdhKN3`{v_M$_6m(NORh<*w{V?iD4E*iMc_>BbdZl_zi2ht*pMDU;y*5^C-TB~S zq{)x``?!^CYKG^13UwyX2(e(fxCilxKdw`UQHB!4kAnT=)r9n_JjAG4v@CoTD`y^j z_3>pbq3OX?kJdO7Y!he@VuXxCq<%PA&jCaB;ko#r&&O;OE_5i3+pMEPBDDol=9>$3`O$0AbiHhsa@+Wd`a`yls`0$h~*sG z)AJ(aTkPo&eq}kaOC&nC3TrHEc_F9S6D1FJRDhCUXF$P!rW3KbmCjA4F*#HhX00k( zAw~GK3Rd4^GX-MrSUFmchyZG0Q@w-%itBU~Kif<;h&+2+c`-W3v{VWGR(w47j(g!Zoa!>w ztHyN`Vfok~-g>V460Rw$NJQLUG6kMM9_MOi7-lK41ozMT-KWDtLf#u?`}++5 z{P-laWIm2bgF4*ttAf)}3l{wcf%oeDl-C+k89XEE#^N+}eY+FeMmoLn$IiSRg%yBl z%2k`}=Zn|@*D!Ri&gUnJ?@z0EtUcsg2K#y>h7@`%PKz^XiW_R&r8#TaGo*h-hu;0w zJhxd1lo}u|iXA3!2sOO@$usmj|CSTSD4)n>;`tjlWZ}!WQz`|9q+Xzmb^xhWA?9Gh z*6w#;%&iS3{3wzGne^p6{yU=K9GUx-xin;R*3t2x^M;E7T7HGGnG~Q+kZ05#kWT`a zca_L(6%d8(L>9C*lR}N`XMJ5r>Q*=2WPNj1iw}m^Bku%5346SMsRQEe;cks892;$Jp2sg0EBpludNo~>}$1Uti2A! zWkf(3vfi>0PmBRs@wNFd*$|um@7yIj9{92xyB!|l4@U{Jw)~PwYi@9@2itpBB-L<3 z1#%wW>L_6xM&@%{?6%Pn<2YlPn&Q#k1v}U7w}^WndZ5lAVe*To^#0A&4_CW<2x@48 z5y@0AN3;6nhU8fG)yA!5w6joqH}4;JwrKbN{pyq?vrXPRsy>=#nH!243j_1qAyBOF zN61TS?B9)!{iTX-6r0Xhz2#mNcJ^f5$S>um#5P* z&E{z@<>HL1jAvPIpg4aNeGX6$_r*mH6FN_W-%H0&C<}hwqo$|~p6rIb{u=7d{)hpw zC%f4NgIFwkHCCV!`{<4X#Dd|f8`&KH{J?1S#!Rw3PSN9ampI&Qk@3_-iqD@ZL zWk(UTA=P<-U*&)!|8q|igZhKm zruG<=+!p9NU;4r)hc&{Pb`|fVPcwFiUCPr^;$!v|odI?Shep7JBeCn|Kj(gfsg%gR zJw{+wuVG!*K)V(XIsw?s_`bVvfbuGNqN9V^cNI^kF8Lg*J7=}%U=0ZkH@3f2xuWbK zfkKya&Z@VnpnYE^usHYH+d{{KOJ^?)7rn(VzISGIHeesRQJ=pn6zus~rQM#?N|qYx z>b$wm2U+a^xZ8uyT{SzjiU==ZpX}!)0DCTvQq|-kf}XS0mA3Ym?ITFfelNFt zC!#G~<=yxp{VPboFE#m>_(^2zdKNain;N7EVn>Pmd7?<|!Ghf_1U3t>kl8Q4k)bc1 zU`VAF+mB{3i1@0ALNFKVZ3%O`5sJgmJW@P)aAPrGd~CH~z33P4Mu{ zc9?+F9&yH#xi8X5wzvLYSLzri&uS$3nh?%FDBpQ4lpG{Jp8si>ucBdE?B$Hk${s`g z>SEyxZuI{`C!$6P&mq2~->xt}gCr4<>^pSU9jXKX2^Of_F#jwtn0_C4XL`|I`@Y%y zO6n}?D7}`^cX_O4uj{G|@a8Ym&+gfmndf9c{ha!<_U?fYx&RNgVLE&+&u!sov);O# ziL10?LPR_y#%JhuE55Q3cl_b{rt+gR0Z^hqee$$bLQryP3u%7_52zn&d6N#(Ezfbxngg9* zP;LKx^~Cg<@ziq?%n1T47#8fjW6^MzE_2m84LRXYGTz?_ABqE+MwI0-^WMNmqUdwg zR4A#RoBuEKF%ItP4TGJ0NVQUN1Oc^UAm>wK%ZcmP}Q)GELczJFGz<~k{M#Tpk*w%#=&qnwm7 z)E@6$(xzWcZe@c|R}6fo+gG0>6VR8S(5G0pX8`NNSu8h|qj~#MQ`~FBP)yLmc2YSQ zIS-9%GT)R5wgeC=pHZ=-=>P@&T7hi`&yyuSwZ)KqNepv9v}w8LxCM={X|~eA@=OrH z>(*v=QLXBh2NR=uL=s?w1Zq>a@hT}Zusb%Nzb3_{J~TvlO4E|OyBGX|Gip7=AgIwX z;P(qYY>yEAZ}$IWYiHzQ;|C!tqKbUw%$z+DSa1m@AtW^y+KHX7=2c$II5yKi7zTRF{m zTnB{y4{2_kEm5C@woe>~xaxIFW=H6yHy7i#C{tQp+ zhXIr^is9U^??v#O$rjig&&*)%@k;?CV(cUf!;Vj(wy@2+Z>opx&KQalYpsHofP#wU zyaKbTF$QJj;`P~q?JOkS_<5gtsda)~+<7db_jqIfR+c}qp^nnNFK1U$06Y;%; z+s{1=hirvKybgMl)Wb0w)R1?Q3#n&&@608*_A*M>Yn?~uEB5mD)u9xMqB-n27bMR^ z9bV^Wh4c@+yGjd?3wzEJ9c`FuqP7+K4cuQA2B*RL z<&!DFLz#NB?{?TAHye!RyIxqiOgk*xMvbTeWh%vr)cltqB!>+xKMxu$M87CwuT&Ef zWX2_CDB9GJy0TwyBxlXIS1(M%TxHV0>9`5=hb-oubMFhK=Xn=AkyLE6N)md@`AYh8 z2PCKW6ISTMVWrXb{Ss5LjmlFnX&aE*mV~}&+LSLGurK_pDfxOFp!aX!z_&P1QqDSt z8ujE)xBJ=PsEjNI(};R^>5*6;f#+M=<#tM(N**KKN1Ik1k!<+vnQ_>{!PRbtZ%QqG zrqjx%^Xy92#17RizcF7Z?@e7|i|VmY!C z0zf8-v7hEGC?IQ8*%(>Y>Z4I6^Y<*cx}n@D`1)&Ja7z*AI&@xX-lj7F>-IpJ*MF%1 zjkLMDeNf>H%1f}n)haAvHNRbxv(+3Q8b1v}*V{1Mo=wdULUeu-jelk%9})bBfH`7! zG4m(xN^kYmU+3W{STM_!nFh~nsyfX8Wuwu1Jh!Dj`2*ez^Z-RfXBd7Ua3saq>@>^d zg6*XCa}fzlhvAik6EJ2iL73lkFZzDahjq2YE>aT95o~mf`g-1_{9l6{ErqfgN3UER z{hggf5#irj&uvRA_(L)9L`YlG*X?ztsBrN&7t46-J@!}JKnl=+P4!Jmh8{2O%apQ^ zX)+54timKQX{Zr9Ih`_=(7~$Ra#Tj5Rs@v`(}48cq*z*_Q)@2I=N^d8WGbT?-E zh)cZ&=a$Y99}uaq<{$A3wjQlqW~joIfa>v# z#f0G4x-aKv?Fzm_07M9?Bp_V{z&;l1ztZ=fO~J_8>}p)EYLwW-H+$RDuc3UI6&1ne zT%#iT0XHaVF<6 z&!>ABRGWZ>|0;d;d)+z=rEt`*O)r|gTQG+a$LfbQ_v)QQBlp=nhlgsdZ7Hxw4w2`)m!A7 zfa#ENOU;7&-Z%uP`p0xUm1*$d!rt?U03(rGrT6QR<;^8!r8RpI2#bJY=eFr676Nw@ zbW+Q$c?B41#)H&LjWci}5sYN7G?_>!d&1rK6yzns+$41SaCxx#ngNsr)^H-jZyoqqGX#K1RS{rB)qi)!qc2|M|75+PE$A$ZO8v#wx^j zAJ{DNN=GbaQ&c#ZY=}pn#q8cW0cD^3R&TD)Yp*DAQ0YG>k5Cv)3`15ZXMmPAKg!8E zj}}s|SgCen!2XbpT+A434+=C_pV3Q}mfZp&dC^S`X~+c|jP3JNw0QTv!=Lht1`0-Y zl{jr!U(gRS%pE#vaB{$XtglX(9J0pnvM4BqY2U3fPgiJv%P|&%Ef?D9+U$mMcpM2I zNYE8u@<*rY7hOCE=;=G@6o<+dB6y}#C@dHH28pzi^R4+a4|*5R+zg9BN(4kz=GQBN zv6^G|YxM;f(~|fu10!ZbQ2=^739(IkLLoSEl1Tk@i{lf(tZTnp=|lbq2Z zND!`3SpFI5?Q5eCPaZ8L<77;Q*GF4{Mx9t}7wpbM5j6{{W=SO9YM1PxdUyr+n!?R2 zO>C~_KV>nD3hFis02oNIVVc~=(Sk^N#t(i~dkNG+rBeU5j{j%ZXwt7H|EG;x=u>7P zXOh8-%<=$tpCz!fq>aIe|1lT(lEKxbK3%%sxKH;qM^OvTd2C_T()AW>S@nnF0XbTT zd8VJ0%d+Y&$mc> z>KJ3dh%f&$;``KWfk6vxG`MmY#$5djwSv!*v_>H-kh{sghEQ--mQNB${1bgn>*dn-mH1g z93T^HzxB{>I&hS=qT}NS>voX~d?>58N35QZt0}6!7p56wU}}}1Qm8_FTeeH7CS|q zisVp?eLwaJJ~}G;GOeeZq2%HMSQglm^K;M+V^~~$S`Q6ULZ=UzR=@4zl6pLR108J| zg6%;Zziz;rLvMp`HvUQrG+Rr+yR3Qb${~d^h5hk1Su>%G74&=mv?wz|bRz}D-t`6S zrlH6`2;Ta3U|)t*_7VxqT2Poi`@B_Bs9La?iP;xui7hb zo}q1H)U5|Xftsd;*34%f8*0XnXCBUTACnlZX=q*? zb7r{idw3l~tRI9K&@(%Q?G?i0OXO7zr>VZ|B-K6|FM}#{Ld7GSwkjmlLd-AFsj)bi z?t4XTRgkYEY>GQ?9)Cr{p<49bUfiP9xa&kOSp_fi)dJQoQ%y#f8UTLcgPVId=1cqm@{{_DTsBBp_D@A=c^FL4M!ZK570^G~6roG$ z9v48ar=?x4;z><6J&u;u_^1w;CVwIt(7@@Zh!z*Xp^YVOOqSd z!K;(iq`Cyv;@w|t-Cbwm^7HB1c|~hQnU_L(CBHgah1?`A8Dn&$SaK#lv6!tigi`to z={?Umza`^&SNITj_U*avt8ew`fcuEA!-6Rv#aN z)5yniBrwgTcF&Hc{6CuRBrD9^9#?YRSJ_~82sahyS^k|MT2bgwC1LDTc8s;pL)OE& zu3dJl0RGMO(26+8E8Q_se)9^aKdY;bp9ulLde)}bf~PLIvApx`xyvck6ks=%9Mwa` zz9RVTu2}IAF2R$P-??CytfqxdcVC`{`nL{K{oM-*Xf21|T&f-38o&ajn@QPYW4}$8 z?M+c$O>8g%3v#xx$Ib}S;?45&wsFnK_4foCuPGRo#)Bu{Ju_Co7s;u8({{?e(j+aR zOM%-39TH!bD#!J7{!8)KKWa%F^h=xW&qP-j`N4A9-+wuy9|0os@8~#@Gp1l;LAzhD zWjX?@?hXq?vUB0d&RuF`)S)!#Ew@N0^X4 zJdQ6#;S$`AQzF_E?7-HCzN9|sV5o!03h8GT>3#%jkL#ccYhWkgD>v3PIfeX zuDRj+ulr_acz5RwsB|fT_3KIAyS6}?7%4#nm;QlywFTdCo&k?s>feTEK9x+nrUI<~Z*VhA2I=)ZgeB$j+8U$gw0KtSgm3tEebuV& zk@r2)VVqdJ9~tFLN`Q8*Lj4lo-88Is*sz0zxG#aCCxz|M#Gq0BYW4O(B%qSnwb@x0 z0zM<#WUOOa47jO!+#`U&=!xGp%Rc_&lO^X;CeO2s7jq`u0upcQs{u~)^gyo9zA;(v zZvojpX)i#~_j$h`M#GXM^ou=(+eMH74s*g`oevWxW>goun-artjB1^_rz-~v)3iOc zxcz_eaIraFB4rCyafKOUduzSu^%_82K58j zv$h7TVjua-e#PslcJ~!x3v5>8gVJ`LHg-kruUA{5N@eoCe+9i^&QSmcXlC2y4~3Py z(s}KZr?Z4P^2=bSDOHu3{>Ar6xV{o3C*Zj+REvs?gi4dU{01ljoF2tfxmV}CWojhx z5le3TH^&-#mXU5Ef8p7wcZYKraw5H$rKTks%FTG3PPP1ROi1N+N3(Hn8uY_-?01lP z)0S64J02stiNTvt-VV1TAwqpjW`(EFl9xxkC}#1fBk-^Z-w#;-xq5(idXSYr<|Uyd zda>s=Ft(%R{`gAJo+49wZh1)HBamPq(|Xl%+kpe>Ilge% zcZ92o$vsFc1|L){rC5t}LeQ!8O5B(33L>aGNSJ-#-ezG5!>SWHy7pM-1*cT>_Z?r@ z3uOd(4_JtCxY4U_HQ;AM_3Seet~^EoBXr+ATkY)km3TbJUinLV#Vo&vQ*q~o3KJ~6y`_?uUxl4S#7G^tGlsGbGfqPnEOg0cLvhl&qLw{o{{T^ z*C*bQYZ+1kh-!~@0?zj-{pke2dHS{a12r2<2eO25HT9>=F|q2Q%BI=A6KVH(xbJ8` zrOiJ3&xE@Yw%&yrS~rRy;8A4z_sjV&VxqMh>W(dxoNw*_862CN5)ZknUJsASEU(?a z5wMTWCWO{PtYOVu0o)Ip<51U@>$t#KhEjDzZ(({z6>_lk1VQ9BJRaUj2o1GlIGx4v z4p8HqLB2<=jH_`;O+MmAQqO#8UhX6%zV7Q z-+c1auc^yvodjTwKSbWuHxc)#2c^RB@5@9SAd}{MWyyiH4TgEs4Z7kW{Ua4QgaYzi ziD$9xzlS35RuToJsS?<^M>hO6CVe3t>5Sx;M#bQD?qb3Gd{&qjMrrOLuGn2r*4x!B z3055q@p$Eyo&t6_i@I%)>_~dv;5g-e;R1$`nFH2D4D4uc@zkij_>CzLF>~AR-%r}2 zGZbAv3dd@4=&zKj>eJrRC$7dY+d8(&;h;U=7M}jhnz(+euC{mXkxm0r(cfJDF+XmT zr-2#b{`1)HKGp_TP5ISfY3%-)%>E@oLeA2DE5bG?LA-_2BA5Lu*m9qj(RDphN9rn2G|7^a{5A+Ug)^BYJ>Zx zC5d}sk8EqM#7K(Y0Q+%|pGz6fKGKFlHXKUaU_3Gw_~Zu2=6a0h@XR+{z~||x1in{Q z=QeyKueWu3iYW#%(35zB6QfS;Ir1B)1hbRS0?D+YlU9Gm8WLJY35@^?GcwM&*Z7^ZEt+TddQvQxt0$iY z?dLpckz+bfGWJRWUhxfDKpBE>{ew;+Q$Yi8c(GJgSp2Yn@wipGI_#L$?Ja$(*Ob(u z?R$RLcW`hZY)9RxXO z4bJ}of|#!BPAZBMJw!tNt zqgB-sVahzELiJ4VM6efak2K)B&zgB%ZGNr^zKH^jizG^4I_;RZdQbx6a^=aGQA{Z> ztQJY;yX&?P5~q^1k~}j&T}sx|_F=zGipTmL>EosIXDHP0_yPi91~qYIz2{a{iXa&G z0QH3R%hcB^Pu369#|zW7gj1EHixUPFVkIoT>x@Y7#4$+9+%6ibC{C7A7UQa=d$!{W z7T(f4?RtiPO8-l>Hk=eeqqsawK4bNE1JO{sT3OAPp6W6_3ZC(J>FWsbo5eRTqc@D; z?83oi2d6T?AYjvN46io>WW}L;Q1rD+@5DVXS6MbOim4M}o8@dk)uaSFgq;bsWtqpD z4J81$oLUMBod4-kdX!zy4t)sYrfnoIVr*^6MW{XSVK@RzP1P3@4I7HSJ4hwY7Iqe3 z0KC`Q_2r4@D_c*?qE($P7SGxwmpEo61@2Pg+g*P&++MGuA8&(iki&K#T@TdhSKtI5 z@&_JM0ZZ+`9#6CVO{9Ttl!W<+(6QFay z0cMECs%Il|SubG=!%f{L?6MH1%oVl8^R}g;Nz&m?GKqlQonUK`4hdkM+d*I3q?!lC ztJ2~g-V68Yy;bEi`4^8YfsY#nyGC+QWy6%O!ooAXBBetTQb!s!aK?}8`z3O^O@kn@ zH~t>BOZTe9COxFzp$u98385H?id{ zP{KSuo}R=Xo_95Gdj7^RVL)_lD0J2~n5q$tvcvj+TfMn|jIP_XSy&{xllV}al;Vy{ z?M5UkX2{ahLPy!H9GK>ezJ42-6V3>93apG?F~E?vADy6)bwM03#tiEe-v!}mHS%~_ z(m4K(^n3JqCpu&OYKv+<_@g%=Cid;K9!M}b?WT^*Og;z^ys&R+)UyG9{`4>FffA<; z?7}}Y``0k`1ZCJi;~a_={^TfF;JU?wmj1#!~mXP;6ONO(IxLU{?u!IyRn4!XWyK9vKyngxRh4LT-J%1 z$ke6a&fkO;(Bn(>tSmtVfZC%OFR2OGh?Xp7F5d=hC1}Hggfvm+DDB`;H;aBSCB+yn zSDO%A^#PWl{s9Ddy3)%{a*YVUJVYRDMlhd(v#Pc!t6C#QZls95c!L&wX_Qf>0|skSlQXiJG+{ocdzG3mgAlh2o%-jS)a*YY93o)&=kf zb5apWxcg22p>%K$ZqvTOj(o)(Z{`ZzXIXt-Zn`s=XFqyVkB(o^v{@dp*U&EK#Yn^R z;$%!TyijCk{Bi7AyW;kpe$t-1)AZ5@y;<$Jl61w(bYk*K@waeLry=~v8E(_J0RY09t0c(XDFf!L ziVmZm@}-y6_}z-GKw%)e`MrROXwP`@((B(TF((2DgTK)l4Y!{_Q|&TIc`+Z}fs*O$ zWJuVt)bed=Ya|lC)>+8#`Q-^osF|0wQ{!C?Yh|sfbJ>Lc|9!57`-M4!L0E5dEkOBJ zgw2Id$lhjuleFY0@V&&a{#$0MC_}ap3lh1}Dx>oMYm^DStm)tVj3D^lnh!ey)llKS zwl@1tY`cg=Sa%MvRf2iHRNXe-e84*x+-mQ7J~5156aJM(Pfn zNKZ6aecyhtHmhlUmAD4Oq_!f$dn=Ry2FFJP7$`o+5tt%znYdYKQ3y=1YSfU2(YI-M zj5;_bA@@p_iS&7n{`OI-7AT+Q&;r|R)c9!nPG7X~E~;6Vi&|SDvUn{vDLyrUlYh?s!HQ>)X$F`gh8R-4oLVs@Kg zbq0S?GK8f>KGHgI--(_GB)wDtfeTh25R@RirKZK;Odsjt+Y@~osfh1ZY|Z-l4;zjJ zy#F{l2ZuV}K8$DEEqlw0OD8XD*|u$S^~-k4ty;EiFWa^|;eGc01?QaSIrsh5_5EDX zqTfvjgqJN9XorCtY9219{$P)-r)RP#!3~$G`Mk{4;rTyC7j&f5X69}QVG!1?9Z^{U z%(F3*6N~0Q4=}TZwpQWC5v*an9Qnr7Gia5>)ENns9Rx7J0n5izZOvS`=(!|!c=y-r z(P+?%D4<&PynP?6-(n>Y^z-XHj{fFzV?R`9Fk?WeXEtV8o+cIW`n~+rr`J;R>6@^U z!=*M4a7XoJy4k6e&xC|e<)|hRn*{iG&QSI0(Dc*j_6_)XVK@2@@G~`Lz~p|so4Occ z|1)>~v)Yyg<3>BY-880G(1d>lL*~Uaf0OR9-+%q!Vh7o%CpJ=;ag5=>BS%G|M*vW0 z);kw7o$)2Qaf+ypWC);HQO7hdUlrwFk==b+bTY4w5YJuf)7&Jt} z5CGOqkRHk4x_VqrK^?437wggCLjO<%xvfly#?uY7LORZT6{V^nayL1am|<9N?by1V z9k`c0$#B@PeV0=`!}F+4clwyfLxAP!>hho9VL;WWN?bwq5C^`K#K?oqf4>0JuIFj* zqPp2D*IttziEXFeKmAc^9o7LtdddSOH=7?iU_?*LE^1By*<5l`b+uYJ8N>k>y9^S5 zvzUA~=LeT2RXeqf;;qa_=w7a}45l=qd@u6e*#D^nP^8JY<8nedSmTxXJ)djHvycsL zO;-4kxYBD-u^#|tz3PfiACo+Sd;-VN z2h7yJ_h8ox1A}s{0^h)W4dooeu{ikbNIR2` zK^>6oqgz^4w_WB3_k_j%EZLmviMH?_%6s@>#2wyz+U`K)R(tW+u~D1)XiBT9f?67Q zwEXuYn)>}|h$(dMrjuGpp~vCwn$eFe0i7Y)W25ow5YHnW7)9P~Fyvk0*X4XwtALzk zli>~(tMzP}eS)=CRTTarIq@w)nHDwJNW%Ro7q<@&e6O$|se#=1>@qa^A3fj%8?$fV z)sR(!yvfh1>ny4R9XVVPvFE4nJGuSWnL9i5%diCca3O=nk=$;rGpNbaC$~fPK+(hr~RNHXn9{5vs<4 z!X>o3K78(r2TySGXPHW(8s_fK52LDn_<2l44zQ>8Z6Ba@6;%HU&%ewLnUKgA0hNGe zl8x$$OOPCxOtv_r!$%wVW|cE>K6$csjDhPawY%yC+?!aJMX9$It*pV8xqg50$j4oa zWSnd>;K&YnSzecC706{4={Y0Nka`pH3;E0O?Hwf=8(ybZUQ5tkuUyIr(@KJ=)IK#) zo^J-esD&F-NQW*t`F{FHOCE6`KX}*_hWr8*m zMEVHd1d*`}qIJf3`mH(RsQg{g@Dj}ECVBPSUvCaabAQxBM+FVN2+4@}L`Eg;H0#H6t|{c$MkII(e&p@X`u9U0Cc&&*zUx z4qw%N3g!DcovvjQ-)}($#9~wza2sbj`ghpnFZv)#^icK?eW_6{Oi(Ajh8_w)1Kwa7 zXVBD#+3uR-m&g_8+KJJz9T^e0phod`%w;g{ z^vf9esY^*jI6iJO)Er$GXCQd*?SMH#N~3? zz7ce?qF87Z-mcEyZ~ba}yLfcLG1z;7*gc7QU9vsIOJgUhH`whQ@jXu@0uF1gnZB3L zj2wLA#!Ye3*Z8f4({%apj>rgTr4hQIv<%1_L#_pA1>_V+^LmQ8H94T^IrtguuJDe9)uA`8r zu-LwNH-B?#{QtC>A)OjUrO9&O-v zKQiI=mvza7Ri331y3LlXb+ItVu-s6in}3TJ+3oPQ`>&N z@QFj+TOUERkVoj6G74dkwqhvF%`5^i;QP17U6Y0o!|lf3nW;Y7JlsUw zXWp9T|1nh@k!LLa@~`9skXp!rp{`EBY;5=s%v68`wC1=zkTB$gEa zhXmqyu9Ex>JXBB_X;a{o7px0g54-(48129mrF`9m=j*Eqcu&L$TL{f_2;&E-2GrzO z#ZK=kFwz253!Yxj!qRJuHZ;uUOb52b&@M{a$A^;eE`u{bQAXOm$pJk6Ov9OvBm7DF zp+JYFNb}-v0iJ-zlL$IzS~w)s(u++hM^FSqXbBd97@}K2ZfyHCK2|;duy1+TPhie$ zVN_zF@QgIPYqav(po|yR&twzHt(WcGw6b=Sikvv1qAE%x$ z!+o2u9Z@bFg&?ammevj54V**1tgRa8s^+|9QF^98luptg&ZsfQD5Wy@KSXJ6=2ZYO z%c@s(O2EUn*byPxFj81}YHiFHO)LQd9xfjv>ZPyEG!GWM|E6-jh^jh`ktl68T!;Mh zh5-w6&%0a+1O4U14<5_caAz5P$%OVXio(oMw2Rhsz;Wxva;N4KJerU?Tr}AIol40vY`n9L# z_`5NY6PRsgwImW%qjJ+&+0;|^VYaGgi3HgvTyFtewmW+95MG?ANL^ zNcdVnusX8NysRFKa=2#Oc}`>mGz^~Namg{H;nB>XX9_ksDURLLIgTT#alXXDj^4N9 zn9OO8%rK*RHiL8MI$Dwvf!wKovi|hPv5b(JJ)`E3Ivi-SW%i|lEpuu6*MnWh5o2IQ z$!9gM5?zc>6}lQr?ghZBUV9mL8q{dP*6=&yOv+q_dX7nz({W1{@Jkr7T?c_)89d$$Ny0Ju#D919jUs|{Y#NDM(tiL>92GJD80aLDrrMe7`9EJare!!pg7H8!&i56 zw2NWE75ki#aWJYGw*01l95p;ckOJ&I8Y2{R8-7M$ls%$Jc+F+%o;9rDvBHPpNf)`IHWfkuwA#ATE)6vD@k=`(8byDBEts-)L-j60_1u4uW`DBw(v<8~SZvPEtpdFYemK?IHa|a?O(@@8);9_C&xCo%#kq~|#l(VO zMrQ8g3v!n}_i63Qf}GCB^ne%<;JQ*b zL6BKfqa^5aF?5te!SWvM%za#b^*ob3aVSk~vq?h z#r*ImL|KTDh0PrvABuTE*R#hJ4O)cyT+%L84j%mAWgF196SJ^`wYcCKwWdwn${ph# zV<}U|#@pnR_M7_z;k33AKB@Z3u;sPa(XEaL_>yU(ktK3n6$H0I(X0#7cm=R^g}yya z>G!Yk6fup}6fJep_`b2MkwN7)$Y*&?fd1pV39RBvQNW80Kf>>CMI;60nC#wP=S3HQF z;=y%g$NQxw{zg@aX53(bSPS3%{6ByeKXcQ!_F45SL8)mg?Wr_;S7Df+WMmSiqKPxs zR5qTCV9A1nTQW+ub&Igp5y?Ljrm-scCU@ERZ57>}XX7TRYP+3KY^IWgD>=1KV4D@B zxV|}WH)V-bVV}E^)4?2IDDE#+3iFp~4#K=p>4^&2kzf>)$n1VHoAu+pwYS5Al$?Qa z)DrW%lf&XJ!-%;yE|99!p)(#{+0O^!yPv!{sbU6o`Sj}yP0B%XHoLM(Sj7oVrkq71 z@UtM8hnorhxgQ0>e0S&==NHbdp8Bctrg+00#ks`=X@6gOhgJe_h7xZya{aUx>|}fv zHRU3{XAf?hcvAj(8Xa9(Y0T$O9r2vZjH9ls5VW?R-3B&4|0xSvlwqi9B*D{OuTn26fTdH0eyni!)#AI$_K>*0JiGASAA z=C|V81rua3CiYZ4a+wp)bP4o7^}VA%&i-1#4ud~XiFMb+VK<>4z7&HBcVe>4m_{() zW8j9FnZ93jpYY?l?CjNLg8CsR19^9`ie}^6zN8*ByV zN+MZZvtx^+ekA4aPKk0f$pATQf4u!#H$(l|Yxh3%+}H&W{f~@9GzL#F3j~ts3dP@Q5_vJ>TFrH1^YoK+pAUGGiiLJj%ctEYxhSi2uz~ zU+7lvgqzaLFyO#2GnT3Ei@k9_7g7%1RJgbmU@P6u!2IWQV*9INVvqYEXCzvu{e-L2 z4<;IsQ111O`wmRL6LBS-RbpHdiv;8{G!DQo{?^p~LQ)5Eo03k~Tjgl07uIh(qn98E zC-Lq#dp<&DF!6lzv{7nK`Vim@(P#I;U&IFYG;UGRb@&IBdp@hVbg>+T=Fpui zPYh8hPTQx9-Fj8UaI3qAe}e)N_)BS_9b9hM7D1Ecj5kA4V7aLAk5D+2XEbkvZyv6T z=AUo<@v1kg$hN9c`lC7Y&dh**woOyv&7TWuR27C&l^krGkXQSh8z%yENW|d3z2R^j zFtw4=J+hOC6a*X$O*TX_TQRQ+57V38Jq-p^dW+VB5^a$DCZC=?E=U|f#v<}@ANY+K zGl{Jst5gPGDC;&&>A#T-_r9e{_ZF zgY{Gue*p}`IFcC`hjQk2TxRM~a659yJ>iR3>;Yz`2(m_>xlD~K;{qen#wUo_f&;9? zRXAV~cWfSfb2m?MMf53Mr&S8RNv;HCK1c?kjpUbAiYC)i>kqGu;}W&Y4z$C8{N{hH zW97#)=N5+mL}{;|tSgUf-IG)3p|0?eKOr~#RGsq?SKpf3^hMs-SoItEp#KAwtH?(G zw!|MQKnrHMqh}u%29I+h>Gn~Ghg6ULv~~L>w{*ve43(^?9J>$@{h zvT+3r#Zp^_f{NK*Nxk2a#R!gd4--7HVs#rZBuC{);hyu0BGDKAu^vrqV=ETVzC|p1 z<-{7h`r2S(Ut_LrNT;1y&#s)eA;c-0zxC?S!cd%ELw(F{^RC4w+QM<{7KY~im>Q^Z z6@;bOE&Px?@b41!yEUG^SR)U7t&W$HW>-X*-31L?uHQug^4b%ORm#JCujvEtT&j*t zG)i0_J$S|Jz@3ErbL3!=vwLC3y+u2dZ|j7hR#)VI*|xFf{lzUc+?El^`P!`AYzx!~K)>B0KW5+As0o@{?U=SbN?h#NWn_%8Y*kH)i7u zc6j!7l#@)iA;CL3X^)iBci*BRDsKn-;lWci6hi*>!`vBzyB9Dx{)k~5{`g@)>T_O@b-BlT1wLJdjvis`0SS)$$%D^~;vy*_}aAddkT!^l(@bzC?wx1mF2KL|EF zCWbpm=*cd*FNitgL=K_8vAX3k67Q9|=_k{%7mJ1x&YaA28SO*oSKs)=>43_^qWdA2MS^Pm3yh9SegH;h z2fLChHSz_ca>hTHm<4($lP?>o>VqcW^VHzfA76-N%dT_1USWid^>#VSqyf^r7#$}L z!26GhkH3hzo~WO_8>wU5%-8V?rl^(=Ct$jwn`zrH!5#u+d6;#dHwYRf_<#}iTswzWWY$6qQv4UN%jVF4ZGMJCL;?R3^inM- z1Is)j4?XV(5owxqMd@|#9@*ILMuj!5%^nW8lebUjJpWf8#AY>g%&@@~>PxM+?R^g- zDgd=CqRnF-p3zG~NAp59Ha`@XHu}@CG=jup97oSTF-7RkiW5of=1n}L&MQtiw@4A64e*q zZZWU5s%XzpgEEB{Bt9YJw!NOdeg-y<;^5*>lCE*5Th#6*cz855m~&xO)5Z|l4k=g| zg1caDxW4HZd&(p5s&#PZc&VZ*O60VOB&+yz!p!cR8@qF|34vV4R`O>>@|S2?nPzKo zy+f*UbKEkJ@FtlY0y=;&O!)JoUzT}R*k38(XLt%s`;uwL=Z6dU(h(V*Yd66DeVk7L z7n?&ZtY1FoX`OV03F6K4W#V{=9;a`t$|)>REGfoB=8_fQ z;}%AY;)y>iIsD!Vzdfx(!644uY4~u&b&OvgIums#YP?kfWju_teS5BzL%9GF!FDsD zZKGH5PZ|#V4C?9&XbYWD4~BAIs5k7m9($jfFpd7m`aE z4)@?!`4p$ORmPk@CXNdKfeR@K^zdv)!ADL8a<`)`x-!qc8jw4#!d@wgxS*b0$z^V{ z#D)37$6UN}^9tQ{_+h*lhx})&HIuZ2M-PKKuC@tZ{CzEc7tCOUG%LO}PwY1_E+U-P zS+_HJyjv#(`fTP=;~gQS=Xu1)%Sa9LB>}d}w+IR-E}(O>w7psyF`L&cEOd?x10c^Y z_}RyPP%b(2oLpzpp2bC8ww|V@bl2C+IgCdEGAa^tG@J{?!a(Cuf9I}0N&!T*SdU4U zdN3>r-ax|)01NOfG#91L23?ud)=$Tja011B(;`Cbrjb2tWyxp3!#nTptg9I0OZd8< zhuPtEym+@Y3Z_B4DJ_@|QXO_uMvgGz?%ufTMJ7Ag$D0Z&H*1xk#CdZnff0cR5T~6r?&(KFi(Pj96{&O*C zVmXwrJ?l4RQe?2#%K1vQF4P6w z^m1w5O3B?(nLbc`-ut|mvRrCGB8BfdN11U_JT7x4tEGQZj4Z@~_Zavx4ELItn@?&b z94f!TerP5Jd;-~{&r|;`3cC;U6J6k75rP27?$nO;6+TRP@ImmJ3}Scyx_VtgAEVeS zir5tUlu}Wm(a2A}MY#j6HS-MfFx3#kciu@H@j_5+aH~PtJ%6Q!k5NPrCRYoRLSMhD zIiU?;Sjoyb9IJA{#Vsu{7%duA1ONoC#fRy_hP%@xGz7#ya#rzi7^1;T= zJWf&Roid^PcrWI+X`A@r&O|BEExg>`&vpw;Ik5Lh!z{~UgAOtse|V>w7=G;fpy8L3 z=3kVxagHgOoiQluedzgNhb-WEKDeu9I!ffM<{3Fx$l%0Cax|x_vUW4mkvuG;s`fXC z)+u=WU9I76AtQOLBNy(xqFSc&{?~oHL<(J`VM#R91ZyU5lj{yM;gu2=Fd)yD{wxqz z5U<(XXuqj^3d0*$zTWNZkO3O(wMeG#*Oa>We;TB)hi6Zq-rTEF)ycll@_%D{*vly$ zct26osmSC-V5CAxNy!Adk9enEUK}$11mmW`71cI!k}{M2*e;S-Iey>S)ju5+llyC* z5;ky)lS(Jjnwq^V0)iA~kDH&Z&nr+*K2KrpcPE|O9-nu@T(XIJdU*PnwiRREBsc4C z>4RZJyNb^=wEMbAmhTR~xOzd7>}}L#;dT|GI+LFHKkffvyqno_Xmc`Pf_-*gb(5lF zp&=mhk!4T;hQ0hb|IIz63FLpkth zs<}_D1~}X-Clxq?1=9hp4_d>GCGc5p7ZyBV%4h_y%!VIJSy9<4y9w&_Aedg!u&Iq) zGC+>9uW*06*!5okt(3HLTsD9EC6njN%&xe@UY^Osb6*EUIt};Vc7sX?6G1}qg|Djs zre4SY?C_U4Au+3w!g*7N48zvhKn1^2td_|7-9bp81Mk`r@G)Qp0Rxq#ty^=o4OCMu6Y@(i-=o&L`yP`j0krXhwB~8|9Y>YU9 zf04i@WVBj0C~5DJB$Xk>yb1EG8j;0q{H-~$^keJu^for%ZJrYVU;CAiTxYDRoR_Z< zeBR6rJwA^VuH=S?J*Ag=vyo%pjThbEH!xTSrDCd@?Z)#jHMNaVCr+8}Vcxi84k3ds z-E<(ibD5wGOPBm%+Jd^oOIP__{YFx8noe|5JQN4%ly})W zT-8zEMJui)OatBJ6h3+%wbwNM*WI+{=TlU9;7O5stx(#LA{(TR>O1(6k-Ylpd--1* z6aKPuW}wllf(37`uX>VNaa@IRzBRw#0@u_#w0`A9yCx(kJLaZUwS1~Ws#A%_rIVDo8d9?5i61F#|B=V%zq;2HhQvQ+!>>=L>oV7Vq}KA^go1gH=rDiEX?wD zRo(x5i=EpjusvP>B-Bch@(Tf8uIo2TiOJ?JagR1P))DZ~M-9lir2^XWOT`|lu0HlX z7vt+h3xw4uH#oRYjoJSMtDfxU*oo6fSISsPd`6paY@hLe*hY;-l>2`&_HCLs+HC(8T8OcI;(k1U<$l5zMNOiK`MN{uRD46pQ2$x zJG64sI{r<>9tnMXP6#C7&7HIQ_caKGSW8EF{5I8%u&0=i=jB|N8mNrSq3@)sZ`3Bv zRrLOe8YU>jzqn7u8K_)!{0u8W!Js-PyT0;(oZ-7>r77Lv=EBZhABnmh>wf5$7{o*a z>d2CESCDM%56Jo9GrMUnUJblW|H>Z0WXV>6#V6~0B<*W&=`}MV-njb)?{V)e0BrPq za$IGM06dH!91kD`+eqyY1U8HIpwCN*{)?1n$s6o%QdoP2X_oW@BYwf1YVskX(F^OglA=dQN9B+ZhLz_78a{K(46)hdE=adS3CT5 z$w?6`+#&SWz@Xk|NFgZqqf%N?j)E&u(s->Y9`Z_KVm0D&ksQ!K!|l2c&7%ZY2ul3$ zu{t6@`dxoqA(7;Kxf1Bh?Vr3= zmn??4NPG^PHs-(btoa~v3)Qg8n|p**%&hR1zZihH7@qh|XuNuX78LGR)qv|~(fbE= z>=E?6BA9D|#ecHcQ8}(eAbjmp>=z+z`(T&sw=5tiLGy!dEi)J)Kpp91x_T&At>=VQ zBb{PbsTqe~>UoGVH&b-qAczRHI@vP0mWBamf(=l~C<9R4UVSGV(JEpM=na*;EgHe1 zd`{}=5?R1IyH;e@z5WEp`pisJU?H6kEF*b{uQ^ol6Fwxov^M0!{?aQfkjdPm9yW|< z$(VUT+ylQUH0E$)24R8uWKQ7N9VPUZFHo}?{eu@thjL<39)b{#y0sFYLzlFU{TEp~ zF}z#NtR)gw2n>$1(Gt7dZ&0+Igg|fDV0_BGf^Jw|TSy6wrOKVkG5gi1WB^)yVG*h%tAW-OkD9(Hl-k_ z<78P2Yk+k(`EhC&4N$yTSJDcsw$q4J`27967AFM7n$`p22eYSOocw?ET&D{JIh-k< z?Kd5Y0)VDidEe9YI-|e^a8=QJeIaxX*np9`Ekt7rrOAHZb^xyf#}LCm2J+;4(ir1Z zB5*%#J{G+M!LYp+X5OxT4S|6s*~#^wk$@20H*VMS5rn*1l`BxK@))jmn01;c&;VR= z*`k+rYy1UC*0!x%*O}$v7a1#0k|P-+V)m;0dwR{zR%G19Log6QK5YJv8gT#GZ(BJh zGc7;Zviz&Me`rX+3z~jA5hRJBbD95yeIcV}=q`n#zh(?z^<(ee-E8s!Zzz z7SA((5v%+)LU?6=5@~)JU9@Z07ba)vNWJ-6h8HqOCgm7ZYYI3=bF+Js>F^CeiSEm; z3;rJI6?kLZQ}z)M%c!Zd71#{hp)6O zUv+PyPCzR58lXbWu)91fD`0a1}LG0CWa0i03 zpyY;+tOd4s)XoL`LedQa_AP~-ybj0_7OS~E5E6b~w5byLHXRt2bgd`6*7*~Jd`oAd zaYNaSSu4WHD=gqfYE6dvG;uC9owB!I`ddS84M+K#;K34H+@Y?go7KEBWQkAGK-DeK zA`*AQtl1`EFo+eYDU}g~wn0tLN{MBp{9VZqc46|?Gx^Qr;<&OA<-bj=ndB+pC*uj$ zna#AOA>HNrxOr0L!7ekKFTar~J(5JZ)2i&DEAa!E3JKJeY|p zIWsZ&V=mFSY9Ajq?oXSZdu|TkVTg&{|69J;1vV~=uo(I?_B&_OC~I z;%yk3<(d}6%f0q*LG>&xhvPO4TMLO79HvtOy*oZj5!foWbM}C_@wn&zQOERQ(|_G? zt2bHb@ZWbJ*d7;0&(lA1kkh^Cyub&;WF`6W`$t3}naK_LS$e8t4AWXt>GgTfy0r>Duovjq9s5w~*c4`a1qwIGoWv7AG{U6aaFo+-(%ZEg_8(|Tdt@Iq7`swMnqHYK z!eK|6%Vv^7b{Q?A(HzH^g{GFoX@dhrEaVg?*PnEdgwU%UXAPSR$!Dc$s0wrrLCdfF z$Jp2(LEF<36n}tq<`n9_`0h&v^(nJ+KD3hz;Q4;}%e5Nl3-$MUjI84Y;DL`8Ppztd zkZ;7T-hm^XYslz2Jv#{PvKq;9t7--G;8J0m70hRcLGhOcTS7==uWJUlZzIM~)2+F41+BmgU{PN` z<*(IE-^3^W$INsQ;0CTOv(xiXLmyO|vW(m~f=11R9rDOZ_{sgNtH8Cvxtff@k2PC| z&)n-}@#1W;!nn1B*R2u$NML(JIuMfoN>tXnfgmXD~*5-lig^HrE&mYA7az+vaq%1Qjt~$8fC}i}qPxuDJ65dYax{UyA%Z zX&IydK%mhtXtcu89=C}|4RklDv^S>9WsN;zhfN2EmN1<|YS-DlUOCS=L#S?D~_9~&4ZoVoONOVMxnJnP#1&Wz-9TD%F8 zSTNrQhVls_+XU% z#D#|_;_V5g$JH)Ows?}5rm^yxTya|vw0&G&V_L}Ly9iJy|KNE=mS0zymaEzDr*J#x ziLU8ns&hk6Kf#G?|E4HU4)$c=WN*0@AxdFqDq2ScUU=A-x83l?${@aqCLbge?Etqu z2jed4^drP&Llxf+gv>50=`S267!?;%=^bO-|M58;%yrrb5yB!*5_4%u|8_X;7N6B0 zkgGPwKTT@qU?9{y1`m^(GfSnNrMS-K$E5=Z)?SAMmG*byCH3Ox&Xi!7aNCQ+&1xn( z(gOzb*Y+AN`?tfX%TuJkq!m!1mAqJ~EEPL3#1q5!NuAM9&C4k#_ZJbp$K;5EtyxA_ z0Uosp#30x>{5cgiSq1yhXwakWA#!5^;Eo&r)Nf!}0M#=vWLupCv;6ST$(O11o%JIk z0+h3W631e~uMw%Bmuao~mP%CxFo&3Za!2{fYaaZ%uHBdwWwBbD8^>}xn<04R->J<} zU7$=3SB`ny@Ic=%PlY}hSLK1e)AXw}xZ7LpXlaudhiwIJugQ)XWSJ}V&3_B$_X&`n@cVX@T+GHRk*k`6`r*>m!?pM-7iA<{qVGb#Dy!-nqhZ$k9j8le9ANPZ`R7nPS zvPL8f@Ao`ZuhiaQV9^q!SLeGZ(0L*obAt&ICONDJ_5}>XWkbEst#OpKIQoFITmA%o^ln&Cb!+v? z7tUa`9dWdx= znX@`ga^7W72K`CPOTB3#CZr^%OaPk!*-&z0;lFM`7D6X=U7V%vCLFsnDgfW|ciYqW zxkUaAtNI%Y=l-H7GuzEJ^pDy=SSQw_jpNj1KcbORD#2IqPR({Kjl)5b)f??+r1R7b z{^Q@zkT5$FSw+ev5I4V`=0p|72ewOOGR%yHv49sy^q9*#U$2SE7W_uHN%XTXF5Y^b zG*GmEQ1`HNra)4uG|PuJ{bDutIwHkCBQKKO9xN$0o3c$mqzh_QC#wY5=hU-w?>&TzJ5@5=s*h0q8 zoA`DI^28(GY^*ipZo&ya*Jo^A-jIw_lE^7nca~LE4PNN8EvZ7277E=zct?JofXP%c znV21i5^{6c<(=E_h5yz5Tc}rz>SFk2B>Y^#2S!i|-bvwYB~8BgansQLjeN zAmy2f|89gLD-ws9Sny?Z^mfd6j#4L8FbC`teNpg#m6irviEk0F!CE_e&$gk=IEdJjU};xy<_-NqX{1<#4(@2&QWER`JhV8cQzbN$(m7Uw|p z!&>Ap`Sfc$hIpatB_c@_b{?04m&nFaNI4L1Wc4M?qaXX#Nz@RsvFD~}-Cmyf zix>T0+#~DERGL|_?kdqeD5-0wzSEp&ca-xXM0g_~m>lZI9yUz<7!epd2*uTnRH#as z2e8a^FLibxcKIN}`$a1An`4OfS!{K)3R>9$IY!urdc#e>!D0=y1}NDLX8$oqEdaQ_ zdMBcwfefpn_K4brkQaAW^%Fb3nltUFRS?|?D?q{spl}je_SG)pepjYA7Y}l zOQMcCqPy_#_t7kI{$VWskz7X?IC5lpy^T_BN;H{4(DS{kBoHq24EegwYtwj>QgRo* z3Q!@kkm|SC<8Y(<%)hVv_8q5*Ya_Zy8W^iO_q_SCsZKo#q-*=5!ncPJD)pa7kR= z{`PdAtJORid%fVx}T}%c6QKDg~!3|Fa{!cIL zL3=z7XWOqY=eVLUwTg|-yJLiYPiA6oTffB#0(qU*kz)d{pWwDK$SJz$%E(-@-pcef z36Rl<9hg3oq4sR#T%R5s#!%#ae6xMMUm^$EtMEffu?tkedB3N}z@{0rYj2JqN`rG} zk7u#lF^b_>CZ+sZMn7THNO&3=oCZ4pnBShKscZK658{-UQbG{jz%RkBSQyQc)MoRw z%SDEIx6Kdp;FWx`@Wlt5m{d_+wM8w!1Y~p)mEP$foc2=gG%88#7xKtm$Wows0AGmz zrszITz#4{Q*r9&WH{vm~s`fkWgnyv+vZ{B(FRsJ)1Fhtv;97hA-&EUb<+`gv%#69M%Kzq>^8H;}h~@2^l5;kg%r&sL0>k2=WC1WERu`E!BdYGXs# z$Z`w8Ma zv%V|9|1j!ChP2DO0rJz3%Z17Qez=Ub|0Swx2J9v;H~*&;V(K_n%sh5uJXv~aQXd^CtNAImUldx{VH$njzwKq>Gt2@8%aR= z#ecj1Dnmm;|2bjOQPn6v@Y~$|7rWysgtDcQ$NdbM>R8_IYl78o3R;&S>$!7Dz_{il z_Ii&Cm6t$St$7K59)Z}23zf~om(DA!)T*S|&v2;q&xO-A0mLb1UuYE^UH@~%=?>rA_tK&yi9K59wI~}fqg|I1)IVwnnX-i z6-+GE(uKHbyH`Rq!E=#_^#gOG+wCyk%Lk>vCgqLZw6D0$mt*?dY9A6VmH27pUDILb zmwtzesXg=&7nLdTnYsfc%eUQ^mX)U}TgQ(aoB(gaVI>f&M2Y$iB;*MRHd`+O*tD41+%heaMj4E&BVDOYSaZUpaU>_)>-mkqdpi` z@XV{Aiy};RWL&$hXH&$J8uzWv**urn+YP6V#R)IPzwT{Mk=jOlPcwJgtmt%ehbNWW z+Wa+b0nqrQ@vnoIZ$E@ceK1{mP<6KsHS{~-kQdMVm$~&7fx$oT5OwcTO5__NI__|6 zE)dq;V(iI%_N-{yvFBhNDfseJiHi*qe5=%xs9Z!IC|YmioJx%Pd!OI>803PJOKh3R z-A$yDx}4X;M?Q(mbg4>In6>^VOnpHJMTaQx`AUD4ongTcl*!Mv<->V6S4rJeSTO-O zCI{plAv!2^ume4I+iSc?ij^qsm7@GV1aI(sT-}yVv3iABH}*!BU@dNCpC!Ky4Ho}h z%Kp=~uuSHI(T}qmCYJIkvO8%Fc&Hz@OA-n$qe8Ny%`HhcMqZ#`01HL${bS%xhBWO4Bv!x z-TUY;K?u%gb0U%#1*jxD!K;b^YiC%PlP}Nv4#o(r3`^54Eq4^#Htq`1UA6F(C7H@~H&GjXC?f-4A!8a1r{G)4c12&}d3oMvv9&D2RW~W;TCg4tuCC*s+_ahoTYC zkR4K)1L@5vX17N`yi=iawpJRB3WLjVZjp*~8&#rfno_^1BgKaclX1WVAw_H5+ z?pw~|*c6hCbLqgb zr1^MFs@UO%L|FLrrdb?A~!F^{wV{KGiXKpRT6ZH00?+ur-_mf72;Ty9g$a%0>vy3 zo|dROk^hAv}f9%9_RXwnh;sN zRt+(0Y7)Cr+jRfRIj7}4 z)v-vapx5@jfdYCDl&iK4Z*wgGIpp$w>R)~dg{Ni4flG>&5;T0^dl@O?h7;60|ODyxhxDbcK!Wr68=)>o^?Za;8u`!6O8iD>J zu;SPJwvQjGfS3(-+3Fr`Z-k!C&{J5imP0&c5x&LUQvO1^oH4EHRs$;tImxNjLd0Ij z%HC008wKz?-b+01V^cnVVlyYp<9%dtc)$imN~_e+h~WcTlhMdV;SJS}-ED?w-5C7t zf)6+UonXXy;+vdtaT(A2bE1i?C-zIdN`HK%Gq!r&X6ETjRQ~O0m8v3GO_OvE%@#{^{Rz4O?+aed`-h+V%Us}SjoUj^T z(7Ud|vm&6e3Ril&ohPW|5n?vs_@zv)=T{mcMt0;FfsvzVC&%G!3x$`Dl3-`xdW;~4 zx;(ASmOa#+0k*1HnL&o21CnDqDL4r8?F3Tr;LYFsY8t&0Y)k!QGAw01BK}_^CzOG= z9!4}Clv7HbK~{4Fnnq0XD3%ka+??6vnmGM*25xVV^Iu1e<+Ot|E@KD)3C`Dj`2Y`0 zG(YR|xInvxhs^O7lr#An+G^kZA5rBVP-b+`{6cVq*71D8B>-Qjy zQOm~nxBnGMAQHQh zuV$n@SOyoyBrJ50A#&pNz!Yz1%=NcSntucwz_98G-XV~8+4|0}&8miKY*5n2^tf%( zrSRQUyW0L#$KvTQO%wt{KK7oZGd}aX0HcnEF`cx{xPM^QVn4XtN>F>rw0?OQwIj-_ z_v{}VE<>i2CiRI+rLRMYzM$6M^#qc%=h{k*%?D51tAX2`mA!9tPs_4@wIEWo7x2v^ zKDWunfvA3qcPlPPwXe1=le=X99rc`@9LuHeiXGr=IKOC6Aero~?=eEcl`XL46=VibFj z-_$#oDhisZ;yrh31x#2^hpt?UCgy@(Z!u5^2G@cV&HCxMA*^tkj#q43X?Aw57ndak z(`e8xVW7}J+e37Bv!QZR=t#&H5X)spsyl>BnHVN!laZOGTA$NC2g|4eu$_s8_xuo z@vm;pJKz^jhq@*az;Lph4SrIOgDUQ`$v@nhs5DOTIBWToPG|cfbEP)y&Ho(=7FZJ- z`D1gI?;QQE3snSTL^e(ZZW4-L=QXU%2?Rd-dcqQU&xrY|CwHKB7838M18^iMGJcw~ zq{hi;$t$UmBU9G|B%ykUM#0L^SCH)NAL4oosQPjEc}^vV-vj%aBjS@5GQf7g>OFz~ z+o4Q+A;?ru*e|{I>9b7B_M^sUypP#pJxmdh$M71ZwM=5SNTEcpy%ZQAQkH;lKM23; zJ4O1PXA4WFE8nJ_Y^~H**>v2EHRnGC@})djp=^ zT|~g{Sr)No_@G&kjES~e;8}i@Zqaz_v4Z$tl|Dkxj)700;D5sHbA%SXYk~^UhcYIQ zdv{j0Pc%a_n}KqB?d1`t(-tOy9cqv4Y>r5iVT?@|6vX{xY5Td21CGyFxlfZN>+wfz+y8&7AuFE2XDa_3^Bl>!tE62Y-8 z$L>hkOnn!wtN|XELS%om?I+{4iy<}dhim;rur_0W?%&@s3av1-Iz1-tk?b97VsJ%s z1V*6N(NDl#c_j_TrIRY#bw&knezxm|{J!`Cd*b7%AymAu{VW!^$-AGiZ8J8>f=9%D z#ye29@14z1o3Ht}wbk(#xQ!fSl>H@&xgWf4JlzQpsgN%OCJg@q@UV1$WBmR#`3^gp zt*h2dgi;xz=u8j!+6tW2@vY&%^laeH;xXmoZOXthfTgG;r6PYdSibs;qHvkM)0p2y zf~%l(hIk0eT7b{*@bvgKbv=~u^mVrZzW@U{sq^y z%BlL10(_d7_a^zrRhH1leAjCZz-IqA%Mpb+U&-ID3nm>i6T?iD;f4l^UiW05UNN)A z{O7w?C|!3S>PePmL?0pBTy50 z)11UfYPou5C06bQnYFSVcDL6$I3CK1V;)PesI}Iu50&y{|2^BUHU1pLYEq@$s$$c| zwP;s*&mN4PB;r@psHNz_^n(GX!akcdR+xGViY8vy)<9Ug)9>*qoijCp5Cz}V#v9B! z#k_m*tTE@$otQvGnhlp&svw#FDB5X=I)GkLwLSHeLnSFf!iI2@`qT!L-8hS< zouA|$S-oN6MtqpR3=L?AU?H!m?Z)e7sZ$)VZffQs{kT#!)u7I9pB4=fdr%;)?zVva{0qvR8K1*{3hiY<+aFBzRmgy{BogA_fWpm1>9$pSjZuXIHy7Y4qjrEptkdWco{_YC zHlg{cnJEV9B?n{(iQffWpLyP8e{*EOkRY96geKtDg0GQBXu~K$H3#l7I`QGcI;<<7 zhZRC*MC>mw4GV!TzU|e-k5T>vBhXLSPcgpFptjQKQ>sMzUI2xS?;8*+CQ>=rp&J%V zAzQDQUcB^mC;BXTc6Y8)6>;@@AVmuK+xul`J|ZDIJSLXLpOP;{0mfjz2yJ&(5`^;( z+c92YX(#D`n}(VeLt9kR)w8X8+HYvG;rh=y#q=oi(dAJMw9c_{@X3Et9vb8%X6)(U z&Y!e^0x>-2-E!O6oV@jF41-)$F+_6kSYhe*_E(>R?!RDVPO9KjBi=378+r zO@MdYj(s)p<^+YR(Q&10H+>V0novr3DBF+jfz;#Sf`hTQoAaF3+Ak0;HTj9)(ufE^ zv6=1avTT;K_xinrTF{EahI)9W`Rbz}U3c^}o&P4OeZ*U8@%g~ff1Kcp=BQ^*4WxE* z+ZrF{%|mhq$yZq}Y5HVlLW_dQ`3Do=&g)!J@1gilT_^s;ff$T7Hm+vs{eeFZ?58<2 zD54Vluq!%azw~e-b^8Z1C&Dj(bZ7d$APNmiyYJZ6t!RbA$o*l*I@X|%tgY6^)zxZ^ zVK%-HTfPjEE1ZLDSNzIV|Jk2%+FnbA7r;GvQ3QK&G2*ex^IsX$q4>h#y3f`taB69|P-G2i zHAJ_4ooN!TA3lE#G34~XUISlzt3`RkOd-ok`wXb}0zUVM9%JC43MWmi<|-m)TZHht zAZ+IPYYt8T{OIMHh8PqfrjO#|W&V}j;QzEE$mjSR1TC{c*OKQt^9;nTs+zC)vELQ+ zw0WIUYU*Ki%e(pj2Us$$t=h&%zyD|1b|(+RR_V|l0jSB*Im;+?i|)3<5FW&DzLM^% zfl*Lq;H8Cr<~E@#NxM$p-yT#zCZEEYz0oXnx_uZoU#7AFOX>5`T4d`Q-C5aC<|%E~ z^Gufo)scEXtoP*Jr!riIc%oCo&y5=VF)`jHfF;|}C;s@jI#|jY@Khc#mE`=Aa`WJ z6!qNL;+JLpUqBZ5b%DFOj+o(z2K8&xgwPzujW>@C=r82m5_|>#~AxF?gs~5=3TVpk(ovYE-`i9f!bM{5`uH zVp!JB59^gTUyTa1(`>>V8L-HNJxb|3&?zm+us4S&n9!AKZJ;N_{!3AlXPVz%S_%=C zAU+ne0cChhuSq%{ehHGb7e2>vulyKmx06<0ikfs!&Gj?WJ8A?Mqoxb;z4R;UnJIy|;i7xth9v5_B52Ia-ppB2mx(=)W(WAOVX;R(K5THA5snt}J zBWA(qOuxa<_jVWEJkzD%!f5BcX$&?Aw&mV_nRdVv4e5o5Dpge%V&w-0k+y6*INA$% z)t)EjMd)E)`@Xn>+Y@M(hwLQ#s5y{toQov=P>KM&mAxzdfr=p7(c%pHL~FUk!0|@8 zpc>DYjEfY+(62nPabPaj-P?ZZyp-5$)f|ogO7+A(g=j_${2=}TqPNAU^jH`AZjksc zekr9xiaH(BZ~c*fWlJkXDC!;>UoXxR>42@)$1gy_%$gwcJt6SD@MbkYC;O$&JU4yx zaaHuXy_{%GS1I7q*A(TmjG{?&w?ZG8c8tvP%y77xQF~|Bt~?Ey5ZGpl__iuU>&%l| zTlC)_VSz*aq6QDv5k$}IWnV8~#c1G zZ}|hool;;UAp-T^-fq8e6`=pqs#j!Xj+3h?XWo(wgT{qkOlL?L|4a4Oal=mrZ&{yg zK}goH48&}?_B-Mu@C8~s)8RPwYHZl@qz9U3&?-vIgLhyNoCoQDjc6Tz>!iQd;Jy0K zp|A2?==>IP7$GBSe)CS9T7ZuxYrFd1Tt{+O*)d)#Pfty#AS?O<>1{xx`I*N>*8~;r zTDx9=PXWLznfx?PZgeM(AbV6U<-CNp?!m@+<}JdcU&vAXfw*t-xaBp-6KIb_4N=}0 zbG8N)IarYBM>?Eg@tczHMsf}A(j#6P;oWwka{q3;0+YJnKkJmUHUTw?*e+zwE4`M3 zQa~X#G!%Y*)hFrXdb{YD;l(TdAa8nVkmew1tEn)!(ea!Q))Mr1Wq!BJSkMqZe`IwBKYj=1hTV4k z=35?wNdI{mUbK8gtix+@SL|k?eJj6BPg>$Oay-oXq&-s^Qblf3q4Hnv4#)0sqJ2TN zw-sjO*}?~-wOQV~Y%Nht4G9xcZ-{)>y_vY(lTBsxpwO7=J`Oa^=hQ#0xJyupfxzr> zVi@jP4|)TR8(&nk@?9a7vttU&uTkR;RW#*n564>n4v~m}SG+;cbJdl^x?ix}bD1ky z&FG!62}U2$Tnit(Efv|tMx@;lGsNOnfil@f%{>2?4%lSdw0Aa|SkPz*sh{?W#Zbvm zh3)O1Q^J3fLDcn3{5b4tfwq%h(NDIlWQlK5P=dM zD#BpBb*WQ|LzlYBG7Z{Ye_fFM^Izm%^XNviy)J|X|AZ!ckAzUVDT!F(tT8*eG_)T? zN)s*ntUc~MY>^}Q7|SL^Y77987_E+qs__Kt>fc`bM#Yk!vXlYC3(74an~Gvw7oVeA$xVJ^)a@2laCrQ{xUi^rjCW5 zzT~SZ9Yws?Gyj>wXaig^55qtx#8=XXaeZ;fnd}yOP{iy=nI>T-tl+$grxyuH;XA<} z9!1g?320UK3kG1@^-!*ehBq>_sZLKwf$7Gq-zHa^u6BKx`Zi_f*1f4oz~fCW+5a9x zDRp0bq`^(Vvz@oI$mVQ|ffnJ9d6+{LNxj;Cr~*-_2Jt2dPjh&tiXHHSJH@(wVQ?fe z%A1ACug68ANSnq`*u$qoh&!cwW`n;Zd?bu|mcB!yNZZ{17wjMSq^MlUOg1ZPK;z#2 zUtb=4uu5JxV-XbXdw<8Rre>rndRWkALGxsOx_Di1FJZP9@5!ha&?UI-Fdv$VYIm# z=5~*UD)tRDprM=Zizu#R7_g$R+e>wwDJ;P9jiHJ32hZafl_#gR*uDd=pj6=p`u<~F zO2X|yQUZmLo-vDu#7d6-iT4wTI0QfFjI-p$D%lwR>@sD-d$$effx};?@>g2pk=}2l zcHhd-f!=LSZ1(Tc*i`1a z{J2vGnn62338xDL6Ca?Scb#p|>wW#4G*$nY%c`PXj7D-_)44Kx8JF)w=TbPhU3nJ8 zLdp{eKK3YDCelz+bd-e0-%n@2*^;NvoX7({1p!_p7^WCnlZOey(t{Vao#$gb%Ay*VA}uc@Mc z?fl-M8gAcnC^7mAq|SC%>B8mW4g?E#l{JTFaR#=B^aoK)Da2j+M;G)PbxcQTmKy^( zn|_bVu70iC2o%D94oA25zwQ?SSB8ndmE8;!R3=mjpG zBG99~0#>|4(*E0?;M*%Pl#PD$cz8!emdN)0GuUKT?7)k4R*x$xZbqjR3?PY}$k_`{ zNO_C$dnly?;B;GQ-e+0tIH>Q6qJ?+`D9GVM)fK#IxnGLI)4O9aiB>``Rb-MH7%~$~ z7$9qO-+<$->)O=^Wh#W_rtL8$RR)T)b`?IgQz2-J72Ot^E9qt){6fzl&RR}FE1a0H+^ZkG$A zHTeQ%W4{~VS&v4&Z0L%F^R9RW9g0<4n)&VxS%e+uMGWfg?(!Xo#@LB|!OV2KDpL=;j&6VBLt$3qQ*UHknoM58mq8qtBe5xa zltqT{af?t*`<%IVRh%k_)`VbZm8|i929oj1iKW?5nkPx%36 zIP$Wa8G7QfPrA4j7}Ba1HMzOEd&7&Z-Pa(ifu%@<3|2i1S;I8$IZkomlGDbLajv(H zbUf#k2gDxBUQq$_McIEb_=}ov&hluxJ_mD#?I5j`@CW+Jm6n6~uO+7E z-tT$tQ>n@Dz6aCxW&)U@JfGqbWX(tq35S%oH4KVF=$rZ3$fZrSTXEJFCl>88fL}aP zc1WR>;B9>Cqq(#+^Nr2TrTd3)ef)B>y}0SuS|Uo<@~;V0tD0gL1({cWmVj5v5#xlv z$?7Y-ZgSI&ujv!0Zc5bO_Gln?^2Qpn6e|w%T(S)YV}JCk&E+cw#VUWg7>!*MW2~-4 zUrv<{b4*SM+RW-y*`Hz_+#58OeiblmZ|_B%PAtg?n|&9 z7?oe;miBd1#s4DAZR!22*4l=)Jer_7l_FuaZ~};@ZW8S>=f?J_uGMn>_Z`Hq7LtE$ zBXGk@5DC|qJ)Ps?_CxEZbHEHArZ#oZYS)|qHK|9&ch8P?U!pT2KhTYA5V~8okBh5d z7h<<(Qh_HPo>7dCp3Cv;mymElec?inc|gQBqlxgtlfLRaNqY5XsE$vt-kVs=`Lf|B zp{IhG-fIp!@O9O;908(Og@L$Cz$!2vz8=ab`RDf+Bcbcx&21rLBoEsB-MV z>%NCZYxIgDUUN$#pCWlF0D^F8j&@q}gNV6Bdh3=6BXp=Eh1JHS3_Rjw7Y6N5F4(<> zTi(qYp4h-ZoP=(0kSu#Su>c1n7} zwKeg18-Bh;TIT~c@TjTst+INa-u$(WDLaVSmyyr^W`8iK$&Ku{2%6Z;Mr*$bVpv%XQC&pcPFPQD|3&(3!ikpnm|? zQFxCxKDA#4iW}>h8L?vtjP@!`PHW|-etJQJ{a6)P4?l~T-79aD*~ZBTo8}Tww4ExM z7JX-P31KR=jAqnqAHVvW=t=(2;K8PusQI(SSxtwx&mZoTzTmFI<%A-jC!rXt8UK4l z0vh~=I^nr|4>;Is3+yYRI~%i9e;KNQ>)?1PYAm`%IwH05o^`c43xtT447xmBxM#x| zEopDJwx~Ik*}Pheo*Vv%8UPKZAucSJ;OD0^T+S_C#Gs>NVF2-K^~=)M<9cpr-Hsp& zhhuwCf}m?lksSF)dx>JF&gwy0Q8b2ZCJJboM>PH_2LNu_IaNAyB{PR>)Ujz;^{7O4 zlJgnEvy~FHhL4lj>4)R+!)7^NO;Rz6U{ZzT7DX~J?aFlMck)do2Enh(Yn!X#6EgXW z$3cO)EEDGY)4#pl1iv7=xTA%Gb=i=Eye%uvX~02t&zd}v`QJPjrXS_E)49)RdrG1L zE*vaBOC3MNbdRfr2@4SLbUnqQpZMOr+MZei+z8ya(aI@#L~c5I-6=R~ka5hxT?>g# zgw5l+J|}+`6u+ykd{qvSs2)GdsyO!x;LO;M2z{8Hb2eL~a4}WNfV?R{=XMaJPLyW? zxr;wbun1Z|F?LABm4?=3D$JoV+4`(n5}4~fTsKl- zHc%Yb{ogL8oA8`gItG`%`vJ6!CEoUNDt=r{KN(5QaX(D6O{G24R$OVoraaA+c+V(9 zAwbpIgcv?NA0eJP3OF2&CIzO$Psw3D^!F3~xd|+@PE$;FzNRd@I^G+N_xYUh@jK7* zb;31DJ#1-m=?s&l>GFqLYl2WPi-yo3*97729AE6h9Uid$(1j1Rr4iLueUFj6Jl+n) zF4(zt5M2cp#8Fdtf}|eiTetkB%Kas*X}w%_Fd|h%A+t_A^wNCovCddl$1 z(gv{A7<{r%e;1JItI^z&cxLqoeJ!AUITLh2TJe8rRtYUyZVGknmxT#6`Y~L8W#R#Z zu16~W;-TMEVuP7oE2XpRR69>xS;P?@)P>L$y zo^%9kroOU4OMX>m$!FBF$Fg&0w;=$q=X$1fgrIeSJ2`@w%dlvSJVwB6@zDUP$6pYWR$ig?`^c-wmu*QnAiNo(mY zWR{i@rL-Z%2<$Z)8}`7~t2(@7>t_4kkn$8FmoMte;(>mXp}YKvn^UWbe_-mFsKkWI zZTtAX#u+^S^j1&!H)X?iuudW4f9HME-ZfGA7=$11O|Ud;%Bb(M$r!G$?P)G(1np_c zRH5rlE7AQ6NGUq&&cS1A&uGAIdGQUr?Dh>x#BGuBg;EYNRE-Ed^d9+Z_egcnm#U&= zodeggaL2hIrP)Ql-yDFob9n z=dVr5-3 zhOyZE08|GDBp6yre#1xvZ+fPNyagy5(%sX-pO@kITevA|g!;v$4vd!E%{u6i;bojW zR7Dtp=X7myk-6|rb<(|C7Vth2Ly=fGNyQPL6=(Oookdm(S2i?1|0Aw~1jGFzrZwgF z6*VcD0Ut86%PyINI*xIn(?iz|NcAcB5c2SJndz!ub9n3Fni+m8Hh-a{gnsEbn-s`d z!f->iotolxaWyU+Z70yeUZUkgDlhz(gD8f@3tJpt7H8hMz0B$?xpC zLbU$ue-ZV^j{bp;u6m@bL}oS&!t3XkBm;#1;ik}vYf9K7xJP$c$fqweL2~3x6SSye0jx7#B8BbXf5Vv@KE5x-jWpsSgoI0O*RF;%F1IDQ(u1@AX&ERK`gKm<-y0z|Uol=*bCSD( zND1PMyEzO2!vx|E@db(B$gN~=v5loYeZ@ybAt$LYA(v3+(DKY9JkNUxN7YL3T~g*t z^M}CH_66J68T(XmNG5??Ik5n2?$q9Z*=%#ppb?l?Ji*s}S+u_V;jdwID3y@^aMDcz z;9%0#HG0`-K}>p_u_k@~>5GMBiOc;V5u3r2*PvI3EG6r4Z42Q^-1eu&*krdyz#Y+J zdpVAvVHx$senlrE1{KDsvd~vWDCt{EH-|8eW`w@LioxL!5A-?V<$0UZ{oFe=Z`%~~HZJ#g+O@O*p z^wDRXPZDvMDXqm_%|2wy;7<>S9QKI8%ouOW;}2T9j4|Dl^~!Gmf}$t8Gj>H&_~=&F zZp-5yE4S`Gw!eVF5XmtQ`KP*6(K4B*^v#P*LeR!qx!cm3Xe$++x0@AxyoK0~44~pq zY45{HDID1JY5PGvbtCie9l2Qv9FuLkHY^tC9-QZJ3t&pugbf(2_mqOzoo!o`5Q~ha zsdA3@h5|nMsfTII(h!R^&oNc#2+_cGMcyPtlmi~w;m_t?{ZBl-qVR#Z7qYez(br@} zC^a;o)u-^nFG_9nqZ%VPu&{pnM)uhqJYY!{z~|-UW;#X@aWXVxb;}}y0v)QU9DS-= z^!e+}_xJ=iD?k;u&tF#a5eMYcQ@b=+0Ne%1b5s3BS`GsClE-2L_%T@Ic&X@cU_RoY z<`Vn;VsfPTEh>5%BQL~sSp2ug2oU{6aGmANl=Ra5i*JR z3pe6W+LqHxkB!atHl%;|Z^r~?PMBWKgG}EEb61&PX2FX9(b&zKQ#-#B65K$ws>!P9FjwR)#RJ)ZKMQEAaF0`_3H$^Qr>9I%+-WA72XdQ zNj%a5CB9Bb1}GRz8hb7Ga4kTh(0bhiMh6_x2QXBYdYBZe@+dvw&%D;0EJ-rc1RKDA z+0lWoNzo3YgDH6nL9S@GtP!~nx^7<2gDcDV+8TA-E&ptD7J5@&w4x*(oNBS$l)?hE zLkOsq><%N+p~?g{6iY^RC%QP&45C2;T0KLgy10?p8} zS}Vq(BeVDE;!3!4L;Y=q{541!D8`${SDTVU&QL7L@c$&{Zolj)@HA9>28JQGklpst zG7vj{w^z#slE7`&t%SFKcK?yPl#K&sX*Loy@@-z7u|p;GFaGD{6#$$_=w5Gx7M-c~ zZqR5S?7FLb_C6SdE-+>P@pJ7#H30t|>c$Klec@mIw|4w>{wXr$KVroe^+{QY#cA*3 zR{!a=fpJIM<57 zL{HjI2g9|@H?&~M8rIF^{J}M}mxjkx2xoMR1f-%Q)8<{ST%@o{E;GkuZNqSXD z+Ki_$`0cqKyswJjVuLIWeE)M_e$NfD^G07NaC{Tglf(ZZa-+m(*&X zF744Bhk%_nu4d=-W%3;gI-BvCgd*0cH;WfmtqNr)_P8_}whM<+QwHrOrRZ5p;1 z`ZQXhZL=?}5Z*mIRWG6@HmnB~x7z2jB=lmT-_Z^`5{kq2_{}4Y0oqDY!*4TXQ3`;| zL{Fr@^mVz+kff4z9F{@1*>ofFM8$5)`&S=s@&c%sIpMIxuj|;ox81PDCn*9Lww$($n#RBGI;4v$YAn$1bJfH89Lp ztTaSa`Znm`yE6g9`4}qoKJgk8yJR)_*|W5l#d7ZN2Wf4P{nnhLE1h;L)uG6FX*Gjc zu>3)0gHNM=(igB6YVa7uAvV}Tv8wjm~ghM&8p(d90*S$uBp zLt#_&mR8;sY4###ASj0Vf5_@C9?!ulrXYpLjLawq^~EUqNaRS7_B`l8Q?@c-Zly5ZtOHd#XmWO<*7_EZ2AsmKj3}7U_J%-~5BksjDXo2X?ek8s zO*#yd=O!D7&z$GNieT$^L66_NuCBt7*W+Ln8I!xOGhjACruzm}XbA%s@Z;H3zO1uU zZT$=EMDtZ<(VQ(wL=doaaA>;E2mCqR;v68h!Z=RHo8z6cdB_+pgm%wFRM2SWLt6=E z-k(Ro?i37gN~66`)UdW+6dZsTq{O`(UxJkhYFI)oyfBS6(Ze~A-NgWgyr=Su2ced< z_}gw$LvZtF*h^H6cF~^ZWWY{W`!eq=uF`v!gcVO=a|4<~ar7=+f1FNaO07v@opH!P zH>qE6t+~F$5A#f`N)YfzT==?Hw(<{|QvRx1fsqV>M`a8b{oZ#l4}6ngqb*u%m}(#B zyM0WkWm`9;(`o^1=2@a+YY$mq*tb#3<&AWc5Ve7DJ;&CH2+tT3N7{z=+6=d8H#z6O zy-j?n1sPHUWNkDPO;67<2(`lG`xA@rBwStePOl2%A73Wq9K%VOhTe{Nyc=qbNn3w; z9x$TH1K?sGexIKAReCY+FT0KyM~EJwFg8*M^n)2Md?pzR&<|br6a!pEBSD7%Th#s! z@K2~m8XT4RWg-+gyGI(Ne47o7nu9l=;@C+wE3OhZq!ZiZOY=FM+2Q!SV^ZPc7Xj>1 zFUqDqE@Wh*3)!ZU&9!0`oA?TW&y>o`ey8`R`fv|}E5Gwn@TgNi-!k?6Ns$DgFMjt! zKOa?4F)8#J9wl?&6?wQ3+Z(%STn2sA3riQ4^`Z>_s8-6Bx}M&f>HE7 zHi?XJ$h5U^6m}a*etSUnlxQs;$zl!s@!_%22#mj{0vnKYoyK?69BxZ zV@0*K1>bb*-0esd`wM)D;q*mAH$N~`=2IO%oUpx1$wcWo0Q!XU+M4{2yTXe=Z^zKf zI8!ey%jjLxvxMtIZvklc6owY?FPKhQ*o`^U6bbxW^0m2HZU9yyo4-o#L++FO&gl00 z3G!Zs{YDaPr#+o0^R9k1 zwx=9}RXU#BY8+r#r`_4a?>?W$-fIrNFkYv}o@9S}u{NuYUv6`6m|A~h3CjGuhUa|E ziFV{?cK7Hz3;2o8d{DelF%F5nBOu-;rCxsJR0}&+mc4sBy5F*0fR42nVIoSlVh!CD z?T8Mf&>bez=GQDs@{&d@=|(#k^0R=-6IB6Eql&`l&0MyUUV?u?=r5F%ZFrCuf491Q zM{fY+7U#BGO_P7Rk*cXY1`I1j2P5a{33DZCwm&5T$-u%69Tc!h6<-7nmq0Cq&ZSHX< zt-VZrEw#P<@TaSTn2SJFiYWrIe7(7RgeU7E)4r7rpEG2Nf_{~biW8aEFpBZP-g?D6wu~72h0>46b5Hp9u%F(U8=D8$ol`Ck z4nUUqopl!tuhYcbcz^flEQqst1cqrDG^W%9B+UP99S8z9MI}^Pxextl%mn!X8FmO;g#B_?NUUk0R)-1w~_4TV+}rTtziCmB6diD;bRWQ z14L3t@DnM=(x8+$`U7zh>gmmZ{3ZTES%3lXB?`r-4;MyD;Yv083TI~D`m*#h!BW-D zSQeL_7xIR@$gw}GqcV`4ki@qbwwtCieglqmJ)UJAa>5ksqD03p`&bFZWWkab5940QwjGy}}$I6JpIurHdxw3MC1tIA}sZ2wr4)=H~h9h`eIj ztRHq~cP4j`*AY%06MWMB6GS}XydF2uhVB}dMHgJ+xfuUAK#rMNep?1eP(NakU80$n z*HUbmmwiQu4yxVXM9L}!g7&$v-qaHUU2n=qwiDG+xJAF>5YHMg&L#R-jP;L1qsLjL zig2R(zNnXHB}Q2wwOOj*%JgiofVnvz>932DznYz;IS}_Ha&E5)xm_HyIQwZbURO;j zF#GBra9xHD3ox3wRSte3(Y7w!79FYs+r)jwjq0pCF^ZDV#f$ye7jcnQrsnI27#J?r z8vZVNS26(l0!gnt`Jjv6*Mk}3GNwe#)_3sgjYH+WETWzdiSLXHnS7X%X_VK3l~rjk zT71O?kYej+nR&zFJ3;4kO5d@)eS&k*W;8K+a=!jpwlYcg!1I_R$hK=}Q=y#D?|nMr z1i}|DNHbq34GJBQ2JKiRf#2_)1ZN6~Nvp z93t>1$O~;)LOvAtCbG)&eEU1PZ*ElbAnj*Vm@F0`X&_&!K>4NoBwSd5ARRapBZ&9c z@xEfmG`d>?YGa;W1G|b*xCir_Hdhq^wx5^U zYY=?v(rf>B5V9onSzwZTvnPI|k;j?ztmKLWu#6V^sZBT3?Vmo|{nd4+LcTaOg$s`@ zk7yD)AIaGQIvKk^zf-u}rUXyanNq}K0HPuTeLRL&e{B>%hx`DD2Jwaq4S$kvvn z2vNC;&tI5W1<%*1$E~^>5ie1pi*F{N=*~CYx$6iu1WYcfAt9k945<(CVZRV_kWSqb z&4urCmLnTj55i!i#b;Qx)tUbj;)f#oaR?V{91I-72pl`-*HXIY$gA}cNQ`CZ+qybu=YdxHOfBnjrXN z5wsk>MeZjAxN7s8&N4FiQsHFYE6RZ( zFtpVzLENRqio3g0+@TbwSaElEic68=P+W@_cXxL!5ZqmYJLKK({es-&ue48)`&wXOVKIPgzYsiNLqdt8{@+2#c*jhX8FFz`kYT zADsnbx38s!aHAb)xwzlIS|&jGXI|o*boS@lh1vViEkEHGoBG-)FB!n6;?FokpFb@2 zKp1YrIks^S$9Br>>>n_BkxO@L%^{y%eZAvk6Jbp+j{~ox5dRmPf3+HXg2@mwm;#)S zRZc1qqS!QJF6ngcd^KO|^5* z4?bGt%Z;_{qSaJ#~7sKI~foS8*yzJ;FIZM?V?i33)n7Rm}jmTu5O>UK`U!@SM69ESc)<&%P|X3h7UyN`PCXyoYeMg7CX_vTfX ze|UB|0=%y6mE&8Yqa_>T@Z*3kh5q@fLn;;H9-TS+F`)-a+FWsLQY$KQ{L`7ko*TDG zwI|BvijgwnRnnB>=J2euY**dMGXcHvv1Xj#(g@{ylK|>J zz1O|t_~`+X)~cD^%t=zb54HA3_|CI|O988^!CvlZFL4iR#rfzsW+@Sx&*{W0^bhNb zkEWRaPYU;Gr>)lokym$}ZR`rQvAb_7{whkO?f{+M6mSMm-LHh?oOz z?Zy#4aoy&Gtp;w#Zgg4XS`Xo((F=D(F%KbQQnr?K1jeQ!k#mcZ-Pj2-xth2dF6cB7 z%}-pDaI7(_RwbhTQ)zb00Xhhb(BhNIN+ zii}5EClBPS-a>OM^kYtqmChntcNMoI%}UF*RfGi}0!Wsf`nd-!4T!%ccP(^jOv6>N zZw3ixZo!8= zF_{a-sRDOws&o?KUC+-JiblZ#4H{v&*Za}{Cu_K!fYZf0f$?^pi}5;R5yU67B#A+j z`eC%~eewJ+3+TtbZuN0>mggPIbi*C?Q45u8q`SrHA!lHHNe{6`G~64CZ`5LyJ^4uI z{c|jxKlC0=$e`ye1#`_6J}r(M1~%5f8dhnPU@wt6-#lbiq2 z9UL_=aPnr-$?XsC;y*1=k-yAYFggF_-Z2gc`_?0f;=xtDhFpGFKrUY5r{igc=4l3Q z`!aXcpCsnl>*M&`O;KY7NThu1Ih|>D#4{G&eb1))g{jJ^hI^MX1T{kpb^%p+#)Px| zbuLso;=|1f=@YsheTHXpxOsEZtt{yj|Ki zb7OhNZ90kfrQt#&rnkUTg|*>cnU`N2ile}I%}{eQ--b>AwgaVw&mYx1IBpsdzC@-Q zn}$d+2|bs`Bvo^*KIykPjEKgzq5uZ4L4b)PqeIhe9E8~(m2X<%UyQ^htRPd87IY6%^WF-FqJ=59qyb zf?y|5$9DwRAImv&t3Y=^w$f#Y)0G!u=;$VaMs^!g?>Ny)H7<(XbbqtPi7O3?&Gdk@ zv?#y_Ly)rx8}I>F4qPp4mUch$xN+Ba0~^WU$+qD1*IXNK{1;$}3%IWxmD2c3laRdJFQ{Exgv+8#Tb#x9M7v&KIs?KoJJx1HoI!)kD$5l`= zF@Tfj3^Q2;l}XY%Uz618V*$%af*0Jku?Xzg15sG!73k|q9}Zb2{V(yBsO$3uQBvY0 z%XRF@OvPd7g#LoW75D>iPlRncqni5z(g%_Ozf74t-ojFU7d6pbF3~XEjBEh&oaV7H zu)q%=bMRh+eM^lZ!olL0?t;_OM~kn>J^?MPP=tjet15rpvxx zz5c_Qh3*F>URv=aOI_;C92UAd&bUM+*9NG)$LGcEsNvMW!yHgm?i_$sP6Kke(+0J*Q+$H0fvNHBHqY{eyThj3_UK3Y~P)ql(@rpUqhsDgzhHgVE~NB#ZnO zMR;p}G9Dg#F>=Q|sS@qnp#DykNa=vT|B^@U-I!3*Fy(vSst4Z1NE}x)WZh^KPKX;l zXoZSd>=0|~+PwuKwmT)Ei%KiluX#}Rn4gTO!}Z8cA%OV5G-rlr&1U`qIPAe}uKt(r zMvL@}TGqv}rTlY-^H{4P!h^0iigR0>^e=OipO}<~NxpCAR&*`3Ccntnsk#mWO6ofo zOMP@7Xk+K`gI&VNuV=M|fRvb6z31z3`5b*dkdM`B5tAypj}N-%6j3yP_@Mp1_(8n< zMS?oMd&psyb+Ac6`(#mo7lScema9yc4$xDz^DfrYSfY642tPkrNr<*^?H+vh5Do#| zz1h6$&gX&*s2m3=?T300GG6OnbZG%gNDAU|9(NOzmTHn5mS|(>mGZ9CYIFUF(fLT* zd_Vb`f>k>lBz zmaHQ@XT;_Om4#j91%RzKeq{;j9sE3Y|5r6*?*iCd&Mlu^ad&TN;nw0p(|cgAJglfr)zMsqSG2aj^u}okPLU>M-Ia79Te1)LTZ!# zD6i3BeqY4^G>?NJSu}b~hc|BTpm1UatXqb*>LW`%Ik#nWgdDvkK<50~-4eiGizb4f zygu_Ge>+y_pU1E>Uu_*<;XwOxihRE>O@4hu`)~F})jI*VIwJbqsA#`-zHsQ-nR!0m>HQw~y1k!#&hb~RMvY^iw7C;#wD)-2ZIa?R z8}mBC-r{VGzdsr-b^h{gg}>BJV5W@cMT_@Lc&tbzC-6WOomnSZ17Zd`Xs33CSkj4j z1)Ipq%W%ppGJ^do|FrB39nsTMbNUW$02SwjHGx{LkfIYcSx~K#qZy%m7Yt#TGSuCq>wzFVnZx3I4(zAF! zIe2U&^TU;;lyQBY7yZPb#Vvek*mP_Vp(*b8zdm4gA{tNU@m{DL^eT+v>vy?yWLWLUt6~>|x*j3|%VFaM0TYg)noXTzTwU)O ziT-Q}#6NRgvKIS5yY`}o88fS!-rY$Sjgw&((FZFsm$UpyGz6GM9&KI{1a_EPTcB%| z;`s6lIR|!;D*`pPc;km~ti8@9PW#AEN4A8M*ZEQ;Za&FOw_jP@ZP<@p@iX|GL0)nN=GB$ zQ#Y(mR|LkKNvrmCt!m4EIxCD29br(N=mVOX?#gLoI?)kv-h66FDq$%fL$nT_6yIeH zG-sV;MVyZ-y8q(9+P&I}aA}ReZNp-cl0=k|<8_QQ|9f4n1zV5UhVsq?#?9BuRht56 z!j{>yWI>Z%OkQ2gfi4Ew4X*oa`y(sWSvh2#F#4=Vlg|;mgGoG?OxY5n><#QQ1nH() z(q<7hWEsM+71ey_w~-3&?p)BL__0T zm9sL+4@`35~Im0kB!fv-EA} zA|dZRn_S~KL0pU@$MLo`ODIQotHUd1bQjvxQtQ%?)qB#bS-fROp(?vTzFR)Q%6hyAl9-XaU%L)vkafwZx5NDA3Nw;imH#p!RM|sy{L!V;e;Z92J~1z`wZv zEYF=`itIocj>Io_fLZR{uagnW_;9v$p&oHv3Y<1uGU{lI3|p|E37Ul%CbCk82Laei zU;1BlReEdTDsud$j=Z0NkTk5J2ni+Q=6}b1{HXnI1W&^J$}fe?93ST0SuMNdXG?1X zeiL{yw2a72Pg^*b_!(DYs2Dzt{>Z?R>3eJHSf#WAz! z|6+R*$Qhks?$g3N`X5~3(ki?Nq8jg6>^S)LW7`5mSjdsMT?<9ax2gfbs6re`ZYs~A zd&3Ux^~^~V_WB3Rj?Q$t!E%E_$Us)EFtt|&;^iuQhaa;9#Za{e{Ag3M(SyHko?#3D zB2jX?Y4{zjvn;LFQ^+*-x2;r1y9kR8H1+3=O8*CT!G;c&lvW!{R-um9t7)RRg%R_-7dCaRY`exYj7lN^zcwBKS3lWx0^8h^|~lqdLhDr&9+ z4Zs7viSuy^&y3zDl_dqRoIA+O#KxCdA02~wk}M~7T}<4-#r79}SrKxk%O0!xIEtzh z1aSH&@;dD$;7v0jIdExBKxXDcws0!t{opzHx=+&OW-@-l+fmdy8{~E4JClP3APV1D zK{maw=1^MQ1(h9<)buGE8A(iytxV(;Hq+Nu{6kXYZm^jY;lz(q;y!>yFX+JI4) z>)urj7-Thq?$8o9@UVjt6Zh+X0ecjD%D01?KJrHSzkCoK=Yb#hq57|H1fON#bTpe1 zgBu=F{M87d!X4e~;*~hKG8x44Lo*y^slNApvl_D7Jp>q|r(xyp!5h=6kS%8kd1;~k z`s7cktvYvU@%2U89RUdbi`WlM7Vm^nSa-`|dtCcZr?l#^iU$~UL){ZU9SfPhiCO#r zFI3Ho5A5soND5^9^b=WJF{>BBby5=!Wi|xz8{Ww`_^E_BQJQEiQ!ti1pp}q+&9P=n z^vTCu9;4C^V)&MPnCmMHeoQ-!I`mg_mc2+|ntaygN5L?|u_sSL6mR-ExEt~#JydPd z%>U+2;;eBF{#tZlNX%3yvmoO1^TkL-j^y)1mz+_W-D%IVC>*bxd`wfrI+SvjAS<_% z{~(4rz499&k-oQxZ~&Hv+ZX(yJk1H8cn3cfEIadG469xIw4oH?inW zq1W{%n>`0QOaOU>6nnHk`KE}!H4c6nhL^kSkwHzE6)uvxp4P0(@*ons9}S=~ACQ9` zc%vRJ+vNr_;juq^$*~=aJ?&Orjnu<#WfbNQGtN^}-amKRHp3#FEfWilLSNL0q^ ze+OT$WYEjDlJ^|6~s`cfux-a z7&({nBvLdSY#(0LH%!v9-iys7?bl%wxHHfT#jemQu$oOOUmPCdMJM(}XQAlX&rhtX zMtjFvLL}i_n-gN=&hJsZQ?OSuBxwX|tStPAA21nR(>!mhO)AJcxPPU>#)FM`k=A?1 zOOX-!b)v-hv3giU$v~MG(hKwLB6Lkx7U;odWiv+0L0>NWx%f2)3+Z3ohcfKnt%$t> zd@L`-#{;0!Ukm;O)TpB%w)U|gdRr*yf z(%zulIOf{)=p{zT4~pP5AW)oG_xennGz4Den{@cbF(wRMS?;pxGTXpK_(zHholu?3cZN%jc#ZV;Kgbf8d#5jEwtPntDXK@FjHw){aOE6(&Uod{8SZ~__-1aG zHu;VN@dutdiGx;Xc8Y^P?$%GJy&rj3+%j~c-{?Jd`ev?>o$SMVH=zH>ttBic{Y30+ zRtg%k{A(;zE%isi#%x6P9*t5(TTCv!0WIEDJw3{xZ0^zp?z=Lim>H-v*BUG)7ey=a zDbIJGuEepc>~&K-Hj1DR)$yleqZ|s!nMefNE?u)}*P5P9H+p100#Bu9x6iA)R3qu> z9(CJ?fbc<}pKrszHV8!E`3hT^kGRTbQ(W+X2K$@jhrXi}yOV4z>0Yg|Za<7I3N<2l zAbzX<3Bfu$k#k2B@_aexXAkw1>z285S!>RoyJqIGa|B#=*$e?5X7V#)DCRHxCzpwbJKHp@OKkn@`LeSPf4Pa-(ev)zt{qEWR| z_g@q2>Q(WY%%=dtmduBXMjbjpL)5MV_E-MODK_}jg<4zNcG+~^{>ECOb#PdUE)Wa* z3ffD_YVA{8QQ@4wOa;cuz*($gDrK!0RKf;auWy`8Ohd_;$83PnBqO_FrZ>I`e61xy zfQTd~Q}tGR@>n)w);q}_SY7KBl_~_k8{kw&YM6oE?w*^QYq^YiXUA{;fstXBCFq@G zj-x-^;)f<4dKwOpEC+XZAKnjn7Xo}hnA1rfS*51-1 z4BcF-r>mfJOW;ExXBMVRS(Dm3a1 zx5VaoSp;g-L6U*zo!>dJ5yH=nFn$H6zGs2mA*turQ6-O{wj4@79%0AUgJ&to9ln| zAe&Vl@wTb1zs0)sK{(FL$m5cM>Doh}g~U920Y?Qce!&3r*S0ljJ1C+6I%rh@(1@Hj z7q-z(I!XA?Vn3yd+`~SLc|J9+!Z|}8f>c=V7|-Sp-J=+fOv!8af5vjV0veGLo5)RD z#rHs69{UQGe-wFjf;2)xuQc(y7@}ta+0lMR-W_hHOZe<-3t~wHF@WjhIG%?BL64}I zciJnHN*Fxz!ohl+pASY?&Jpq=J5vuvI(&AKHbm>UXye zUPY>!w%hwPVFL4HZI*O3dM**KTq<7vYD^_YvK;e6=0c4L`CG_)nm^(YBBhrz3>PTG4%7JfZ=Mk+r36+7cC+e&kpX*Sw z!sDurrUZXVitD_Smlx~nn^V5#x*%$lKr(dLb=^AUwTJ2v^&1Nj^3*x!XbnG-r71*d z9xT6At@CFyd5UH&AqaWj{>q*ZUzmE%{?!R;z+qZ&4o2820hvf?1%r1!o8kA z2cs;d1M8)cvB}3J^?|$Qm9?B)a-}v!^9J|!(7ssv?Slt~Q1PNsj@D4d!IxrBt>E$v zo{yzehe}e;E06J8V^c!BA2wj7R&j0J0-hD@ZujJ(v8RT*{9gPG^C3tzOir=oa>al_ z_ezQpBoU<@Jy{_^y}P7QJ)jDKS~huEn1`tzVQ2eG)^fP zDilRPUgqHK;QptNxS>&33tEn9D>dNidYbeY<`D9qbac}l|3%LgYf^&>CZY5h9b`Jb zQh)yT!HHI+;J1p%@yLPsDoT9#^r5p=S7A`;2J=)U(*y8wm#d@8uU8Nl_1)+$Q|aT4 zM4{h0x%pyRnQTuhmmHWj2bCYYTWO~$)l&bsO{|L%u-P4E#alC)??hKt@!nXE?e?}MT=T-ma;0HI zuE$#0WFPRafqs688)@kT^=2#ze%IjHwVFo?W>^1tzGvJE3Lo z+g5VsHU*2+*ZHr29-h1A3)4KE_(z0I(!2S#%Y{}OCd;7YC;b+qQOm^WPPzD{#~}-Q z?RIk?pU&T$z^qM%GETooUSB)?(1Fa39Kk*JE=^=d5w1J*pTH8sJM4&o$NPqbXd(G5 zfk&ne?SGn9_bbuJDfAU5#yJ5$Rd4eg&*dz-#Z>XnBDr24PgR2a-d(OkY6|RTrXdLr z2I&9Q^5yi6--x=J2N7{e7IFJOjpDm%Iw@YzK8%(?+$#ua;)P*b;B>El=Dky73#K~Y z0=qHb1A9GIBS+|OILEKe8fZ@b0p|1ae`)i(g@@FBAN8iRAKy0Fv0zhsSzL(-4+3|+ zxFeZX9~It=9uxV)Jre4xR`KDj;3IT`E}>e}jV{4G47jNQ-j(-JicMm&BN$jzMZN1! zaDP_VBKud#*BFJYHvf0Y!GVdYi2$6nroQouBw;)a^)3$<`u=@DF$&;YyF?#mrv{8~So+HufZ|cADY}iC344*+ z^^;Z@ALB>b_kUF0^))2`F{o8%h){;7&HI@6is4`Tp}*_{{{nRYfk(I}|NZ z8p)_!R#i37McO&I>OM_>Bs8}}V4pGj6< zPx}yo{<*9~$dLPjvUh}`I_zcX7`v-IrN?{ZF9YnNb9}?X4}2lhdLO(`tSlv ztwMBgg3vAuH1M3F=(c)q4JoNw|%{WHuQF{EaLJ#0dIupNzgX36*yGPn_MMOUz-Ht`a zg)+MyoWH;NN?Ro#J?^V9vLU;hNqRUYSPH2-F&=$&JH)ltp8jHC;Ik&KXI6Dk!_15@ zl6V$i$bxy@Z>d~)mhwCY1sG&ToBjzWPB*T9T}mH7VSFS%X%w{H<7eOhoBl*=7}^;y z?aRt-5%?l#j!_872cRzawUligzgZ;r2PSt!r&{V8jI^&JUA|FTbhBkp{sh3LP77nO-38u*zM3CNWJx-u$f2 zI+(AYOe(bJw19Z`7x(8qrTjzz66_a|ij$LXf5i9UN3%8{$& zt2J6IAe*RJ$8Qb439Z75_AP_&0j8a(WOHRf>myr-Ulqm?w=rb2jUt6i82Z|AoOt*KlJESP?XJQ)ya*7(WhL=n4D7l@;-#`09#G$s3*K)C7&?h6OFVlAVAn zfLCrDCnlsAZMYXb8+N+kMR79t_ol7fATT33!mr-NCYwn+G%eG zRYdE+-q~JOw|Y2ki_HpM+8Jq~T1#)4eMidpb4iU<$6TC17aQ5u1uop8DZ*PCj|$Pd>?#sx2fKOscs2;(So|JMTfHKU0*g%Q-% z&-r>(I|P;7)3aj;4t%`(tL&O@$O>b&P@W`zQpf3Z>vH*b$BiF&tZl8hPG{iK3+Uc- z)$`{?Y7x^(%`nBg3gqY>J(eZ#Fb^0$T9(`;57F!!5#a=YF`MIHUy(kx5u0s})${Xf z)u!RKERPrRh`)MU;j?wL*t_R!pQyQ@s9Wj@;o*fXu;-vOB63k_yZ|i)aj31@P6~5v zJPbJKdXb~Pz_D+w;t(UxtjzE@e7KVQyD465dvXp)Tb4^)3CEq#oovHcggzz&?@%Sb z^a-Z+etB7bU;TIvwOnf3Jtp;m?3I^q*ZWEg9bgnzvZukXzwo!dL6;155b2T!B&r*_ zwDDcJ@QAIj`$3Zvt#&oDMy7^+^&3l1IlU1$84;&-JdgSP&-hkh;z9o_EO|!+N7rIo z{MI+-Z|i6JLFbOAjV*MZSf4Z9)ax`9f#C7APc6%C&Ion{K?$*AtdvE*6!^f)M-kMFMN3H0BUvAZ<-&@vJfYmUe_x7uFkIiXZ7h=<1+<^l--3r z%b?QwU){u$DX83|Z*7RU_+NmK?-4(+`MhahW$5+tE{&TJPQ9Wv=HK5c{_<^>+lxW= zSe~{X0%_2UxZp3K);=)_l5}uJQ1C83m9O1ci5p)i%Gb1%&=T$Ph%mHjvVt2H5H<-z znD_*a3T)hAj{;CUx|l@TO3baqLbXJXh}mHEtRqU0X*51EcjJ+%3baGlx&GO-WWbdv z?WHPh+GnCd2AG|Xsbwq>j$SLa(?)Z2Li|4r!^>bysz=it>=>=Gn(WA|MSEZFy!Iq{ z`hehHf_2xSxq6N~=r!`UcFk4mF!TL4yj5ntP(KVdm~5^92V#YVLn8?>LJ@n~zrL*u zlE7D(BKo@}nuo$A)qT(b*hNigRMh0^q9pQtV)l&uWy05TcDL=M`crXdf+c_Q8mJvn z4}9`v6;=}9Y=5o#Uu}VUO|yt)bdjY5UakK8480gFXmF;QNgdxavGyo@pt1IpCRh zcdz5T9$>XRV-#bwP>_dh$*5W;%WFGJU6*t9hoF`!LDBjYz-WSNa0-!WN(tE6&}g?^ zJRA}z_|u!vp+mWUzC<`>zYY>GxUrv{GOIa{zn{-3z*$QmAeqLnf`DDC{aXsO%Q4;f zWrfKTcaYE9pVdy4v2@j&b4zgu;R*MZ9n$J!f&Z%e>%{qC39VS*E6QP&VTcjO)Z;9A z?vI^>!vGo^276F9kl)m5=$pprJH);nlmoU2C_KtqY5+Po4Xy`c&|oY z0B=CqvlD~Z!Akb$%(EWEX+dlJ%@q}8pnY|<_fc(PpdywxJ@MP@gztLp0;%p^;XO|J z@_)KIU=xdFCBBG&T5WV77=zxveBywprk4api#*u73Am6x1aVI8bQH8ZLp+6@>3 z^8{7MXDB<`Y=;cpn+_R-#Q+S4rEt-MK3(ZnWcm8rG=&>^C6vH1qqNjPKb<7ko~GTj z;M!Tj=|k@aql&x8}E3G!Zk#k`vHMRdpHx{n@qm2Hrb zQ`!|Kja_fvuags)6D>0zCNYqFGpZ~~r?F1K(0kBksfT zRn|Ts2aWKoC6qibKCCI?I8hu(w)UZs=tUZcj2vixDed$;tK{E^&VKQnce;W{X`ww{ zzLbmtQbZDKnKfL~U#q| zDFDdal}t$>+c}w8-KVelJPx(IT=|nLcJYI%LD?|qL;%XA7a!?cLLt=m)*(n&$~Pxj zO|)$jWZt5nL@aPMvLj;PZ$FSJ`z3hgcHcMI;cy}6>^mrH!(-(^7Ys&{M%{|L&=Sp=Rq$ps_l71?<1{nQn1kxs)b%`LZBFJzGa`rGu(m8TJ zYGNM_XcXvAH^7=z)|Y5LYH9^N>?>>OPc8wkQM--N%wq-`=uM9>q?s^MkoFGkX{L|*a%LN#Bet%qc7aF1|5(S;XEbO*@Hpg( zYsfYVKa!#89AGc`lo!^pYQ}C$1YC7PA&;GzCFxsB0nH6Tl4MA;srkdwIM|C=8qK8D z(-ffYD*q4lX>dG(v<(m?B|uqPDDP}SmJYu{OhEgo%_=WfLxS?Y4SxGZ+fQjxJh$a(t8(?!eI`-uyhN zzOGt>^Zsfyd$kJBFQd!qpj?K>YD5RlCK(iZ&c_8@+#8ophw)g4b zc8F|Zgld~+T|pg>PyM0XtOroVTs+Z01lr)l29lU45W%qjsS^pnvu^e=jC^y zH@CR#pNAUQF*>twuqicDa{2nR2IXvb4r6h{a;R6w!r3+u3}9Y9yx8^SR!&&ZTF9`E z$#Gy*@c|c&uJkRM3y&p@yHRz8v%-kuA1LXlQiC@_;BxniG3>x5n-TkRRV}MbY;Fw7 zMtM29d$PMf{G%&LhF>$D;)pIkd@cDF^w$LOE8WFNc!@;Qv<0eo^JtJ_r8J(MvM?9k zNxWE%0bIyWa}&}a4LU?eCEk8kLPP*@e9xqlE#cPctuP0v8-_D0Y~nAv(z@Z65^)tS z4Mcw&p`aVG|3-QxS=-{1TlJ{%p_FRV&**iXv6+OJ@bjOp?g$v9n|!{i!c8d%^gbvC zQ>UgI<+Ab}I-33Gal}!w;eRbrdc#S|uWl~!)?K|6j8oUOx8L)gq>WP8ci9e&8>{6t zg9zQ!E4Y9*p(7fvN(Uem&&M=wy$hEPiymjk!{-p8cDr=#yKv#9N_1bMeg>kP5ngZ| zZVtx;#^?^Xl%@itl>d9W6N5@N9PO-tqhjb^vDeU;c`s*SRr)`;hf{Mu-@g5{x_+ze zimjAw(ntc_`P*rm)6?w=pi{`|76Zb0w)=Gsume&Hx06Q6NPR5eYb6`*ygeiS_Eypc zZ|ClL!~-fMPLSUdNYVb0Wq$Y9W`J&<<)*0XWI)0|fWer9hAafetazILJIUbO<%DaJ zvIo%~05CVru1RNkzJ;UMrRv;cUdDxs(ljNt^2Ja&q1bh>CsB`z z0=~K;nTii*ao$^^X||2wen?2aa`w*Oo}sjv;b@m*-ohtW8r^$$FX18t6EO~>{<|fr zeUjWs6pDMcgM$|ebu>PklsxVwq@euEwtxOiLMI{Nfj;M&aiJcRoslW$A500Hg?VVT zg&$-DE+EwBEj@p>2Y#CVFW#G0ppC_)v5PFhy(|%Q`qkYFl664%ig5st6I>UVcCj$4 zCs5Xs+V()XfduS)wF2mSCb z+u}t(dz^HWzf^{&AkgL*cj|&)jc4q_Cu~Ph%854fo|XXE6nk|F$!Zb!ET#4H_dE}z zXzK52Ar~q;hocse-!GWYhF0UM3>S%DeUdu9Hu}c_8!Cui1Kpb0P&iFS{P!^aEvKtP zJ)rd)@}tI?bkTWJIG1WDUH{A^DB^?*Ia1vxU=Twr3r1fDhK3%@;KD0X=47>S==g4i$&Qn5i?8q~ z%|7(Fp_We|fw=t{r>CzZhYbBYX8+QV6CJHCGUPd-`+imG&xm0^`)~ zH(<);7c8~`CX4rM7K0LDKeKC^WuQ@!#oPb!Tz#TKO(PtRz^WIJ|T|`0w4UZeNWnz;6Lgx@pD_u z1?jib7(A2qLMfX|kG!ppevu&Y{!%{SB^Qm1=O@g{l*0pKRfUtOB%_s=$YAB<{rKrV zTY_=8Kg@Zi#U6k>rPbk~DWnkDb`VJV@Hli^{dsX@394bAvd|U3Gmh(%h zNjKv9XbY9@gW_S`dw!sR<8@UbNg4Y!wmbGy;Ai55c0!Lw9zy?g=k!FXtE>p5e|R?H$svfbZNOWz4troRp$@3k*sE_7jh44gDDI%)jP zcQJCH5I043=m`7ozKZX4^LVR}lUwQeGRTTEt5qSAewdd=L`O!OvrkKUBf*927%<~A zQ(S)lTu+zo^pdBLxi6V@{kvCP&}W5e^0sk6k=b3KwvgK&=-SNR&wcWwhe*7SMFr=n zig4mx@=AqokYI^b^tZ2dDrp{h{r{}w;Sy!zrWNL-RhjZFE~=Mb}w%7J@9454pJ%O{8eTI*!2vph

11rycj$w=8I%GkNTE~ z)?`sPqNil_HsmYY1|9`PwQ$QQb*(+--oo^rVksW&pV+e=V$XKfXaa#XE1#xoWx_IF zzpbZLtF$~`1Cx5DA{eve7SoDd+t+x0Hx-+1SHz2v5}MDP4>`D@WoYY&KbFCAQ+Z>VL#4?XQ=jcwZYHCUcGZ-$#2 zPg}F5KJBi77>g}qo8U_&V^H}zX&x97fzfPDdxe?vci11}9Tb`7YT{qigZQ7c2sjLk z^d>y=2v+sLZR3K5oHg~Y`8t_0!0COSq#wMegFid*HnFgqLmrdvVt-U&ihL?#yU>-p z1G(NEVzH8>BZP*Wpc-+82y*7W?(N;pyOJ9?(F#8cqT^HlkD_Y~h_sEO+1Rw%cAL%3 zwvElU?ag*uZT4nN*lfG0P1|O>zW4h-KjxizpL@@9&$;I)lJI|=aa=w66oLPWf4Q$q z-Tg3%o$ZJB*dRL;;RK91!tuYR3H{v(C_YrYpMu_D)c?M#Jfb$hcYBl)BuB}85~|tX zHDbPV$q;b9IRc@gK$Fn&D(|7Zv6%JQa;?CR2)buKS}>=@Y6=`}!b`$`_u ziCIZ5(j+%dDY0}vgE{6!U;JR8H-9?yFs!L4L1asCYneGftcguOYj#rL3ksVBHWbGJ zW92{j!4G^Z6+2JR%Wp`P?nM~4U%{P?v5zc&J?);P;qRw%r@ztYF84u7*p%^vT5KkR zs2+taO!Yt`BXOJF3}Ey>j_F#fw?~*$5q{?f>Dnd}y~P2c%cgEK3z9$;_pL8J-?p{dR>48yhYa7Z~NbT z;dM~Zx-W9K;U`-IxtLNWsr8(gGy{SW zZigA%xx1I;{%&>2@5p_5^>lY~=bu70eR?VWOlw2_y|8vw-VE&{e)Gsy~pq5={Y@A}M~GI?;U2|*9zoG0*@ z5B2k!thgAA1<0lYsa&f!n?J<(pmi96u+{*zm@F7PT7dAI?DS=T#br(k;R%^jB z&&tY!%9OZfuMw>%Ni!3REpBn}A7wcxxN~fPGi8za{Vh|qKl69aBi3nt@HgYv8)lyC z=>1T<>>tVE_S$IWlbPg{qBcX*Q(~@we~IDTI90z!2Qy>UjB z!KqiSPj&~#i>L!rNxH5P>G>#)zy85O`AdkW?C$CJ(mS`={Waku)Pt|4oxVHh+bNpRP< zA%u)DKHSiA0KADkub%T5M14p4{@6sbF^bEw7C$Kw)!mQ zofPyDuN9U^n<+ZL31+;#hy^D_>JCQ1YL;sC8w(>Al0T3K`#ZVh-lVia+**_Vay)hb zCd67lNm0*(#^AE0J443;t7bn2$_|bQ%r0{Sb=ZS$XfR#j+e}&9N>KJ013Pv@Ac0P| zk0o)@#15M&y6MGu@{FNK_sXbriDAPSF6Wi6S+3Kle*|h^x~(33*%L-v!NQRRhO2km zZUPP3(4pT;1FM5Hc7#|1kM7RQLVH)Aomqb2zeH%6&sln~f0CWpJM>WiAl+TZk)j?S zcHfh#YAkON+Htc}xUj6OMB(p#r^A~~Dhp)W0Ex;2ZW$D}4hDK>0Feu;``-T{%(T2@ z`zus@&;(18Y5B~w`5MvAPGhBydyh`Wu_n)6V44;(r0m;Hkp4d)zj*u2W9O?*Jl*aZ z?*~8HM=Tg-!)Tl-W}<*PbD|D{a4mi){@ZU8Xia;E=}Ln)aeN+X?>Z$u0XBL%nUYt@?4(Diq&3{{+fh7o<+MMLKKE3}#4)8c}y#_sVM z>;2m%IpR}#btnHU2XJ)yuV!`rt%kzb0oZQYxe9RTS8fg9qr;!ng&Ws0Yjp(18BlWSlKe8dxu zEe+b+IfM=NSGB%mVFaNt-DGL_95YFa6L-8L>FXGE^9$k(E+h-rK!R}4$Bvcd2bK=P z=}3i4?L7zOFJMV4#Fo7d?|UMUfal;dDS46>W2WP5NF``XhU^5lznt~=@(+kQ&WAaH zNrPW|6(}RN!r@A}Hy`=;Wk!gzHJ?rm>*e4^*E@C3C1{B^TT(~Csm99Q9rwSauf5EI z_V1BDlhf@OW9zRVL7LDW5 zIOChALH^gkdm^x$hd8U^oCA!94~MYPn?iT)YOibRhN{c}eaZ+P;#g3i1@6ONwg=ZX z#GtfI`ngEK4IUVMKGMY)L0&Z8I;9|pPtaa=(?aP zS`)FW6M6uFo&;bJ215h2=SyY$>WGGk6Ib5u`m`LpvNG5oLklor&A#UI*)=C4&f<13lUZIF9ihy{t*9^Tchg5#w1Q|oeigr)P_tnB!ZL0_WZ)jx<>2E7 zkrob1`e7mVNq4go?f65}ROF@Ls&T^|rRLbB5vE z*`?w!d21C3*Z-Cj7shMk@|=?RY?MBmWu6B93LGTY3tR8vccf3wv2o4`>7g&LylBX1 zb-|6F;D=IDBOrXNRF1_yage_5&6xT0{VD)#2o&L?AWJBS-M8wA9xs1FpK2Rs3!EA% zyrx>z^p>cG1vovf4>xbnLbi;YkMH~gW><(%O<(Mp7syOHqPtej5O}!~`12B96e@yt zZTOxka9?~SHs>OC>Dll+S3hF^aGsAkV6aFCt8VKZh}UI*UNw zPJLRHmE0^#_blnF;A}FuzXJp)Fg`R80j&pb^cZxPc0*X%G2R3I$Wo2kyVoQN%`$k%Db zLV$mB9%OxFDQuBlGNg}r9H+(i_QKNJ`oyBFOI$laYUq7rFH5xH!%GRmj{JHO!4Ol3}lxt*XoD#zp zPN7hi?+7mMDa~7E9n72)=kEeY3u8>H^Og0g?NuX)ziKMhH$nlgIM1XR2|rfOY*XRI zyp5ykyS+tM@J1$kzAKc3dIwqjDWxB7V5dkSw6j}`0=xB{#`)# znbm9%Lji2~p2kQ<;607~8=<1G7?#COOAhhJY8ntf=P0^$97D&DgqVTV@%al}UGo8P zMg;;@LZ>BNH~Q4jc40-c;=g^~hS_b6tD|!OMNQ9zFXCNr%DCP#3+NOEnoC(OQHrep2>9?!kM4Z-XJ7ilUI-?WI(flt4PSHM{AD9tR&$&`e=|hem|P3 zw3XMmhg=;ARCg#V-deU~v1WFH*Lfh1Swgv?O7t$P=(`<>eb1!|!SJ>f@M7*E-aGf1XB&LKe|swqXO%X@T%an{Qw+oDL-< z_&iIgNYh{6#q{L){f44#D5+wwE>ERFfQt(WuhwW$qzWJKlG(ngpSPQ_QRz4R-QVQ( zNyee))<$2IV? z&<>thBAOO3jccHP+J=}~Vaq$yVY1Y)zzEb8o3Ar6lO}$B&7FBI7Vf(6_eh}ch78dm zIO_y^H6s6oeVfBS4{CtcTiAnD#aa5j(!ku4A|1)SPGm7?UIu!Bt?x&cns^qbsy0b| zA^hmMZj4RB2>wo*23}+%EbXdKP$1{gZ94+I17zV`j){;T<0&DwzpAvw2n3m;`<|&6ZCHQulA)DmN>^g2bY9A=-wYBO+Pc`IlGT z?5;p3J|UYguhl?81>y17yAA8pZnffdKBS?BGxuVKTN+nK`rbltPn@Q_no0^B zOAkj%r@1TuZJI#w$bw~I&7IxxmLhmN-jh9*+R|0g{9Rc_$kmR)c?-)f_lcbNL>GB@ zLepaX#JavGQu<;p1Qm+dl_dOf@D^=Nl0vD{eUF}l(AwYG?T4PIo{LzAAnEOBq5kg#J41*%i#Uxbz*tl{1y7N!6LW1RJsYx}hu+yC!`y41Ab zr_>zhquXQ3C&Vo>y=%ssdznx?&s__=yXw9}{in*Cr*}4$D*X5dPEx>qyJp%ayEYK& zcXxozP?8W#!9~uxt{-DwgTR|0xehQb3Ks|feY&5^Ru?%-qeEPUM z{}j>fH@4n#TG;QIEdXoQDG%{v=XW?`H#e`cSi4~K1dNtFER4f`v&;qA&PFP$o}J6W z@%|9FOW&%^Xus8MJ3K{SMHT(6@RyL)|Dq^HR!wLmk7yZb(eM`5ti!L5FbD zVn(b;R&(M0rdaV9Gc}8qqY(c+WYe$;U5WKOka5@BXG`v4h26IvzAa76ep&CGRWT1X zqA+=R9J*Fz7qyao+*j1GTh0bO?oY zmlwubj)o;Y&#w-)#PABY(To=k|MNhpULn7FPHwtJTT{_F-cv(}_;DtWDm{MRf_1x) z%2b29z4LR_{Inq)iTKm5!%6_f-m}~a0nRtaQ3?Dktbk6~&c`f5RE}$mN`XJyM@Fyk zN!4I%3ys(0NI&%>!Ltkt;HO<_L~ZO{)Q+OZDC@eQpBVUBN#a>Z8SvZgYOx&GGOIy^ z9^-V1r?Q&vnkx+&amie{RNKrjNeC+clmeWQ@z~XUV37!Y>$!;p& z+hv`5)w||#6C}xk`EOOR?!&Or2v&1zSiV^G-{ml1_ub6IH%i%$i#ISLFRs)g_e7Ue zjo>F7Ow=Yw0@Ry@2X&MH{}qT=;WVC4>`?A0$hp|}(U?!~^0_>yRwg2G3(K7Pgz#}( zl797XBqPLpPJG(#cM~vw7xl2*L9)=0p2%H_+h9nzu(=PJTlP~fc0c(Ra>|-dEhrCs zqk!h?38q-T16u)pQ$)_N^5U!M;NFNx=WBI;Qo!n)Qin~jLH5=V5r_sd=sxG{&WBYD z;7_IxEk4SB2(fu5F?djW50l-1HZ(?&Fdp5u7UZ~}=@jn)L!ubkKDH_3Cr1ldi%jBI1@+lnKDgKf zh5mw5SnmeOp0`tJ5DBpe*D!{@nIwhUL0XBhC9@i!1~-8 zU0xT>h*!As_p1cZd88DC3ALO};zpER|UG^XB_c#U`GPknuOT(fRZWDoB5_khmSYI*rBeB2Gz#nro0v( z^r>28Pou95yqfdnnF=~W)udH*slneCc*EDin9cU;wH4L#4^kpk6la&_Ata8g$ zm>A;8RIKe^fik0smhM;EaXTEZ{ZQfoy~B}FlOy^OEs!Mtqx<6fD@MqXNl;C!GYo<+>O|`w3(WD;cUOuIIDwh# zU3M@l9PjMVy^LlI;4(B<)^r}f#c49)f8=y6M8I~=(y7IXBYGLo zPct+1>^0g>34Z#5{%S_Q<0PFK6jIKx{{fZFQKn&{ZsMBc@PiG}M|a5ng9KXB8>BpG z_R#+S9e7aR(rDTN*r~a*7<#Ck5B><56YjK!Rh@Iy|M8%}=oziZzSlU$HTx_7YN>7l z7{K>RUe=i9Ll?HcYygAN86c^{*ngfr1X_IJ zwSDXKkRzCOI&sal{YP#gf3|(Ts}D7rhoOZY5BF$#x9Pcue5Kem&zaoLx(c+-$Isb4pN+2#5a9)04@V=lAp+KvOjHv7Yd_ah3P?0tq>>>ge0 zD@V|htvb^iLH*5}GY^aeKN0qE-!F_Jy%76&qeOIH(t>~iWz@_o{Wqcu2-@%(#a>d= zaLrb}p}i>iXrnzDmcd+rKXC~JPkx)=`ZRf2KcpA}@F(YCsG)U1^nG4Z!QMp-5U|YW zf!>G0&?K5M>5OdOF-AN0+Yi-;pqx`9!MJ{r|1UAtK1_M&kLZP*ZV!>w!Dx>D?o2(I z(L!8pw$`~^3yuq~+0gT4*@Vcu^xYgQ*hb{|zGG7a$OiqWvQb7fEjPKkOV%fD zogOG% zoi>NUq$>d;P%`y3B6V5lnz(uxhf4O#KXY4FB$KsY=T^7lR9{vgu1`0NHgM6Oinp0h z4q5cj&qpUC?Q7L{LocOX+@|-Eo18~l4Vfg=tAh`^ijU?u*+gmdmG^sYkD}I!14q7J z|Gy$XA&+&w6>AnnOF}IzTwfFxQ-RiV6^0m`8Rx>^(+ZKR9-2Y}NFId-1_@(X{*P^^ z{IE~v$|?&@L$(qqPt_=9)E;imS`$*4TWYG(H4G0w)e_0|8bS<&O!v51sdl) zPMyFcjAX34WtJu0j-0cu=ys2eNY|e-$JO$Xc01;h>y>X?cI}iid{5B@ zdDLOu(hnWJPnKlzIs1{l%a+cqN+)ZtTVR;$=)E8@ILdCedG=Xhszx9Y$H)A{8hH0VTYeEqY1=K0beMSQe5MO7wX(Z#I_z&@* zCO_`N5Pt@~M>bQ5t5I0YPxcV#Q*h~DiQUpU141Zn0%8Dt9H=)gMg6iVI{d-IR=bKQ zX9dsGjramd1l9R9RWKD{f1!LT2P+mC(nH!PSnQA$P;{A#%#<-4mO=(*N~&%<^IxL) zty|0+$lWqiO>M{94@IguN^3*Y?aW=cJy7+~0a9l+_-N7&1=t~4thCQ)?0s?aP&x9< z>EYtuS>Y9$xT1B4Ykr|_Z`*$in6Lh>Q3AdkLcXpWUJj+9;<)HIPb~ZmHtnB;oD4+; zGt%N8{MTc9F8sm0c8Yc;q^aKuI`HwmET+rrNCF8f`a-1Dv}js!qn-1W9sV(q^^V2# zyw0mf8s1$h<0=qChY|N&4lTF^;5t5;8M!$ew#|VP(U$wk zez=P}9mvXWC6@nR@dV0}XYfRp!^;sCG)C^8Y$Zmhyz;%7i;Z%5rrzsOyVO~zwgX9F z6}AcFUT1)D(sfAY08^@zMnm$o8E9(Zj!$W)@lfJ{UEKevuHWe7^C`?1=CQaox}6~~ z;mo$k4GL{poXYsfW(k=t= zb*gat5j|U_I9K}B=|$mR6Z3P~u(&v`uOAcGP8(&8r+??FB!}NMcfK4^cq-=sg}nVy zYsr>_At}iIy7*TX8p>u6oueWvd5Rx;f;CsGN#S15(T~+exU9%?@2xa4z?k#)CB^03 z6Dg^Enuw)j4C28lzlPt1Jj;85u1Ry>7*+J${66?sM>Z14lu(+8kpdv1j0qr|C{Z9l zP|)=|(3XIG7OqFQTQe9)Fr?cQt;X<+y5OOf|0d=AHTUhl(p?I`o?7xdrI*&9&h;EIfjOzavwi;T-kIJCZVD&t~@j)#$Hu}4l zvkVUCaFOa;@yr7x(E{6#e2#fW2xe~qR~#>HKmeef85edXOzPjB+VNQ6%IciXj+a-+ zLVl<%sOvgx*BDiYXjJhbjA}cYyUI6Wl^sJAa!Rzu~+~!{}WJ22&Re7DC9w-ra)$QqT7h7yT==^{3A9k_aw_<(uwRL zw;8`UeeTHjaJI2=!U0UK63DnOmE$0{k$ezZj2D9AvKH3aD$^=d#~<4|8W3Ng;oEi% zW4Lyj2wqg?z0N)!KAMBT)2azy*<}zh)3$vQ;Iz<`lFD%9Vi=1uYG1{XxtWVD_FK5v z+go1h?)a>LM-Y5S(Pes}>)WN|ix-K7tBb~SP~v`;;*^qi6hu8~V+%Jg^uD2iov;@?Pn_N`%7NzOOYWmZa~&WtbYyOE|DX$P6H_xFBc2Ng+(+{T&)aB*XQcw#mhDYcr;OMq*=Cq{Z&(!FL0uxKB(nZ7xm<;6& zc-Qytz#wqW8+DY3Lx;f!Yy>j#VCp}FgNayA`?;&nJ#1gaA&r$9ysnIZ?Yl`8=ZZHx zTw;sL5jjOKG$`aloa>*C0*1e$s?t$*g{ZB9*UtJ{wG_^!_!HKpw&Y*I7M0mPFwL>x32nOfR5D!l|jNMQioBA8v*Dd1-zXZMM)7 z<-K4Zn%>l)Z0uZi6?G4yI8Xd)4U1&^4$xi<4roUC<-tDM*?XBpD=SeikN9&VfMB!y z`0nA$P_vpX!<_-2bY3G^V6 zMhvK!rPlCvw})clQ>EO2P3?LOMaWtrhIa5&#nForj?zy<#+5nDDC7+TP#vFhauVq& z-{mZg!sp>LqhB)iCbYl|zQWx!HpHwNQ-;WAhdq18H2_6=*yj#xzfuJHHzmk}vj;z}+J6km?uQ?t7 zy3VC1O+cnmfQUkux?JAV>SJLh(!~7wY2!sB?UXgmRA9X&Gp*t~^hLeALdYPnlI3^H zmrp;M3%A#VSZ1Nh-;j&U?(~nIHXJ$}#*pWi`3b(OUS?hi#Kf8i&9_JZ*L*{4&irjq z9P*CM^0RV`dDd-VBotLwR`gBr`93=g8KR>aNo%4_cCbyv{&i{C66mKQdXt*H?ZVo& z9Y+M;JZ2&9l>53Q{0yUOPs3&Wtf{%TxLnKzG9X<;3<*aDZGfDiHG>xuzF;J!?PA%} zQoFvA)RMxDiPD{334I2uaLI;d;c;8)R}jUy08uqh;Lf9jRNCp+)+X^a_H%uyn}qvWsmMv2MEli%K6>rTADAQ9u0m&BvaX`ks1k-{J} z3FzxYg!_O=Evk})$?Sb&{OU4f`F6+1_N)o9e=eSFZkdPu-8yqern6tkM0zB2>us4K zh%?kyyd{@`Ge*b-zxplr1NsDY?WCU=?r)w5#y@wVf~<}gjIq)zm6cAhJ&~zU%+yMeb4$Ag|?$9s?uo1 zc?+LeR>F17IWSN7e8r@LRnn^5@UL!C2M4u?>-uDlL!b0cJWK=Hr^)P88{hp z5sra$Ex}#3s^a++5#`lG743OCfm!)L5oNOzJbQ;Z_P^nD$9ATM3MO7(xC7lROC4#J z|37sk!$+Cu%3m~7*~yKv7gB}c`sxrINHRS;c!R{c5#5P2F9Ae?iFdJU9Fq|A#*VP? z-+IV?wh5|EKk9`L_p=scDqDpzJ`K+tN&^2IYt@^2cR(y64Q|+0Oa+U{Y>ki$byuFu zX99~QNBh1&DuEvr{L+wcH%lUc7kQ5#??H!reN$bH9!OL-6Hpg=4u4ski2qu!Ktrox zag-~>gNhjHm=WBJ}S$46*2AO*{XPxH=(!}L@P~} zYGaNL3atbjw8IuZ%mffgjyV8DD9KAu{znwrkCt`#wYLZp=({qNnPy!Rm7NSfU!Q2v zX_d3R(b>{1#xjia_ z$OEao;$xf63ApA5JMg9YkrPiXrQLT6Qacp~Bz~w^vIxeHP{$P=8+#%!0_+fUrvCu+ zZws>B8&UBg{e*bH(J5=)=28!NAT}mpuCV&0JlLyhVOV#E%aZ=~56A}UY4XprF1|MT z=rUKgIY^%z&{8!MU%aK9dj>bAnoSXYphDH6uEl^E7Gi>!(DVtcjT@^MU3sZur9xs0 zgu=FRfV;zVmjIGeLp=1l$Otd1CfuxthscG0TdXy2muq)R9r1=}>P^aT`p*?QZP!DN z%#8RR77t%?ad&;~OxpKDhGyHS{${a{xwupn@DA1;v)HeqB?UEf<><|6i;9zOZBl0e zYrRfl;*LVd#DAqMv~C4;w?L%{Kac(2WcG1aXMrGh(`v0Zmoo&*(C&M^mB-I;=c7*j z51D0DG!5M~h3JJG!8_8`&1(G*F$3Z7iBcqsW+!R_j7w8lJ3027J?-qk=h=hyXlm}+ z#o(S^oC{|@$y8;Gb?_1>Y#K-$`Ts7A3J_QIM~yni+v(VNYZ`I{s`~`4eCt${64Xp% zpZ3g|*2BV?X_w^;H>PRWy}@iV;RaJ!+(uFa%phglXZxU(Q9yY`+|&b-55Xz8rxPHj zZ^NncAtU$un8swI(W^LFENjdhR44h^m_eEu&GAEs^8(%u!UN`vb`{H_zm;td{@V*; z6FbLqz14Rx7hzt_PNn<}IPBc?*cG!O2Ww^4h0eg*9L}+rpY1r_j)+LzVFHTk=y4v6 z?+ys_M{Z%dkSQ2S^!${!=jW^}97+7iTY6P{1W?TqD!-kWq1#EEyHtKrM216{R_ko> zuFBxW=P#}*-Hgq*bqIXgq9m~9{by_~3dCOD`}Gk0H`vo0dwVcV0^s9t zi_c=C7=1pMYmu)110_~>aHFxqj)IEk6NeM#qV5KW$WmL0F339Rs?rI5^jE6iUnVgs zUYpERAHUGAQpDNE+Ev!u(@-O>Gs*8^+Hp=`eNyT7gAUjH2B4op&CWY&aJ2 zdAKDgK-NX;)$C^-J_UHAO+;V)>X$xPQ)SQWN`oIiy_MnH7T+A%UA6ms$KISQcSf`0N}aHXEEbci zYtDV)L0Rx_F9R1_i_0PA^SJK`k+S`ldGQy>NVyF?C>O*EKE;UAZY0k1FZ9W(fNA?O zgFRrUG}57SF&uR)`mm?Jwe;0;_X3H;7b&0gC3&|lRdQ1=DR=FxkiSMoikL4@_u$h=mnQ)S@Tm9AI`R2yYxDPf@-@YGscs>J*voapP3KkAX`(L&vK zW1Wu&@qbJDRCiw;I<1m&5JuTc(29D$FI1EG0XzOi)lw{&&N(m)8P_~i@Gz$R?UX_$ zca?!n*jQ@K3gk)h@@=TooX7)zBPoCV8`1}k#Sx*iJ^vM9)~M+FvXmI!y+^*8_cNz+ z96CYt7+|C(As|0;eupI9;_;2get8s-FlNB`txj*WL1^Dp7y?11VguS8oSkN{VlAt` zNz&A#h;wa7F$5JMXUt|^@VL~RrR!eYj;1Z<@w{~$|5O&zAV~YQ1~$4DLW<8+XunX= z!CWU)ba4)ekyl)nncRq5qnwW#OMZrGUipBsq8R!STTa)P^``FkXH((_4d=rY?1{KN z6wkEf@+`vsspAY9~lBGRhA@wmWy>V~8Fw4uD!vDKcu>Tc-@&bU@O{as{$ zWXy?!paOr*o(f>r%=L+gb*cJ-a%C`f>sfllF@qzYje}zN``kM;$W>+)o|u#FK^bWv zul(q~eajILvTOtqTTJUyu-$4U#64p|d*kV%pAmK8Aen$jP%zbR@$LB&$7Jg zcJPLY67%tV?Pc#OfZUc}jC=E&fw)L%1?(_XW&b88bZz3E_O&K1>Q|eMK{*ZI`NvsX zk(VSek(PE{f{nF!?{*&l-@UR7I$YSxtePgp~k3 zbC$kYlO-07--&8lNyiF8ld-(RXV2D5!0DtDWe&W$8Fc5E(2wJMJI0@U#;WZstz~NN z^sX-odnGRL{_9guk@wLS7bp)YT8Pj7KtPPTH9*%lS8<=Wh$WVUI_Cd~cP#4kyLdYS z1JEE}>lG1n!!N~z8;j3a9vdl#IYu7?+;RaFDeE$!uRpB1!kKh{_9Y-}MuT@@7Qql` zf#IZx>7PSA$7_5Q_V?x9kK^-%ltfA6y z#9Y?g&Uie58@$$0Jq=&M7i0U?m($1bfar1a#wNA%f(k)MP)FA<25o>bgF)b_7vnQ3 zhi#4+r~%A^oe5$u4(Se3nxD`EYDaC?9y2@j-=af=p3+AFXn&l1-E}=fX~E2Px3xoU z_j^pX8W-A8e58=s*kk4ITxmzAbp|b_h2ZfM|=6r z4_eQ{RdBX>*<^ep2ha`rP|3J#ZgwBv&HJEo%3D#`kxjXiHTM^74~8R8SNeN6MkLS{ z2GZ!yq24<-Kzikq2!8Uu$P5y_U&*yvLbupiV&&m$rM<@*+1&nXk8R#>m7vUiUG&M{ z_2f3~q65&h`7m_%SWQV5O-O~n(@ZNQkuGYS-;~9-H_cmh^=*f~3H5Rw-J!xEl(|^s zWPbt7vUx9y)T5>$9Ct7D_ITL(vxk4xi)7|RKVDwtzM2NC_WJYG=UAi`ecu_*<$h)Y z`ikHA%!PcLX@uBT3hUqZup+v%GVQGur>{pjd!hdFEvs-OQz8k>@gd{!J=~!lz?cck z;f|L5g{D7uRx=X{^KpT{u~7Q7>Lq19$=!kqejq!TG>Q% zGJ||HSrG#l{7m)gS489My0^z&YLLlj+h~7*gp^?m6%TVnUZnvRm&%Con?Eb`E8&v5+UJN3$PcoB1?;GPnJu+i0jT5cXM9;?;OD>pvd_Ia9S~+w zltwi8hM@}ANfJ^sQyN;7es0+);z3hTvqo=tVgZ*HO|;uWHtouAyBs!c|`Pa~fl+ z?7vz{K3i8!C>yR~>kGYbz?ES^DgA_a^A~p8I5pzuG17WofQFwLy^N6SG$kHW>)!UGU@{K}0@HOo~_(+O*LxrBH+fu5^j>!6zzep0lnW6@}j7WmQo~@zHcru z`kUD2<1$$6OAKThC(qSQ9DB&tVw*IBejR2LQvno-9M|gR(yKeQ_GjzE>t~+oPcgv% zwlP?vjwXU1?Dua%;5I?@a4 z&bAwPc&jh_8NrO{h;pJDp(q1BBmVn|{zYd)xB&aYUdX9ZEsiKw z?wp_08LXeksR8K78c|h5r|IsgTF*XJXdBKYwuCIh-Lio{3Yfp-VM!oIm-a>wQv+t2O zzIcGy2%+FpeP=)A$1U5@8|F1h)zUHo*+F^jd!6{B`DQ9YtzU%Eg9T-rBS`3|iVT$E zr+Y(P_&|`ZVM%UYCR<34&Q}GBRopm$5|K)YHf|}vSHTN`AAMeoynbI!K@*dFw8cX8 zss(8yFsuEVJQtGNg85!&gB^%A*3Y`)$+Zk#0h5x>bEQUFty_|_gL4q3bhv3Y1!0o5 zrhY38PazHLl|&)`i~r{={n-OuE304=!nl1|1F#$KZOv7f*;rb_FhveH$3W+A;OMkw zHUC*zbaqQPlLZ0b6GJ$nsJD#cB5*HRwSxe3ywxH1k^&W`TnTE>?`;k9wy&f5f=A^2 zpu9-dR~;FkdWV(e!3`#+7VX|9;$Va#_D&0{es4Ea{8jsL$R5xQo6CWsHwn^*{OM9J zk}d;WZ8HA3%&B;lK=$Mk)-7g!=`)EneTH3{`TfUiMi(tX%HA-M2VS8TuW06>KYi2@ zxcio<;vPe`;ghwmnntB}eA1W}=-)5Mfh8B~nwdwUhjAUg=JUD}CeM0uZ11fQ$^-() z`&xK9zj-0E5hPz)cb7tgSj$kcqDpr`;&;ab{HCXs)+G~(p0;9F$z>JCzSKYsNbe1~ z$291iWf%OSRHIDTI{pt=h*4K4Q)p;!2L9T#TIzn^2hDasjXQ|4S{ey>Xd6sz8ubU; z!GyefbN&!$6Rp@p%iDRs&|ltW$D^L?p7sNdb}qSyNgqCbJ{#wVo5|#b1HaZ|WSxI4 z?KtNZGv#&lTjI@ZDX37VX0J47Lb3;-77nWvLTq|2e9X@A)B;Y4s}_wgxk!VedZNKjWhyMBd zgP6^6Tk@Q@7shtEHe!WXumeOVGhux{*c){pC&Z-ymV=g)%=3&uhZo!3L_rnBw~U1~ zD_a+VDeY~Uo#d28h=aBud~f@9_+|;q5OIYc!7ApfwQjb z7+>`%N)dIe2(tcnOaalH()s6`j{qR<43d3g6y$7z@h<%OD&!i2h$K1Xt51a#y?#P# z!K{(fFoMc^!~-)Yw%Hh+5zh#WBPY5^XzGpMddlnW&JrcVccxg(g{vk|J~4X;`wrF= ziqa?;1je)?ifQ)f+p;!q?<5Geg8wO=TMN;39zEAh#UX03e6#$h>qHjxZ%fK^ooIBs zMW4!dq!3#UcV3n+&j$J^6izm~r!*cJt+mU}!CPRG+woAgd5|!sU_um~7{27HmoWB1 zR<4xjMh=hS)ios$I_%n=?>uLXO}Cz1v*j=Yam~-QmAkT!*}shYhY&l^%viRt)3S*_ z^Rm3$Ly`?>i-qbQv)%MfonD64ZZ2ab(6Tm3FKT?>*{=QUAM08^3rtE=NgOa?UCO-? zexEf3INMUXFQ10`A--m@myg@P$!uqs-Ld@)j2F}4ivJ| ztgiSF^`O4JM9{rZ2P<^-jG)?MekaVLewnvHuOhU?4Nr6b5zUk7(AJ*Rq(DCKGxbI` z^YB-%^uOt;StSc9kae9g%9oi4eW4Po<=>x+aX9f=UfxJYq5w&jQmIw6Q^pZ8sR;AW z^>a@E*kUZqgm=1(Q~M103!jt7z=ryF=BmHABc9$+pFWQXa}@(D%F384Sb*Xco(Q9Y z%bLS*i?y!${Ji&*0>aaQd#r!`@76cU7a!AjL?tV)w=_CSK#QD&u@;1tQuJpfFsOIo zt?w*u6EXe$>wv7}Ok5Wg?#sDu5BJ@o5}To0%}JFx;98V2=cpM{MCkn5jkm8k1d}m7 zqhU*J7k%l`%z3p{yJ~~K!47!YLQKnVpR60!qDzcZ)CXM z+*#gS8o$^Mv|`@e%b}7}hhbb2GZWU~*nq$>6}}?zilm}y_KVu-ji!cQPgw&l+1vxJ zezTXwvpB(%AcL|>V;Y2dTDN+bsb2sCOF=v9>^>vaF8tc^Ce{l{c2>$kdCwm~rW_jJ zmxt5<0)d59-7SddA{gz>Je7bqBkJbQsv>^$4s!NuBS|-g}>w3vCE=jGI<~3VRn1ICg zs=n4MLGiz?z5}X>wOboSK?OktMQPE4ii#2yl@cJLB6<)aqN23uvEUIQGzozeB~lb= zB65%t6cq(2ibx40ARUx|2*Cgegc3?fLJFkM&AI=*>s$YwSu>Nh=H1D9vu4jO&wlrV z$E~G2GGw2+{+n}13p{*}*)M#LVb3W}yGP#DAMbt^U+HfZ51UuTmp8iIBIoD+b~4Rz zF?z8wyAglmb4x|(qcv_Zo9`hf3?k>V^b@|BXkR0T&R-?#t75rBS^J6Lv@^Z$cg@-$ zEY$TK{`8<3o_A~cQxTL2^u-<+o&D=*RQ|dn&)SgEI2Con^HTF;3=TA`V($KKS27Z4i3; zsavPM+u)x+OQ!hluE5_G|h@}dIU zuOimEEw2rFdi>ph#;V+p8y_7)$_$sq_S?_9^jx@P?{I~#-4kLurQG5YOU=}y-NetW z5nwM31}!b9)fTeOE-HDO8@;x-b{D(1np|zJ3s^qqxc(r-#`0Y}BH=^!(y zyI1k>DLahQrZF+WU>zrqXJe>ZhZtwUDxd-)1dt!XI(kvw(H^lQuGwVVbI zy)i`+Sd$c?%2uEi=V&?S+SfKJ%mEi>w8qxOl8qJ@@9vBoJ%~gJ-y0EU7Qg4DEbpwz z=MKN~fNfFvL8;Z<@pS3;bzF>u>-%im+S~QYi^thg_lx^EV#D%*b!oCyhGxb-AGY%z z_o;_FsoceTpqHH8Px_tuoq{^+P3;m5U$qQPQ#Y-M?{{MtmJWS)%D?txoqDgHS$WaY z&rlcarEiC}%=V}mXJ)~~*;Y=a20n>tSM1kBc+w0!F2x4r#mwJ~8k@5Zjr#R-U$T>m zBcw}Ehn+Sw`R8^|ut(Mv1)%LK`)K=(x{e2>B^_-HYZRG97zLg*PSu z1|_B-^(z%$?l(R54~Yu_or&^xy0Rv9()6ArCGQ10R}|d5D(ZvM_jApyO~{+ryPmMo z-XlYsn--vTEo$ld1C=DD=+O>b$;7WQ1bZaOiTNk>&T+H8Z5qmP-t_Q`iv!IM zOnfkWF8e#aW#zX+_DoiL+F>>dxVY9U-=iW(((}kwsAAwdTWa+~E^B+xQ0j7xF}|^J zUZxx|ySpVcCh*j`;LyEG&l$mm1}PI`k1OcoE(iWCFIYHurQgGGbx+9!=>7G=l}0Q* zpHj!HP3!H79BiioKUte2K1F%ktb7Rqi35hLRIuLdhgs&8EqjmmN+&EjKV9#YiN?B% zqd*5qkjA@OQw~dKifeP5SFGFGt+(y`Qjw|;9-`JSRD6lO^+7e2IAV6lDP4Y{tW`cI z!2;3o&;2aE4pm`7*TzSrwOkg%qm$kKIOdtC(-Ro4@BO~>xW^Q-`9f*;_C}wp z7q(Y#-i{E;PB7efC%0jjRb0zysk@ZQz$x{~ z7w1`z{f7sV^obA}St>I<}R%YKJhBdE-avRV|p9#X^TZlOewF zCW$s>I{_bgxBeYVxtJDb2CLeLz9ylf0 zv(9+KqwdI;x}qCas%cbyd}|p|oQePHLf+E^foy%^!%-gUB0|xr3+^ zQR!p-y9?>BHg8hlzDC1#LDr?W;_4}S;3$id=AX_kvFUXt@t7WYeuKxOr}sYjhkdNQ zrfI)a&d2yGPpj0l>dCyR`I(9n3z9bkgIn9S!$QrAUiXIo;o;jtKlgD|#T`Eq*Si9YgclM^J(-Go4{C z$)|%4sHWae9Xav+%N8~2c;OamV0OVp)>c2d`YG) zl%3~YEVq~*SY&Q*@>2{N4HOSI>I%{i*AAw(AO$&AhMd+R4a*lGLht0y(CAK zuYyy~x^cGpB&pA(n=a(#-cKa!QhqF8Oq`kcKXL_J&WuPP^DZDIi zcqxc3|K81ngJUGgF}ds{(u zRFE$%bH&iRTCbJF*J`a2*7>*hS1)Bn@+~Tj_J_>BeE0m0$G=Y@R1O|_O+T#0-5s}O z*NsgVT_-)f6U%pgIq9FtwotB4bD-3|ah&&FnS9->Xcc(>M2hkBmm{xzDp!`h^`jqA z#_Kq4jR?_NHLxlD*xR2PFG~Tg(CzH$lJKQ2i+IG$R@MKMQPzG7ncUa(Vy#FU6X>?) zK$KRBA46O8==7>K@4@tRx1<~I+&6sYd4GEW;l|Xe(lso|{NjPo1F_ydnHJgCwYTf# zv0h!e=xW1JqFvKR;)6nm98N~Xu1k>)dhPkAS4ATc9m0wjbF<^={u0tRp45yB)P&7H zBJVEVfA~oTzWCEX`}*lqUMy02LCmqIxN{@v&C$%s!0NOyK<&J%`YL@jHMKRWV~5&C zfIHW@RZY$2s+!t*HGQ>U1pGGQHas}oGB^aaLT$r;-%yQI`*+a4Ti(d6p?8<68W(r8 zUSH+hsq`JHc`UvP3>v3lyC2T`X| zS@i(Jml}h!r)1qPH3@8QSe{eleqAy!|43ZCcw@;VywP6Ie4%P#67?cKJpWdtZ&?27 z>D&O~s5#dGH9z`w1jBDR3;2*|gQ^0!S?E;ELWRgQLy4ylJDw$3RyCrvzN30`0S05p zrN~f#BYT~0{Ku*-xp8VAJgjYF4fl%~Z`kT-BPhQ7m}rf?UCm5{S;!*KuV~xDEUGg5 zlNqmomiNm>7Don)|C)-iCiv_Ft_V<8(bdO#giWJHTniDS9veQ$ecENddilMgx;gc| zf?Y)}t25yA4Uslx5lnsd=-3AzMZpPpwYT#0SzS zZ8^n@ZSfEU;e%YH;&OA)mzU2ZmyB9vmeXn=2{0p$;{wQjP2N~&so*(p*GtNuBHWk7 zV`YGICfrYACL&tcA-!;sJeQ`cc#G5R62}I4qy}ZXm#-DgHn=%z*;yG2V=(s^KH@5gPE8 zUl?n>syaB|=M?KBt=vz6&n*8LRaC_hhyoP>@wjSiwF~Pd?=6j*wGTKwm2?{MQS^%= zrrGN1b=1;I&l4^7E&Jt{C=7qF+BtBc<$BXc+_((5#bxE=wrrBpMydoBg+-O$>dnCHryD%1ij+Oy-u_mxeaF%DvxCZq{ z><|}$zAnVQ2H~3M?y@S#K^vq<%&1BpSs*q6Nj0HD}X=X;L=g;MhP4V&_uJ%`y_!29dApAEUKE@znXLu<&}^r$iRG`zWG3aI7TT1Zil=b z(-f=QWeMl+Ye>7>W7!{rd~_keMwu~s|BP=bocuNiFiwt1#1xM%RYA5(+pWQoJ(}Lu zkm)fR_;A|9@FPJ&?ys8m(^>S-VN*qM8580^YTJW%!pZ~vIqD9-Q8mfv_lodwcAPBM zVs%jfpglQ495NZNrs^;v9N%q2Bc;@l1zlwv{27rom^xZ_ZNkmyCX{nU;jH%72Dy(NLh?*c4_zp>a0``m1fQC&0(+MiQ#bcD=B8w_c!`w25_JdLuB(G`) z1^ZQ7!ffKeD> zNLZsd+*eVlDH@@Ge;A$QiQbtw5C-m&Pm7i>D-(DFG_K!_`T#kJ{6;Ci>^i7JuCpDf zeQD2YKX-}T9m{xUt}(mKJcBzf?#L6~UJ4dXikjHd(`U;8>_T~S`|RUP__*&y;7UYi zQP%8&{48gq?C*lqpU8kU$Y2R-OBpb4cJ2FzadOazd0Wc6X47hL(Q3dS7uKbiYA04j z$}<9wqEoP{+|36!6^ts;ss1EViDPi7z=qw-^s}US_sQumbqeTvh2% zqvr4O7=hNQtbABL*k4l2ZkXvAtjXfJ9<{_UAB~mt4X+0UP@WZ5RZ`lug`2U8WxnVA zROkuin2{6K6FcgMDU$XF=se-@2M8|EK&;?P4`@~A3Vxg8D73UVOv~40_hk@5L7vZnV^EpbeYHqdK ztt;QgF1lY>2@|hXZ}>&ZP#0W=^*ob7TwKsAP0&+HDe#V8q7il@wToiNcMi*|*CCw& z>HJJZLs>HTI6`ANIKT2}`O#QhGk1|S?LzqK$O@&*z>VaXh2NX2KQ$LF_qV~r3P8a= zMgAa2ID)pSiA#c1_!8R5NByzO*qD#-V;t%CVf zib(}tD~0{bR6sMcGUG*Z&#Po$WX;w}PtkG>g3TLq@rDAKQGI3OF{))M*M)YS@Z~3@ zdjv`Ukdyp7#2MH25IQ|5?dM*8oBE58JAwNH!3$UNPQEn9oEk~Pg!LbX>p^R5q{3#* ztZpB%T$-e^FVk_l>0IUw>S{unB34*E>oRsu93O7nK>0j@DIyIYR>#eykBbv)7{jXP zWl5yRqP>j{LrUgA#rgGb$mzpub9oN^FkF1EuL+hu7N)Du? zhDS}wS9^&Zcut`>B`k90&Fty^-=&f4v-6Bf$ikA$*E$u~@oR9->bE{nj(t zAF#HlE*ExNSQxnMq9WJfSdB198CDpi94v<&jrLtK!@*Z|v6>{K)X%qwFMfC&VYipA!~0FP@ETiDxDb zATGqPUizPb8h|#N+eOm)=JUF1cWY`Y?O4x7q{ykIjX-951)LRu!)int5O@2M)+yrb zcLm%|HbqeoiQo>`Z&YOuc3l?qbL*Hr=&}P@tM&w%PB zKQ#YUXOUKjXHHuTx}&GNGeP~1i+Vj9CSloEhzuRhr<$hlWLN)k*I&d$9=y2QwVDks#H2U0BD zC+NAIApHokxTHhmlcU?905!E*;7XT(HLM~BvpwWzegb_6X^9`ogQE`Po^r^lu%m>x zL!vbRA9mOUqeoEiE`45$%Uu+0+_4etgf2ALSb2F#Sn{L2wusuDVE<()kPp+AU#Q%S zV3bQ3BR2f*86W1Tkc9LC+Gl!8+K=Yfj5=omJL<@W;=U1x#6TE|I*DAIA5glellTjB zvzf%WO3xPONpK>#8;q@5%zx8fiJ#n&&`pUTPZnaTFqtlm1VQcG6qFA*ZuXPJZYTY) z#GqH5TkNLz5Xrwd;5_PC;YbMjC8-TZDwKP%>LcZ+A?uesMndqkPmtEtfHySkjPfw~ zp$!iv)-%j9lbPZFFLc?G%=*QZ?y~URjnRu=?D2tOn!(If3r@;eH1&?IJ&; zP`x|i;eT*7BFEz8d6`LYW00RbX060Ry%s&O<{xIl3+wPLKx-qt$N+A`E2$r;;b(}~ z4%tq!)~Y-1a}@QB+5O0H*o){QJ}l}KG}RhpMOQ6ZQB85r;JeEcK#7Et5bU|7gqTx= zP;%QvSQ!s5bQ@z|%Z)A~8BHUApK;6_2%BL%UH1eFIpv29DtPl7g z)5vDQlKv$TN7{YT_c=5dcc-z45M(URAT1Cr$Mc_gC0p;<15PKuFx?M`mo^@p?&jQB zSTvB*($&dHHl&)B#4C;ylQZ2puURy6l!;y-xO~YF&whh`Q2{q8V*<`IMqw_8h)Shi$~qSBBh~Km~*cN6_`$DYgNt&OI)X_3)3ik~@)Dh!hI! zz*#7pO%=bkgXFK8kcz7d4ajG(0NkWW1}^njnfNCjLqHYcup;KTxEO7Qn&BHRI%EHu z`1n(j>+c_=01mBu*J3tl@H30vtrIvZ*UdVjtE}iZbQwuf?1RfckPKpe%CUOSb@wt} z)DMr;UQ0d3L9^FN?>k7Lf{(&**U-Ck;USl#9lx3@Y&=s@R~jG7M|M$Qrq8%F-dVE5~tDnrjSP zg#OL7H`}8@GY-vq>f}`p-u@PjdpQ&SpYee0!i?lI&;WU6y`S(>*-QvKCs3STXfaqa z8G205OG>E4iTfjdxcZ_`qs;nHz;?vKi?J|~pv;-RMRpf$1K9{nSib-@6RsIcc1?C> zFK7WfiJdh}E&30>7s${TR-Z)(Z8UH7ni?-XIB>_eK9KUz@t~`0r*eTFQw@fWL6}XM z{XT4S2@`j6MpIecD7&(hfvl!$%|WLW?Tx{=5swSqP0*)J^TQAKdj5t^rqyo@ljBaR0&#oW0mcsF&2<`x}gokU6og(a9;;+*JOk{z5gu$>g~;*=-U$lW~= z(Or1ki!kZvK$p4|$9y(Zok)+_EIn3B439u)Il^(=-J~NGP|Ighzii7~uZmA)&=&5gr`R6sVPp_URBD)55Se+^glO~B**)EKvQ90n4mnLrcH5C4Vp(*An zIb8e|@R5XwGfMF|4|*b?3keCq!8RfbL7JT_A}1g6k90Im6Pu0`(m^N6{q1r`7ckl4 z2XfOe6mh%k6g`LA$!ImLd500lVn3E2eR^Q;8{` zPyxAq4Eq_M$g7NaVsORo$=`s_X|e{IFCJxRhQhAR|szdKnHA(`*nNPpY-Jw_+{~AhK&(! z6NG0ZKT&0XczN7XlUkIJkW|^vZ3&okvt>^xFZHOHY+(h|2X3;8EE4_A=DO+p-V#EAJbWB7Jq!_4etj*YIvT=8I)zN|WuVa^Z1LVc@SA6q23X?K@*3#Ec@*MdcAI$|y9hn+x?-ii`hSp+(GwkB_@os) Date: Fri, 1 Mar 2024 12:52:22 -0800 Subject: [PATCH 06/18] Retrained with new dataset --- .pylintrc | 3 + .../food_on_fork_detection.py | 76 ++++- .../food_on_fork_detectors.py | 116 ++++--- .../food_on_fork_train_test.py | 307 ++++++++++++++---- .../ada_feeding_perception/helpers.py | 13 +- .../config/food_on_fork_detection.yaml | 8 +- .../model/pointcloud_t_test_detector.npz | Bin 210863 -> 30676 bytes ada_feeding_perception/package.xml | 2 + 8 files changed, 406 insertions(+), 119 deletions(-) diff --git a/.pylintrc b/.pylintrc index e140f0da..4f111ac1 100644 --- a/.pylintrc +++ b/.pylintrc @@ -204,9 +204,12 @@ good-names=a, m, n, p, + ps, x, + x0, X, y, + y0, z, u, v, diff --git a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py index e65625b5..9e4d020e 100644 --- a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py +++ b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py @@ -59,6 +59,10 @@ def __init__(self): model_dir, model_kwargs, self.rate_hz, + self.crop_top_left, + self.crop_bottom_right, + self.depth_min_mm, + self.depth_max_mm, ) = self.read_params() # Construct the FoodOnForkDetector model @@ -120,7 +124,11 @@ def __init__(self): callback_group=MutuallyExclusiveCallbackGroup(), ) - def read_params(self) -> Tuple[str, str, str, Dict[str, Any], float]: + def read_params( + self, + ) -> Tuple[ + str, str, str, Dict[str, Any], float, Tuple[int, int], Tuple[int, int], int, int + ]: """ Reads the parameters for the FoodOnForkDetection. @@ -132,6 +140,10 @@ def read_params(self) -> Tuple[str, str, str, Dict[str, Any], float]: model_dir: The directory to load the model from. model_kwargs: The keywords to pass to the FoodOnFork class's constructor. rate_hz: The rate (Hz) at which to publish. + crop_top_left: The top left corner of the crop box. + crop_bottom_right: The bottom right corner of the crop box. + depth_min_mm: The minimum depth (mm) to consider. + depth_max_mm: The maximum depth (mm) to consider. """ # Read the model_class model_class = self.declare_parameter( @@ -217,12 +229,64 @@ def read_params(self) -> Tuple[str, str, str, Dict[str, Any], float]: ) rate_hz = rate_hz.value + # Get the crop box + crop_top_left = self.declare_parameter( + "crop_top_left", + (0, 0), + descriptor=ParameterDescriptor( + name="crop_top_left", + type=ParameterType.PARAMETER_INTEGER_ARRAY, + description="The top left corner of the crop box.", + read_only=True, + ), + ) + crop_top_left = crop_top_left.value + crop_bottom_right = self.declare_parameter( + "crop_bottom_right", + (0, 0), + descriptor=ParameterDescriptor( + name="crop_bottom_right", + type=ParameterType.PARAMETER_INTEGER_ARRAY, + description="The bottom right corner of the crop box.", + read_only=True, + ), + ) + crop_bottom_right = crop_bottom_right.value + + # Get the depth range + depth_min_mm = self.declare_parameter( + "depth_min_mm", + 0, + descriptor=ParameterDescriptor( + name="depth_min_mm", + type=ParameterType.PARAMETER_INTEGER, + description="The minimum depth (mm) to consider.", + read_only=True, + ), + ) + depth_min_mm = depth_min_mm.value + depth_max_mm = self.declare_parameter( + "depth_max_mm", + 20000, + descriptor=ParameterDescriptor( + name="depth_max_mm", + type=ParameterType.PARAMETER_INTEGER, + description="The maximum depth (mm) to consider.", + read_only=True, + ), + ) + depth_max_mm = depth_max_mm.value + return ( model_class, model_path, model_dir, model_kwargs, rate_hz, + crop_top_left, + crop_bottom_right, + depth_min_mm, + depth_max_mm, ) def toggle_food_on_fork_detection( @@ -302,6 +366,16 @@ def run(self) -> None: # Convert the depth image to a cv2 image depth_img_cv2 = ros_msg_to_cv2_image(depth_img_msg, self.cv_bridge) + depth_img_cv2 = depth_img_cv2[ + self.crop_top_left[1] : self.crop_bottom_right[1], + self.crop_top_left[0] : self.crop_bottom_right[0], + ] + depth_img_cv2 = np.where( + (depth_img_cv2 >= self.depth_min_mm) + & (depth_img_cv2 <= self.depth_max_mm), + depth_img_cv2, + 0, + ) X = np.expand_dims(depth_img_cv2, axis=0) # Get the probability that there is food on the fork diff --git a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py index 9f41149e..00bf4180 100644 --- a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py +++ b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py @@ -43,6 +43,8 @@ def __init__(self, verbose: bool = False) -> None: verbose: Whether to print debug messages. """ self.__camera_info = None + self.__crop_top_left = (0, 0) + self.__crop_bottom_right = (640, 480) self.__tf_buffer = None self.__seed = int(time.time() * 1000) self.verbose = verbose @@ -69,6 +71,54 @@ def camera_info(self, camera_info: CameraInfo) -> None: """ self.__camera_info = camera_info + @property + def crop_top_left(self) -> Tuple[int, int]: + """ + The top left corner of the region of interest in the depth image. + + Returns + ------- + crop_top_left: The top left corner of the region of interest in the depth + image. + """ + return self.__crop_top_left + + @crop_top_left.setter + def crop_top_left(self, crop_top_left: Tuple[int, int]) -> None: + """ + Sets the top left corner of the region of interest in the depth image. + + Parameters + ---------- + crop_top_left: The top left corner of the region of interest in the depth + image. + """ + self.__crop_top_left = crop_top_left + + @property + def crop_bottom_right(self) -> Tuple[int, int]: + """ + The bottom right corner of the region of interest in the depth image. + + Returns + ------- + crop_bottom_right: The bottom right corner of the region of interest in + the depth image. + """ + return self.__crop_bottom_right + + @crop_bottom_right.setter + def crop_bottom_right(self, crop_bottom_right: Tuple[int, int]) -> None: + """ + Sets the bottom right corner of the region of interest in the depth image. + + Parameters + ---------- + crop_bottom_right: The bottom right corner of the region of interest in + the depth image. + """ + self.__crop_bottom_right = crop_bottom_right + @property def tf_buffer(self) -> Optional[Buffer]: """ @@ -251,10 +301,6 @@ class FoodOnForkPointCloudTTestDetector(FoodOnForkDetector): def __init__( self, camera_matrix: npt.NDArray, - crop_top_left: Tuple[float, float] = (297, 248), - crop_bottom_right: Tuple[float, float] = (425, 332), - depth_min_mm: int = 310, - depth_max_mm: int = 370, min_points: int = 40, verbose: bool = False, ) -> None: @@ -264,11 +310,6 @@ def __init__( Parameters ---------- camera_matrix: The camera intrinsic matrix (K). - crop_top_left, crop_bottom_right: Specifies the subset of the depth image - to convert to a pointcloud. This is a rectanglar region around the fork. - depth_min_mm, depth_max_mm: The minimum and maximum depth values to - consider for the pointcloud. Points outside this range will be - ignored. min_points: The minimum number of points in a pointcloud to consider it for comparison. If a pointcloud has fewer points than this, it will return a probability of nan (prediction of UNSURE). @@ -278,48 +319,32 @@ def __init__( # Necessary for this class. super().__init__(verbose) self.camera_matrix = camera_matrix - self.crop_top_left = crop_top_left - self.crop_bottom_right = crop_bottom_right - self.depth_min_mm = depth_min_mm - self.depth_max_mm = depth_max_mm self.min_points = min_points self.no_fof_means = None self.no_fof_covs = None self.no_fof_ns = None - def depth_to_pointcloud( - self, depth_image: npt.NDArray, is_cropped: bool = False - ) -> npt.NDArray: + def depth_to_pointcloud(self, depth_image: npt.NDArray) -> npt.NDArray: """ Converts a depth image to a point cloud. Parameters ---------- depth_image: The depth image to convert to a point cloud. - is_cropped: Whether the depth image has already been cropped to the - region of interest. Returns ------- pointcloud: The point cloud representation of the depth image. """ - # Get the depth values - if is_cropped: - depth_values = depth_image - else: - depth_values = depth_image[ - int(self.crop_top_left[1]) : int(self.crop_bottom_right[1]), - int(self.crop_top_left[0]) : int(self.crop_bottom_right[0]), - ] # Get the pixel coordinates pixel_coords = np.mgrid[ int(self.crop_top_left[1]) : int(self.crop_bottom_right[1]), int(self.crop_top_left[0]) : int(self.crop_bottom_right[0]), ] # Mask out values outside the depth range - mask = (depth_values > self.depth_min_mm) & (depth_values < self.depth_max_mm) - depth_values = depth_values[mask] + mask = depth_image > 0 + depth_values = depth_image[mask] pixel_coords = pixel_coords[:, mask] # Convert mm to m depth_values = np.divide(depth_values, 1000.0) @@ -351,13 +376,13 @@ def fit(self, X: npt.NDArray, y: npt.NDArray[int]) -> None: """ # Get the most up-to-date camera info if self.camera_info is not None: - self.camera_matrix = np.array(self.camera_info.K) + self.camera_matrix = np.array(self.camera_info.k) no_fof_imgs = X[y == FoodOnForkLabel.NO_FOOD.value] - # TODO: remove the `is_cropped` from below once we move to ROS bags as - # the training set. - no_fof_pointclouds = [ - self.depth_to_pointcloud(img, is_cropped=True) for img in no_fof_imgs - ] + no_fof_pointclouds = [] + for img in no_fof_imgs: + pointcloud = self.depth_to_pointcloud(img) + if len(pointcloud) >= self.min_points: + no_fof_pointclouds.append(pointcloud) self.no_fof_means = np.array([np.mean(pc, axis=0) for pc in no_fof_pointclouds]) self.no_fof_covs = np.array( [np.cov(pc, rowvar=False, bias=False) for pc in no_fof_pointclouds] @@ -386,7 +411,7 @@ def save(self, path: str) -> str: @override def load(self, path: str) -> None: - prefix, ext = os.path.splitext(path) + ext = os.path.splitext(path)[1] if len(ext) == 0: path = path + ".npz" params = np.load(path) @@ -394,8 +419,6 @@ def load(self, path: str) -> None: self.no_fof_covs = params["no_fof_covs"] self.no_fof_ns = params["no_fof_ns"] - # pylint: disable=too--many-arguments, too-many-locals - # Necessary for this function. @staticmethod def hotellings_t_test( samp1_means: npt.NDArray, @@ -428,6 +451,9 @@ def hotellings_t_test( ------- ps: The p-values of the pairwise tests between samp1 and every sample in samp2. """ + # pylint: disable=too-many-arguments, too-many-locals + # Necessary for this function. + # Get sizes m, k = samp1_means.shape @@ -475,10 +501,10 @@ def trace_mkk(a: npt.NDArray): # Calculate the corresponding F value f_vals = np.multiply(np.divide(df2 - df1 + 1, df1 * df2), t_sq) - # Calculate the p value - p = 1 - scipy.stats.f.cdf(f_vals, df1, df2 - df1 + 1) + # Calculate the p values + ps = 1 - scipy.stats.f.cdf(f_vals, df1, df2 - df1 + 1) - return p + return ps @override def predict_proba(self, X: npt.NDArray) -> npt.NDArray: @@ -490,18 +516,16 @@ def predict_proba(self, X: npt.NDArray) -> npt.NDArray: raise ValueError( "The model has not been trained yet. Call fit before predicting." ) - # TODO: remove the `is_cropped` from below once we move to ROS bags as - # the training set. - pointclouds = [self.depth_to_pointcloud(img, is_cropped=True) for img in X] + pointclouds = [self.depth_to_pointcloud(img) for img in X] probas = [] n = len(pointclouds) - for i in range(len(pointclouds)): + for i, pointcloud in enumerate(pointclouds): if self.verbose: print(f"Predicting on pointcloud {i+1}/{n}") - pointcloud = pointclouds[i] m = pointcloud.shape[0] if m < self.min_points: - probas.append(np.nan) + # probas.append(np.nan) + probas.append(0.0) continue # Calculate the T^2 statistic and p-value ps = FoodOnForkPointCloudTTestDetector.hotellings_t_test( diff --git a/ada_feeding_perception/ada_feeding_perception/food_on_fork_train_test.py b/ada_feeding_perception/ada_feeding_perception/food_on_fork_train_test.py index b10843b2..14bcad7e 100644 --- a/ada_feeding_perception/ada_feeding_perception/food_on_fork_train_test.py +++ b/ada_feeding_perception/ada_feeding_perception/food_on_fork_train_test.py @@ -13,9 +13,13 @@ # Third-party imports import cv2 +from cv_bridge import CvBridge import numpy as np import numpy.typing as npt import pandas as pd +from rosbags.rosbag2 import Reader +from rosbags.serde import deserialize_cdr +from sensor_msgs.msg import CameraInfo from sklearn.metrics import ( accuracy_score, confusion_matrix, @@ -28,6 +32,25 @@ FoodOnForkDetector, FoodOnForkLabel, ) +from ada_feeding_perception.helpers import ros_msg_to_cv2_image + + +def show_normalized_depth_img(img, wait=True): + """ + Show the normalized depth image. Useful for debugging. + + Parameters + ---------- + img: npt.NDArray + The depth image to show. + wait: bool, optional + If True, wait for a key press before closing the window. + """ + # Show the normalized depth image + img_normalized = ((img - img.min()) / (img.max() - img.min()) * 255).astype("uint8") + cv2.imshow("img", img_normalized) + if wait: + cv2.waitKey(0) def read_args() -> argparse.Namespace: @@ -66,43 +89,66 @@ def read_args() -> argparse.Namespace: ), ) + # Configure the cropping/masking of depth images. These should exactly match + # the cropping/masking done in the real-time detector (in config/food_on_fork_detection.yaml). + parser.add_argument( + "--crop-top-left", + default=(0, 0), + type=int, + nargs="+", + help=("The top-left corner of the crop rectangle. The format is (x, y)."), + ) + parser.add_argument( + "--crop-bottom-right", + default=(640, 480), + type=int, + nargs="+", + help=("The bottom-right corner of the crop rectangle. The format is (x, y)."), + ) + parser.add_argument( + "--depth-min-mm", + default=0, + type=int, + help=("The minimum depth value to consider in the depth images."), + ) + parser.add_argument( + "--depth-max-mm", + default=20000, + type=int, + help=("The maximum depth value to consider in the depth images."), + ) + # Configure the dataset parser.add_argument( "--data-dir", default="../data/food_on_fork", help=( - "The directory containing the training and testing data. The path should be " - "relative to **this file's** location. This directory should have two " - "subdirectories: 'food' and 'no_food', each containing either .png files " - "corresponding to depth images or ROS bag files with the topics specified " - "in command line arguments." + "The directory containing the training and testing data. This path should " + "have a file called `bags_metadata.csv` that contains the labels for bagfiles, " + "and one folder per bagfile referred to in the CSV. This path should be " + "relative to **this file's** location." ), ) - parser.add_argument( - "--data-type", - help=( - "The type of data to use. Either 'bag' or 'png'. If 'bag', the data " - "subdirectoryies should contain ROS bag files. If 'png', the data " - "subdirectories should contain .png files." - ), - choices=["bag", "png"], - required=True, - ) parser.add_argument( "--depth-topic", default="/local/camera/aligned_depth_to_color/image_raw", - help=( - "The topic to use for depth images. This is only used if --data-type is " - "'bag'." - ), + help=("The topic to use for depth images."), + ) + parser.add_argument( + "--color-topic", + default="/local/camera/color/image_raw/compressed", + help=("The topic to use for color images. Used for debugging."), ) parser.add_argument( "--camera-info-topic", default="/local/camera/color/camera_info", - help=( - "The topic to use for camera info. This is only used if --data-type is " - "'bag'." - ), + help=("The topic to use for camera info."), + ) + parser.add_argument( + "--include-motion", + default=False, + action="store_true", + help=("If set, include images when the robot arm is moving in the dataset."), ) # Configure the training and testing operations @@ -175,8 +221,17 @@ def read_args() -> argparse.Namespace: def load_data( - data_dir: str, data_type: str, depth_topic: str, camera_info_topic: str -) -> Tuple[npt.NDArray, npt.NDArray]: + data_dir: str, + depth_topic: str, + color_topic: str, + camera_info_topic: str, + crop_top_left: Tuple[int, int], + crop_bottom_right: Tuple[int, int], + depth_min_mm: int, + depth_max_mm: int, + include_motion: bool, + viz: bool = False, +) -> Tuple[npt.NDArray, npt.NDArray[int], CameraInfo]: """ Load the data specified in the command line arguments. @@ -188,59 +243,139 @@ def load_data( subdirectories: 'food' and 'no_food', each containing either .png files corresponding to depth images or ROS bag files with the topics specified in command line arguments. - data_type: str - The type of data to use. Either 'bag' or 'png'. If 'bag', the data - subdirectoryies should contain ROS bag files. If 'png', the data - subdirectories should contain .png files. depth_topic: str - The topic to use for depth images. This is only used if --data-type is - 'bag'. + The topic to use for depth images. + color_topic: str + The topic to use for color images. Used for debugging. camera_info_topic: str - The topic to use for camera info. This is only used if --data-type is - 'bag'. + The topic to use for camera info. + crop_top_left, crop_bottom_right: Tuple[int, int] + The top-left and bottom-right corners of the crop rectangle. + depth_min_mm, depth_max_mm: int + The minimum and maximum depth values to consider in the depth images. + include_motion: bool + If True, include images when the robot arm is moving in the dataset. + viz: bool, optional + If True, visualize the depth images as they are loaded. Returns ------- X: npt.NDArray The depth images to predict on. - y: npt.NDArray + y: npt.NDArray[int] The labels for whether there is food on the fork. + camera_info: CameraInfo + The camera info for the depth images. We assume it is static across all + depth images. """ - absolute_data_dir = os.path.join(os.path.dirname(__file__), data_dir) + # pylint: disable=too-many-locals, too-many-arguments, too-many-branches, too-many-statements + # Okay since we want to make it a flexible method. - X = [] - y = [] - if data_type == "bag": - raise NotImplementedError("Bag file loading not implemented yet.") - elif data_type == "png": - food_dir = os.path.join(absolute_data_dir, "food") - no_food_dir = os.path.join(absolute_data_dir, "no_food") - for data_path, label in [ - (food_dir, FoodOnForkLabel.FOOD.value), - (no_food_dir, FoodOnForkLabel.NO_FOOD.value), - ]: - print(f"Loading data from {data_path} with label {label}...", end="") - n = 0 - for filename in os.listdir(data_path): - if filename.endswith(".png"): - # Load the image - image = cv2.imread( - os.path.join(data_path, filename), cv2.IMREAD_UNCHANGED - ) + absolute_data_dir = os.path.join(os.path.dirname(__file__), data_dir) - # Add the image and label to the dataset - X.append(image) - y.append(label) - n += 1 - print(f"Loaded {n} images.") - else: - raise ValueError(f"Invalid data type: {data_type}. Must be 'bag' or 'png'.") + w = crop_bottom_right[0] - crop_top_left[0] + h = crop_bottom_right[1] - crop_top_left[1] + X = np.zeros((0, h, w), dtype=np.uint16) + y = np.zeros(0, dtype=int) + + # Load the metadata + metadata = pd.read_csv(os.path.join(absolute_data_dir, "bags_metadata.csv")) + bagname_to_annotations = {} + for _, row in metadata.iterrows(): + rosbag_name = row["rosbag_name"] + time_from_start = row["time_from_start"] + food_on_fork = row["food_on_fork"] + arm_moving = row["arm_moving"] + if rosbag_name not in bagname_to_annotations: + bagname_to_annotations[rosbag_name] = [] + bagname_to_annotations[rosbag_name].append( + (time_from_start, food_on_fork, arm_moving) + ) - return np.array(X), np.array(y) + # Load the data + bridge = CvBridge() + camera_info = None + for rosbag_name, annotations in bagname_to_annotations.items(): + annotations.sort() + i = 0 + with Reader(os.path.join(absolute_data_dir, rosbag_name)) as reader: + # Get the depth message count + for connection in reader.connections: + if connection.topic == depth_topic: + depth_msg_count = connection.msgcount + break + # Extend X and y by depth_msg_count + j = y.shape[0] + X = np.concatenate((X, np.zeros((depth_msg_count, h, w), dtype=np.uint16))) + y = np.concatenate((y, np.zeros(depth_msg_count, dtype=int))) + + start_time = None + for connection, timestamp, rawdata in reader.messages(): + if start_time is None: + start_time = timestamp + # Depth Image + if connection.topic == depth_topic: + msg = deserialize_cdr(rawdata, connection.msgtype) + elapsed_time = (timestamp - start_time) / 10.0**9 + while ( + i < len(annotations) - 1 + and elapsed_time > annotations[i + 1][0] + ): + i += 1 + arm_moving = annotations[i][2] + if not include_motion and arm_moving: + # Skip images when the robot arm is moving + continue + if annotations[i][1] == FoodOnForkLabel.FOOD.value: + label = 1 + elif annotations[i][1] == FoodOnForkLabel.NO_FOOD.value: + label = 0 + else: + # Skip images with unknown label + continue + img = ros_msg_to_cv2_image(msg, bridge) + img = img[ + crop_top_left[1] : crop_bottom_right[1], + crop_top_left[0] : crop_bottom_right[0], + ] + img = np.where( + (img >= depth_min_mm) & (img <= depth_max_mm), img, 0 + ) + X[j, :, :] = img + y[j] = label + j += 1 + # Camera Info + elif connection.topic == camera_info_topic and camera_info is None: + camera_info = deserialize_cdr(rawdata, connection.msgtype) + # RGB Image + elif connection.topic == color_topic and viz: + msg = deserialize_cdr(rawdata, connection.msgtype) + print((timestamp - start_time) / 10.0**9) + img = ros_msg_to_cv2_image(msg, bridge) + # A box around the forktip + x0, y0 = 308, 242 + w, h = 128, 128 + fof_color = (0, 255, 0) + no_fof_color = (255, 0, 0) + color = fof_color if len(y) == 0 or y[-1] == 1 else no_fof_color + img = cv2.rectangle(img, (x0, y0), (x0 + w, y0 + h), color, 2) + img = cv2.circle(img, (x0 + w // 2, y0 + h // 2), 5, color, -1) + cv2.imshow("RGB Image", img) + cv2.waitKey(10) + + # Truncate extra all-zero rows on the end of Z and y + X = X[:j] + y = y[:j] + + return X, y, camera_info def load_models( - model_classes: str, model_kwargs: str, seed: int + model_classes: str, + model_kwargs: str, + seed: int, + crop_top_left: Tuple[int, int], + crop_bottom_right: Tuple[int, int], ) -> Dict[str, FoodOnForkDetector]: """ Load the models specified in the command line arguments. @@ -255,6 +390,8 @@ def load_models( dictionary of keyword arguments to pass to the model's constructor. seed: int The random seed to use in the detector. + crop_top_left, crop_bottom_right: Tuple[int, int] + The top-left and bottom-right corners of the crop rectangle. Returns ------- @@ -276,6 +413,8 @@ def load_models( # Create the model models[model_id] = model_class(**kwargs) models[model_id].seed = seed + models[model_id].crop_top_left = crop_top_left + models[model_id].crop_bottom_right = crop_bottom_right return models @@ -318,6 +457,7 @@ def evaluate_models( lower_thresh: float, upper_thresh: float, max_eval_n: Optional[int] = None, + viz: bool = False, ) -> None: """ Test the models on the testing data. @@ -345,8 +485,10 @@ def evaluate_models( max_eval_n: int, optional The maximum number of evaluations to perform. If None, all evaluations will be performed. Typically used when debugging a detector. + viz: bool, optional + If True, visualize the depth images as they are evaluated. """ - # pylint: disable=too-many-locals, too-many-arguments + # pylint: disable=too-many-locals, too-many-arguments, too-many-nested-blocks # This function is meant to be flexible. absolute_model_dir = os.path.join(os.path.dirname(__file__), model_dir) @@ -386,6 +528,18 @@ def evaluate_models( ) print("Done.") + if viz: + # Visualize all images where the model was wrong + last_0_0 = None + for i in range(y_pred_proba.shape[0]): + if y[i] != y_pred[i]: + print(f"y_true: {y[i]}, y_pred: {y_pred[i]}") + show_normalized_depth_img(X[i], wait=True) + if last_0_0 is not None: + show_normalized_depth_img(X[last_0_0], wait=True) + if y[i] == 0 and y_pred[i] == 0: + last_0_0 = i + # Compute the summary statistics txt = textwrap.indent(f"Results on {label} dataset:\n", " " * 4) results_txt += txt @@ -429,9 +583,19 @@ def main() -> None: args = read_args() # Load the dataset - X, y = load_data( - args.data_dir, args.data_type, args.depth_topic, args.camera_info_topic + X, y, camera_info = load_data( + args.data_dir, + args.depth_topic, + args.color_topic, + args.camera_info_topic, + args.crop_top_left, + args.crop_bottom_right, + args.depth_min_mm, + args.depth_max_mm, + args.include_motion, + viz=False, ) + print("X.shape", X.shape, "y.shape", y.shape) # Do a train-test split of the dataset if args.seed is None: @@ -443,7 +607,15 @@ def main() -> None: ) # Load the models - models = load_models(args.model_classes, args.model_kwargs, seed) + models = load_models( + args.model_classes, + args.model_kwargs, + seed, + args.crop_top_left, + args.crop_bottom_right, + ) + for _, model in models.items(): + model.camera_info = camera_info # Train the model if not args.no_train: @@ -461,6 +633,7 @@ def main() -> None: args.lower_thresh, args.upper_thresh, args.max_eval_n, + viz=False, ) diff --git a/ada_feeding_perception/ada_feeding_perception/helpers.py b/ada_feeding_perception/ada_feeding_perception/helpers.py index 1116a89e..6777b60f 100644 --- a/ada_feeding_perception/ada_feeding_perception/helpers.py +++ b/ada_feeding_perception/ada_feeding_perception/helpers.py @@ -15,12 +15,17 @@ import numpy.typing as npt import rclpy from rclpy.node import Node +from rosbags.typesys.types import ( + sensor_msgs__msg__CompressedImage as rCompressedImage, + sensor_msgs__msg__Image as rImage, +) from sensor_msgs.msg import CompressedImage, Image from skimage.morphology import flood_fill def ros_msg_to_cv2_image( - msg: Union[Image, CompressedImage], bridge: Optional[CvBridge] = None + msg: Union[Image, rImage, CompressedImage, rCompressedImage], + bridge: Optional[CvBridge] = None, ) -> npt.NDArray: """ Convert a ROS Image or CompressedImage message to a cv2 image. By default, @@ -39,12 +44,12 @@ def ros_msg_to_cv2_image( is a ROS Image message. If `bridge` is None, a new CvBridge will be created. """ - if isinstance(msg, Image): + if isinstance(msg, (Image, rImage)): if bridge is None: bridge = CvBridge() return bridge.imgmsg_to_cv2(msg, desired_encoding="passthrough") - if isinstance(msg, CompressedImage): - # TODO: This shoudl use bridge as well + if isinstance(msg, (CompressedImage, rCompressedImage)): + # TODO: This should use bridge as well return cv2.imdecode(np.frombuffer(msg.data, np.uint8), cv2.IMREAD_UNCHANGED) raise ValueError("msg must be a ROS Image or CompressedImage") diff --git a/ada_feeding_perception/config/food_on_fork_detection.yaml b/ada_feeding_perception/config/food_on_fork_detection.yaml index 68f32841..7a8fd557 100644 --- a/ada_feeding_perception/config/food_on_fork_detection.yaml +++ b/ada_feeding_perception/config/food_on_fork_detection.yaml @@ -14,4 +14,10 @@ food_on_fork_detection: camera_matrix: [614.5933227539062, 0.0, 312.1358947753906, 0.0, 614.6914672851562, 223.70831298828125, 0.0, 0.0, 1.0] # The rate at which to detect and publish the confidence that there is food on the fork - rate_hz: 10.0 \ No newline at end of file + rate_hz: 10.0 + # The top-left and bottom-right corners to crop the depth image to + crop_top_left: [308, 242] + crop_bottom_right: [436, 370] + # The min and max depth to consider for the food on the fork + depth_min_mm: 310 + depth_max_mm: 370 \ No newline at end of file diff --git a/ada_feeding_perception/model/pointcloud_t_test_detector.npz b/ada_feeding_perception/model/pointcloud_t_test_detector.npz index a8b963a9cee4b6ad13c85e011c995db8d67bc181..ed257a5bbfeb5d754bac2ef80690dda110b44de7 100644 GIT binary patch literal 30676 zcmY&eWl&vBkj3HQ!3i!wg1fuBB}j00c(}W}y9EgD?jGEOyYp~+xGvwH-P)J$(V(o_%-=nz;CcJ}&a_GbFFriOM-jCMc| z$j`U`&HXq2`|iJy^UIR`r+q7zcqkm}57FXyGS+0#I1~9FSl_V{;fyU(Wk>K5l54p# z`URzUu*>2_$sDpNoG`zbhMROw`>{_;z=%oK~Lu_)UYerV=e0wmhdH6=T^5aZ_SF zVOsOlSHBmU0Ogfr6eN$+FOPfYss+P*lt}I#FWWLIH2mQO(YP;8Kmk2;rxsQfqZTz9 zNr2QRzjuVnM>Cu(Y%l1)VM^Y>&N2U*yO^Z4AIrUWe?9i}?4gR`Yw*rbX`#}NV~>S5 z)zckbe*Si?f;cPmQT@@y*5|Z8{CbOyRJv?Vf(!@X7P57iu;xH%#pFY^uFbfbyI#y) z#(_$dy~k6K%qoIWCAv%GrNB^D1n9)A8Jn%$i-TIB;oG+ z2m`Qu*Z4T$C-?U|hyd=f^8Pi8+?UNZ7v0wke}V^x{eC6u`mL25>=lbrzj;nS($+q5 zQYwKL-06AV-4zYlE@?S$YtESr&iO)PjNQA!F?s<@z-l;Q;^s@^>no)ePtBAAAt+fJ zdFP4v3^(sPG|6gs8(-a4!VQS{xfHM#0|(&s1lL_=T#5WxUeM!5yw`i(qdf2TFB2m` z4KA(QnJ95r$JsSw`n#oEqZp*srx9hVol$FW-8s<93DrMmrAP&0?WLxDP*43v5KUa> zRLLVFIxS}`*~EwPz56E>zl9(IVl6L0`7cu34H26l2U_oL^?i_Q8+hWFQ|V>aBjYr?R4GIB<$1MGG-J z@6EMhHGRf8z2+d_mN8rDmZm9DKFnOD&}k1$f0a&PzcozSJIcVGKbZ+t#*ig|^1;$) zq@OOWg##%!=F-%NOpE@n2Rw7ggz4;7?%Oj-B|@`#%*fBko(j`u%)KK!Rr3>6oF>v>FFB4R;Lsp_IofryZuizIG`XSg1?qjnD#QiJ=oP|o<6nfz;uy#p@6(=|3?A zcU}>Rb&FaPUog4j1I7&{xaOJ5T`LMo3Y78kLgKkl5C1;ve3A3bz(p~{EQNrGvAd_p zg)J7q3OVGuC^tYFD|Qz2iwxQo`%khsnSQIRT2Yl#0_Z1KcXvXGNN%~R3ezA=Sa)_o zy)V=Wj*?Wk*KFU6e(U=T2UTf`!T~W0+4l9-Oak3ImV3tj^t}QzS*;^lOCT|z!k5wY z`5_qY_W15!^|kznx~eR*$`tf-ZwXxq-JBum3-c)zEb{*rdJ1TZkvkp6GPGK z^QZwyO30~t72VuatY86x=#{uf)=Arv73{{QGuzc5 zVK>?fr&oBE>T*jcqmHp(uKBr95!1M7`MIYtt+p8hZTqon*6PQ~K!#)FJ<6M?gJ!PU zwiy4xE%^{VmmRQk-|qCIn`u?`Yv*mW{}_?F9b7pUB{$kB!uI-b9xl;$9n#*HgN@Q~ zSVULG>=xZXUgNKFPH!cr0IPn2Ds{rPxn(l=ll? zOyt47qV7&89k^#Sx-6~3?M>xEoZM;H+YD$PFG;dFN)O9y>4=XD*@__`o)P}p_@YjJ z0_-vKdaQSvrZkk>vvnFWRq0?6#)!}plW$mO1Hu2usi08$l6n1xx$DoT~ zFg9x3wooT6q39-?OdUJi1g$TWhGWmb=Dph!(pOO#ot!k zt&(lZ_Skqcy4>gcZ=tXRf%;NYb%q2q~odW zG?NkY2toQ_n#o1M)&QI`C-kYm?u4j=MzYr2fP zy(tCid;-nir|}(I6%Yyyg1h-VV5CrWt2z9h6NCI>Gp@Ti7%q-b?oM%+Fb$un^ki`Z z;%s%r1V@&JU}iypKM6yaxLVW5r&9T@Nt-}zF$pA`b=n^GR%rtY>kC&f|I_@ zPNV%aK##jx&Y4m~I0nJC;l*WSr3s{UoLpShz$bn5XQ}p#MdiynxJzVY7P$zSa7h}Z zM6hYndIe$=!MS1qFWW|8uIp|Oe!f!v!Ft52+Wy@aFtrdD2~?`D8gua_nFzvWR9W(& zL||6fzdLvw47C1QG|TJg@mrv=&SCZ#nR~Iqy~j8nmS7-Q63d$PcYgwxR}cmfj;~Mo z8{TMeQ8y;;-vzM$_tR`*j|9|6H4k+}V|tpJ!aUyZDFF4iD9MRfbmmvZ*Y-7B9O>6s z`45*Yf2FyF`VOA>ILPMeEQgEr;!6qFtw{f-=`Ala9Jb%}R!`aIf}H$Iz}3q^xj?I} z8j2zAt=gm$ZzS%t+&Xj1V@JxF$+=`3LW^4Kw{BbVnDkRKUm;3X1kFa?#ivOt#9w;w zL^Hi_Tg7%Zz^QcqNxNt+#E;|iv-^uSiK>~J)oDbO;Ro-QILtR)7={KUS68 z%!oFJ(d*LHwRh**Z~rQp23dDTzIN|4pdrwl$B#dC;k(#J{rUavmOyKmk&A0yZA%e5x^9AgAkW!@wp zH?%{mN6j~OyCb;Z>ehVMGkw4#8jamPoe89^a6j`gJHTiW=O*eYKF)HHh&W1Hr1{%* z-8nDD5AXX_JzuFXl0ZP(*8zu*Aoe9V)8Zg^aOnfb1e=JHP;)F&Lw@a|XLbw^*+g5L znsh2$UCE9j^vS52r1xyY1TtQkOs>tcSQznM+|+fSJYEED(%P@+&TyU;-qAn5cg8UX zrtBsHv|iREnMtTjJ%{gM)#5oF7tXhps9I}OTpas5Gjmm*$$tgIb#%%7xJ!uJf3CuT z{sJ@ef_AAclB0wo-BCw!r!e!!BNz8>@n9=Ri*a7tDQqV|H(crU*|6Y}_%Lsvg#XQi zg=E#@IP3R&B`@*Dmur1RIqsHk2w*4L2J=D6?%{a!_m$gpe_b&^VCLgH#U$=R<(0<~ zoI`%T0aU+s{Q-j67xDC-TlGEbkQ_mx8)_9Lb^NBQ_NzHVBlo|_VPP$yyr9jknuOU0+>*YHEc{fm{N zvF2)&owg5aYEiG{T%_=f_N0B*+i#kP-CI&a@v{N%n}4aERnvf5BE2tNI(`Nmt4{c*;p6f4GP&}xaYo>Z?dUUEH9`iaKn-o#AS{u36e zAAx49!|#2_;0sMhcvY?_e+7jHL82Iv$ft~S=S&`7{flY}9PA4{OR6~}P$Ll?*i2jZ z@{(pw!8qxd8x1U=*Uq+T&A@M)7GXT z3hn`xp-YoQInQ``^P~17l}6?%h)V_m_s zuJR#oo9kqa5%-SW(pj{}@|d@+5NQ&QX8v1^?RCa~$jo+yIV{JOybT@cV8t za>(1U3NL{RRj_vAyDc{0D>NAJEF84YpA>_wz+EFeAht^a7-?(h=>H&r&0I=KJ_Gt; zy+29=9}Iy_vE#o zU+O2#75#pEet&y`p1K4B z8PbrtabCK1?b}IOyCb6pX;vLpSHn=s+C znf#x>Z8G7Amj}$NK|bY6EOzam$;%(GXKQwF$=)eX-g|Mc&O(C&SMD&idxl_-DRH*) z89O&-GF(s(I{~Ld!;a}9fx@se)RbTp??HD|V8+sALmEZyhu(%}n=}&0h}O^~;NAWG zM*4vvTMi=5do2hO>eb^fmtJr7dS2uAPGZmnmBAdgXFAMO$WXJxgmFJhXejWp%GFOPcw1Ns_pK-ad#Z|4pJ7bF57V0UW)5q3e{jJF{gk zuqU@B9bhk$9tL+31h#llgZ@-KU5!tjrH)p}Q13EgHDq>GJyd~))Sw${s;F}lLha@@ ziSZHy;ht941U+@6dO0r!q2jLB<9|&{2iiJL!^(#|pN~5D3;XUusV2}>eMn5Xe3gsE5d+raFf|tod+%jes%S{{|Fxnb_wN~`_!pZ78Ofp*XM0iK z+bFK)vgZVq&DH&CVkX~bHkZZj^mmKus%6D=UV!3mPse_c20f!O=1^Qnpo*&mOGP2@ zUs{1h04Do3(-mTO(jW}+URl=1CPsY6-;Eu#LmYwA;=G&3Txz1Fj#pm5%(_Y`qBV=Y zz|q5RGCNtlED~E+^8C~B1of>oXN1O%(jUGAPW9HuVUUa%{Bnsm>aG9!KCW~!H&Ce7 zIh=a>g+ES&n%%uaSW$et7S+0g+7iCmzb-e21`7?RQ6ZWuZ>R9Obs@ay!p_Y`gbJ{` zcd#tAG^G#2eC!j6W~W^E7KNQlbfxeOjJotdh(c+dVxl$mf3sXW@thYZY};ruyWxKD z?+U$X{Wuro%Y2Du>r3*i`|wxA`D=rsv$5R|<%kP@1`h%8Xoy#Hqux`DYq+hEY%FfD z4v#9SwvFl}C1lWHjpJVO(0+Gkz{Y9P8g^$+@!_gB2Euuhd9_o|`UN$Y_+qV#^q>Fq zEQmPDVhpMCR=rg5`|6wP9p;PU?b*gQ(>#O+QS-2VP)yn2wD}lJxV5*WC zEwsD+%if^Vaaat!%$8FdNWG(C;@sefeSbtNu#>aw*T9WSEv|+I9A1}RzE1(*zy<*} zI4K`N*D*DyVm=M4?jmGCfM}$jdnGsMpj0&q+4PS3R_fTsUA>=YLRnjkQE!S9IdyKS zaCX;W#IE^q&czl%N=%TycrU3Y6H4yXzN+GsY7iU4;s{;o`J&S4-V|DFcm4qnK-`-u zy-`;Y0StixRp1$A0Q92UA<1gAK-3errKSdg*W#?nG}c*)2$I(UMy*EoOn2#r9W9`a zH?1n{kA(qVz9$!qgEp^ks4uJoac;UEDRUV7=CsSCXfD-4Py6=dNU#t-Kl(=z`VD>4 zJ~{F)kw6*MF+%5FwH?M^>+>~nK+&*cc@8AXz-Q^3dFMew&b z+N>V^u-v;eu0Q-{y00RjD)(ieFH6OT>JDs1B0ZeHp?W2$ zFaPaz+V41Rij{QXH*e}!A%e^O=vLjwv2;P4Izx7^3IRRgcg}%^aiLt+J%PWX;Yz5J zFbdI04!EOgOSEN1s<~Tv|3;vieH(qaWdT(X$|L8lN(W9ny!{&xVLx)dvS5+wQvH!q z;kXg%>mZ!5)(QV+bgNE|B*e7HpgZ>*0}%jCDO8n?Dt?}khQF-M$3~($l)P5}T?Te74aF=s^l?xZqP{zB^q#|3u-U>&V zfDaGQhgna~Y|sbKgJy_JEc*G$zjda*vHOsCOl8vo>z; zHcRqUp*7Al^PArP<4E;ZDsc8;pMOe)N5VL6oeJ^K&u_V`@%nCsk*bcUQo{GAX`9w_ z_*bY)`l3N7{FY+V`=$lkH+Q!*#Z1rz&U;H7Rbt&W=t|28!lHL`pdL`{oPl~Pcyk__ zDwseaGQ^meJHCCOQXwO-*cLxg);*V~Xw#=+W(h`#qlsHf<@dW1lO^3D=5s;ynCa2w zu+R57;%S_|so5mrnB^DtL@#R}SQ$KIQ_Y`t`F%_Nq;q6vu*DvB0GagDvu7R7e>b$t zK+QeHP233rts9LK2YsQ{xOwsM8DS>FG#a9}5izeKwLd?pG_!K(UZimPk4HQRyeiZm zJ?*Cvq_6=4`4uOKBPbDy_?@DdNU`kcXTD8p+N_FA3kV%UjKgW)_yzG z4q{Mbb7yM2rxS61&uaLN8}gWBs0$Vf`T3Uu;c{AFo^2p7J)PcI>^3B6K>xs|wrA$4 z*^WarJ8mhbSnw(low#U?xmq~LI)uWzp%e{VYy60i0_n+;SZGypM0(#lpWzb=7;3uq z^s+|yOGnLmDFewrD&M+$`VZ0XCggS@3UGy>)~#+K2C49?^aya6%>+ojZpeiJf=va% zYx2;Z!FF#hXQnCoHAr{6KGwtxmVPgxfh(X(>^3hI_}w9o<#aYnA=_Ly;~JgSwzhrP zldP)8<}0BiwVHobQESXh3hO(E#9|w@8bCi!9{>QyMdU`Hz!@F+O3NsPyzd!#L`aVKbUP@zk=?|A)Xh4EHlw7|$WVL1r*(vmCD^KQzq-=dQcJh9{Z zB$vwmo45L(fK$c{N!dh-A2so&bhM?c5`QRo#fp#8uYNn(GH{;y8^+O|49K*>^2+=& z81;c@LPF^s`6{8PZlTF_bHfqKBP<-3Y^^gt)CercuWcv)&s-n;sP_;QOf7Yho*{f0A@!YX)2<55Zzmi0JRus zp+vhZBj~jmpTdni%fQA6nYWw#K-o-4ztT+vAN+nhB$5-?$_@WNQs0*_qv8R`n z!R#3N^ppxdGCT2pkvWgr(UQI)Il+f4JC=N!$MJLAqqr`{xJfJkV)B+-(<2JANMY0b z4`(tcU;4al+qX&o)=N%0Aq<;Ge(U%_iWC&RaaKDa5-Nk19yNqvDV#s`-E~Lwogd2^ zL7wf-K<)3PjDfuTEnD}Z3Njd)o#9C~@7D;5gMt=OZ&QH_Ztgtr7%aF93y%Ek>M(VP z*13n^=Kj>*47N6$&*A2$XkX^xeYunZ*w?`#8}mI?Hc*@{%ewD_azXKVXr;u$8YvbD zFN3?H|9 z*fy-;(AFD`hG31UpKzf?b=SKE1BE`X$mgM--{6bRnfW_2l-0e@wQV8Zm24y1k2P$s z7HDwe{yl;_$49=Pek^1XW`e!DUY-B>a}F?%yf9_aY${(6+46a#HITOu zZ>-0yH3^Cq?FrjjW%y?7O%K@|efuh*7$}wpB`8&Btm6L8wZFkJOfwNvc2ZJQS%*u~ z{D>3K-nZ)Q5cg=By_e;%h_~BG^DKXkeMV%rc>)$mZ&5gdX52T}bp6=s?Ap3+6IJJd zv}%Vwt!JP;+Vax0fB$Hz)yJ7H=2Y> zEq7^kM8%pP4dw?cc|g+aYcCwtj0STIv6ZEkLQfv|M2DUM5H4jky}6PDnZ{1ckoM%c z@yuK1kw7$MU)y<|QBXEtFF!ukH4G*tQKk6lm=*z^X5^&1UQ<5?Av1FSmNS;iB{TN-4^V z3ZG4h$yv(elO7|e=8S?O)g7lSqw-fQP4b+f1cfF#<7e^fHiXA{_%uCISA%kq09tRf@UzY!(X6Xx{UtDBzF(Gu>FXc|apFr-f{l=TJEZN@r*!s}S>o zQAsww@O*Voa2Brc!A*-ttvmy9yGFC5^Zu=nu^lHh9x2fW5m~$rqT@p>)M|6u@+9xG zW^RHzvX-?uC-VIhoFn6A$Mrw*@S_oZ33>bDCttX%Ou0SL!g10aE2RqcD!RkbZu`y; zO&Y_)>ocaJmW*wY)TA|zKeXH@BXlYeL`wWCJBw@AX0*OO2IqDzsfuz$#e^HX53BVd zS2DaEoyqi`+^Ul}W8|aJg|V;Fa-}D;w49n_3O+r;d{BzP^Q^8MAA_#Oxfu6ro(RzS ztSt{Xa@)oc*=G!)4h0lTiy954OY;7vxv$i=X5=#kGDQb~fu4t;)usbWonYMtdn$da z_`sAN!7UhG2eG?EpP^Kdef7NphEYFQ{E zJFdbuuk-L&8{$sFVr47n;<30D*(^kn@;0}Qbq&tfAqHc;d>O(1y))>>XLC~nC4R<8 zuLukxp34%?jNn7a*2`{}xf~r{&EKIsy}Gc%jy0+?;pLdZg2!|j&9@229ZMgbV;8@- zODSH6j)}WXClIqR-*vjuYmxgcl!i2K)Q!3~Z7nIx2@sGFO>)wy6SjE-58@^PScEPn z`8TcgM1Ctf{}S>O;|ABOR7rma+wJl!K=$a4kZs1x$t2dPpSAN*@7;_^qr4*+y zRuzgiZz#KbEv@Twny^yc<=Q#Th=1#+Ib}cY#;GPA?O4?NLIB?lWdS6e|G7?rk0;s+ zmfPUC*Yo8r3~y$0=lBTo5W+6E=(6pHwYdBB0$&ClIg4=H++ar!6QUSVn^5~Ou>h|2x2IRX(ZGrjWKOHD{Ddu&ijSzE`#knY}=kGit@0~ z6v_KPlD57`56Y<9N~Jh9?~D+@OXhrbbL8)z{L}o0Dk6RR!JoJ0%+q{8O7Bs2xi#JZ zwU`?BOnB}cxzKsP>0zQxxr0H`r;@@;%B#5 z5F|mX^A1-(;Eh-zsAVwXX;hX`=|FkJ?|7|hgNZLiv{G6wb-rY$Zee%y8v4^2jeW7! zf+>CFFVs&(cGp{a2$Szwk8}QVUORmlA*fmA-k)c?;#z?plm=sX3+~QoIXN<@KEqy{ zo44@+?VP9w`h z{ua0BiIp|r5svkxq(~nX4mj{xG2cY2{X~^M%Dq?4VkY|@d4k9cv|2)XG(my*`w{V!vr?zuD zC^2Ga8bH_m)i(2~ABJnM*=S zpzjbB9&b6dqlqM190k&yLl#i%ZO}SD{Sm9}nG^+H){+w56#Av94u{)UIr32Z1!pnO zEwq!$_|bB!($s#ZB$IYFS;&+VwPSrTknt@J-huYyrqz&l_@nM`nQ@Hi=2vVu5-OC$ z7yOInDr)3KF0D!vIG>QUY0hc0X&A8vbaJN!fXL<;!Fn<{a~8B!P(&2=+P zOELg-{PSgqQtQ*gwmSsGVA3Gso5i-Ib9cN=b*gyUI1lx^P0Z!;E=&vJiRtG;C4UI= zr6=uL<;j2Ua2TyI=>XdR93p+L(pJd?8$n8yy+^va7vtp*TYI!0>zJmH` z18fvOLsrKvZCsO^~i#ZT$npYbJ)4k#e5J>|AW`U(}|EvU{Ht%JLH~^ zxRhWfekF7jmH)+Ac%=6^+RW(v%cx=>$e&YA=A=MDE2##gm)5slYIIq1KU$FieOu_s!yDxbm0G?eVNAS0s_dE6OX?wB)C zi)<7mu6Syb8BDAyCvP%CK}${7@N!BTj2MRz(E#)d12zlkp3YH7m_Ju#H(6r*GZq4b z*PjbAWrTRfMVlgd#6YvaWpl?q31Z%#l8ZpI*Eb5Tqr+tjUH*$YA^;cE8K(vn4G+!#Y z)~Kb1;BQwFrDe4NbR*V0U<;XnDQMoMdI|CH*t3GaRfC(YBo{q5R~#*1taKiG&}u^s zY{ica2Tl66yepB|%j7+8r0r(A*815o-q{2s%5IW%qY(tOi^e8;#XnBWS+EQquBrrIrEh#62~h!hQWx~=7e&WRR3;>{X1u&;}W5d@DC z%j@XtsIKM6NMT~RLS$jVkGy^|9S@wmT;^g!AIteE&MlKqM|fca#iy|78`o(`f}aurjw{Kg=|uD!uQ}K5PsUC`%8gZrFp+s1W2_$%q|p|_~$EXDbNEo+ov;Kfk`}j_lxd>Roaw;JZM9MY~}q%==so(>X~!3EMVmZA@zPpMspR67IE0mJ7SdtL3%T;P)jw z;yR6sJ}uCTSZTVw0n2d2_6fI9_k&qv&FizU15W>36|}wM%lBes!ve>sUp1-Bm9Orb zjH;oKTQ*Z37&D^^tv%x^H_Tz|mGR{Q`G%z8&L*<+x@%r2USwi_2kE>_rG&SODn{X+ zkC#*A%rr)AV1tjBp<_ErngjjQ^-qK(IzGd~@550j>WsA2Yp=w>YaGLZGqG9dfd-m6 z*V;RXh01UwkxZ9KNzWi~yuAMbfw=FhlmfpG6Rm{b;<9Hw^YL>Wxf^6TIIzo;_{R#TPG2dPcFFfj;)4+SqwWn0CK zQLO(qOCb_A3-1m2J9a51hE}hL>d+)f&?Vz=yzj3}wGTjjyVt6vht3~Hn~w#tl%Fcp%}!-i+KhV!bm&B_^G~A90)o zZIC~5yp%-kKzxQqy|voUO@MHqw*uBANE8a_a~1gGu?=N{vAWG=$qr-3st_>;&enn3 zCuW~%unSv?sI9&ECS>VFmwAEH$DFAQk2|ck%gn-UZExAG6)=-rV`ht`wvgk zhn+ccd_zz*dza5>2x$IUD1NDpzLcK_q>wxzBOoW z0I!1zvMV!dD|8WA`Ao(Wc(~Z}vg}4rUSW$ara0yclm~I5WQUUu6AMoJ7se6_fd2T_ z<|51GS(9wY>O*1aql(-3oQJyb-zG9UIrhivSD&j{A}KR%cwNOY=yhr%Z7au}ZaOxLp5gx&)?n~E zO`!7dr~zh9X<1_p5~ke=Gy2yQrIfxM))!!W*`oFt7A5vkqa4x=Vw?7>i?uzz{N-1#=xb?^+(<_O4D0-9v#z zD$_l5%K02KYk>wQT|ET^+a_}zII)7fpVIndm1*oaVUjMKdWrOhF^J)kwVQGH2_pAw zJ;_y2J-Fqv-J5ze9dKWjku0N||Cyk-d;`1S&DV<+5EN;oVb`4I9pKXl}%A655G~&?paA$iE;i?|HLRdMJLy zD0e?^BM~lpUP!`S-FHw~s+-(xwnUyC)|tgeSv7kac3zGQ2cOlP`K1zU!@uc!j8OhxLj^! zCGN~jigxE2{g;J|xMGx@&=5o)9$=~TG(%-aw+R4Uh3NM&<=T6ear-+P`sGy?qOY_y zUX(8RSwF=x|4k{$)YP>!qv75Cb(pm@-We+m`zi9Lf&f@x_$sK@^$PkV6_v_8yW@P9 zLILqp{9e0A?&Df&2T+yRLTOw*ORIdhF2>J+%4SnKq-yIIfEU}uox7Lo);^j~ z;CkFe=up3@yIQyo$Spa#d@)#RRFZ8-4sv{=zlrw#655&ED%);94dZj>Ek-;1UyL(F zVy%zs<@aiAgLPZhx3*QPyhqO1n9i~yoTi;-A^M@<)A5s9z6Gs4u3u*%lSIVIQ+OTO z{MJXeh&l4B~4I=}Q;w^a?xjN^`9Gwgv>IcOzK%=u~^+lhMaD^iCNf)W{}&VFTE6 z;QAgebr;O62i&Qd1TAxkNY}B%(n_vO0p7Z8e>dNv;Xb!9<6o{=P7b&SWv@Gk2N6%{ z-=e6D^!HBOkceDwE#lpj^-ZKC&6;pie9&d=Y`sCc?El*IxxoK!!@P5Iot+aG>K|5G z2N;O8vRSqqH43dt07@7@_Ug{E z0PAstQ!i@-QDpFlo!|9+hY^SvZG1P+CHhsQI4x6O-lkr*+FP$>%9WZiO0&Cj*&R2& z5b%t${MrRcan~N(#s*um#t+lmRQ`evk6pLh~Zo&&Ab0s@Vh&Ob>AkmyB)Cd!(YwNr_s<+DCI?UTm79x9AnO zW9*%8+gFkT0f5v~fn)%h!KX6>Wj-cG*rE~hRI)siOQQM?TCb>=Qu|q|lFxUYNZ6S7 z1upeQ*Xqpz@f!xwoS1~5<`d{RMmQDYi~~CM&u!JU0+~;*w(cr^o@)9Wy(O%{RR%xk zb=3RCfkiac4lqX8`oaoh%HM7UgSK zy*}vJ74nlt)B|j>?*lQEopfh^@Oytvo)9`=+9&8`ZR2{&^+HC!$42IsJk*0S{&CcU z$0_E#zZ`l<&Qz^6<2vlU>3#{}&RR6xx2zhrkcB=ILxDGJ|rAK`&+>qT&PeWIVCpy>Y=hWXzH@9aNV+;#JDMtE_*q(Y~ z%j&0jw$ZeX+0dFJg~7u~T61%a?sM7i&KnmJ{u2$9&pV(k=qnMnsArZ;U2&;yJE5vg z4sy7d_NL9aHbk+hBMRBDT$a6QDa#>2Bjn(ivX`eY)AuT|RL@lApJW9Teoriqx(sT_ zs%G+j#+4%muuLbiD(C^B{tE-^6iYo6G?I)i!D8eKdxXAA@3a24(AG z`)oh41ZTH!-`cZK(YS;jx@nA2NVi5-w6SHFAdNxIwa1$0RJ=EHoEMm5u?4{4t=IK! z+b{zyp`xSx7nrl>Q|*nxE-}3N-nch45Q$9x4*c61V?ygE7fQLOElhF;8AxvS%MTG&Gd=MVEbqVqon!jbQy{SD%BIU-a~%>)BuH=77yxVp6wbtwu^6IQ{n3y9ycl~ z60jH8Bp~874A{3{L3GI>Q(I^tEnyk>S^MjJ^w9Q&XMlg@&iJ7Cm5plFZpFNXG7i{5?Lx#Ih_Z{)IX>+5%{O_lQHy{805~Q&!o?U)d&#Esv9!G0e-OWo-OyBm4 zs`)se<`Vf~MZXaNQArl%IHL-aC?lu)r|&fvkuwHm3q6$*6n0Ikdt4*x#IVy+!S<<0 zzqJIe9BdPpe`C6&z_OtZII zx9hnDQ(&DZ8~K27{L#pFV!;+L6})i4iD%L8??m#KSU>XU-yv3GnR(l4-{D3|N<7wn z1=BEt?p!tUAwCbPKF7aLZkod83T%O?Hr3!U1H5XFCnzQj0IHah}Y+#5CU%&Zk`%parRVtOpzK)73U%pPL^o`kUGA32a^Ev zSGmRK8e{2~fB0&~h)w8C!(#b5i^B8imbX7gN6DRk^O>dE=LAx;?VR5l)%Fp1hQ zolQKm_2G$rY@lU(5eP36&2?3-OQc(Zf$B>!M*X|g6!$>9ssJL|O4!|B8{$&UcX&R^ z&XurOw&2YQ!aOwTHE+epE>vg&IH8t2exf)sFe8nIE%*`O$|sOierQe)2Ev##&2O3BYKHoD(Vmbqar zti)c`ZEx?18%q7K%U|*y^5vPe-tOk3AwMzIR=?|g@QaX-o@KL+^iTp`!81iaD;Wp! zX;r5Vo>c^|epr4Hc2*HFS@7V)T0ZF0f+ua4)^2tPbvYj=-oLG{N+D68>ai28=0SYDqnC{P zpSr#QII<|(HpawGCZ2dQv2D!6wllG9Ogyn|+qP|WY)ou*@H_AQ_g}qN^>0_*uCBhj z`<`>p*;s3zeazn>MhN*5#qJ%9;cVe;5E61h%{b+gM&~XYfx+`FvxRy~k6-%RhH1H0 zR%3XHV=bQ(eubi9F&94uEof2Ct@E`;)@lEQ(x$pD9nX_2g`wp&P9wjz3Vu&Z z>s3-|S^7zSJt(XskxPC#N4;*0QQXP+;)kB*;w4$m*)m6#cqN*h5K|dX84J8toZCSO zTe{FwK-0Zo5s-Pr5b=@j?>ad*bGd{3KOZ8PCvqCb6X}2CF|tk3`W*`q&!sTXno*Bv zn+MbF*3(DOH35~ZXWD}xU{QxBKHy-JMG#mO)hL}zGxL^Jp=q!fbuD3dDzkYWIDPjQ z)BPp#&q&c+dpk=o2-|4oJR(eGL+&HPPhq79@10*w!JC%z$jLquEp$pj*tr;yV*yHI z^y+`8bSmvM;hu~jbLVpTLjCBSXS4}I10c9GhN%uDuo?Uo!%>%;zC&Hw8)wtF(uDLh zCp&wbnE+8mz?Vs)fFkItz?C0{+J<;{k>`_bJ;{NU5m2*oTm|Shx-BiPZ5dGAH4{yn z_MgvTT!c?^a-4v15~nOZc)k~(Ec^#)y}O{CG5LZr8y<<)*Yz+v9^qi0-M`~Y!1v1b z5AK^O(aK=6Bi~b0W^6GnIFXebQTHO=FI|>nVw=}5s(sM$Cr20?1qR#xGK8>r3VCFf zxJ+J|Xgpv+vMZOS?HmvuEma2SXwCp?zTu7IHS0jrW+GfK>qap8mey*4t&DHnH)fH~h0+={%BiAr3spQgc~rGV>l z*aYI5$o*-qEibz6t;Cgb=x{i11n>Jtu5mpVBqrbXW6;-z0|d6*5cbx+j}lPg5}oCI zEoOnfAjoHR(thTUARH|WyS*Uu;#hbw(q83lDHpX=+-d`{#xl9Lh2e3CS6h4vit>@j z--EMLf37@%yPP+2{g8h~CP~K&5@TS9Gg!WyppJd~^ok5}tESnTtY#LK?Z#T9kjK{P zUTNww@lGbQ*4nA|ae^y6o`IUvXd2XPc9We_Sy{&;@57?C#vEuRzm*H>=M#}(I2-iP zQKq1?Wfv;c*Qa1cVlN3#1xn<%g%u0W(&>JHViFwUXPmRGLF5l(LKPpSaPYLW?$X5E zDL}2M#IE!g0fP}?I$g&|dj);=4~L;>O;-@K5&Cp}_7@&%LxaI$x)Uu}%gNg>fDn%% z)^t_jviHh2$w(SkjYG$t(~hMtGPM-lZojsuhUk94=K0J( zVd7VBjC*Fd6)-5TH)1vLG_?dQ598gDbME8;C#J|@gqgybKs$U!kE?GcRA=uf`n~cl z`KsPFeB%CZXHRYD$KuhfP#&2hQ+8xJVj2W*qw~T-ayW_W(S}2ANGXY%#vR4-ktm{u z*n+G_PBPk3=MsSCL6-WrWl*jJm^uFZb zpB8MnJlQEW8gi%@CD0OACO}JQp2zm0vY*%EOS-DH2V6Um3XSV8Z7B1iT}ybObdbl= zF-pYHo(=!KZe0!90>aLCN~u&nGtd24m{I%q!Tzf?>h1qplxn4WyR4eu@{R z&p}*)OD(RoVH%WlGVZqVg#|{7|FqRh+$Mc}>S1BB2*+H%u~4yp=mZ6z-AhlAe2;6e zmcIWkRYtVIE2<=pncZ(|ijPoiZ+D-?o>t`Em>qC2_E!vC_zyTi<|vhqHs<}**+o5n z>^{Kq6f6Z@HaF~9F)~pdwvM&KhO(m4*x9#RUI5_4yoPS)k#IbsKIE;E`Ht6Pkl{V0 z*os>rb{JmR?qL9bx%X#`*tahx2thcy3d^qx}_iJwy0AKq!0?iJ_1KyUT{JnCby0p1-=|Y8gqoO zU{?7aK@hF^>pf0Y+EMo-BZ}nw!{jRhpj6Qt& zxk#Lo1xl~p5QDjIq>77emlRC}3*in-^6{vo5wS64R>r~*<`?cXteU{~HL0rIR=i|e zrrM@t1ZMnmqatLEBabEu!OF&Sa;6w`-4<$kVsw3=!;N=!8P;k+3mDis446!kf_*ey zH}M^QfnwF@|m&R}C20INga_P(nJGx%ebA(N4Sr>TL3c-^4?M$e7mX z%G5laDHu5){4Xu>HHZ<#Wj5VBm;r=MdFj8s(|)$>)(2%J@xa$f`T|rxB0xiGqN@9& zE0_UxpeSF~Q4TR6vzSxermM8?Z`H3Q+Yf*=An>9d5aoO838|*0`Tde)HWsqL$V}9m z(hsi(;yXDGC-sG^<Qv7(H9EB8KAXf%< zR$`K`MQS*>CVsaj(t9%)m(2P5MwS7ybYbif_xDdWCW%8D$#&czC`E5phvob?$qyo0 z3%d&*7kIT&Y>W%!twisf4ET#uOM2h%PZCN1hQI|#I|WWBkoI@;gB;>_J~pk<$9a5( znzx0u9uu06Zt|nsyC3;0mTST5l7c}V85MT{uVfTXNI%sBo~L647)8kAQfZsNx{^Z8 zj+xJwokpF`F&jE^H>2^ki)&lZd^KKD{23o0$CdN%dVKb|dI)^kHPxspTGv4FdflsF z8zm5l+(E2WMYX3x`|kZdjBq4Q1jv`(J)F z+Sc!A2LyOeWrF%GukpCEv4rf}Kd~VcQKvC!SH{>7H#cMLoLtNM)uo~Z#;E^&iy*xD z8mDv&E~gH$$>)Uojk~V!)oxsG*&NkX*`+AO5f5-~V~gnd0?xA0@#K+yMb-EFBEW;F zSd#In2t?~Hz~F&J?5>zBH4uUQ+162}iyht5h2~#%C@={2oU=NsRxL6z zL!Ysa-7f@sdb%?D35_x)LEKET!%0qun{zD=CkZm#`5y$d#e7ga8z#uy2Ap~{xX>}afXaPos5B` z?6k#HN;yYLR(NvnoHgC<+Bdm%6g8Hf>mE0)Y{BbG3Jue9*3gm?u||qWW}p$3oiIG7 zV{YpAm*!I9;!PX;<LSu}QB<@VLRpVN!Lv2-(r6nrcH%GsmQac>IO)NXl13UgP1?qau|=b{o({K7o{=BN;@ z8yQullZj3)n7RpiA0V|i4}GMc#Bc>Ev-PI0==FoUdgI2M=RbMMA;Feg4_aDY@?PA> zoh@$6O_9^mCIN8jA}*{m*CDXFd$vLzi830-i(}`B7fggGZe|9Gwu&xLI`}D)WX~pj z0KS^7!&V8?;NDW0(pgp|U^Otr(3Z6V1^wIy_~N?39qXQd<`#mDTo0szm3U4MNLrkE0$F zT>c45Iy%(5E-t6I zQ|vxIYqMN_+WHNb=D>qadDXiE8E0>PkhSdS)_warAv`m&eU)|Ta96XDf0hZ=h}-ak z3pP6;3PdBCTG_WI3kL7~V^$OQECF@Z#$S}1GV7Jxb^Os@%`7y1FOmhz1F?VIm+lO* z>GPsb(c-5&}rde ziVgJ}AMUkcOuVK+fO43dPsd0D}^XuFm%KlE2Saqpumdm=0`6 z?#I3nI=-mH;k{kgQfDR_r7Xi^QJb9qOUI_x&t)w} z(KP-eo3ptO=H5DLh5`@e&k#@UbFIcCz<+F3mVJf24=3ev97!(~8mR2?HrGN0N@h)? zb!%$3MUQa>aM5Jt1bA4hF=3mUVs0KVbH z;Q?e=&g|syf7O0c?TrKwn20q>Mgo~CXMONE7Y{^|I8;KF!5$*NeLi8=$%)i0L=Gd=XX}sd=w^^k22({D&xxXK*;HiVaEWPEip>qD?lkqqGTi$=ohRe>f?_g!F8CRQ?&}aK8!A^GQU`>uyQ3#Za=%2(-oJUrV>7-8iZU8rs$ z&+55@kADwE5(6{yU1c7#ZNNOWfD=9r&ZvZ~Px+x)1|9-e;c`Ur(Rl$)8vhm}C=B$y z(%jXBZ&3s{uk_H&=qdXPCkF4%CqHfLhV9@#O^FqQVk-~A0v_gl+CCiT)+=WME{yThLn@R8AL!Y^Doi7z*_c)k4kgdK}FJ!bSpUA`Y&aYhIR znZPMq$gJ636esxKnbnkGQ5h>noWF~i!FTJ*e2y>9U|{SEn%c6s&zvtvujgm)1CeY? z($aA0Ax{?R7`lvQ(Fj-OY4e0K>|sj8puBz>tAh(4w#slh^lr->E{+ntyY-z;?4DNf zN5rJxI7bTjgLv$-*Y^GSeGM0C?QeALxXo~8|N8kWIS&8CN=$4rv@#*OcRrVk2N94p zq!qeh!+)kWY8jC!mP64n3LPiCL$h$F*l{ZraI>J9K^0iv-c7=ec*3q9ub7qA#NJ!I zX1jhO2zP(nvP;-`ymFjdE%NfPLZ$ybwcB?L@7CKWHe+!a22%ad6;oRVgIC=|aeJdBkCGpnvQj4>U01Zehu%^(i;!t}$ABeN*Q`B9YR_Mqhjv34VX!Azn6lU6c4Y z9ZBMBlkGY6|bWD{6uma$`792)tQp(0KLmY`t@cpBtqU+@D8pOvl%T;=e?TE9x zU9neYd3Z9l6dW}>pUZ-)W3`ZSPU=RGwyz`1-ofERE~T#gZT?=wv=EEMbpEgWBwSGZ z(Nsuvo3*8O+Z)i*0nU?Z@_eeJ&#*(cd?b^Mg##wjUk^*bekv-l$uCkiCS&Z^oIh1S zcdiY7kJ8+XVpVv@z)#xC809hz_23Hx_!6#YRoN?~Cqn)@YA;Cl zgzE>JH6}WuhRG1R7s^%^z~6akwwZM(F4)#lJxuoe4HX(C{bE6N^VW=u7@6dTgU^Rj zQTCMj73NfEv^2DPNY8@FxM?xDwU2N@erLZ&{n+zUxix0%!hlLkU7aOK*v7XF^`dT^ zovrPBt&lzjUyCq>-T8GfiotQ@(Q_QeF$AM2A}V2HFjF7H`0i?ht{;^g*R=tXcb51)R2?<|a-2IpUgKQEvo!qoR6})AYxwR)fyd3e) z_pgnz6I;!lQQE@q6|X*~sk-SFm7r8PY_~~^1jnH$G~ay77u*CA4p!u%0!v(lTzOiv z80Gp4R;%+fNruuylU7$jFr-EQ%f&!Ct5+b_ z<)j~&{Yf^97EEZ=gnL?Z*@vY7uC`f~Db6LBXB#2KCB>58tY9ZxQ;-LuMnECuk>dsW zh%~=@`N1+}Fn8UO)MG3tg_xQIk0l-;2HWo9#hFi&g^;(V7nl}G1#ZkSSA3^o&75$u z{G)4764bF(Jp3ehzs6zAdAXV`5}hH2O)(H=*}LB-Enz&75ef`PlFi*zR*+@=aTYIz zwW<4YPe#HKj*2*{9{o{M-z>E+fxQ7$Q8bONZ0hNvMHK-;JUhz_>*lV%?)@NPtqGv4 zf|Aiu8=z-C~&j5zi$U3zAYF9=w{0>VSw z>)tjl6ors+z1mJ=wM>yYORQ4)u}dJmiVr%^yPow&bT2|MJX5;;Xn$wAbJgX7Zi<_V z%IW|h0O27Xq)>iIA?T!OBK>^=b-b%4VZ8nTI@oJhusH74kX2H8iMRsC2SgdXLGS&o zVuH=NwCnlh5QjZwu#A3b zS2w3^;1tb;cn*3N2dCRy;~RVfW!T#lhSWY6i_riK|GAniyMv%hPn_|OLY!4tEl#s? zuP#4h9{ri754$y5%rE~tB(a!6=8nsw z#{y2-A=bQiWL9X)+VBMqpL#@~qhKCk3J;(eNk9Zj6DIs>{!s>io>7l+e&}fBRHijZ zkq_`?dfnoca!1PYgcz^WLsewSXiO`~f82r+{ZiQd@a zASFP38~uY+VF1`lG1b88~Tj-{h_I zrtUMJJzLfJ4CbC}BsQ6shAVw(Gg{X=`I+mmkvHX{5JSAAs_p2e#sk0o77h_Ul&P+9 z)&oF3FzB0A?0myd8_)5cKG~l^(*!x(OWB!QDwV0ZC=AIXb4c7zU4vw?BINk$$)gh% z6@}pYQr}|%9qiCB^*5GL^kmXTK`Om@IG;*}6R?9nTJGwzcn=mC=*pvlf6A1vRC89WjIk5m zjO~WpSQ)_PB{D&6`uBLGy%ldg!fFW2F?u2hQj1Ek`R2M`uI^p`JCJRhvn34x zZ2uT0#N#+6Vh9LIp%gJ$8!R2)BYFNFDSi+|%Gj~ZeBqY+)pNU?oPSa*u3BHbBgM#b zpcf19gK})EY^nHPc+a6>3tXDyi1Pxvoq74Q)865=9f_VPy&|DU82TR7+x{wUzhH0W z+@pLVf6Ew{zh=4E&HnKUP@gry4M`X}Plc#}zdu|P8`fjtI_L~{PWwJE_f66`Z|BS?Y@AUw#yPiFCVAUA|0{)V9>pzhe3$UG3%RJ4@AmhYAF^R8a5qHOIQ zeq3Q>&Y0wqBM${DF>J+mg)F{z&@yD-p^LD8FUi8d4~0;J3U;?%)I}%M0M*$`pGq|; zGc!N}>9wqqVTJ(By?&8h?e$q|CxIj6(Ij=b_2cI&kGv0rlp?TSx@02vbq8|_njd-ZOt!p zYkkOPERM2KE_;ZN0yGqB&EmqY;9S> zBq}Ti%AF=*q#WAp0EtZ*e<^|{k7B-0Bw;xqUiOS16qVGttEkA7WBsXLBva^9yw9orEDl_$FN>3xWvRsk3#y5v|Bgd=2rYx~1i;+#c$OFc?A=s3g5VZ1iu!RJ|FI9HDLxF&-4C&fQz-QFw@v z#2^z2)ACWft=-C${OOO$%Ma)MH8o7lpm0FW48@}CJ20Q5|20Z({apJD-@HzizCGdU z23`{${=wxcB}$|)za`{&gykR$!w8*ho4|FmIl+Z{WIoTkm+zSa@WO7TXM2U?_iDc< z_mV%3S<*>ua9{Bk1jW8C9rnJp$+Mdw&0WyVMnR;)S2O)6h0?lM?K?M7mjdidI1L7i za!?CkX_5@H3pyDOhvpupwb{pf2-^xXnM0?rWINDBGeDg@)A(u;9~z7lXYXp(BS_nw zO@(h0+tPp@$PdHP(>9;8na;lBvEEk-`M3j5Qd=!3Rrd1f7}iu#&Qon}wz^=b!EE{^ zMjnMvWvHG$h`zwNT?*L7&M?9ih4*yiy0{qn>jC+o&GL`T3cuduc)A-RVd+<%3!O9u zp$3`jI1x)4-nMI<_G3mX?)ow7&XcD#vQe%1qr5K*M9fADqN%FegW%$-*81K_2k4&E z2!4G{H*yumiZ8t-b?Db$k6~|#EJSupv%q~&wx!etE{W1Yr$el+*=9Csan zB`(4}?evsOQrG&=f$J0fJ0UZEWn1<= zEZ-r~Nxsf1H}O)7*-hJZe7DtyUywa-%k}sO<%@D-GzAs==NdI7t^s9ya=y{;jt+nUlfCzVEfXeMR(M$G~=fIW)QP0`H!4!O9WBAR*RM50fDgM zgMuc-i4*1ZaL;QP$PP(zIU9x5{(QMkXn9?F=t=UKG#g$K2B-H0KVqW;tDu()>H*u^ zl$%RFppiIQAp5l{{A$QwC-?|0nhAv(^#KNGBOQf6k zD-%B>Y#TYPW)m>uhfHUUBo9n##j0dV{{MjL340PoHwIw1s7xR|qHa)*7*dV? zac{zY6>v8i`J;EF-OL*a;b1wfg?QE(8udEByQis~NEOO48SjW(4fD>LR$fG#&Ggpc z*St9N*d4HFcmD=!#S4mHZJmaOe6Jx}4EXOr%jQtcin=?_d(Vi^MB|>V z(`X|D1!567odF*ZmNYIvzZxIV0wFqgoecJDF!NcPrQx!FIqzKWd9XRC+j=%NGxh?* zF?!NOx-Xkj!N9F_*{xS`koQT{(d_MXywx?PoFq`HDG4jqN9c)7j|sN4kK9UtgYP#% z73X}K$A|ac_RZ_GLg2G^{T-BkfS%QQC^^0#qF(9zC&9~}| zpBcqW%~g)LS(}X8A&h2GFgz1{GcQbzkxmCj>5KNCe>g}?x1k#znqJ_6gkw<_D$Q~F z=^xbsCZ(UDK0eaMBlt8|4rcU3+{qKV+qYH*x@!w0^;3S5*2>ziBK%K|SMj5S=nWcj zbA}y)pbS-d9^6uBV~w2HR-59&y)U5|ZR?8a=!jpu*D!CAA(-|rv`90_5zt?+DX*qF zI6fO8sQJB~;@Q`u<<_jMjo)u?DBM$~Fb{QbUWL>M?`BOgR5VO6S~P4-{yJem=@)Y} zlBAeJIyKtp3>R~ICth5H*qm6HR#DZ=sm|%f(e(7oyW^7X(OJFkX@zq^Y+822o#C)c z%*MxlvCAQ$dbyfqdZ(R zR`uTBlZ^VbVJ-{%7WCq}VK5ch!dvj`wJ2GtvP^F}NGmpZE-SZ>jsqD(<%JSuJvGui zlrk*PHEPtZbo|;R!A_!bP+Xn)@hwKSOg}TybjbbJr?CVUXpedWTCNhZO4A1(E@l!| zz2#_%k-6VJAEV*o|eJ%A`XsP{eLEzBVm#O%8j}h_<&tRib zBq0d2(Z<&hN|147KDJ-RU97d-U5>)WlIeL)TDV6J5|M8vllk8Dj4kc9cIP>F3x9T= z*h?XWXG>Z*arp*&%>i`*P%Ps4Yl07`p%QGOOqK(i#f;V_nkf5|46|+UcEGIfiswde z82FcTF(G0Mh=5Ce0r&;(>*-w?D>yHKES5oV0Y00T%JQmJ4!5`USnd7SN2XQJXjaSR zkTYTI@{8T=lZ>;~`1n~1+SaqXCt?OBr%j>cI;oW)cQKJY6%b(@HF6 zGh1&_S2ALN(DV6xp_kBPH?(%%2vh?98{%7y;D(7aDN((5i;~^sJFba3c8a~g@kZA-mf#aKJ138tj=pEc)v#y zNSu42G~DLfYb6`L&2sBk!4p;U#7gVCl3ydwI}OP1v^uf~93A1W*NUNA5nK=^h)TS% zXUhM=_h(MJeiBcn|MpbuRrH%Vq^^hz=(z&G)ULmTW7wLM*p2cYp=zS&5rXnD1;3m~pl_>)k9HQ9SxL^OI z1|zaTVk3OVUBfaFAyVL)EYom`LDpm7`HZt(*v2MJPn_`&j!4+ZlHe6?5xs$Co>55Cf0dGH3> zcsCa1o1u98rj4d!HF(z7(m8B%;Zl!*^6*blb;#ZmrWrWNDLg1M6+6k(XdBL7XUGvNz1P00{?svX*u?B&!c!#Da z^2o*(>`nk_;bgZWZag*#XRF?X_8SpH)`T*KM|smzz2n=;#p?=K*0||5`=O6#;vVD= z*=(6;^^mlTr)T+??~ApL?%%_moEH?vlM5>5En!Iog`4&9nqx|cJq`pO8&Yo;`ogJf zJU$@0*DmQhYH@S8n|6LWR^}v;Zcl$V_4^>ft(TJ4QTZN96cir!=RGpvJh78mz(Ldh zP3!tg$Oq(NZSp=Y{zmHzN=74*S4ZPmNsBd5GJcAA?k4KbK^Qz`m^Wvoj!d~F6Z$=O z%-p>+^iI^di>TF{M;P*7`wqI541OpfccgsT$VpM*?zBmxZrL%6W|cVGTMr>B-pxNU zd-8-@Zo3oKkJe=JZk9C<4sp!PXknXck3m9JV_&IfViI$;d2sDy>22xCTIh*tJET)j z08M;26PlhXv6{USOtz84F*;g?j=TqS2J5bFhbX5Q2YbYDlNYr=0pz|lDthiwCx9ac zJnRv8gnYKCZ{M^Im)ABVc?>;%@-bal?$7ZGWE=T5vTfBS0?}HK+y9Cj2q+PHHiOp> zwHm^G860}}F{dJSuSvQ%J%=41jm%R|(L5rrs#i3>`z(Xs%E?Npm#L?>UP}gAEk1hi zm73b{(U<;xTcQ}<+UIUuIiOQ+ZjxYF6k_dRX2RJKn!By*FID)o@qRva;pJt*?n;=eESqK6-M-0%?83_#ba9Y_Sc{tjcFZ zfr`G1!$0fT254%_BU!6W#wzlvP>btO>?lfqm#e>-mKjwu@V450H^XfJh(JCf%k)zU z&`!@}2!FGid5$c#q&PSeWB%8y4K<5W-&y_WJ}N#! z`{hnpenOC%cnLPmtN#+l${~LBq$1&(q)6+e{w@mj>RG0JMv@r3NtoU|b5aa`%EK&5 zgPR{=Yvq)Lw+WLb&G^_9!;{!{)EocsqZr`SrbKa+$!nz_T8h7v+d~h*eygGr;QE{R zAgie|lU6{cukJooRl?|~B#O|IwB(*u71y4?A-e!aT1e=wv&R=lwFemI`5fW<7tX4i zjVQc+%&bJ=Ufu)HKpn>8f^hri4xiTESRvWOCTTLjdo%R{Vad3!ccT+lvx*!IV4sK( zj%8wIrjaY={`UGz=xW7ae!AV#T`-%TqrNI(OHa+O{+7PH@(WI?{hpuaCDlQDNP{Z3 zJ>HHy@gUaIE9nFUy#>x|Uv-gNvm7N2f_4H;;B2Y?-eEwX)oJ5v+jEsId9 zxOfqFK08)z^o2|{LVW;^d{F?0K;C4aQ+ziQJ#L%xK{~B0o&exKABk@3FsgPbJf>rb zIa@`3_%gsnxN#Gt@xdIxGW-7U1qPY57;T(o@rgd~J-cQJuQSO{y-sB-uz-FZbqlHM zFq@LZqS4ZO3<(+TbTq-ssFO0(47SR2o@b0cuTR#J-C5-1@62AXk+~`^?mo)PJP(gdZT;K*4+u*2xJ@f#>Q3j^w(D(weooO>clax=qj?SbN{aD*+D*iE! zH|0URSU$S$b}vPjh34Af=n%@P%4Zb1G3x<$ZR!h6#?mWzD0iBTI8Vs+-}Ef zn6}%KgyXvJf1St3l3TG>Y~2}p<$oy{XZ8_@l--RYtT~O7-({yUHf-2X_`~DN_noR9 z1~VJ|y(&DQa}!IE-)#T*s5URg*W85DkVV#*KTyp;_HzIHg+`V5$|L|n4spfm& zF-@J+N$g{o3vzoDRPO@Dlq9O!(@ zGT!t~uhag1o}e8Mr?}?jJHIvj>HSf7qFf2g#*0U1EN=QRcYQmgtpL5Jdps>DW2@R4pucWvbl5-Kk+deO*p~ zczBuI7hy=ljWf~urQAFZ>fB}Qp`i?I@-X(G#IJ75(6c;;7P+smP?DoC+z3(pFjiBU zj63;Nh9$0msl|&=1Kgg$bmL)K0JW;*I4hy#hRS+@GElnAhK{D`>_8gAL!B)*#-Lhr z9x(Y*T)n}|A?a+T;wX@q+$+$tvU>jJCy5v6m9>$}b_(mzRUVwh^a^j4{{nf018v%$ zl%a%RW`qXvlld*Mq9rs%dYqq)y+>idm5=SV=d2fT?22d0pKt6a^p9+G>2T^}qY~Hy zPc}M+NbHBBc+m_Eo21cyHau{@{lXBe;=z4fa>eooUnBRPmZaA|1sqbb{S3=3#R`5= z`3q9~R*w!Iz(TX1`*(+hwkyYA$1V>v2jWf`5v#mrahLhpoHTqlPFwVD-H~+5)(~mWCWB9j zF3LaR@^~bD9~h6p!4(nnbEt<6G9)zYWT%;zZ(&(C-h9f#F12A^)R;q}AJG4^U|v^+ zs4Ey07#J=R7#Pxj7tH(bT`WJp_>Tj0(dUtwBqyn?fH`E^P$V=VJ^AfN5%sWf3~1Q^ zo~Y znBn;CfDk+wgqd({R(1bu`?J;9>eh-E3E2RfSDNnVY-jA6}{ZYHv1wom!tJ@FZZYngcSiFsIL*7C_w(3)WGcU zO^8?2586Nx%Iz3fkEWRs~U@)8}a zci*;QjuZ%Qw##ki(=c9($mE7)k5KZ71&KoV{dE1i{&b6-gCBpJfqpQ2jN)X-wd~=Z zB)ev#x}`7g{&rIQJj-RgmBT;p({Ga~tXfVF$dq@zcZ_=gw`coM0R&yOA2(!q;=VhS z^@`kRD{jm%kWCfMr$xU{Q{A(?626vnkBw4AWgF}U#mKc*Jc+$UZ)A;^5!Wt~VZDTU z-y*%Cq^f$z0qHij|2}+mK=Ij~@T7SU0IwAomIsY%1KLT$OXZ zPeP;n35dLtod`U=T{YS!J=qf7V_h%GQOrQ^=kqUiDnSq~zXfK#xJutfe0YVhO%vRy z(f5YP4%$S0G!GFJ`L{KHYwFS+q!-+5yCj$?`vAXRZ{Fxuy32pjd8K=e@H9MF28Sc0NG61R$3SEav08)7dMx|5>l|Q{q1lKkyXLuDSnL s`oF4o{%_&`sk{D5^z*Mr9sZy2e`+#$DQK9_3m`$SCeS;a>*uHc1K^{mbN~PV literal 210863 zcmV(!K;^$sO9KQH000080000X07kxCw5;|30H_K901yBa0B&zzW^ZO+ZDnC@b1rUh zc>w?r0H_K9000000Ic=^000000GyilKb8L*$Bnc|sVJ3El7=!$gj`ByG^rF3sXihz zWv>QhRK|VFI-HzyA3}@@OaCew{x>~l~b3N)4ZT2Coe5`!O7L#_1qOJC)e|K|323{=ip|CpSxW;=WK`n z-mI*)bC10A&MorNzS95Se~TYzm|Id)1c*03Pg-rqg2NsmG=(rW=tPjO?qv|LcDHKC z`upjydue^wcUv};NIa9<^M(WlLqH@YE(!Xr26jFz;Xu|lc5>|^682YaQeQC6g7zRg zOD8`zxNLYkvdWi&ZoYshv8fa=TIuiJqR9ov8u4i510?v4G~Alap+Jz$xqi2b4TD>D z)UL2ghX)UC)U2wYgDPdVDCjH~8cytf=A=o2<_^!AumB1U_e{C-zG1^#PrvoS zEb`f}i46yHGlR9AQ{dqJLfY=pI9T*DVfCyX7sfY9*(}-1gpk9QyuvFPko@`WWSkKP z`1P+D7%nAYDEi!@vilSW{Aeh>TFZvdPg646yeWt%xl29!k^=5`JD()zav?fbIo~&h zfIU&cJDq@cs?v!B6{`T_ZWar6Jd9Opxxt3edv{W9KO7M{9!d-@4DYW(_IxDgA+KO77j zz&>7=9F(hQA|doV+uJ6jZ zUSz_7lHS(p4IKmwzH&bn=+A-$Z%yPRu@0|a=?l5OAV4AaL4nK`3La^GPc-UaL$-G^}&0h4uFr`UC{?xt`qD%!2gG^BaEpvcX(Z;HJuN0;n~^ z8i(>(5W=AE`-0D3y0G$*TQURm^JCko9tJqb9KBt)f&+#&qRz0Kgwc*%nQjLbL}`WU zm*2(yo{xH?{SeO?Uzc#1mx9JjG2S^m&($wERZny%xM;9Kh>tH73IuphhH7&m{`jBK zqen?lvf13Q4f{Kk80KLf%7z@}a*eA$86cRblNs#7fPDq59$$41bg$X!ufK(a*!P?2 zPj|B5%(`-!bljsI?R`tu5$RBWGGXX>D;<^;-qbi^!G%nA_C#n54I=(5-NgBj0KS$d z5{r)F+-6U|$}MKXzBQb~8WbIrrw(|nIl=|=xlX5nOa_FlYMlyoro;JiR!g5X7X-Jg zvi~bWf}q~21CLI!Ag~F{_D8Z|(N6vFzt<>mTeMn`wjvcAy}W8YOt|n_Rjq5xi-bQf zKM2|fvLHKT_vM5THhgrk3SC*vgg4ff9!80H&I^rRqn2E-nr=29jwHY-V_&~*8xypf zj_=LxWrNJlKlF|?0&MLvz8=GV9k=SZ{ob1mwQp}7`u zd47h2Didz!T^>77&ww1afHF`*{Ykcd@@$-d|Dw~s4b-rJ`}$Cs~&ZxsnK(!w8q~@q(uS>exr? zda?2i6r6n9_;7w69UeHp&pd97bqJWAdw}{bVcKG;8?{Ye%uJv-fRX~S> z%9rHEP*)pL(?eg?6TniL6Jui?CjBoo>}q3!(Uk6N@O1)~*jToCF<9`hQZu>->o3FU zlb&}l9d0dKV$feo2bZMzYnC*gy03Fr5z!(8%>#Tq?nV)iRTr3GJx! zc|KA+4_KfsyH;Zx)^nHc{dwyGDNvU`HB~i0ht!q1m8!?NpgH^Do+Iwhk%uRookqCY3GvHl?}yi*36xYv%sm5-byNwE5?VZy?>`c|H^;$S@+ z+D&=uzWEZcUP&~-n$Chhn;#$B9E^RRNXiYjBf;abZDdn11xgjGUSdq-4(BX z2w&$+E`^=pg3|B>`{oD&4mn*~5wwGXP!Z$r*IL=IcuUW>?g<8T>`PdDbuL)+`OaalKMOC5uxKKQKvtj_xzeG-a_#SeC{z6_S7W%$*aa+c6EgHPP7o750 zm4Nz|1s@F^xiGWfQ|)0J8a$_&$6V7$09NIN&3kZ8+RSf(=nEz&&sJ|2CF#H)^i+E( z`ndQqS}Ffq0?6OHmBO$u1*b}e@1y=05D!(}_K?seKN9KiI}yxmes)Q=ap3RWbD!6l zFk$}4Go3L<23(f@JeRG{fkqwK@~$KT{?OaLJ?Ue?>kRs8S=3t%^2D_{e14RG*GSJC z6HL98=PRH;O8+VDa9B%%Y*r0~Ix7lzr^X;-c)V=HikEAoo6v!yq3AVSR zZp(|h51@|JhYD>o3t|B&74tm`ebb_{sWYI7fNFC#&)!WGi1{z<{mEv-lZkS^4SPsX zJb&0=8SZ^<8x{z8?EY`jjdffCVp8V9@3^k43>Y5&OjWu@n&5Vm$oXfD2Me z_qG+7k)XeLNV(951ulXmc|+KD!~C2I@$&@u&%IhE$Yz1WMxHk^sJAW4+~Ck<3Z_IY zq*A}9K;+_FwL;XTEo%y<2i+;CU-Xc_raJ{x2=5wQeJ;50HVC$J2vFgsCtPx3f$^31 zdMod+VQQ1p$=QV@m>9WSA9F^Xq&ysG5y;!ljSr(XlhCAeF>M?2k;>-iWgi;Ypzxsc zjXUlU&%rkJvcVLvHrcxKHtx|9g|mxiP=A(<_0+3hV1ey_#r&SgIikCkzVHkqVEfS( z$MTSKG8%UC*kWItF28CzBS6B}OU9dZUZG#ht1sAx_x-Aq{c8LV0ZrxpujCvlFl$;- z|E-Y?Uy{!DyYVu?XOZ?137j9tChxw>I6rS(Z~c6=feBia_CA$(2E5xgMRn+KpgdOZ zNUb{w$;KJ2eM}Z)hVzINp)S4Pf9XAwN5Hyk#yM`LEKt@zz^3qn2osGq(v7Vm0w zn9$J3n;Uta0WY3^*KnPSucHd#4(s3p@HP0Ws*3E|J6Qu+Dok^JQ%@W^< zeJGtuOWA{cDL7i{HbxSle!_3PAae5Nm0v^>kdvkQ&MBTkf4Or&?8uFhBydkyydwQI z2Y6pA&T?-NaO&zi(uB)|gzSxKzl-_Sr2^M!srVF4kF# zI)CL`4QFF36AG7YSn;qA_c8s*xh1&2D{n>2dG4cNK|s`nB+L<0pGI81)iEIN!PZ>0 z@igeHm6v&^$pQP*N7S@LNqA~|@$66J|DBy_3p}yEoohNHOi`~S_k~5qU`{!AS331H z>hK#LqgIz-3ib}!sC}(Wfe()rHD4kB)T?ZG^+1<|&ryr&@8zOD2jq<&MP9PY;IXT_ zln!p80lbv{mV^H z5@67Cq^baO)5SbLpHQrGc8s#fLd=!=A$K$eu+CL~MXs&I&!gWQ^4507T;_Z%wBaxd zu0Hflj>Y|5@j(2nyD0&FrCC=BR!~s9+4$rv`lHBhia8dG`gyMge$S_1mWM_YNBz`x zSkk-zxhT?S*@DpbOwiR>rci;;*I0i_rwIE}{PL;#JP z5WQE&f&-s6N}oi1p1Ndav*ZQ=y8PcgFW*TA6}zvQi!WgwF|5|SIf`|z)NW5rVnI-B zU$6>tl)ZNEp>*^$f%Q%5GekUz8&Xb(T~WX zwb@KK?NL;%fj)b=w4&{|4Hp(>{Zdj*Az^#T%*Yv>=kE!r*ENecF!{``+Yz~Ie@vT{ z=Q|eM?r~qj^}(F0GH00ei3vwn40j9$)1jr4S|x;>li%1rw*Ec=oqxAyIA^gSYe~tv zJ9r*H#Z4Or>}epARAsc8p8%hNX8pg|_pxKI7*&G=YG6u1BsgWcqkUZo2gJ7MW}U}+e!3N5 zcyuELnVFmZMxt->vGN84MrgoqaPewYSR$O`ciplLxx$5?-|rtkcbzehsu82$%uu0T zEY7VTWB>krf+WbLWt?9Ufjn|amFF?e)!u|FyltCESlDyANCERyJ-MIz~=o?p31{@f@Gk9DW7wL|7A8%9ipDj75i91Rbh{Jts`N*V&r`6F+PhIy^3d&_|KaLpen*BHR(l65U$ z8wb2{*4vLhBVeIr$@#OGyWiAUhYR6-MJCMyX51&s@~AU7G>7Cbf0GlFyw>cX411YsdDhy#%oPeLSAY zqrX)7#nmB)zhnLv%Bx1gzABsO7Mv@G->ZD*<6Koai{JQmoC5n{txIWdQ=q@{)y8w^ zkEOyhibZQ!U>z)(v?+rQ#+eUnZ(%Oj+4471p^taelXy z0;O%fDyEo&y2mS@rx_vCa^{sO?nuxb3PP3{y4Mb;fK;WD!%{si zB-!6~j;f@gKS{aMod}SxINN&@=dGkR8#F=*c+@vw`L>q{t6X@@`p_?4h`K9Y#?M_@ zN4|2fJ~XAd#OY=>R0u9@Fx2f^!$wbZT1kkC)BrQSWO%v%WmjPy2ZTjF4)QLfVB^k1e6%<^T#e|o(lX(~ zykCoDhIf--fAoGvsWk=D(g)TYM?b1QKEk>uPC}4u*t@_xs1K1ptA~&qb3zo4(Q)2J zum4tTK+dsSz$@|Z=ld(DI)3!U-%imJhL|^BE%WxU!u~E=x=URgbF0|>ZrvxCpAygB zb2CNXG`;40epZzU$6gelWG!UC4Xxw9pB?6a_$+;SE7o%~`Iute2n*hZ3Aglmv*D+^ z&Z+1fOjy(G-u_0N0SoO5`LproudkVH$Pgi+VYyDpbBcl!ytc3JVXir$&=l{?AizsX zU};@A3u+YSE}zAEu59ycUyQl?rrbuR*G?9c3-?|(jbg(>b6MIm%%|tI%z|zqkL}(r zb7ci`-I;`7o--HH!G7M7uU9_P;Y#6lBh#~7coMB`e5{Osx{M9#^2ozY^4qil;0RmzCH*kZ{>YW~$Gmf% zD->tb$%Gg0#g{P9U&?nCdB@075FI8pvT|7}!0k_bpB1@KcBgV~G7~vQ~$4?EFaL{M-}1V4;J2>w8G^K-^^(NG=mUmw|QQk8%_mkR{={ zvSg7L>dfrPjg_D3*l_BD(VAMU^9oJF@HzbX1rrgAhma3>wne4;b&+siwUtPE3v@RF6OR8z!?ImG_ z!R9sJ29iL)?9GLa7aZ8eqb_dgN)Ul6cE z@O4NZ>e!7PF7be$pL?>$@i5MRtbNTg(Pey-L^00 zb-*zaR+HX7udoi;!G6#AP=Crik{bij$M1i1tDiwG&RW$_!;3z?C3H`drv~cMka3j} z=DRI*n>;g-pGO0YuF^1fTv}(N714zLzBKvV$pAL&>=<~|BtwIPu`f-&x5q#%cW0N- zH7=AdyV>_ghk~MY#V1LE4t5c5BoolD*EaVQ4NVYmMn&A*4C}fq->q^z@>pj_)N`$J z0*o&{77SLPK-fU(t`GKQRC${x8@bE#)PlX*c`P`_3O?e7`oI6`+Fh^T5g`1v;Ov5L z$S1Vem1bUS@f?*oMbh2W1Vk#7(_fh%7iPCcHes27?3o*G-7%W z<{(;FvR4uQ`|i_0VJ`;QpWnvS+QES!k*d=HSQq=VUbQsL3u=1fvt;Vniqv)h5|PUXg*!`QD_|n zaIgG(58n4x_Ciy;?Ih$nUYnIFVu4+JBG}+Lt+{0sk2eAD*X1?DA%9vwUCcO+KGpnN zf@gID0UuZy{tIJSaOf=0$wt)Y+7*36_g@n5xcd2i9pqS9&(}RMmw zV|dI^Hw?BL34TT0*!gK^0~4RmSCn{Q^*si>{_6JQe0~~qn8}Im(&j(}?;b%udgr!z;@@J5vC*s*58yQ`>`)cOVoeeRUtv=^nWa`2Nc|>zI%Ee^2w>f;~Rr6r$gZ6 zmlZDMbWnMDF4ha{(^#ue)rom_{gy0?dB-TIy6T*lg!`g1m>)Re!~p5)vTw1uX)t%E za+0lux%F+lyv>Pp2;I7UeIM#@Qcz% zoR+d5DPZyTeClfCPu_zteH?kqGH%?pdnN^j^Jm{LR_DUem)eT&dq`NC=Wm=mmIRS= zVMNO-#kPHlvHIt-=n z*_bd)ht<;Bs;%fp0@vflmf5F+#v1Q4aXoYhj%+KPvf={MeSgNTv+2;DdhH`IK!=8x z5EqQk+0{LNRi`Ztj;$PbeZD*v91m&Fyufp+v%aie%0~m1N{GShukpYyGVXB_`##*A z`7?rt2H%&f^JX-}L&1n`IS2F3#0&AVQQY^U%cqvO;r@1x-gzH|`)eU>&p*b?1k&Wg zEp1;0%>UH#-0UE7^~%16ZjuSlY?pZaLf-Cpc`d{B7zcJwbe`@9ak*Ud+N zUDh4pLX~LvGNJiQ@O|xN_T?x8!p9r}%=9^+DEunJZ$NOdh+wu zYZVp!beNnNKBe@L4hNbImUv(tJUe3`ZqPv16<%4b@7$eq=CtC zr^j9~v5?-vFUWG`0$!T;_KoCu07+xuRFJ7b(f&e{<=ZqAa~9G((&YO4I7@1 z2!|BhC7|W|m&y7vCVYzg>bn>Bk>5y0pAYqD{N~Q%S99nPrI>HzjdlL@;4kfZC35NU zse_^)QlREkHmA~@3(qq{U2OFz`1Nv`^x^&#u-+ZLfHc58O%`&o$RD?OelCaIsVgfbt)9`M9<^di~Hr^ z{M0vx3A64SyRV$4gJr2aZzJ-sNNK;GKIR>ZiO&TYQmHVOa&yibb_i3Tgv)Yg9zh=rqNvIU>qxIk>(F0-&S8LA{*=Xux1Kvw_EzJ3ob*bJr4FJNN+ zT6KC^U~m$IA88abt>OSDYERNRArcb5h<|*Tf_iZF>2^QV;m~=-A1-zxpZm-;l%hWW zY_OX7gP%J@o}M_EM!G;tX{U}NK=56%T|JpX)yy<`(Sm{%I1Nm*k zWXW8w1`W~}voWE11Zc%PAx%)9ng1C&EvOmOo6OY#$`X{`p286Kbky+eMm=0O6y7TNOR&v7ou#T^oT_L~8dO5vyegfSrX z@=rCo4hIUvYu9b6C*Y1j=N6uD3jEU_J_$zt-+V`zYf(XhP*1nb!{#J#v)J8`RKNkX zx!25vJ4xs_IriC@V!?GEF^Q*`r~dOY`aXm|U-BkaY95|vC2y^FN*M?4E)3Zg{$D!W zeX~_VBcBedJSW`aP?w_U{O98EJ{KL5$(BSq96Nd`wdMpDKE$<7(9F}}>M6bP%04={ zm@KZ{f_s|9$jYDGN$u%5J&osUUguBR`=;={dd@)%s$~#cZ!1BQI2ZT=-1pc zi}i%jNA!*D1v=zO@OX6h*0pR3j>gD}4Prgh#n+y>l23x;vZKuNlSvS@)cWve^x?x- zDQI3gmFPd60+!M#kuOl6cMa?KiLwaDX=J_GjeJ|%UFNV9>(-t&U99I%f?lP_=CRil zRMnHdXo4`tN(L=@g$>?2BM$e03n|>J^y*iJxsu$UNWDo{o8KBj2Rp@wZI)oN3

f^oo%;MyRh+ks;)#)$N+gu8QB`Vz@xB$V9Ir;2Pe zQ+k;Y<1eHUgnb0@J%NEoF`p|+OT_q5Q0?}`v=DvvV8%}k0(FD&OL%i!00pWaMXSUA zeeW;PZv;f`777AnUU2ycG2JeKq4kDq18A51UQOxnTZUv#sU~?xTO#e7-6( z3clM)JGeEcK*;9m8+piM5giHImLCa_wtF!z33Jmo#>#9F^v&4LV(F8C_#C+~&fGN? z2)e7%tU}qan_sy-@+$$C^Rg4(V7=|le7)A;UMQS@teap(fimBwZ8Xf$_D_E;+4avK zUnXVkJWGM${r%3;$n$mz8us_FKH(n{HAor(E>cO3{fj9$X{q~N1o=GSLi|?K4+Olm zcT~&0K!KlBw=RL_nb$R6@9TaNDy|fNzKeRYPSrx<3g&uO3%^Uln`oeaIxNg*EdfmX zr+l)=)#D#qope#J*k{)M7l?KH5g_0ZgmvrtJD6D!NojT9_ta~X?lLC#s)C3fE#|7|1uTYM@7giA8ESYb}N^U;rba*77c8^rGG zIwgQ0Lp)y${ZY|C|Gmfy0$wc8S)3lgg78wa=y_QG%RY}|if@zfT6;`)Mj{#fJWJPn z%EFu#pzTqJIy^mB8sKlv0!^-=)ochGE~&dq*csBGi8!PXXcG&AKb+^j;Jwm*-#@g+ zoCF6hn|U97N-iSq_d}e|w{=%8{8~f8{42qMuD6g+56@R{#Qb~O#iGd5fP^Do9Deho zZvQD-tu%`|@Nxpux-JoLU{o#n`3juhTY?WiVXho%IN7>m9u0=iZHbTs%u|y1+2tDXO@UpN(XiY$9nFsDmyzA~1v0e$m~<%D@C1zRn)RtuwU?~tf`k`X~b zah7?e8s_C{$!|U?xbKJGEvWjAdPqweP>POb0e|8)&s;oz;>ngbCV2h=PfK3END2b& zsoozm&%Y)GUYpwwo4tp{y z*I*9y`(U_UU@`@Y$d2)2m>;jLACm1y{i#nk610<`VAcHUFC_Y1@refqE+B_+XCj7Y zJ6T|3P~E@Vn+*d4krz5V2{?8|>%IN}6Lu81FfwsYR+1I5(K47dzPT#azf2r6lNpe6`r+*6!Cp zfmvp@Oy6({+%Jo7J&n40bk)1#N4Ma-h0GT`(?Y@B$?%lyGB$*NOkbCbeSgGbv3z`j z32#cy3u|GW)zTN)?zJM})LSRt3W9<}pL_aZc&}Tw+boP`3FH{l3fDRo82%U)YW876 zg!`Afk6H*w^Zd~{fH|cgNAXHJa?y^8v4~?9sPo5;Ik>c^z=sNjR4ZLBe6xA`?4c7A zRQ9PBo%+gvL7;u=P)BZ;y|lz32j|B~Huqac5^%n*QmlA|`FB#$=p=^;?7t^Ygon|g zI!KR>LH=iWrW{;y}eJ`i)CJp1K;?U;iv_|6NT!~62=8CE8rkE|JFmQu z;e~w8xH~0A@?rA_tn9qFV@IOy01k1S2>p znPu~4v0vRorlc0~ztY$3Uh0^;iwz?0|NA?ii{00zEk+37`}SJkDEi~!(sJfI+zXc8 zf2&>_QgEnO#X`cD4&&JoVtlq-7!}*FJJc;55;nEWFMUr3&qbfix{)&#B^w%+<`YmS zpdYvD4HJAFbbqvAeID8_?n#zK-9GJIYWVmwS!p3)ho2Srsw4ao^`r~^z zjK&h=wA#&GtG;1BO3PH&??m5h*FGS2@-!FPA8oODUP1tm`r}VL=`2t)7zI1fVoPuW(OU&LGV zTQ9m|eM}C1+kwwnpKw0%WjzVg1M<37FOtBT^$N|uj%-?Rl~@iyKYw-4&c2Geu<%n zd?#StRsEkEF&FeY-rAp!KKR}3N=|162{gqcV;xe-knhUg>#s6tJBVP+PT=3w_4Qj4zu=Xmg~CO9mlV=j?k!;Jq{gzgAS26JW4>;TjLj zO;a|L<~qoM1J)%&@*xE5KDBT{<~tLv9L+NR_jl~tFAqvfPQhqJV-?-8*^iQ(T^uzlHgLP*6gZ64g`4C4QnQ# zoIT`eKXK(K#+(F#8B`0n52Iw#=Q5BPf+_Lw`59Z|#0s>R6W_4$>!1KPv=r`og zGwWXn3hFYULri2@xd$EQjzuMuqfV~u-Zz<>MS_3I+l#iC%ccU8xmq}fLG$I6UOyus zgg!Np`d>P%_Z1mybYO#+NkPc`E(Uzx=$LrKo&j+m+Q$#?3MIpI zSaW6mF8T9ZxITA>R(O>J1r3+}=fx~IX-IakF)xb=I_dzBQ2T+s=|e09+uAqmYewIE zx8zXBbS(knQCV$SNfc;V^*uJidHC;ItWN~`Y{~J}AG)xQ_bqL z{9+@CJSOD#>V78HS)8s@acCHj3O>CFy_D6ge~K+%MCuUvN*quL@}LWP=y| z^yVF_NyrIX)hhfLbI^15Q*x-EqZ1E828@{?IhvS84`9Fxc}E@hL)b_8&u=O*=iWXS zJ!)M;hZR=@qeIXa915gQe?cEr+H`T;yPFQbCTiujp1`_kStbf~5n$VRxT{Nvf+X>R z!2QV8heAcAi)@i6j)XlE#9aKV&EHl9eRG40mC?ss68bJV989cC0?O;R@D|KR@dx@G zMrRptT{Y~m#8C#^-}lF2#FzuWb!YR_Fee^3y`5gBOhNeIx|mJK=cd~WoQE)1Qubka zA;__MwqxTCk!)CgHoHIjBmu8I@8sQ`VZ!=lXEypG2R_=-AbC}sgoRc8FS=P2e7fW! z;Er|3o*M2LR-{45#SJfvGkIkIG;C2&q~u<>5v`!ap$2TI{4Nu)jx;mNaSzbyN-z&?wQrDP6!1-`aXg2P3;H1;5{Twz#k$cwr;PYiJ@cop+ddt7^p3SRa zLyflVW{;yZkQ=_^YtSAGMscq%HskZ}=|3|>9@CI{@!cKw!dlGWwUQ(5 z-I_L`o#Lqwov&SRUXu$6Ns+rA+fd+e#C-RMDmpApq*DtqN6YS*-QO}8w%HwZb(3lOn3yh!epo6Q8q9*fUL~Vv(AP{x zvYv$EoWJ{BG@+Ehf_r<0t(A}u$Knj~_uxIR_S}{Tj-`Y1$E13XV_awwD#+x=`N>dh z$uRV0!PYSQ-~;&cBH!w~xL*h$1~tacMX}(UZlU}U^pTV*vA{+i5*{wx?r;(H&HjLZ zfhp#)Eeg_k8KVRwXw-gX{$j!GS%rDF*V!Ptn_0FVb%tkKfz;MB>99(8>E%*)+`Gze zB@Rv$405h`8P87zwXJ_I>mg^FFH%`jXPpjSUFKT{3hA(R(e&tZ^rMQ1+l|C;0%nsN z9xuoHZqV_Yl|kPRJNWngXTNk9zwK=M3pwPy!;yLS&vGGJ`>^uRbpqDE3@w(#JRW*x z_D2AozrbkspEFBH=$(%HaovptC+kD(?4bCc!JyO6>GX6E4)9p%S{D+54 zK(Tk3&8c@x;HzEez7hH4RPqe5@C*TaemsB3i#pHRy7HVM&ga0LH^=|@(m*kRTD|8; zEYLFpY}Yt(Vep~pi%^^gwJgdj?idRuV~h>H;Jj^bIrKm>;Gs+68e|f{%D6n>=bR$z2r&(kd)?D>Gi+dk=ZOHdXYJCHmd&@*T6D|9-!^as1!+>{oRq9)uyE=)Rp< za9k%G4xzn5;qdcOVeQ@6pGgnHRW3u-U1K=*NB zks0>aHqpOF0`({FYJvWJoWtKWSq5#GBU0r)M%t-UaOG9Qop zgSnV%m=cTk&Di)LZ$g5Eq2S|IzFO&^IcOG@i288KeP?1@5EBZuYRu$sF`z)?qv8(} z4p;@UPG1(q`WcOjM^~T7n%O5+(5)61hRR`nq86ffaq_LVN2L?Ek+rA8u z;8Q$v=v;jg@S2piPnX~vZcDNi-9f;gM~ZvQL}@V4{lI)~t{o0X9GAN`kA!)%e*>d2 zcMM(MU?Pii9sK|L`_y3D}O zlgd|mnyM2J9(?z`K@|(wI_+hE`Y_P^NlM<8fP<-v_821PhDW4`EosF%*T2}6OJUwI z(3`t+BnhGg1U{{K!+{%`F?#a?Xb>zI_1O?LQ6O%lvq_0lVEvY_&E$d3oOFWPhO zw48hhh@Gm?jl^8?X~xy<8S=x+kBfB%FyDq{J8=0GQsD~SFWF)b7rcW;Y%@{_*n0Zd z=d;2TT(hf6i~09G`?EWY9hS&lXL4F?o>Fl7l)$pMDmD~vzbcpJ{f|!`i)|QS!X?hq zA{WeqRS7b`>f8uea;vAs5Bup>EGfDf^C|E4H*bhE64D%P>H{w(fpE&yJnc#jL}-RM z-a}s#dF3JMbb=N|E1_C z`bcnc8=L)%2IS?8?;&wX@FF}c^DFM}JAGc&9wrHV$_7Tx#YwQXWRJ)Ia#YTLYxKK# zQh<@jX|UBHAeWdmb9Lkb^K`3}P&xzjBFc`3_@;q!NU+T_oKMSWtC(FPOlUt|Ww}v@ z0edeeT`N@Kz`^0889oizms`D77IEpYwc%#ciHmFyzQeOHB8PYFtGD`CUEH#5Uu zEJ#>Xn|Nrlk^<{<8@4!Ozbdi@jNFY-zw%X-<6kmBvF+6Wj~)kTrY{d(^&+8Dd3Sx_ zT^0(CmZr+mYdb6 zld%1SP4gD?Wm%bF^9l63#Zrr2>_@)eeW}9LcP0fE_1dM?=%LTDMl$OUFyXn@g<&31 z2FPi2SIc3Yqm??;vxfR#E@CjOWkaUA48CWcg4FB;?$??4a;>L{1l&KZ-R{uD1ZSNDClQ>Vl!Ma-qF7Jw z!r)zxpRr)4pJez^)K8v%A$_+e$O+zi8GqJLpsH#zWs01cdh?mO1nP|1gy-c=m}kq? z)IUXI-Im2Y+vJl;z(C((Ic==7x~1^x#s9uv6WJUz{W2M}?JicFy%P@#k*^H4V%?VW zZR9RyOE`a}@gZ+~DlL-#3y!}{wH!b6L_G3RtAi5Fv?P0PnM zbPTv4ovxe|tw=)L(huQlGAKygV|cb5d6n{CRk)c(!ZW?Ky{yMcP}w!D*H_Mg9p_f> zReM2zp11{%Q703gz8uo=#y#y)I&9LJ@2-863voGCd=|Jz@4r6! zZ@drl$JUGvBL^};y6$AC z9zVc=%|BaS3bZ7HTDCw{ZA%OYejX*w-MJ9(-EedIBLeJyF-Dbpm>`ulqHyV-E)AyT z+A)$q^v0Fwd)W`++H-4%6{omhTD=|)l#@_CwfgJ9@FbYpuMUFDZC1zo@dlA_XYf%NzVqXCha2Iy~M$f~v@5bxy}4-RN+$a9(j9JJnu=(kb^HDY z{zY-{%-H15In*WNecJ}hE|Sobo6GwEdA>O@<8mzW;a3ki<$K8lNJXEnmg{Fhl>2MG z7<{kfSNY{5S15Su++qFkO$wAO>>hA9#08fRREN%60-_aC?lVhSApCyo@lqc)Y~25X zIqx6^vmovh$WDQK_dYcEAP;BvW{jHfGT{tt=PUJNzF6a$zke;tXfeGiQ^7c47yuQ?z(2nQNm+U`a zRf~C#Ua-u6I0Zg`UUVhP2={BO|9pZB3F1nUI*C~<_^wh}^)ClWxh|YkSwVuec7w=M z%z1oIa?`f``}=(Jl$|}d2}o;HysO7c0d?x*DT5B2&!47up4AY*&-q;~H^BrRsn~Nq z$UjWw?Qi~~pN4j4UHc-I4(xUL56@z5svaDgs5pjtJ5y+IhQWek$2Zarpx(YL4gGpg zg@lh%wYmmRSa8zyiREeR7c0AFmnP;Tjo+qXDaft0sST^;ao$87?Zmc*63{TSDra9U z6W(np@7>#{w3p1s+iNQ60D@6A{Y?<`K-du%?vR4altV| zfdkxMw#u!j!wL^at(ZeuR~aC2T4JAi}{b@lBUz7!lPR(rb`^O0lCVxRZX zG%))U%YRprfF_N=4K$o{<>%{r7d$1Q`i#y2XSF0)moPp826f{)U#k?YR+_jddqLtRq8+O&Kx1)uw zLFZBkJ>+56#-F>3k=wibpO`o}V7@m0(Nlx{Rk<8vWPXf-&X;S;+OQ5ac2<6w+Fba~ zbke%`m4x*o7q0w4F1o0eKM_#PftMTm+e>iX7A{Fx&n!uY`0O1`P3O_~2eaGO*OG9J z@@Ww;O9G8eVkyaW9N=BAw(?Ov0X3z+>;e{2@H&1Z=sV7#Rcr6L(0b%asf6Vg!z>_q zSy7$1?-msc8U;{)7`?=*RoM4yE#EHv`@31Wg4)T>G6D{R+Mi%?3jC%yhs1Gy%%|A7 z2SW(Zc{yhP=`#~NPA!g6M<1CL`r4S&!hlT{f9B?EF<`#S=U-B|?_x#2Pu)L4LXpAj zhkdA5pDVa->rltm3jMNIK;O(;aP*`LhY1!v#)r#LpL?`thVMRLz%IqvH*eJ#@Hn;A zsdEB|0cdB_$$T31vwodqqjIgck8kh+#7G%phyBmo2i#G?OKX zRF;w@k?nWpx_<9}uUyZ3pYuKEzCX8l7R+~>{fWO=2hAH|ZW~ZH+B?LYcLkAP7B%F0 z1ZY~i^8I3`8yIl^V~t-u z*8gWyt3>@u3iM8VG75_&A#UgU*j1+kpHQ zMP6^Kx1j))mDx5gl?gZKPY?61TNc_TW0~DRK(^eW)9a;4pw}h8+J<^kVIgX*b)EzX z#+RF^t%;EDsF*c=hzs&kud^l&5umT}Z$$DA6O3(-FIkK89_+WyT=N_S-t9_T?uh(D z3%8eTME*&ez5S@ilR*B=j^}YK-8giQ59S*4^Y-6VZ{z2#n~|TYW5TWxf9Iw<=(A!c z=!7H{$^#y!E+31Azi(5t+;M+juD4DU;!?o4&gPBH>UdDF{w%81$bs17qp!Uw6fk-b zlgklJfcvc%)5|k4=Sm9LX<|Kp4F_CbaF>LH!#DC9k@xr*7n__P5%7BdJEb?+pLz{G z%=x&UePI(C-avs&ZF?JPAPHZH8WRKLgv-HYI*F)<-3=iNZvSDxHVP|G6#eVNh_l6V z?*|iAOwtw|M7&Le;As!%MC9ZQsd#b2ZrtCL+H1@GNQfv}diEUF znWl0)B@**Kqdo1A|91u?*)PBK5_RCsX#6=XO$uCMSj(q9BO%)$vcngBxkUNfCNVP# zSey!!f6O3Z`tkbnN;pU9`wEtF(f8W}DwT|GlCbpQ&}0DmX%bARjvD$JSQHlg0abQtK4-S9(~11>Jl zzxtwXSC_}{6i|zY?`3xlD~oEk53(>Fu^Vx285(@0dzKK78kP>C^1DL=f7Nr2Ijh3mR{)g$#A!zGv=xpN0H8cr$vAjr+2?cqA%A zf&!Dw3#!UY5|%w(uOW>&dU@e&lVdIegf<^O^7SDdM%_|`mm6^4>61N%bJ*vZ-`{U< zE+^sFw@**>D%mj8ve+(6gaUl?Uz^@dWP(J8`G70Vk?O<#V@oa&@N{zZudv0~pX!%q zjIci&7f`C@3JFl)bF^<%Bw^sl_n*P2W7qy{?ca5T0!y0K9O7Iefjw#&n8CZR&A)D| z1?JX2Q*Sa%PO{*@=`)W9FXP-T99EoW5s-MuDZ6pgz%$(U&0SaR*Q!upQR0vD z6FApimn5pku|8UnUbgNJ=x|T)rJK~xWDqG;)R)10-5#(%yu6+OuTj^)$QA~C-Jg4B z?lT*<%0yZ{UWYn%yZFtTY9_2taFf$U-Ojysu*&5M6|x4z7l*n>!}^ui<5uE4uJZG| ze~ga;@vn_)btxoN+&8Ftj&t$Rq1b-{`DDvtwa5?8n9#CitM{59HfW^(-6)51)f?B- z8P`PvkqMu#&(X)fvY&YJa`b|ApEM6FBH{9juCipT+g()!yWKMc98Pk5d9Q^Dw3#$@ zFIGO9l1(R{ak~3Fcf*>5bHkBog}G2(`QL*25_fjGQAN z;IYKbz0XN_c~SU%Ebso=I~2`uDghB2ziqpK$G`GZ$m%|F)Vo5B5j73uw+qM5OrBsu zp~#t48ILe8|5>pn2Inq2$h2oiIRomw+73Hn-9GPYRnJc*fW>(qbZr|6mEOnydGoHX zzW%ShfmvXelEYF8bN~Osgx7zTWD}-|H1|G=sTsm8YART$B3J{ud?Duu-VjH zdk6O=IEteunM#K<&V+$iB^^$D)G<7)z=3B^Gecsq{*oJNj~pu`AzWC|P8a9S@8!2o zt6vkq>5Uj*%%HArlMwuh^*N)I*=yxR0Drwjs7(_C;-}4w)^(z899qz}68&=bIV+Lm z*+kg-C;vaXCKoQbcqaV5Pr&wtBevJs3}AUJFuaBPxL8El^i&(>*_MFk?`f!4@_$n+ zaGiTrdsS+$q=Med(ds=?aS(KV&t6G0F3eW>+U-X_wNj4mIq{qcx2yUr4x-;hmo4|G z93VjMpVg70ub7bU6n=6C<~~??-XVT31uA|?YVE-O96zkwznSMRUyC))qJMZDei`zr zga+FZL=E>LABKP5+igG)uqsJa$riafx$3QeG@e(_tE?4|&XCZ&DA=4{O@jm5H$VID zBo~y03Q9ks&W!E<8E{{mgbnTXPhGGNqim(!N;2u7)#D%Jsz!%p9Rll$nr=34*zeiNEoD*Sz@4AB=VJbWfP^jiG^IMde8MK`s=9SBM{bNrCGpZqBX9 zj)y^&Rr$Kb92i{NxHbuSuOw9M04t1y1vkT+{@`)^Pj~NbU=!f+H?Q>XBNDX7elJnS z{&_T^bc!G6mlGEqa0B`06Vq{r75@C>67eF@QxupmdOB?Qo(WIWAEohxuh}iA~3qIPCwL1tPm2F+ow!Y(5QjSmEX)O^Z|lqM8dlt;(2? zx-p=t8ujqk{rjt4`xCIq>y_GI7Xx-%zo7)7er7bztWiR}>bg{~c6%-Ah8|_!7}jlv zywBA}><4xB0ZyJ939~_;*8W3&DEww$a^oZFTP>j@)WrlJdXB{#oL^SkWagghEI2*c z>asV52LHa+`D!6Qr$#+J+1*74Wm<8j;Tk$jsE?%m+QWgvrCK&yeW;+7U|+8IFdE+c zX3Y*<<3h|v!yp|O7QD#H(Mx?#1IKcm)s~iAV5`~63>IR2C?R4tKjI-ZByAHEa$pH5 z*0~Mq{6=LFWorQmBj;;3i1NNSKV*IRqcR0L+F05LvCf@l9crCeXY%6-qafsjA%kA& z)?6mcO9`)CjqA@1Y?A4SN`T!587sYy#RBb2z=lF&F8tc2Es!9E$gGH^O zoRJv^Y!q(ox=#{Nf3UFZ*F7eDyK$%6iT4~fe(#Vwm_rRcn|GcqLhg#)A5O1e!-&7* zvMX30-N#o<4usQyt@$j@$C?X$M@)1^P>0)Y6l}V&kObRRk*5`Lu5%-lsvVK{;^gJM z<|VPA5>VRt zIF|#IE%yz6_dsKQB`+u!S*WZi3 z33zcfG|JPA2`A0!=-*L?=Xt!fGNhs3P0mZ|ME)$BpSE2U`IB9{^TG)FbxjP_Y&MF7 zE~_=im!l6R*|)cB$2_ZyC$~WgbI13cMIX?oTxU(5irpfCd~qRb@@patopka|K|S|b z^B{1AHwh=>X!&A8iEvEsXNQ>v7rJf+mmAno!D>FG-qjk{YZkS)+?@;a=l|kQOeY}i zcxCS0w@i><&91(Wd7-4}YD+%yu=mgNPpv|kFp{-qiw$x@MuFs96$95Znwg-AzL~r1 zR?b`t8_wA*Z5`M~0lg8kH&2i^HadyDdWwBMs1WNx!~PKp+mO?O`k?yheexFUAEk>O z4+op*!1S0N&J?GE^lQFbLoyr?W_X3l>XD$k`@!W!ku*p=Q{1J1b^dZQ;L7R`Gb{S)`*gt_zLG>}n72Y~kf&}{7=RyC| z=dcein47yN30@@xnK@$vxV{CJoCi2V;psA1a8q-E0} z^7YcZt@d2Ftz=aC-j@YGJ6ehtf1rW?BF#mec)mHCEq5DH5};13H2A-}vG8MT*_@sU z7urHTM!k+D;OYsFAkHraoIfDUcL;SmB#-)1Fr5Lm)jo_YoFlt`wl`?UTB8nNfj~kyaS$q#UEpPEAMgi)W z{_$yvdei}>2MJH&FptEJDE@#4OrV5so6E%d2=|s;);x-OD;M(U7W(oP^*x`4+u4wr zN_pLwh<(3Zp+QCxeK6)*x)t{AhGSdOe-zQ+z2V62g(5UqJn7-#eS`}pGYU6e2vEQ% z&9jYne}>tNP+sbLHZ-{(+Pxh8@%Y*;{BLS;UtBg?si8jm>prJf^1dfa&um@q*F1{(_P?{$5&9j8kU;x=^6617Ncd~M`i*rf(7sqNN@Iewgi0S3`+<9} zpNw+%P(FMkopPS$|&m!iWo>KmxNUF^O@JtM{F3*OcMQm-x*&`c77R zZqGZcf6}(g>JN92ptWQ4jI=uqmPsz$YKXeWda`4o*f9zeXua%RA;*F%eV=24-PvGm zdr9|JI|T&vW%t)zj0XvkRMD(T4t(EpEah1q0UGvae!&V7bk1p9OT>O?dwH}?(SZaF z?LedGFdF2%S9mCj{pohfjUk1cmU`fZn@Ru);tS@P@vf`qzL*WpWMKZP{4w(AQal{3 z@!>bD;=qChtl=L41e7H6)4p*T&@HmlP!+jLZK-3@gCqj#l%xXXrx~!BEz$k}_x;^( z>tGq=gk+^3W|HV5M`W87ig3P|S|HH82mNfc%~pa#gD}t-nnq6hBB6AygG+}U1=@}g zEIJ5twSE|@aDemcKlNAGw;e0~dv!aL2~~F&Ke&TDZ=&idCa{VE^*>Z+o$rzG(S13| zMGg^Pc63AQTLL0OO0RtsV}Zd3cF!(PHmv)=ywj3I0efpnV{_$rX#DYhdbELqeBiUz z!+-)W{wkMQ;9UH%q_?=#^7P8<-zm&}KNfZ?X(5N!=Ba$;Jx__XFi5)B9Ovgvy5lVN zn`X_Yqk8CrQH%DjR$oPeSb|lZToMh6`5ZQ9TX13J`(SHj+~0i*Tg)<=6Jf*MGc+sU zg7y3vuv$Wa#S@ltKFFC{@~p(YuphD&RiB$TGGL4KlLMw1G^nGPyxf4i5j5>X{47R} zRh-Psf5(LW73<1*_ZK{sY$=m!qr!$}C;jqs6v)~3x0B<@g+s!xM5i#_Lrqu@h4ObwfDx{%L- zp0STwvz{zy2=P3=AM?u{jiBH-D=vgqNSGXwqrkZxF1JQwnXuM`BB+M?P%hTyv<>@w zMS9r>Bb>kN;}M1dShpEl^Ns%uDIjZDp=Xf8gdQD7?GL#AW%3&9J023?`%7!R7w^8R zWB)y0i9VikMQ^^rO$z*S(ePUmgL%;P`Hp<#*xp-r%r4@-cPrdd)55yRuQ%!4h;@5w zrq1`Ri3;Lx51h0!$6VN&`p?pZ3wwlWCVBfs{D~S$S(pT4dmjAOQR6~_{k{+rSqcQ? zUA=9Id?;YtlN^gYcJ9-@$e{U5FuT&y9y*)|vBJeRS-8Jt(kz?Sc zf_cwRd;cOZGHgEu6zO}mUri=qev_8#MfBgh(+%5ostDL`?ea=FoC%L)=l!?nKJs=( zuSiP}3BST@v_^UpLF&IAr5WUenZXus6ZFlc4zBN#eMq1bBxldzJnnZJoBGNjz-iFA ztXGf(-{I`g-@NONbbMXpf)hYZ%xL}Gf%+;Y zGY*e$UtIrr*Ig>~th-DTtBeL)&Ba{WRW3LcYFGIpC%hYSe(~}H1GGaw7PdBIe;#_pg(4>Ba5)jmUDQM~+1HxCF_qFGJ{}QNm_ypg2$*+TbVt@RE{tgZaHrfLVSP{3+qo(l2o)CG zyNJ5C$8pJO?gs)c9yI-LGxESied@CRkRM1@m4+(xQx#=a69fCIvFNE8?|zDR!GbHa zx^ONAlzTR=B;jcCgPmKke*(PJ<-)AzFS3Y$^ zJuh?W{^)jzfaB%6Tx}~EptCG`M+Nc#zxzOwYbSD7tHjqqAN0o!H|GAKUY)!9%#V4H z0{K%RR|AvqbN~Nbvg03`e%sE{VX|*UaXddAmWynPDBs6{rB@P9?ZzA-{HCdDPdfvY zOJ48DKwiB&r6RC3hylj*1){@Qba?#uj7xzw2MiOYZwZ-F;KM${yQTHm&&1a$UcPuY zsJC1M^*Oy-z$R>tgzKLcKdOsj!{p#H57TA>?y+J6oJJYYX3}yt9(6l3xZ8=8#<}vk z-@VX^21j~7sr)#@1uOq^S>+uJ2)cM~OAGqci(Q2c?a2Ajb2?U=m8eilET8MY6$f8_ z*t^^~&4n;d-XN$pxSmfANatm1pecM|ty)?x+6{c{57iYo@ox5q;Ex{I|3@c61#7bO-U*O@gA zMn6hHu6uau!9MhH`*mspKTfbfGdJtkt8X;WjS*TGk9lg-AM^3X1K`>UfA5H-k@koRVSiHT>p5$?+mm}gRqbM5wl(xI8kgiAdF`n=~f28C`b z75+kiUQUg~ggq0MvHp{zhO;4jgP_~HCj@+-4iXPU|NZ-E?EFXULmBm-g=b`W&q)Zd zmW*b?_}%#b7GggLw{a>eVyF<$BROxR4#bjJb)Q0;f*IkEESsLcsN^ z^ggUl@Eh@+V?#Kne6C_f5hO$@x34L{c`PxN6%0tHgTQZ@&%eFsaP0Q?T-tsPT#ja& zn~o45x@l)*trzAOy^P+g4akRIn|sQyB0nf{zU4n8L37Mh`xojb87yBzwv%&*I@_L&yB&JZMs+=^^pa<=ajFz{K1il z9KKu4R9zV7@s{eXw{^-S6dTQd!h1e>$p&-!ZRDkg$J*~|ARoC@nI6l<_4j%Nl^MTF z0@6SFi{SPIP@iHb8XjhYX^3q{h6)8PoVr0dh7+_#!-HvNITBssw5#~kS9|S{3sYYw6ilSkLQwN3QuUrGWRbv!_P=NyzhP5V(iON&Nh`M{Xen zF7JDi9^l9VvB#(Og9{tHbdPUko5zD;N?gjwp%{qtfBATq4HxI8IinJ};h~V>adF=B zYQ*p6s=Q^x)%gW28_@53uO8}h`pSg4F$F@j{pyi`ymbl6UM$$V%Fol zIA=1-6dDG_bDXT?LlAD zG}LZO#oQ5{t-AWZn{2pOd40iDBmp7zVM;Ej$4h>w$FeamylPd+Q?h1(bi+p;UTIxsjR3s=+S!}@yzQ%>8 zNsFEY8<5bG*gSBWKM5|?EcRX4t7O&;=drG-;>P!UCKSzEtELmchORy4V1(zJ(igcR*_niI zt{sdS%zay*kycuh1bn)aX){^H1jW~WTY@mZtST|?TpmLJ^-``z?g-|LARkJQ5Bkw& zGJeX40!n|lhI>0maP8{?--wU3idy$&=}C4`1QJv;$+qmTUsloB7V_1!F(= zsfF?0Q}C^%EdF#U0cZG{s&tK+P`*#F+{`>89I;d~wo0I3XYcbyi-QfF*es`iw z%`W{D18#jh+cE4%11YOl`*hGB_0FBqzuiEBR@?_$6|^95oQ^vx~j zO!UqoFIEPQW!>sb1bfZKnXuhln4kYsH#iCXwQ*(kU>XfDTTMFmm8zt~>f?wB|j9I$Tdc^P(=^^UVw^G6ZAMZ@*r(3XaCPzOCf9 z*Y`aE^J{jc&YCm9d_eBmzc4nqZ}GB7UqZs!Bey7q{fXeN?kL_0c!Gw~Mu`rGQlS+Kg32Brso! zXoMptxc)U+#KfGXv3QgFa^y!!n$o%+^oy)THx0GNaNg;bYOz0=Q2E}GPaXSHbj+es z1bs6@q5bIgcO(?1umi`+kxLJz>m*(yAi`7fnNmFiT2zI$&_3b(4vop4FQC9rlak+i zgW@6Wzt(SssD}+-IwWHn2?)-A*~dYCJAOs{if$_#$`(04h(aE=T)AFd_5%|Pj`1lk z^JT-*m`xr79xQn9uslGvkp}*$SJ-{H@5NWSu0ARRT-fu(``KwGgg!~NEJR;^wej&T zfn?;dpLe=`NRTjIax(K1a(nM((L*bhC@@kIthEg})LZ02@h9ZTjru^vvD95Gf9RaLnw?f_jNbnka?&gZRME$uaKpp);KJ2B*wgpLGvc02b z*B&mM?IJd3VgLVhi@me}eP@%6pzYBhHWYZBkoLMrKx%tcA;*ykdt?Xfr!W^N3#Gi8 zz&W|zx$Xs>L4&x(%L+H0;KKNUe5tPy===TMT(=*4`C>8}Ohjy?gfLGTsFp%R zBL$Z9swHSXiwCaCvu8_6I53#>qip6l1@8S9V}29!ft~Nj^)ZJQpNekW$RuHZYAH1b^ViWB%MDH& zD6pzL>vG*CCbagio)qN${;~g-m-@0`Tv2U#2J#`FXyuR{_K%L#%Yc=)36PL@U9z6e z1g&u5@^aL3&+}2i%B2)|%x}itC>0NNw!RLjjT{J(ptr5PLjtEK!RoV~1I5If3VSRcsjdz4qFI7Gd0%-PeXrDI*{5 znXL#P!MqYvEazr|^%49xTe2>b0$#plW-gKOu*mGFLw-32j%w`eTfLKnA<;x-Hy;{w zv$Wnjpe{-Li#yL3O@%{Zi)ht-(I6PXD4|{E0=LihX#ZXkHf4I#r$cBkoo3+^VvIba zX{@m%lK_Rkt27TFhhJZ)e9-9u8&o7E0Ux*wgn)4w10K zOzu-@UPsgx1f6UcA3EuiC3>*Z!0NtE`Ar0-o`m2~3eAA#&c`jr=&j;*qxDdiew#-eTsHgU7ih zyKPrK>J|To9s7?m2~a&{G;)0n_H&~jOe4=rZwdL~1u52^F_S zZ^t~Q0TCduM&~3K)F;XW^6>K%o$@cdL_bm+ce?sij|+lFR?kljr9kcX#-AnENk|^5 z5s*V}uMfU29{r5~@07K4I&!a#u!vbRa+=zi2~`&6g@1Dyqp_V#Xh=@-Uxc}D;nI|@ ze=-!krDLkgEM2LPE@gXR|EFl!_(XB1 z9`;*#-NgJ5%$2sqpT(n*rxb_1ZO!obg{0 z;cm<=WlPkV$!Z1b!AL6XJtFM=DJ~ke$-lg`5cPJo=M#119_-JI)qdNqGC?N&DZT|ZMv0sFk`m-33@ zp)@O(-vxF4Zzo@+JwN*0Oz!T7i<3Zq=~2rya$M-LS){+LfB?dJl|a*L-u-2&U!*X9 zJ#6%^w{9f>R_BEWSu;VL52xwsfBl_uC-uK!yA71a=F^>ZA zFP1#GfH~LL(KMfT|C+>8xfB2FC~(gAYqoGQ6J#rhIBC>@zZDG^x{$+V+o>^!?;|HK z|8B#3UyN4r<+|=r5{5_mwiXU2g0Y!rODxv^Qzj>$wwVELLyupqyh?{tk_p@2@8dwT z;9e`yBq|)ZRM8nW8Vx7b82{nDcVn<$CT9iu*Xh&d2S-zoPr71^QmU~(yMM_obfSQ9 z_EvGbH%w@Mm|@Sm&U5qie_OVF!G6Bh7c`x~gokpc9eB^NS3jd%FDgidq{Z0{U*5&S zl~X>i8!%s6@6$-%L?=Kpd)zmB5#~6-rT!OCKPjiedh|3gA6{A~{JS<0_Wf4rSaOsL zD#zlAmB*2Xzjfs1VXn6xoLagb`*V+7;k$QxDBvrqz2f~V61v_B_xwSwt1EdsbP;p$ z)->0d3&<(otfQ~J#NU7LH-9i3`NXzV!JakDgv$qXuXiI~RhE9w;7$>s?Wb~8C5Qy) zt?RCo;+$?=i?eNmU5zJ+QeJ?F~CJ0D) zHK5RViwPRSLOm=dwfpMo?XB*!4YuN6`8=URW*3A0*7y*uN$Skatgss=AExs4zJsg6Gu| zyZ`#LF%rUaKL3#rNP@B}+i!^D9LYX8vNCER>fKel)&9P8kh$9!pQXyd`neVU)}X+y zdzPbam_J~<*a`>qFV=y`wl#_j_)l(8Yd3*8PqODhwE+hv9rYZR=n$}CZ_()xcP6NP z*!_{GZ?e8F@_8>v=&pF^@v)c&_hyXvb&!W!h>gF}IGA?^`sdHQcX|J@;r@<*E5n#CJPrt3_n?0bczQg@MBRveX{zV{ngPoN zkKCjM)1mmx%f%ngbHM+!Z0XAg7WkIY;>Fu(5EYu55O0or&Xm0z{z8Kh zX?s5pTP|$KQV^0FMO_tn*33A?gf|X-C(ItPf!X}ZO!yid-tiH8+sBe2YBE6dsT2o< zvj(2_R}wI~cWvs?R3>!ajWe}DU2?8??wOKJKvsRf(?&%S_#eCvT>pU$Uwlory1gJU z|Lo0UjbMLu-#Kf8`JI!ssx=$)h`jz4ruuRcuE#e}AE93Ptt>J;UW4oLx_#g$@4bf$ zmF0QQWAUx@59>9iz(ST!(^xVIlBR35-eDaKtrMST=un|#;|2fcp3$JarDn4f>VP22 zGAZ{21+w_EBF>_I_Axg6d>PD!vDVM24lx9*)HAcy`@?|w1$jvec-L=~oqQ2&OG2W- z;6Y`5zn$OvBp!DpD8&vcKl6tXkE)Lfjn(v~8^Yu$CFtKKmfF&8{_>W^wY3XmN z{E9zcD6S?m@tXiwL%~&3MkI(Wv!X{Jzlp{1(kyztQv zbvq*PLoOS2)$veIM+S5Z^2B;*?+?mAl zm1;bjde4RevTvX6OiO3NuXFRHt z{(bNEwdgGGzVpGdDSgxviod^0CxZ_8Gl?oAnsi|6eG|9e&4C|kwbzb5r^Ed63p1jl z$>6rPPe?$61N`dyR3wmBwTpA6?rx^QwHGpP$5GEy%7o401t?IeVbruAbJ<4Lk=u%x z7q0vpF;vBTB-5`k*7Ge9Is|ul|A!p1a`L~YbZ-jCNMyfIdB=qHeV%+H$fcgF-v(9; zmsZKy(i_El!JrfRuXrJqS$cFs1y_zdM2so?w%>Tw_5*7tpnRVg* zT0fqiE{RQm_osIbR~W`Zu!X5IKl-xV%FjEON>Cv089#qQJPCr7|6l@jg-*|V+YsjS^s+Vhdml2RTxb?|`IR?ZTHax7y z`C8E%nV^UIA5}jUD*ToSrtA#@RmjQq4il%6*qHCG*dDBzON4jr%XPEVxlpukT$mqy zDvmnwf`vIk+or{X_Z*>0BXti^9SThHJ%3uoWP<2~zr+Ok>H3rRHs8bk*V@Cg#+H+x@xtxntKJ(B_IzPp%8QY(TE~c4T4WTCAJ&x~}ojhxoZE z^XD~T&e}Bj=4}b;kAT;KpX-|l=wIf}Y(tLw-m~`KADmPE^D)jPSpPOXpG7g@On86c z=DsZKpM7nKPV(3%6KQf9Rj3cm^W3}R+SqV2-*fV%HuAxIXQQKIiSYKmM4b5^E-W23 z7d?gRD8A%oYVe*0`{fnR(l8f)Pj#c&Op%bjwEm~2P!im`vP^QH1{VqyM1=1kZ``eq zdR~A&@*=+_I2hO8PD{V!`GWwd7ftWmWJzeAyKis;`!i^b<=&bziIDZrk?&MI0cq5U z%{G|Fvp45<`Rt@Xz_Q>e@+}F6gtvQe%1~FwrW!vAFd#@*?}q0gI?PgRluM6sfO^$u z%eO27&J59nZhvI}%fV($A9WyvYkwqYBL#Z4J-=mfiUg_R;z3u`nPURmeLndR5No6O zPtb)4U*4wtutxtPg5DVawV=Sxjgq=4#h6RZEHv>%KBQL4ZKy;&-?H2#@}ve67JUCU zWP$rA`1{c2ie3WDEx3gET@oh4W)F+=a+bk0kLF`u5O(PZc1IxBAL=Gz66uu{=lg7+SWku=%Q%?}6=|J>=r z`Nx2a_H)PLv2JrCZdBnb1T-CQUAniQ0f#zI#5&`;sZ9Z5x2Z-e=Ghls!iJf==V9(Ol3#5~fExX|vv@B9lH5kFN8)<^ zo7bMz5I}{)SCxeh9wi_StW>-~$)r3ibV?9p8EH#mhga`T>2`dC!U3B-DB3 zWDWUdcM>+P(^UA~z=lUA7PF?PWA>JRrw+cyyjEXkEsJ^WeFJ?7@BUKj@JoA)`x1d+ zWBWi5`&Q^r&7md93_uDf=TD}=#>{0qZzI1+rZ2CT!#wpo#O&Mz=IG~9E0c@x`2KUc zrcM>e5xwmj_GL--u)Xu&F;9 zY_UE;_ZWGG*q>LG@`^4G5OBL!)pPVB=JdW}WzLOk_*gloSWrcQ9KzyBKP4W_{dVq> zDd)h`$xj*gkjL}_&A)_{V15}^y%15!2JT%(`blXD>^b+W=4UVyeA(++yyt$byYxnU zMKuMO!@-RflJO8M&{L@To&)L(!sdcp0zA5MRBZuYEL>7snEl{17d|c%*m>d^o@Z`H zx;`fnq|9IaFgN7F_=LUS=K$XO`!2P8!SmJP8~!Yf`LyEux2=zQv7Q2}^xrllLidH7 zVjtA)3tFjR{*Nf2vcM{9sxuyjejZ;_U&Mj244H``78L{sXMMw+pF!7(JlCA#Tv&7Y zfszL1vL;sLUC-+zEO)l*6U92)P8vD&wh-WV?67KL1QY5E1{Uk#d2KFYSw-fMaC6Z) zqfl-l9M0l@cMtcgWN)fx^J5CUeC4}@eVc^c(n>0J*q?GW^&S&eRA?Ii`j#&%4yGp4 zj)bD`)LJL(5L!b4^}w$E2cPkttF}xzrG|GM@5R|W$me++focI<&pcvGB@z2}$Cc8H zGKaC>0!1vxx=9H3>i3^CaG+?hB; zA*}PQ-(Mc)A?HNTO0lWPrNoUBcX-^@zpGfUOo9rIj|cjkN}|CcwJwEp<%00c_feWA z<^;>4k!nLaI3B2KanR$y&uBifAN}rV_{=p9@=VPIwW3_qy~-OMJCu-D&;LhGm(DTa zLvZMS0n0=Y3geescrn;-FO=st)h@pIh8~q%j9IDtu{`d&-2igUf%3qaJRl zyp_wgDoaivm z{DwioQ4UBxT9UI;lL8JdG|x#Y2?v*^JQS_wy|44%TSe6EgPn);D>0{BI5wBpg7fub zl}5nZ4-}BRx1puEDjxnx$b55t!+}mY$;aJ#6j-strj}92gvnXkb6nni1l5*Hss02Q z1UH>5t!?JS6?TJ;GEBBkzc<)2(F=LF2xRH>% zoo%d*a~JQYlz+MqebCW9Ls>KdWYY7<;am z7-jQ{fNi!JRpX-!5Su%?s0;PnQ>kG|8Tyw_=a!(m(+rT_AKUx_dC6$6jbTJ7739); zBetIwy5L%p||R=wCx-7p}2_(8uln&9z2T;BnI7lk!^eP&HZ8 z&#C7?s)_j3b3v%LL$Rs4*e6lx^CKm(Z%y)~rYjN&IDDu{fsOn&zFKvQH}+xc;UG)W z8|$OBxygGg34guSg+3zRI_7DPM~G6OcwXU^6Ih2~&g8Ka^l{%~Lyr3~uNB?*A$>u@pC9)VV6^I7-=JmrW zPH`djTSnd>>h`WzEgFAcV?QhDEOkbnx!JjUmysn4)+${x78$0&vC>+5E6lC8UIz@% zN3OGAMDr{1-ea?Fx412ym+!BJa~XDY*x@U|A6S$O1!bUWBF}*j>-JY{QlP@cKOf&e zcaDO&bEoSQkdw1NnD`o@cT++- zMX1ob<8}C3%Qz6!`!72eePnZmMsjr=`uC&#C(|~fep2;m8o2(refj%2s54iR!=+j4 zNf62`_w{OF!$a^lUzvmzn0#zjRCKhZVUxqIZc&zi@&vwz_#w_?fwBqO5t8CcRv-NoO zAOlu?Vnn%R(BQoBuKNPGFSc1Cl>BG{H1oKt5*L$D@U_f__k2k0s;l`7Tt8j@W7vrp zCS;aA+xh@?L%frwqTfY_$+eePHVZQ#LBaOW7OcOv=ZTB9aV#+Cv-n}tNP|1qt7AK{ z&IuX5?tBF1Dcu!c4}4-k5p8!M?|o`q+KF;!uDvb+R`pys_dJ~ghm9AhZ^L;XbsmU_tR-PzQjXdL_RnourJ4~L63)t;i{D>F zgL!Kgt#LYxKJvjLPi7Yh?so<6>Mlrvx6=zuCsCKY|6610@RI;O{yoYwAtc<*cHA9@ zepeG{`D7@TfIMHn4x<(ZP*#b`g@0y4a>{-8=bi+3$NgIK4>>dUO{nk(;b)S@CNO-;2B=sb6$g>iUj?4r))DFoX>(!z| z(B@Miwi+DRydpG*f%;}==9uI4g8^6LoB(e?kiVPFvEQ;ghUUFRpK?F?P@wBqBK#KZ zjdey|a^WAo{V5XnT~1)ZKM4|!3|QShk8?V2MRzCf{;cA+M2o~E1N`GkSGpn3R~NLc zN^!*8QTltAf;b6J&%%{As_MHtFrA@-sTFd=fOsu zyqmoD*a$y6ivH65X-ekk69QImiVh1HV1QHok=o^W{OkGOtK54b*Y|FH3IbbO#HUdwmwY)DbvBiNjmaG~ zS1}(+E^Z=Z(ZBd^#OTx@zkO{9F0f@GZ^{pZkl2UfFWUqT7Z4!2q-r3np9%lTc2Sdj z*&y;X;`tEzglnq)z`hC^JR4A$_v$PcCRYu+a-~rB9W%8(U(;aj_NT3HjJOc^@rxeQ z1?TI6s!k2&*1*%%RtK=(IBL;?{FuM=QwtX=vzf4b=dIAyH;}hw?UY0|QDJP~-D8Tf z1nB3??ef2hzPWI*rb004m4SujKRFWg{pC~qP*=Cj+#_ouNTBW6Wufvj5#&PZl#GB2 zF>5>dE$`tzM(eI}Vl%+4NZb1^er{nj`*I`l!;xz~2F_m?(7)_Vl^_0`Z)x=_?UfWb z>t38(ZAZeD?pe1k-upz17xg=14&rPoP~3#`*yJyJy(AG3&N@#Z=TT+Whe@m5R#YW!e6I~()Sq8CA)wk(L% zHqBFxqd}qc*bcjMy!V%R6dov{z@@Kd)gvkKptem(byXP$mc@?opWIBsj{U6t@7!rH zbU*r{l?~>gX{pKG$qDeJ?d*ZO*P=mO?^ww-FD~f!jk??BAy4LTj~qfifA)F1^I_bV z*lo1n9k+Pz*ZW;loI{5NcD;9&;yhORr|p@+9QW#${l6z(@zAa|vw2B12V(YHyQ{Au zVYKi0`IzoR2(O72G*iVK)O%B~_c#SawG9nwkPkQ6g-L%vKHL^-xLzIeb*l2sBjL+P zxW{+ccrWk%?x$CeTj2jwHU3b2yl8N-$s*%3_FLX`me3gLwz{{oqSI#vc*;lp3q($v za2*>IdCP#N=1al#t~5wZTdXmOJm22bRQ$e>3O-Gm&aFiR+)w`8J^wNnygX|A9MPw) zueDy&dmeq?XrlMxeKx41FQ0V8d0(M2?DWtDb;H)Pl=t519>Q5k1ox2X$l4 z)r;fg$%3U78960?Xt1Ycl>a#HqxHr>(^j z#}S>jc(}nP$`cAWAb2+H(xPP)7#mu7XCeV}S?n#Jcf9vCyu3V;C(D34?VF3X{!WHx zCV{oKv{sd&wYxgoJk;GnY}H?G9(;@?#z}I&dfT_r@lHL(;yZUpLozQ#G%3C zAo~t?+^;1RpBzuj3r7{zOqFpzr}9IuZ$}^blt zPyZ^W$Aw4!c~cRBm^(Tb^rT}y>->+UGmnSrkNP<6q=iyHX;E3Cvb9NZ5-L*Jl`Tt> zHl!#ayM*lS%{mO`4p~ap3JDbo(Tsh`79mTEP(5d!=ke#f=5^=Z^F8PDd4FcE`wf4j zy%_sB+&N+BvJ45k&rOXF$KzZJ1(`(S>x;)@-uWM3z*_lrE*c%_P*g6lOBi{taPVJ^ z&neWktfQavH>4n69)C2X!Ulr_|0!O;eqE=2>&DL-22>j@emjDCb$h(|R50rH;-!2) zKfPr__}96quO7{?Ing9XKa+&*;iExZafzUt;H-1CiUqgyR#vUXdTRS>{Amtg!eQC2 z8f9D;#|skhC`0n|1TdG zXzHKI0RG)^RWiu)CV4wqZ*d;uH)`C=LZ1J6h|zHz^PS$=*9}LpZ%5?%EqplN(@OG* zYu=$iMD*7c&i&yQ3ENkmt;HPl+D|hrjR~v|SD!z^{4#DZ=d%s-;~mB0k1bs>ufdmR zn=z-@SG^Q1K!1AEcf-(uSf#jQxC@5i&zjpchcm`eiBNSr#@a(!UPHP5)D4@W|00@ek7~FuaTi6eVrIiXFaNUCgj++r%Nyt*PwA5{7!U5rB;+FTC!S>~k z7XMhx%dR`G=^ajlJ??K?H`cIVxPG&&yfX>I;|-;*fykMezc+FF8AHPen!(k=Vj}T($fhrQ<7fx1@qb+|0i!LCIiwhine*@)8TaMpX2wD_gtjX z3q_8TFq32~!;7DL;JeafHS&MokNCo*Z6v%&+x0B-DihBCxFcDK{kbFX$==fNbeJ@1 zZVhNp137lej(vMrAdueaYgv&F^GlXI__`t;^pA`#CY4wavUGgqKIGU$QKjpSbmaDR zM;>vWuX0D~M$=Of5+thUwC%BPSFh;Ym5SGUX8SUesxa)&lN0L>4>3TZtLol!oL^(f zm?o!16pa5Vby<->2l1t@N7tCM;n?|~<@N0Z1hi5AR%bFndaCwE6VB-lt<)n1(*(?Z zZX8IqWy0*~(A2ehEIvvS`wDvDtGB}S% zxU%gI+@ryg-#c|9yJO(c*Y67iP*=B0e0R9;0CSdZP;W;Y1FDwKeR0C;x+qzG&t-iw z)ciUSf61GGgE?zvbM4r$m+R-T+Y%%k(!1ZDLgKoZ?R;K}>s#$^F3vMTfSA26HHo?; zu5N7?iPxLCV#SYJ3n+;H&XbeoM~Cs=7uJ{0AWzDRSo&Td!J#f~uMPTgEpJ0gHR{r* zf0LTRuSw|AoNPScmk8w!FYOB7u%OklEn+h*1r!S7Sk7H^@Y#JJe?prDlj8Y1-dWK= zKO%4U7T0)4r%lIXW3G=gxT|iA`nlV?kEl4zgk2w2x<8I=26rLDCs)>!a5=MMqvBmA zC~a-ZuElvQUZa;m7bQVvLmErl!Q-BnT87jDDYx@3gSFRH*EIJ{M9`) zxV&Mj(mL&U2-DGgdJy~n*WEQY=CTQx>Hf)>7p1^GQlM{VOEUyjTzl*wOTulvz&c-? zqjNl=DxBxps(as!f5q8Xag2M)C4mVgrk(%%FrSJj)ef(x7_e+-N$RQqtWVI+JiSw> z4|P1=&MwF~#TDMC8X3^cHeCD@*H`|1{gyY#hvk&>+obm|hF`RRcPQEPEnYGqN z{a!|FQ2V`3J?a$!1L6tRoyHW1N4O~0A}2HN->Z(p`I0=bps50NKE&69+>AQ&z1G!H z3OV0#JSp4u1rw^cRv(W>K0p2J;DtNrUz??vr*`C0u)!uczzcQQYL86LkOcv1f0cQq zpJJa=o=c@s|A#bMZB!4_z)HaU%)0&9`zN!80 zZU#^1rh`#F1SrWA4m(J2p2K5us2X+bOmtYXDEgyb=YJNz(I2f6rK{ee-k!d%^RYB??<3EogC7zJ$ajsB^6g;2 z=GsqVocremHaE+5f2V-l+^*XAHyQ5yH>E75#DXLR(?(Y>k1mszLI6VFldCJq(+7v z!1~w2m>U$vBu-jjKlko4dF+Jz@IKJ=g8N1a`a<*dj^R4Smib<-$Nm@GfA;5hZzgyM zGuk%bbuAsC9M?EeP%gP*AoFW7NIZ-?ntzJ(JCt_3Mm7Z#r*{S3{+0~q4VQ>+K|c-9 zxHcbjoCboX?NXPOSOo+7LyKseaSx5SQ_*` z;s!Nj_-kd2^QzdN^^<4F)1yqduT}TsFXo+!%)Le38o?rLb$h^YysrP zz{9M>uh~2lSSjDh(!|fL9sC_OA&6X39P^^6lnyZ|vF9gIS9i&ajHnbb;OceS$@LL* z=v4Fk+p5h5a#iHj>@=LO(G~+$aSDiv1v}sq_Gi`AhZCw4>R;>h^GrGf@3G9LokQM` zEl{mhN4^?3-CG~bguNFJ_>(w~a@t;uQEt?qn9H6ip%fhcdv;Qpb01v`6=k>vxpvp& z3zlv=ygQokSXq$;pHok8S;i7@Yx|{@%6R@>GpeF>I2Zi-wrfn^65yBerNY;Q0_BO~ zcoo!{W3O482aqf7)cn4a8Iu7&Mi*G=*)_v(MD6&{3hXN*iMgwBaquc*la)8>r{W{G zs5taH@xuw!4NWFA7TpS1hC09ZO^3Q6_CvW+LXuk<`q5#(hOM~n_uV~2ThPA_2he)I zBfl*=Fl7JMtr>nS7Zv%3e$wV^)C^5eM6G9bT?kYmBcK zlP`;f3rOe{4b}bSkqAOtyuZy>3@+;7y88!&HQ;p(~@q zHjd209O}Ynugf>hfcrIP4}QZwVFZ~tDD9(QMC3(VY%m?fBK~c3F=NAk&Z@t!Z=sKG zELc|mi3$EI?lU;gcM6%^>wNPJ4R}^+T2E6kQ2pEE@{608AFqy|8Ap9H-SPEH$U_P~ zN6&p;hrY9HrgME3gWk+8{XH9Elh)BSInh5R>i}ZSn}3soFm!fb6m6}0=^q~ z2tPs26z66Hjbfh%jV!H}c}T!oxAu+eh8fWGgZZ8F{mccQkD@+unByF}3k<&F`Ah_V zibG!gUT1S)3Uj;M!%HOzb`)6jZQfe=p&5St__ViuG#wU|dkhOzr-4VpJ-2+$z7n)- zdES>aC_JnxCxdz*D{%Mj$Q3sD@cd?5R+BI^=$ag0nFyW#U9@kg!*#iOL4!Mo0twry z&pQNDpu1mln6Z})N0fEDbS*PLbQ+;fbA%`$ekFZU(`zfxW#1K6O?dd`!AK6}P1-r*zq;L*|ScV}_#red9R zeg%-A?eK76ryB*nZ#=~wV*mWJ%KNsDPQc*@=^ke2%e;@R>0Wrf$BgZ3mUF&WxtVBq z{0jp-s^zRBux@ST))#Fb5g?~^%{cWJ14I=fiI3=m_AYwMDD)K#`8!`fkaX~pnb3NO z97{j&Vtain@=x$=eY-c#)7|YG6EFvLNFP))l_H@b>YSV0OXPu78<*0N!?*cmC8q2q z!7F0>NdX@UL=Syxc!cNqr!S~6{Z|s4+m>f`s4os|_Y58D z5u7IdRODZ>pd{O=r*H!W+b3kbk3C0UcowjDFP_h+ai2|FHwpDI+6t4Kk{~6FAQdm>f5g?IZqa& zuPHn|EjYpXKkjLdo-62^)8cP>?f<63xw^et-(}MwN&M^ZL12N`<$;rXV^9aI14LVp zi+=t)t?iDyL9O{CFk3`IZmP}7$jU@`@$snVgI6pNCcNzLdDCEfZ06&{pcrW8o?G_e zIvYOJe{KoCNdqbIlZtG2aT7Qg9Gpu14U9(AlO=E8DQ)Q$KQ!K<(DQ;>UN<90J# z-y5&5oe!=eAS|uB!36nQx9el1DfUUnpZocldr9~&ap?9?E)y1LN{UOMFIU9bocMNy z1XsenQ(_QgJ>%KRGSkjBQ-JERYjutKA?yAOG6)diWt zP1skSEt!9kwMckhG`prUm4drjeq45#BlcfO@OjNbt{X|?t;l17rPi6VpS_wP&r3Jg z)_{bN7YWP9e3|fD;)iJw_Jh}{>Z zhVh*y`X`Xb)@+skDfl}X_KehMPpGgVp4)~f$NKQ?t+sJN-FW+#hq{i(KfBT0;zkw$ zCmQ3@eU4&(X7||kp-gDmD}P z{^O6%K!4fbR{mjeCIQLMlFUOGOepB`_$iF%x#!qq!29%0nYc3y*>w%ijZ%&C@#O)n27n}?<4+n{9NDC!Cb2aB&2J7 zh>AC3g6s19)Ya&B%G3$_7m5s6nLcV8_B0(d{C|szB0pqiiG81`PX|Wj!}k}x(qT*U z?5|TtSx}SV(JC2=Tw0$vb^ci*T*|t!`CB;)4mu4R1{;xZ%24M+zzqtzdtNCvpzdXb z(%g;2(eDhU8y;PYhd}1R;0om159G;*i&0n0#h;W3FQFi>>#E-f_Vd}eF}u431ZWj8 zHts=wbLd!Ee}%K3=GNd;2Rwh{{=Hk_H4{em+5gPPK1mtn35uUdhi`5D z3n@@!M_mrZxtNHo+trP^+ULWAe-n#Sz)fJ}PtGAWtghpE`UtNp#*Oc=Kjy^#f2vCt zV*YjaEq$Ga{Jl2S&TYp`G91d1()U$hgTwil-$gjTHyFvZDjFT)|9f!t6!KxS8n5Id zCIKsrd+r=VzL?C{I_rfxZ}sim!`wZ{MW+)xb1$YtdF7UW{HWV}#TxE$mNfYIWL!>9 zHU@IMUK$<3JidF?WyMpK40t{IDpV75im%eOXg|*HkA)>%)HV_twcae&??)Y8`?$Fd z`%^(LCP1XUiAkKyC zre_vV4H^jW^4k5R8*k`IDeLQ;&%OU^!_1Iuqq7TIJ#OQ5h! z+Y}uPK7>=8{Wptbnx+D`5+L7Zm3F2#1B%^u8w46RgX?j6>J>ZWs}mbdjadxPvs-VF zi~SQpY2=JL(O}nab9bNN1lae_JYtnT8{`tcZ_P|Ve{9{iKF=Zv!jA;zmoZt8zj<#! z80s_apU9;d^v5jGrYINe&!+x6Pm2xF-?#KcY)9YeTUT=83;LW5EwkNHv{xL-)98hP^j&DQ9PYcR)I@>V|fr*IAj!hA3< z_wW10tig5p-mov_7Uomuq>Y2|IFBvMqo^Q761+F2IL;SPaJg@*Lka3bf%U_+-ZCVZ zpW`|uT7>l^Uyr5Y>tUS|SHFdmP(@Q59kxmYPv`WbQ`IccJIAX?6Qx1io4*&l{bFGE z`vd8PPRRLgLGM2I5s+1S%l=;j6ZVFPa*1G{mj??*Jg6X`$4NXt5p|xc*Is%7`fsIk zMY#d$Mo&9&b?7$(qOMzyYhit4E7jyW@i^OG9A2|9moT|+0nK38vhckK$ycPsvx`=DR1GHVZZ z#D3VLy{bOt6#+UrM<=*;Qy|Oh%LqC6 zpoxH*U+SMK`6)1X79E|2=ef^WMsEo%15lJ$U1fB5rY)DCV}*X5xkThn8v$NH@0RGE zXF`gh|AQ9%+&3CS=_2kl$eVj=u|GTphIBQX1aGk6U#G?M$lCGVU(OZp`Q&VPQ8j64M{*|r@qn16X# z3pP|D7nwZ^eXkNpL3zHh3TJ=41*@_hJuxRkoH{DBIGp-j;dJ=9#~C-=h+Vr2yn;1u-CAC685K= z%R%#Dmn2BIv?uoV%{Vy0RG6DU-`BkGX@!dl2?N6VPTHs^E(v+tYf(?G`wyL8R7HWK z^qWq(>14RMt^Y_r=IbN;tJ!aGjwXT>B&#AQ;Jf0=$9YZ{Z=_F$7wWmSgNvm@CY&Zd5m-f{bugnB9cdd}YbIouwXV7Hz1p+1y3kgm2F+g9| z=Ug$>TnD>GpDPh zCb=B_@#V$yTIg#+CK0!^$_e;f|K{xy1*~VU**e`%*tcHRX?FDlM1<3OqR@v0-=-DJ zI-(Bi7%e(zMxyV&ciffCglYE#r(ryffp>gY6ZVynyz^P3G$v@A+!Ov4U%x=(UOcZ$ zgL;c0-a@Y!kQB`Lpn!81arQx`m^2eQ)~jkioK1#++>6bDr`W(Nv9VN4hx43{&s?p) zk|A7G$x8${-!r?tl0iM$*)vuqjk#OPv~*&@HQi@(uQMUhzD;)&=SYQ~^0c84>mFM7M0)~rn49%Wiz6(!o8cw2XdMl{ z?e9VDbWx*y+wymzi|V~Zg6r#S=GyiOs&a^a@#F|4Pd zf?=8w^5;s`;s@2p16%&Gb9iI$b1f^4O3<(OFFWGXjP*IxL`-V5GC(?YVcJvVz4eD9 zt8U#TAj-0FY!mY5#{$F=E1-a)vL%e@2(1c zxOFZG5)Y0jIqJp1u{DJ!P4N9f`p)e?4w1lklk_wj>kw|*ywMSLoA}-MTb74}8o9Es zIyk2XycN%Nah_lIJTmz=u4CmW_aDz^6zr_nnBZ28{i)%?wT1J$Smb7XVNWJFPn*#* zunuOYG@QcoNZ7P@p%lM*5*Qm^*t|QJ1xEkLYL*|NK>KUKk}uuK5N+BqAdP*pHe~Wx zHrDfE&(-$weg+ulIG81MG{flP^Oeu|NubqT+fx6C3ASPjJ^`+a;KCN$W7sE;J6rE7 zXHjseV4t=Ua@V)ZWrBthB(QalW@uVaV7~T6$w$=NQ}fS5f+q>^o-Z^d6DX)NFn(u< z@821?ly4*I^X$$KTb@W$@S1B~>L}-X=DK(1ow$)3)UJ5Hb)rMB=QW}8#%$PTwpZ`A z7Y#l{>`*Q%jtAF{fusRFHhiuLsJN<^0iPOsOR@*(ki5z`mKSq+^!(e2ZH^>d)7u~$ zM_|6rIPv-u)^p3(g6}7$3Ai5JcvUKl36%;5JMQ6ioqVyJ>EK7e(xVCD(a2+`pT0Y= z0AF{m`fF;3=P&cCq~t_B`fSF3H#TA4cGd6V9;zduIHNjK?q4EkE&I96_c;sHUtQFj zp`)I}me_?YO#&@F1);fo7KDTjh3vw7)EWBMc5;9LbL^s_KbVh9*AD2)q90veKL3?M zU3y|WOQ&#NQj29>B)LiW)qh~Q_#FzoW>werp+8PPNSF|gqd-U7^qlZpI;0$al6eb# zyyvisSTyFNc`NE?!7V08$GUGX!@m8?AA6?*{as!2ZP-mmti!dHUVHF3Cbac3?ORD` zJ$`wa!+Q$!qOx+uE6_KK-?m9FBEhF*d)(Ah3L@U82DMwHPqEB^H1h^#Mk^go zf1TdBozwsM9%iF78f+Ak_Kg4+k z@tv7v=#OhUhet7wOh5S5)rQ>F{Ki9mEpp3doe-CQ)l4{(!hK*T)>+=YuU28h&Y*~u#|H^G`eF7|qYnkcV`@tt;&nL&XM2A^{gt|@Sjv-&IY`a& z?+vU^6qPozID`VB%RjlEjV8lci}vEzcpRsuXN#1E2~ep@6`FHr!mrrF-<~43+@4IE z_d>pU&g&U=?I8s{+iNE-p?;d2xpd@GbSfmdTJzu6Wx)I4Rp&6bWnqq2Vcotv0&vRYjE zC;IHBgNyZAQBR_V>ltThm>+9=UfKFLgQdgSg%PDB{0ZQ3eyx!R1!i5Psx>T_UVNAG zz1QR*!w`qAr0p-vu?G}V>Jq---Xj-hm*l*)2f9J zmDy13RM;ePn*y~vM2Hc-?(w&a+xjGaZd>i~#pWbf-t0L7ICu8-brP?!pL5G(4%@qv zP+t|1c@zC;!yZ@0OI)wD_BZ-UIeD-^TjKO{3JL|QnHtFRX)EQUrZ1DQ?*4$iQE&2Z6sDXi4Hm=Lhol-P!_ie1k?{a==!n^o`j_ZHVJijU6)92BLVCO*}sP$ zN**I&N%^7Hz+dPK_4P459?kINj@8pNl7O50|1j?KF=0eU(lHfz=JQK0>&Gc1c(}3N zi@i*Qk^?>x6Uc|TJ|}*j{6xTO#*wbq^GwJ-RxG85{XbgukHKY+T=meLH*h8y91gEP zF}0r!joTuA3F7;M-yc?ZhWcsqiS||>^^+E=9VGmS06m-hrv&EKpI0P%1Xx(NDCg!Z zSqesO3H{wQo($*G)B-;4WkXqOd(prf0``?E)J{uLkjhoA9*yfexAl~)dlmsgk~N#R zgfih;?4QTHn1ia$_=W#RC*bkw@T?MCuL|uyxzK_Pi(ZVYOen-2)~R`nsI%!S%}W>rdK` z+?$`=<|;JK0Q)S1kG;qt>Q3w%Yt=Kr{`YF_9mq3$HuuA8kXxqYogKuGXG9+CtDEXb zhAYdz-Yz|YoWCh!WAQo)7!%Ku`@SZ_o=~cs|1i#D#m=AEsH>MAKDzlIa=ZMr#-=$u z|N9f-)9Gg^a1#IX$r`ya_w((x{}k9D;WnG0dzqqcWdiM!< zHh*aADeSl5yIbycHwfMqZlps5 zU(&T&3pS{9xQcXPe$)@C_TGc}T1(w9S`oQL?fmG4&`{*4e8*jn@j6}=`3`XI>saSF z=u$tL4o&>JrNJfXpc0{Uj%x=C{ECmU0{pPA4D?&tFEPPPRis}CkMrQU(n9ha3HL;^ zKdU4%;cl)N`xfdza`Vpl9WfM`b<4&++m-^qoJ*57Apa<&h1yul&_Hup@PV<71dOOx z-ZDo2k{jrLJc!3Xm}(JPbdL$Zv=p?&>-AZbpzNkjz{-~D_hZP1%P$_UU~%^2D48fG zzY@@4CJ=7!PQmxfd~>OoFNWE!X;FU(=qHXm`sYbOK(b!NC7iEKCps1@qJJG@s#-a5 zerM+y-DAwz7cx6#u^@8ME2U>Aul+~C8sFn9SE9b%k-O&@*hfO!_8<+lrHL@htG&YD z6Z+2Ah#gmN;QJ!%ek}8+!{`(#$DKRb-`r?$iBkFH5cUYvreY;^T=06EM8~q{ z3CL))&D>GSgrUvy`{vMRw;mMJ#^irDFWh3oL`SS@b1U*>*Z#i;QMVZryOwhJ z`Pgj7i6@v7?XR2l5AIKb<#tbf3bRQ*UBLrVRz`Gyl?fP|rorBz~CfA|P({kIz{`6x2)KAM?id_tqr|JMfY4 zUwA}8-(3n)GQ9f2aD8p{#7BfmY2c+&{ceVffM&Np+Xt_*VN{M!%^m9_t7Z+sbxdg4 z6BXm@irnHld({?wfB7%r;!Rc*NV-;4O5kw{ilQ49<&se6Q*)+}OoaRG0%JQXSWsj# zdyQ)c1uuOIJ8IJDkXi#;zi{2xzL1>S{VfTKP zXQZ6bYHg`SI5*|A zIL`fYP9isU4d{{3-8LiSgZ^(m=KuT}p6A?0$z@KunA5-A_#TG*9^SrRah!8s)|(-J zgYyLVc7KdXM*ZnodO9HaEdK^HphBzUdJSUWR7$}D9Ve_$q}ikGVl-HOmfRI=5(EEjXnlGG>+@#m z`WAad#5oB4uswJcb*YIJ)A>RzeH z=hoZBOjv05Qy>`E-FK;gd)$%M=rU7bv7{!%L!%>K#3;B zw<1>v3!WdfKn~QJ(ACXC4$KNJ(|F2m^aVS<|FXWFV?wFklek%2cTcSp9`6k#uID#JP?jgnetuy5nr--JaY z2WFbh4GbaY2R3{6_F%t7vUygFu1EgSUKyqxM+e)JyFv`lv4Ig5;uVCsn~yyAsRFrn<&&gVO@A2PS~rYx!>;LElQQkW3X^a?Ntk3(uODx?)NC>fU zZ)wL|8QoeF*o-;OB&WGANScHr#>grf&1+P znH)S$rbwB83HAxk_~fi19!K9@ck@47FA*DI^?1x{uAZqgFXtIh`_>|a4>{AVN~wKk z2MK{8cBjq@C&8Oe*S|(jS>SB+pr>Dz1lw}{p{Exqcv)L$E=5uiwW;i@0Rgf+ca{=7lXsaW0}zas;4$AEF$U*zpR(fzO6Ua+9{D`Bq1 zq(HWQVYMK43LKmgDHG=Wf1-Aw&vl&)SbDnm@tbNo{9CkjFALZAZ}|AtPpEId&Ze_J zIZ&{#Onmwmes27Op4CrzNVxy`%Ke&8Oc>W6^mRpkxF9$!#=yC@aLEudNJx$fn`s1nr4fay4m&0|IW<)z&CQ+-iymE<(v~10h5J(e&o~Nl z<6eoia_&ptWZ;#H`SHTJ58Jr$x)zv-o!yAnb%slL|C?+A+#@0mb?u~JI8oqeB=+0l z4b~RhkVCjdt`|?|Fkw!*<;Vlh_lI{JyE}SN2in*gT$pS8a^Bu}iSPG5qwv=95Dn%U zHv}>a6TmtkO2E&A4X<;CWvccvpexEpWRY$)z&$<61gbDC8~bvJQG|s zp1!ijb!<1LH)@=TfRR04<18ej;Y*bVI@nyvB!)6r@8|HG9wH)+2bJ{&*6}@F;d0hNpLlwrT1859IW_! z_>Lyd?;!vFwtyuh9CI(}}a-IL+U3<74Z^MCPGqkvae<+MN6*+p8} z71`h-V=|qLzFc?ABS*uDf}>|xjY{}_)93(&je0Z~TlFZH zzbzUx9^EjJK#mI2$@yzTBj8PmA0ax)fV@?P>HlFqy`x2OCrD5*m|zm{Dx3~();^Q_ zblFh)ByVlNc^aG?yLP)%B?b;$;j5L$=~YKG3aZFmo_Y@ zj38i@?rN#ow+!&QF7o0{S2M&IH7WVtBOsb2GlZg;;DWJ6hO>{%{S!PLHwZ{gxiGAY z`n+{qOOzk=aNCR+dvh-V3w(GUZn%Is^hdLeVnj0>ifKtY@{|VhO7AY!TucBBNk^UM zI&AQnf2Aq>9l6fw?(IY!v+;7U*-}oxjw^X87MQ!u6}GL~f!uDDzVF2v z{R~L_RTiA_g$`EQ**fm1C#6~&GLE7zoKs(`qK5pF$X@W7v+oI?UFnQY9|0b!me(V9 zqs}}j9?tmG3`vp9PqksKejLHFebrHKQJgZk%CU$)BJs? zC)aPrm44hzLeS}lQ%a~aA%hpj3#*&q`!X(-RW-Qo+uk|0rZ8d0vV}qccpRE>k;*Dv z5^{g5cN}h{;6;G(`i$4ju#lD#UE@f>C86!y|F9qa@H&6XQ)i$%dN}*J z-^(RbZdnkpSjz4r<0TWgLXR7yA)h$1emFlUB7p3E7q%7q$M?{R8XL^TYV)fa9$}yK zCLPu|cZUg@L&fABtn<~4EbmgBcW>X-?Itx0u)fJ23q(FKS)Trprbxk^BW~&OsdUhF z-@QH@dCzQ%oZZQO0s=fY?>&Es0=H+1|8ah|wUM8DHFTPU$>Xg?0Z*8)Ua_s92z77s zi$A==niP~q4E^+~@Z)ST>!6;8vD>a%v(BEcw{@2=kiw z{KnZcgA5p!Gr8_{pAMm>RY`l$FFyWl_m4P9!U-|j?)s}Zzh||KVvwWE`?w?(&S!vo zXTy580y-r34Xg?<$3EO1{#hNlaaW&WR4w|Km7XX~4ePIP>vHm0^nKmfNWIB-iSTvo z%qPB=Ebx4*3W3*XU~Xf&n@ceUcx!_yMmfLZYntB_B_L>4>$frL>V+-m;}cN_xF+1C?(9M?o%x(u zhjXJI*vTD;ugi=EU)kJ1LfOC}H8_?CquOfGe`{E9=kWYCW0efBHmZ5Zxlifix<9VV zP#@y81^X6Vp`cQV;&*(X4BC4yI!9vOmrr*$vq#=IH(Yq+fDZ+ebvtz5Ah%b!n;4UL zp67j2&!q=bkox0#!e;c-^z|FYjyxh@x4d(-vM2>=i&=l1(Z^R04f);`BZ2j!(27n{ zFqFGxQVVs%meddQoMJ#(`rJ!@59FUPso)LRho*rORy)*5xOgFdR-gv+l>XXTPJT%` zzTc?qF9Y(EnolH!(qX6iV5i}E%=L>K-b?dh4r&S~L-F`2n%&zU;_>rOFL>26KmcR$ zo@Jc-Id`0XQFj^FcSXjLmm8B%cfKD{{M^O)|0zf7Z=C14Y|Fnb_7(Z0g4nni>;KMJ zzEBK($Na*!uS?HSutlI@-~N$gXf2-hFFDEv(M97nSvQcI{mX3EPb5RA{-&V2s2f7B z1gH~^$mi?Ie+;1xbe4G@3dMOJ63E(~ripwX>+;nxf`nb^ePflE*r-njRtVtwNlpCD z68J@jb8+dshYZ;8)XlVS@)`*%lNaWQWHDhc{nlcRe)=?Svs<0W0FwxrjzOMO*e)>9 z@#{1j#OL0=c(9&?zOcH)o=ggAvJ$TE#yV7{{CW8<7IQ?CBu^o(drtgDML$zE*#F+5 zkn$i2B(B)4{-hZX`T15JHOME&(^hx7XyAHrm1gbsrQmkRfX+3}ex|qcYnEZZHJ`tf zF^@Xjb3N@=cSSQa*By|mpHGKuQ7%V5?{rvRao^=D^2~_D>ix6R3;=vUgTK(8(9n>= z{BrS=j`TvDy9NUzBefO+co&;ps6_u4emc{u%DFG=YL@@wIILS}X_847@=@v!`8Ldh zy{-lQi)l3Y{igfk z`Et2j0M2#N>%yW8KN|cw)3IJK6@7bMZQmCB+|XZbVzc`(*OUqC*n$0_$e^HZ; z|ELNHBJxu<-82e#aurhNF%O$a~GH5v&JkdFHCm`>0|lxbZC1+2pMQ8)ot>y5;d+tl*VpNZU?G3IYHv9UCanDx-K)mfH5)2N+h5OfH{ilyP0&?KCALSpnVSaH}iSp%NM!}z(Po2Y%yG&2DI;(pT5bR^2 zD~0`|+Sye(iQN9|kk-N^Z5mkGDvt8`$3T+7^-&WiHiVn}am^_}|N7#ocyK=xY~4SW zbc8plVP6NH-!+(Ur;(>?a;n{+ECG%ZR zen}Du>phwb)VwKp`~T~;=hwvPtC-_h9lYX(m^*XV2$!;uTk`DY{>xlUf|cf6Z>v8O zzW@Kehf-2oPHGC%;BSkG*gyFgDBV>sRDwKH;+Wy%?n8r?jF7O&OUM`PF1fPUw_jcQ zzc?f3OI{3H>Vi4wUbQ%1C+Gi_%rXMIgh&`(cA|bHodVX+ zOp8qe;n!W#<(e$ytyHhMkEpjRLatD#>xp;k#ol1P5ZWWL|0rj_I&r~uCL?s)-i=;2Y`j6J$eYzZTmO$>;6(^9#Mh;rWgl&m|Egy_l9>();ebHp( zu1UhvT@B@KsQ27kVr=eV9h$mo%6aY+u)M_hNETPN6;`WQeSIXk6# zgAR_C+KZDgFKmC~Mw_oDK-gDj*-zwQqwW(vr;+Cu2dwVts3)K&VsdiInh7(%>wL;^ zPCu`D+Abf1eZJ*v^ekRi>&=xE=XscF|2#K4ej=nedcZ@_hr5R-`ZNML{ht4rFdEgi0iR3&I?v*7(e!6jJ{1~@I4 zey;c;9n=SB>IC<&phA*+T@L1{-48zTan~Y0s~kGKrh;?7mVDm)Mhg7rYGR%bB*O_2 z=@-FjY!I|xKB1sZLc*GL7GxCiHRrx87szP{{C!S%==m2DhIW4eG$vF$V)Yj>uePO#VR< zp1Tb?SKm&U%lcT#2$G}9Jz+=suY&a5DFZOW<38hl4`8DYK zE$%-Czj69%pVToEc@ng)D}|40;QaplL|ck_Tboh%$1oh{j%%6GzV8gsuUIel1NG<1 zg0WSc{l%W8QXhr7nXrLB$D$woD`j)t8Ey2Dk{;EIDyVz4EBElwkxNI0k_WC~9k#e% zw&}-t@pqa&x)Sqdg+#Ni&k8Q)2|&`8lq# z3iEES;)(l4IA7Ua*DOiS?{G?|B^;2e#lm}QlhIEt)|quf4gqQcN4M`q4j);&EqA?7 zGnBLMZ`s#E1Fdjf=Q`xUKFj3`tlar~)!+BM^j*qekFu(1*P%D7~ zCYQ%PC-jjUgIo+Z67y-FP$$X9d9DjxRQOXfM9y)^uCXS-@6T#k!+0hHHLxz5;<}H> z2)#{+qk+#NZJuMM1P~^5*DX-5h6mJif{jTywPREAcrFu^sr#EnIp5=XimlDlC6RMQ z9p|Gdu+z#`{fzx4ec;)G|7q#W!=ZZLFdkAAMJV5rrA4R+*+P#j5rv8-=BLr?|Xi95%4-i z+d)2w30l1UnMaT(t46%}?H&>^wk&M_DBjnuz)jP1?DxQ>VxJG&k~iL0`*=3^^9+<* z>2g2_={*YPe^20#bBe2w|8tH;1Y%zd{FS(O;Ry+H`;V*ZuE%`cD=Dz9g$ODKs9 z;P-7bcCfI&TnD4$bC3syI*9~hMGC?Os>EY)eT5Z@DmI4^pq%$E#1i#kp5(&wj@U2T z2Gryd+mTb9*q)Pv*+8RvuP)oqfpa^Iwwg+y?%9Ogxk{r!UD|}(BCO|)st+EFw~}z$ zP4}ub6H|0uxm0*E(HgiDko=I*2M$^;MBlG@>pW-g&xAD#!jp_J$LVjDf9p6zfapwk!p{3lxcGBV{^4*Iyk5U? z`!nPmD!p}94Re#HYtfc4?4y?fqtyF;?8oGYyz~|(*nacs6AD7UY7h0_-$%d~wWrUb zA2NZjy~SV$cfW?xu-TJD1}rUkyiVVd23L<3OLn3UzOl=<_Rc1uZNy=V;_nQ2e08&* zDss_`f!|zxGzsDpZ}V0DWx!~0vZ(wcHu!xn_2xKYKmS?P6O}@P&+0$aj$^)NX+GdN zj&(b&?>g`jxz2v(;ktv!nIc~_t7TV_5WQ|usPQQ#9Fp_-@Ef^t@Zoxe6k8IGKX!=v zj=bX>7vYy)%Yw9*Yp&CfHv}E%w=RZI(6oTLo%@{Fk~OBTO2}^qUA z(3dBpm=zo5lMrLiY*~DUg29Q@j{U7H82y$U6sk@DAOG;q z#VTo|`8W^dACj%z?^5u~cBqbtIxqfj%<=mPw z)@`{Yjs0cP=OEXHeHZe+!>;TL)-CwaWJt{Ken;Sw}{O?@%sdCVQV%^wy-5D=;9G|4x_0K$Gng)R2ijh$02 z0)iw=T=r`g#vGAwB(G%)`of94!oaCH zk_NhbwD+fRo?j-Ns*O0E1&xi>XYaKqLu6?1+G!sSq&B6EJ7YfL9Uh}vZ_?n+W^YH* z6?1pK=c;|kKc_g)gB`y!z^BcA7k7W9-QCAKBCn&K@7W&a`w{EmNR{p_oKIy3=^*g} z0)%?jw};|=J&irryAt((w?#C6k~0aZzaEEogi$bWuf;$!-k0X;$0u?W>CmGiF6-ET z2Wsa84%a9km%bWH2u~xyKI%bwA3Fn{<_rIAF2~PpW%}9_Nmv;@trKO-1bN$ha-4e} zOA}@D+>(I(3oXn>JehE~mH5SaMviTlu%>oJWwu0-Cx8b<5kXRx5$nQ;)nSYTF z9m@_pujR${T~OuGgWOU=2<~V*MnLX=iHa(fd5~h~wSUZw1<_@HY6de@Y>Gz$mc%QPjALzJ#1ciX8Vx}0xT3%BL(7^Fu<^OTZF#j znXptXJ|qtkrGr*`571!F)FOD}5e{f4BxN)(NswHTvVE&|2Jk;GPCe1Y28EzaRaY^e z`Z=Y`@|G~+{Izj+4*Kk|Pa9?Zg7YBegyZ8UKWN}o-0~_9Iee$k(NoKF2zZ_o73;Hs z0*$i;o3gkZczre(G7v+Ldh|Y~RM-I5jUsdRjCm_|#I;s(Q`!;{fv*kT_o$eFo z8@H06QF%P90CT8^i-9H|>R3%AbJg2LBorQ=GwSd~9|<1bUxW3Qw(?JBJo59##-oi7 zL@CgJIB?4n*FE^h#N~Du5`yQIYFxfefv=8uggaix^8?tQ49|oQ#W!-(CsTp$Ghcie z`bgXJ6+A_#*NjzGUfS4q^Z6e2gkwLtq*hmd$jbszn-{)o*Cj)juxFGi_E*9xiRY*E z2{^j^sOw}=9%T5bJo@53>@|O0b7xmJ_;o+lI*lB~3Ubxd&?3Rw zUgh8*>S2WxZnf=?g?vxbDO5$56p%#&a8Fn5f2jW5Ycra)Xt z@g{fQimrblN5hDOe8(d{)-X}u@|KJJzzNuLRLa=W6f?Go1cbA^>8j^Ci!ceKnMb7)%s_RK3xNWY!z z*NXN0Tq)me6uIlqC-2WiJ`}inDE36)JgaxRe5Ps$sQkM0{+%}DmU%hFddL+&^PA?K z)g|Cir06#lQ}oBxuhzw3j;s0cu6tl^%Ztf=B*C`nudxp8d;DDaTe4L*LrYY`ZFaZ^%F&#^Sm|#Dl^YJG3 z;|HGq-cg<;$f&*YnL%BZ+biFth&m9?H);DFIp9v0fAVAWO~t(%U%as9z_T|U!Um{& zdiL9|4|yfS!o~X!GtO|}Y;=h4okBX?axyDBaOV!Vd9l~sbYR1f`Cc!5%;Tx~=6qSP z=qF18mrSCLIb7Qksa~H2`x<3@nMVl7(El%Dg%=0vrk-z;L_S&CxoM4EZwBnNkl${E z+&f}@^Fj803N#}$`N=}`_hZLbSKD&nxK>v}0}b<0nUNYPiT%jQ$QZ=>G?fqNs}9Wq zo6MBro`GbTmtDFBi3=7sDbDBVV!&wV{2;La8W@CM+7O1^#gn+i>R>Se6G6tWzY$Eh z_w1@zCni$`%FJQb<<~q z?2f6mvFK|9L61As_EB*9Rb9CzuFJH;%(bLrB-}l`a^Lc73K~kU6!v31k3GBhdOC^# zksHKiPt;GLydFMl4))^)iRK~`5?*MIgvP{Cury?M?J3l^SLOMyq)~@s^KRvZZKj}9 zt8stB8y0ltTyv^hO~Q41k2?a%OgJ;HUTlf$?%0r>bL2=K)Snm&uEL!DGhw_S1AXB~ zNtJ{29TGfi2M$?1&48J>EBQspf$vV~ODTJqkA8@4z+rp*4j%613zbjTh8JrAfPkdB7je2Ml*eITmK*9Pp zdEK!)G`QE-a5@b0R8-jdu2RhD7xN2DMHoyVy`s)dVg2XEy&C>ENPuC;s-~SrOlbVN zet7o{7OXh`W3P8I0jg!d`J zOKhKKXa7!v4C_CheL*Vs0My`Cg8?Asha|s@0E#1sC0q zkE0$6%?bZ{T#tNcb>Ta82zBt1&c};Q*&yI((;5vN5VTq!#gBXwzPx_7;Y2p1<;)Cx z*2i_+ykATnb@lbx@Pe{y6ue6Kkt~G$wZW4eI$cPB&%H?BkX9xb<~+B46O7{-+wUIn zjesJtA|6NX^GKK5KU86zt1W(}{K}RAr9~T0_(sq{Z$MRg0CO2lN`LU+D-!e%tO*bf z%>a$r{wzt%amv$5j^lhJ+;5B?;-LP_w7R>u;omiO_%3!9xuS4yK+s+<3KUB^GuC7M zZ>oA6y9n#{pvFa`&)!T(u6e<7M}N8h5%oxU)f_D8@_D*^|Eu8 z4wkn&bkh&efhb?(q=I$j@9~B426K&S#L(*9I3M}xUl}j3FPsOTzaBYAg2Up%DAs)n zi2v^kmehJ?7F$U|{o9qJr4KT|JNuyU?kYBv@C?SrXA>ZBsdLBpUj}Fd-EmrneMcA1 z3toUeK3Tk5MCK9`ZhD!F(XkGl%K2`eGNK?WeB{ru582>7J>l zj-9rl!5=HWpQUOnxEt#m`?r9EjPYkOPPa0EFr41C@Hrb|{#>YZ>L$S4?o+h`t(&8tuW6RhW&^UlKd`dM&z-pgLf0{wYwz>Nlf4s^0PB3r)EA#-OIk$sE~|Dx2b zuj0DINVXXDqt5UoPVdXX^>tfmeg8J*5uWG})s9#KavU}Ze?c8St;M)qhPl<@uh5@B zA204LM@hzL5>655G>dy$)eQVOY0GXgmuT{58^kyD50@(X_U+ zBOC5~bc!#H;{$L&k6g%@cFaO2G}!L@_t5_BNH|?&DZ*ds{XJefd+j=T8yT z)pZ(6{}mDh^j?=#)Kj3qSRufy5y!KiUpagNxis*rThBuLyUm8i@12nc(poq|DMk!P zQ1N4rPtjrWQ@Pz0Z8qp!Oqa6XLqORLS1WQF*TtaeV|O6x6)1YdV2(SouSlxjo(VjA zn+#T7$Lq%nAMEMQ1iir5(;s+mgR?wS|CT)mvJ@9zF>FKbs*Q}iU!4JFU9t4gXKYw_ zfRV~vMnc}4%V>Ts1+Oz6lwZcWRqD@fojXB*tX>2=?j~}MrLuPBRTdml=-D}ELxE$U zM)%@h*{~sAWV5U;^3|`&JZaRQ3xR3zU)-7CT;F489EY4-kiTgZeQ0<%b>7OkY*6uV zjZ8D-K&XJ)@cncWjt0~bAf=GI0=EZr#O)8T)g-0L>BPQR1btZlHi^ar~lN0162}h`pm>p_pIM# zD4al^Y~AAyI6rZgP6;P){!g5?b=vou0n8hh95!G*gPYFTkWVCJmx{l9`6?YQ|9ZLW zNEaJAl_M;SfP@2EoOT%EeVsS{R?mGNBf?j(Wh?s2&VlimIAIE=wCD7dFekdEXb;a$ zV7}&We_C^$37_;?FLY3!&;GIRQBNg+rekU^>CA+n;OVHR$XCBJ7pgdgFhH*_PdUAW z4!fu7HZM14!`Zu~!^%&Q8;4v@-BZqk^}`BxN07Vx%~p?W!~1&Gzx?P5)a|Qv3sVA7 z=V=}?w$lFyxL^A;oO`a9-K6*f5A?O5MWx56g9Nl2&R?g~%Ya*>yRVF6&Xrwco%TT% zbC7ZOE(135fLQNohiVqA<Ll&IqBpnrLx1nBVxAQB^t@)pVOF*W{o%pIO3i_;qMZaO6zS`9=D$UJB>;4|DoRMrH;8)4pb znxgAf6L3%C*>b@@3|Pnbn8JN;+MD_O-zpRHzfct(8 z(+ZEea0+Sz{r`SLKT29+_;HzU9>mWXQ1xXr7^P2l{zl$gTU%eT&n^oReScn!zn=_+ z^%4)okq`B|7C43oVLw{r>Jt~3kl^vN${?3 z(M>7LFS2V-k(v1Y9<2>D?(-y#xmryYLztU*wBI$CB3E?gKc#Wc)s(!wAoV!~E*_Hn zmV?S=Lj12)@r}m7fU_QNPSKATT z&4R4E6OltYIB&N$-YS^MhUnD%HNJWr@M4cR-9e6gY`(Rk8u`cO7D#i?PflOH>FeMiS_2BeuG!DEg$7k$J36XR-=6Px5nGi)LVSGpEWJ4c^j;{OA3~m- zOG}FB}x)*9YL<}*Crow_hGqpY&SvQ3HsRcPY->kX0_li3+}!iGfm+wS1FiF z_b=!Eexf3grzLD;!MIESiT>lc+vC@6- z9ksuVA3b}L#}%)CT5G%D z)&S%;9)UyL+}d5(^LzOM5)LXXXGQe)e)1a7zeDdObpq3uv+vtZlBgEa>J1PrdZxS<8t zUB{|iS{T>;;jE}%F^TzWcfiqCmIN3ipZuDRdVVYa(u5c0cem3#_Sv7Zq1a0L&AOe~ zFZ_xEN6=?O{f_kxU7=vCLEbnO`|FHZdfMPi3T!`kw^%R9fkTg`?H}ym09&tS!iXY4 zpd(UD(e4gyVnPx%MCG$!LRNg6V4lE^L03 zenW`~CbJvDexYwZY_^QAIZT3Y=a72UO$xk>S3lwM?Ngd)(!UtwuE)9Y!RRl0s-+5# zVZYNCZ1c>uMg7#Mzo8vX0pCgoDODU#q|c5kM=S`)TDnPQRVWiIohoEDqkj!~pFCFE zPlrp_`#+VuyaR8I10{FZu)*9yQ)`WA7Cd#`wDqM(GB7JF#=J3K@A_~0yAk%$w{F)@ zQiDu*=sdQHjl9QDXH$mfv*6(uhIK`2GB^Y8ueH7$7`vwQLc5WGzP^yMwxm1=7d!v% z@i7*tN`1&s$|68F_t2K{pA7h7!@lQ(el)TDVuKLoyL-pyOzU4UfR^QN_XTxE^x66s z!k9VX-H0T5m`|10{`%$C-XSL_i{`-Lebk;d`k3Q?9O#_WzZ9E=IwCU;l{OT^by>4lVzU z`L0Fa)B66yS>Q%?zdZivHtdQ%ZB>arb)oV?xztk3P2qo|=bcBL*B$7V!M+=sTQ1JG zk%U}piP*|8Cb)TN-Rwi&Sk`(h|0i;9zI5({ZaWiFlvFc|E@EHIC9RI0#=awfxp>O&QYO}+ zxJZC%{xltiYU|6Qg6JT8r&79UE9RrDo$iIz47ebt=9J2$fnKWfVV?sWDB8Or=Gbil z7`n>0PtP!*&`0h!AI^W_Y^}bOVQU{m~ksxP(RJyNBO->Bw*vlu9l>Q6kHZQ z6IF?M|As1STOjJjk?xW|?XQ?nceh|kCXQ#%O0SsQJq+ma|319W0(G^K5*x8%!@c;m z(Y*W=L?)j6E|5ush-}f5kvMPhLSBkbbn>9sv2LFr*2&hx+ad-XI8gWBuuz~49TLu+ zuJx9ogZtF{jBA=~IK_F?C{s^DOUKwyd~F6SN*CMKRL%zDd-s%tBlB?lsXM$r)4;^m z>EAym@=$h94BL83ps@AH76m{BmaW|d@T?EaL<>xYSw$x zRGtLqKmWw$p}z=R95Hvqet(;*@LCn;GiTfJ*hA>Ui*oed=%UW_XD1|nLH=1K6Bslp zO+nyaHPaT%n`a0K5$^jPCgv%%xn5&}q8;y00P^ZF1L?WT$hTsO&N&P8Q0L{cHrr!; znw+q2yONs*6~-<>hUmlYrK=-{McP4c+WOAqArk06{3idMp&&h1<=Qe_uloi0fA6%T zznrO9ovxM%4GHl#gzmE;>EW}n#cm{A-PakoI2m)tzJrEe&|kLJUZU&!Qm`jJu||3% z8!m4;Av$WwfsSjey?I>(D0V!zH%Vkd2fzs^p`FhWeZ1f3ZA)2(nj&V zMDBlBEdPRnaq@V^rq9`Mk9GizEjUmjuV^)RlYsn1!@jrXQ?TSN=M49G$YmD&9>x;* z@8x_^hT$|gEOqSHs$(3GH`Oj>Vc)GuXHNXbN5MVsj(2PD`+ur0aJrGhzZB;5+(N!} z?b1844t+31@#VLL9mwI6_9`{^m|*p5v3|^D7V6DPfj93-?0-$;`w1B^rcLMR!u-Wk z5N^?YC<|7rgocwxlEGA|pxMNa1DZ6-+V?f~b57a@b8R}X*w>EM>agKIn=y-+k92U( zSpQcI^K7!qg3fs+Y`A~c`Si8HiBzT)TEd#}`wcVK?8 zTs8D4oCQaGm3#zFlkk&oE&USmRau?#s;^i-QD=%aseR4@Ro?aD)h-0IxwuGeK|K$* zIwZsiCLp2n=h5DiO!(*fR(vz++nc{aI!-Qmu;ps2_PHS%$iA~G&BeYTKa4G$xt<4Y za_4i8R?{Hkkv{*uqZ|k_{OV_IiCmO(qJ8;uCTQ?fP7Y(8|E+U89q640pDOB9s{Ya7 zn_fcfRTmDtvlcI@>c)Cb*Nkb8L@s^4px`FzHt#m(Dn(TiGVi=ObSwhvztU@`8tTbJ zl{HOF4eLNWWF?p9XC7J$m~+pmQ2VMCkNHdfL=rs<>z^k0bCE0ZiCRFS#VzD&vFzX1 zH+(}qh!%Nx1N)`@Riot9b^`oeW1E8mDVVl;KEd6mpFboYZiietanVt}lcYfE?UuXT zeZhGjTdpXTASbls(-);M;rGX)P3yS(T9ASU=(yc>}Vg z&_}lF>Q`UKe5^3B$`t2+8UL>Zji^^gx7z%>j&G6(o!)<?b0GcXoKLdD(Ky57_b_!;`)^13QE ze7Lf!dD||$zH2#sE%tkE+mqld>?7N4>5-HJ2~ID1`uF-#U~W>cR)&0=sCdVO#$Wb>9 z!;fbWaKpggm6V}?c{$`#MH}XhFQ#t%e+OtYNNdY8?N4eSYCP zYQjLiTnFb}pZMG#}?-3*q{Wm?FSCu1@1?7wX>8z{~{v ze!yCJfle0^X5Th^)4{xdJ>bSnhk-9z7uwVF$Gb~>kknke&X^R%-9%(Z z&o%!#ng@#v?n>?F&4sE|!Rf@q9H8$Kb68hJhx8{a6uvE`gIDA3#ES-Oc+V@RsG`7t zC;J4;S6IC>?!MYCkvD9tllj-4DWps>K#KSE?u+<& z#g0T_h36!MIV^o{&CG!Q+zorwF^@lb;ys*<UvUlL3&VY=SHH%~GA##~a8Ix6tr_al zxtrBB@Pz;&yCW+Hw^7h{-&bc0uODwSx;<_l3Ec+uZoG07?A`8jjUU%N@mz|6hX)C} zBxZsiW1S>HaAy(sxrkPgwO`&5;NYrd#m;5IS<}_IgQ%;CWzKb#TPWz+($|&{O@rA@ zje*o|4(y%egv4*cymoo(=f7A-7E7)(`(9$+QOkW&dLDE1z}Ju2hndhm{P`O9{qMVE zP6lYT5O8(tvsntcuHb;&a$X$I&AFpx!&uKBEL-c^urAb}R;zY;vEbj(;s(v-=u;0f zUY$jsvY&5KSc=y_Z?a9DyU)Gs(y1Z=3=X9SOhQ?hfpqadrCX-G8!SEONx) z-Zl>WUbDXY6zad!_c)){SSF-e$vc>%UvCQhdUh7Md}B+FQo8<0< zNr6m|>9S8XT&eQx8_W_NxT1*w%b%23OKPPZd|T{xcaOT69QCg6BnZa))5 zzM5awvLU|-bt$c>zx67UdtOv&JL;kS{g%xQw@Dzwz0E2yPtB!W{I&q~aM0jXzkeli z+S22K7P#(tbB})tqu$mF#WCtcNch7m-XtDQ!H$5V4~I|(H28LI8W$qr#(4E>2J+Q` zbBm07u&<{CHV+QS5wPd{MO_B^zT=If*%r9&3k526&O4b0DoicSWtBAW=DaAWN6wes z`T4gGUgvz^(KvPVeFd+AlTPUGmsgcMjLFS_B?Wc!sQan#`=;WdbmXY*vmei2m&t-t zS2Uw_`jWxk?qcUj?(c;3EOK2R0YCrvCEi|%`KZY~aS`^N;WP8}QS9qAb9xtdVckYY z9VlCeoTD7R@LwS2W!=X-JR?|FW^lmc7S8kYta1C%2Lw=NN$L}r*JK+u%B3Q=EVvt_ zB`izA+sT`|hjuc7XfB){OF%sjJ9AD#X*U<+;6vU5u#eLtzH{tIMJ4iVAO6mPd)D5X=xabnRzAlIH67 zn%Jk#SNLBq!t2PpE~D9FuIa8Yw_S_<_4|~*wv81De*dII2dkM7qG{L>9L9pi<1&vV zQMb1ZjhRhfHU<%3$A0QP?r{EE}t!RF0@`tKrZ#C18)#((>Db}#0sM{Dvd zTbZEWcAvjLGhY1ZdeSQU|=5Fc1P7+~=ihuDkrQ;77hH;H^+hV}h8hiNfzVOS5CiPC!l{! zum88moIwMNgAEFvwj5Y<#WT8i69p;`@%M8ia=_YU`0UhH4y^uEkZ*Jl^V*#A??-F~ zNbu%gWcRSZ=Vm$G{2l@Sof7qvlcnH8_|0Q~kc(z6)OlY#NP($Slj!wi8l=o|qPmfv z|IS4PD1{Sn@}avmuLuPxRws2-P~U>)lH|h!GGRfunRSPG8g%RZ9eacQ=qsLf*b&#a zCR)d2De~$J+v&tr^qn=Dx8{rl3QdElDl@>A#>3*?uCU-YIEVCbMSuJ6Hw`0mmrQRvql2B%ftO%kw- z8j{{|6?2-O51S>vmh;y|@MQj_nGm3#eCve5I~8J|Pd3jjOL$sUx%;w5o>%_$dV)H&0VTx!~QsRQybO>97WD=+4P-|M22 z-m~C;P)h>@6aWAK2mk;8Api??=FO}o0s#0P0{{;I6aa2-UuJJ+Ut@1}b1rUhc>w?r z0QepQ000000IVhg000000G!u(I8<-k`0+s!vXd?QPGnEgeMeuBkkV!kkx(QGiI9?| z&6-k4l1h>#>ls`2UG~Vn%f649$M3qH`#k^u=9+(A^Zx71%(>6!6J>nf$i$3_aGP*f z>WafHdk-m1VJR&~4XFddQjTsOo*uS0Y}`DqIQ+lQPuRNNa@hI&mXoc!!;YnuHB=5C z5LVfF%N!8CC;b2MVt8*|zM&0=K}O$)0!zCrY~gtHh05A8+%FM}~=z0dU)Fsn9I?6^M^jN(ZHAA8cjOL<@vQjaZP3Do z*>jh1Kpwqw19qN^;K#$=FH@byF=U}vzI)A9IH5;*#q39w1Ppa#ih{k4;p}fPq7lEY ztw;t#ZzwjeM4GT=%qwuxw->i()j|2>t}QVAedejRKMC*1j~6nZ+p?2EgK1i@xu`PS zpVnWNaArT;&&$yFaE6hHd{y>ZfVZJ2eCGG6u;LLt5q0Df($~zpxYxkN!N@;Z@yd`u zV`P_LAP6N#-9p{I(G!tl!X%~wW@RAX=XI;m&|O5-k@v>NU)gY60ZZ?$2{Zqqf(M_i z-6DlIVYi!vTW`_)0mvW5&n#yzZUeTO8$WmzD0oNCsJ8LnDki|g9ZCr%$JAig?pIaG z`(@#2ZT^klksL(i1-eexBWD$13#JlyMv0w>Ix;SE>WGL1~XGX*>m^{ zLGHat`e&QCaG&en)T-F63J0;$${IBpBI?LaQkhk$Zt76gO8bq5HW?ftlmt&C)MC`G z^V+`E9k|(ez8q^*CV|?c8 zwpbOevQ;2J(f-@JH47+sN50^4Jg{q(0+bVKBz<-bfz_3dZ}f`3VEg%~ZiKKF;||nG z>9~_J2C94`j6lX1-jTnL^fVUknE;-3VY{UFk%8@(UmQv9@mT6-|6Y2=THFC8_nS

keQK!(@FH}Yh_KX_^*TyF$awYq&2ivEmAH`ITUzf_7F1EmissnZ}~>zP-4 z(G1>^i%Ea{dxYme*`ax}bw)nO^W9~kFfJP;wbifMTwDamrKtxOKidjJ^MU z{`Iyk6>I}3#@MvOu_7?_LzKYk*A|Rd&-U)m`eA?^>GUcpIhF%ve;$3rkeQ2jWa*W| zUwt$fA?M=Ck4+K{Ph^4y0 zZSd{cy3ph{Cnfo925s_<24@wkS6=D0ssT+gZ`-rF`!(~aTU&U0A zHO}#`p7AJPOc!+JwaUOw{V1j>zgmi$b7p_|&ABO%t(q&=O# zWdI~MENgvTti^htri^)Fzj3q6FbL#E&w$Xgnl^v-&*L4L>v-`*_2MEp*Oqqq-a9hr zy)57R{zC*N{2aT--(87&pXEPR4s$Z#xtv;ak+O|<pmwOoV@gZ}+6pGl zvpW63?0W*(n$;%&GXGyp*8dDAlj?pv7R9{UmQ1@5o=yvpj#9I|B^l(t2+vk%1P$d+2@jGfdbJq(-GXJO8hlqjwhEAKm$-HX zT5-V1lg)fvG0k{K{yQ$Xa{es`%yC>hcjdofARH1Frpl0oQBluVrFEC$PC2k0vi*1x zu+ho7%6CrU9eLm>O+5M1G!T21Y5nB08npdmxhUf!3~LxH@11hnhnwm7<@OvJ6J`&r3ud znbB(HZ_ouA_(7=f6x$Oqs9HjM=Kkk(AbI6QuXV!!K%QPv!>*^YLzn5VR}QduW2htZ z-8;x;mPQBbtM|HzHVD8?voK-qgCrnYbNhVO#$OEibniEZ1L3St+@#ZJP$nNk9XVto zs0Jo>0vU8{+dx4cEm{}*)^jMw@eGg_wLgvpr7#G=|s;I-jSoO=3Gkh zp8;~t*PNe=3PZCyJ~^H9AFKLPSx8Y8pE(`@jJfJQjOr~3ePWX?8T^$@XL z(AmTH)Oy@72!L%$X_C?8u7;^B_a}xpe>`-m5m4@p?8HPHt$Y%4El-V8-Y9K!U zbc+m<4%UrKn7sj4TBw+Ob1QM53B9AHXhH=ItJ~}gmaH<~cjVT}+IT$~a@O3nv6+!GwehWU_8NQ5FVAkZMCgOoqRT`E4bbr;KRANiCByj<4D|7a6 zDjyB;v|eLf_2SS!`$*!EUQtbl;btx#VIF?Wh4WZ_b1?wjBDEDX64&!jSQqAlTh*e1 z&mC&deb_NE6`ybG{e$J~-u5XhKlZiqb$6%8*rv7fV53Aq5at9rZjD})d8k<0mg={m z`ZkH2SNSw47b=GzO+W=-9I$d~DXutPFHCp(=@m1Hn|w;ENq;43EFEC^bXmr^@ff4W zlAv-}JmMUlcF~jV8_J3I%aX+c{Lc0G$J$-8zcBcGo2={U?hk(s*(CCixiZ0 zw*6(U<2%z*O47nN!*Zq>n3A6~{6^XIVrw~(Qm^TeUZJ$bAYk#)dr)2p*pwXGLP6_u z-6OyUkCLmuG}oih=Xsp!=Jhf`8qVa^XONbUVDG?4T$9{E?L8@ULzl4H1rPOzD$d~j z_fGew1CZSzYh(dn$eZC4d$yd#%NuJa{$U*+x$~Cw$d^IG%HPMrILOp~qsRxvG=E|h zo*%7hvguIH1eWP>{dBR*os=}334WM%9hgqIAE>vwrFGHKb7a+aD_R6(&Xaahk}?S6 zo(W8&$k5(@!d1NP^-!|objJ_qqZ#fF^({4k8lA#j^WT)m3i49N=3k+420&Vm12!&o zU72JwGmnWws=rf$$L7;%@(N!5ZCZ}BF@nRC4$qC$GyA0+*H5Bi?r@L2@jDG`Tz|)^8&cXc#*VZX_TK%8V3r2^3OxkY~^NS9Tt^Bkn{1u-i zR9-&@>~(gyiIj#)kwWVr78ky#iiy%!R)TDnCrnRp!0x2XTmvtWT~PN5#88YhmP7WM zW1Zd6?GW=MOR8BJTq4Xj(B)WU?84ud4S!>43OmZ?Ziu2uJ$#e57selm zXS6Asd75+TClyu9QC`uA^)T;B6U6mm5D@1j*UF>xL@um)?7yP#A3qv;p6QM)Ru zX%fZkfUN}9hIT|9lj60{#R@s~m$=tdQ2>wgjE3j)Qt4>5Jz zIP#LcM6dFS2^zGm1(wB5`q%NcJ!e8&5uz0A(O`TWw~4**kvR0x*Wn5me#^5@7UZSh zD}*@MPz?{*&*d%Vgy=C#&QjU?5_KZIrff9}#d_@V=3+K~!KUrINwVc?m@uye$5dKh zJrGp#(%3Z()Dk~1%<#{6r7%17mu%;RPk-J>(28zCT#p0puowo9?sgqAxr&M( z`Iy{WpjM=)H)*OU6pdl%wAaASb4d#MDR8YTn=>jc&G2|)Sor?rY*DK0aT+cNLW{v# zJN_4`AhqY;ofW~{XnHx~E?p>r3=On9?rlHj?q|W9Zx<*XmOfB+tqywedCNbmMiRQa zn~z~f)opjeaOtq)KWrb8lktGsHgAGmVCvCl@Z@Mncfa9+tbbV^QgKW&^YD&ROl2C6GAyBTxIBQc{cN~ zzZ)a>fJsZ>sJ;+eeZeQ@pWcOk z{&yU*%D+v7@{)UpScljA=i!(DXJL}FADpGR(-CdQOO^x&&)bW{p9oEy3ryA&?|VrY zyd4g~?plRDK@R4p9Tj^7s7gnnt3QwZWXn$c*DcKDczW(rcy$HU{n?8Q2^Am4P?M0P zYptSKo-&5X8N16oX;7{{!6bi$F~U~@$|lPjHG?wb0@GJ+VE~2gM^toeDvEB-*-5tk z(U7uCwOgvqQhj~|KE6z_o-0oNz9D#-UK94wnXGZJli}4TtsFFL5Dv_b+oyD4 z{vsPTS_}5IFL`L{wNFUbHopDs7ow>C`dQI>u5EVq6h6p5;pdT2{qO-k)zh4{J?fEY zd{sYNGc_kn23D7y8d|hu`uaG$xu1I8%4+S@ThQN-r*a>Cx4Y%lNtr8 z;8jtFIr1~t)kyY$sH5adtc^dVUIEw>W?uBhW!9YZ9J!i)>bO1H@4AyzA_tDXTG2t5J z<#mwa3?#;RVL#LcC+vav=(@@-y~6|x9=)A}pB{Hc&nu2RFuy|*`L1GJ{cc|fm$jx2 z;^l9Gh?nlt68h2=Y8*LSQs#Q43q_{#ZtFE&a7ka!SV4 zNk}a-!snHr18~x2T?=Ccr2hM>N;6!#Br*v=)PK?)F742hUU9O2*t#l|r&7d{EWSr2LGFx&*-3!rTdQLeL9%wYX-w;>C$^PKEXx!dG-O7s#XZowY zxOXKpEZ`nx1|Xm3FUhp@#Yo2glBN|$-3UuNEpd4B-haNCcX!@X*5kJ%7;nzw6lA-m zULR&~umVt1#vyB}r&kK{+P30_mJ}6YA!F+5wIG)*NB99|;sbl@^ZWN5+9yk>?`pE( zo9&E2!E5|FQD)*GwcZn6H@3H49#7YWczTr;)ZG?J{?C4ueKB1XNJ!T-(BW6_Lp^8a zos@#uK0KpEi9!A^O|+D$2y6vkm4n>0pzoD47DjVsk>bsG-`BngG{APtt#ZM70ARMQ zYd-Y-VEWx(VpdsLGZkV0foN*w+qbkI1Z!^Abv+R2hum(@ZEHsBtb7U%tNsiM5D`38w4HA&Z5O*gJRgu#SAvwnT+*sz+ph0kgaSZ`p@YhID~9A4u$DI zl+pG^$I0H9s<+`CrtRKWXBf5So*(eKo~FUno52@E)qL9}UXd=^3oY3ZjlX{a!%TM5y6uu9KsFgw*5`F2>5muV<=z+lU4J2Mv@2oRR zGlUD8W~SdJ-S+TjF`8*7(N9~4p%SU-hoHDOBbiuT7Jiz)GYDng)&cE`(Y<0RFm*Lt z#M=KFx5bQ~jRJ-Ie)&JJA;A~cgbYG6rhCf7y4Saj(|6%^w;wRjURmS)@|Mk*B~=>g ztckD;pfGNAHMAnK%*=$DWVXUZTT|F2ek$2sIgaydAlv!jM!I_;K6~OL+Z_wW|Lmg9 zGowm_)UsE6b@h9P{*rYmT|CwwP;e5z+4G_qWkB+>cDHixe}l{pF%oJ?VPrE4SJN^J z5pWU($5|S9H^UlouEVmLfAy4EL`XD!OzJ>^8dDi`t?R#(m_%A3Dfv!Z+E+Tp2ZeGaO4<6wmr=5v<$S(AePPn}HqbxnAG zQx%x9aaK_}MKI+9hq?lmlU=)dot1uF{WCj^^hw^PNc|i6Pl?WF=$&8nHMr4@MT`x9Ig_L@G$>U z@sgj=9lhm6GVpg#WQ8CaS^G!>WB@%(}^_--)2PfUTg~)zh^xB&K*L_mum`?Uy3}u-T#>Sh<7qN zYkSflU_t!YBEFP>>Uj9!jxhmH1=Sf{{~Rv~$eoLMmdwOlNJlL9aN7c8k3xOp(N_*g zRo74P|HkP6cadAS0;WNcqqU`HE9FTP@e(=8-FVKi55&{0u>9p?DEpen>FvmXBM)~} z#IEiO0BEQBkP_4c)Z?9$!5t0h0$G1}3OL6x!o!43T@Ow9oDXZ%1qrLl#Nf-Iq+cBC zfx`2dqTq0dCJCkyj&*-nrxOd$E_N?$MSQ8Mc|E#x5xlVTFdBG*#5^i+;nvpyj2f?} zgQ3WzDEoNhM6Z)f99UoOBwoSuyclAZ>R%^jW&KsU^^9rqzajV?_0ck(#QFqX_8zV^ zYyM_$c8uS;_ga}e`cZc5W`Bdex8nedUr6wW>;IDN!dsbu%q59^81suqP?p&kxS+YT zizI+5n<&OD{4~oPkV!-}8wwk4#;oDd0a0(a=sNr~p|@34XBkPitHE zP7xJ{9D;jZtggd5=S-hS@UOi{M8e2lE?9_^HMT<|0?yx=$uj__MlT|^!$tbscp-Gi z--rwUtG!GF!;_|I&eNvt_wFCt&HoVcV)1Bue=?7hE4`}&{}U&&eU3^`K{(3oAJ-ru zn_9}yWA*px4a@iZ@*WFb+>2Dss+b1@jV({Nlk5@w|CY3DNoajXuChK#oeM{8_i1_z z8LxGFNJ#CPm-DnqWKImPjRyI{p4)8U<;$s6J7G#dE=e1JcD0uyB=a0_Vv_DbBZ6_2 znD=2j^RMr9x&2Okp@k7Diuq?Z&@V%NIMEUi*R%T=C9AU3wyu#5w*C~6*N%H64M>;b zH7Nco@+UBg$h=!Pwf#5^DrlwTK2PjZrIB9(Vu?6g~97&5_~+|XPs=} zjx3(3M4ug>yLInpF}O4Qqd;fegEASgE#zDK)5e-pM-9sJt8L2NPOV zKyu6!?O=mtp(Z&?K17az2~uwa>0}YV%HQ+3L*!BkC1em(orR;LmY2wNXs#I_Bbad7 z504N+f64Kd^m6|>+zTD(RYK}T_r$fQqfnx8GKKdP|Z2U*QuD1@{f2ALQ z7xcLUBbm{3{`c|tb?|g?vCB;MODCI+xbd+!vYNe~-*CPYTU&Ke>xRD^F2KuDOJZ+* z9rIFmXm&ODSW7@_5Sq7ODTJ8oU8*dZr^^Gi8E-6Y6B-W{m-tpiJ2hk}feCY|drMY^ z4x`WLfl^Iv_52Vhix(e_g4%5IgYl%NO}~2uv7U+Nwt)@iHX*#K{ZDz!mT8W1d=D_V z+X11xrT22ZlnKFHp37V42R_WQ;{|eEHR5E?q4(Uv+EnXtdTy@LMJ|L)rX|IKbjek$ zuWka(Vi%b7=fVNe2iQ}zb*wz0ZzU~KS~>goygYMX*Rx2^f%Z7*<=2*rzw0?7os`i_ zzR`wbco6y~dix`2F%X91wk2(CEz4o;gQfB>h)%rt-B+fXxiE(VMphr1xd31;hA{|B z8N-e@%qjSlO9F>UUh&IjX0A5rhh+p;P;M(TCvb&bCn@w9t`$L{JRq#w72ss;BhdCr zc=`uO6GIZ@3cPALH)3|&KE)3U#wi9eRbpxsa@NCoZpI_C`ux6(ecgcsOXpnKZ#}={ zuI;(8r`2`U%glK|gM41@rR$IR!n4etFB=zddH4oEJo8N@n3BX#*e%I*Ll+L{KCPcl zr?Qu+3Y6y6BOQVd6U1jWH?z#0qiO(Z24lL@9@rwR@!eY}>kAG|pf9eO#9!Pa>Cpu{Y`0Q|0TiWyaL%gnF$K91eW6$F_NP{T zSa-kRiRV#iS83+n4nEwspf;WeJOycQt6xBaC;-sBOrK&SE+o6)ln~AG>KI9}GJ;RE zSN{FpmfhL5H%!A*aw})J#hEZlp(6q6`q_hmE?Y5#S_6wE5UvkO_ZA{JkBonH0&b$v z2Z`Jdr#(2Z5?JfTXyfzw6xOxVeX;tbq=?%pRmi2Ce4r}>_&;1P?O4<7j~84LCWlC7 zotTDmm1QUv+2#*C~Oh0*z_Mc_D;}WDx812{T|Apz_wW;v4tMk_csnV zN+18{=*#^SpCA^!49q^a)T#S@ikxa3fei0-|Ltb$sx^ z+8PKTXCKl357MSq<9Hszs0_4zCI5?{1Ert4z|lBU-kT(xhQ0aM1Hv4OKG-H?iH1+O zId5;ZE7HS!g~}}Dmn0Rs7&_*5G$D+GTxWsz%%<7uPX66awR9^zZ>x-^p+YdU`-cKo zwGyB#ZGc}EAS&pU-5b;myi7lVs$(x}5ZYmrh6Jsm0z$jUy6J5`*LA3S;$r#D^1w6Q1ZdlAsCDdKwHnnCZ zPj*Lan7YULO(7;^ElS3Dgc|R<+#FYH%B%_qo%E2yR%&6|#^%npx-SmHg4cxWAptqU zRuQ+Lr^@a56Q>_WQ9+5ZY?aG=mXfvm!|QaIb82;!$f8qjauu5LSSm887?y?B!cLzI zv$gq-pOcaGU6-s7Swc;Tm1ml76p0<~(PoaZN#lcHPcPz{z+;{=IU>omJ~Rg zJ_~r7s0ZaasHq~}le=?NPWi!-`G_p5&ak5gxvYevP<#vm!;Xm1Vb#~t41u1WQmFat zevz9~W%awhNgJd-nJ4@W{sNzzq(&u~`LciO1>=KI&r`*%B=ZAZ4jsVE$ z_I2Nt)ui-D3Re_kIz;en%_4}!9VhLd`kH711)xknHTn(D-$aTt*+> zOkYf^IWy+NUZh6x8N&E5tc@fV)tH(_iMx?CgFtcJMrtAFf zjP8s8X4GfHOCXhKCsY^bC0XG%`YQJIT0*O6K<5h{sl)3?PUl zKog{IOcn#-U5+K(axm(BVgiMjvSRCAbz-U#aslgGZ zLbzNrCc`;EnrIjPJ8_;-3jHbI0`s(#_Uey=*KX+TSEr1<8Yhc8)Kmk}6_)a@Fk~1w zIko7?@Fpk-+Cv>RbojqqSrB^kcVbR_%wEmRR0#HwzVRc5+i?)oO{L4Ze%5avP%p4! z$AF-0kdmnjrUuMBl$pH)^?e>?fvdNu>n)zkU$mdxxJ8FqV2TOxr?hrcdcG6|JP^Zn z+Jif2?h=AM_Cm+jm{b;FMh^(tv9W|9P_uoXE=ARlUmPV@wd%_dJ-&llSO0458ZV8I zb#cZ3nyaEFZlho^AIdyxPETPv19HnpvF}g*)kp(f>t?~fg0S&M6I1T0_f8U|eaXFA zx@`dMCdbOU%}z6U|5bJ{lkLa4*KR$8+`wk{QqOzqOa~w@1Ip7T?=%?mC_!!Y04r7i zd42t20$t&8x|NMpZ17LhFhM5sgv zv*XwBzQAoT-fd2+VHpop7^PRVxhT z_6i}xV;N74GF<{R$tMgZ9xPp$^74TyaO()$9)zwyEN@oU<(J-|{O}6!RjmHYV~!r- zH(I>T@dN%J#(3H_oM9l(8^mav`DMb#QkVw=NWbNNcG%w%&$XmTYMwHdX0yLDw6b7h z*k4ka4qFN43w)08UE?vDguJZ(+!3TC88jgn+Mx3!du;i_Pp@E)>t2~( zFyn{igXI-3?0af56U)IP%O+KFV0eolT>uWA3A-FbpjAR#Q+#S%8-e%JEzQ754louW zf*PSlT!iFE++I{;sb}j{aW_3)^#I1NR8Ug5^dX>_D<`wSC{o?L5d#F)oMtQZ?{^KDj={qbco)%570R z-vQ*!;*ft-F%pNuQY5L>nv5{$26GD z!QrUP#sPaPU6j54T5=hy-=VqS;OR~9z24p8$sjM#2ioYLfzJuMVF-SDr6_T00FTe# z69l^uF>l2O^f!ATv9ttJBS1t6{ZeD~(}V7h^1r9vS(n*iC%vcrz?IL%j zpd~q>5Kdz4Yh6yysl=9!_c!SiG2m84LXK?EBW=(_SX$jtAp&4soMbVSCFQ_S zn;mbj3%unCw%`2e-nFXK{)mZdHO9EWY9_E95`1_`3|)G4#s$Q3-}ADZY_BaCvW6cK zpCi$NQ#QgK!ErEMkHw~t|`u#X@#TJqPE$+$}%K;23*6n4ZOaOOzbaK zfzZ_odbuka?J)Hxx8s9?GHm9XpqgCVXg=e|)!n78rH0GcECc7B3CALo+tKkHY#T~w z`mUuepU3N3B^6c_DPcV)LIWNw#T6OI%AiHy0FhB3*;=U(04kJ+#JpOcaO6g~^!~jR zWVfbzR;2~r9O%)5yzVNn`9Q|z4OHx>eb2Hb1QuFkQg?qpH>~dhew^H>U|0s1lYwF{ z(K>Tg7D-To3n=$bb{uE;ub`~pNIc1N_D;$*PrkTiwHWB&9d`K$dqi|s)6pm954Zxu z$2hY38n}n-#7H>NdzC)zcAkb#1t8Hz+J#bA@q;4d(ZSl}QX89NKv%rERpbofFo-dO zSiKdOA*3ik)=8{sNX*4%O5&T-R*?^W!|HTq?D+oo@7cL_QO$*^Bi8^tWpzs*j$g3e zz3JEI%f|yNqL#iF4($is$^dclc&aUed~t(>4A;WhU;P*t=;a-amvS|N2*5; zThq(mLqK+nKTMt4p4SRu-i+wxMIH|7@UuE`w}wdv4ndFQbkpv8b^9Ud!{)cVo+i2( zst$nI8*&?@OL1f3*(PcuJhQ|6Sh<_)R^2xf*Qpqo>epx`j(z3be|A9Ri#BXaQ4tRF z*h^_4$Lzl4G-j9_qgzcu%PCaxEq$sW!UlXuYQuE+Q32K;+#Y2}eRC;uUtw1gL`*$jVe6_NyAJGX8iuy+R~WzfpJSChT|3%%D4uzkzjGinS_~1BQ}rQ z;3&EumRD+K8d37j;prE@Uo$l?B<8_)v%C`PRowlQ8LCR zktU@&NVBPct|i-UXpaK>rQ`cuJ>&fA&Yqolz^peqxQedYSchxo@Ho5oql9LlI3N2k z4YY6ESiTQN8_1B4Ju{G1_(g zG&(vEDLcB-bV`H zbCla<%DV`(QtUr+7{?a(czLuFzW8_ZiHfAb%@U6H_})VLxU7Jd{# zystOyDS9DdnJ4ncK~?QnL4a;U_^S6oJMk7m3-zgYke5>+2oM zSoEFm+nPb*dk)MA+`C&A>$xY&dmdZgnABJD-E8XPg>A+z=fwTc{P*L4Tp# ztFvewkMV;;i`oRRF`E<{GbUCVjFUPhO}B4(dV}5eaB_t=_*qMT8%`$gG<*Je6QECn z$ehu})g8wIo*+YHh%~xL-K&4Fm&Zen_%n9v?duuChydva@xcXnSlHri?#N+#+I4o? zmr6bf@SHfx4wP)N*tpG~R|~JkVxi=csjG8;R`zj7+>DCCw>wu1?e{f_Au1~y*fu7R z1L-t}uWD*%`+32`cKQrs9&lm-wMWV3_lQhnOFI}19-J2y9uxTYotrB)Nt%ln7g-a4 zY7ocIpIz||Z;nYoh+Wkjq;+uWn^TOaptNur@fN8FO3^~R|Ky}9K9QMGWuICGjDohD zp0`Ix3Z-MT?T?Yy7coc0UqL@^^q8(JHKX3mNgO16559!lVgK}}pZi$x1p+DXr0D|g z8@X^w*l50Z%w!>mx${CFi+qzW7{x&-3p?Ew*J*lUSr99qEa18B)h=U+=Dlw&8iimB z1GqLUS3ZYN{l1ArkZG^YCmMOs*_ePxAK`Za=;lTbra`>yLm}{leDyGI8E@_FtR_db z1b#?=Q*)<;XM>n*(+s|I;x&YL58U^L^2avLh&a*$&GijHpUvl7OzHeX6+aNb^1xQW z*GXQYXic{QBXj>6^{Qag7cct$^CGg!Dk21Ku0>JUx=&fAn~qbB(y{?^v1SDW&XR76 zU}~|%@k>)$YTE6hN|++Z`)^It`A;h46RcHGQvi@&e71x2_B$LSi&@YS)RM>c?p%1^ zf3rjHxF(A!pvWP3cyIdKuLtHgj_%&d7_SCYW+Xr1RHps`qyTo`y9fptI&wnx?qrQP z*hVF_3;z??QNt~w*|}Ay4FURg3rj%1(fs8tjBYOnHDXp09EVyyU};dZi&7%B&7Ci; zqlU!;g07RJ(bOzgW_0nhh^r$4qGpl!@`tqYgf5)*K*+^B_py&E101##DmEUwlLXBLpj9|L#pOn@BaN zU(|7*iXRM!(so4xm98Brhy>glOF!~4LR?5t(+^%xw|WIktfxz`$ZiY~$Eb76Lnex$P@{5Qui-a~AT3+j|)0^ida#fc%tpR!7&Ns>t`3>s<2g3@cpV z+Gta^8u7qk_9a_d^^pyd$FO}~sA(nY$pK3jS_Te+Lvv5I!chT|EAsVkr6ml|!X%9b zv|M&d^X}^kx^yW|E{}^4K2PbZET3=S(KckFv}p8#3+q{MN{=)qh^VP$fJG4dWwJ%> zIb!Ry(@IGs+(qmj#^1EyR@5mp(%IkA8Bwyk&aInlG6#!>e%7PW7H*eV=Ve~Wiu;De ziP5swk@XO-6}aLd-Jg-v=iJvae!30OPm9El-E2tlb0m>o;3m@u^&YqqMv@1UQpz|r)6|?#90T)|-ch`( zQh9p+q75YKs?wAQh1bFiJ(pFG<`smxXy5Ur$O1r6_7O>Vz#M7&=Nc}qq@F*D7gRx?Dxm3Tx2DH82^I4-F+mh!&k+9yYxVe zi@~pIc~|}F%+Dv8KqQpi2Q*54hg0&ya6WE3B*7Wn_Yi0Tkhf33OeFu-UVQgKB6l$P z#PyRh&Xa3@s2>`F(p=w z$!BL`k)ZU@dyW<%OA@ygnQyYVm9ZFeBswVvMq!OVKl!5&WkL$*#AaxS0+LaQrzn7ulvwrn+ba=j6Hdu<M~9tHHz z4qDf1+5d_KdSxag^U%!!!_n-T*(_N#awI%bnHK@}c3ZWQ^{O98YR_vILj;UXtxdA} z*J~mg0ADV}Kck~t8M%ql8e{B-leQe2Ju-GJqh`(5{J2!YB7O?_J~%tJwPOl>BEBC_ zb_PD6|Be&6Lk|avdTwP#01zoX;5Glp2O6)9mev^$$Z6iqVezU=ZdDB2TYcHycmK~Z zJr%jY%HYlq_X>CzE74a8nOc0J^?H@s8ZipCQT?pn8c=1^s@+=JTl4P?Bf<3l2_D48 zPUgpQR8h|Ki7#)OVOoUuvpQUe{Tsq&GL%hi&a?xNa5%6yUmqybHVVW5ji~-aY-(S} zmiuv}g3=6ZEske?n40#x6FEG@ph$xW7ouL*_kHKV>WrQ5#ky^+`2VyZHu4m4M*pMRlH^DoQusz~ zS&QG^?NNZ$@^2NP_%#Vdx&9@vVDIT$C#56k>ECmn1(NTMK^u=tE^^K>ic*3PVeQnC zdYNmraBEcwG#cZ+Jrw0jw4WJk%VjLnH)6pYH-ADqlA2`9)a@{GSe}=vO(`h2({|G? z8F`3wOJh2+%al)9!cW!$(ehaU1F%YPMGJF(k8t>_-kj)%E!Ny>m8Gf`B#ivLF#UTW z%EwwOj<*IxL-tS#_d2)n+VkG?PWtCUFz4hU;Pp}5GRe7eoQ7i@)!9H6L0U!Ck%56K zNg}_HoSK3GB_SO{6$8J<3@qI6U^w>4>dn`&W#;br&8tTkpW;J^ceqpT@W?*eL)_mrp%B0y4S$J0YfZZl zw4NG(?^`vYT*{6L-MLgDt+1O0<~uRTK9Irn<7J0oi%(|h(SwG7{z=Fj5Q)qGD}H+$ zLMb4Yu2M6==j%BThKnz`d8l0>MNT*JCvPl?Mq^RfNTf`JgFG2^2`?V&V0{SAUsjmv zGe+QR>d7?~T?)>A7`<}Ew}l$@t`1d?KoHRenJVLwzN6&Do_QIaNjMM@-d?uiwcH7z zgbK&tfcBs9=GtfizSgwDc?3R17ZFF`Z4pg7{12Z z%H5~h&$e0$cRuG0PXZr@e=e~#uOi)?-h*4-D(+DLuDuwYnORvJ2o1(xIWdw0PE;%X z8NK$xw$IhTocyo|>2gF}V1(ZHDjvwR(e`n_U(h*woS#au|KteB@OEJ9kz>)yc=ao()Z6c_MkG$zL^edd z-3Bfqp97Ku2@S{2SXbmiyPsX1_pR3fHf8JAMM{FU5;!|qvdNA=BAu)L8S~;p zDz_=7;akumE(a}eio}0RSf^^4v5~*FeZfdk`9QGMc^9dH40l zytOmOswr05B2JGi+dW~7m369S0bA?|YkVg#DD*igf|zt(zcDp+^_OmT-jEkKWk$r; zDUY)=GA0Lhy_|2bTpF9fdRm|+DIS!HC9L@guDnFfHhmZ&9YWkk@E7&RDCv$5O^v7j2t0JX!G;F3D~0Kvlil^=6Er**c9p>=4(1 z%{!2_ABX5);80B$^!&4_#ME%7DEW!^wU^t@Ew>NbAvj!}zMfn@p`aJ5JZ{wcLW4)o zBDJvO_vw4Lo-Uc668yKuU(HT+QlNgdEPl+L2g-rcMWcKCp%Qz4Gx|8oPjCSnXtC^- zY8NL%4%Xb{%p{O6=M~yO6-_ow*P|Eco9pWk>ELFUuLPv93Y+6y)9BKDg4cCSP5Te< z)@0V#cKesK8l!nhn|?i-MDH$nPx=m?|i#CXh-4J)Ux|jJa`4yG^jhJ=d7t-2`Q9Fh<{i@}~9yF}b zOjER7#fCL~2T`gLF&FO8=DB!(Md1zY0_9};FLINBMS(CE_C#%o&e#L$<=!>2U-=Pn zBHrCa$kO1A;f;2VL(Eti`I^FtTr$>)FzFHMwp(%T9skLk6}tOlC*z*+%y@}5@I_z!E zz4Y(bj9T5)flSB)%`@GfBV^x5BqrQ{1H*VwL@KQ@ujms|EI*ru5aD}#xEa_PhDGNo zTkE*s4I-~Np(aG-u%9-PvDia^mjiYx$anj#ShwLU|0s4wGr_Dq(^Z+z!^ijZ@HW~B zq=a}avf~A8Ft5&i$YkNl+ORD1YpPf@IGwLbao~4osZ3D}D4Y_u zy@{DY^W3VdJ~qPm1VIBp<%@G2d?`^_?L}}V%|V($s2#}sd}MAEQN^T*t&n>GIqGUv zoU7%TD4ukPnv+@&Y~ED6AHHBH&w~n3y(3GeLX`0>yKm81>W%o(faS)V4WT2sVesyP z$BIpO!OrD$HVF7ZHa{8|<@oa0tI58VDhl9O#Df-3%}AUJev#*;c4CjEqWo3}RK(uyfY{fE z|Ezk3t862i4;Ar&J5f1qO|z}Cdu!F@2Q~$V$M4FQnfjoW%^86+l}yO@nQ|%_LQ5dr zRla-hZF`=7R&_1!waw**AC02htHTzrqt+a2=rIklg?)3fpkh*r@88CylIRcf>gvvHbHPFjw-|8WR=-(x-|t{JFF7uz6>$tQOzhvH92s z5YBTPwYRzNsXlt;Kux;578eE?kR`GR$P_XMm$986<}cEuBcfuPlOG(7*da?spl$+4 z&N?ht`2*?uXgrs>zc`8xj3T8}gU<2B>@dnQ{z-mpGB1G>8TK3**skx3nvV!-g34%7TqA~23eNq zT_fhh_SX=2Nx9uXzGcgCXCET)=*{lHK?4$2-ky?H#p)l1PTN#|w-$R>QcG$x4@g3U zw%@Y!;KKM%>YchzHcDKa2yT0jV`QG-DUPGNpGGL$c|jvB31$BcFm#FAoW zx3x_kkkaz3-ESr2g*>4~szZYon4R^1U+XO+G0Xk^`QO?`nBZ>?3B^hp=mPkF+>VVR zAjP-ke%nDVfKwQd%}HB|wY98>^+!;NKjqI-D?bcy?m+qMbdF=rso2kNlG@k1a2p8? zj@dk+x%69-%}XaMBa~z=CufHD9-_5tZ)lDu45{1q@j?^VpdWCaKf>1;>T-t!UF1rN z{cYBSmRH>Rp7h7rWV z1=p&=YCHte$bsSiD7pr=%DONbZ?4J4Oq^`HsU|nswrz8=J!!Hv*|u%lc75mj0rxp) z-+lIr^{%ycTLNu2@@a~T&Gr%0(0v+ldg1(#Uye{Fou?GQ*mpjdpXH%dBC*C!GGCrT z##=@|fPqJ-o|NJRy}%bVrHMYi$JP))2aJZ{71RS@Ji7vZ7(#LuROp9=u4LGDV2qbd zfk#^^_=dk+$+c7hPHj){nq2|I54FK-rBA6`J^;A7m>}g)Twm$3uQ(h$Wa-f76jq2AyO6M7j z4nxN?_b)zcVk;xm$PG}bT$<+_?6M?)1H|gXK9Vmtq?5;?Wv-S4IhL+%2F~legT}n+VhC>0fCU;)w$=O$^AgItJ?4PqZ#K6OPCM8X})$cE_-7~5veMA_k9OaN)Jddy`@MB?OeF+FmYFDI! zvir|BXkWy)2;C#_ZfPAkS**$>wMzM<{C>4+CnlpL8paUUuMol8Ko6nOd1pI5Rzm)| z@@W*B=H7^#9gR-5S)>eHCiY~vIY!Tsk5jht{=k-hda!hA5ylndcPq5dR^eCuheI9HCA4npT=|e2jd@* zWTV(*ED!m1$8|UHwfJK9m{Svjh#RHgL0x&vdTJNK^TYWhjmH|mIvr~lUiiEOM{v4) zF3fRL!RWZ@s8#K_CjQA}GH+O!3O4i!=tdZmu6t(qnRksOX@GL*L8L)?k<5h3tCOny z`wz4QH1!x4qT?=~)OZ>C3pL0g4#QSN)$wP&@&wr1Ws!T}K$ygT)~2I+S=MmJevf8r#|9Dn!HK|pybNr89B)+Rfd^KOZ2Ee~mNo{)0yn2iWRlL9tmu)h z@7VEC!*&r!6hUG`PSg-fX<{MYm*f0Y`;P#~6eptss}77ZW{KmA_bonOjBs4kCL@Xr zE*Tct&ENrTXwxZboGdPkFb^j@{W3t7P6L66uQ=o&MvovOOhoN}j_u>kH?u}w_aB1N z_|%|>_~Xn?QaHn|Do&yzL?<(@q9dR24i`YS6A_y%I-il~Av*#Etk%`UIqD?0L#Iii zet%AVRi1t}a?-lzX^D~kjFT5vp_=KiJ1OM;rx$M+=F1M7NEqF*%$^<|92BJf_L30u zn$qcgG&uoBqGv>5xFMS7U zXiyVf%}98Vr?$G_A`Fe3oAb=T+5Dn|Q%lmE{$XW45YyKD!3yC7Y=}_GQ2Dxu{ZW}k z8=s@Q2+VoU;%uxo9-gMnHP%uX{|*x5xH-6v@4n=FIqP<$yx%l=u9kJ-lnNDHgUG7J z38)(WA*&x0qR(z2w+2c`;uDrHjpL}CMSx?j9!!egChui=x<06~C2 zgxxy6zV}ve{uxNi@ZQng8)d%H-r!#XCw6R_K=^~DAktq;MCd)dAAC;V#egaI7&u52gU_9KYo z53$wf6@viv(uTUBLAO9UFo$KY z=n!lytYetCS z+bHAe1jhHe6_vG-B4VU9GMH?&vZL#&cIp-srVG8Nfk{le*yAkTv{Q_(Vv zR)%4;!Jcy~7AN-5_@5lFj~E=o7~4oa%LX}_vUmN!#rfpcTE$=vVbJ>93CkD@Q@HIl zvz&JqYLd5Zj=u@M7uzOML;v4zr%1?=sifj;bBsIwJ0rr&x$!JrDM>U889htKO}B2! zxTs{&5|9HAfms6xD@+4$^qk@y3E zPd0A+)H5mw$GRQ0yi*b4#_aCuWb|%)6`o~_>`STO`x3C!PZ)c7-fXHcA<XclOUx(ceX#rGd!=0_YEBak+F- z!&n6GV`Ht$PJ6rRJ)3_$PvK9sw1}3Llc7F}PIAnne@D;R>3*GhA4LZ!A4u7WL~5Ec z{*SAW8!NtFLXgr|O@(8U3=IAMEHw7H^lIOf)MML|4=1UZlz82f@b(j=^ zpBqN{u)jtJaKJMWw$yHu(6byvmyKYrX?3_Z@NqLiMqAS7*Nja7tat&n*#?32TCfrA zq$c0Qk{-Caeb(ns}R9-p)Apc6fH9gd)A6%Yek?`vA z)`mvC(tJ1k8Gn&&NPn5inu7&#rs~u=+{M8w26-!P27Gd+A(pYv(hmt&wobzM+Ur0IK1Z@X7 z$r_vw6n3qmR=Zi}nH#isSjOXx*s<$CL|`|>17N_1F5Sg$9zWmy($0U z%kHVq?~r`WekVy0NT31tRqbzw%hn?WU_|%r%Fg%!YBkOM@aqpMcw!j*-@Z#skz7PZ zW7bk?pr%zz@$G~5eOIBe+my)@fO0zGemDP<9>s`t{THD}5b}o$)r^hIg8mIpmVn{L zY*=fiW@Ku0C}P9eM5OI41u%BqJUmnWy@xf$^-XrPkXZ_CtteYxkZ#fC2T?x z4lrRWg0m}Wy>pt7`2TFD$6Y#nLt*R*4?lP@JZ~4|x=m`kHi8!0ywECLTn<_tpYhBi zafA2rpg*|%Y6(=D_VGzS#OI-}+F!b?wh#C*N?-ebxz*#1G7_S1?;Q8N2dLTwZ`6S! z8u@rEY63^ET=sT*XY8-vDa3POlqT$yBH3w?l`A>>-Lo9At_P3cMtbLKNFFWj9Y6fn zi+3?VA~S)$6j<@5q<5da^)>V-+>%3A&u*p=W%9>-O&zTV63O6I`I*3kc#zhGdE`R2 z#&vX?Uh|`4D;}!N=9Qtp0C~>ywdt=`agXXotnPCcCwRe$pgNCGf-w1-zo>1%B7LQ|3xoHwza!4!U=%xlTalGkAZiLbFh)jGn#^12mJwDD1*K%#_|FudD#N3XS&z#U&RGSwi+H)vI&xA$9Vq+p6^b_;EXi@qEd4op267Wj?bXg5)j55HT21UIW{ zC(!%n`|cYUfY#*Qo*Zs0v&Xq6C=SG*tZ*M>7WahnM{L&$1TdcvSQq?5j@J*@`cDBT zj#OU!Rd;{H1+wrujL-MY$L~x16@;?gFS41d%wkpp>v$NPhiH<1OmfD`B6wzQ;x5T% z9hB-~(33jAW$37d0hsO-$^G~6V+X;C_7i$MHYKO3YNLnjUC{I^e?-XuP2pc`PR_7D zN`mBPrm)Y=&B(4H?P^~S^#UENpOw3TnshAlSDEruJz_SRu6fZ7qJgTcG?9Q1>|1r`8T80Gfg0gYbXs*&yE%RATGw zpIwS#Q7@Op=QyF-Fao2K+SCbz^JJ}fZ1TX- z!zCwwW_<~+NcN3ZDuUnTe;i)q8JEX=An+itXI2Oa;&w1kT^Y>ML3&!DQDSM(z-hr9 zrC<@?H%yw^_&Dvx^z*uvINukp<>d9v%`cbI2oK_}eLCLUXV99)nnBifz&wQ775)HlxL#H1B6A{BcGO;9445%KWPgQB62jI z?n&2rf%8*=@ho@KCHr3m%o=~!z0v-tXO6`0U6+H?tWh*jOB40ywL+TYVl+g^8?Frq zB$ov6^i1X(VCTLwc{04ipPiqRt(l~4?Hp8KE(orCoN_P?bOMw8>t%xm5M;Mj(yjIg zys42?3@c#w3c4;?Ti<{&UeSEL1hF7EUVrI6DaGrSExW8pGa2*{gX^$p)MPKTiTq4Er1#GaSO!xnU31)1Ddo+f=+x5yRfnMoA_GqKoNn@ARdd5#@G90kdU zAm6GX!WLlCRC^MfA9@_2RK2^2m-iy0>?XJUT%{YpljG1=F8`Ma8;Un%ltb-#$yCPT3zW*{vVxp+lT=B|}OCr#eYsN4y9>jDL9C~-}aTV>A zn)RdEA(Yr5b$u6?Ul1l)+&bZm9xEU-Y7*ih#jE$7$)HlwF&GR}=0fo=I3YlYNf)9? z)slivVKZ_4M~Avq>_>yh|I43kQ_|Uj$Qpb|u7m8*y0s1YW)N*5Se*k{L>_%a>mDnv zQt4Y`v7HE7ZRp}P7ws>`-vBex=S3LgAHv!(@f!G>DV{nimk@?}^o{MVv5 z)L5EbWm&jOJsEZ7f z@A}ZhoT-^&=(8RhIN7>4g|Pdvd2^`>I8^}@w>d-Q%kNkJYVl`*n~Mg+E$8(=26@vcY|4H`6ZNSb)r8!d>>B#D}m&Yj3fW6$RyF!!c=2s|GWRI*NkF5UD?u zXwB}*nen_;l8Q-Lgn$FUrPrm8s6rXH+r)6mnCrJ*u@r{Yy!LLWeLfg>5;0i=vCdFX zG&MzDjNcD-WNU1>fP#On2><(Y{-)p=;wEtWDeITD+N@)#-+fr)wC=WXmUbK=)_g{W zlVFn>qoBm&FTmCjCzU)s?Bfu6XCTDM8kz-meieU`+=c(0K| zx1M3UK3MAmW$fGQW~emi*jKQ^Qs$RP16P$8<9ZSYU;aTA}l;sf!oG}LFpK_!?H%iX*2UxZ+Ama8^X0 zGcX3=0ro-m8wOvzekFRm968b-bhEu|`FY~n0IU^iEwd06ed~?8DC{vlgNK2Jt z@pc$Gc)T`6`$6CZDvI`G_#5=c8t}jN{Ok-xTobmN4f;fucney-MXdnO^}dFC+ zI0o5)>@LCxs+1|(pGQQvhpi`SY?}H-!xQSd2ihb&En3486fEDKwpJFl>u)(j z=ORb;tTAm?k+a7ovE8QZFt3jH1I4H>+k%?|fz$P43_51nQZN(_q>$B1Vz#2{w&g0% zwlKu10h^p*NBN0)=UvW+gymAmjAIQbCYHJW%G?pH62N*jo!$qJ#$Vx)4*JE2QJQ2W z4)M@4!p6!yqk5F*KW*8a?qkx-w*oL)2Ie`O@pl6G_JOzb`_^$sdA+&oTVXbroPXQV zZwvHmd5hd)9Ru_F_tSS&3u-z0NNW?*zk&M^feqHOIWcmS3=hu@Ic}t}sigp_hKvatv@_pqV zf`Poax579@0s2}O)&a-RM#ee9@;aN7BJk@1>@=5Uq*QZrzgdw-*|o+cOZqe`biwnm3fM11iBeG9ROt?^VJ z0{F;T$PN-Tu;Cc@0+t8M##r^vU)bqhEua^Y9i8O%{5P90WrIJwoP)qGEF)fVUNioO zK3LFM#>wGHX`7rr{SInS?M|kNZ8;*~&*XmTGffszto4gU<8dUL_(gl$yPR)uwUJJG zN-%XCYl5{}7SluClWqy?->5sr>8jZUz_kv@bJ;Mo9P*0vVoVvOs(_WR3GP;G#6U3W&l-JKfPbv=&zU1bECgmFU~}C+ScRo zxW&UfYCG!G;MIhVrGa<7`!L!MyqtueE7K+FlOLojU6PL03lRUyA6;NZm9v2Y#T1k94G%wCN>tcrjQDlmcTyM&zKSdtexofa9MXKPd z`WjDSQ}dWc%l_4Zu|Vsu^~D|$5D*wf_tE&hR#3_s#MHe!CSW?lmTL3r^zr9A>Qh=k?l{6VFQ$6nf5r0^#!(D{HGFGFps@~ur2$JOebx$QC~l^n ziERU4&%oG;`FI`}^H#LJ(e<|tkxbWdoh9&ta~t7$u(rfAcBUBPzg6Rsh;L4GV4c-; zaHZ^VdY%Iets62d-z+5 zAqWHS_};p20?BOJ*4bH;+~rk}@)H*Omk+kf=$G`olI5 zqD(nj{(S67Lqbc{)i|)@F&gyA?)r_=l=m)?=m6vwZ zLFjZDFUOoAF+s^ZCn`niMOB#3#MLg={6>!0=6LqcY$(r>AQd@_Qwk*z4{G-$x;vKT zK~1~STeb#kR9g**C#71n177b`#-@9Cc7qtmeRYY_evk<-FhmH_fTux(wy%E|6N1`l zyO!q*2Q$@&1hGQ3$^8IlF^4dV7-1@Ud6SBz!Cio!(pp!=CzTCce`3<4;b_nvh zSnvxJNMA#)3lpKac*fgy2VYaDC``9tvbd_td+RAk{hyoVy;73Z@hx3mN?QNn(B~U1 z7k5py$O%LBp~r(u_BvEZ+k@NdX&nZ?nS-tc0=_shFqJbqy=fQEa2!4E!!Nbh?aK)f zX7fJm#H?=Z30=(ggeAG;cKJcS8HF7lWS_AFx&y=pFo?4{q0MzY3RZpf?1At;#8qWX1ds^8$P=+DjGT%^#8yR+y zrVcaXOlE_KJ!k1v=D>T_3pTTK>;EulBgN+XF6nBx3~D_fH_~rplx_(88ybjS4Ntyo z+=r#TF~-Ly%<3T#570LZ8&Fl=i<+vU$QRpkS>~Y!W|HBX6B}-uYwW3 zHLYn2;sxZ8;4O=!+UOI>bECaJ<;->=y=BzuiJDvnf{-5w85(ji7xcL4DUc~=J?+Y- z)i4thj{W`)Zqs|j0FMV->K$QxL-FK}Gl>FJTEiY`zw{f13QK~VS} z$wl3Nzuf;j>H%z?h$$$e-<8r~bRO6E#wVr(JzmbzEb4UCde6x&H#$_-N(xX99|?^7 z;Qd{^Kecdx3f1@LjpqgF0PG^}TdyV}Y_w4`XP?)cVQ6o>b75OO|5IenRmG$&)X4xJlDf@F}8+AN(qJ8`N>c0Pqo}!d9OIWaK z>=_I^13#U8D2SO+2%_nEM}(hv?f^`|=J5k!ddVp|D8wEyElG|!Q9PZP|D5z`MYa>5 zi>dtN+vf28i@sJFMXWiQ8`v2WuxCq9Ik7hKZ0xEtz?KV%71~5mX zlAU2QW9lP0Pr{vFRS@oUQNdZVXMT;s!Ua3+0KZI5pYX@=cQ~~y;?^h1jl_PFw zjJBKK?8W&3ay=cN+)Ja?*2e=1rBT{Vo9`dxvKWSb_=^vjW>E&f(Jmj~$Rm1)Lj8D4 zzWP~`1iBb>CPz$MG|-B+knxp$-12$2S9)aNV!p}}I6T@G8sNDwty<^l{NpWc? zVYB{DPluYxhWw4yk2lv_W_U0a_Eoo_nu>-UFov4Zy8jtSF5pF5K9WcN6**<2FKWj2 z4bpXXG)5LP8q8=gg8LA&-FV0ZSN^M)-Ri}z^#Q{)nzS) zuE1QK2I4>v)9mX5eo(G2ixxYd0lvyAOi|lQuAlu!y=B^+c}eettBEKDF}7$qq$BKO zFZkMV5&l>g1W*9_ee{_H@Kg27GTmZCKB$&h9DUXV-mw>Go{%{`l(yJ$Slenm^zrQW zhF!`Y0f*t|`;_-xqK-Pf*sHOtQUCFGE@4XE#3!WIFH-IvWra|Uh>ns(t)pZ=CAn#h z;DJ{nKxh8g+Kl6}yV}B+EBK2V%btO!`<4sFqHN=){F#UMn16RaIpUol=v(t)*qa6v z66hZ^-p6JgU_lcJs|6z-{`2*RxDy}HOVL?|GKY%PcAIKjk^)|q1Vbl}h)T>dfI399 zC{Fls9IJK3JQ(tdntQ{S8n#8}Y(%@kedV%7tfbi{X&YB66gb(F`NY_M$^{@sy_}5exh9*4Jo7KMnX`drg0she>Puv4wkE-#;^^ zN^U!-wZ%tz7o+3y2-6LWgKN&rz7=*IX(+2stpLRB3{LM}6VRcb%)TnVPCpUJCHgJ> zSSwD1<*z88k3x7?+n^Wu^))Cn7S@<{Z61I#K+&jrT(CR~+#ge7w#7r(1Ye|M6J6Si zLwrenDs$3(&W$;d<(`NrUBx;?+m~=1{ihza+_+yFIvH(aamNOIOOd;(IzXL`y?@=; z_1+NR#dx@RXA{IBa^f-AJs!pZZd+&_Ke73wp&yr{_ND8^!Fa#Xv#lruX`6c-VN&VD ztfm{W{F>!MS|Y3}>SLM&Y^|8?e;AbB63c(L%}sn4gNSbLkl}1$KsePPlbWeGVcM&O zm)ajT;5S=*vELH0MiL}!o|ogG<4Xavgpi{@pf~Gs%7hWLX{C~G<~08h)xmM?#t$*= zSFm8rb5}a0*-w#u+LPh&h&hmC#*Vf`hFbO;Oy+Q1C z4unjAytd8G^BT7XJ@so1Prh9m5)Al|v*%f*7IL{f1wgw-aZ8K2I*wqYK8x~&z1uVgU znoc+B2JR}BS$pE{5Ej;AJY6qRuJ?u%>H_5odsjy)$;*z?0pciy+Zlc%wU4K^YJUgR zxz5UodVA~~m5+xJkBUI;xCEzo%AZ}=IVvi=z$wIjwDJwEzT86qH~SDs64H^*#6;9O zkWo5^Hiw-=-~kAAJrQu5;O{NczlS{tLf+P|18qbv5jmw2?%|~~fEyP~MmGyTPL_Fp z6P$WX+NB^z#=I|T)m6Y*Mk3#;yw8Sd-d-Fsw|-@QYCCvZknjf(hKj-w*-PnSFq>Tm z_BH`n_^P8nsFhVcR;i}D&3l@5*)#N8U+HDRah+*E?MFc1z_z}Un4cRDG!!0P7fj5?3)fvwOO(>DS09H8>8oPJBW&a3Noh0oW%IQyA$AKY^$FTf<$g7TeVVkO*v0%=rqlHRJR(JRFNueO73D*bzi<4zD5Te$xXeaF zqM?^iv;m%4v1L)+?KBt-WJ9PB30~ba ztQTFaLd2`H=mQjb99T2%M&Iijz)DT~cyY*!Cjj?h_;|6+=z?`S`)6Z8gcD|dr8bA~ z@rdx)zHuY5ggdAP zF4z(}U`EjIC4JvlWP$!5XttiU&zulrY@LDI^ABu=m39ab3vECW&#G4tn<=AFt|Ecv zrPOUVpDHNpMN0~hwcOTKMjx>qv? zT7=Nu@Hi*}KMK`HQps0?Q3kr>@}kr?{eB=nL!GN(qj3;F7;>-Vi zPBEq$FI3)rQw}+?P@`#ZEQ@4yRuhgjBV_It3uZPKi2#CnsKm|u&+Iba@ zk{GE0hOS$g`qMVj4|j0Y$2*B@X&m2iF|U-yj`GRwr4}RuZgagT-~bKqyUR)BKFHsl zL0UXte@2>73hJU#*jlKPCwJT`4Gg}YgDo3F2I#ORv zUA`~Ah9ln)m$fZzs)lFIMDBUnE<|fSpR@~nf55n+@~2rM_XAFz=NP{V$EE`K_5OX8 zNu>yhLjUnaXp5Wl$D=9eaap(N)=N5dXRlDGK8pDFX*N*Dw)yTn-507~v5#oH&uuU< z@^);(iVoD|rV7S~gr(>UyjKFnhQ(eGc@Jg3gjN z9gdHyOapGHDC(~ih|hzWBF-3;{7)ad{@yzGx&Ze}lahJmUjs`|@~=TC(T{QWsefLL zG6q~KW&et+PNw`b##1-1F74r$E{DM=@V>i=SE62S{82R5tKTRSrILqa_fX-IG>Q-j zWU&2UtcTm8Fb|vIYE}L!XO}aX4Z;P&X8olhl-#~$S4B}mFl)AgP&{w%%hNr|Qmm%k zeQP@PT1|9h=uHxwe7V@qsoFGv4uroed-LlJ>c~!wosqkfxDVrtjp8Py{sLbqxT|8x9}PI6BFMeT)XiS1 zY{H@7QzSOcpmJ*b`q-*;VWXjs>Qg}5Ev6q!X z0TZ2a(`9QxPK=)Uq#iZ8);wj23m=oi7cYTIZit+c5geG#3tRlnYDIFPt< zrTrB+T6;!7M{oo5!F3a7TrD-G0&PO7yH0HD;O5U56&0Tb-IBW9{mog%egwBy7=hEN zoMS)vUQQe;0FcWlrT%HpR^z0a^!A`8fl}4q`|Sx1VR-!Y&G$HPSm?H?d9#(u{IsmA zq(OWhS=$15NV}5j#Cxk5tcXLHpG+LGy4$~YtmkF zO%(#@J(?h6qoZ`tN4MVbg3Ba-KU2Ax&@rG}tU#2&!a z2j<aGmDGDq*X(o#=Mj9ym)}HD?&FyuVT;QknpYunhAL!i3Z+N>{KU8lS34`mZK#6m5N`%1^ULP-(qV!rQ#-9 z4zZfT0TW&KgM!V_@Nxs#-jfFfcKxz*wUcv0tA;x;1XDFikHSNV6>_{yfzP#o!`Ypq zx|TQ~&cQn4H7;d^hz*nrnf!%(C7jDMZ`jzt4sbzzsi;h4_Kbq{lVMyw`FWs($L2G6 zprxu)Gis7b#4YW0FSXa*Y&qa`mNK59$N%rw{5baN%r98CTGhVTTK|L*Y2cDG{ZR(! zdpcmmsn(lno~16OZNB744u>4ciTyt$B??#FAcJG+`B_OK{{D;UY2xIC^r0EmO8%kq z6Ergn)~uYZZo0-pMt^OEAa$bfjv z<4#tiT-xfqgkKWwp^6DTGk~*xsL;>+eN9C*aoJc@)ywy&+tnvyx852@Pkc-2e&|KvOIEEGPmHs!fYZA4NZG%Q| zQ+@ABP3s&0ux>PI{7b!?8iaEeT$~Ee!(E(i<8g$ZL6jiRGn~Q4Z8EsVv%V-X>;YUm|KZnz z;vN9e+;{o;#r4MoWaicUNNcB=-YVFwP*(1uUqnp-HDwj7>&`{R;hivC^*w~#e!Dpy zFkwVK)RvMnDbAVkH2rt;PDHZBxpT!vgWY<2qoX4sjCv98LEM_=jjlK55u=i~3-F_H zQ<3-Iym;V}>90;i&kOvqJB{x{#&sdHW>;*}m`ChFWe&3Db`1SoeY~h`C;tLp6wRN< zH=TWH$P`hXKJ~M2Jwx!;BHDS-TesE0megK|A}Ur6-Z%O|D3a&L6sOjnKr>SAH_$Y> zKJG_ub;_tMf*HNO*n*yw3sFV8*^1w+>lakM(rwXe@fX~dttLm&SfRp~#RB^YOIV)EpqKstD^B^V)Y~UI<6EB6d##PFovArlr z1~zr#SwbpI@VH9ooA+aoz3B&2q8^80pnMVrR$ohK5I3`nvHzDlA@rM@RL6}(JP0UR z!v(+XBDFQ2%DQlKxTZ(@fyS?(dn-m@;|Ndd18@4RRB*C`SFa@3IfRH{2nv)1en@D?C z+gKzEm8wIG_$)3*!3tqm=kVr6;K(0-TM`i>E%}N}-0MncfS;Txg7UbP*5X35m3hd0 z|N2*~a#1GJIqS(xRq*Xea5Vv-hC@df?89ai?%(!N4aQ-6jiqHbQfTMBzs4`qM8YsG zrRS+in{)7zdm*!~ho9fxY?gS-^WFvyTp}(TXz`(3)gqLk3t{ZVJJOQvFG)`sQ<+)! z>LW}7V1tu&p{t~R%l#!jNP$eRKCWZe{llx`cN~bG%dbe&MA}Gv5PLuS7kq#F{dO7q z)z2ThJm*Y`lox{b2Uo+sq3>8VV*to-Yjij6MR1pCEv_OY!CAaAI`DhNu&O=-#@2G+ zA97U>l`heSYPb3!b_nX`oES8gqjsh-}rJ_NKIRc!VmCuGp zNhJ*ZvRHCuOr7X=n^3d9WKU^3ea_K>9X|OACzB-x|@? z1;Wijers!A&5qhUh|sPNvzu^?wxiGb+hYz*D6rdB`jyJ2W`gqx>mKpdi~)<@Fym_` zRIA4fZ+lzP`rK82Qp3jx7guJLY_r5Q zhEkW~cj-}(m{G)p0Sf3)Cqo(ix+&{esSv)ch-srdX*o|B4u^&fUIvqV+mqn_NK4cB zDYrHi7v{th?LQM?8vhC=jvu8HKst{_6MIu`~JRec?vuauCsO z88f3QxG|C(gV0*iM5@@~UPygjZRMh3x9f%!FC9WdaKy;iyUk2?M>ik)s5sCLnLHA_6uUy3&EQg zpYR~zvu>Bd0}3%n?=wd6eGm(nih7Z719ojKlJARbDkIZ9UxyEJo?F#l2 zE-Op32!9|G8fh%E?F}J9_@g_G_^L3#-iF5M^K2R!Mrgpa$c>`}re4+&b1p<~MSETM z(I|2;!fS|J+`2EB32$OeZGS04ZXf3ME~NbNeaO1madIi1P4BPA(ngr+H;lPBLVD4b zR3c-4c&X0^)+{5xM&bq0^jQR04wDdt9RtV*UrW!FyT?kffCt@UncI>r8d zy2`mQc2B*c7?OHlKr7~}Ke`y4frzD3DIXH*eExcf5-urhMB~qW6Yb419h0}%H57fq zb_fen%TQHtFy&6XdKjhXGajkQ^x}N&sNl!;gq55Yqy7xgp&HOc{mfk%gIjzw*8NZEbYQBM?!u8Kbz8kLQ8 zzi%D%-z&4q9OphAt3Aw0fa4!?BV&;0Zc;I6eQm9F!yW%puYbk~;%1~>S7-mc7R z=nvlOfWD?2`EL3Sb&30xImo7{hjv*4*a}ayahQvtN`BRk&Uo#!{jC{{<3jaaw4ZAV zI9y9BNU^%5@Auv!Sbn{D+dOMDns7i%5dW<b$X=1@+t-ukPmRT?LmU zbwEnUhv?Tg)=pjM2YL%wPucRKoajI9Iv>!J+s5+yx2hvYIB-PXv(PRfYe2gjt@WTAC{sp*dDi&3&_N>z!%Su6&O9+=hcEG#-rUCd zz}D+l;U;cfJfryB%_5r?!0nL16e=#5L$B4#{Edh@AC4m!xjugM6%S z0rhVm^tccqF4NWfwPmVe(hS_>)eP~;z(1e?4jvmc#CrUWLDh7z-cmLZvg_VXGkNwYV@O_8K1~C&s_%4|l9{el--DOQXqiB*uy7Wv3LV@HftijwPZ6 z71fL_tQ|)cjL^`}ao0C0-lL!deh7P!$OOMn^zno}R&ykK;aNx&EUg@KpZ-wkR6XQt zH8~XlUW#-iD-mgLru(7fVFMx4Ne@j=_o7!*)-H8|frxiKsN%t;;wkVN({5}>c{72N z`eG=4F@HIK?pUz&zPjH7l8#DI-?{%J6XUJ^7P#UhhOkhtk?7rQVf(p z!uvOQkQaK71#TS1!Dkpq@J8xINO1Wq$~ww%ne^|NJa&_spz--b=*tB`E8tdA4xbb4 zMaKSf>bnW*zg9x_v-1n+v{P*5kj;J62q7BxiS2@=Z>M=MRBydoZL_?e>9(Xzq{Qn! zRLh6soJ(IuXP6wrpsHM*@u-heP?Pg~W&_(Qz_>bGr>{3o-o~zbeimt_hx0JECu1FB z%0lW!j0a+}$Li@hDeWdSGYjXtUQdsfA%QKY#e7-L5`h*;8eDg7GH)W~u^>R^qZfzi z42D13R=0i%Ih?<|{3a=X)lY$6(%6Qv*M1+?AS0`}B`6|X$jgBOtlP1X9?m9K4Fn^3 zAT}rR(p}s(a_!0&{Nt<_dt-CVvRYBP$kxk~7XrfjP?TY2&`$he`UEuzEgdv_na57| zehw`W7t*H63IBUI?GIgcLyEpHry7Y!9wInG5{j-dX{f!pO_s-?_M0094vmlO^6gI| z{}nZr&99Vj(9unZGC;&;_$LIl0{qN`SE#O%anQ}>IfGa3cPf1EqZ&LD0lj^)NO%%{%=;vcKJZtN_FrW_gwzUeI3j*&!{ z)MY|}cIOn%7j&0I-Jn}unDe@^YSY(qXV5FB^7^F}^ zyH}}s@A1eW9VvBEZE1fM79vbjUS0TDKH+UpT^U@UR3chv|Fd4MQUmd!O`!4i(T+l5 z**ua;vxe<=$t;jzAz<-MUR+0BHk-F51)aacd{R$sRCx35g7SmrJ}A`Yp}D%0)~_u@ z)T6UC`ODkm(u@!{FJVr!^kZ60!lXek_M}w}jr%N80Nip;PYJ=_Q|%%lDM7f0!~I(7h{V9diQ~)(R0&yXZ2@*FlAs2S=00Op0+b4 zP_x{Cbck{T;Sr})b|#zim!RM$+h;!PpLkIBdMFc9GeX;s3q9g?6i|*@Kh-WFJy9-( zsxE*UdE*GY7S&YL_-v(n?)LjZ^k{I<&!iNYw{GgQwyx8;&{OfQZb*{7{^?(9ao*XI zQm-F4Ft2qL%~C8pLiXDkM_Z4bu-%^yB1_mKHH#LQpH5e}AarByl3c7jAb{|2(KZRV zKydz`)oH2{3ee}WL5h(ag{65Qd{e$t@oSUnHyP#F#kBK|(eS_V00LonDf%nHtQiUa ze9@_Z04VmBu8G^13L~{9)yi0TxVLhC7CTOvtT(iyo*Zpm8p3(62}OCP@5I~jYp()Z zcK}>|ax|TK)%S1oHfs$R&mEw%SDJ}mX>nw3cmr{ooWnpcw++*9w~!y6I@7!Ca6s2? z8om#jwIqQV?Z=50YVEIHzhE?#)iCRQ*t+U$Z^-~sQnn0VtBOGt|C*EBm9-2x^7!W60fN@rT*dvE>e@1&zD+} z8x(s7=^Cy#A%uoQ9+prf1lFl#%;(goAA^MM0-Xi#Jtu4EwW;N~#yLob(HjC{j>&V~5P`!Jr$=#zn*sE=;{rZ=L2*-yS!T(Wo z6>L#0W93aW z)c{pDMs{aQnz1^fIu)LP8omd)?+NrVAhvT7_f)->Rd%|t#oJu)JDZrZ_U4iizF8gG zpKW2X91PiE1*rxTf{8>ic4D(?<+6HbI1yMs$kIYalk(=*c6aM3e;j^5O{lhuJcoHe zm!&ec9X;uK_S)X;5d;jRZZ@}cgz{)BLU+-6f{^8p!}F|DWgPuGubg_bMgC7{9JzfW zF@1*(1{=$=ijhpefuq8f?8CIy)i4E3idivj9l`uu?dS`yX zZZP733YeU}smNZel@&{}=)4(g0FFHc&Mr-7?k>lFGV8cR=7Bt=# z`&ww&vhH$QJUuWz*jMGMo-ZR|?(xLSP>f1gPA!UuRYe)77Ar4vFNvMU9%;CZYs-52Ox-4oM0!&zGj5?9TbfS8UVb-x_)KF~uL z1bb|JST4TMUwgaX-1GDGL2PT*x^&tg>02fiAkf@!?c+f@2&y?$UX!V=BV0=$!CsWJ zS0M;-k84<@98C_;FFMnFlcNv1dR~i@3p<3l?m{22=6~4VLa%3bn;5$WE@Ncfw0R<| zA@9dW_shO*K>vAaJDH_Jz2yQvqKJuoAFoVi{@n3+$9rVPYh6?J9%U|}R5?ot?RgBr zX@)uO{4ODQ{ae@O49gzy&yy%8m>;99#6g)4 zVL7@ODjmUt6Si4WdrRwycekZ~SyvN^2?`{GUMJm$6d%(8JO7^hYE!Bh^c16JCpF$2 zOmE5ass5Gguj17V2?YoZa{hGj@t-Ap&+Wtyy1F-*i(z5qIL0-9E|j?#8^-3^#Jpyv zlxyym#LrGsTz;DC81a=_LrJsV>SCw)<$DQz0G|Pl_*g&j_^-z{ySIi>PT)@@gZ-<+ z9UU$;aRYa_W}vP0qD)o+hnRQc!BG7K###bh8DSe^_ov>)S$m$2)&ZD`{ii8`GC~}* z>M{kyTppvvAqL)G2#JRFns%WwoB-6WQ>$10ti_1_?zNKm$+(>r!(3N^b2ur?a*EAA zT7*92{GoYQME^HW$BHLZi#LuD08(FAMZjI6ZPQ-A*>PkzVcsm1Mv~6I_aEsxN3=u` z+B63LS}imCvn4)?-No{SYb{}9HTw^v;89QO@li&3YPx|{^g!kJJpxB?Fqlnb*~vyQ z{fH$cigx(D>!+5AFd(;@2g#Y9(;>xA5vWr1v)BQX`Rts=i{}fI zl6$vrGLZH>3(rjJsA!V;=|AyFTqKc`)BD??iZMCX@Z3htK=1 z9X#~-7G;xn&J(k}x0^9$P%EWC-;qvc)^E~FeQZU$MHGo!KOJfx$DL`>PKM7Q%&TeD zpD+33pGTC<#t-p>^TZmShs*$oU*~)}Bbk8o zk4dxRQhgP&1A{}&FRXWX9PXh7`*mft5hXWm?FYz#J5SYrKM?_t)~)12WBZs=z@vcN zlXJOuV$BnvByn*E>qJg z9+iZSP%DS+5K#5cdR&T3afuO9VqJZ<-w7Kb_d3tmI0v|*q4K{M1Vz=sKQTgALoh(J zKOK0#3%^K_E8xjvc|*vwbxqFAA-c30TSwe}c0VHoug|03tK-Yz74m}X*-nq(?AA>q zSfKv6L_evMxYx#N7t=R+h1f+f7^UbH*1rIMg2#e!4VvePVe-5+qnPwPWIrsc*%dkw zOo>=B3S#sICVa{t;~KS7J>%!>dP;Privj&;JEx(kl4mt$<4nUs;M4o>Pvj zpPchP9b!ZDoln=pSd+H@-fgI2>m>m0sl1zY9$TOfu6_JkZ48=}r+oWQw{dpAf7hSa zt;V$hZf`Nw!u~KUHBc?MHNkie?P8eskm726?swoPO|<>|L^x(Ij-8Iz9_p5Q*`mAe zUOZwOjErq#o8mBS7z30w9Sbu3Ei4=HZPsrm};Tf^jG9)x6nl2dAgtFMx_sb6Z$--M1(&}i7&vTIdAO$ zt}vFdX}ae+N(J+io502JIQX~(k&ncn*STvRD#OO-aa}Jrcfn<}HzNQJnt?lu(et() z5XA@tr@(CtDu+49ZVXPX))HXoWr<6Ezpyb(I8wGytglqfWEn7S< zc8!DZiusTo-$K4{^NcqkEOSWzI6U*2&V!kVPM_=U&ug$%4W*@(maq{etg)4(P8dkmQI_YRT{>$% z69$r)1q!P?HgKEV{e=5Xn#(`IUR!lO=$s(u`=N~(qNBN&+O_*X2iXfq)Ynd+fsq+2 z(C#2e;Zpfcolw@C|C6p|5v_#fU{fla&8Nbu$uM!s1Ld}O!2asN;PSQ3$E<_2s(P!d zV|Zu!Imk zTzzF0!zJ&YH}ak&bl&YT2_34D6B2AmfCIww$pwMnGJ2Nhk<^9AKKt=zvvnQsQv308 zx9m|0=kC#*0zJ=0mn$&PlZb9QpGsqp7f zm)~X4%sN&;2NPuFBD7jf#iws;;`(e5L9M~VyH+q69cmpZ+0Y) zeecC}k-gnwQ6R^9ucGz?KxmBF-FC0dD#Anc`CWC54TG9vbVB@BqY%Q0wdQ_%GY?L!|ZSu&$Q?);SBIxgk=Z^7!c7Nss;6DC)<(_p08%Ael-l zPEnCk0L|(RKbyRDDPou59Qv9a=~4-%Y_1i$+&#|W@7E_5Ez#*OMn1Sh1A`Zvvc@^d zdqC-`7nU(w5r#eWJVFK&=}PRjd&v^j4@!J@(ac|$&}&vjytwsAKrnTBpncuC;1-%E zn?;`^H)E9W2BoC3w^JmmOhW7G<2S0GN<{M|sr$z2=~yX_2iWjenVMQF#Q+n?UPwgTq`}3*ozIM+K!$CuCFGT1B?^)DjE}c<{05hk$5B2ZclZ2m6-$oWNV(BlP>mz*M7t$@pL>ul!Qy4jd(xF*it8n&mZ>iH+ zo-$XL5p;?7o&m z#M*qw)foB?bfHIbg6!Pip#G^ImCC%G3<}6=9(^86HS>KMGcnc&)09$tqV7`-ax=GiOb5W$gZ}qZ4`E`M zEJKRbn?zJU;)OqjB9&CJXH{k>U6#FFo=ZxxxlveWe|gPs(`EtMG^PBD6PkGd%GhK~ zV`G~`UF%L91Qzjww~N1BYdTC*eX!%x6G|c}f;_PvLEF_eUIp;beOu!!=n30QY0aX-1o0%zJWg*oKD77nj$MrtiP0 zAR5jQxLg0J!fof<)V*vtL;HNyqRsrRAxO|^T&vUN5R=Pc^s|v{o*dDV?dYoJCvlwI zs0*+Y_J;wtT?IwK40a4Vt-CW(Z!4gD&JQt$GZbWixzgNejSYd@TOYz9ad z);5CKd+2+6dF6eNBKkc>=i3(eFR1lVx$SoSoSK~>=92;X=Nk2wo7lDGFF~9?7R48f zK~$pk`N7>DTm&4(w|jM zK`dY5^?}AYlGoavZk}pa?ryhIMgN%&vDviO}BYGvT%oCZ4Q|bIOH;1xns0m*azx>LA zi&{vkR3QkGORb1 zcO$Hr4nRVBN4KXQ)jY6zLXgekig5%E6JCo%9R+sQwGUBko8i6#MQW3KD5zR=uO-`` z=~V#*$weM9Lqj&=iW;l_$C4TGLyU5n{s^`Zg>^Zs**2@Q1S_Uo7gA9CZfarNYte3O zhdfpp@tZ*agwMKZ5t+oGqHk+R#gOjnx>LJeLNkeXi2d)%-FNVNLYwO4%OgD?&rOML zo1pCzzhap~{iYM7)Kt9wu#mcl#{pZ`*rM)QPT6XcC*oT;KkDS?&-K{ud&i|<>Ar1v zv8xEl3QcbK@VyO>$7hJU!#_{$bRR6l_Dk7+x`E}i8Wm|8mKl9iDzbJO7*J1rabyO_ zhhov=Q+PjSSJ5Qf-SA4$QC`C4Jwx}+wYpqSFBEdi)Aj4iWp-eSFtu=Hne69iA7&s4Z&3!b{W9HBvH8^--zoHd#$r>_`6Ph zZ%=Ale2c;L=u(vG@z?+4rv2MHd{3IgrsdMIm}GI6>z*a`u}a&Vb?IG zJ&0Kl;Lx4HHDBcX`MdEJLO%RU7@?{5wcJCK7r5ySsQFz5Q~@T+Beki7bcKE1+J5_Y z41$_{IHu2ANLbKwwryNYODx=N%d)B_&xo8jXn9G`C9#b3PkjjzvG$3*^#wb zc?!`dSqg&YRLQxLAl2Tc)Mg#LUrSiu)=f$@?(1=EvR)r?udDf-^6cDY0vnRWa_WLf zf;4Peg2n1KjbQLVmF;}%0uK=C8ebxXxI;l+*ej_Q(*^<6soy3W$`1u6snW%Hu^qH0|H|UW;QXEYJHE#pBP_QIaNvJO338v+{~`B}`fS1d zBw_UeGmt;C_#yQ-K2o+d@rkx+d>d^W z3;ScxercQ=fCSK=VJq7c9OeQVeAHT4dzwSTu@{L1X? z=s-$!logqp6evvof_RuDt8}Jzis+I+miVG)DHYgZjj^p}fw*Gzs zIN0{)m~}Rq7?{<%Y@bytEe4U~j;VitkH=+*-o2 z)WWk4MmExoob^nhe0spuBZ6wyHQps()|h}{neU1epg1tUT`DxsuKIDC~iDg+K*KQ{9M`t+1f-Gf^_AbQkdmF3G(XJ_j0WQ*m;oB$P zLq%_p=sViXh!WQE3;>O9iNX-G! zNT}y9_8JlTG_5zikux(?*$#&UaUl-oZP(ct2)}(g0^d7a@eMfU9_GcSU^M(+^!25u ziGoI+cp194iJE2?cA8IS3i2Kj4%+5M07@C!%e?w!Dn;&wn!z~-BNNSC0_2SHU{tnanOqFwe>1^bPQJwHeWKBnbjzzaQg`OXZ6nF zaT&?ldQ81#y(9``@4Fwj)%Vf(e`wl$ALHk`?eNsV?lDzKb3dgy0+ogI#(Dc#Lii zF&=s=P}f+;Ar|@~FFjEL6wgz}qpgKZhaI9I=W*agte^<<4ktk?nsB9V0jExBU>y9A z4peLY>-4uVTT&Yl0A3EL8JhEaLUPM~Ty%U2XHHH`nn0sYQ6ZJi8!2ytC#dr ze&`Gp@9tl6{hvoV^jkkNxY-H}LY&$~UpelEfOI!hXMS@EK8#dq$0K(xxaDnHFpy+=x8( z^B+K@GyuOL?>-w~MCH1E72~3^OYVQgF=v8HlOge@e;rmcc?Rp_JcyS(98s75oa9L=5AZ>fxWO7ei%oQ+GF+^%^C3ZJo`~ zAEEi4Z|3y+S|lCSC3c`NWw@KJDmu|KNB+?Gl#x7RtSBL`cS=xanH0FYDWS2pht?FV z&kYf*vLTEcgrd?9mR8lW$7&msgT`Q?9FZ!Tw{ zOoHHiy1hGsCJ%AoN_Z&2Yr4^$B`OugV(thYpeWz>(Q9x2Zf zezpJ1K`X!cdhP~I{RlWg?CzxsWx-*DebzObVDUBw|HL@=Yj^(PQG!7xE#~M>m+z7f zIW0UDYiv-)a-9@_9XYr=RA10M?M0p;o#@DMF*xy}7yn)R3r4+cp*XqGu)4iu?VZ?f z*q0nH>KA5A_q}Y&cVrwLM_V`hr_GZcUjrfzV{9Jb4#W$S9-FHT$6#7FZe+ACl3|j$ zyt;-wI>G>Y)%VRNBDRp~cEnA+CFcXy9mXa&H@^^fL*i4?4B{J19b=Yj^cxNGnD7f2 zd-5aTZ(hqfixy9Yc{~(_=eBV~@lEu{v%HM;WQCAPM4AG#mrnGtE}>YnJ$R=hx59@< zK=r3`jlVIz7bdsU%j{WKF5a^zm9f1#e7b#hVVeJnh$;-{YLVyN*TABj`Pa@)pqS(N zJwp9~k?YQjKZJY-uM;|VRNvekKr8W9+nV@pwT3CP^$Hw5pJqEa_h8V0h?h8VJIefIag0D@Q0>r zGc^H|hO{oVC#-;A2^L>}*zrWcfRN#;fhr?VkYh|3)QkowL^Tky#tZP8f0&A9O$-Z>u%-I^`ZD*0lBL z>!@Fg)8Rajk-vK%1H6heXECvIf6n`U?xDI)WpcY)V(@%x4r=17aJXpx6E+pwCU~Q` zLxuuP7F7G$+aB(>n8J;`Vq+ zeT3@i$Z-w9yBJ0qkch6xF%@&&EL+EwMMlzm`jS~WhElYO{BE@Ur1pWSie)vcBxobk z{L3685WsltF_p&+^5Nq;y7tkz*Yn)AcFWhZi=_OC^~c@wwa$|IKYdU2?b}MZP5Bcu z36Of#t?o^`nv2AIU#I=MS|spgYM1qri_80Lr);|3hH(q1ZhWye>Zau2t0pgq=)(T@ z{rK~~Lup`*Z8-G?WE)yAzU01Bn% zX0hR{P^`0G?vppHU_{xw@^1fBMd}5e^f~On}a^H&uZdES|JTLJ)RYj6RG!5`TvOHfMT@yizH{yWycHI%&8xo=K_0@Xb?S0{lLXb%H}1YQYAj^h>VQ66H|Zv zISyh%8h)F!uwS|h{NS7W_@S!hop;x^J7ZB0>cuqc{>6mBPAvH`knz~uJuUHtnKWkG zB1;k(+4alN;`PcSQ7o|4)$E%DQ(k?XgH2fYjUVge+Ct;)^72mfzLf$)U@!#nya-+- zlS=lFp5h;hrY**`l}KT|Nl?SvJ4~T{!Mf&CB)~D3`~)p$;kw|g;SYkmzLPs)MqV>W zd*X<)Jw6W~Wx@|LXUKDLvv_K_SBP!0sV4wXqMYR1T>qe{H!hcFjXBo}5fw^I&)=Y9 zwB-Mu)1egw*sL3n6LG{Ij}yJ!RrD!Runr+*|3~K?!d6>-9&y<$wjbLdeOsMB{Vh~k zbA*(@m?4^BZE}GMo_5h$Thimsu)hS+>iP%@2WV zhfY?nIi>7tx`bu~!^7_Zo;zzzZQHFBHQH(A8a*5mIOu+YJ!Ahyt!KXf%)s>{W`cA6 zMTg(=UG#$=*`u2&x%=MlX}|r*vXAkEV2dUdHk8dXg>_HEb7q62*~$lDP6;XoTlA)q zvWlGYI~MUV6MZ0V`{kPp6Xo*2SJ$l+OwEOE(Q8QvF!&N?g~3V`Q%fRTvwjIGFiBAS7 zdSy0<_MFf1wJ>^xtaQhqdidugEE+{2i&J2|tIE-_NpjV;pC3xf!#j4E$kE4ub2VAD zeyMw_oD5TMCS%69N!+r0e^@3<#1#IQa*Sy9-73uWR#cvq;4DF&BUhkKZ7yIRi6)Gm zt2_cYb_VmgO$I@~<=qY_` zs}UQ||9WrBWdT+1u7o>eJb&hfdW&C-(9&YlLWc^)J^IwvR%ILxX#IKpoQsBP61w^d zI1~F{VM_YRe#%<6xVxKbE82BsySH$h?lMZS^pgcLv=&HJDLgjR@Z-6#+aOjtZt$QU zbGP?b`Y-kpOWw9Q5_a4?@(`D~K1IpA))2p;1sfof)Vp%cqFyMVy8bX!eXSiVW~Wrj z+sOXQA;$hVb8%{rKIvS2LjWTfRGTu^)Cy1r{@?T#IR}VgBWPFgrHxi^mPg;K$>klwdC+cpL0fy)O`! zK|P^dJagwXgm!BQ9qfK~0L|KWpWfF$N1#ThK{+hT+G_S@M`m#czs3I$?UpN0hikt~ zh(Z2TiAY3w*~Y(Q1AG&?2c`{O)M;O?`XLVsc~V%!=r`?e?*Dqj0?*7j56%(lf=tdT z5A_iYdsR}(9aUKZ1)QY+<)i=OloxX!p6)M|MUT}ROXv8S9Qw<%n8z?52&=*L1*n0n zUsU=9j~xMs2V`K^Uv@D4_|XmcQ~&9EW1fm7&B$M?2{OI}MkzYI1qo0NVJ`)(@=q}A5R$T^4&(g?ZlPhU-UTU_86||+L zSK;3rWm&NaRv{j-NJ|#MP584II4)Y=iuvLqSIv9pGsv?tXSy-w^!(k4c`uK>wPBAY zz&Gj6beg*;Xi`NDM#9Q+phlXnb!3rhijfmvBx5UBzzwT^dKU3-Gcx z_AgU38tF(@an65M_|g6%tH%8lRi6rcy*jt8bP7h`aF3=LQ|2~YVj#YjV87x9Xe)4k zG_-FvM$9+0Jo-WpFU0-ra(?WMUPgm$dDiR{w(fp`fYaNJ5e3>R_}e`lczLyjH;L0^ zr18tF;7*Hq>{m{w24|Fy^k?K3p>uD~Q6RlH{nWb*$1O?<$jDb;Joi0?(@NikJred| zqaOz~B?KSL_*IwCol#B;^Hy_DZ)!Ugre;q}L2}=c_QNp63uT z$WiFjMo-Jmx}OKTJO&%5%&yPx*dL^m%AcUYajW2io^QWv z6a2NTt8g=oA*kLND44YCjva+vIX?xRy2)s`@?(%1JbgH^Z-*sVyBdiWg|uOnIkH-_ z6p&E%%;k!!Vlm;SpNaK(W&J(@SN9h)e;R%SQ;c=MtVUiL$LYjv{-H=ISSNF_blDRg z;kxvk=t~r4h@ot={xotnpvkI-b7DiYv4hcbWFT)~wUB6D7qQpI`XgyueZ-h8|NGru zKxhs~mz4BUHX`j=KN1Dt?Ln;|C`(*T&yXlTcgQ12k7VaSD*H7}_>dr;R`}+U3p(`n z7XluT+1dr|$N+CusH6&Gobz)$q2Nbd<0=$v-I(xN7Y#T_X2~F2j2Dd4$hkso%)g+T zjJr!^`+t6b@BijBTQFe8<8fjz-Tj9Puc5_@OK@L~C0(KL}1`32#h=yDT+r8F~WiS1lo73wqp!FEttFiIL1jv}WmC#bAUXaNV zf#r^oV;pj9_Q4be2m}Wf9avl1;=qhI-K^3)9q5IJ=GK@ckb;2Xz{bu*DI{tTS)1;u zy2-~hC};hz$gJ={f8Z|5v%Yj@?PjY6Ws8Okyl8nDHYXG)$^DuU$@l-53VW@!PfD(I z3+MI^Y|kJ4L5ei2J$<*}o6QKPpq^AAW}v$cC!)*~(E7lt-74S3EQ%Ie7|ZYRVYqK9 z(O7sbR8dO6dnFaDCl8}JXJZzGjM6)a8hBM}{=J1J?isafae@tHej!2mxay*okxQ7N zktQXi`+Asucm6b-`HHJ4s1<0 zen|er1 zJ3#-(4ClEn|MW~$BvEru<325yjuar^#N&OF1LkLfv3rJ1RZQEuO7tJAJz$iO^MoF2 zE&e#`2w4|F+E8Qne?L6qiVq-WSHY>=x$*p9+gifg3Qmq`$Zi^g`~mfr2N@I6nHNmm ze)gmNr;l*#n&=)~S8wt__l@#DW*P7rsm6sy-6y9k)aau2f!pO%l*oqO9LFJ6n?qlQ z4*Tkg$wpyQ@A21Z2ic#F`xRNrM+SfYYIVN_3n^R}6;xGfWs}uK(S*7y;SN78j!!-f zqlnE`NsR5zcLP8$Zt)A)dd?m(-&onO(2MEbOY-6Bp~C0y(&xFS!Le^=@c%S7$(pfY z77Ge=dwfuUxgmIGR#1(h9wu)bBv0C{iee%4EH840H+)UGrVRLDHU$JsmYBUQtyka8 zFX;a(Yll7zKQ)Wl^7%YM)0Z3t92$4gss9;;$F@$7?=BO(ZB7P8=gs%{0btPmK@i1x2+yim~cM}T%6}o%{ zpH8%&-d-~f5oVi#6Zi?RJZS=(nuQod~*z3 za>$AJ>y@REa#HuIDz3XyAKliM89J(`DlZ(Nzkcs){NKGdd(!P&KTFfw$~Qy_q6p6W znGSLO#~E|ap|*E`5mh6N@~FiB`W0tk!Sl~=cMKq@_(n2OO;!w}exA#vsP1`ml)v*@ zXoq{$UHzPA$_0$Y;e3(66GF&4ot#}98d?DW*B$GZoCLLWjl~p%`D*tF%BSxVHux0{ z&n|@|RQldSe1Ez-;PeK&iT$)>0WTgyi%*v%hfL^8)IcaJ09!&p_d)be_=l7$mbAvo z-h-A^dG&g7gvl(|OzcshL-p)&c;8re2?3{xDRMdvH*Acd!q2su31N%>`)y4>h8T}h z!qhumHe}@JVcCJheL#aDyIheJSvMOrQow?oCWF!QGVynKr9Q}FjGed5rJiK<#?$ID zLyd9C>6<&VVR9r;afavVwiLj$`9@J=$tMIGXj5hv-}~Mjc{|7Sz&f$xi}DO1HILh7GQ z_M9~KT&tX!o?A1%zZoUQMGMrCcA5{>Fd}w5F%VRh)1nSF37d%KH=rna{rECZNs2Jc z@dXZE7%qtY8awLP^n4RI_|m5zRX0y+-`luw!!vRp}C1;4g^;v_$w;y&hLwWm_f34NJ5+(Ki?G(*L=4FL5ku8Qk zG$?&s`dgLO-l6;}THtzJ<~41XjVs?R`i3&JtxB?$?%-4x{lT>uxL$Pc!`c)N_j<%_ zbC#ID6FbgyY+~b(hNOqW;Hv@g>V$nfBW+c!5g2x1J`&0*kQlSUAOY-#ELt zSO6_~4)jvhJL3_z46is&&IZI~NEqaJ!s2#+ADt>HAP_79@BTH_$8(`zGpyP+qb`W; zcnp6?49DZl^85igi9g5j;3XAF;!Rd^Vbe5k(bHjo*fmS~WaD%PK%P4Mzv<2~ z3Cxe-_REOZHE8?Rp8XX{{M9o>S@_C!r8Regn>FuQG{Z3(Zh#y)b$g1A^<= zAWM@!b+5^xuE;ndqSWl?S$H&kbg|dJ+T;3yO>kAVx}$D08bDzw>S}Z!ESPRBr^KA zI%nEw*uEmN^jK_4z}3ztB77{-3wp54YYU%SdF@qmqF;#53!F~vZO1PViqMMR!?V$i zeUZu$q*hKw5T#qIQhgZ*WHzrY(%v0Hs27II0>kg}kk)5Th3{T?|5j+doo8QVne2@n z)1Nht;yI{7QZTVMYLdRnHdSM^Cs)2=tG#-u2==mK7TH%$T_>K?73zisp__hy;kVPh z4zr|uKim+QF!Or}$a>YhhhvnRL#e)YKkBF`z+*8tMo=973NY=qwPIV_r>9Xq84+CP zi4U&pah(OHW|_<-WL{9dG)w8iLG-+hk)2<`(3<2ana4P>g7Go>;J8wFxL=Uv+23iaNsEjsUBvMAVvNo_RT%G zH_QMKYeZ1wnv^XbNTyplPn;kkO{l&`1|M;ANMj?}nB81L%-fq_ z?77}zZ|Th^3ABUx7xcMKaYTkNt+RFMHk30=u>6Q4Tut_Fe0lv>5b#NjOUu=v<8M8B zbhQO|%5pUx*~ZUxrth~Q#Wc?g-)O`pr~L{G{R{|Dknb;_LaKIRJ8W}3wxWd4jzBHE z{jce;h5d0;&xd;Amj_2UO@aco($>Kl$1LxrJ+}WXIH&@rkWKo_^FjA zRoFT5RtFmRhe_alNsdm$M8DE4Au>BmW^{sDKA;9Mv6SP^*Z0M6SWWnZtI39#GHMhu za0duNvu+EFyR(*3Db*nercTtcDQy8y8t@?pA_?kXR z_wHvO3_rD{WA?0_xJA();-`IkvOocjr#ol?WIStn@?7Th&dYJh<8eY&|DNbR0WL+D2~t`wnV=pzeB zyP<)%OCS+Gm+?&Gw7SNs_1j_s>Rqg31eQR}dh+9(Kr6C|h$2?*%-DPSZiTC9)2Lee zBawe`AW}r$sZ3^_J>nsdrW0Sk`BxvjC8WhDB{pohX+o|~Y5L-SY?L>>&n?j13Lu|e zv`u%Z&KLVYdxe0Ir~3%=9~@*N2;N(XgR!h3UlU%KZ%hnLDN3?Z{hi_2N&aV)g@7v=#)y85(On(7lVUo3wwRnJi(pp96FVQo#imZ}6s z3pi~nF3WzI)p8hvRF0zl!icxprtOw13u?h%fByPl!36R2g->5dCosrKcnUpy1dIvK z^w$PY-@7fgJ;!{nHp-)JfmF8@nj{N6Xy;vPA-T3}+VLjPB$d~9qL)G_5GKf>@^o)J zYzo`ruA8>=ezvF2T$jVF`Y*~7-r1hHPN*-V&N`!TAi_irXGy;uUBXw{4FXMmC+QS~ z&=3$>dsva7DU^lfe8zt(sNIHo(FQXxEBmmNq^3#zul6$cr2`G{f}jDH&P{^lVp$%k zm7G-YngLkqufI%dE{;7mi8ATo9*C`nCTx)r-XB&Z$OTIRZ?5hy?r#+;8`!lSe+@Se zaS&R@veIiuArjQikJ#Lt?Td_G$1p8@<5y5dct~MAQB?d_SrH39gKk$*&W_q#)r*=S zQZ-$}%NJL*Q0F)ficJ%gqy+gAS>ZR(Y(QfASG|>U3Bdgoa2@LS`5OiyimHt#LZQLI z;JT=`gEiE~jl6BCZSpf-8D*=gi!``6(TdYnUA|DkI`mMQ1JyAMKF5BaZ+F+sDpF+CdWO}Ry1=*^=2v>4H z%SelOalf88v-ep-4uXsr~00o>WMa_@yl!}2JJp8{T34&B!iKPD-nBWPS2;mrc z2>=yfPr+vcE8LK?MG7d3#2ar)9yhN{(MK#pvDY@+ zU=cnn`s9|>msNTP*#%onF3hP+q|gpg^e*YUpbYH0#0axZRJW?8T4i_nnq9SxgIsq? zL^kY0#L1Ev0G(|xm!sIFBlvn_WZ%5q!YOOq_Lb9S$Do)FEo#KVX z>rDbJPG+@x<{8}h2EIY}mV|CdX_vw#(9C0|Ph%`o+dJRl*5B71_i5`P@g1uTk>V-= z{UTd_{~Tfj;HR~*2KS%bgB5B%yNV>qW!dO^sXMg6w0DR-IV@Ivb?A))qxeq)6;tzd zx^9GL5In_|5i7Y*#w9$sI;I2k?XtD*%HEnzgyR~XozqKHox%&LUeNY&QWC&sTw3u7 zzLtm`f&vb*?Rk_YkLAK0M;Xffd_RucZ&Qt*y1j&Qa=B4`zVx?4Kv{o552w|!^}YnN zV$PY$nhKbxR#tIogyhw9T{f$ntp1hwRJp1`wZR&Ch#VKq2zEy*4zd&%o*uGm8E8Vr zo2wkP)_upOKZ>}BNQUR=x*UYnaJ=~;-hnIPn8ZiF@}BHF@km@vl7_b!@bw$szY#oa z=ksFVwFpS%o2YP_KTV68rh_lS%-PW{ES!9_Cu88L&8m2Oe2m zYVNcLnySJXC6?KKnla2ovOL`=#Ls<4+wyj2r7I2xgyJssuq8M4jO<6OB$gbBK?P>y z!3UjDVmr1O`>D-+Fs+eVDXpEElwIMDi>|nqK!MUtf$LuD*A$j2|A!&&QLg+xtQ34j zBQ%GuqtXXed{_>rk#4FR_1|(gvqbGPe{@1#8Gq5GHLwQ^yefyJ%D(?MyUJKW z^DnZ}bxuIh$%KHM)nu7FN4yu*iuTOWvMmF@!*ZG{=tB_T+(fpsVke&@{^0%3_`()u z`Tl@)!J3H6FyAm9{MhJ;R+Ht0ry)W~}Bt1!SH4wet z_9O3=L|oyuYDSF!3Nda`KAxX#&mYq_d`y&&xdjX|@@%~B`NIvobIkWz>fu(?Pq;W) zMq%jp{Ph-vpiz!hAO2Ip$DI3{o)GMsTU{$A$ioq9!dJK&X2-CN^GX79V~`y5k@471iM_ zcXk<16fbMsp^8&};eE${6kTIrU271Gtu|_GH@4kajcwbub;HJNY}<_+HnwdW@4WxH zxj5gqJ3Bi&i(VO>E$Fjy%j-D#ajof{AYx-)g*X-CIUI1f!+f}Q2S`N2@rrQ9be``)E=KXJtr z&XrVfz}b64`a6Yz2Qr@VOSp+kYf)b8;NBdGuO$E@iUZv~uzKe5YdBkGhGluUny*!M zqwViQBCqI3gSuclf;iBa+XA7ea-fMGr2fyr95ugKHWr7Wctz$r@6Wyo2{Tg(m3AZ_ zxpNO^;Ld=myq-oyd$2LksJ>zPNQMBMbJCL05B+b*K78$a2|1g{e{qgAvDA7Z5=*v4 z65XTf;>KM}inA}E*QG=@QBm%9K$X+)s#{)8f>)z;sLYeffj>P_%`g4eVdznC+Lt%5 zD9QXM1S;B`$557zH14$1MbiMLU`T&iUgTKzs-C)M$$=Po4wET&w_8ovr4rw>q-Q3~ zH)-8L^BfJDNll}Q;X80syJ<08>4-C6*22py!F{d0|594hlvrzuwOiOSmlb|n{rsbi zD)nke?C)~CFw+4DvkzY&+eRq+i5ug`$ZYGe`Jz}9kSZKu?cN!l%R2;&Q4lEcl0W_~HURxL}!?PZOJ)JTHkP4XFm(%F=by_b&G{B}hc zsP6*P6L=CNp~E2W6KhdliOc~ab({c~ZJWhbe@y1vezD<%IZ&53N7wnq%HhRKsWdAO zU}N`O;#bT1%7x4n#&FlEM+kPERpSqpJ5JSo`rJK>SN11|$DzV?szZs1!I@i&#}G)^ zZ$)?|wxPv+I!l2T=-4n3b%s&+GG!Em+5#CogA2j*o$DFh{^$7Cag2>te7#~n2sHB- zIgM8-%tj_|<WY%@UgRDfspa?Z>68GU)WQ08u+{;J;bB>Kyl-7=>j9I` zQr==r469k-Ov{yemMh)(n%k%9Dul@xbR=Sp| zTYp1~@^SLFsWO89a>2W>$4Bqm@E-bH^ofG;8S)j|_K9QxE}kkRKc%-Y!H9!zR~?rP z`k7rU{f+NcR6NRM*Y{;s)Oc+TiI15UNzsSHERph$dLUO|hWDRP_*?xU3hjHw7JCi+ zJ6f>37&JN{D$QM{Rfw{>ztAGn3sWWOId9fT>}()_Awj&JYn*%R*y|$-0rS{2L1=J{Hf9r z;$_h&bU$5}v}5)~^M=299GJdYQ@Vb2H{q|S-{=}_FbH4x@Lp7S1pndFTTZme_$RSN zLBm`Dr&*zLcR@QmTv&04u%*Qx@T_`how_*SU_<$F*zR`|m1uAv2bnK=SpnDAM!^30 zZUsAXjJI%%OsEIb?&fy*yAc>1Q5$bvCT-!k)LuqrzkRgoUl^Wrex|EudfvM~!mqnu z(h3JzbbD99Ll2=|Q4i7n&n+a!$#c@p1eMH=nU!{ulC^*+&NR)EyvDo-Xus_wlLEqEU!n!2aeEr7=LpW*eKisXQO6)r839-k+ z-}tKF`hP}xS^e=EL)mw^0Utcrbh+QZj`J!}s+9N9`;U3y#prBMLEdT9PL`?eqC2LG zFcP3x&7{{^XSiXOj(j+Rl&B$X$!*;h^mJfQzH7ey+58K3BT?|r_VpQR+vo3D*hF9~ z5J85{iE=u%%z{eDd9k|ZrUMi{a@5T`lzY2&C%kd7>g&wk3x+#ENn0v^NvbrJ0MxZt z_lYI)b!(-KE|cWaNgLuv_nG0vI=7@p7ooQ|+?3La_H*QS2_uX{YvS3QAjtJinr}Zcwd3{%Jc{Dk3ArYOc?I7QJqAGSE~lD8ZIx;hY>=aXTQN-63DK$=f92 z>q5QUab}W{p9chmDeRCazr1Cudf23hwV^vPY~Q~_eL7F*Nb0?d0iL8adAg)bvk)r} z`dN0I`H+av#w|Rq{=YS7`1%Tqzj|-A4DYc+Qno6aD&F(+{{Q2;vR4_3QW3Dp3dW<+ zB?d`Xq0k16_lv!b-uJ}Wnh&PD)HV$KmP89fLT#;?yW0g-b{XqGTrwzGxT|-Iyw-eY z>nwHK==O)t`iEzilAH-MV#RoO&vycC0P=G#u5$x=X*WsuLt@vydK!*37lZ$DXW}Vx zWk(q_VSY%tS80Jv&_~on=>(r(pGa`d+@!C zTz~w-`H(#BPLsMrWx$)W!%6hZKxLPU3BrZXb+?Rx|30j{N z6-Y#^XeE;nSn6&h6@?DtYsqn}OElO#$9_1WVH@UD1SP*`)%ZX`hr~^<+*>dA4DIMPsQ~jA$}Z^5 zs6fPid7jyUi%I*~5EVY>wYpt=wI*?i=Y0$8*@;(3?{mxU=g&QatL8RyZSpptLV6z= z?JhDvm`>SDdbxpwJYz!G7Fa@qlvmj2_65-oK4{%n0e=GJx`9y5=rsi>92n$0rs>X} z{XZ{<&K@2YDbt1soU^G&P~H|mXkK0>gv8O3--~P?lY{IY{P##TOh!t{qA@Z*mK^jT zu@H2?Q%#NoZaRDWIhfP(+Ea&EtyK-Zb(eS_4rn0B-;dVz6!L+Y&-Y>PvA<2e#7EuQ zuV;baOt%@k(lR0fbb<3Z2-#8bxXO4SFj_4AkJ`9^Z;|&bVyt=0wIq=malMBf zB^&SJK2WVXRC)Hn2K80N_Lra#6@kg2+`^0IZYY*+NYKY zC6Rz!7IIP%zu$`*x}?s?&ck+r11qO$?u5@p1yBH&O3!W*MhHIWAGl*4BCs6{XLYaC zS2;`f+1&Em1_Z!ZQttiU&!a88DZGn+-Y#ni6Q3T1j6`N&eI4_W+oCQ)?Ko&ZnyV^Gla` z)JoWaOkDxY$xV<=`c|uuURfde{{d>Et_Xk870E%PQ1qBukYH(3l@(sPlzh@<4y{!EXomu|g*Y?rXDD zf3;0MXOQ9_(%yxvIY7ecv#@v*zewuf5@t2TGY{L@NsoFFLrwf0pS!~(=%nuRTyI6O ziVdE2VtI;Si6@x1-UVLy=kGnfqqFrl`9F?eK9?iik8z&_*G~!$%70}bUPV5Pc4K(2_z?LcaBjQp&+Fy!Y@6nVT1C(6`|C!U8&Ov0utP;-$(s&9;&kHnRP25gPax zT+BQ`QNM@2!fRi|oR?0^r7fHo7lp}(z^{s->_-Xxz(pUfSR#A7##;&sS) z9xw})Pbd#;uE9|3A(?u%5)(X%WB7$r;!75T8s)^47F9>VHfbjiF97c0&B&)YpE*FF zS-0cOm^r|<<(uO0F=}e5!C$dMHnJ=PSFg^h-NFHB(n3{|@hpfSf*HMYRk;cnn(6D? zjkG3Az}Kw(lS1|w0rRg9qBhIN4Dr<-!;?=(ISaC`Ll5CWe}lV&bAtOnCeMeFLKeS{ zUxl4AHJmCVAJuhBTwf$}>EJ6Z`!u*i;ym}{w$+H9?&sBh^hZHy69Pe&65EHRF-kqa zLU-)E@VDHw;~i3q%a!*PC#}U^(T9G3PK%$}XI;%t2b0obr|Y8sOT)#*H=MR;T&6pa z<@<1pi$jAq$-SW=%{GotG%e0z)cf%9z)XQ6!j&w$n}T`C4(K~8Z};GM8qDM>gTO`c zbRT12q%z^zpcu}qFnJtnV6RCeZ z`=QU7@yt`<{gL{S)870TGE|Ad79)#5rSbz0k~9jx&g|E2D_Qi5>sS|KHk7`F>7t;0K4j53kwsyu_`s2f zz7t4+?4cRod8OdCVoTH#E-h0VkWpw7Z;i&GtMo3G(JlH}qN(6m4=FK9e1(O@HNRne z8>n8rb$qqkaO@?St+J@$1gu3l^`CF{x8NQ2S)zgeCj9jGV3s6bTRq{ZVY_HI8yYB@lv>NEb^;kHy`Q&Zu&*jg#rWak{tzbf$Mj|3xQ+ z@Z!8r7H<{;VfoM z0PvcY&c#^J*pz{pe-jk)v)+4?DY(nWXp_(c{gf)C+rDW(oyH7VJ#ty}crK6L^+8>X zaC8*ysW!_7jy*Q6$5oy~7h&JiwWz6~Z?aesAq+MeeRi-fiM@zH2dxDy#3}>F$@b&k zo^MPVHgZdRV6Yd^(Ki?Vun|z{AqJ&5snSuDFeh#QqwD(Sq$3bU_cGo9uo{!Y=I6 zJQ`QmV@PoVLcN>Y=?t`R+O@$yt7nEp9jg z%FHZ>2Ze@Wajr9|E(jLP9q*TlAFu)VRn}jc*`?7kCLWfDEM32rl37b;e^#DPLg=qo z&#n#3!fwQ9ZE*5D1RkkG@_GMh276Uip8Nj9f)aD#FhT7IR2Of)9|z~bIM&{E-4w_D zWrAD(eq~R)&2s)W+;nBED0yC52{y0aZKCQu!CyTYTyR`Vh(=;;XVb|BLzIPXnMf%z z)cD*KZ%#l6I>pX?nF+NAYg4mrx$Oc2U&5_+xW25w1sshFAa~@}62CimK&knPB7y5#VXbGp6nrAe&J|~d3{`v1+N1`W;gJN6B^P&nOLas~0 zX!~~*ar+C_<-tyzOw&?ZjS^9U3<^%<-g5+?z^za(o@nQ7%HyL~pmq;Na_QPX&SVe* z=T3J-X2|ykt9Pta*ugdhKN3`{v_M$_6m(NORh<*w{V?iD4E*iMc_>BbdZl_zi2ht*pMDU;y*5^C-TB~S zq{)x``?!^CYKG^13UwyX2(e(fxCilxKdw`UQHB!4kAnT=)r9n_JjAG4v@CoTD`y^j z_3>pbq3OX?kJdO7Y!he@VuXxCq<%PA&jCaB;ko#r&&O;OE_5i3+pMEPBDDol=9>$3`O$0AbiHhsa@+Wd`a`yls`0$h~*sG z)AJ(aTkPo&eq}kaOC&nC3TrHEc_F9S6D1FJRDhCUXF$P!rW3KbmCjA4F*#HhX00k( zAw~GK3Rd4^GX-MrSUFmchyZG0Q@w-%itBU~Kif<;h&+2+c`-W3v{VWGR(w47j(g!Zoa!>w ztHyN`Vfok~-g>V460Rw$NJQLUG6kMM9_MOi7-lK41ozMT-KWDtLf#u?`}++5 z{P-laWIm2bgF4*ttAf)}3l{wcf%oeDl-C+k89XEE#^N+}eY+FeMmoLn$IiSRg%yBl z%2k`}=Zn|@*D!Ri&gUnJ?@z0EtUcsg2K#y>h7@`%PKz^XiW_R&r8#TaGo*h-hu;0w zJhxd1lo}u|iXA3!2sOO@$usmj|CSTSD4)n>;`tjlWZ}!WQz`|9q+Xzmb^xhWA?9Gh z*6w#;%&iS3{3wzGne^p6{yU=K9GUx-xin;R*3t2x^M;E7T7HGGnG~Q+kZ05#kWT`a zca_L(6%d8(L>9C*lR}N`XMJ5r>Q*=2WPNj1iw}m^Bku%5346SMsRQEe;cks892;$Jp2sg0EBpludNo~>}$1Uti2A! zWkf(3vfi>0PmBRs@wNFd*$|um@7yIj9{92xyB!|l4@U{Jw)~PwYi@9@2itpBB-L<3 z1#%wW>L_6xM&@%{?6%Pn<2YlPn&Q#k1v}U7w}^WndZ5lAVe*To^#0A&4_CW<2x@48 z5y@0AN3;6nhU8fG)yA!5w6joqH}4;JwrKbN{pyq?vrXPRsy>=#nH!243j_1qAyBOF zN61TS?B9)!{iTX-6r0Xhz2#mNcJ^f5$S>um#5P* z&E{z@<>HL1jAvPIpg4aNeGX6$_r*mH6FN_W-%H0&C<}hwqo$|~p6rIb{u=7d{)hpw zC%f4NgIFwkHCCV!`{<4X#Dd|f8`&KH{J?1S#!Rw3PSN9ampI&Qk@3_-iqD@ZL zWk(UTA=P<-U*&)!|8q|igZhKm zruG<=+!p9NU;4r)hc&{Pb`|fVPcwFiUCPr^;$!v|odI?Shep7JBeCn|Kj(gfsg%gR zJw{+wuVG!*K)V(XIsw?s_`bVvfbuGNqN9V^cNI^kF8Lg*J7=}%U=0ZkH@3f2xuWbK zfkKya&Z@VnpnYE^usHYH+d{{KOJ^?)7rn(VzISGIHeesRQJ=pn6zus~rQM#?N|qYx z>b$wm2U+a^xZ8uyT{SzjiU==ZpX}!)0DCTvQq|-kf}XS0mA3Ym?ITFfelNFt zC!#G~<=yxp{VPboFE#m>_(^2zdKNain;N7EVn>Pmd7?<|!Ghf_1U3t>kl8Q4k)bc1 zU`VAF+mB{3i1@0ALNFKVZ3%O`5sJgmJW@P)aAPrGd~CH~z33P4Mu{ zc9?+F9&yH#xi8X5wzvLYSLzri&uS$3nh?%FDBpQ4lpG{Jp8si>ucBdE?B$Hk${s`g z>SEyxZuI{`C!$6P&mq2~->xt}gCr4<>^pSU9jXKX2^Of_F#jwtn0_C4XL`|I`@Y%y zO6n}?D7}`^cX_O4uj{G|@a8Ym&+gfmndf9c{ha!<_U?fYx&RNgVLE&+&u!sov);O# ziL10?LPR_y#%JhuE55Q3cl_b{rt+gR0Z^hqee$$bLQryP3u%7_52zn&d6N#(Ezfbxngg9* zP;LKx^~Cg<@ziq?%n1T47#8fjW6^MzE_2m84LRXYGTz?_ABqE+MwI0-^WMNmqUdwg zR4A#RoBuEKF%ItP4TGJ0NVQUN1Oc^UAm>wK%ZcmP}Q)GELczJFGz<~k{M#Tpk*w%#=&qnwm7 z)E@6$(xzWcZe@c|R}6fo+gG0>6VR8S(5G0pX8`NNSu8h|qj~#MQ`~FBP)yLmc2YSQ zIS-9%GT)R5wgeC=pHZ=-=>P@&T7hi`&yyuSwZ)KqNepv9v}w8LxCM={X|~eA@=OrH z>(*v=QLXBh2NR=uL=s?w1Zq>a@hT}Zusb%Nzb3_{J~TvlO4E|OyBGX|Gip7=AgIwX z;P(qYY>yEAZ}$IWYiHzQ;|C!tqKbUw%$z+DSa1m@AtW^y+KHX7=2c$II5yKi7zTRF{m zTnB{y4{2_kEm5C@woe>~xaxIFW=H6yHy7i#C{tQp+ zhXIr^is9U^??v#O$rjig&&*)%@k;?CV(cUf!;Vj(wy@2+Z>opx&KQalYpsHofP#wU zyaKbTF$QJj;`P~q?JOkS_<5gtsda)~+<7db_jqIfR+c}qp^nnNFK1U$06Y;%; z+s{1=hirvKybgMl)Wb0w)R1?Q3#n&&@608*_A*M>Yn?~uEB5mD)u9xMqB-n27bMR^ z9bV^Wh4c@+yGjd?3wzEJ9c`FuqP7+K4cuQA2B*RL z<&!DFLz#NB?{?TAHye!RyIxqiOgk*xMvbTeWh%vr)cltqB!>+xKMxu$M87CwuT&Ef zWX2_CDB9GJy0TwyBxlXIS1(M%TxHV0>9`5=hb-oubMFhK=Xn=AkyLE6N)md@`AYh8 z2PCKW6ISTMVWrXb{Ss5LjmlFnX&aE*mV~}&+LSLGurK_pDfxOFp!aX!z_&P1QqDSt z8ujE)xBJ=PsEjNI(};R^>5*6;f#+M=<#tM(N**KKN1Ik1k!<+vnQ_>{!PRbtZ%QqG zrqjx%^Xy92#17RizcF7Z?@e7|i|VmY!C z0zf8-v7hEGC?IQ8*%(>Y>Z4I6^Y<*cx}n@D`1)&Ja7z*AI&@xX-lj7F>-IpJ*MF%1 zjkLMDeNf>H%1f}n)haAvHNRbxv(+3Q8b1v}*V{1Mo=wdULUeu-jelk%9})bBfH`7! zG4m(xN^kYmU+3W{STM_!nFh~nsyfX8Wuwu1Jh!Dj`2*ez^Z-RfXBd7Ua3saq>@>^d zg6*XCa}fzlhvAik6EJ2iL73lkFZzDahjq2YE>aT95o~mf`g-1_{9l6{ErqfgN3UER z{hggf5#irj&uvRA_(L)9L`YlG*X?ztsBrN&7t46-J@!}JKnl=+P4!Jmh8{2O%apQ^ zX)+54timKQX{Zr9Ih`_=(7~$Ra#Tj5Rs@v`(}48cq*z*_Q)@2I=N^d8WGbT?-E zh)cZ&=a$Y99}uaq<{$A3wjQlqW~joIfa>v# z#f0G4x-aKv?Fzm_07M9?Bp_V{z&;l1ztZ=fO~J_8>}p)EYLwW-H+$RDuc3UI6&1ne zT%#iT0XHaVF<6 z&!>ABRGWZ>|0;d;d)+z=rEt`*O)r|gTQG+a$LfbQ_v)QQBlp=nhlgsdZ7Hxw4w2`)m!A7 zfa#ENOU;7&-Z%uP`p0xUm1*$d!rt?U03(rGrT6QR<;^8!r8RpI2#bJY=eFr676Nw@ zbW+Q$c?B41#)H&LjWci}5sYN7G?_>!d&1rK6yzns+$41SaCxx#ngNsr)^H-jZyoqqGX#K1RS{rB)qi)!qc2|M|75+PE$A$ZO8v#wx^j zAJ{DNN=GbaQ&c#ZY=}pn#q8cW0cD^3R&TD)Yp*DAQ0YG>k5Cv)3`15ZXMmPAKg!8E zj}}s|SgCen!2XbpT+A434+=C_pV3Q}mfZp&dC^S`X~+c|jP3JNw0QTv!=Lht1`0-Y zl{jr!U(gRS%pE#vaB{$XtglX(9J0pnvM4BqY2U3fPgiJv%P|&%Ef?D9+U$mMcpM2I zNYE8u@<*rY7hOCE=;=G@6o<+dB6y}#C@dHH28pzi^R4+a4|*5R+zg9BN(4kz=GQBN zv6^G|YxM;f(~|fu10!ZbQ2=^739(IkLLoSEl1Tk@i{lf(tZTnp=|lbq2Z zND!`3SpFI5?Q5eCPaZ8L<77;Q*GF4{Mx9t}7wpbM5j6{{W=SO9YM1PxdUyr+n!?R2 zO>C~_KV>nD3hFis02oNIVVc~=(Sk^N#t(i~dkNG+rBeU5j{j%ZXwt7H|EG;x=u>7P zXOh8-%<=$tpCz!fq>aIe|1lT(lEKxbK3%%sxKH;qM^OvTd2C_T()AW>S@nnF0XbTT zd8VJ0%d+Y&$mc> z>KJ3dh%f&$;``KWfk6vxG`MmY#$5djwSv!*v_>H-kh{sghEQ--mQNB${1bgn>*dn-mH1g z93T^HzxB{>I&hS=qT}NS>voX~d?>58N35QZt0}6!7p56wU}}}1Qm8_FTeeH7CS|q zisVp?eLwaJJ~}G;GOeeZq2%HMSQglm^K;M+V^~~$S`Q6ULZ=UzR=@4zl6pLR108J| zg6%;Zziz;rLvMp`HvUQrG+Rr+yR3Qb${~d^h5hk1Su>%G74&=mv?wz|bRz}D-t`6S zrlH6`2;Ta3U|)t*_7VxqT2Poi`@B_Bs9La?iP;xui7hb zo}q1H)U5|Xftsd;*34%f8*0XnXCBUTACnlZX=q*? zb7r{idw3l~tRI9K&@(%Q?G?i0OXO7zr>VZ|B-K6|FM}#{Ld7GSwkjmlLd-AFsj)bi z?t4XTRgkYEY>GQ?9)Cr{p<49bUfiP9xa&kOSp_fi)dJQoQ%y#f8UTLcgPVId=1cqm@{{_DTsBBp_D@A=c^FL4M!ZK570^G~6roG$ z9v48ar=?x4;z><6J&u;u_^1w;CVwIt(7@@Zh!z*Xp^YVOOqSd z!K;(iq`Cyv;@w|t-Cbwm^7HB1c|~hQnU_L(CBHgah1?`A8Dn&$SaK#lv6!tigi`to z={?Umza`^&SNITj_U*avt8ew`fcuEA!-6Rv#aN z)5yniBrwgTcF&Hc{6CuRBrD9^9#?YRSJ_~82sahyS^k|MT2bgwC1LDTc8s;pL)OE& zu3dJl0RGMO(26+8E8Q_se)9^aKdY;bp9ulLde)}bf~PLIvApx`xyvck6ks=%9Mwa` zz9RVTu2}IAF2R$P-??CytfqxdcVC`{`nL{K{oM-*Xf21|T&f-38o&ajn@QPYW4}$8 z?M+c$O>8g%3v#xx$Ib}S;?45&wsFnK_4foCuPGRo#)Bu{Ju_Co7s;u8({{?e(j+aR zOM%-39TH!bD#!J7{!8)KKWa%F^h=xW&qP-j`N4A9-+wuy9|0os@8~#@Gp1l;LAzhD zWjX?@?hXq?vUB0d&RuF`)S)!#Ew@N0^X4 zJdQ6#;S$`AQzF_E?7-HCzN9|sV5o!03h8GT>3#%jkL#ccYhWkgD>v3PIfeX zuDRj+ulr_acz5RwsB|fT_3KIAyS6}?7%4#nm;QlywFTdCo&k?s>feTEK9x+nrUI<~Z*VhA2I=)ZgeB$j+8U$gw0KtSgm3tEebuV& zk@r2)VVqdJ9~tFLN`Q8*Lj4lo-88Is*sz0zxG#aCCxz|M#Gq0BYW4O(B%qSnwb@x0 z0zM<#WUOOa47jO!+#`U&=!xGp%Rc_&lO^X;CeO2s7jq`u0upcQs{u~)^gyo9zA;(v zZvojpX)i#~_j$h`M#GXM^ou=(+eMH74s*g`oevWxW>goun-artjB1^_rz-~v)3iOc zxcz_eaIraFB4rCyafKOUduzSu^%_82K58j zv$h7TVjua-e#PslcJ~!x3v5>8gVJ`LHg-kruUA{5N@eoCe+9i^&QSmcXlC2y4~3Py z(s}KZr?Z4P^2=bSDOHu3{>Ar6xV{o3C*Zj+REvs?gi4dU{01ljoF2tfxmV}CWojhx z5le3TH^&-#mXU5Ef8p7wcZYKraw5H$rKTks%FTG3PPP1ROi1N+N3(Hn8uY_-?01lP z)0S64J02stiNTvt-VV1TAwqpjW`(EFl9xxkC}#1fBk-^Z-w#;-xq5(idXSYr<|Uyd zda>s=Ft(%R{`gAJo+49wZh1)HBamPq(|Xl%+kpe>Ilge% zcZ92o$vsFc1|L){rC5t}LeQ!8O5B(33L>aGNSJ-#-ezG5!>SWHy7pM-1*cT>_Z?r@ z3uOd(4_JtCxY4U_HQ;AM_3Seet~^EoBXr+ATkY)km3TbJUinLV#Vo&vQ*q~o3KJ~6y`_?uUxl4S#7G^tGlsGbGfqPnEOg0cLvhl&qLw{o{{T^ z*C*bQYZ+1kh-!~@0?zj-{pke2dHS{a12r2<2eO25HT9>=F|q2Q%BI=A6KVH(xbJ8` zrOiJ3&xE@Yw%&yrS~rRy;8A4z_sjV&VxqMh>W(dxoNw*_862CN5)ZknUJsASEU(?a z5wMTWCWO{PtYOVu0o)Ip<51U@>$t#KhEjDzZ(({z6>_lk1VQ9BJRaUj2o1GlIGx4v z4p8HqLB2<=jH_`;O+MmAQqO#8UhX6%zV7Q z-+c1auc^yvodjTwKSbWuHxc)#2c^RB@5@9SAd}{MWyyiH4TgEs4Z7kW{Ua4QgaYzi ziD$9xzlS35RuToJsS?<^M>hO6CVe3t>5Sx;M#bQD?qb3Gd{&qjMrrOLuGn2r*4x!B z3055q@p$Eyo&t6_i@I%)>_~dv;5g-e;R1$`nFH2D4D4uc@zkij_>CzLF>~AR-%r}2 zGZbAv3dd@4=&zKj>eJrRC$7dY+d8(&;h;U=7M}jhnz(+euC{mXkxm0r(cfJDF+XmT zr-2#b{`1)HKGp_TP5ISfY3%-)%>E@oLeA2DE5bG?LA-_2BA5Lu*m9qj(RDphN9rn2G|7^a{5A+Ug)^BYJ>Zx zC5d}sk8EqM#7K(Y0Q+%|pGz6fKGKFlHXKUaU_3Gw_~Zu2=6a0h@XR+{z~||x1in{Q z=QeyKueWu3iYW#%(35zB6QfS;Ir1B)1hbRS0?D+YlU9Gm8WLJY35@^?GcwM&*Z7^ZEt+TddQvQxt0$iY z?dLpckz+bfGWJRWUhxfDKpBE>{ew;+Q$Yi8c(GJgSp2Yn@wipGI_#L$?Ja$(*Ob(u z?R$RLcW`hZY)9RxXO z4bJ}of|#!BPAZBMJw!tNt zqgB-sVahzELiJ4VM6efak2K)B&zgB%ZGNr^zKH^jizG^4I_;RZdQbx6a^=aGQA{Z> ztQJY;yX&?P5~q^1k~}j&T}sx|_F=zGipTmL>EosIXDHP0_yPi91~qYIz2{a{iXa&G z0QH3R%hcB^Pu369#|zW7gj1EHixUPFVkIoT>x@Y7#4$+9+%6ibC{C7A7UQa=d$!{W z7T(f4?RtiPO8-l>Hk=eeqqsawK4bNE1JO{sT3OAPp6W6_3ZC(J>FWsbo5eRTqc@D; z?83oi2d6T?AYjvN46io>WW}L;Q1rD+@5DVXS6MbOim4M}o8@dk)uaSFgq;bsWtqpD z4J81$oLUMBod4-kdX!zy4t)sYrfnoIVr*^6MW{XSVK@RzP1P3@4I7HSJ4hwY7Iqe3 z0KC`Q_2r4@D_c*?qE($P7SGxwmpEo61@2Pg+g*P&++MGuA8&(iki&K#T@TdhSKtI5 z@&_JM0ZZ+`9#6CVO{9Ttl!W<+(6QFay z0cMECs%Il|SubG=!%f{L?6MH1%oVl8^R}g;Nz&m?GKqlQonUK`4hdkM+d*I3q?!lC ztJ2~g-V68Yy;bEi`4^8YfsY#nyGC+QWy6%O!ooAXBBetTQb!s!aK?}8`z3O^O@kn@ zH~t>BOZTe9COxFzp$u98385H?id{ zP{KSuo}R=Xo_95Gdj7^RVL)_lD0J2~n5q$tvcvj+TfMn|jIP_XSy&{xllV}al;Vy{ z?M5UkX2{ahLPy!H9GK>ezJ42-6V3>93apG?F~E?vADy6)bwM03#tiEe-v!}mHS%~_ z(m4K(^n3JqCpu&OYKv+<_@g%=Cid;K9!M}b?WT^*Og;z^ys&R+)UyG9{`4>FffA<; z?7}}Y``0k`1ZCJi;~a_={^TfF;JU?wmj1#!~mXP;6ONO(IxLU{?u!IyRn4!XWyK9vKyngxRh4LT-J%1 z$ke6a&fkO;(Bn(>tSmtVfZC%OFR2OGh?Xp7F5d=hC1}Hggfvm+DDB`;H;aBSCB+yn zSDO%A^#PWl{s9Ddy3)%{a*YVUJVYRDMlhd(v#Pc!t6C#QZls95c!L&wX_Qf>0|skSlQXiJG+{ocdzG3mgAlh2o%-jS)a*YY93o)&=kf zb5apWxcg22p>%K$ZqvTOj(o)(Z{`ZzXIXt-Zn`s=XFqyVkB(o^v{@dp*U&EK#Yn^R z;$%!TyijCk{Bi7AyW;kpe$t-1)AZ5@y;<$Jl61w(bYk*K@waeLry=~v8E(_J0RY09t0c(XDFf!L ziVmZm@}-y6_}z-GKw%)e`MrROXwP`@((B(TF((2DgTK)l4Y!{_Q|&TIc`+Z}fs*O$ zWJuVt)bed=Ya|lC)>+8#`Q-^osF|0wQ{!C?Yh|sfbJ>Lc|9!57`-M4!L0E5dEkOBJ zgw2Id$lhjuleFY0@V&&a{#$0MC_}ap3lh1}Dx>oMYm^DStm)tVj3D^lnh!ey)llKS zwl@1tY`cg=Sa%MvRf2iHRNXe-e84*x+-mQ7J~5156aJM(Pfn zNKZ6aecyhtHmhlUmAD4Oq_!f$dn=Ry2FFJP7$`o+5tt%znYdYKQ3y=1YSfU2(YI-M zj5;_bA@@p_iS&7n{`OI-7AT+Q&;r|R)c9!nPG7X~E~;6Vi&|SDvUn{vDLyrUlYh?s!HQ>)X$F`gh8R-4oLVs@Kg zbq0S?GK8f>KGHgI--(_GB)wDtfeTh25R@RirKZK;Odsjt+Y@~osfh1ZY|Z-l4;zjJ zy#F{l2ZuV}K8$DEEqlw0OD8XD*|u$S^~-k4ty;EiFWa^|;eGc01?QaSIrsh5_5EDX zqTfvjgqJN9XorCtY9219{$P)-r)RP#!3~$G`Mk{4;rTyC7j&f5X69}QVG!1?9Z^{U z%(F3*6N~0Q4=}TZwpQWC5v*an9Qnr7Gia5>)ENns9Rx7J0n5izZOvS`=(!|!c=y-r z(P+?%D4<&PynP?6-(n>Y^z-XHj{fFzV?R`9Fk?WeXEtV8o+cIW`n~+rr`J;R>6@^U z!=*M4a7XoJy4k6e&xC|e<)|hRn*{iG&QSI0(Dc*j_6_)XVK@2@@G~`Lz~p|so4Occ z|1)>~v)Yyg<3>BY-880G(1d>lL*~Uaf0OR9-+%q!Vh7o%CpJ=;ag5=>BS%G|M*vW0 z);kw7o$)2Qaf+ypWC);HQO7hdUlrwFk==b+bTY4w5YJuf)7&Jt} z5CGOqkRHk4x_VqrK^?437wggCLjO<%xvfly#?uY7LORZT6{V^nayL1am|<9N?by1V z9k`c0$#B@PeV0=`!}F+4clwyfLxAP!>hho9VL;WWN?bwq5C^`K#K?oqf4>0JuIFj* zqPp2D*IttziEXFeKmAc^9o7LtdddSOH=7?iU_?*LE^1By*<5l`b+uYJ8N>k>y9^S5 zvzUA~=LeT2RXeqf;;qa_=w7a}45l=qd@u6e*#D^nP^8JY<8nedSmTxXJ)djHvycsL zO;-4kxYBD-u^#|tz3PfiACo+Sd;-VN z2h7yJ_h8ox1A}s{0^h)W4dooeu{ikbNIR2` zK^>6oqgz^4w_WB3_k_j%EZLmviMH?_%6s@>#2wyz+U`K)R(tW+u~D1)XiBT9f?67Q zwEXuYn)>}|h$(dMrjuGpp~vCwn$eFe0i7Y)W25ow5YHnW7)9P~Fyvk0*X4XwtALzk zli>~(tMzP}eS)=CRTTarIq@w)nHDwJNW%Ro7q<@&e6O$|se#=1>@qa^A3fj%8?$fV z)sR(!yvfh1>ny4R9XVVPvFE4nJGuSWnL9i5%diCca3O=nk=$;rGpNbaC$~fPK+(hr~RNHXn9{5vs<4 z!X>o3K78(r2TySGXPHW(8s_fK52LDn_<2l44zQ>8Z6Ba@6;%HU&%ewLnUKgA0hNGe zl8x$$OOPCxOtv_r!$%wVW|cE>K6$csjDhPawY%yC+?!aJMX9$It*pV8xqg50$j4oa zWSnd>;K&YnSzecC706{4={Y0Nka`pH3;E0O?Hwf=8(ybZUQ5tkuUyIr(@KJ=)IK#) zo^J-esD&F-NQW*t`F{FHOCE6`KX}*_hWr8*m zMEVHd1d*`}qIJf3`mH(RsQg{g@Dj}ECVBPSUvCaabAQxBM+FVN2+4@}L`Eg;H0#H6t|{c$MkII(e&p@X`u9U0Cc&&*zUx z4qw%N3g!DcovvjQ-)}($#9~wza2sbj`ghpnFZv)#^icK?eW_6{Oi(Ajh8_w)1Kwa7 zXVBD#+3uR-m&g_8+KJJz9T^e0phod`%w;g{ z^vf9esY^*jI6iJO)Er$GXCQd*?SMH#N~3? zz7ce?qF87Z-mcEyZ~ba}yLfcLG1z;7*gc7QU9vsIOJgUhH`whQ@jXu@0uF1gnZB3L zj2wLA#!Ye3*Z8f4({%apj>rgTr4hQIv<%1_L#_pA1>_V+^LmQ8H94T^IrtguuJDe9)uA`8r zu-LwNH-B?#{QtC>A)OjUrO9&O-v zKQiI=mvza7Ri331y3LlXb+ItVu-s6in}3TJ+3oPQ`>&N z@QFj+TOUERkVoj6G74dkwqhvF%`5^i;QP17U6Y0o!|lf3nW;Y7JlsUw zXWp9T|1nh@k!LLa@~`9skXp!rp{`EBY;5=s%v68`wC1=zkTB$gEa zhXmqyu9Ex>JXBB_X;a{o7px0g54-(48129mrF`9m=j*Eqcu&L$TL{f_2;&E-2GrzO z#ZK=kFwz253!Yxj!qRJuHZ;uUOb52b&@M{a$A^;eE`u{bQAXOm$pJk6Ov9OvBm7DF zp+JYFNb}-v0iJ-zlL$IzS~w)s(u++hM^FSqXbBd97@}K2ZfyHCK2|;duy1+TPhie$ zVN_zF@QgIPYqav(po|yR&twzHt(WcGw6b=Sikvv1qAE%x$ z!+o2u9Z@bFg&?ammevj54V**1tgRa8s^+|9QF^98luptg&ZsfQD5Wy@KSXJ6=2ZYO z%c@s(O2EUn*byPxFj81}YHiFHO)LQd9xfjv>ZPyEG!GWM|E6-jh^jh`ktl68T!;Mh zh5-w6&%0a+1O4U14<5_caAz5P$%OVXio(oMw2Rhsz;Wxva;N4KJerU?Tr}AIol40vY`n9L# z_`5NY6PRsgwImW%qjJ+&+0;|^VYaGgi3HgvTyFtewmW+95MG?ANL^ zNcdVnusX8NysRFKa=2#Oc}`>mGz^~Namg{H;nB>XX9_ksDURLLIgTT#alXXDj^4N9 zn9OO8%rK*RHiL8MI$Dwvf!wKovi|hPv5b(JJ)`E3Ivi-SW%i|lEpuu6*MnWh5o2IQ z$!9gM5?zc>6}lQr?ghZBUV9mL8q{dP*6=&yOv+q_dX7nz({W1{@Jkr7T?c_)89d$$Ny0Ju#D919jUs|{Y#NDM(tiL>92GJD80aLDrrMe7`9EJare!!pg7H8!&i56 zw2NWE75ki#aWJYGw*01l95p;ckOJ&I8Y2{R8-7M$ls%$Jc+F+%o;9rDvBHPpNf)`IHWfkuwA#ATE)6vD@k=`(8byDBEts-)L-j60_1u4uW`DBw(v<8~SZvPEtpdFYemK?IHa|a?O(@@8);9_C&xCo%#kq~|#l(VO zMrQ8g3v!n}_i63Qf}GCB^ne%<;JQ*b zL6BKfqa^5aF?5te!SWvM%za#b^*ob3aVSk~vq?h z#r*ImL|KTDh0PrvABuTE*R#hJ4O)cyT+%L84j%mAWgF196SJ^`wYcCKwWdwn${ph# zV<}U|#@pnR_M7_z;k33AKB@Z3u;sPa(XEaL_>yU(ktK3n6$H0I(X0#7cm=R^g}yya z>G!Yk6fup}6fJep_`b2MkwN7)$Y*&?fd1pV39RBvQNW80Kf>>CMI;60nC#wP=S3HQF z;=y%g$NQxw{zg@aX53(bSPS3%{6ByeKXcQ!_F45SL8)mg?Wr_;S7Df+WMmSiqKPxs zR5qTCV9A1nTQW+ub&Igp5y?Ljrm-scCU@ERZ57>}XX7TRYP+3KY^IWgD>=1KV4D@B zxV|}WH)V-bVV}E^)4?2IDDE#+3iFp~4#K=p>4^&2kzf>)$n1VHoAu+pwYS5Al$?Qa z)DrW%lf&XJ!-%;yE|99!p)(#{+0O^!yPv!{sbU6o`Sj}yP0B%XHoLM(Sj7oVrkq71 z@UtM8hnorhxgQ0>e0S&==NHbdp8Bctrg+00#ks`=X@6gOhgJe_h7xZya{aUx>|}fv zHRU3{XAf?hcvAj(8Xa9(Y0T$O9r2vZjH9ls5VW?R-3B&4|0xSvlwqi9B*D{OuTn26fTdH0eyni!)#AI$_K>*0JiGASAA z=C|V81rua3CiYZ4a+wp)bP4o7^}VA%&i-1#4ud~XiFMb+VK<>4z7&HBcVe>4m_{() zW8j9FnZ93jpYY?l?CjNLg8CsR19^9`ie}^6zN8*ByV zN+MZZvtx^+ekA4aPKk0f$pATQf4u!#H$(l|Yxh3%+}H&W{f~@9GzL#F3j~ts3dP@Q5_vJ>TFrH1^YoK+pAUGGiiLJj%ctEYxhSi2uz~ zU+7lvgqzaLFyO#2GnT3Ei@k9_7g7%1RJgbmU@P6u!2IWQV*9INVvqYEXCzvu{e-L2 z4<;IsQ111O`wmRL6LBS-RbpHdiv;8{G!DQo{?^p~LQ)5Eo03k~Tjgl07uIh(qn98E zC-Lq#dp<&DF!6lzv{7nK`Vim@(P#I;U&IFYG;UGRb@&IBdp@hVbg>+T=Fpui zPYh8hPTQx9-Fj8UaI3qAe}e)N_)BS_9b9hM7D1Ecj5kA4V7aLAk5D+2XEbkvZyv6T z=AUo<@v1kg$hN9c`lC7Y&dh**woOyv&7TWuR27C&l^krGkXQSh8z%yENW|d3z2R^j zFtw4=J+hOC6a*X$O*TX_TQRQ+57V38Jq-p^dW+VB5^a$DCZC=?E=U|f#v<}@ANY+K zGl{Jst5gPGDC;&&>A#T-_r9e{_ZF zgY{Gue*p}`IFcC`hjQk2TxRM~a659yJ>iR3>;Yz`2(m_>xlD~K;{qen#wUo_f&;9? zRXAV~cWfSfb2m?MMf53Mr&S8RNv;HCK1c?kjpUbAiYC)i>kqGu;}W&Y4z$C8{N{hH zW97#)=N5+mL}{;|tSgUf-IG)3p|0?eKOr~#RGsq?SKpf3^hMs-SoItEp#KAwtH?(G zw!|MQKnrHMqh}u%29I+h>Gn~Ghg6ULv~~L>w{*ve43(^?9J>$@{h zvT+3r#Zp^_f{NK*Nxk2a#R!gd4--7HVs#rZBuC{);hyu0BGDKAu^vrqV=ETVzC|p1 z<-{7h`r2S(Ut_LrNT;1y&#s)eA;c-0zxC?S!cd%ELw(F{^RC4w+QM<{7KY~im>Q^Z z6@;bOE&Px?@b41!yEUG^SR)U7t&W$HW>-X*-31L?uHQug^4b%ORm#JCujvEtT&j*t zG)i0_J$S|Jz@3ErbL3!=vwLC3y+u2dZ|j7hR#)VI*|xFf{lzUc+?El^`P!`AYzx!~K)>B0KW5+As0o@{?U=SbN?h#NWn_%8Y*kH)i7u zc6j!7l#@)iA;CL3X^)iBci*BRDsKn-;lWci6hi*>!`vBzyB9Dx{)k~5{`g@)>T_O@b-BlT1wLJdjvis`0SS)$$%D^~;vy*_}aAddkT!^l(@bzC?wx1mF2KL|EF zCWbpm=*cd*FNitgL=K_8vAX3k67Q9|=_k{%7mJ1x&YaA28SO*oSKs)=>43_^qWdA2MS^Pm3yh9SegH;h z2fLChHSz_ca>hTHm<4($lP?>o>VqcW^VHzfA76-N%dT_1USWid^>#VSqyf^r7#$}L z!26GhkH3hzo~WO_8>wU5%-8V?rl^(=Ct$jwn`zrH!5#u+d6;#dHwYRf_<#}iTswzWWY$6qQv4UN%jVF4ZGMJCL;?R3^inM- z1Is)j4?XV(5owxqMd@|#9@*ILMuj!5%^nW8lebUjJpWf8#AY>g%&@@~>PxM+?R^g- zDgd=CqRnF-p3zG~NAp59Ha`@XHu}@CG=jup97oSTF-7RkiW5of=1n}L&MQtiw@4A64e*q zZZWU5s%XzpgEEB{Bt9YJw!NOdeg-y<;^5*>lCE*5Th#6*cz855m~&xO)5Z|l4k=g| zg1caDxW4HZd&(p5s&#PZc&VZ*O60VOB&+yz!p!cR8@qF|34vV4R`O>>@|S2?nPzKo zy+f*UbKEkJ@FtlY0y=;&O!)JoUzT}R*k38(XLt%s`;uwL=Z6dU(h(V*Yd66DeVk7L z7n?&ZtY1FoX`OV03F6K4W#V{=9;a`t$|)>REGfoB=8_fQ z;}%AY;)y>iIsD!Vzdfx(!644uY4~u&b&OvgIums#YP?kfWju_teS5BzL%9GF!FDsD zZKGH5PZ|#V4C?9&XbYWD4~BAIs5k7m9($jfFpd7m`aE z4)@?!`4p$ORmPk@CXNdKfeR@K^zdv)!ADL8a<`)`x-!qc8jw4#!d@wgxS*b0$z^V{ z#D)37$6UN}^9tQ{_+h*lhx})&HIuZ2M-PKKuC@tZ{CzEc7tCOUG%LO}PwY1_E+U-P zS+_HJyjv#(`fTP=;~gQS=Xu1)%Sa9LB>}d}w+IR-E}(O>w7psyF`L&cEOd?x10c^Y z_}RyPP%b(2oLpzpp2bC8ww|V@bl2C+IgCdEGAa^tG@J{?!a(Cuf9I}0N&!T*SdU4U zdN3>r-ax|)01NOfG#91L23?ud)=$Tja011B(;`Cbrjb2tWyxp3!#nTptg9I0OZd8< zhuPtEym+@Y3Z_B4DJ_@|QXO_uMvgGz?%ufTMJ7Ag$D0Z&H*1xk#CdZnff0cR5T~6r?&(KFi(Pj96{&O*C zVmXwrJ?l4RQe?2#%K1vQF4P6w z^m1w5O3B?(nLbc`-ut|mvRrCGB8BfdN11U_JT7x4tEGQZj4Z@~_Zavx4ELItn@?&b z94f!TerP5Jd;-~{&r|;`3cC;U6J6k75rP27?$nO;6+TRP@ImmJ3}Scyx_VtgAEVeS zir5tUlu}Wm(a2A}MY#j6HS-MfFx3#kciu@H@j_5+aH~PtJ%6Q!k5NPrCRYoRLSMhD zIiU?;Sjoyb9IJA{#Vsu{7%duA1ONoC#fRy_hP%@xGz7#ya#rzi7^1;T= zJWf&Roid^PcrWI+X`A@r&O|BEExg>`&vpw;Ik5Lh!z{~UgAOtse|V>w7=G;fpy8L3 z=3kVxagHgOoiQluedzgNhb-WEKDeu9I!ffM<{3Fx$l%0Cax|x_vUW4mkvuG;s`fXC z)+u=WU9I76AtQOLBNy(xqFSc&{?~oHL<(J`VM#R91ZyU5lj{yM;gu2=Fd)yD{wxqz z5U<(XXuqj^3d0*$zTWNZkO3O(wMeG#*Oa>We;TB)hi6Zq-rTEF)ycll@_%D{*vly$ zct26osmSC-V5CAxNy!Adk9enEUK}$11mmW`71cI!k}{M2*e;S-Iey>S)ju5+llyC* z5;ky)lS(Jjnwq^V0)iA~kDH&Z&nr+*K2KrpcPE|O9-nu@T(XIJdU*PnwiRREBsc4C z>4RZJyNb^=wEMbAmhTR~xOzd7>}}L#;dT|GI+LFHKkffvyqno_Xmc`Pf_-*gb(5lF zp&=mhk!4T;hQ0hb|IIz63FLpkth zs<}_D1~}X-Clxq?1=9hp4_d>GCGc5p7ZyBV%4h_y%!VIJSy9<4y9w&_Aedg!u&Iq) zGC+>9uW*06*!5okt(3HLTsD9EC6njN%&xe@UY^Osb6*EUIt};Vc7sX?6G1}qg|Djs zre4SY?C_U4Au+3w!g*7N48zvhKn1^2td_|7-9bp81Mk`r@G)Qp0Rxq#ty^=o4OCMu6Y@(i-=o&L`yP`j0krXhwB~8|9Y>YU9 zf04i@WVBj0C~5DJB$Xk>yb1EG8j;0q{H-~$^keJu^for%ZJrYVU;CAiTxYDRoR_Z< zeBR6rJwA^VuH=S?J*Ag=vyo%pjThbEH!xTSrDCd@?Z)#jHMNaVCr+8}Vcxi84k3ds z-E<(ibD5wGOPBm%+Jd^oOIP__{YFx8noe|5JQN4%ly})W zT-8zEMJui)OatBJ6h3+%wbwNM*WI+{=TlU9;7O5stx(#LA{(TR>O1(6k-Ylpd--1* z6aKPuW}wllf(37`uX>VNaa@IRzBRw#0@u_#w0`A9yCx(kJLaZUwS1~Ws#A%_rIVDo8d9?5i61F#|B=V%zq;2HhQvQ+!>>=L>oV7Vq}KA^go1gH=rDiEX?wD zRo(x5i=EpjusvP>B-Bch@(Tf8uIo2TiOJ?JagR1P))DZ~M-9lir2^XWOT`|lu0HlX z7vt+h3xw4uH#oRYjoJSMtDfxU*oo6fSISsPd`6paY@hLe*hY;-l>2`&_HCLs+HC(8T8OcI;(k1U<$l5zMNOiK`MN{uRD46pQ2$x zJG64sI{r<>9tnMXP6#C7&7HIQ_caKGSW8EF{5I8%u&0=i=jB|N8mNrSq3@)sZ`3Bv zRrLOe8YU>jzqn7u8K_)!{0u8W!Js-PyT0;(oZ-7>r77Lv=EBZhABnmh>wf5$7{o*a z>d2CESCDM%56Jo9GrMUnUJblW|H>Z0WXV>6#V6~0B<*W&=`}MV-njb)?{V)e0BrPq za$IGM06dH!91kD`+eqyY1U8HIpwCN*{)?1n$s6o%QdoP2X_oW@BYwf1YVskX(F^OglA=dQN9B+ZhLz_78a{K(46)hdE=adS3CT5 z$w?6`+#&SWz@Xk|NFgZqqf%N?j)E&u(s->Y9`Z_KVm0D&ksQ!K!|l2c&7%ZY2ul3$ zu{t6@`dxoqA(7;Kxf1Bh?Vr3= zmn??4NPG^PHs-(btoa~v3)Qg8n|p**%&hR1zZihH7@qh|XuNuX78LGR)qv|~(fbE= z>=E?6BA9D|#ecHcQ8}(eAbjmp>=z+z`(T&sw=5tiLGy!dEi)J)Kpp91x_T&At>=VQ zBb{PbsTqe~>UoGVH&b-qAczRHI@vP0mWBamf(=l~C<9R4UVSGV(JEpM=na*;EgHe1 zd`{}=5?R1IyH;e@z5WEp`pisJU?H6kEF*b{uQ^ol6Fwxov^M0!{?aQfkjdPm9yW|< z$(VUT+ylQUH0E$)24R8uWKQ7N9VPUZFHo}?{eu@thjL<39)b{#y0sFYLzlFU{TEp~ zF}z#NtR)gw2n>$1(Gt7dZ&0+Igg|fDV0_BGf^Jw|TSy6wrOKVkG5gi1WB^)yVG*h%tAW-OkD9(Hl-k_ z<78P2Yk+k(`EhC&4N$yTSJDcsw$q4J`27967AFM7n$`p22eYSOocw?ET&D{JIh-k< z?Kd5Y0)VDidEe9YI-|e^a8=QJeIaxX*np9`Ekt7rrOAHZb^xyf#}LCm2J+;4(ir1Z zB5*%#J{G+M!LYp+X5OxT4S|6s*~#^wk$@20H*VMS5rn*1l`BxK@))jmn01;c&;VR= z*`k+rYy1UC*0!x%*O}$v7a1#0k|P-+V)m;0dwR{zR%G19Log6QK5YJv8gT#GZ(BJh zGc7;Zviz&Me`rX+3z~jA5hRJBbD95yeIcV}=q`n#zh(?z^<(ee-E8s!Zzz z7SA((5v%+)LU?6=5@~)JU9@Z07ba)vNWJ-6h8HqOCgm7ZYYI3=bF+Js>F^CeiSEm; z3;rJI6?kLZQ}z)M%c!Zd71#{hp)6O zUv+PyPCzR58lXbWu)91fD`0a1}LG0CWa0i03 zpyY;+tOd4s)XoL`LedQa_AP~-ybj0_7OS~E5E6b~w5byLHXRt2bgd`6*7*~Jd`oAd zaYNaSSu4WHD=gqfYE6dvG;uC9owB!I`ddS84M+K#;K34H+@Y?go7KEBWQkAGK-DeK zA`*AQtl1`EFo+eYDU}g~wn0tLN{MBp{9VZqc46|?Gx^Qr;<&OA<-bj=ndB+pC*uj$ zna#AOA>HNrxOr0L!7ekKFTar~J(5JZ)2i&DEAa!E3JKJeY|p zIWsZ&V=mFSY9Ajq?oXSZdu|TkVTg&{|69J;1vV~=uo(I?_B&_OC~I z;%yk3<(d}6%f0q*LG>&xhvPO4TMLO79HvtOy*oZj5!foWbM}C_@wn&zQOERQ(|_G? zt2bHb@ZWbJ*d7;0&(lA1kkh^Cyub&;WF`6W`$t3}naK_LS$e8t4AWXt>GgTfy0r>Duovjq9s5w~*c4`a1qwIGoWv7AG{U6aaFo+-(%ZEg_8(|Tdt@Iq7`swMnqHYK z!eK|6%Vv^7b{Q?A(HzH^g{GFoX@dhrEaVg?*PnEdgwU%UXAPSR$!Dc$s0wrrLCdfF z$Jp2(LEF<36n}tq<`n9_`0h&v^(nJ+KD3hz;Q4;}%e5Nl3-$MUjI84Y;DL`8Ppztd zkZ;7T-hm^XYslz2Jv#{PvKq;9t7--G;8J0m70hRcLGhOcTS7==uWJUlZzIM~)2+F41+BmgU{PN` z<*(IE-^3^W$INsQ;0CTOv(xiXLmyO|vW(m~f=11R9rDOZ_{sgNtH8Cvxtff@k2PC| z&)n-}@#1W;!nn1B*R2u$NML(JIuMfoN>tXnfgmXD~*5-lig^HrE&mYA7az+vaq%1Qjt~$8fC}i}qPxuDJ65dYax{UyA%Z zX&IydK%mhtXtcu89=C}|4RklDv^S>9WsN;zhfN2EmN1<|YS-DlUOCS=L#S?D~_9~&4ZoVoONOVMxnJnP#1&Wz-9TD%F8 zSTNrQhVls_+XU% z#D#|_;_V5g$JH)Ows?}5rm^yxTya|vw0&G&V_L}Ly9iJy|KNE=mS0zymaEzDr*J#x ziLU8ns&hk6Kf#G?|E4HU4)$c=WN*0@AxdFqDq2ScUU=A-x83l?${@aqCLbge?Etqu z2jed4^drP&Llxf+gv>50=`S267!?;%=^bO-|M58;%yrrb5yB!*5_4%u|8_X;7N6B0 zkgGPwKTT@qU?9{y1`m^(GfSnNrMS-K$E5=Z)?SAMmG*byCH3Ox&Xi!7aNCQ+&1xn( z(gOzb*Y+AN`?tfX%TuJkq!m!1mAqJ~EEPL3#1q5!NuAM9&C4k#_ZJbp$K;5EtyxA_ z0Uosp#30x>{5cgiSq1yhXwakWA#!5^;Eo&r)Nf!}0M#=vWLupCv;6ST$(O11o%JIk z0+h3W631e~uMw%Bmuao~mP%CxFo&3Za!2{fYaaZ%uHBdwWwBbD8^>}xn<04R->J<} zU7$=3SB`ny@Ic=%PlY}hSLK1e)AXw}xZ7LpXlaudhiwIJugQ)XWSJ}V&3_B$_X&`n@cVX@T+GHRk*k`6`r*>m!?pM-7iA<{qVGb#Dy!-nqhZ$k9j8le9ANPZ`R7nPS zvPL8f@Ao`ZuhiaQV9^q!SLeGZ(0L*obAt&ICONDJ_5}>XWkbEst#OpKIQoFITmA%o^ln&Cb!+v? z7tUa`9dWdx= znX@`ga^7W72K`CPOTB3#CZr^%OaPk!*-&z0;lFM`7D6X=U7V%vCLFsnDgfW|ciYqW zxkUaAtNI%Y=l-H7GuzEJ^pDy=SSQw_jpNj1KcbORD#2IqPR({Kjl)5b)f??+r1R7b z{^Q@zkT5$FSw+ev5I4V`=0p|72ewOOGR%yHv49sy^q9*#U$2SE7W_uHN%XTXF5Y^b zG*GmEQ1`HNra)4uG|PuJ{bDutIwHkCBQKKO9xN$0o3c$mqzh_QC#wY5=hU-w?>&TzJ5@5=s*h0q8 zoA`DI^28(GY^*ipZo&ya*Jo^A-jIw_lE^7nca~LE4PNN8EvZ7277E=zct?JofXP%c znV21i5^{6c<(=E_h5yz5Tc}rz>SFk2B>Y^#2S!i|-bvwYB~8BgansQLjeN zAmy2f|89gLD-ws9Sny?Z^mfd6j#4L8FbC`teNpg#m6irviEk0F!CE_e&$gk=IEdJjU};xy<_-NqX{1<#4(@2&QWER`JhV8cQzbN$(m7Uw|p z!&>Ap`Sfc$hIpatB_c@_b{?04m&nFaNI4L1Wc4M?qaXX#Nz@RsvFD~}-Cmyf zix>T0+#~DERGL|_?kdqeD5-0wzSEp&ca-xXM0g_~m>lZI9yUz<7!epd2*uTnRH#as z2e8a^FLibxcKIN}`$a1An`4OfS!{K)3R>9$IY!urdc#e>!D0=y1}NDLX8$oqEdaQ_ zdMBcwfefpn_K4brkQaAW^%Fb3nltUFRS?|?D?q{spl}je_SG)pepjYA7Y}l zOQMcCqPy_#_t7kI{$VWskz7X?IC5lpy^T_BN;H{4(DS{kBoHq24EegwYtwj>QgRo* z3Q!@kkm|SC<8Y(<%)hVv_8q5*Ya_Zy8W^iO_q_SCsZKo#q-*=5!ncPJD)pa7kR= z{`PdAtJORid%fVx}T}%c6QKDg~!3|Fa{!cIL zL3=z7XWOqY=eVLUwTg|-yJLiYPiA6oTffB#0(qU*kz)d{pWwDK$SJz$%E(-@-pcef z36Rl<9hg3oq4sR#T%R5s#!%#ae6xMMUm^$EtMEffu?tkedB3N}z@{0rYj2JqN`rG} zk7u#lF^b_>CZ+sZMn7THNO&3=oCZ4pnBShKscZK658{-UQbG{jz%RkBSQyQc)MoRw z%SDEIx6Kdp;FWx`@Wlt5m{d_+wM8w!1Y~p)mEP$foc2=gG%88#7xKtm$Wows0AGmz zrszITz#4{Q*r9&WH{vm~s`fkWgnyv+vZ{B(FRsJ)1Fhtv;97hA-&EUb<+`gv%#69M%Kzq>^8H;}h~@2^l5;kg%r&sL0>k2=WC1WERu`E!BdYGXs# z$Z`w8Ma zv%V|9|1j!ChP2DO0rJz3%Z17Qez=Ub|0Swx2J9v;H~*&;V(K_n%sh5uJXv~aQXd^CtNAImUldx{VH$njzwKq>Gt2@8%aR= z#ecj1Dnmm;|2bjOQPn6v@Y~$|7rWysgtDcQ$NdbM>R8_IYl78o3R;&S>$!7Dz_{il z_Ii&Cm6t$St$7K59)Z}23zf~om(DA!)T*S|&v2;q&xO-A0mLb1UuYE^UH@~%=?>rA_tK&yi9K59wI~}fqg|I1)IVwnnX-i z6-+GE(uKHbyH`Rq!E=#_^#gOG+wCyk%Lk>vCgqLZw6D0$mt*?dY9A6VmH27pUDILb zmwtzesXg=&7nLdTnYsfc%eUQ^mX)U}TgQ(aoB(gaVI>f&M2Y$iB;*MRHd`+O*tD41+%heaMj4E&BVDOYSaZUpaU>_)>-mkqdpi` z@XV{Aiy};RWL&$hXH&$J8uzWv**urn+YP6V#R)IPzwT{Mk=jOlPcwJgtmt%ehbNWW z+Wa+b0nqrQ@vnoIZ$E@ceK1{mP<6KsHS{~-kQdMVm$~&7fx$oT5OwcTO5__NI__|6 zE)dq;V(iI%_N-{yvFBhNDfseJiHi*qe5=%xs9Z!IC|YmioJx%Pd!OI>803PJOKh3R z-A$yDx}4X;M?Q(mbg4>In6>^VOnpHJMTaQx`AUD4ongTcl*!Mv<->V6S4rJeSTO-O zCI{plAv!2^ume4I+iSc?ij^qsm7@GV1aI(sT-}yVv3iABH}*!BU@dNCpC!Ky4Ho}h z%Kp=~uuSHI(T}qmCYJIkvO8%Fc&Hz@OA-n$qe8Ny%`HhcMqZ#`01HL${bS%xhBWO4Bv!x z-TUY;K?u%gb0U%#1*jxD!K;b^YiC%PlP}Nv4#o(r3`^54Eq4^#Htq`1UA6F(C7H@~H&GjXC?f-4A!8a1r{G)4c12&}d3oMvv9&D2RW~W;TCg4tuCC*s+_ahoTYC zkR4K)1L@5vX17N`yi=iawpJRB3WLjVZjp*~8&#rfno_^1BgKaclX1WVAw_H5+ z?pw~|*c6hCbLqgb zr1^MFs@UO%L|FLrrdb?A~!F^{wV{KGiXKpRT6ZH00?+ur-_mf72;Ty9g$a%0>vy3 zo|dROk^hAv}f9%9_RXwnh;sN zRt+(0Y7)Cr+jRfRIj7}4 z)v-vapx5@jfdYCDl&iK4Z*wgGIpp$w>R)~dg{Ni4flG>&5;T0^dl@O?h7;60|ODyxhxDbcK!Wr68=)>o^?Za;8u`!6O8iD>J zu;SPJwvQjGfS3(-+3Fr`Z-k!C&{J5imP0&c5x&LUQvO1^oH4EHRs$;tImxNjLd0Ij z%HC008wKz?-b+01V^cnVVlyYp<9%dtc)$imN~_e+h~WcTlhMdV;SJS}-ED?w-5C7t zf)6+UonXXy;+vdtaT(A2bE1i?C-zIdN`HK%Gq!r&X6ETjRQ~O0m8v3GO_OvE%@#{^{Rz4O?+aed`-h+V%Us}SjoUj^T z(7Ud|vm&6e3Ril&ohPW|5n?vs_@zv)=T{mcMt0;FfsvzVC&%G!3x$`Dl3-`xdW;~4 zx;(ASmOa#+0k*1HnL&o21CnDqDL4r8?F3Tr;LYFsY8t&0Y)k!QGAw01BK}_^CzOG= z9!4}Clv7HbK~{4Fnnq0XD3%ka+??6vnmGM*25xVV^Iu1e<+Ot|E@KD)3C`Dj`2Y`0 zG(YR|xInvxhs^O7lr#An+G^kZA5rBVP-b+`{6cVq*71D8B>-Qjy zQOm~nxBnGMAQHQh zuV$n@SOyoyBrJ50A#&pNz!Yz1%=NcSntucwz_98G-XV~8+4|0}&8miKY*5n2^tf%( zrSRQUyW0L#$KvTQO%wt{KK7oZGd}aX0HcnEF`cx{xPM^QVn4XtN>F>rw0?OQwIj-_ z_v{}VE<>i2CiRI+rLRMYzM$6M^#qc%=h{k*%?D51tAX2`mA!9tPs_4@wIEWo7x2v^ zKDWunfvA3qcPlPPwXe1=le=X99rc`@9LuHeiXGr=IKOC6Aero~?=eEcl`XL46=VibFj z-_$#oDhisZ;yrh31x#2^hpt?UCgy@(Z!u5^2G@cV&HCxMA*^tkj#q43X?Aw57ndak z(`e8xVW7}J+e37Bv!QZR=t#&H5X)spsyl>BnHVN!laZOGTA$NC2g|4eu$_s8_xuo z@vm;pJKz^jhq@*az;Lph4SrIOgDUQ`$v@nhs5DOTIBWToPG|cfbEP)y&Ho(=7FZJ- z`D1gI?;QQE3snSTL^e(ZZW4-L=QXU%2?Rd-dcqQU&xrY|CwHKB7838M18^iMGJcw~ zq{hi;$t$UmBU9G|B%ykUM#0L^SCH)NAL4oosQPjEc}^vV-vj%aBjS@5GQf7g>OFz~ z+o4Q+A;?ru*e|{I>9b7B_M^sUypP#pJxmdh$M71ZwM=5SNTEcpy%ZQAQkH;lKM23; zJ4O1PXA4WFE8nJ_Y^~H**>v2EHRnGC@})djp=^ zT|~g{Sr)No_@G&kjES~e;8}i@Zqaz_v4Z$tl|Dkxj)700;D5sHbA%SXYk~^UhcYIQ zdv{j0Pc%a_n}KqB?d1`t(-tOy9cqv4Y>r5iVT?@|6vX{xY5Td21CGyFxlfZN>+wfz+y8&7AuFE2XDa_3^Bl>!tE62Y-8 z$L>hkOnn!wtN|XELS%om?I+{4iy<}dhim;rur_0W?%&@s3av1-Iz1-tk?b97VsJ%s z1V*6N(NDl#c_j_TrIRY#bw&knezxm|{J!`Cd*b7%AymAu{VW!^$-AGiZ8J8>f=9%D z#ye29@14z1o3Ht}wbk(#xQ!fSl>H@&xgWf4JlzQpsgN%OCJg@q@UV1$WBmR#`3^gp zt*h2dgi;xz=u8j!+6tW2@vY&%^laeH;xXmoZOXthfTgG;r6PYdSibs;qHvkM)0p2y zf~%l(hIk0eT7b{*@bvgKbv=~u^mVrZzW@U{sq^y z%BlL10(_d7_a^zrRhH1leAjCZz-IqA%Mpb+U&-ID3nm>i6T?iD;f4l^UiW05UNN)A z{O7w?C|!3S>PePmL?0pBTy50 z)11UfYPou5C06bQnYFSVcDL6$I3CK1V;)PesI}Iu50&y{|2^BUHU1pLYEq@$s$$c| zwP;s*&mN4PB;r@psHNz_^n(GX!akcdR+xGViY8vy)<9Ug)9>*qoijCp5Cz}V#v9B! z#k_m*tTE@$otQvGnhlp&svw#FDB5X=I)GkLwLSHeLnSFf!iI2@`qT!L-8hS< zouA|$S-oN6MtqpR3=L?AU?H!m?Z)e7sZ$)VZffQs{kT#!)u7I9pB4=fdr%;)?zVva{0qvR8K1*{3hiY<+aFBzRmgy{BogA_fWpm1>9$pSjZuXIHy7Y4qjrEptkdWco{_YC zHlg{cnJEV9B?n{(iQffWpLyP8e{*EOkRY96geKtDg0GQBXu~K$H3#l7I`QGcI;<<7 zhZRC*MC>mw4GV!TzU|e-k5T>vBhXLSPcgpFptjQKQ>sMzUI2xS?;8*+CQ>=rp&J%V zAzQDQUcB^mC;BXTc6Y8)6>;@@AVmuK+xul`J|ZDIJSLXLpOP;{0mfjz2yJ&(5`^;( z+c92YX(#D`n}(VeLt9kR)w8X8+HYvG;rh=y#q=oi(dAJMw9c_{@X3Et9vb8%X6)(U z&Y!e^0x>-2-E!O6oV@jF41-)$F+_6kSYhe*_E(>R?!RDVPO9KjBi=378+r zO@MdYj(s)p<^+YR(Q&10H+>V0novr3DBF+jfz;#Sf`hTQoAaF3+Ak0;HTj9)(ufE^ zv6=1avTT;K_xinrTF{EahI)9W`Rbz}U3c^}o&P4OeZ*U8@%g~ff1Kcp=BQ^*4WxE* z+ZrF{%|mhq$yZq}Y5HVlLW_dQ`3Do=&g)!J@1gilT_^s;ff$T7Hm+vs{eeFZ?58<2 zD54Vluq!%azw~e-b^8Z1C&Dj(bZ7d$APNmiyYJZ6t!RbA$o*l*I@X|%tgY6^)zxZ^ zVK%-HTfPjEE1ZLDSNzIV|Jk2%+FnbA7r;GvQ3QK&G2*ex^IsX$q4>h#y3f`taB69|P-G2i zHAJ_4ooN!TA3lE#G34~XUISlzt3`RkOd-ok`wXb}0zUVM9%JC43MWmi<|-m)TZHht zAZ+IPYYt8T{OIMHh8PqfrjO#|W&V}j;QzEE$mjSR1TC{c*OKQt^9;nTs+zC)vELQ+ zw0WIUYU*Ki%e(pj2Us$$t=h&%zyD|1b|(+RR_V|l0jSB*Im;+?i|)3<5FW&DzLM^% zfl*Lq;H8Cr<~E@#NxM$p-yT#zCZEEYz0oXnx_uZoU#7AFOX>5`T4d`Q-C5aC<|%E~ z^Gufo)scEXtoP*Jr!riIc%oCo&y5=VF)`jHfF;|}C;s@jI#|jY@Khc#mE`=Aa`WJ z6!qNL;+JLpUqBZ5b%DFOj+o(z2K8&xgwPzujW>@C=r82m5_|>#~AxF?gs~5=3TVpk(ovYE-`i9f!bM{5`uH zVp!JB59^gTUyTa1(`>>V8L-HNJxb|3&?zm+us4S&n9!AKZJ;N_{!3AlXPVz%S_%=C zAU+ne0cChhuSq%{ehHGb7e2>vulyKmx06<0ikfs!&Gj?WJ8A?Mqoxb;z4R;UnJIy|;i7xth9v5_B52Ia-ppB2mx(=)W(WAOVX;R(K5THA5snt}J zBWA(qOuxa<_jVWEJkzD%!f5BcX$&?Aw&mV_nRdVv4e5o5Dpge%V&w-0k+y6*INA$% z)t)EjMd)E)`@Xn>+Y@M(hwLQ#s5y{toQov=P>KM&mAxzdfr=p7(c%pHL~FUk!0|@8 zpc>DYjEfY+(62nPabPaj-P?ZZyp-5$)f|ogO7+A(g=j_${2=}TqPNAU^jH`AZjksc zekr9xiaH(BZ~c*fWlJkXDC!;>UoXxR>42@)$1gy_%$gwcJt6SD@MbkYC;O$&JU4yx zaaHuXy_{%GS1I7q*A(TmjG{?&w?ZG8c8tvP%y77xQF~|Bt~?Ey5ZGpl__iuU>&%l| zTlC)_VSz*aq6QDv5k$}IWnV8~#c1G zZ}|hool;;UAp-T^-fq8e6`=pqs#j!Xj+3h?XWo(wgT{qkOlL?L|4a4Oal=mrZ&{yg zK}goH48&}?_B-Mu@C8~s)8RPwYHZl@qz9U3&?-vIgLhyNoCoQDjc6Tz>!iQd;Jy0K zp|A2?==>IP7$GBSe)CS9T7ZuxYrFd1Tt{+O*)d)#Pfty#AS?O<>1{xx`I*N>*8~;r zTDx9=PXWLznfx?PZgeM(AbV6U<-CNp?!m@+<}JdcU&vAXfw*t-xaBp-6KIb_4N=}0 zbG8N)IarYBM>?Eg@tczHMsf}A(j#6P;oWwka{q3;0+YJnKkJmUHUTw?*e+zwE4`M3 zQa~X#G!%Y*)hFrXdb{YD;l(TdAa8nVkmew1tEn)!(ea!Q))Mr1Wq!BJSkMqZe`IwBKYj=1hTV4k z=35?wNdI{mUbK8gtix+@SL|k?eJj6BPg>$Oay-oXq&-s^Qblf3q4Hnv4#)0sqJ2TN zw-sjO*}?~-wOQV~Y%Nht4G9xcZ-{)>y_vY(lTBsxpwO7=J`Oa^=hQ#0xJyupfxzr> zVi@jP4|)TR8(&nk@?9a7vttU&uTkR;RW#*n564>n4v~m}SG+;cbJdl^x?ix}bD1ky z&FG!62}U2$Tnit(Efv|tMx@;lGsNOnfil@f%{>2?4%lSdw0Aa|SkPz*sh{?W#Zbvm zh3)O1Q^J3fLDcn3{5b4tfwq%h(NDIlWQlK5P=dM zD#BpBb*WQ|LzlYBG7Z{Ye_fFM^Izm%^XNviy)J|X|AZ!ckAzUVDT!F(tT8*eG_)T? zN)s*ntUc~MY>^}Q7|SL^Y77987_E+qs__Kt>fc`bM#Yk!vXlYC3(74an~Gvw7oVeA$xVJ^)a@2laCrQ{xUi^rjCW5 zzT~SZ9Yws?Gyj>wXaig^55qtx#8=XXaeZ;fnd}yOP{iy=nI>T-tl+$grxyuH;XA<} z9!1g?320UK3kG1@^-!*ehBq>_sZLKwf$7Gq-zHa^u6BKx`Zi_f*1f4oz~fCW+5a9x zDRp0bq`^(Vvz@oI$mVQ|ffnJ9d6+{LNxj;Cr~*-_2Jt2dPjh&tiXHHSJH@(wVQ?fe z%A1ACug68ANSnq`*u$qoh&!cwW`n;Zd?bu|mcB!yNZZ{17wjMSq^MlUOg1ZPK;z#2 zUtb=4uu5JxV-XbXdw<8Rre>rndRWkALGxsOx_Di1FJZP9@5!ha&?UI-Fdv$VYIm# z=5~*UD)tRDprM=Zizu#R7_g$R+e>wwDJ;P9jiHJ32hZafl_#gR*uDd=pj6=p`u<~F zO2X|yQUZmLo-vDu#7d6-iT4wTI0QfFjI-p$D%lwR>@sD-d$$effx};?@>g2pk=}2l zcHhd-f!=LSZ1(Tc*i`1a z{J2vGnn62338xDL6Ca?Scb#p|>wW#4G*$nY%c`PXj7D-_)44Kx8JF)w=TbPhU3nJ8 zLdp{eKK3YDCelz+bd-e0-%n@2*^;NvoX7({1p!_p7^WCnlZOey(t{Vao#$gb%Ay*VA}uc@Mc z?fl-M8gAcnC^7mAq|SC%>B8mW4g?E#l{JTFaR#=B^aoK)Da2j+M;G)PbxcQTmKy^( zn|_bVu70iC2o%D94oA25zwQ?SSB8ndmE8;!R3=mjpG zBG99~0#>|4(*E0?;M*%Pl#PD$cz8!emdN)0GuUKT?7)k4R*x$xZbqjR3?PY}$k_`{ zNO_C$dnly?;B;GQ-e+0tIH>Q6qJ?+`D9GVM)fK#IxnGLI)4O9aiB>``Rb-MH7%~$~ z7$9qO-+<$->)O=^Wh#W_rtL8$RR)T)b`?IgQz2-J72Ot^E9qt){6fzl&RR}FE1a0H+^ZkG$A zHTeQ%W4{~VS&v4&Z0L%F^R9RW9g0<4n)&VxS%e+uMGWfg?(!Xo#@LB|!OV2KDpL=;j&6VBLt$3qQ*UHknoM58mq8qtBe5xa zltqT{af?t*`<%IVRh%k_)`VbZm8|i929oj1iKW?5nkPx%36 zIP$Wa8G7QfPrA4j7}Ba1HMzOEd&7&Z-Pa(ifu%@<3|2i1S;I8$IZkomlGDbLajv(H zbUf#k2gDxBUQq$_McIEb_=}ov&hluxJ_mD#?I5j`@CW+Jm6n6~uO+7E z-tT$tQ>n@Dz6aCxW&)U@JfGqbWX(tq35S%oH4KVF=$rZ3$fZrSTXEJFCl>88fL}aP zc1WR>;B9>Cqq(#+^Nr2TrTd3)ef)B>y}0SuS|Uo<@~;V0tD0gL1({cWmVj5v5#xlv z$?7Y-ZgSI&ujv!0Zc5bO_Gln?^2Qpn6e|w%T(S)YV}JCk&E+cw#VUWg7>!*MW2~-4 zUrv<{b4*SM+RW-y*`Hz_+#58OeiblmZ|_B%PAtg?n|&9 z7?oe;miBd1#s4DAZR!22*4l=)Jer_7l_FuaZ~};@ZW8S>=f?J_uGMn>_Z`Hq7LtE$ zBXGk@5DC|qJ)Ps?_CxEZbHEHArZ#oZYS)|qHK|9&ch8P?U!pT2KhTYA5V~8okBh5d z7h<<(Qh_HPo>7dCp3Cv;mymElec?inc|gQBqlxgtlfLRaNqY5XsE$vt-kVs=`Lf|B zp{IhG-fIp!@O9O;908(Og@L$Cz$!2vz8=ab`RDf+Bcbcx&21rLBoEsB-MV z>%NCZYxIgDUUN$#pCWlF0D^F8j&@q}gNV6Bdh3=6BXp=Eh1JHS3_Rjw7Y6N5F4(<> zTi(qYp4h-ZoP=(0kSu#Su>c1n7} zwKeg18-Bh;TIT~c@TjTst+INa-u$(WDLaVSmyyr^W`8iK$&Ku{2%6Z;Mr*$bVpv%XQC&pcPFPQD|3&(3!ikpnm|? zQFxCxKDA#4iW}>h8L?vtjP@!`PHW|-etJQJ{a6)P4?l~T-79aD*~ZBTo8}Tww4ExM z7JX-P31KR=jAqnqAHVvW=t=(2;K8PusQI(SSxtwx&mZoTzTmFI<%A-jC!rXt8UK4l z0vh~=I^nr|4>;Is3+yYRI~%i9e;KNQ>)?1PYAm`%IwH05o^`c43xtT447xmBxM#x| zEopDJwx~Ik*}Pheo*Vv%8UPKZAucSJ;OD0^T+S_C#Gs>NVF2-K^~=)M<9cpr-Hsp& zhhuwCf}m?lksSF)dx>JF&gwy0Q8b2ZCJJboM>PH_2LNu_IaNAyB{PR>)Ujz;^{7O4 zlJgnEvy~FHhL4lj>4)R+!)7^NO;Rz6U{ZzT7DX~J?aFlMck)do2Enh(Yn!X#6EgXW z$3cO)EEDGY)4#pl1iv7=xTA%Gb=i=Eye%uvX~02t&zd}v`QJPjrXS_E)49)RdrG1L zE*vaBOC3MNbdRfr2@4SLbUnqQpZMOr+MZei+z8ya(aI@#L~c5I-6=R~ka5hxT?>g# zgw5l+J|}+`6u+ykd{qvSs2)GdsyO!x;LO;M2z{8Hb2eL~a4}WNfV?R{=XMaJPLyW? zxr;wbun1Z|F?LABm4?=3D$JoV+4`(n5}4~fTsKl- zHc%Yb{ogL8oA8`gItG`%`vJ6!CEoUNDt=r{KN(5QaX(D6O{G24R$OVoraaA+c+V(9 zAwbpIgcv?NA0eJP3OF2&CIzO$Psw3D^!F3~xd|+@PE$;FzNRd@I^G+N_xYUh@jK7* zb;31DJ#1-m=?s&l>GFqLYl2WPi-yo3*97729AE6h9Uid$(1j1Rr4iLueUFj6Jl+n) zF4(zt5M2cp#8Fdtf}|eiTetkB%Kas*X}w%_Fd|h%A+t_A^wNCovCddl$1 z(gv{A7<{r%e;1JItI^z&cxLqoeJ!AUITLh2TJe8rRtYUyZVGknmxT#6`Y~L8W#R#Z zu16~W;-TMEVuP7oE2XpRR69>xS;P?@)P>L$y zo^%9kroOU4OMX>m$!FBF$Fg&0w;=$q=X$1fgrIeSJ2`@w%dlvSJVwB6@zDUP$6pYWR$ig?`^c-wmu*QnAiNo(mY zWR{i@rL-Z%2<$Z)8}`7~t2(@7>t_4kkn$8FmoMte;(>mXp}YKvn^UWbe_-mFsKkWI zZTtAX#u+^S^j1&!H)X?iuudW4f9HME-ZfGA7=$11O|Ud;%Bb(M$r!G$?P)G(1np_c zRH5rlE7AQ6NGUq&&cS1A&uGAIdGQUr?Dh>x#BGuBg;EYNRE-Ed^d9+Z_egcnm#U&= zodeggaL2hIrP)Ql-yDFob9n z=dVr5-3 zhOyZE08|GDBp6yre#1xvZ+fPNyagy5(%sX-pO@kITevA|g!;v$4vd!E%{u6i;bojW zR7Dtp=X7myk-6|rb<(|C7Vth2Ly=fGNyQPL6=(Oookdm(S2i?1|0Aw~1jGFzrZwgF z6*VcD0Ut86%PyINI*xIn(?iz|NcAcB5c2SJndz!ub9n3Fni+m8Hh-a{gnsEbn-s`d z!f->iotolxaWyU+Z70yeUZUkgDlhz(gD8f@3tJpt7H8hMz0B$?xpC zLbU$ue-ZV^j{bp;u6m@bL}oS&!t3XkBm;#1;ik}vYf9K7xJP$c$fqweL2~3x6SSye0jx7#B8BbXf5Vv@KE5x-jWpsSgoI0O*RF;%F1IDQ(u1@AX&ERK`gKm<-y0z|Uol=*bCSD( zND1PMyEzO2!vx|E@db(B$gN~=v5loYeZ@ybAt$LYA(v3+(DKY9JkNUxN7YL3T~g*t z^M}CH_66J68T(XmNG5??Ik5n2?$q9Z*=%#ppb?l?Ji*s}S+u_V;jdwID3y@^aMDcz z;9%0#HG0`-K}>p_u_k@~>5GMBiOc;V5u3r2*PvI3EG6r4Z42Q^-1eu&*krdyz#Y+J zdpVAvVHx$senlrE1{KDsvd~vWDCt{EH-|8eW`w@LioxL!5A-?V<$0UZ{oFe=Z`%~~HZJ#g+O@O*p z^wDRXPZDvMDXqm_%|2wy;7<>S9QKI8%ouOW;}2T9j4|Dl^~!Gmf}$t8Gj>H&_~=&F zZp-5yE4S`Gw!eVF5XmtQ`KP*6(K4B*^v#P*LeR!qx!cm3Xe$++x0@AxyoK0~44~pq zY45{HDID1JY5PGvbtCie9l2Qv9FuLkHY^tC9-QZJ3t&pugbf(2_mqOzoo!o`5Q~ha zsdA3@h5|nMsfTII(h!R^&oNc#2+_cGMcyPtlmi~w;m_t?{ZBl-qVR#Z7qYez(br@} zC^a;o)u-^nFG_9nqZ%VPu&{pnM)uhqJYY!{z~|-UW;#X@aWXVxb;}}y0v)QU9DS-= z^!e+}_xJ=iD?k;u&tF#a5eMYcQ@b=+0Ne%1b5s3BS`GsClE-2L_%T@Ic&X@cU_RoY z<`Vn;VsfPTEh>5%BQL~sSp2ug2oU{6aGmANl=Ra5i*JR z3pe6W+LqHxkB!atHl%;|Z^r~?PMBWKgG}EEb61&PX2FX9(b&zKQ#-#B65K$ws>!P9FjwR)#RJ)ZKMQEAaF0`_3H$^Qr>9I%+-WA72XdQ zNj%a5CB9Bb1}GRz8hb7Ga4kTh(0bhiMh6_x2QXBYdYBZe@+dvw&%D;0EJ-rc1RKDA z+0lWoNzo3YgDH6nL9S@GtP!~nx^7<2gDcDV+8TA-E&ptD7J5@&w4x*(oNBS$l)?hE zLkOsq><%N+p~?g{6iY^RC%QP&45C2;T0KLgy10?p8} zS}Vq(BeVDE;!3!4L;Y=q{541!D8`${SDTVU&QL7L@c$&{Zolj)@HA9>28JQGklpst zG7vj{w^z#slE7`&t%SFKcK?yPl#K&sX*Loy@@-z7u|p;GFaGD{6#$$_=w5Gx7M-c~ zZqR5S?7FLb_C6SdE-+>P@pJ7#H30t|>c$Klec@mIw|4w>{wXr$KVroe^+{QY#cA*3 zR{!a=fpJIM<57 zL{HjI2g9|@H?&~M8rIF^{J}M}mxjkx2xoMR1f-%Q)8<{ST%@o{E;GkuZNqSXD z+Ki_$`0cqKyswJjVuLIWeE)M_e$NfD^G07NaC{Tglf(ZZa-+m(*&X zF744Bhk%_nu4d=-W%3;gI-BvCgd*0cH;WfmtqNr)_P8_}whM<+QwHrOrRZ5p;1 z`ZQXhZL=?}5Z*mIRWG6@HmnB~x7z2jB=lmT-_Z^`5{kq2_{}4Y0oqDY!*4TXQ3`;| zL{Fr@^mVz+kff4z9F{@1*>ofFM8$5)`&S=s@&c%sIpMIxuj|;ox81PDCn*9Lww$($n#RBGI;4v$YAn$1bJfH89Lp ztTaSa`Znm`yE6g9`4}qoKJgk8yJR)_*|W5l#d7ZN2Wf4P{nnhLE1h;L)uG6FX*Gjc zu>3)0gHNM=(igB6YVa7uAvV}Tv8wjm~ghM&8p(d90*S$uBp zLt#_&mR8;sY4###ASj0Vf5_@C9?!ulrXYpLjLawq^~EUqNaRS7_B`l8Q?@c-Zly5ZtOHd#XmWO<*7_EZ2AsmKj3}7U_J%-~5BksjDXo2X?ek8s zO*#yd=O!D7&z$GNieT$^L66_NuCBt7*W+Ln8I!xOGhjACruzm}XbA%s@Z;H3zO1uU zZT$=EMDtZ<(VQ(wL=doaaA>;E2mCqR;v68h!Z=RHo8z6cdB_+pgm%wFRM2SWLt6=E z-k(Ro?i37gN~66`)UdW+6dZsTq{O`(UxJkhYFI)oyfBS6(Ze~A-NgWgyr=Su2ced< z_}gw$LvZtF*h^H6cF~^ZWWY{W`!eq=uF`v!gcVO=a|4<~ar7=+f1FNaO07v@opH!P zH>qE6t+~F$5A#f`N)YfzT==?Hw(<{|QvRx1fsqV>M`a8b{oZ#l4}6ngqb*u%m}(#B zyM0WkWm`9;(`o^1=2@a+YY$mq*tb#3<&AWc5Ve7DJ;&CH2+tT3N7{z=+6=d8H#z6O zy-j?n1sPHUWNkDPO;67<2(`lG`xA@rBwStePOl2%A73Wq9K%VOhTe{Nyc=qbNn3w; z9x$TH1K?sGexIKAReCY+FT0KyM~EJwFg8*M^n)2Md?pzR&<|br6a!pEBSD7%Th#s! z@K2~m8XT4RWg-+gyGI(Ne47o7nu9l=;@C+wE3OhZq!ZiZOY=FM+2Q!SV^ZPc7Xj>1 zFUqDqE@Wh*3)!ZU&9!0`oA?TW&y>o`ey8`R`fv|}E5Gwn@TgNi-!k?6Ns$DgFMjt! zKOa?4F)8#J9wl?&6?wQ3+Z(%STn2sA3riQ4^`Z>_s8-6Bx}M&f>HE7 zHi?XJ$h5U^6m}a*etSUnlxQs;$zl!s@!_%22#mj{0vnKYoyK?69BxZ zV@0*K1>bb*-0esd`wM)D;q*mAH$N~`=2IO%oUpx1$wcWo0Q!XU+M4{2yTXe=Z^zKf zI8!ey%jjLxvxMtIZvklc6owY?FPKhQ*o`^U6bbxW^0m2HZU9yyo4-o#L++FO&gl00 z3G!Zs{YDaPr#+o0^R9k1 zwx=9}RXU#BY8+r#r`_4a?>?W$-fIrNFkYv}o@9S}u{NuYUv6`6m|A~h3CjGuhUa|E ziFV{?cK7Hz3;2o8d{DelF%F5nBOu-;rCxsJR0}&+mc4sBy5F*0fR42nVIoSlVh!CD z?T8Mf&>bez=GQDs@{&d@=|(#k^0R=-6IB6Eql&`l&0MyUUV?u?=r5F%ZFrCuf491Q zM{fY+7U#BGO_P7Rk*cXY1`I1j2P5a{33DZCwm&5T$-u%69Tc!h6<-7nmq0Cq&ZSHX< zt-VZrEw#P<@TaSTn2SJFiYWrIe7(7RgeU7E)4r7rpEG2Nf_{~biW8aEFpBZP-g?D6wu~72h0>46b5Hp9u%F(U8=D8$ol`Ck z4nUUqopl!tuhYcbcz^flEQqst1cqrDG^W%9B+UP99S8z9MI}^Pxextl%mn!X8FmO;g#B_?NUUk0R)-1w~_4TV+}rTtziCmB6diD;bRWQ z14L3t@DnM=(x8+$`U7zh>gmmZ{3ZTES%3lXB?`r-4;MyD;Yv083TI~D`m*#h!BW-D zSQeL_7xIR@$gw}GqcV`4ki@qbwwtCieglqmJ)UJAa>5ksqD03p`&bFZWWkab5940QwjGy}}$I6JpIurHdxw3MC1tIA}sZ2wr4)=H~h9h`eIj ztRHq~cP4j`*AY%06MWMB6GS}XydF2uhVB}dMHgJ+xfuUAK#rMNep?1eP(NakU80$n z*HUbmmwiQu4yxVXM9L}!g7&$v-qaHUU2n=qwiDG+xJAF>5YHMg&L#R-jP;L1qsLjL zig2R(zNnXHB}Q2wwOOj*%JgiofVnvz>932DznYz;IS}_Ha&E5)xm_HyIQwZbURO;j zF#GBra9xHD3ox3wRSte3(Y7w!79FYs+r)jwjq0pCF^ZDV#f$ye7jcnQrsnI27#J?r z8vZVNS26(l0!gnt`Jjv6*Mk}3GNwe#)_3sgjYH+WETWzdiSLXHnS7X%X_VK3l~rjk zT71O?kYej+nR&zFJ3;4kO5d@)eS&k*W;8K+a=!jpwlYcg!1I_R$hK=}Q=y#D?|nMr z1i}|DNHbq34GJBQ2JKiRf#2_)1ZN6~Nvp z93t>1$O~;)LOvAtCbG)&eEU1PZ*ElbAnj*Vm@F0`X&_&!K>4NoBwSd5ARRapBZ&9c z@xEfmG`d>?YGa;W1G|b*xCir_Hdhq^wx5^U zYY=?v(rf>B5V9onSzwZTvnPI|k;j?ztmKLWu#6V^sZBT3?Vmo|{nd4+LcTaOg$s`@ zk7yD)AIaGQIvKk^zf-u}rUXyanNq}K0HPuTeLRL&e{B>%hx`DD2Jwaq4S$kvvn z2vNC;&tI5W1<%*1$E~^>5ie1pi*F{N=*~CYx$6iu1WYcfAt9k945<(CVZRV_kWSqb z&4urCmLnTj55i!i#b;Qx)tUbj;)f#oaR?V{91I-72pl`-*HXIY$gA}cNQ`CZ+qybu=YdxHOfBnjrXN z5wsk>MeZjAxN7s8&N4FiQsHFYE6RZ( zFtpVzLENRqio3g0+@TbwSaElEic68=P+W@_cXxL!5ZqmYJLKK({es-&ue48)`&wXOVKIPgzYsiNLqdt8{@+2#c*jhX8FFz`kYT zADsnbx38s!aHAb)xwzlIS|&jGXI|o*boS@lh1vViEkEHGoBG-)FB!n6;?FokpFb@2 zKp1YrIks^S$9Br>>>n_BkxO@L%^{y%eZAvk6Jbp+j{~ox5dRmPf3+HXg2@mwm;#)S zRZc1qqS!QJF6ngcd^KO|^5* z4?bGt%Z;_{qSaJ#~7sKI~foS8*yzJ;FIZM?V?i33)n7Rm}jmTu5O>UK`U!@SM69ESc)<&%P|X3h7UyN`PCXyoYeMg7CX_vTfX ze|UB|0=%y6mE&8Yqa_>T@Z*3kh5q@fLn;;H9-TS+F`)-a+FWsLQY$KQ{L`7ko*TDG zwI|BvijgwnRnnB>=J2euY**dMGXcHvv1Xj#(g@{ylK|>J zz1O|t_~`+X)~cD^%t=zb54HA3_|CI|O988^!CvlZFL4iR#rfzsW+@Sx&*{W0^bhNb zkEWRaPYU;Gr>)lokym$}ZR`rQvAb_7{whkO?f{+M6mSMm-LHh?oOz z?Zy#4aoy&Gtp;w#Zgg4XS`Xo((F=D(F%KbQQnr?K1jeQ!k#mcZ-Pj2-xth2dF6cB7 z%}-pDaI7(_RwbhTQ)zb00Xhhb(BhNIN+ zii}5EClBPS-a>OM^kYtqmChntcNMoI%}UF*RfGi}0!Wsf`nd-!4T!%ccP(^jOv6>N zZw3ixZo!8= zF_{a-sRDOws&o?KUC+-JiblZ#4H{v&*Za}{Cu_K!fYZf0f$?^pi}5;R5yU67B#A+j z`eC%~eewJ+3+TtbZuN0>mggPIbi*C?Q45u8q`SrHA!lHHNe{6`G~64CZ`5LyJ^4uI z{c|jxKlC0=$e`ye1#`_6J}r(M1~%5f8dhnPU@wt6-#lbiq2 z9UL_=aPnr-$?XsC;y*1=k-yAYFggF_-Z2gc`_?0f;=xtDhFpGFKrUY5r{igc=4l3Q z`!aXcpCsnl>*M&`O;KY7NThu1Ih|>D#4{G&eb1))g{jJ^hI^MX1T{kpb^%p+#)Px| zbuLso;=|1f=@YsheTHXpxOsEZtt{yj|Ki zb7OhNZ90kfrQt#&rnkUTg|*>cnU`N2ile}I%}{eQ--b>AwgaVw&mYx1IBpsdzC@-Q zn}$d+2|bs`Bvo^*KIykPjEKgzq5uZ4L4b)PqeIhe9E8~(m2X<%UyQ^htRPd87IY6%^WF-FqJ=59qyb zf?y|5$9DwRAImv&t3Y=^w$f#Y)0G!u=;$VaMs^!g?>Ny)H7<(XbbqtPi7O3?&Gdk@ zv?#y_Ly)rx8}I>F4qPp4mUch$xN+Ba0~^WU$+qD1*IXNK{1;$}3%IWxmD2c3laRdJFQ{Exgv+8#Tb#x9M7v&KIs?KoJJx1HoI!)kD$5l`= zF@Tfj3^Q2;l}XY%Uz618V*$%af*0Jku?Xzg15sG!73k|q9}Zb2{V(yBsO$3uQBvY0 z%XRF@OvPd7g#LoW75D>iPlRncqni5z(g%_Ozf74t-ojFU7d6pbF3~XEjBEh&oaV7H zu)q%=bMRh+eM^lZ!olL0?t;_OM~kn>J^?MPP=tjet15rpvxx zz5c_Qh3*F>URv=aOI_;C92UAd&bUM+*9NG)$LGcEsNvMW!yHgm?i_$sP6Kke(+0J*Q+$H0fvNHBHqY{eyThj3_UK3Y~P)ql(@rpUqhsDgzhHgVE~NB#ZnO zMR;p}G9Dg#F>=Q|sS@qnp#DykNa=vT|B^@U-I!3*Fy(vSst4Z1NE}x)WZh^KPKX;l zXoZSd>=0|~+PwuKwmT)Ei%KiluX#}Rn4gTO!}Z8cA%OV5G-rlr&1U`qIPAe}uKt(r zMvL@}TGqv}rTlY-^H{4P!h^0iigR0>^e=OipO}<~NxpCAR&*`3Ccntnsk#mWO6ofo zOMP@7Xk+K`gI&VNuV=M|fRvb6z31z3`5b*dkdM`B5tAypj}N-%6j3yP_@Mp1_(8n< zMS?oMd&psyb+Ac6`(#mo7lScema9yc4$xDz^DfrYSfY642tPkrNr<*^?H+vh5Do#| zz1h6$&gX&*s2m3=?T300GG6OnbZG%gNDAU|9(NOzmTHn5mS|(>mGZ9CYIFUF(fLT* zd_Vb`f>k>lBz zmaHQ@XT;_Om4#j91%RzKeq{;j9sE3Y|5r6*?*iCd&Mlu^ad&TN;nw0p(|cgAJglfr)zMsqSG2aj^u}okPLU>M-Ia79Te1)LTZ!# zD6i3BeqY4^G>?NJSu}b~hc|BTpm1UatXqb*>LW`%Ik#nWgdDvkK<50~-4eiGizb4f zygu_Ge>+y_pU1E>Uu_*<;XwOxihRE>O@4hu`)~F})jI*VIwJbqsA#`-zHsQ-nR!0m>HQw~y1k!#&hb~RMvY^iw7C;#wD)-2ZIa?R z8}mBC-r{VGzdsr-b^h{gg}>BJV5W@cMT_@Lc&tbzC-6WOomnSZ17Zd`Xs33CSkj4j z1)Ipq%W%ppGJ^do|FrB39nsTMbNUW$02SwjHGx{LkfIYcSx~K#qZy%m7Yt#TGSuCq>wzFVnZx3I4(zAF! zIe2U&^TU;;lyQBY7yZPb#Vvek*mP_Vp(*b8zdm4gA{tNU@m{DL^eT+v>vy?yWLWLUt6~>|x*j3|%VFaM0TYg)noXTzTwU)O ziT-Q}#6NRgvKIS5yY`}o88fS!-rY$Sjgw&((FZFsm$UpyGz6GM9&KI{1a_EPTcB%| z;`s6lIR|!;D*`pPc;km~ti8@9PW#AEN4A8M*ZEQ;Za&FOw_jP@ZP<@p@iX|GL0)nN=GB$ zQ#Y(mR|LkKNvrmCt!m4EIxCD29br(N=mVOX?#gLoI?)kv-h66FDq$%fL$nT_6yIeH zG-sV;MVyZ-y8q(9+P&I}aA}ReZNp-cl0=k|<8_QQ|9f4n1zV5UhVsq?#?9BuRht56 z!j{>yWI>Z%OkQ2gfi4Ew4X*oa`y(sWSvh2#F#4=Vlg|;mgGoG?OxY5n><#QQ1nH() z(q<7hWEsM+71ey_w~-3&?p)BL__0T zm9sL+4@`35~Im0kB!fv-EA} zA|dZRn_S~KL0pU@$MLo`ODIQotHUd1bQjvxQtQ%?)qB#bS-fROp(?vTzFR)Q%6hyAl9-XaU%L)vkafwZx5NDA3Nw;imH#p!RM|sy{L!V;e;Z92J~1z`wZv zEYF=`itIocj>Io_fLZR{uagnW_;9v$p&oHv3Y<1uGU{lI3|p|E37Ul%CbCk82Laei zU;1BlReEdTDsud$j=Z0NkTk5J2ni+Q=6}b1{HXnI1W&^J$}fe?93ST0SuMNdXG?1X zeiL{yw2a72Pg^*b_!(DYs2Dzt{>Z?R>3eJHSf#WAz! z|6+R*$Qhks?$g3N`X5~3(ki?Nq8jg6>^S)LW7`5mSjdsMT?<9ax2gfbs6re`ZYs~A zd&3Ux^~^~V_WB3Rj?Q$t!E%E_$Us)EFtt|&;^iuQhaa;9#Za{e{Ag3M(SyHko?#3D zB2jX?Y4{zjvn;LFQ^+*-x2;r1y9kR8H1+3=O8*CT!G;c&lvW!{R-um9t7)RRg%R_-7dCaRY`exYj7lN^zcwBKS3lWx0^8h^|~lqdLhDr&9+ z4Zs7viSuy^&y3zDl_dqRoIA+O#KxCdA02~wk}M~7T}<4-#r79}SrKxk%O0!xIEtzh z1aSH&@;dD$;7v0jIdExBKxXDcws0!t{opzHx=+&OW-@-l+fmdy8{~E4JClP3APV1D zK{maw=1^MQ1(h9<)buGE8A(iytxV(;Hq+Nu{6kXYZm^jY;lz(q;y!>yFX+JI4) z>)urj7-Thq?$8o9@UVjt6Zh+X0ecjD%D01?KJrHSzkCoK=Yb#hq57|H1fON#bTpe1 zgBu=F{M87d!X4e~;*~hKG8x44Lo*y^slNApvl_D7Jp>q|r(xyp!5h=6kS%8kd1;~k z`s7cktvYvU@%2U89RUdbi`WlM7Vm^nSa-`|dtCcZr?l#^iU$~UL){ZU9SfPhiCO#r zFI3Ho5A5soND5^9^b=WJF{>BBby5=!Wi|xz8{Ww`_^E_BQJQEiQ!ti1pp}q+&9P=n z^vTCu9;4C^V)&MPnCmMHeoQ-!I`mg_mc2+|ntaygN5L?|u_sSL6mR-ExEt~#JydPd z%>U+2;;eBF{#tZlNX%3yvmoO1^TkL-j^y)1mz+_W-D%IVC>*bxd`wfrI+SvjAS<_% z{~(4rz499&k-oQxZ~&Hv+ZX(yJk1H8cn3cfEIadG469xIw4oH?inW zq1W{%n>`0QOaOU>6nnHk`KE}!H4c6nhL^kSkwHzE6)uvxp4P0(@*ons9}S=~ACQ9` zc%vRJ+vNr_;juq^$*~=aJ?&Orjnu<#WfbNQGtN^}-amKRHp3#FEfWilLSNL0q^ ze+OT$WYEjDlJ^|6~s`cfux-a z7&({nBvLdSY#(0LH%!v9-iys7?bl%wxHHfT#jemQu$oOOUmPCdMJM(}XQAlX&rhtX zMtjFvLL}i_n-gN=&hJsZQ?OSuBxwX|tStPAA21nR(>!mhO)AJcxPPU>#)FM`k=A?1 zOOX-!b)v-hv3giU$v~MG(hKwLB6Lkx7U;odWiv+0L0>NWx%f2)3+Z3ohcfKnt%$t> zd@L`-#{;0!Ukm;O)TpB%w)U|gdRr*yf z(%zulIOf{)=p{zT4~pP5AW)oG_xennGz4Den{@cbF(wRMS?;pxGTXpK_(zHholu?3cZN%jc#ZV;Kgbf8d#5jEwtPntDXK@FjHw){aOE6(&Uod{8SZ~__-1aG zHu;VN@dutdiGx;Xc8Y^P?$%GJy&rj3+%j~c-{?Jd`ev?>o$SMVH=zH>ttBic{Y30+ zRtg%k{A(;zE%isi#%x6P9*t5(TTCv!0WIEDJw3{xZ0^zp?z=Lim>H-v*BUG)7ey=a zDbIJGuEepc>~&K-Hj1DR)$yleqZ|s!nMefNE?u)}*P5P9H+p100#Bu9x6iA)R3qu> z9(CJ?fbc<}pKrszHV8!E`3hT^kGRTbQ(W+X2K$@jhrXi}yOV4z>0Yg|Za<7I3N<2l zAbzX<3Bfu$k#k2B@_aexXAkw1>z285S!>RoyJqIGa|B#=*$e?5X7V#)DCRHxCzpwbJKHp@OKkn@`LeSPf4Pa-(ev)zt{qEWR| z_g@q2>Q(WY%%=dtmduBXMjbjpL)5MV_E-MODK_}jg<4zNcG+~^{>ECOb#PdUE)Wa* z3ffD_YVA{8QQ@4wOa;cuz*($gDrK!0RKf;auWy`8Ohd_;$83PnBqO_FrZ>I`e61xy zfQTd~Q}tGR@>n)w);q}_SY7KBl_~_k8{kw&YM6oE?w*^QYq^YiXUA{;fstXBCFq@G zj-x-^;)f<4dKwOpEC+XZAKnjn7Xo}hnA1rfS*51-1 z4BcF-r>mfJOW;ExXBMVRS(Dm3a1 zx5VaoSp;g-L6U*zo!>dJ5yH=nFn$H6zGs2mA*turQ6-O{wj4@79%0AUgJ&to9ln| zAe&Vl@wTb1zs0)sK{(FL$m5cM>Doh}g~U920Y?Qce!&3r*S0ljJ1C+6I%rh@(1@Hj z7q-z(I!XA?Vn3yd+`~SLc|J9+!Z|}8f>c=V7|-Sp-J=+fOv!8af5vjV0veGLo5)RD z#rHs69{UQGe-wFjf;2)xuQc(y7@}ta+0lMR-W_hHOZe<-3t~wHF@WjhIG%?BL64}I zciJnHN*Fxz!ohl+pASY?&Jpq=J5vuvI(&AKHbm>UXye zUPY>!w%hwPVFL4HZI*O3dM**KTq<7vYD^_YvK;e6=0c4L`CG_)nm^(YBBhrz3>PTG4%7JfZ=Mk+r36+7cC+e&kpX*Sw z!sDurrUZXVitD_Smlx~nn^V5#x*%$lKr(dLb=^AUwTJ2v^&1Nj^3*x!XbnG-r71*d z9xT6At@CFyd5UH&AqaWj{>q*ZUzmE%{?!R;z+qZ&4o2820hvf?1%r1!o8kA z2cs;d1M8)cvB}3J^?|$Qm9?B)a-}v!^9J|!(7ssv?Slt~Q1PNsj@D4d!IxrBt>E$v zo{yzehe}e;E06J8V^c!BA2wj7R&j0J0-hD@ZujJ(v8RT*{9gPG^C3tzOir=oa>al_ z_ezQpBoU<@Jy{_^y}P7QJ)jDKS~huEn1`tzVQ2eG)^fP zDilRPUgqHK;QptNxS>&33tEn9D>dNidYbeY<`D9qbac}l|3%LgYf^&>CZY5h9b`Jb zQh)yT!HHI+;J1p%@yLPsDoT9#^r5p=S7A`;2J=)U(*y8wm#d@8uU8Nl_1)+$Q|aT4 zM4{h0x%pyRnQTuhmmHWj2bCYYTWO~$)l&bsO{|L%u-P4E#alC)??hKt@!nXE?e?}MT=T-ma;0HI zuE$#0WFPRafqs688)@kT^=2#ze%IjHwVFo?W>^1tzGvJE3Lo z+g5VsHU*2+*ZHr29-h1A3)4KE_(z0I(!2S#%Y{}OCd;7YC;b+qQOm^WPPzD{#~}-Q z?RIk?pU&T$z^qM%GETooUSB)?(1Fa39Kk*JE=^=d5w1J*pTH8sJM4&o$NPqbXd(G5 zfk&ne?SGn9_bbuJDfAU5#yJ5$Rd4eg&*dz-#Z>XnBDr24PgR2a-d(OkY6|RTrXdLr z2I&9Q^5yi6--x=J2N7{e7IFJOjpDm%Iw@YzK8%(?+$#ua;)P*b;B>El=Dky73#K~Y z0=qHb1A9GIBS+|OILEKe8fZ@b0p|1ae`)i(g@@FBAN8iRAKy0Fv0zhsSzL(-4+3|+ zxFeZX9~It=9uxV)Jre4xR`KDj;3IT`E}>e}jV{4G47jNQ-j(-JicMm&BN$jzMZN1! zaDP_VBKud#*BFJYHvf0Y!GVdYi2$6nroQouBw;)a^)3$<`u=@DF$&;YyF?#mrv{8~So+HufZ|cADY}iC344*+ z^^;Z@ALB>b_kUF0^))2`F{o8%h){;7&HI@6is4`Tp}*_{{{nRYfk(I}|NZ z8p)_!R#i37McO&I>OM_>Bs8}}V4pGj6< zPx}yo{<*9~$dLPjvUh}`I_zcX7`v-IrN?{ZF9YnNb9}?X4}2lhdLO(`tSlv ztwMBgg3vAuH1M3F=(c)q4JoNw|%{WHuQF{EaLJ#0dIupNzgX36*yGPn_MMOUz-Ht`a zg)+MyoWH;NN?Ro#J?^V9vLU;hNqRUYSPH2-F&=$&JH)ltp8jHC;Ik&KXI6Dk!_15@ zl6V$i$bxy@Z>d~)mhwCY1sG&ToBjzWPB*T9T}mH7VSFS%X%w{H<7eOhoBl*=7}^;y z?aRt-5%?l#j!_872cRzawUligzgZ;r2PSt!r&{V8jI^&JUA|FTbhBkp{sh3LP77nO-38u*zM3CNWJx-u$f2 zI+(AYOe(bJw19Z`7x(8qrTjzz66_a|ij$LXf5i9UN3%8{$& zt2J6IAe*RJ$8Qb439Z75_AP_&0j8a(WOHRf>myr-Ulqm?w=rb2jUt6i82Z|AoOt*KlJESP?XJQ)ya*7(WhL=n4D7l@;-#`09#G$s3*K)C7&?h6OFVlAVAn zfLCrDCnlsAZMYXb8+N+kMR79t_ol7fATT33!mr-NCYwn+G%eG zRYdE+-q~JOw|Y2ki_HpM+8Jq~T1#)4eMidpb4iU<$6TC17aQ5u1uop8DZ*PCj|$Pd>?#sx2fKOscs2;(So|JMTfHKU0*g%Q-% z&-r>(I|P;7)3aj;4t%`(tL&O@$O>b&P@W`zQpf3Z>vH*b$BiF&tZl8hPG{iK3+Uc- z)$`{?Y7x^(%`nBg3gqY>J(eZ#Fb^0$T9(`;57F!!5#a=YF`MIHUy(kx5u0s})${Xf z)u!RKERPrRh`)MU;j?wL*t_R!pQyQ@s9Wj@;o*fXu;-vOB63k_yZ|i)aj31@P6~5v zJPbJKdXb~Pz_D+w;t(UxtjzE@e7KVQyD465dvXp)Tb4^)3CEq#oovHcggzz&?@%Sb z^a-Z+etB7bU;TIvwOnf3Jtp;m?3I^q*ZWEg9bgnzvZukXzwo!dL6;155b2T!B&r*_ zwDDcJ@QAIj`$3Zvt#&oDMy7^+^&3l1IlU1$84;&-JdgSP&-hkh;z9o_EO|!+N7rIo z{MI+-Z|i6JLFbOAjV*MZSf4Z9)ax`9f#C7APc6%C&Ion{K?$*AtdvE*6!^f)M-kMFMN3H0BUvAZ<-&@vJfYmUe_x7uFkIiXZ7h=<1+<^l--3r z%b?QwU){u$DX83|Z*7RU_+NmK?-4(+`MhahW$5+tE{&TJPQ9Wv=HK5c{_<^>+lxW= zSe~{X0%_2UxZp3K);=)_l5}uJQ1C83m9O1ci5p)i%Gb1%&=T$Ph%mHjvVt2H5H<-z znD_*a3T)hAj{;CUx|l@TO3baqLbXJXh}mHEtRqU0X*51EcjJ+%3baGlx&GO-WWbdv z?WHPh+GnCd2AG|Xsbwq>j$SLa(?)Z2Li|4r!^>bysz=it>=>=Gn(WA|MSEZFy!Iq{ z`hehHf_2xSxq6N~=r!`UcFk4mF!TL4yj5ntP(KVdm~5^92V#YVLn8?>LJ@n~zrL*u zlE7D(BKo@}nuo$A)qT(b*hNigRMh0^q9pQtV)l&uWy05TcDL=M`crXdf+c_Q8mJvn z4}9`v6;=}9Y=5o#Uu}VUO|yt)bdjY5UakK8480gFXmF;QNgdxavGyo@pt1IpCRh zcdz5T9$>XRV-#bwP>_dh$*5W;%WFGJU6*t9hoF`!LDBjYz-WSNa0-!WN(tE6&}g?^ zJRA}z_|u!vp+mWUzC<`>zYY>GxUrv{GOIa{zn{-3z*$QmAeqLnf`DDC{aXsO%Q4;f zWrfKTcaYE9pVdy4v2@j&b4zgu;R*MZ9n$J!f&Z%e>%{qC39VS*E6QP&VTcjO)Z;9A z?vI^>!vGo^276F9kl)m5=$pprJH);nlmoU2C_KtqY5+Po4Xy`c&|oY z0B=CqvlD~Z!Akb$%(EWEX+dlJ%@q}8pnY|<_fc(PpdywxJ@MP@gztLp0;%p^;XO|J z@_)KIU=xdFCBBG&T5WV77=zxveBywprk4api#*u73Am6x1aVI8bQH8ZLp+6@>3 z^8{7MXDB<`Y=;cpn+_R-#Q+S4rEt-MK3(ZnWcm8rG=&>^C6vH1qqNjPKb<7ko~GTj z;M!Tj=|k@aql&x8}E3G!Zk#k`vHMRdpHx{n@qm2Hrb zQ`!|Kja_fvuags)6D>0zCNYqFGpZ~~r?F1K(0kBksfT zRn|Ts2aWKoC6qibKCCI?I8hu(w)UZs=tUZcj2vixDed$;tK{E^&VKQnce;W{X`ww{ zzLbmtQbZDKnKfL~U#q| zDFDdal}t$>+c}w8-KVelJPx(IT=|nLcJYI%LD?|qL;%XA7a!?cLLt=m)*(n&$~Pxj zO|)$jWZt5nL@aPMvLj;PZ$FSJ`z3hgcHcMI;cy}6>^mrH!(-(^7Ys&{M%{|L&=Sp=Rq$ps_l71?<1{nQn1kxs)b%`LZBFJzGa`rGu(m8TJ zYGNM_XcXvAH^7=z)|Y5LYH9^N>?>>OPc8wkQM--N%wq-`=uM9>q?s^MkoFGkX{L|*a%LN#Bet%qc7aF1|5(S;XEbO*@Hpg( zYsfYVKa!#89AGc`lo!^pYQ}C$1YC7PA&;GzCFxsB0nH6Tl4MA;srkdwIM|C=8qK8D z(-ffYD*q4lX>dG(v<(m?B|uqPDDP}SmJYu{OhEgo%_=WfLxS?Y4SxGZ+fQjxJh$a(t8(?!eI`-uyhN zzOGt>^Zsfyd$kJBFQd!qpj?K>YD5RlCK(iZ&c_8@+#8ophw)g4b zc8F|Zgld~+T|pg>PyM0XtOroVTs+Z01lr)l29lU45W%qjsS^pnvu^e=jC^y zH@CR#pNAUQF*>twuqicDa{2nR2IXvb4r6h{a;R6w!r3+u3}9Y9yx8^SR!&&ZTF9`E z$#Gy*@c|c&uJkRM3y&p@yHRz8v%-kuA1LXlQiC@_;BxniG3>x5n-TkRRV}MbY;Fw7 zMtM29d$PMf{G%&LhF>$D;)pIkd@cDF^w$LOE8WFNc!@;Qv<0eo^JtJ_r8J(MvM?9k zNxWE%0bIyWa}&}a4LU?eCEk8kLPP*@e9xqlE#cPctuP0v8-_D0Y~nAv(z@Z65^)tS z4Mcw&p`aVG|3-QxS=-{1TlJ{%p_FRV&**iXv6+OJ@bjOp?g$v9n|!{i!c8d%^gbvC zQ>UgI<+Ab}I-33Gal}!w;eRbrdc#S|uWl~!)?K|6j8oUOx8L)gq>WP8ci9e&8>{6t zg9zQ!E4Y9*p(7fvN(Uem&&M=wy$hEPiymjk!{-p8cDr=#yKv#9N_1bMeg>kP5ngZ| zZVtx;#^?^Xl%@itl>d9W6N5@N9PO-tqhjb^vDeU;c`s*SRr)`;hf{Mu-@g5{x_+ze zimjAw(ntc_`P*rm)6?w=pi{`|76Zb0w)=Gsume&Hx06Q6NPR5eYb6`*ygeiS_Eypc zZ|ClL!~-fMPLSUdNYVb0Wq$Y9W`J&<<)*0XWI)0|fWer9hAafetazILJIUbO<%DaJ zvIo%~05CVru1RNkzJ;UMrRv;cUdDxs(ljNt^2Ja&q1bh>CsB`z z0=~K;nTii*ao$^^X||2wen?2aa`w*Oo}sjv;b@m*-ohtW8r^$$FX18t6EO~>{<|fr zeUjWs6pDMcgM$|ebu>PklsxVwq@euEwtxOiLMI{Nfj;M&aiJcRoslW$A500Hg?VVT zg&$-DE+EwBEj@p>2Y#CVFW#G0ppC_)v5PFhy(|%Q`qkYFl664%ig5st6I>UVcCj$4 zCs5Xs+V()XfduS)wF2mSCb z+u}t(dz^HWzf^{&AkgL*cj|&)jc4q_Cu~Ph%854fo|XXE6nk|F$!Zb!ET#4H_dE}z zXzK52Ar~q;hocse-!GWYhF0UM3>S%DeUdu9Hu}c_8!Cui1Kpb0P&iFS{P!^aEvKtP zJ)rd)@}tI?bkTWJIG1WDUH{A^DB^?*Ia1vxU=Twr3r1fDhK3%@;KD0X=47>S==g4i$&Qn5i?8q~ z%|7(Fp_We|fw=t{r>CzZhYbBYX8+QV6CJHCGUPd-`+imG&xm0^`)~ zH(<);7c8~`CX4rM7K0LDKeKC^WuQ@!#oPb!Tz#TKO(PtRz^WIJ|T|`0w4UZeNWnz;6Lgx@pD_u z1?jib7(A2qLMfX|kG!ppevu&Y{!%{SB^Qm1=O@g{l*0pKRfUtOB%_s=$YAB<{rKrV zTY_=8Kg@Zi#U6k>rPbk~DWnkDb`VJV@Hli^{dsX@394bAvd|U3Gmh(%h zNjKv9XbY9@gW_S`dw!sR<8@UbNg4Y!wmbGy;Ai55c0!Lw9zy?g=k!FXtE>p5e|R?H$svfbZNOWz4troRp$@3k*sE_7jh44gDDI%)jP zcQJCH5I043=m`7ozKZX4^LVR}lUwQeGRTTEt5qSAewdd=L`O!OvrkKUBf*927%<~A zQ(S)lTu+zo^pdBLxi6V@{kvCP&}W5e^0sk6k=b3KwvgK&=-SNR&wcWwhe*7SMFr=n zig4mx@=AqokYI^b^tZ2dDrp{h{r{}w;Sy!zrWNL-RhjZFE~=Mb}w%7J@9454pJ%O{8eTI*!2vph

11rycj$w=8I%GkNTE~ z)?`sPqNil_HsmYY1|9`PwQ$QQb*(+--oo^rVksW&pV+e=V$XKfXaa#XE1#xoWx_IF zzpbZLtF$~`1Cx5DA{eve7SoDd+t+x0Hx-+1SHz2v5}MDP4>`D@WoYY&KbFCAQ+Z>VL#4?XQ=jcwZYHCUcGZ-$#2 zPg}F5KJBi77>g}qo8U_&V^H}zX&x97fzfPDdxe?vci11}9Tb`7YT{qigZQ7c2sjLk z^d>y=2v+sLZR3K5oHg~Y`8t_0!0COSq#wMegFid*HnFgqLmrdvVt-U&ihL?#yU>-p z1G(NEVzH8>BZP*Wpc-+82y*7W?(N;pyOJ9?(F#8cqT^HlkD_Y~h_sEO+1Rw%cAL%3 zwvElU?ag*uZT4nN*lfG0P1|O>zW4h-KjxizpL@@9&$;I)lJI|=aa=w66oLPWf4Q$q z-Tg3%o$ZJB*dRL;;RK91!tuYR3H{v(C_YrYpMu_D)c?M#Jfb$hcYBl)BuB}85~|tX zHDbPV$q;b9IRc@gK$Fn&D(|7Zv6%JQa;?CR2)buKS}>=@Y6=`}!b`$`_u ziCIZ5(j+%dDY0}vgE{6!U;JR8H-9?yFs!L4L1asCYneGftcguOYj#rL3ksVBHWbGJ zW92{j!4G^Z6+2JR%Wp`P?nM~4U%{P?v5zc&J?);P;qRw%r@ztYF84u7*p%^vT5KkR zs2+taO!Yt`BXOJF3}Ey>j_F#fw?~*$5q{?f>Dnd}y~P2c%cgEK3z9$;_pL8J-?p{dR>48yhYa7Z~NbT z;dM~Zx-W9K;U`-IxtLNWsr8(gGy{SW zZigA%xx1I;{%&>2@5p_5^>lY~=bu70eR?VWOlw2_y|8vw-VE&{e)Gsy~pq5={Y@A}M~GI?;U2|*9zoG0*@ z5B2k!thgAA1<0lYsa&f!n?J<(pmi96u+{*zm@F7PT7dAI?DS=T#br(k;R%^jB z&&tY!%9OZfuMw>%Ni!3REpBn}A7wcxxN~fPGi8za{Vh|qKl69aBi3nt@HgYv8)lyC z=>1T<>>tVE_S$IWlbPg{qBcX*Q(~@we~IDTI90z!2Qy>UjB z!KqiSPj&~#i>L!rNxH5P>G>#)zy85O`AdkW?C$CJ(mS`={Waku)Pt|4oxVHh+bNpRP< zA%u)DKHSiA0KADkub%T5M14p4{@6sbF^bEw7C$Kw)!mQ zofPyDuN9U^n<+ZL31+;#hy^D_>JCQ1YL;sC8w(>Al0T3K`#ZVh-lVia+**_Vay)hb zCd67lNm0*(#^AE0J443;t7bn2$_|bQ%r0{Sb=ZS$XfR#j+e}&9N>KJ013Pv@Ac0P| zk0o)@#15M&y6MGu@{FNK_sXbriDAPSF6Wi6S+3Kle*|h^x~(33*%L-v!NQRRhO2km zZUPP3(4pT;1FM5Hc7#|1kM7RQLVH)Aomqb2zeH%6&sln~f0CWpJM>WiAl+TZk)j?S zcHfh#YAkON+Htc}xUj6OMB(p#r^A~~Dhp)W0Ex;2ZW$D}4hDK>0Feu;``-T{%(T2@ z`zus@&;(18Y5B~w`5MvAPGhBydyh`Wu_n)6V44;(r0m;Hkp4d)zj*u2W9O?*Jl*aZ z?*~8HM=Tg-!)Tl-W}<*PbD|D{a4mi){@ZU8Xia;E=}Ln)aeN+X?>Z$u0XBL%nUYt@?4(Diq&3{{+fh7o<+MMLKKE3}#4)8c}y#_sVM z>;2m%IpR}#btnHU2XJ)yuV!`rt%kzb0oZQYxe9RTS8fg9qr;!ng&Ws0Yjp(18BlWSlKe8dxu zEe+b+IfM=NSGB%mVFaNt-DGL_95YFa6L-8L>FXGE^9$k(E+h-rK!R}4$Bvcd2bK=P z=}3i4?L7zOFJMV4#Fo7d?|UMUfal;dDS46>W2WP5NF``XhU^5lznt~=@(+kQ&WAaH zNrPW|6(}RN!r@A}Hy`=;Wk!gzHJ?rm>*e4^*E@C3C1{B^TT(~Csm99Q9rwSauf5EI z_V1BDlhf@OW9zRVL7LDW5 zIOChALH^gkdm^x$hd8U^oCA!94~MYPn?iT)YOibRhN{c}eaZ+P;#g3i1@6ONwg=ZX z#GtfI`ngEK4IUVMKGMY)L0&Z8I;9|pPtaa=(?aP zS`)FW6M6uFo&;bJ215h2=SyY$>WGGk6Ib5u`m`LpvNG5oLklor&A#UI*)=C4&f<13lUZIF9ihy{t*9^Tchg5#w1Q|oeigr)P_tnB!ZL0_WZ)jx<>2E7 zkrob1`e7mVNq4go?f65}ROF@Ls&T^|rRLbB5vE z*`?w!d21C3*Z-Cj7shMk@|=?RY?MBmWu6B93LGTY3tR8vccf3wv2o4`>7g&LylBX1 zb-|6F;D=IDBOrXNRF1_yage_5&6xT0{VD)#2o&L?AWJBS-M8wA9xs1FpK2Rs3!EA% zyrx>z^p>cG1vovf4>xbnLbi;YkMH~gW><(%O<(Mp7syOHqPtej5O}!~`12B96e@yt zZTOxka9?~SHs>OC>Dll+S3hF^aGsAkV6aFCt8VKZh}UI*UNw zPJLRHmE0^#_blnF;A}FuzXJp)Fg`R80j&pb^cZxPc0*X%G2R3I$Wo2kyVoQN%`$k%Db zLV$mB9%OxFDQuBlGNg}r9H+(i_QKNJ`oyBFOI$laYUq7rFH5xH!%GRmj{JHO!4Ol3}lxt*XoD#zp zPN7hi?+7mMDa~7E9n72)=kEeY3u8>H^Og0g?NuX)ziKMhH$nlgIM1XR2|rfOY*XRI zyp5ykyS+tM@J1$kzAKc3dIwqjDWxB7V5dkSw6j}`0=xB{#`)# znbm9%Lji2~p2kQ<;607~8=<1G7?#COOAhhJY8ntf=P0^$97D&DgqVTV@%al}UGo8P zMg;;@LZ>BNH~Q4jc40-c;=g^~hS_b6tD|!OMNQ9zFXCNr%DCP#3+NOEnoC(OQHrep2>9?!kM4Z-XJ7ilUI-?WI(flt4PSHM{AD9tR&$&`e=|hem|P3 zw3XMmhg=;ARCg#V-deU~v1WFH*Lfh1Swgv?O7t$P=(`<>eb1!|!SJ>f@M7*E-aGf1XB&LKe|swqXO%X@T%an{Qw+oDL-< z_&iIgNYh{6#q{L){f44#D5+wwE>ERFfQt(WuhwW$qzWJKlG(ngpSPQ_QRz4R-QVQ( zNyee))<$2IV? z&<>thBAOO3jccHP+J=}~Vaq$yVY1Y)zzEb8o3Ar6lO}$B&7FBI7Vf(6_eh}ch78dm zIO_y^H6s6oeVfBS4{CtcTiAnD#aa5j(!ku4A|1)SPGm7?UIu!Bt?x&cns^qbsy0b| zA^hmMZj4RB2>wo*23}+%EbXdKP$1{gZ94+I17zV`j){;T<0&DwzpAvw2n3m;`<|&6ZCHQulA)DmN>^g2bY9A=-wYBO+Pc`IlGT z?5;p3J|UYguhl?81>y17yAA8pZnffdKBS?BGxuVKTN+nK`rbltPn@Q_no0^B zOAkj%r@1TuZJI#w$bw~I&7IxxmLhmN-jh9*+R|0g{9Rc_$kmR)c?-)f_lcbNL>GB@ zLepaX#JavGQu<;p1Qm+dl_dOf@D^=Nl0vD{eUF}l(AwYG?T4PIo{LzAAnEOBq5kg#J41*%i#Uxbz*tl{1y7N!6LW1RJsYx}hu+yC!`y41Ab zr_>zhquXQ3C&Vo>y=%ssdznx?&s__=yXw9}{in*Cr*}4$D*X5dPEx>qyJp%ayEYK& zcXxozP?8W#!9~uxt{-DwgTR|0xehQb3Ks|feY&5^Ru?%-qeEPUM z{}j>fH@4n#TG;QIEdXoQDG%{v=XW?`H#e`cSi4~K1dNtFER4f`v&;qA&PFP$o}J6W z@%|9FOW&%^Xus8MJ3K{SMHT(6@RyL)|Dq^HR!wLmk7yZb(eM`5ti!L5FbD zVn(b;R&(M0rdaV9Gc}8qqY(c+WYe$;U5WKOka5@BXG`v4h26IvzAa76ep&CGRWT1X zqA+=R9J*Fz7qyao+*j1GTh0bO?oY zmlwubj)o;Y&#w-)#PABY(To=k|MNhpULn7FPHwtJTT{_F-cv(}_;DtWDm{MRf_1x) z%2b29z4LR_{Inq)iTKm5!%6_f-m}~a0nRtaQ3?Dktbk6~&c`f5RE}$mN`XJyM@Fyk zN!4I%3ys(0NI&%>!Ltkt;HO<_L~ZO{)Q+OZDC@eQpBVUBN#a>Z8SvZgYOx&GGOIy^ z9^-V1r?Q&vnkx+&amie{RNKrjNeC+clmeWQ@z~XUV37!Y>$!;p& z+hv`5)w||#6C}xk`EOOR?!&Or2v&1zSiV^G-{ml1_ub6IH%i%$i#ISLFRs)g_e7Ue zjo>F7Ow=Yw0@Ry@2X&MH{}qT=;WVC4>`?A0$hp|}(U?!~^0_>yRwg2G3(K7Pgz#}( zl797XBqPLpPJG(#cM~vw7xl2*L9)=0p2%H_+h9nzu(=PJTlP~fc0c(Ra>|-dEhrCs zqk!h?38q-T16u)pQ$)_N^5U!M;NFNx=WBI;Qo!n)Qin~jLH5=V5r_sd=sxG{&WBYD z;7_IxEk4SB2(fu5F?djW50l-1HZ(?&Fdp5u7UZ~}=@jn)L!ubkKDH_3Cr1ldi%jBI1@+lnKDgKf zh5mw5SnmeOp0`tJ5DBpe*D!{@nIwhUL0XBhC9@i!1~-8 zU0xT>h*!As_p1cZd88DC3ALO};zpER|UG^XB_c#U`GPknuOT(fRZWDoB5_khmSYI*rBeB2Gz#nro0v( z^r>28Pou95yqfdnnF=~W)udH*slneCc*EDin9cU;wH4L#4^kpk6la&_Ata8g$ zm>A;8RIKe^fik0smhM;EaXTEZ{ZQfoy~B}FlOy^OEs!Mtqx<6fD@MqXNl;C!GYo<+>O|`w3(WD;cUOuIIDwh# zU3M@l9PjMVy^LlI;4(B<)^r}f#c49)f8=y6M8I~=(y7IXBYGLo zPct+1>^0g>34Z#5{%S_Q<0PFK6jIKx{{fZFQKn&{ZsMBc@PiG}M|a5ng9KXB8>BpG z_R#+S9e7aR(rDTN*r~a*7<#Ck5B><56YjK!Rh@Iy|M8%}=oziZzSlU$HTx_7YN>7l z7{K>RUe=i9Ll?HcYygAN86c^{*ngfr1X_IJ zwSDXKkRzCOI&sal{YP#gf3|(Ts}D7rhoOZY5BF$#x9Pcue5Kem&zaoLx(c+-$Isb4pN+2#5a9)04@V=lAp+KvOjHv7Yd_ah3P?0tq>>>ge0 zD@V|htvb^iLH*5}GY^aeKN0qE-!F_Jy%76&qeOIH(t>~iWz@_o{Wqcu2-@%(#a>d= zaLrb}p}i>iXrnzDmcd+rKXC~JPkx)=`ZRf2KcpA}@F(YCsG)U1^nG4Z!QMp-5U|YW zf!>G0&?K5M>5OdOF-AN0+Yi-;pqx`9!MJ{r|1UAtK1_M&kLZP*ZV!>w!Dx>D?o2(I z(L!8pw$`~^3yuq~+0gT4*@Vcu^xYgQ*hb{|zGG7a$OiqWvQb7fEjPKkOV%fD zogOG% zoi>NUq$>d;P%`y3B6V5lnz(uxhf4O#KXY4FB$KsY=T^7lR9{vgu1`0NHgM6Oinp0h z4q5cj&qpUC?Q7L{LocOX+@|-Eo18~l4Vfg=tAh`^ijU?u*+gmdmG^sYkD}I!14q7J z|Gy$XA&+&w6>AnnOF}IzTwfFxQ-RiV6^0m`8Rx>^(+ZKR9-2Y}NFId-1_@(X{*P^^ z{IE~v$|?&@L$(qqPt_=9)E;imS`$*4TWYG(H4G0w)e_0|8bS<&O!v51sdl) zPMyFcjAX34WtJu0j-0cu=ys2eNY|e-$JO$Xc01;h>y>X?cI}iid{5B@ zdDLOu(hnWJPnKlzIs1{l%a+cqN+)ZtTVR;$=)E8@ILdCedG=Xhszx9Y$H)A{8hH0VTYeEqY1=K0beMSQe5MO7wX(Z#I_z&@* zCO_`N5Pt@~M>bQ5t5I0YPxcV#Q*h~DiQUpU141Zn0%8Dt9H=)gMg6iVI{d-IR=bKQ zX9dsGjramd1l9R9RWKD{f1!LT2P+mC(nH!PSnQA$P;{A#%#<-4mO=(*N~&%<^IxL) zty|0+$lWqiO>M{94@IguN^3*Y?aW=cJy7+~0a9l+_-N7&1=t~4thCQ)?0s?aP&x9< z>EYtuS>Y9$xT1B4Ykr|_Z`*$in6Lh>Q3AdkLcXpWUJj+9;<)HIPb~ZmHtnB;oD4+; zGt%N8{MTc9F8sm0c8Yc;q^aKuI`HwmET+rrNCF8f`a-1Dv}js!qn-1W9sV(q^^V2# zyw0mf8s1$h<0=qChY|N&4lTF^;5t5;8M!$ew#|VP(U$wk zez=P}9mvXWC6@nR@dV0}XYfRp!^;sCG)C^8Y$Zmhyz;%7i;Z%5rrzsOyVO~zwgX9F z6}AcFUT1)D(sfAY08^@zMnm$o8E9(Zj!$W)@lfJ{UEKevuHWe7^C`?1=CQaox}6~~ z;mo$k4GL{poXYsfW(k=t= zb*gat5j|U_I9K}B=|$mR6Z3P~u(&v`uOAcGP8(&8r+??FB!}NMcfK4^cq-=sg}nVy zYsr>_At}iIy7*TX8p>u6oueWvd5Rx;f;CsGN#S15(T~+exU9%?@2xa4z?k#)CB^03 z6Dg^Enuw)j4C28lzlPt1Jj;85u1Ry>7*+J${66?sM>Z14lu(+8kpdv1j0qr|C{Z9l zP|)=|(3XIG7OqFQTQe9)Fr?cQt;X<+y5OOf|0d=AHTUhl(p?I`o?7xdrI*&9&h;EIfjOzavwi;T-kIJCZVD&t~@j)#$Hu}4l zvkVUCaFOa;@yr7x(E{6#e2#fW2xe~qR~#>HKmeef85edXOzPjB+VNQ6%IciXj+a-+ zLVl<%sOvgx*BDiYXjJhbjA}cYyUI6Wl^sJAa!Rzu~+~!{}WJ22&Re7DC9w-ra)$QqT7h7yT==^{3A9k_aw_<(uwRL zw;8`UeeTHjaJI2=!U0UK63DnOmE$0{k$ezZj2D9AvKH3aD$^=d#~<4|8W3Ng;oEi% zW4Lyj2wqg?z0N)!KAMBT)2azy*<}zh)3$vQ;Iz<`lFD%9Vi=1uYG1{XxtWVD_FK5v z+go1h?)a>LM-Y5S(Pes}>)WN|ix-K7tBb~SP~v`;;*^qi6hu8~V+%Jg^uD2iov;@?Pn_N`%7NzOOYWmZa~&WtbYyOE|DX$P6H_xFBc2Ng+(+{T&)aB*XQcw#mhDYcr;OMq*=Cq{Z&(!FL0uxKB(nZ7xm<;6& zc-Qytz#wqW8+DY3Lx;f!Yy>j#VCp}FgNayA`?;&nJ#1gaA&r$9ysnIZ?Yl`8=ZZHx zTw;sL5jjOKG$`aloa>*C0*1e$s?t$*g{ZB9*UtJ{wG_^!_!HKpw&Y*I7M0mPFwL>x32nOfR5D!l|jNMQioBA8v*Dd1-zXZMM)7 z<-K4Zn%>l)Z0uZi6?G4yI8Xd)4U1&^4$xi<4roUC<-tDM*?XBpD=SeikN9&VfMB!y z`0nA$P_vpX!<_-2bY3G^V6 zMhvK!rPlCvw})clQ>EO2P3?LOMaWtrhIa5&#nForj?zy<#+5nDDC7+TP#vFhauVq& z-{mZg!sp>LqhB)iCbYl|zQWx!HpHwNQ-;WAhdq18H2_6=*yj#xzfuJHHzmk}vj;z}+J6km?uQ?t7 zy3VC1O+cnmfQUkux?JAV>SJLh(!~7wY2!sB?UXgmRA9X&Gp*t~^hLeALdYPnlI3^H zmrp;M3%A#VSZ1Nh-;j&U?(~nIHXJ$}#*pWi`3b(OUS?hi#Kf8i&9_JZ*L*{4&irjq z9P*CM^0RV`dDd-VBotLwR`gBr`93=g8KR>aNo%4_cCbyv{&i{C66mKQdXt*H?ZVo& z9Y+M;JZ2&9l>53Q{0yUOPs3&Wtf{%TxLnKzG9X<;3<*aDZGfDiHG>xuzF;J!?PA%} zQoFvA)RMxDiPD{334I2uaLI;d;c;8)R}jUy08uqh;Lf9jRNCp+)+X^a_H%uyn}qvWsmMv2MEli%K6>rTADAQ9u0m&BvaX`ks1k-{J} z3FzxYg!_O=Evk})$?Sb&{OU4f`F6+1_N)o9e=eSFZkdPu-8yqern6tkM0zB2>us4K zh%?kyyd{@`Ge*b-zxplr1NsDY?WCU=?r)w5#y@wVf~<}gjIq)zm6cAhJ&~zU%+yMeb4$Ag|?$9s?uo1 zc?+LeR>F17IWSN7e8r@LRnn^5@UL!C2M4u?>-uDlL!b0cJWK=Hr^)P88{hp z5sra$Ex}#3s^a++5#`lG743OCfm!)L5oNOzJbQ;Z_P^nD$9ATM3MO7(xC7lROC4#J z|37sk!$+Cu%3m~7*~yKv7gB}c`sxrINHRS;c!R{c5#5P2F9Ae?iFdJU9Fq|A#*VP? z-+IV?wh5|EKk9`L_p=scDqDpzJ`K+tN&^2IYt@^2cR(y64Q|+0Oa+U{Y>ki$byuFu zX99~QNBh1&DuEvr{L+wcH%lUc7kQ5#??H!reN$bH9!OL-6Hpg=4u4ski2qu!Ktrox zag-~>gNhjHm=WBJ}S$46*2AO*{XPxH=(!}L@P~} zYGaNL3atbjw8IuZ%mffgjyV8DD9KAu{znwrkCt`#wYLZp=({qNnPy!Rm7NSfU!Q2v zX_d3R(b>{1#xjia_ z$OEao;$xf63ApA5JMg9YkrPiXrQLT6Qacp~Bz~w^vIxeHP{$P=8+#%!0_+fUrvCu+ zZws>B8&UBg{e*bH(J5=)=28!NAT}mpuCV&0JlLyhVOV#E%aZ=~56A}UY4XprF1|MT z=rUKgIY^%z&{8!MU%aK9dj>bAnoSXYphDH6uEl^E7Gi>!(DVtcjT@^MU3sZur9xs0 zgu=FRfV;zVmjIGeLp=1l$Otd1CfuxthscG0TdXy2muq)R9r1=}>P^aT`p*?QZP!DN z%#8RR77t%?ad&;~OxpKDhGyHS{${a{xwupn@DA1;v)HeqB?UEf<><|6i;9zOZBl0e zYrRfl;*LVd#DAqMv~C4;w?L%{Kac(2WcG1aXMrGh(`v0Zmoo&*(C&M^mB-I;=c7*j z51D0DG!5M~h3JJG!8_8`&1(G*F$3Z7iBcqsW+!R_j7w8lJ3027J?-qk=h=hyXlm}+ z#o(S^oC{|@$y8;Gb?_1>Y#K-$`Ts7A3J_QIM~yni+v(VNYZ`I{s`~`4eCt${64Xp% zpZ3g|*2BV?X_w^;H>PRWy}@iV;RaJ!+(uFa%phglXZxU(Q9yY`+|&b-55Xz8rxPHj zZ^NncAtU$un8swI(W^LFENjdhR44h^m_eEu&GAEs^8(%u!UN`vb`{H_zm;td{@V*; z6FbLqz14Rx7hzt_PNn<}IPBc?*cG!O2Ww^4h0eg*9L}+rpY1r_j)+LzVFHTk=y4v6 z?+ys_M{Z%dkSQ2S^!${!=jW^}97+7iTY6P{1W?TqD!-kWq1#EEyHtKrM216{R_ko> zuFBxW=P#}*-Hgq*bqIXgq9m~9{by_~3dCOD`}Gk0H`vo0dwVcV0^s9t zi_c=C7=1pMYmu)110_~>aHFxqj)IEk6NeM#qV5KW$WmL0F339Rs?rI5^jE6iUnVgs zUYpERAHUGAQpDNE+Ev!u(@-O>Gs*8^+Hp=`eNyT7gAUjH2B4op&CWY&aJ2 zdAKDgK-NX;)$C^-J_UHAO+;V)>X$xPQ)SQWN`oIiy_MnH7T+A%UA6ms$KISQcSf`0N}aHXEEbci zYtDV)L0Rx_F9R1_i_0PA^SJK`k+S`ldGQy>NVyF?C>O*EKE;UAZY0k1FZ9W(fNA?O zgFRrUG}57SF&uR)`mm?Jwe;0;_X3H;7b&0gC3&|lRdQ1=DR=FxkiSMoikL4@_u$h=mnQ)S@Tm9AI`R2yYxDPf@-@YGscs>J*voapP3KkAX`(L&vK zW1Wu&@qbJDRCiw;I<1m&5JuTc(29D$FI1EG0XzOi)lw{&&N(m)8P_~i@Gz$R?UX_$ zca?!n*jQ@K3gk)h@@=TooX7)zBPoCV8`1}k#Sx*iJ^vM9)~M+FvXmI!y+^*8_cNz+ z96CYt7+|C(As|0;eupI9;_;2get8s-FlNB`txj*WL1^Dp7y?11VguS8oSkN{VlAt` zNz&A#h;wa7F$5JMXUt|^@VL~RrR!eYj;1Z<@w{~$|5O&zAV~YQ1~$4DLW<8+XunX= z!CWU)ba4)ekyl)nncRq5qnwW#OMZrGUipBsq8R!STTa)P^``FkXH((_4d=rY?1{KN z6wkEf@+`vsspAY9~lBGRhA@wmWy>V~8Fw4uD!vDKcu>Tc-@&bU@O{as{$ zWXy?!paOr*o(f>r%=L+gb*cJ-a%C`f>sfllF@qzYje}zN``kM;$W>+)o|u#FK^bWv zul(q~eajILvTOtqTTJUyu-$4U#64p|d*kV%pAmK8Aen$jP%zbR@$LB&$7Jg zcJPLY67%tV?Pc#OfZUc}jC=E&fw)L%1?(_XW&b88bZz3E_O&K1>Q|eMK{*ZI`NvsX zk(VSek(PE{f{nF!?{*&l-@UR7I$YSxtePgp~k3 zbC$kYlO-07--&8lNyiF8ld-(RXV2D5!0DtDWe&W$8Fc5E(2wJMJI0@U#;WZstz~NN z^sX-odnGRL{_9guk@wLS7bp)YT8Pj7KtPPTH9*%lS8<=Wh$WVUI_Cd~cP#4kyLdYS z1JEE}>lG1n!!N~z8;j3a9vdl#IYu7?+;RaFDeE$!uRpB1!kKh{_9Y-}MuT@@7Qql` zf#IZx>7PSA$7_5Q_V?x9kK^-%ltfA6y z#9Y?g&Uie58@$$0Jq=&M7i0U?m($1bfar1a#wNA%f(k)MP)FA<25o>bgF)b_7vnQ3 zhi#4+r~%A^oe5$u4(Se3nxD`EYDaC?9y2@j-=af=p3+AFXn&l1-E}=fX~E2Px3xoU z_j^pX8W-A8e58=s*kk4ITxmzAbp|b_h2ZfM|=6r z4_eQ{RdBX>*<^ep2ha`rP|3J#ZgwBv&HJEo%3D#`kxjXiHTM^74~8R8SNeN6MkLS{ z2GZ!yq24<-Kzikq2!8Uu$P5y_U&*yvLbupiV&&m$rM<@*+1&nXk8R#>m7vUiUG&M{ z_2f3~q65&h`7m_%SWQV5O-O~n(@ZNQkuGYS-;~9-H_cmh^=*f~3H5Rw-J!xEl(|^s zWPbt7vUx9y)T5>$9Ct7D_ITL(vxk4xi)7|RKVDwtzM2NC_WJYG=UAi`ecu_*<$h)Y z`ikHA%!PcLX@uBT3hUqZup+v%GVQGur>{pjd!hdFEvs-OQz8k>@gd{!J=~!lz?cck z;f|L5g{D7uRx=X{^KpT{u~7Q7>Lq19$=!kqejq!TG>Q% zGJ||HSrG#l{7m)gS489My0^z&YLLlj+h~7*gp^?m6%TVnUZnvRm&%Con?Eb`E8&v5+UJN3$PcoB1?;GPnJu+i0jT5cXM9;?;OD>pvd_Ia9S~+w zltwi8hM@}ANfJ^sQyN;7es0+);z3hTvqo=tVgZ*HO|;uWHtouAyBs!c|`Pa~fl+ z?7vz{K3i8!C>yR~>kGYbz?ES^DgA_a^A~p8I5pzuG17WofQFwLy^N6SG$kHW>)!UGU@{K}0@HOo~_(+O*LxrBH+fu5^j>!6zzep0lnW6@}j7WmQo~@zHcru z`kUD2<1$$6OAKThC(qSQ9DB&tVw*IBejR2LQvno-9M|gR(yKeQ_GjzE>t~+oPcgv% zwlP?vjwXU1?Dua%;5I?@a4 z&bAwPc&jh_8NrO{h;pJDp(q1BBmVn|{zYd)xB&aYUdX9ZEsiKw z?wp_08LXeksR8K78c|h5r|IsgTF*XJXdBKYwuCIh-Lio{3Yfp-VM!oIm-a>wQv+t2O zzIcGy2%+FpeP=)A$1U5@8|F1h)zUHo*+F^jd!6{B`DQ9YtzU%Eg9T-rBS`3|iVT$E zr+Y(P_&|`ZVM%UYCR<34&Q}GBRopm$5|K)YHf|}vSHTN`AAMeoynbI!K@*dFw8cX8 zss(8yFsuEVJQtGNg85!&gB^%A*3Y`)$+Zk#0h5x>bEQUFty_|_gL4q3bhv3Y1!0o5 zrhY38PazHLl|&)`i~r{={n-OuE304=!nl1|1F#$KZOv7f*;rb_FhveH$3W+A;OMkw zHUC*zbaqQPlLZ0b6GJ$nsJD#cB5*HRwSxe3ywxH1k^&W`TnTE>?`;k9wy&f5f=A^2 zpu9-dR~;FkdWV(e!3`#+7VX|9;$Va#_D&0{es4Ea{8jsL$R5xQo6CWsHwn^*{OM9J zk}d;WZ8HA3%&B;lK=$Mk)-7g!=`)EneTH3{`TfUiMi(tX%HA-M2VS8TuW06>KYi2@ zxcio<;vPe`;ghwmnntB}eA1W}=-)5Mfh8B~nwdwUhjAUg=JUD}CeM0uZ11fQ$^-() z`&xK9zj-0E5hPz)cb7tgSj$kcqDpr`;&;ab{HCXs)+G~(p0;9F$z>JCzSKYsNbe1~ z$291iWf%OSRHIDTI{pt=h*4K4Q)p;!2L9T#TIzn^2hDasjXQ|4S{ey>Xd6sz8ubU; z!GyefbN&!$6Rp@p%iDRs&|ltW$D^L?p7sNdb}qSyNgqCbJ{#wVo5|#b1HaZ|WSxI4 z?KtNZGv#&lTjI@ZDX37VX0J47Lb3;-77nWvLTq|2e9X@A)B;Y4s}_wgxk!VedZNKjWhyMBd zgP6^6Tk@Q@7shtEHe!WXumeOVGhux{*c){pC&Z-ymV=g)%=3&uhZo!3L_rnBw~U1~ zD_a+VDeY~Uo#d28h=aBud~f@9_+|;q5OIYc!7ApfwQjb z7+>`%N)dIe2(tcnOaalH()s6`j{qR<43d3g6y$7z@h<%OD&!i2h$K1Xt51a#y?#P# z!K{(fFoMc^!~-)Yw%Hh+5zh#WBPY5^XzGpMddlnW&JrcVccxg(g{vk|J~4X;`wrF= ziqa?;1je)?ifQ)f+p;!q?<5Geg8wO=TMN;39zEAh#UX03e6#$h>qHjxZ%fK^ooIBs zMW4!dq!3#UcV3n+&j$J^6izm~r!*cJt+mU}!CPRG+woAgd5|!sU_um~7{27HmoWB1 zR<4xjMh=hS)ios$I_%n=?>uLXO}Cz1v*j=Yam~-QmAkT!*}shYhY&l^%viRt)3S*_ z^Rm3$Ly`?>i-qbQv)%MfonD64ZZ2ab(6Tm3FKT?>*{=QUAM08^3rtE=NgOa?UCO-? zexEf3INMUXFQ10`A--m@myg@P$!uqs-Ld@)j2F}4ivJ| ztgiSF^`O4JM9{rZ2P<^-jG)?MekaVLewnvHuOhU?4Nr6b5zUk7(AJ*Rq(DCKGxbI` z^YB-%^uOt;StSc9kae9g%9oi4eW4Po<=>x+aX9f=UfxJYq5w&jQmIw6Q^pZ8sR;AW z^>a@E*kUZqgm=1(Q~M103!jt7z=ryF=BmHABc9$+pFWQXa}@(D%F384Sb*Xco(Q9Y z%bLS*i?y!${Ji&*0>aaQd#r!`@76cU7a!AjL?tV)w=_CSK#QD&u@;1tQuJpfFsOIo zt?w*u6EXe$>wv7}Ok5Wg?#sDu5BJ@o5}To0%}JFx;98V2=cpM{MCkn5jkm8k1d}m7 zqhU*J7k%l`%z3p{yJ~~K!47!YLQKnVpR60!qDzcZ)CXM z+*#gS8o$^Mv|`@e%b}7}hhbb2GZWU~*nq$>6}}?zilm}y_KVu-ji!cQPgw&l+1vxJ zezTXwvpB(%AcL|>V;Y2dTDN+bsb2sCOF=v9>^>vaF8tc^Ce{l{c2>$kdCwm~rW_jJ zmxt5<0)d59-7SddA{gz>Je7bqBkJbQsv>^$4s!NuBS|-g}>w3vCE=jGI<~3VRn1ICg zs=n4MLGiz?z5}X>wOboSK?OktMQPE4ii#2yl@cJLB6<)aqN23uvEUIQGzozeB~lb= zB65%t6cq(2ibx40ARUx|2*Cgegc3?fLJFkM&AI=*>s$YwSu>Nh=H1D9vu4jO&wlrV z$E~G2GGw2+{+n}13p{*}*)M#LVb3W}yGP#DAMbt^U+HfZ51UuTmp8iIBIoD+b~4Rz zF?z8wyAglmb4x|(qcv_Zo9`hf3?k>V^b@|BXkR0T&R-?#t75rBS^J6Lv@^Z$cg@-$ zEY$TK{`8<3o_A~cQxTL2^u-<+o&D=*RQ|dn&)SgEI2Con^HTF;3=TA`V($KKS27Z4i3; zsavPM+u)x+OQ!hluE5_G|h@}dIU zuOimEEw2rFdi>ph#;V+p8y_7)$_$sq_S?_9^jx@P?{I~#-4kLurQG5YOU=}y-NetW z5nwM31}!b9)fTeOE-HDO8@;x-b{D(1np|zJ3s^qqxc(r-#`0Y}BH=^!(y zyI1k>DLahQrZF+WU>zrqXJe>ZhZtwUDxd-)1dt!XI(kvw(H^lQuGwVVbI zy)i`+Sd$c?%2uEi=V&?S+SfKJ%mEi>w8qxOl8qJ@@9vBoJ%~gJ-y0EU7Qg4DEbpwz z=MKN~fNfFvL8;Z<@pS3;bzF>u>-%im+S~QYi^thg_lx^EV#D%*b!oCyhGxb-AGY%z z_o;_FsoceTpqHH8Px_tuoq{^+P3;m5U$qQPQ#Y-M?{{MtmJWS)%D?txoqDgHS$WaY z&rlcarEiC}%=V}mXJ)~~*;Y=a20n>tSM1kBc+w0!F2x4r#mwJ~8k@5Zjr#R-U$T>m zBcw}Ehn+Sw`R8^|ut(Mv1)%LK`)K=(x{e2>B^_-HYZRG97zLg*PSu z1|_B-^(z%$?l(R54~Yu_or&^xy0Rv9()6ArCGQ10R}|d5D(ZvM_jApyO~{+ryPmMo z-XlYsn--vTEo$ld1C=DD=+O>b$;7WQ1bZaOiTNk>&T+H8Z5qmP-t_Q`iv!IM zOnfkWF8e#aW#zX+_DoiL+F>>dxVY9U-=iW(((}kwsAAwdTWa+~E^B+xQ0j7xF}|^J zUZxx|ySpVcCh*j`;LyEG&l$mm1}PI`k1OcoE(iWCFIYHurQgGGbx+9!=>7G=l}0Q* zpHj!HP3!H79BiioKUte2K1F%ktb7Rqi35hLRIuLdhgs&8EqjmmN+&EjKV9#YiN?B% zqd*5qkjA@OQw~dKifeP5SFGFGt+(y`Qjw|;9-`JSRD6lO^+7e2IAV6lDP4Y{tW`cI z!2;3o&;2aE4pm`7*TzSrwOkg%qm$kKIOdtC(-Ro4@BO~>xW^Q-`9f*;_C}wp z7q(Y#-i{E;PB7efC%0jjRb0zysk@ZQz$x{~ z7w1`z{f7sV^obA}St>I<}R%YKJhBdE-avRV|p9#X^TZlOewF zCW$s>I{_bgxBeYVxtJDb2CLeLz9ylf0 zv(9+KqwdI;x}qCas%cbyd}|p|oQePHLf+E^foy%^!%-gUB0|xr3+^ zQR!p-y9?>BHg8hlzDC1#LDr?W;_4}S;3$id=AX_kvFUXt@t7WYeuKxOr}sYjhkdNQ zrfI)a&d2yGPpj0l>dCyR`I(9n3z9bkgIn9S!$QrAUiXIo;o;jtKlgD|#T`Eq*Si9YgclM^J(-Go4{C z$)|%4sHWae9Xav+%N8~2c;OamV0OVp)>c2d`YG) zl%3~YEVq~*SY&Q*@>2{N4HOSI>I%{i*AAw(AO$&AhMd+R4a*lGLht0y(CAK zuYyy~x^cGpB&pA(n=a(#-cKa!QhqF8Oq`kcKXL_J&WuPP^DZDIi zcqxc3|K81ngJUGgF}ds{(u zRFE$%bH&iRTCbJF*J`a2*7>*hS1)Bn@+~Tj_J_>BeE0m0$G=Y@R1O|_O+T#0-5s}O z*NsgVT_-)f6U%pgIq9FtwotB4bD-3|ah&&FnS9->Xcc(>M2hkBmm{xzDp!`h^`jqA z#_Kq4jR?_NHLxlD*xR2PFG~Tg(CzH$lJKQ2i+IG$R@MKMQPzG7ncUa(Vy#FU6X>?) zK$KRBA46O8==7>K@4@tRx1<~I+&6sYd4GEW;l|Xe(lso|{NjPo1F_ydnHJgCwYTf# zv0h!e=xW1JqFvKR;)6nm98N~Xu1k>)dhPkAS4ATc9m0wjbF<^={u0tRp45yB)P&7H zBJVEVfA~oTzWCEX`}*lqUMy02LCmqIxN{@v&C$%s!0NOyK<&J%`YL@jHMKRWV~5&C zfIHW@RZY$2s+!t*HGQ>U1pGGQHas}oGB^aaLT$r;-%yQI`*+a4Ti(d6p?8<68W(r8 zUSH+hsq`JHc`UvP3>v3lyC2T`X| zS@i(Jml}h!r)1qPH3@8QSe{eleqAy!|43ZCcw@;VywP6Ie4%P#67?cKJpWdtZ&?27 z>D&O~s5#dGH9z`w1jBDR3;2*|gQ^0!S?E;ELWRgQLy4ylJDw$3RyCrvzN30`0S05p zrN~f#BYT~0{Ku*-xp8VAJgjYF4fl%~Z`kT-BPhQ7m}rf?UCm5{S;!*KuV~xDEUGg5 zlNqmomiNm>7Don)|C)-iCiv_Ft_V<8(bdO#giWJHTniDS9veQ$ecENddilMgx;gc| zf?Y)}t25yA4Uslx5lnsd=-3AzMZpPpwYT#0SzS zZ8^n@ZSfEU;e%YH;&OA)mzU2ZmyB9vmeXn=2{0p$;{wQjP2N~&so*(p*GtNuBHWk7 zV`YGICfrYACL&tcA-!;sJeQ`cc#G5R62}I4qy}ZXm#-DgHn=%z*;yG2V=(s^KH@5gPE8 zUl?n>syaB|=M?KBt=vz6&n*8LRaC_hhyoP>@wjSiwF~Pd?=6j*wGTKwm2?{MQS^%= zrrGN1b=1;I&l4^7E&Jt{C=7qF+BtBc<$BXc+_((5#bxE=wrrBpMydoBg+-O$>dnCHryD%1ij+Oy-u_mxeaF%DvxCZq{ z><|}$zAnVQ2H~3M?y@S#K^vq<%&1BpSs*q6Nj0HD}X=X;L=g;MhP4V&_uJ%`y_!29dApAEUKE@znXLu<&}^r$iRG`zWG3aI7TT1Zil=b z(-f=QWeMl+Ye>7>W7!{rd~_keMwu~s|BP=bocuNiFiwt1#1xM%RYA5(+pWQoJ(}Lu zkm)fR_;A|9@FPJ&?ys8m(^>S-VN*qM8580^YTJW%!pZ~vIqD9-Q8mfv_lodwcAPBM zVs%jfpglQ495NZNrs^;v9N%q2Bc;@l1zlwv{27rom^xZ_ZNkmyCX{nU;jH%72Dy(NLh?*c4_zp>a0``m1fQC&0(+MiQ#bcD=B8w_c!`w25_JdLuB(G`) z1^ZQ7!ffKeD> zNLZsd+*eVlDH@@Ge;A$QiQbtw5C-m&Pm7i>D-(DFG_K!_`T#kJ{6;Ci>^i7JuCpDf zeQD2YKX-}T9m{xUt}(mKJcBzf?#L6~UJ4dXikjHd(`U;8>_T~S`|RUP__*&y;7UYi zQP%8&{48gq?C*lqpU8kU$Y2R-OBpb4cJ2FzadOazd0Wc6X47hL(Q3dS7uKbiYA04j z$}<9wqEoP{+|36!6^ts;ss1EViDPi7z=qw-^s}US_sQumbqeTvh2% zqvr4O7=hNQtbABL*k4l2ZkXvAtjXfJ9<{_UAB~mt4X+0UP@WZ5RZ`lug`2U8WxnVA zROkuin2{6K6FcgMDU$XF=se-@2M8|EK&;?P4`@~A3Vxg8D73UVOv~40_hk@5L7vZnV^EpbeYHqdK ztt;QgF1lY>2@|hXZ}>&ZP#0W=^*ob7TwKsAP0&+HDe#V8q7il@wToiNcMi*|*CCw& z>HJJZLs>HTI6`ANIKT2}`O#QhGk1|S?LzqK$O@&*z>VaXh2NX2KQ$LF_qV~r3P8a= zMgAa2ID)pSiA#c1_!8R5NByzO*qD#-V;t%CVf zib(}tD~0{bR6sMcGUG*Z&#Po$WX;w}PtkG>g3TLq@rDAKQGI3OF{))M*M)YS@Z~3@ zdjv`Ukdyp7#2MH25IQ|5?dM*8oBE58JAwNH!3$UNPQEn9oEk~Pg!LbX>p^R5q{3#* ztZpB%T$-e^FVk_l>0IUw>S{unB34*E>oRsu93O7nK>0j@DIyIYR>#eykBbv)7{jXP zWl5yRqP>j{LrUgA#rgGb$mzpub9oN^FkF1EuL+hu7N)Du? zhDS}wS9^&Zcut`>B`k90&Fty^-=&f4v-6Bf$ikA$*E$u~@oR9->bE{nj(t zAF#HlE*ExNSQxnMq9WJfSdB198CDpi94v<&jrLtK!@*Z|v6>{K)X%qwFMfC&VYipA!~0FP@ETiDxDb zATGqPUizPb8h|#N+eOm)=JUF1cWY`Y?O4x7q{ykIjX-951)LRu!)int5O@2M)+yrb zcLm%|HbqeoiQo>`Z&YOuc3l?qbL*Hr=&}P@tM&w%PB zKQ#YUXOUKjXHHuTx}&GNGeP~1i+Vj9CSloEhzuRhr<$hlWLN)k*I&d$9=y2QwVDks#H2U0BD zC+NAIApHokxTHhmlcU?905!E*;7XT(HLM~BvpwWzegb_6X^9`ogQE`Po^r^lu%m>x zL!vbRA9mOUqeoEiE`45$%Uu+0+_4etgf2ALSb2F#Sn{L2wusuDVE<()kPp+AU#Q%S zV3bQ3BR2f*86W1Tkc9LC+Gl!8+K=Yfj5=omJL<@W;=U1x#6TE|I*DAIA5glellTjB zvzf%WO3xPONpK>#8;q@5%zx8fiJ#n&&`pUTPZnaTFqtlm1VQcG6qFA*ZuXPJZYTY) z#GqH5TkNLz5Xrwd;5_PC;YbMjC8-TZDwKP%>LcZ+A?uesMndqkPmtEtfHySkjPfw~ zp$!iv)-%j9lbPZFFLc?G%=*QZ?y~URjnRu=?D2tOn!(If3r@;eH1&?IJ&; zP`x|i;eT*7BFEz8d6`LYW00RbX060Ry%s&O<{xIl3+wPLKx-qt$N+A`E2$r;;b(}~ z4%tq!)~Y-1a}@QB+5O0H*o){QJ}l}KG}RhpMOQ6ZQB85r;JeEcK#7Et5bU|7gqTx= zP;%QvSQ!s5bQ@z|%Z)A~8BHUApK;6_2%BL%UH1eFIpv29DtPl7g z)5vDQlKv$TN7{YT_c=5dcc-z45M(URAT1Cr$Mc_gC0p;<15PKuFx?M`mo^@p?&jQB zSTvB*($&dHHl&)B#4C;ylQZ2puURy6l!;y-xO~YF&whh`Q2{q8V*<`IMqw_8h)Shi$~qSBBh~Km~*cN6_`$DYgNt&OI)X_3)3ik~@)Dh!hI! zz*#7pO%=bkgXFK8kcz7d4ajG(0NkWW1}^njnfNCjLqHYcup;KTxEO7Qn&BHRI%EHu z`1n(j>+c_=01mBu*J3tl@H30vtrIvZ*UdVjtE}iZbQwuf?1RfckPKpe%CUOSb@wt} z)DMr;UQ0d3L9^FN?>k7Lf{(&**U-Ck;USl#9lx3@Y&=s@R~jG7M|M$Qrq8%F-dVE5~tDnrjSP zg#OL7H`}8@GY-vq>f}`p-u@PjdpQ&SpYee0!i?lI&;WU6y`S(>*-QvKCs3STXfaqa z8G205OG>E4iTfjdxcZ_`qs;nHz;?vKi?J|~pv;-RMRpf$1K9{nSib-@6RsIcc1?C> zFK7WfiJdh}E&30>7s${TR-Z)(Z8UH7ni?-XIB>_eK9KUz@t~`0r*eTFQw@fWL6}XM z{XT4S2@`j6MpIecD7&(hfvl!$%|WLW?Tx{=5swSqP0*)J^TQAKdj5t^rqyo@ljBaR0&#oW0mcsF&2<`x}gokU6og(a9;;+*JOk{z5gu$>g~;*=-U$lW~= z(Or1ki!kZvK$p4|$9y(Zok)+_EIn3B439u)Il^(=-J~NGP|Ighzii7~uZmA)&=&5gr`R6sVPp_URBD)55Se+^glO~B**)EKvQ90n4mnLrcH5C4Vp(*An zIb8e|@R5XwGfMF|4|*b?3keCq!8RfbL7JT_A}1g6k90Im6Pu0`(m^N6{q1r`7ckl4 z2XfOe6mh%k6g`LA$!ImLd500lVn3E2eR^Q;8{` zPyxAq4Eq_M$g7NaVsORo$=`s_X|e{IFCJxRhQhAR|szdKnHA(`*nNPpY-Jw_+{~AhK&(! z6NG0ZKT&0XczN7XlUkIJkW|^vZ3&okvt>^xFZHOHY+(h|2X3;8EE4_A=DO+p-V#EAJbWB7Jq!_4etj*YIvT=8I)zN|WuVa^Z1LVc@SA6q23X?K@*3#Ec@*MdcAI$|y9hn+x?-ii`hSp+(GwkB_@os)python3-matplotlib python3-numpy python3-opencv + python3-pandas + python3-rosbags-pip python3-scikit-spatial-pip python3-scipy python3-shapely From 0b3d6a278957406b0d737ed1a124f95cee050d8a Mon Sep 17 00:00:00 2001 From: Amal Nanavati Date: Fri, 1 Mar 2024 13:33:51 -0800 Subject: [PATCH 07/18] Fix config file --- ada_feeding_perception/config/food_on_fork_detection.yaml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ada_feeding_perception/config/food_on_fork_detection.yaml b/ada_feeding_perception/config/food_on_fork_detection.yaml index 7a8fd557..0cd3b824 100644 --- a/ada_feeding_perception/config/food_on_fork_detection.yaml +++ b/ada_feeding_perception/config/food_on_fork_detection.yaml @@ -2,10 +2,10 @@ food_on_fork_detection: ros__parameters: # The FoodOnFork class to use - model_class: "ada_feeding_perception.food_on_fork_detectors.FoodOnForkDummyDetector" + model_class: "ada_feeding_perception.food_on_fork_detectors.FoodOnForkPointCloudTTestDetector" # The path to load the model from. Ignored if the empty string. - # Should be relative to ada_feeding_perception's share directory. - model_path: "model/pointcloud_t_test_detector.npz" + # Should be relative to the `model_dir` parameter, specified in the launchfile. + model_path: "pointcloud_t_test_detector.npz" # Keywords to pass to the FoodOnFork class's constructor model_kws: - camera_matrix From 65fe926927d5f9f6a9b8bb1672ffef26c9080349 Mon Sep 17 00:00:00 2001 From: Amal Nanavati Date: Fri, 1 Mar 2024 14:13:34 -0800 Subject: [PATCH 08/18] Fix imports --- .../food_on_fork_detection.py | 2 ++ .../ada_feeding_perception/helpers.py | 26 ++++++++++++++----- ada_feeding_perception/package.xml | 4 ++- 3 files changed, 25 insertions(+), 7 deletions(-) diff --git a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py index 9e4d020e..86226d1e 100644 --- a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py +++ b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py @@ -71,6 +71,8 @@ def __init__(self): food_on_fork_class, FoodOnForkDetector ), f"Model {model_class} must subclass FoodOnForkDetector" self.model = food_on_fork_class(**model_kwargs) + self.model.crop_top_left = self.crop_top_left + self.model.crop_bottom_right = self.crop_bottom_right if len(model_path) > 0: self.model.load(os.path.join(model_dir, model_path)) diff --git a/ada_feeding_perception/ada_feeding_perception/helpers.py b/ada_feeding_perception/ada_feeding_perception/helpers.py index 6777b60f..98dc3aa2 100644 --- a/ada_feeding_perception/ada_feeding_perception/helpers.py +++ b/ada_feeding_perception/ada_feeding_perception/helpers.py @@ -15,10 +15,16 @@ import numpy.typing as npt import rclpy from rclpy.node import Node -from rosbags.typesys.types import ( - sensor_msgs__msg__CompressedImage as rCompressedImage, - sensor_msgs__msg__Image as rImage, -) +try: + from rosbags.typesys.types import ( + sensor_msgs__msg__CompressedImage as rCompressedImage, + sensor_msgs__msg__Image as rImage, + ) +except (TypeError, ModuleNotFoundError) as err: + rclpy.logging.get_logger("ada_feeding_perception_helpers").warn( + "rosbags is not installed, or a wrong version is installed (needs 0.9.19). " + f"Typechecking against rosbag types will not work. Error: {err}" + ) from sensor_msgs.msg import CompressedImage, Image from skimage.morphology import flood_fill @@ -44,11 +50,19 @@ def ros_msg_to_cv2_image( is a ROS Image message. If `bridge` is None, a new CvBridge will be created. """ - if isinstance(msg, (Image, rImage)): + imageTypes = [Image] + compressedImageTypes = [CompressedImage] + try: + imageTypes.append(rImage) + compressedImageTypes.append(rCompressedImage) + except NameError as _: + # This only happens if rosbags wasn't imported, which is logged above. + pass + if isinstance(msg, tuple(imageTypes)): if bridge is None: bridge = CvBridge() return bridge.imgmsg_to_cv2(msg, desired_encoding="passthrough") - if isinstance(msg, (CompressedImage, rCompressedImage)): + if isinstance(msg, tuple(compressedImageTypes)): # TODO: This should use bridge as well return cv2.imdecode(np.frombuffer(msg.data, np.uint8), cv2.IMREAD_UNCHANGED) raise ValueError("msg must be a ROS Image or CompressedImage") diff --git a/ada_feeding_perception/package.xml b/ada_feeding_perception/package.xml index 5cb040f6..6967fec2 100644 --- a/ada_feeding_perception/package.xml +++ b/ada_feeding_perception/package.xml @@ -19,7 +19,9 @@ python3-numpy python3-opencv python3-pandas - python3-rosbags-pip + + python3-scikit-spatial-pip python3-scipy python3-shapely From 5435f99e17658d66df35e3c2469ee66490ce0aa2 Mon Sep 17 00:00:00 2001 From: Amal Nanavati Date: Fri, 1 Mar 2024 14:19:24 -0800 Subject: [PATCH 09/18] Re-add wrongly removed masks --- .../model/fork_handle_mask.png | Bin 0 -> 8256 bytes .../model/fork_handle_mask_with_shadow.png | Bin 0 -> 7919 bytes 2 files changed, 0 insertions(+), 0 deletions(-) create mode 100644 ada_feeding_perception/model/fork_handle_mask.png create mode 100644 ada_feeding_perception/model/fork_handle_mask_with_shadow.png diff --git a/ada_feeding_perception/model/fork_handle_mask.png b/ada_feeding_perception/model/fork_handle_mask.png new file mode 100644 index 0000000000000000000000000000000000000000..4728560597ff7406f2751a7d0240e5338cde45fc GIT binary patch literal 8256 zcmeHLdpwkB`+sJLA&Qja${1Q(?VQJ9#%VI+R5`1Z(3p9K(J(TD8Kp)CNs3y#DIt}P zs?}->Ib@wWs1W588>N!a2?_5#RNKD4-F@Ho^SaCVKI*j zLE@HB_g2+k&?@hO5_d}t)U>x7dp}jsFI6=2ob}q6-$mZuce^wzTC7Uo-Om4hwQ#p| z`I$Dg)ZpL-&pSL5dR~xVacYpstG9lV<$B&p0)f$UgN8`{w zl$~}vJ(SZqJ6MJjZ}QbPdS|UnG!1#&27=qlV=&yE8H^9{fG7^e?y+|I#eMcRH?N$- za~4_7URUFu@$4{W_o{6eZ`1|5(=)!tk8Sx{)j4tJkNMI=M6@O0qgIkBiUYKBaht0UZ- zx>*q0?uBpkI~X)FG`4aqWvX{#RD(w)%V<^<({&Tuw-ZR|Rod!~B4nnB0i_4|11<0ZuPyP*eH1wzMR(GP?u&oT(tD@ zcZTWb7f$0TZ9@)hbm&Nxiw}#tZz>2oBRpsW=^R-0RKdbRzA7=b`1#A{nKui@S{n{@ z%p_+=?0P=8>MW?c7#^rEAD5*xwjdP8;s^p^oH#Tb6dnXw*^0wi?6t569S8^U!mKg< zMWq-tk7JElVd_F~31`5;Jg1ll*ek}>n;o;3P32&0ZIrFVGyo6^i&$uJC_hX{6I){@ zacSULwv5N1Cq+bStua0>?r4S}0!CAC6dVC-FXly&FgD6)s|XI4=E-z;4*|YeV}eDZ za2g&T9UYB}CgTJVL3kpSO2rdMcoGQ%LK1U4Bd(c)>Id|d-fqlv3 z(o{=%!Rw~JO?~C_CVL5up6m)5i#-*BkQD`UCjA6hQ(Np{R#*@W#>e}5{jkpagIXYP z$fmHF85?VE4mz7cGUZ^Yq(C;-)Pg{?u;3CcIA;HZE);M@(X0q~Q4rt}a0Tjfk}LE# zQz@MPduO79VOf3vV^|^)`x|4F_l)7+M~s(EjSnGP;r|aQR+9psj2WOewFbr)n1=X| zxFu~+Pw zj+muvhMCdc1wk`=oSBQf#Vvj9lBCqv`qhK|a@X_3>^t{@cZDWCP*0enw%VPw$iw|R zK`F%!)BvaylZtEsv#5)zMmzfNP;>~AM}z-h zsDVp93X($d5FJAP(e|G#|Hrld!iB%E^*6NsI@~|A^}o{k*9rL}4?kb)-%I{K+xmR1 zf4|T^we`Q!`n*>7;Njk{e|$KBZ9w>lQ)C6f@g{RLf%l!iOf~t#u~J3A>i;V=|eceYbrI zA}U?SS{%QMTzdIk^=k(O1d6_@E&Tey;j1%`ZFqhwc64jk5g{`-p!k?esblhy(WAqaN0zt+{sblvJ4{bfL84g6bH#4 zN^`Y@nO22-UdY6TWkCluYIi<=NtbPCD`bVQ&h`Ip+&n;hDo!+*L5E1EqWkafPbf`D zIOWkJE<@WNgpi!qNdE`PF}%~b9zV@pLpKM@fHE47(EfEf;pjHsGAMQFKIeUUi24C! zy%L)4fbZ0?LL`MNqj;V2YO)GXi7HNhy06)Gea{XpF_e9y4XIF*cFw@kczop9sihOP z;-_&hB9N#Q!}Yt;Q%8n(COB1P^9tJyoF96E*vC01kf5etO;r?13(`&-j- zBqU(*1*ZYuzx&A9OfCv^eD~F?uuOG1ZmpSoYFcs}qNd)yXtRyNqpq0yq=o+bW40-3 zgPxEml_ew;hrN|tj_zxm%aQ5LgN!hzg4#7zSFC;>C(EHfl29Ivit`-!dg|r-upzcd z-$5Gn2oU}Qu7!GO+E?mzp>HzsBCl~~TF4xkB~>rcRBQPT@N(31h<8^9(b8LaRD&*6 z@yi#AklN~XtQ(JmCBboua}&n|*X5xn7dy^GSDw{+)c3wVAI}%O?Z3p{tk{WgHk-kt+2kRljC$Ms6#{5>!!Ip^0o@}@ItR(?rweGpPBqt zU6=mL8ryu2>*eV8NgDd{Mp~Ar%F>-*ct3WNu}f{<*jTN{a9)3$Z%Cupx#W1?Fp4}< zP5S089OWl!Yf@`HTY62K7n{Vrv8!q=&P=xV^T|w!qbMXKanpp;FpNV93dy?XUSGL` zqDvF=Tg!7iY`IL2O|^E}YRmQo=wmN-@H>-wX|ZAaqMKLI%{}ZjkWEr4wG{QbMOJY3H`hX+1{0%IaAbK(^N94u{PH;CFgAjGd{wJTjJ0 zn5DDDtd}r&IC%exAe20s9+H)ND@%7u8u##LE7T0t8=8tgZ6$q=MJ=X`%( zboHC)j^vrg0@kWrn=oEq&#QYoY!nZQIDeltE<@AcMg|L2Kg6*VbMnuM)@vhB?gw|? z`;}qjzmkPIpZ(^}H{S;E6|db?TqL)@@#MZ?BldDD-Hed<@gXJg9r1ei60KXVP~5jq z+txZ!O7pL&aeVu(dia#wnE@QfdqzGc*1c#E#vj6nPUw7v?Om?BxqiHuj7XW+Xg!)} zyI^r|!)c83UMGbaM1^@>@@h_J5N!O;CViK|w(=r&zyBC}^iBMUj#r0SC-_^oGg&$3 zLhT_WRdjE@Mpq*|q_=s)DIM)?k!$)=K9=&ua+PtkAem`stjw;t9FYc5|oQ3NB= z*cngO?;YNf%=0V4(B2rV0d%|Xe>;;#^zRtnYS`JJeu))p>^w_9WV@~$0_DBixhGRg zugRK+8n#tlxPnOTeX=CtsZuHKOKD_=(03Zgi8_VSpzt&seA?M+9jD`IzQ z>LQ~aDZRVY671Kdib2uQjIWdR3?gURtU(3u+_(kP961#1msg<)b{-B!H#K_<-QK{U z?-Awd%(ZO7lH~&qn8!i$Od}r{4=UO>y?E7CcY&K`I9v}#);#h^?x4p|N^8k&|H4<6 zHoE4yvO0FEn`Yvi1mz50Gz<61Kl{4i0E$kB>`GKD43%%?o|ntIeiuU0=fy-tiUzLK zfo`tZSKhGpNb8PYRIdbGnx>Nad~=s3A=SQmyt;CC&|U4#$zUK!mG7P(Kl%91ggj%Q zRI3}LcduXgLCCII(qdAsgoe5oSC5-IlqsRz%ct+wpgV0pGHTE2Qn2h!(*Oq2ZLPHQ zM^*C~nE@%52>HcPSJoj>CozZ@*JY~1_RZUEX-QwfDOT2R0J5h|GxWqnbwL(T?feek zG{dF|_5HZ^N5%byGZ&#10Vmsa!@Beu z%9E5>881bFZ9YceK7)4S)^0+dwOW7K5V}@@U2}+EVjHvcU0|IZgI?vd{h1JnN_A;3 zpSG@Yt5Uo)sk!gaT!$J9;9Ikw_|b_=L05i>m#Q>BESu{wF|(u55j5w+!0wDIDb!h* zBJgtYWIZ@(qK5!YD$Rg_5EvlNjknErrFeuP) zp9l&wIK6AVfx27quoi>v@GN2=+hd~YbUcVLv_UvA#%@R#=pspWuAo&9-#cDNyC2G@ z$fM|qH`3`+@3&3&+ba!ZeRa5hkz!RqM=KvylLBV>+q_<>?v|rtgAvoUow_uX+;s}| z{q%gzapu6Hnl#0var?}~cw1W-g+QSpL$|`YH1yBKZ<7o?%K?EWNrM$2Nz+2wUhzeJ zb=7J-Np>G-{6_n$PYk^Caf${yy9Adx2_!(-(W(NI8D>cDOMRO*QE3L@35H-yR@fVD zua0#)YbM`Ke_853QBhq5T6eT5iMUj$0915)cZ1uG!piF^2{~t^zk_|UG-!@0auF_Zq!<@V)cufeWxbD{q6K*-%`4ss8_g{A3IKD zXoDJLlwHNcLFbtTkc! z1PFq(TwNSIAxK3AL5N34bs!H zMw;HAs~6fd&f{g%D(e(8cEpCMap~7@?tZUv6}MZAy3W*2z<68;<|g7G;v@ zILp;`@AAY$h5A!^h3@kzwO9E0?A}@=r-Je}aP93qTXUY^8g%gm!zYcCklW4-Q`nE@`Y;8Gm}jQiNg~NLiiZoINNU3fDqQ9 zU}I*?HZ|QU3*5Dq+UA<|;T7TANtl9lnkJTA4o50iTIFPu%70DNMm}m_kjaM0*F3^w z?%&L=EkP_hK3rn6Vm;wW=8f#}X}c-&u%#wex%=xDJeV{wb77Qc-|E7LThzZd$`EY- zz*u*<>Su2J5)rC)$r|Mi@81*?XVxdi|e*rMWzwG zPw64;Z~oX3^TzJ=M7;u9*FfXzALc!ZOI%p;+|M$;-o3uy_{yg!s(DLm@z2vrL`CC# z-6{9$7j5;+$L>pfZ}#D^n)HF)ivUW&FSH}tsBI?#1^y#YKf!bTvD#)#UeVCN;jIs~ zTWDfl_P3<%pzWf#puM~qi>WLj-;~J~25?Lx_#)7E5M*T&A!4#ZI8r!(6T}tJ&|M|v zXqd~Up;wR?IEKic6U=pq5_6VDE%9PSg|H}Ww2k!ys|YFp;B%x*ID*d;NT?Asv=WyJ z-YdjdG^{j{hS1R73=h~|DCWRKQ=%yj;~2pWBcQD(z*b^*Al1{s=_3TVqM?JOQV|u4 z4G#}D4L36tii5Ct3Wb8j5wHXT23TMukpd|*0wa(ZDwn8yug%VJvkC# zsF=lZ4C4r-#$Q4>yD~gJBPdD=;_^kxq5yfn3&v)BwiAVlc}g2L3(Mhg_yAM_^27hm zUdj#pjjZ40rqC$M`7#j@?lb=HtUuMRGzL}-2Gv2x3RMJkb)caY`BK?J7MD#`zQtLv zEzF5b3IWL)1zpMHeVLU4iVdL1EEbt;Mj>O! z1P&WR#F3a73WdnRumXu@6eixxf=C(7MsW^QTMt(nnqZ1kf-5B+Jf<{IDCX193?>V9 zU;3NIi_7OMl`<8q;ms))78d3N@PmlQ5zT)yTFwzmK*uRS@iuuLUArsPz_*~sc2MytdxUdsPg)0H^BbB1jky^@G zH+nUC$>S<#35JzZL1nT=OOP5He6ePL->3|%FR%@(m=xh z%h$)l_+N&A;jcl)#P3(SzS1=&2F7IkwY$F3H6{keWc;(Hlu&8 zZ5#wm-0A9I>lJbL)%_6OzR;N!Jr8g0;LqH)%Fabo_l9V){KDq%@&ze*&1_ra#dcM& z+yTMVdxD;;zhzM)RlcaSG#&NEk-P>@_^DH~`p(IewFC#%Ysdw=lXcM(PAn`i^jo|m zRm&;7_F3fqj*$7;razx1>2uX(^H5mL20|g%P zk&p~hgXoY71Ve~FQvVzAf8Fa(QuvctWB2+Kus>nr|K|1A2l7X$jNR++9sWPZ8oSru zZ?rFC{lC1%HVU6I9J|-p$4(Jz>|QXm8Tzwf{#3y~4fVef|HX#*54^_SrwXpe?lty4 zRdD^cyy(8Zk=IFEI8C*urv=5%LZeT0e&{qUkNpsSiexf>!-}^N+qY+i-0^z%tj@ZpZRz9PHd^`wz(jBBoszC(qgY|RVO*Ew^^!DK9ej7+-OS-s z*5NGOI&A@g2kK~Ry+XS>_f3~&pi_|5$SrEZrubkp6`A-$zx>6#!LDXPVQj(EbAEtU z`sOu}Pcj-yBPAzR=6$=v)HicrI9B{Rd1OG``$%tfdn z?^%P-5u}YwSE8mly9SR1CFr(nqxL@OTUf?Hf~)6s`PlOP15fH6w;2e`k-^p4Rh_EH z?Y&nR-IJYaTIb~CbWjsyLw<@dQ-Q;^03LZ`y zDSM`#0H}utJ%24@b2a_KPuhY(Ld7mv=M!HoF%G8pA!b+aq01^aX07i#)RI2O2Co*3 zbFQGDI^f=Yh`Y8cw=w^zn*w5X&%w4Srh{2mClOPP{b6#;ykY$p>3hnBAma^$Y3pwW zw$$t|jjDN7A636oOJ#bGeSxvRzx-m|i~ggV7EFyJ<&U&mD}a)$`$VtKmnXG2J|rTy zwj=d}gZqj?zll6MRJ^eDk!ADR#B)uM%GYlfs-)y9J z;oYTzSG`ULbNrTet`4McAJ7Ojpl7$w)2(;D!YGUJNoj7YzO{Xm7VNRKFWJVkyZ!nK z#~qydVb&g7H8?$D&~~kppoluLFf`fLW3WTyTp{aA=m{zB$=5HtcqGGPvAL|G(CgdD z_OhhL*bYp6R8xVL3Ie&k;m*lb2MP)rXhZ%f_3PuN`0Q}JI&P=F`uD9!{l=Q_IY( z(ZQX0u`T|((c-z=MBT|wY!XNldQ!$2qcp3a`k2H(Nlgw6NxFt{w}-jou@B(dpgbJsyy^m zc-zfvqd`72t7RV4qfyi#Uh7iPwUWHrcYYS4F<~;;=kh(DOYS zuHfG+xm=B^V9p^QoN21;r;W`I#_8s8eZ3m2X7KlQWR82h3e^bNT`{~>slAmLxja1O z&Bz59B?Gg05G`tdhVN~AtbSn)sINz3d)1yjcRCA$9_>A=nV?-RXoTYXRNbDQi~R0> z_b$pAXJt-=yL}Poq_rdsH8{xzo^yLR6#w>wL^J;W=~<~V+d;&WJ9qKq2Tg@{;KnQJ zs0oKXkLj!6OuHsp=?sKkGed^uA~wot!Tb@~^um{un5xKDZ5OwY8lHWHI;zSjeeW}~ z1Ju5Ql-bvmmzg$#AMWhl*Ph-RdPymmJ3igifR2izSJvUXV)9H1Z_w4?8;djC90w7T ze(vv9wPdCDhM1{be(2r?F=7mDmDc3Ba$!tng-)0q0$zGU@T(1w*om%j0s zZ9LK!vY2{pov6t|B{4a=V!TaucAH(1lCj3)S2oQQA{D(#cY6@^p=j63`QG5}{g~sU zv-QJ0+cf2BrRu2ZL-5%lRW~Q9UX~)UkGK2!1#X7|kWky!2FUJ!;p)`54O=tAs_J|C zZ%j#;k5g0*J?^bu6!#<7c}57zv1~~b1U{h}r|QZJdC*U_rSG(5rDqWvqil}yMr01r zFO%G>L+siI$a$d)?wdiDb~m4VB9Y@q6{>r=CmT{jtppcsLw z$btSxAmgKZ?1L~VI|uGBU8bPKmIqP--yU?Qrbjh57t7e3Vu@Ne0mc znl`@4+^l^;K;2vOPCI*DKJC0Y7)VujN(~O&+@^1BP>-AHv*Xf*eSSnu1oAp(Km(UE zd~?K~?K5Rlm>*C7ZSjuCNnmNolVpYo-GEyO& Date: Fri, 1 Mar 2024 15:04:37 -0800 Subject: [PATCH 10/18] Retrained with new rosbag --- .../food_on_fork_train_test.py | 59 +++++++++++++++--- .../model/pointcloud_t_test_detector.npz | Bin 30676 -> 59096 bytes 2 files changed, 49 insertions(+), 10 deletions(-) diff --git a/ada_feeding_perception/ada_feeding_perception/food_on_fork_train_test.py b/ada_feeding_perception/ada_feeding_perception/food_on_fork_train_test.py index 14bcad7e..00b8ddf7 100644 --- a/ada_feeding_perception/ada_feeding_perception/food_on_fork_train_test.py +++ b/ada_feeding_perception/ada_feeding_perception/food_on_fork_train_test.py @@ -9,7 +9,7 @@ import os import textwrap import time -from typing import Any, Dict, Optional, Tuple +from typing import Any, Dict, List, Optional, Tuple # Third-party imports import cv2 @@ -35,7 +35,7 @@ from ada_feeding_perception.helpers import ros_msg_to_cv2_image -def show_normalized_depth_img(img, wait=True): +def show_normalized_depth_img(img, wait=True, window_name="img"): """ Show the normalized depth image. Useful for debugging. @@ -45,12 +45,13 @@ def show_normalized_depth_img(img, wait=True): The depth image to show. wait: bool, optional If True, wait for a key press before closing the window. + window_name: str, optional + The name of the window to show the image in. """ # Show the normalized depth image img_normalized = ((img - img.min()) / (img.max() - img.min()) * 255).astype("uint8") - cv2.imshow("img", img_normalized) - if wait: - cv2.waitKey(0) + cv2.imshow(window_name, img_normalized) + cv2.waitKey(0 if wait else 1) def read_args() -> argparse.Namespace: @@ -150,6 +151,20 @@ def read_args() -> argparse.Namespace: action="store_true", help=("If set, include images when the robot arm is moving in the dataset."), ) + parser.add_argument( + "--rosbags-select", + default=[], + type=str, + nargs="+", + help="If set, only rosbags listed here will be included", + ) + parser.add_argument( + "--rosbags-skip", + default=[], + type=str, + nargs="+", + help="If set, rosbags listed here will be excluded", + ) # Configure the training and testing operations parser.add_argument( @@ -216,6 +231,12 @@ def read_args() -> argparse.Namespace: "will be performed. Typically used when debugging a detector" ), ) + parser.add_argument( + "--viz", + default=False, + action="store_true", + help="If set, visualize images during the process", + ) return parser.parse_args() @@ -230,6 +251,8 @@ def load_data( depth_min_mm: int, depth_max_mm: int, include_motion: bool, + rosbags_select: List[str] = [], + rosbags_skip: List[str] = [], viz: bool = False, ) -> Tuple[npt.NDArray, npt.NDArray[int], CameraInfo]: """ @@ -255,6 +278,10 @@ def load_data( The minimum and maximum depth values to consider in the depth images. include_motion: bool If True, include images when the robot arm is moving in the dataset. + rosbags_select: List[str], optional + If set, only rosbags in this list will be included + rosbags_skip: List[str], optional + If set, rosbags in this list will be excluded viz: bool, optional If True, visualize the depth images as they are loaded. @@ -296,8 +323,15 @@ def load_data( bridge = CvBridge() camera_info = None for rosbag_name, annotations in bagname_to_annotations.items(): + if ( + (len(rosbags_select) > 0 and rosbag_name not in rosbags_select) or + (len(rosbags_skip) > 0 and rosbag_name in rosbags_skip) + ): + print(f"Skipping rosbag {rosbag_name}") + continue annotations.sort() i = 0 + num_images_no_points = 0 with Reader(os.path.join(absolute_data_dir, rosbag_name)) as reader: # Get the depth message count for connection in reader.connections: @@ -341,6 +375,8 @@ def load_data( img = np.where( (img >= depth_min_mm) & (img <= depth_max_mm), img, 0 ) + if np.all(img == 0): + num_images_no_points += 1 X[j, :, :] = img y[j] = label j += 1 @@ -361,9 +397,10 @@ def load_data( img = cv2.rectangle(img, (x0, y0), (x0 + w, y0 + h), color, 2) img = cv2.circle(img, (x0 + w // 2, y0 + h // 2), 5, color, -1) cv2.imshow("RGB Image", img) - cv2.waitKey(10) + cv2.waitKey(1) # Truncate extra all-zero rows on the end of Z and y + print(f"Proportion of img with no pixels: {num_images_no_points/j}") X = X[:j] y = y[:j] @@ -534,9 +571,9 @@ def evaluate_models( for i in range(y_pred_proba.shape[0]): if y[i] != y_pred[i]: print(f"y_true: {y[i]}, y_pred: {y_pred[i]}") - show_normalized_depth_img(X[i], wait=True) + show_normalized_depth_img(X[i], wait=False, window_name="misclassified_img") if last_0_0 is not None: - show_normalized_depth_img(X[last_0_0], wait=True) + show_normalized_depth_img(X[last_0_0], wait=False, window_name="last_correct_no_fof_img") if y[i] == 0 and y_pred[i] == 0: last_0_0 = i @@ -593,7 +630,9 @@ def main() -> None: args.depth_min_mm, args.depth_max_mm, args.include_motion, - viz=False, + args.rosbags_select, + args.rosbags_skip, + # viz=args.viz, ) print("X.shape", X.shape, "y.shape", y.shape) @@ -633,7 +672,7 @@ def main() -> None: args.lower_thresh, args.upper_thresh, args.max_eval_n, - viz=False, + viz=args.viz, ) diff --git a/ada_feeding_perception/model/pointcloud_t_test_detector.npz b/ada_feeding_perception/model/pointcloud_t_test_detector.npz index ed257a5bbfeb5d754bac2ef80690dda110b44de7..860a9cf6022dbb5626e9f82ba38eaa9ff04baf37 100644 GIT binary patch literal 59096 zcmV(_K-9lbO9KQH000080000X03g`5<5@%i07yyz01yBa0B&zzW^ZO+ZDnC@b1rUh zc>w?r07yyz0000009ix;000000GwO*Kh^L1w?zqA(I6>FWJJoi3K^9YqM%S2LW72g?De@k9^b#<+i$%d_v3!u_jNt5=Q!txK5^RU z+f4VQFWb4=-jY5jA+2GrCcQ^O+TQ7w+b!#xmz-{0wp)F!XYJ@}htFNFSUcO{ z|99thE?^8-3$9CRraTPO_ISJKZ|Qd3Fr;IKB! zS8)nht^JpIei6^3XZw)$j|9W^oRb@NQQ=Ru+OB6EbYNS^HCEb2z{AZ~?Iy*jaA{+2 z6#GXy_~~?~n&uJkf!LUH=^YugvJ*ny;{J)oa8$&M0L}2QpwIiMuuYlM_U8vWIH(tQ z^hElDUsCV+-$gW#>CHO7->ef9saFJC21%ee{Ko#J5*30HjmALu^&R0TKA+v=YUy5SRVtjMy)m&>>(i1ZNBj;D-~vj!nh*wzG25N zbcuf^;EKOe22(m2VsdOBaZb`fY|DkgpuGeXn5YJ<7oviF_0iwE=yZ^uRpUQ8KtLKZ zXJiP40<58rBelNJp~QuBtx7%+))*_ftxt}C(ETugXNF#%) zRn5L!o(|C4-Cgu_g#-o4jS1;YR49r4@@l-34p$H7n2c;BK_GF2@ME6Sxbg1vxi6h4|c%MwO5s z`T1UczDW|ew~ZE;s8E47R!it`8yy5sUpo3Qmju7kg2wOS+?BrEZF=(;9r8bY@E)us z!2Ys&;P(#>oeugNw8H^Y4aN+ z3Y_{+AocSM9ny@7+j{Ukb5EQ4e!ApA7T2j*w^%xe3bgFV#r;2-ZXlK@xxs|_DFP+@yklF}K(^Hx5w2qg*ZhY72lq#zZT z1{7#t@cGs1_7gnF1H<12FQj`?AwBxy!N+xUNMPT8RhNx`KL3FY_3Tu5!AT8z)YB#}X8i`}ukxQ`r^cx}eM^D&-rHO*5% zjkWipF~0ZkIqsR~DtOLIZeR0xsc#y^g<1usy zjh)KVL!1aob50A}P~l%V^%=cLTN#lEe z#n>Hvv6%|jic-`?SMk{&f8IDI70zrf&-%NU0$cqxEeD(E;8rhux+gyyE}XR2%9c$9 zxwo$CFMnkK-$Av}*!KjS?V{$Cm&d9h`uJ^Qm8NU zmG@*&e?;+gMSi%Nl1%&6Kme6}{k8SQWXPcxURlBUx+e2VI-r06xqh=Z8^~n%^2?7| z1o8j!?gOIsLN?I)N0k({Q$a>g>$(q~lXhk4#`6#Y-p47i*celx{D+-wcOxANw~nA%pmlh`x3;S&9G$N3rLI zK2+c`u)0k_{PRrS&U;uxg3+n@6_O?e+!8aa)8^@LW6Jr$4P?YsEnw*zQ!uHb4Y zvs@?i-(NUua0_*R=rSV}@sn>ZbGiU|hG}mLpNtIwExyf{ZaGuI>g$s$5vX5e)1Mp< zTnLD^3o{w~hWh+6Ay}x50aN$y=?fkrz~GG2UCmW~NGi}{$NIA#`5<5%6$s+5KRBf3 z)1c}d?~)1XY|_52&wFrVZiAVEWVlU?dzDm3)Rxc&DZ9UL2YL~MGpf&Crx1+5PRNYsvOi)m%RT1DF5 z&?Ew$kT;$WXd**CYpZl7@}7s`+9-CMM_y0z&bf1W@cNm>E4g5NF7hTUz91Dc@(i91 zWsZYPe*tLzaBnT*%RJh2S2i;8bfltu?JPpXC&rt}79kcW8LBH|-g5%G4 z#7Wv+$&ly&5wLhsF1ir$v+Y9f(hk(A=(uH5iX8f%m9Oddxv3yvy>j$A-dBI)fv^0M z1h|Kaoqi`zg~+4T8kH?{;OG$gwILhl-RPK%Zvzlufvk z43GWNasm0D=dDC+q%;8o!OZ@?9LS$dvs@2QUp8I|=?N?+!NbVA2iy@4W%SP*rswGJ zX3cHxSBxCEv+1dAj(jRi=o)AFb~E7Hz4`hYJbMnJ+BC-P=Hd zkH6X$P6|^%;%!3l1*Q%lDt+Qs~_hYbo%{s`bQY+<#C- z^R)^3s0q7^Zf;wtP~_5icMIb4#(Iiga5o90Q)kO<=O~~qR!z-EeR=Zyqi^`{$Kbo+ z@gDoRB5?V!Q*li$1D>`WtI`W4LD$XAnooF<4;2g?>X|#>rREz8q7HGQ`nj~F0{!!S z4bCj=ms{0IRw*?CHvZzYoGYe6-n`6KYxE)S7v!6-J5^K9m_p0%LJ) z@^5Vltp9fBLp|zm6qES0;nP%z9PF#mxk3h)X}Phc5jw~++V5APKb(;KcsPWG3a@#% zzOU-98-*jEcOLYNC{B%h=yb6I$SP;E z3J|wf&JBYo^4ML$-1z6nS3k&i#$<4QCTRLMJO(Lnb1miev3@$Fu+-IaIfMf_Fn{n~ zY!P_9PpH4t!+=W~eIvi}NO1mboyKQH3REO6hE^=lfj33skC;y?IF|gY^x1^|q-pgZ z`taRiWnIV*;~OQGGn}Z9>|DQNZz>(O{Sa_yOecX(VQRnERtl{7INNKrg8EhWpisM? z1iQ4Rf3Mj|h3DLJrcd!+uuI#V?JEhsi->vjOH;wHH0hfoK6fmB%(f=RselPsk#MGAzr56^5JLVW*sCgx{X@&&*qjdd+co64j-l$vP zyx1*GcAL>iU}@tU*@eDn%Ypq4nm8}FL<3yOPf4I$7O4}VMgdRZ*jw4itEC<_9UlCd zF#P4w3dfmb$WzUF^xz)@2JRUwc18q(t=5GomS;5h60P+kTB{QtpL=@5Sd4%&bpg+S zmsGfWe`nQ16&+S4K4o1-K2&6EH>+mJ1A4FgFnb94u4f#~KcY!s!lQKN`~(@oq&Agg zadZGju!!(()cr3vdnDV?mku2bH&a2reKC0SX;?Y|L32smIz?nKz22m{g!7nIczRd8 z5&=CnMMieh*kAS20V#Oj(xKno=~@IdwNwEc`j!Q)IH|9QtKpWN9=FjaTaG_GErz(w z*mER!RR{O&+Vw@MN3NKVf?k zG;MuqV$`1plXRC~dg$AG&oUa_yl&<8uN?H_QgK%E_=bF3rmr=PuJePQT(d2`VzIYN$|2z6ys-FyN{!X!KuI+#`&7omcShuad=Q)!xXUW?*HJ-!$&3^iGW+#y# zI(Ihki39~iUlt^HVs8DSGPQp>mIT@2YTj-@fqA#?J?{}ek%8xp?=RxL-mv!OPf?&V z|M8wAzLUJzKV)#(UXNtMnKtRET%@(O>qI4l|3T zl0VR&JU#k{NfGCFHugaFFxGQep*!Gs4hg&h)=I@4qQIsvPuT=#=^!4^V$$-91SO9b zgc#@_+;3YXJ0J77SD!P^|ZciVyUqEhDGtQ{}}LJkz~^E2&|jN(Cn^t6i6_TsGUb%wT;|Z z)q``?DfxY?-2fSLo&D!coE@OidAxmzl>iIzMT51wsqj?2hW-`z50(j3FZ)Y^sq;)p zx$0D4Eg#kQMxHOaHS-Si2(Yz#%_Vv?9;n z?K>pV&P6~uSM-hT^;A%9%qKYB&_VCP_%Z1}B$&^<>rciUw8r~n|1|Dz6s{4P`GSCv z+qe0~dNBX;HAdK??pw`Xo6ZqOAF{9IB#$T+e%@V|vg-e}h5G~Jvk35aTw_CdO$Oh< zwr7Am!2d^#%jG@+yC;%Hd-mKd%divdipnHx?hvr_ zF4`ddDivr==POlly{%Z8Suhrg={xLNwlYz+NR8|OCX=jiL=^X;Qz zkykI6*neBWT38XNiD2;ZOAe+x z(I8kQVn^GKPB6c*-y_?Afcv|BCesh(f#it6w{3BBIDO`|RN5O7>{0o#Bi)b!!>2Cs z{lK}tey47;M>_!xP04Ogu+C+^L*E{+@{G2^!ySd$@Y?3cnByJnr)YHi2F#TL9%EzO zyD?`?$aM{cP=P3u^x~_h!zt(O^fn($ATF2LQLSB5@=FBA$ z2=U+UN#e+Z5EG~J4?c95%TH|Dvx$JUd+j%kr&B>Lr2EAP>KD@*0hYP$063bjBqz0< z29XiGo~k(vDE^#SV1V}(4gWKuf%#%oD)ZYA&UJ*$DCzri5=dOS?%=$Q0((y=sq5mL z7C9F`=IKE`%w_QZHKc-T=K%{*^uv40qy73Y@BEF{`|I9_K6yFpq#pY4e_4F$a`_~% z^WXI-_XGu~TlvVv$a~!Xu?_Jdt}atguBlj|!0g>wr&Ya^6~2;gtcuSsX0IGXpZ2MZ zx!?#sPdX4yO4v_8UfaEcig-@lhp*mg;vDVvbndH_N1e4fRd{(l-naBg-CkV3!}ELH z=}H3r(-EybQAUP-(Tr``=%Z?ajHNu$H_AA3?jAwEYBo)_+k!lh?#?HaQAWVr9+=+`_P9RS$>)7h`#IJ^N7uCs8ds6x1BeMBd_YaCfeg1EeD@%Rx=`C z3z_{S)6qQOGzcqe@uova<4Gk;^cz9)H6ub|n7{69+8~1WEm6}}E=5099REJu7jYgr z8CjcvIPd*LFD42J(D|!*FeaA_WP3jGF4Ud+&*V4LF*)!^l(h9pY$^;hQ>tCxGvK@x z#av{J1lnA07e+;>FwYh;+=O*oOz1SrM;^Wv%X6qUj|`ivjkYZ#o_C*%elV+u`R&{3 zt)uQ#=(Vu>sGo%Tc*_5Q+L;X4$>Nh7W0nlsCyrV_pJYJe?@F~v%yDyC4rhH)_xF7X z*))Z9PVtVL%Jol$g93Wf6E|@GT~(8BcXWVYlYH>xC(Ki=219Fh;dzvIXS~AudNL)h z^~d?T=Quv)@CN7iQ-$1fJkMfW6kCZ90mXWe>o!DFK_sQ4{%8XovP2eny)saDjs~4; z#hfVarDpJWf(~sC{7k)=yYJ=itt@hmSIU%g34TlnVPJpWoc*T}gv5;ZH3y zrk!wiI?_AyEdgA57r9h1cl;{jN!X3=b^3TiK%KyxyE}A6|0m+=d2ypM>Sl=@OWy~~ zk6L9b+nIMz;f2+Y{$89Tl|^ROgF^nWZ1A|jzla8Z-TwJ_nsmbA*&E)x+~}|51ls*B z=fUTJ;GjC3mu;j>ZUfXccIFFeyomF8=e~VmShvNQQ3pzFHXM=mSs>Y`LTR#XpF#}- zh7Ht$FTNx}#Cb=_=eiWojZH8vLp*57X=~ioM*nO>tCf;PoGc#hUt;TkycpgXlg=FY zwd?I-JS7p@)k`R|;+=5gTWHZ-`YJ# zBIP*=&=+C6`HTL)dVN&so@zQsRz+#t$NQ?rKV~&}LWNGI;bf~sIy~zZxouNK!1RHb zoBOND@Xh;6&mHtFBc^3BCoxa$DY!y?yG#X-9}9G&Fx26_>nrNJi3+uA-*TEDPI4~oSobv-d1{+gKihirOQMOfYOEbF)&3@KZUOVA*w3a) z^l57TKNUGq*GA-dooe!t$M$!uNzWle;AOiW0_#6{x5C@jEC9AYtkVYc520`3D{78( zLXLHE%U2%)^hz$vemAGW7z=Nhz4G9p;?u+6Q+NwOUIhz!qbjOuXh5;&}rS)`k1W~#J3whohc*1UMo#k zCou|~RqSLhN8R}xIq`grI{IO8_rLPORPbxb?lnZbyTEn7p(1)}HnIIn(wRX8JQr-8mbbFZ5j8F{!&V(-`-?$egKX!5F! zfYhiQR{wWoh-v!z9~aiaX|t6^$3QB`pAofWUL-@((C=!8E;=|!gff4`yiX0xV@@Kd zurYpSbL~4ikgT4@>;3eH?-~O~?xfJ*kVV~=1=UWVaKXRTyf8bJx*Ww#g?BqcBsL=d zYcTEw<)9DeAD%u7%ZNiFev>_g1o{bbx3*x;Excs#H4uI28i&BggECl$ zXP=a;5dQ|jgDO3EeyJ0F?w?u-F!W(1-zp%(tKxANK|H_2s~g55UdUq`-&(S_QsI|H ziOl6PI*hL~O-@7p(Rjh%po;U=?{=n|3(w>8>8pup8Uf4qd1Y1TWH|SIIN&Avx4`g} zqzGLC2orsQkhSRNZyK)eLcEc(Rz_Q>B%qtKUhH9}z_hu!fh6K>d;i^*Ow=g@{Ybvw znBz__nj07(9=devGxGA#ZxBttTp#yE%m zxtegN#&;6%{pPkP1>}EqH~x$IcrVY%1DSQxByb=bjqKk>1(`*)_FSw3Ltu$*9&_>f zXpwv#T)$tvd^8Mo++~m6D+2vMhaLCb$CYGwDD6e>#rNL0c)m$Q0sY~-4-wYrHxf)5 zZVDq`(cTF@()@@%WaM+4eZ}hMLNWcTpC`X*%)5ShODY^2W*gVDBEjf;VLzK82GrB_ z`F;G5A7FS^B$NXEW5*_BMlc5%IXZ-3Zc=PfzxbV-0=~U#Y3C5n_k%VaY&i~O+EYjdmf!!i z590ZY$6j$4=cd53Y3mPrH1j|`*yRPY7veTr+}e&sH5|IK^S!O~*bC?;+b; zqTg;gE%i#6L^|8BWi~wXA$pxUz#YWdQL|HP3ONFOz`VdZcRR z|HxpJpl5m#`*PUu#vf*!yPWr={ofF8zk?f@FRp&BsCP|XpFIbvFTXoi`k4ffpgsNd z2Ll#=6i3$!65t~_KzbcUh1C0^)&J1{r(Atq^Wb#=^qNu3oFgUxl=KZ^{kG-QUiS;(bIj;~q7eVV@5CsyD-^U~}3@^F4H&xhQT#C|^+N1PS9g?jXrpNPLCOhC8dzn%wnRA`{HoH^P|ht{^8R_q6`@A`GL zZ1e-Ah4G$3xX&7sfwpk;!>_GOc*w{n>zxHRuln#_np7-5`lar&9+AZg8Z=zawlYJ% zRQ1J=Zvf}IzF=KNm42*8rLS3Rmp9gnXP!$1!#*D7nX6*Y3Pc9*xBVhV)H}x9{qF?P;dj@gx za1Ey>dp8}jpS@~+guHa$BUgy$EY zNalUVML=B6%|jb77o6=CEg++>C@n6fuydzEh6;6}EI19c{@W~7wT}U3GD;ofj$-a8 zV~wAcp~94w$5dG>;@tD)#o;d`u&m5{@+b%M*R{V&jA1(LsnoqM@R0=hajia8Q50bK zY`C-;eXJ?Z$2UD1*e{XdiBH&Hvwv#OM-YdNlc(SP#QG2YvCYrFK!rBteFcfwm%i(= z&-VM0K;Hgnt^ww|lzL~o`^eAPRqOU}q0W{YYwcBHr^1esndW8GyT}xJfLbl`e~a9w z1kAa^5sf=0v2JIFz23cegLvS7`Dphd1xUY!O*i6t=7Y@sjSon$OHbit(Lvh&7FsX(Vd$Pc}{!782x?1rYhTeLdC+|XyM6xPA$t25ac zb7d;WwKL3k9y|I%yfoe`WasV=?Kr>t9aG%K5Qhd2@}2dw1EJn*$f=7$gSUdczRK2} zz^*;}WUh_`8S88<{^?Ob&8Y3ycFe8B;RB}r&e_l@xt;f-$*K?9-Xqt;01tUf?k~s# z<{EoUdva-T zJSVOw*sv4EQm^+~XcA!DvMawI@u1U~@{Ds84}0}WJ2BtYjES;Nl#pRA)wst1^T;`O zKc#u}!_M9p4|C(a)>S;*oP#*rvZ?*^x5EVN7wuC`SjQ4=OxUKHl<&NxU11G9e(e*Od~_*j8gRv z#410Ej=#(>1@F1`Fe&x7iyQa47lB!#yo2kQ>D~bm<2bIP|~z=VQOjhqkPp z$2|3nr%#l(h778vC;2zv`SZ13lYe2}ynJbAzf%SoR#KX(oX1vkI!E(U-&|Nb^mfhB z_GGAVWNctCbwVVo&h*UJR9GU5-dj+mfK@?Y!)BIzB%B-^8z@Q_^iICsRRBB&PmX0 zbAW}A`cL*f0pZ7=R9_infW`Nh&PET0{HCtT`%}hVef)6CW>bku742WHWrLbQF{9p}Pp z_{pkBmPzWx+Bg`WW&L< zT&B`l0_wV*Pd1=m;_hlbc&s4+{j`dbX#x#Qx;NdoR_cUn&BdOdke5P)rqX!@D8QEX zem~a=`ieT+=Re&EIMeIzA$JJ#m*%^FH!*hvZToV9Gl~RTxyEPeHX@I4D(E!h`XFYu zl~ahTT7zu;b9H10s{CoPIxpqQ_tf9>pnu-yW%PRs6*L27jcx=pP1BF=kejAE?;dbsKf>&F63h0?dgkwsMl<*SJlqgiF$gzjNF`|O9Ga(lpRk!D3Cr~z!xw@heOZ%m%3kJ?k>%r{)PT| z#B?NE9{YQwNI_QdHRc_~icfml6xe^{2~{8Yioc78$qaL@zVf!w4%CG&_s#AN<9&Z> z96l&DNq|Si;X`ZE$w1sYdG!m<^>2sIJvQM4j0ZHidf%tQIE${WYBC-C229f2QAf5H zdW5FqInP~XALzhywqI!CG+plxhQ&EO-N<92i`?f8k9LCmgKG1`wIrbIR=?9KNdXVb z)5;2ne_P+~Z(ZWp7l-eswk4q6nSM!6s9F8o@7;g?o~e*`CBn^onG7$bm^`-N{!ZSz zQrz_jILG8$*fm0cf?8k5Y4nF@t#wSdng;-PD|-e1a~fRcJ9D7OpcB+C^*r}4B|ze4 z?Nu}6E2)>3{pYbhuVo(Aw8{}+Z=1a@8GYS!9t=0P(_vcg*!`L(1YG)@K?rGzWSUS|XKjGtjj`KLzsx;DuIqSv|lgsFr{;O|Y zDiR^Uy*AUWl{XJOE-3}+M4)ail`NmZ9OPc}C}96SZ3WvHnaR@M=Y^A2k_}uHJ*u%C_5}5yGZb_9uAIn!pd`8_jCcioRMJ*NL`+u732}y&uQP(Q{k0Y*J zFO;1D0^$ptYzJ^&oEwH0oA5julf{xnsDqD+bS-B}$uQI-!qn-ow^&`v|a_zWBXl0~PA71#JC|^{*XxW_GhG6{0Ou63G@6c)21}G>!Zt{Z&lw z<4Y2(jqf^p#4-;AhDNjR1=8V}Yh*e9KN1}K(71jl^6(wm2P$UhKc{~^lWRx+e>C9d z$1S-30k$Lw7rfUc4t9wBLjop==Y0yx6mWjD@hUs|CB}B`LKDoJ|E};v^QTb2F=5G% zy!!n`ihA%#T>qM2HQMiy2cah<+Hd*OVZ&Fwu(YtpAUt}t^^6Yzql)y)I4 zpUAMAZFd9<&etuz-<(~F1e^#v`~DR6cQGdGwhylNYf_#WnN5Y5bBhzHGZc7~vv8y- zhYlH=tC|BFNwB!?=R|TK6)J9Bi5z`{`Rg_Ld@j!2jf(i-K=g-4S3FGC;eCgLcClnV zi-20O35Bgwh2W9CM`!ad1{~MO_6|_S^Q?dDdKGi1$j@2>=r$Rk^fTR0k8k;KAcC(J7(9O;9Sc`yNTK&9`5>Szq5A8ga70uRAU3^ z5TU;IPz8wu%wNQO|4ouXOOwvujW~~YTzR{wLIBG#b=!lOo3vX7OHUylJ~~~PYihte z*id*ag=01NW6vl98TtxE`THY^@-}^I z-)k}~%~O9!+k|2g#AoCE=Vk(}|q6d2kir?-OsDo%gDk0$or zdaAB_6!*Dt^W5fC%%@+TpB!hxoIC2fF;jq<3MV8kcJ9UV=YF@Z*9{8) zJbs{=hxq9%GYkGe2H%9QhWD|*JRg$83B>sW32v8<98|E_#&hBk;`}QMKWiuYOrPK_ zmNx~cVD!7+>AU0e^wGDk#;mcb)S*y@D-erDg zx1Iv?^*f~`P><}CMJ$7krGk;(-B)u&F5C)QK4E^W1MYAY|2D-u@^#~hC?52C*Nu+c z_=9z58N9pc%^%bkM^{@DocFj^uI*A-|LfBY_HBrt)~6XuPYkH=p*$pg8htN^p8TWd zKT|;|x!!DfiVT|68#;2BI|_|y*JaUPvFR<=TxC#zD}XQj`e)Qrsk3u05uYo23^i57 zs1PQdS~i7q^nO}BR!bH2ku5fK9`DOmRrXC6=ZN}4Of%*d0YXLw+d0>uk4iG?vE%Fj z-%G>iIFJudt}zrf#M~!5xk9Y|{Y78dt^c;*z201H&Ukl{3fsaiZB5UnL-h|DL~0SR zg`ZFN6;~eE+wC9Y4Wolec)Fqv=6b`c3mdpAkjJtd4)4N#B|fiWReMIjFXk(|mT6SD zvh9rnXF2xkb));kd;$hJBV6;bZuV~^Bvr6(4YLP*vvHnvwC}II{eujfnoC&-(6y$pC!FIq@0B!Oy6 zcHbP%HQ!^uN3rN*rB8pGUphj7Wz_DXTkTYcI_r8*1O1g%$CKo>$g2%&pZ#7GM?Zg> zQtONOABr@LSacu(>zdS3=lxX33shp>my>xpc~oTbv_%;$xC;*%rxF{BoKSHUmG zJj~0-RCUijM14shw`gxhyonlUkN07nqdx5M^hP`kuxm~B<8$#QPHz4J5+qukp=~%y zff$|(BWg2r_^dNgetb9;JlAU!;RDbPh1`Te;WJIN5 z-k;G3sWw%b5*e)6 zIBl+AuIJUVw)M&+K+I-`op>YqE5lo-!jSiPdDF&|D+x%9KH{?X9p*tAKj#g6ezqip zeGdKSx9Ybi9%AkY3++qM!RL=kkNWeYu8+h?S1F)goWE#N?1Os!X=7Qfd^YOcd`cWL;HG-Lv84z^v69}6qCtt^^V*&@qct!`r;_RJ{IvGnl)A1PKHYrwC;Df z&rL5KujV)sn06mrqOGMs*+S%{6y((+BBE)Jcn+u=xsUQ8-&8I)v7BgUfK+kcA2rm? z$Ql-jJ99X9!wPE^(f@qUDE^~?dNJZ>%kyzN1y1y;7!)Dj4lF6eJwkn~bm(gmHp~O| z^N0RvK0#dzXt`tS_6!m~9i5ssEdY55!}NVK3~>1*Zp8bP1iViLFXU)Z;6l37yIAC_ z;395va?R&8Y=Gk3wdrwNLQedmBSP2bvFurP=Z84rx z;m*)Z9OlrAj;9Q4uFg41M)B zzo18l(KqUAc~x(jCSbmD<8jknRLIvjeee$QNma0EW$8`yAul!_PF5j9!Kp8yOqd^= zSP9pm84}bro-cA!rb7D9<=lVx-aAM95A12hTw~2^WnM-B{Xa71=ZENESTD0X5bHa4 zwd>D8%v0)XmW0)iAJoQe4lGegkTGel@D6j$qnO*YYp8?IRtAj7=m#YKZsM2Zq{1b~ z!U-efF(dwEcE!iYd%fQmHj}6zS9ao5+*8aow?%}PFc%zcE1gOVpu($6#S=yisE?cn z2P5yK!a3FtEMEBDqgsd4rjb8i^m7%gF(Dvf_+BF|f(pCa&9iNBew`ciHmo_841XqP zF0A#=gP*1wyS8rXgd^TRbJH?VuO0le67(o=-hWT3JI-mtzCXNo@cf5TbfS;Xkb&E3 zea8>1v$MrnFMS<)6#@0oF2 zAIfGTphy10A>BJv$f({ydEQ8eH;*kiwj$4`WY+!5+(?B5*B24BsGA(;%OX;82srTH z_Rc4$3*i+hVtf1Ouq};`BNFF={7xXpok9V1zpG=}Uy!fVmZSsGpGXgpL%6R}fh))H z!Lu}+qYZ6geG&xR5)X8~a5WozS@(*LJ?wyExgX~!yr@$$ujA)ksZhj6XVt;;_&mFm zsc4r5a#z#`51WudKrlF{7w5NZD9Fb+i-0P9`6Gw=$j~<)xc?yPxVk0lJi`2UdTN8hg9OUIg!DdvM9bwFLKZA8S}d zoK#M$nvm{9fkcLlmat7BM4fqH6uiQK=Xn&XV9YN=m$ZUCQ1@NmAL<3{i>c>@OZ)r@ zSX2KkzRraTXEn@Rtnt1M3L(2jd(b~vBpSWNoW)!r8(M?9u=HANegyH!Cw{r1xf=P$ z;641qzI0lDBiYWPzoIae>_B}Syn1BY(yGs&{l>$OI{sXkH+g?D6^^j%Z7E0otVpX> zIFn3*JEg(bZI4r6q54BQFYa%WD;ku9{JgEQ>cbt>k>c!ZSKekiP{K-EHP9b=%p2G{ zqCaPi?zy!3yQ76?(SH_jegjN?-UzM8gR>m^jXAE^_dWNX%T}aA8h8ED*`O4#(to&N z`3nQmLJJ;-lS!cDKlS6aHU+F7^|Z)g9aiGRcTZK}yn8+M*w{*jbiT7xC%o5uxW_+7 z#KVTejWf~6pI%nAXSI+&{WRhzD#*hzwElOk3^F)&DqEKz-+o`v-6G72xD6O!I)r{e zcHm6-JnF(W7ju!xtpsHL(RqBzkcvDOQSm(seM`DXlmhzv1w-LozCxJGHgdLwqfa~N zTH#i?3H2AI4(>af2VG|pU3!owofqT!+`=&b+KJrZ+(-fOd4}+F^j+S5e%rpH9`&o# z8t$m2!j58pRhv}Il{Tl`+Pg@=`Sl3j+dkxt-B4OKTGqWbDjY9np84v#1Rz#=NX@`toUG#366Lw;AWX2*m$uMc4X%%$ot5eg>7H zpZQ_+ML8JP|N1S`C#R4K3H162BO3}_53<&Mh4-?#A-C-Q%@1_VT|HkG(!iFB)VbwE zCpQtcbS;635Igd~eBfkEK4$7oLk_k>=P(lj5IAEExpE za;KS5vdIu>=JjL?eBBBv?9esczbe0ui?DA*RUl)!i9Axw)8w)KBGKtiid^;@eb-`}?SL z1!cz(kYqK-ci(~vtve#k8?o=NQU;~MTlJzd?X5Ay1lQrlAK`QZf zLI)YX{&mcVMO;k~SMGl*B*4Cr)O9P93|*X$)x0L?;6HjySO9a){%^i+tUGaz_?`F# zQD>jo$p*BbFP*uzm@HUNh7$)=G!C!&#{Ul8kiqwg*j|ZL#(cqKy8QGQ_R+dYLt8{A z8w48K^;T>NC-*SrxC=p7`?| zERPRY=dbgecxHJp8)WCD=HFAWeuSgR3zklJ z#<590{~7_qIZt|<`SajbJ%gjxC2{=B&A^1+13TtmY3o^j@?KW z(D~)MbhwRx!h+M+S`hzlTleNTp)QmUT5LI`M1Y!8ZqLG6Dr`)$eKx=P{qOXH`6s9^ z*Ii79QZ`UQ*=4hAKAykH+JT@Ue>o}@+CcQ^Js!!9S;{Ky= ztM{(%|9PS`DH(l!o_><_3B>tv88a<`7CLO;Y&TY{#$0e*VP0}S=Jbf$rnj)pcXWs4 zb@NC->TXI9<)HxYFRPv{OdY_IN{F0rNrl)Bwm6?q3b-{*tq;Q-9no0RE`2fssuW*r z9@;{JHlkLZj(ooVdG6tqA`*0N>AiVfmjb&a1lQ_gf8}cLM_Esk;QcAtzMZHS5$j6V ze@4AX(e==pN+Chbk-o_I%@oiWIq0$#=f%h}#Qg~i`eg0pt69EzaEMVFqUBGA5)RGgy&hHGN9$6_);RPEWZ z*|KDK{`6M9@*f5;{F(0VI}ixlOH<`k<7p6BAkjD=(+N-I4vjrVKD18eAiqN29{D#` ztsePs-&99}9P+z!tmh8^j0bz<#J@ z+#dUTWzpz(@C^DHYLsv`_BTG59QX24Af#7U+z?Nu!TZ~*2B;GZGuKUizsN;BSY$gvxG3>Z19uMS+MV5PCz}e3%)tg}Lkw7}+rG^4 zn*UrNWP>06fC z&jf#6Aw#w0wq_yZrMsH*Zem*q&|)_7YuQSLhDo_?YmpDf%ol_Iek9-^_;U2W7ySfG zr$`Vjd7GIfF$cWe7&6i4J0QoJ#U=a&_E$v2XdmV;HicBjn>g=n9$uefP`{M7AIyty zAw!76sR<_3wT+TNA?iaU2rprLw~?m8)S|_IwWt^QfsPst7X!h`bbI2(BpQrt$rv$^ z?}SqgGzHaV5^()gR#K0m!lwf(_M@2hLr-ny+$k3iyI8J?Z~BuDS8Yw(FR*n2U$|N~ zzd8Z0WepExvaRm_nz5=cYW7^mN>35+&ZW#tA9LBw%U0Zr$XAt$&llLt31F{0E3|<9 zRladI{63!NB$d}ZAN@~)*TJ8%i2u6oxVXK@ldT(__@puKCyM0lKV3-%{&kugsi?C> z1>N0reD8DmqGB}qCAF39(pPaGSpiQOt!@&eus^Z>in>40Cvi@;n-1x{vPo)t2=Mx3 zbJh*_S282VJ0qTVTyKsU8hHt4?f;PKj*%di>5t6p2m^ZeYaS$Ho@#u3$=xWmH>Dw8a9&ODR?yTHGnF{gB}9?(VL^p+E^%+-Y%#;_ePDP~0t82vXc$`19U+ z`3qT-JID6k=gi#kQez5HOjl)@{1Y5f?^w0q!13*mBzYU-{1fh|o@0?(9XCi9VjdqA zYJkG44orB_gR33`-g$A|C`V}@cWdT{m72b|SYG*8h~y6EQLiU0V4<8ycSNw96G=MJ zi{}ebH|%Lq{8L~G6n-D`eBGYggTBkT5;;d= zwZ2u<+q}LCUQJZx!)9j#v6Ybe>UGYP?zH6n?-# zes6ZA<5w9~jfDYmgy${0Uq!+L@EyzVBk3sG%gy81P{bl&y0@FCQJi>p=ac*p&kq3% zhd^qfx8I)HidW|@0j_;@bw=}5F<4FbhuH$R>r6K>Q2HI&v#g*dTXG^mCev{!!IGc} z#J}kK14epQ>O?y0+bBWQ1wSV>CggvY)AJf8kCQsMQHYLzf_V($F zKojbmoFK*0l0hZnER0lIq&_GEsp5o(IWiTZZ^H~bg;oa-7}^@cKHL|4PY&xga8tfygJKZQXN%#)Wa zu5cNf%7&V;w>F6=aq*LxE}oWxwNL6D(cX?*eh+SEqUX%lSn}&Ro_Sq8&k?oL_)WK- z*O6F+Yv(=B7l|Y5GJrIKYe4gJm2ipZw9#rLWc)H};e@IVW)@YDWl62ZqiZ; zGz69ZcQuJ)k#5;$1_Hw38Uh0D|6NUD?(FryHGkvaZ?B*1#T%i&FE2f=I8&d& z7`BQpB zj4BHn7@?;1r;GEYIEgXGPUe^>i<0_-V}5{7{I`Fu`i}%V{r3=uK`zu&7g%!v zyB{>AI{Jz_-T0=Dy>a?$MweMwwmjQPS~~^5dfyOpw2+o^E%`pO!W>J6kf9DNM%Vk8nFl3{{YxC> zaLUNBj+0Q-@bNP#4TH;1Zl=3dGHf8ZKpyM8vLQb5n4b^PRr(d8d99K6ktORsp=+_x zmMZtwP|o3kw)+IamRMMgk@X9;;6=(f^%XmpwD{S(iA&;;)xZ|+BJuQ(<@TNI}WiE?Wa?SkQpDWo2 zUvd5`-~v`gDl5gi{<i))q$?4xYkkk zbnp07Ft%{}PIvd_kScILVaR_E=e##C@k<2toim-AOrO43jln_x zX9JalXIIln>knYTi>khvX7lztDw(CHNbWp9i_n^yM9qM?m?2-JSM~(;qte-AGKVF` z38*Odswe{d18fkazONwli4rSr=+yaMISP!eb~!Do@`>v32}rT>6a#UliFr) z5GiJ?rk-9L0gTvX zgYPXabBXjGc5I5WT$|Sxs2MvTp07k}*OtaMZ?4z*nE(8DjT9;TpR91#%{kDer=yIk z;t}vCu|#mHVYU@1*h$*QK7s@@pquL0iXtmam3P4%hR5)!Bi~u$Dlh@_epZ??C-28r zDQ&D##@fFpZb}Eey&3hO9260D9_ZAgcBJc3PB+za12$Efy#JUKd(swUie39uQXTHN z)+k0b&KIWQS!J~6C;HYseFI54y{(9q;ev&K2(Hp<6&^A1x(X9FoGf`VE}-YnBK5;>0pm4P*iunJy*)Sk6W`2 z#=De||KKu{%y-h5o|;vOxcVDAAuEjEIh{q_WQJdK8LH5)3Ive{%=^-BMs_&Izgd6k zL3&6+dB1*HVye}JPQQ%d(&ztNwU3Seqt9w1-njC^IucO$O16!9m zJM30aKF)Wi_!D7r{aEVDsfXRMU#bPwsxN29Z&Be+_=jvGxu)i#cS#qJQVt>J_u>xv zPvkESOWpTdc9)L+ga!%`VPU%$yvpStq;AExjFE!%vJU5=`I5vV0jy4jQE{OPO@yw292(!+m%17z)GAn6mY zr{~+G|89rkYY&OtxyblGNh%WM@08N&2kKlx>v<^y3cIJfxSH@K4N@Id=9mG;&e(u) zElcx}hD<&xTIcs<=PC&gDNFGM;Kx?0OP3$+MCs|pz|3_DRPX}Bsl^`}1!fd6lX7)= z{tO6Xc)_HJjcQvOb5-oY2xu&uY-9I1_)~0c+3g}z?MsaI)f68)N2YXxN`dkF$PVby zHOz~y&g3Dj*>+;VR1$biEGt5#Pk=5*SF&qqiHdmac2!n6pm#Ee+{&ahY1IcR#(7pt zv+6a55l2S}(n`N7DtA;ah^J*`xk!LvrfU;!aF}Yi{r4^ zg>d`Oa$lqSsYLr-P_C8ug(GE~I|*9H#m%Ix`41}vBNo>oj#eV75|2-gY+8l?#R{Pg zch1eS z^@gwKTajVkF>@_abA@|viek8@Ga2*ujy1plRNAR_4DBnp<0@;l6Y;{>cZ7tKS8@r*VFWKZn^R@F%&xZ-8 zKm{cWX?pQ%8vWAnHkHkBXpMIVcQJg4mv*%VFDo%VhbO+yFCrl*rXx7flU$}I-*NgL-x3+5*w*y3c`Ncdec91=HBJ7cPjBX4>$zsn@+B?t| zTZ>|PO9sn+-iO15VPs&(KAB#!?pmdMEY3&2rvR*z6 z=Nsw;j7r%DF9JKWfPFiEL5)b~ZpyFbh)_qqFdXzj6TdR$;v?FwccR3{1g?q^NF`-i zjsC}nuWQiQ>GQCF3 zf+{8f_y-(fgIjHScVsTSdt$#&Uf%Y5d-*GI7ovAR>^I&qNQW4CXS278T5Xon63uy^ z#JHLD8ILl4$&HWf%_!{JIv64%X8+{y^Ir4aR-_82?hU2;=2)9(@vto~JX5(+U7u75 z5&c7kk)1*ak(!sQOp}`f>y*LGZJm3eZ{({=+&)#wA$i??U+0|CmIPX@{Bren>5>2a zv3>^Ni^{rbVuvn` zAXPxt!yRsx(5()(vM|>N@RS-Jo_<{r0o=4#gLjBtBOJT1nHUp8LB|cGyBA7|d7A=T zr(Wtt|28(t&pacB$F};Qa-x7kQvPy3d%YSBhio0c#|TzTC(&}kmi2OspHO!#f0z!n z)0|-6`8*ir+VyFNP6hZum(i~eJ_d~BKxqXp($~15=377VpERQ^mPUjZlen`Q4*x2j zoRu!Gys_gmJ+@39BJ}p+AI>@P%89}RlKaA@HViZDJc#o>=6>~UvA2*^u8WSUM`n=n zXiDjN;ejAa1<7nP=vKK#`SON`w1RGXv5VJPbFQ@_9G6wuS7eLb6EEp=Dc@MX3TKKW zWy;?E8Yom-lE?7K!rgg<^uXhFzloD#xi$`c+^q|K#Nn~)qI9;uFGN7+rRIBd=z(1y zebq7>k*iCue-7UQdbVuR?tjk1`=7;B`#dyP z`ipTtn_jQ|;98pA`wAv=tIaj?k-^5OZtO5O8$vW3xYdZjAg#me{7gBKk4BXj&|pra zn}!sWFcLXl_FDX|!pxV2ud!q@_jSpOmJw&LBNbcrFM0)<>6GP6aUv@@v)`*Y{uhE{ zaa84t2!}fLafMbUxh(jRtcI~G#cH_qyl31*3n=EH&XGKZPL^-M_GRep_@B`u*H%0~ z=0KvsmBkYzOtn3TcS!c88;zizMET@9iJBhaF|*(tDZQv4m*gE1YGh zF%;b3co4$uWw%s=p-wmp&TcFwvi{XRyE^-(BmBniY{$frc~^g}+?Fbn0m<)XAioeN zbqQLalwO4e-g`zOb#*=a!`3HL)&KofX>{m|jq!w}#H*Ub-`VuWatgv9+hFy+Pr~?a zvyAOBVauN@K}>JlWXF-|RAhkn5o70LKxRSx{tYURPQT&s(~uAOpG5O+oS(39mEf8? z-uL&2gjCR#^=>2KceB3zX*&u^w5x*kb&-BSmZA%XDQzycK-~Ub;5WNZ*vsq#AdDJBL`{P-07a3Oc>o6t zzcAEm2%nQx7SR*%{Tf9&=GCaKjMBlXqhkWMHMFpr&suN67CqAs4@4qLNmOeb9V4DW z0$#QIx(26E-e89hlNkcpG9g3$T%UkqGjQ;{qQn}$kL}i98qLVdNrz^@>S1$w(@Lpx z?sJ`D-$#yc_bU#c_KqJAlQYmB;t55qs$2Z$KZ%rS4$xhl5-bQvzyih51aY>K8*mL7uZ{1q4RZ28 z+ftURk9s7N<#?LJtO8HJ=H~xKtVX2wLz=awnPZcLdi%4Pm1ea_Ij(xKYpmP4@W76~ zY{Ly)%>%G?$-ABUditk@M8~v&ZJ*1#d}i+j0CX@#z@%kj(*F4qA%CfV){QmBmf37w z^1BZjI;LcIXLDr8K=O=K=fCB!;c(+jO-k|@6U4j%?E1QT!$s3Qj0)tqz;Kenu@1mB zS%SLlKPbqY3yu-e0kXTD0CKsqVTF$#2_{jJw^PV5tyFDSr}n@>$>4yz3trEQx7c?7 z$QcBBU%Ah7*+R{8W)4xNt#*^u{1Zwhl2dM{B6}UxL+CcWASDM}gDI)_3rP~+0r@=l{nBS8MR;J|hDf0LN@-XR*2dej*Ogm@sA{G{K*!0YO&74A= zN83O_WcUR+tDKt4SVWXrQ=;s4{p+d?4Y)iCCL{3=mA6q8WfEaOH6xeUk|lxb#GkRU zEPv)Bdzb82j|!ZP?n9%k8}QQOJY|=Rr!@N5`Ho{V##KyS5@Rr}S?v;cSmjU2yrK)TfgHWT67b%)@%k=D!>^Cm&O!S>eHC6>4&D>!Wq89EZeoehAb$C2$2u&fk z$4mg!XY8V-luzrm~6Ba_YLladtO9Eb4ZD2p;Gugx6p zfMM~rDTtDoGfL{s3r=cmI_016kaPP~(o1LRt)&6;E;@X2*EhUS(D? zBgdnlEU0gyuc?1<<$@!03&8Q{BTrh3=|JP1+r8zxIr)IV;w>ivI=#FX9?=41Dt$|= z_hT{Yo4b!8>Au-;6|dv1NAW)(3bK*Hr=XR!5v0*i7wtDhbf(hHSbwiDF5g_*AZW%D zV+6PjD4A1bhQO7I)S8gTC~@Qz@=h zm#6ybOeAvn-d6jVUW>|#F5Yll_0(Cst8}rqUIT{j(2cZ~%vWIh zP8yYt2RlIJwpg!czT_i+y`c$aJdoFB<#EsNQU+DL$#>69kT(Rif=Ia)+t3mYJJHC6 zD4!NWh`=wu&wqOup^-o+nw{=OVpp>HS?iq?vd`Wai?u^fv1^4W()t78pdvfXT(8>C zL>B^?)qP`dvpjmwL`Cj51D2M_$vfP^C!{WS-4~B3XD&Od3q-5 zmW|xS6I8;!Zybib*5%pv;6*P^ICV}^P#u6Hzr5VnC}{(KZoaN{uFSjMV54>sn==5K zga1?C!%6#RmwVU8g|u^91OWsHx_4&rmpx>lK(X~J&4{2UgWa~Ced#(C2eS|n^7}RU z9`kLnIAor89@3^N>#T_n1OJhd6dS<&{O;)C1{bg?P(5ry#CPKzVQ1Zo4`ICQb2@FF zT(nquKpRpD3>W#={lTZ?3ArG*uCZG_H5yE|qvo>ifkx8g$dsM=AcEG!hpv6w;Wfmj z+C|T=+JL^Iv-I(LF3Gfh<#2KHBOFz53E8(J*eBt(F=Jyq)CA;x5IX!w4#V!1TyV@8 zVSN(!Sx74y-9_Z8w5>CObk-~9g9BQ`2VBQR>Asg5+34Q>Bl!93ds*1QP8Pd#do=gw z62f627E@;m3cz^l`kBSm4)denMe2sbJ#LpU5~;(Q;H(!oY{Ir_pR`23wmAMr|H&S5 zxCp@DjnDEQog$gIK8($4}lh_mKYR!slFYZtCJcAzl-U+k5=r(dZ z7f)IpXiEa^!m6~#uB}^-Cu@z-Tc6GS*5hQi-&cQj9yPDGTl6c}yI7_@!#_o;%{H|2 z{ui@)oZ)|R91Z^F{VDl^k+k5!wLf9$S)jIdpzT8d6Dc?6I@@JwS@;A(z!%^?OUNk%u}gCD&e}Do+@0u^Jo_rtw2gDA)2OD#~d&39=1Ta)LIr zqD@ehS{Dl)6FM<~MtWi%6{p{+H1hJu;U}IWC10jzTjK~_C+&WBf&`vL>Cv0KPPSAw zl2D(IyraiJBd8-pzSd(XY%`lk3%$>MDI(~ey9aWYhR$5Rn^$!|ha_eU#V0=5JG9F) zH2KNHp30+q!(V#NE2#5Ywf1H7ek_x`2A_c!i$Oq7co0PjbfD_~%aur3t5KF8mYrvS z<{Q|@fJFz$j=ONDiKFjhjkA=5BvAChRyHWW2E&0I@cuZ;T)b0AKt{TTV4OtRPJmWS zrbUBh*+liB?~(}>i|zjrgws5nYR|EhPw5jt

$}Xm{h%fDbQ!RR)jN;Cx>vv)jfHcj5tL$<{gt%Kj^!Fbz^M^`x0;_fYS7tmP z4O(3Y`bKnrvNQkr)GF$EshJ`R4H8!2<<0lB2f|4xvlnG^r6}o_jQ<+OllQ72#%<4)y56@DR{{9X@ zElo6)*PmNdNwope8>#BfFi;2y(_K|t*%h7y_;E?6gOLh-ZdoH!*aQWiT)=SQ^zPKU zCIn?+9L7|mOJx&R9wVjA=hZ^@^D$zBvTvIXxkBVbHsP>S>eD^TD}2r`>Q%0z|6CeL zo~GT&ht!r=bn^YIVu)90op+h#CDx@^ZM)l>9D5TMb&M&{UnL22YUz9kXmn#|_#VA5 z3MEEsU%Zt&TobF)=`XISK5j$z{(Sn}SZ$B`)n1B3NJN)L@FF>f?1QXwOMdlkk7<<- zVftf0M8C1{2Xk-L8gzL%T7zY_069l|0N0#G&74-%gyM_mZo!3=aF%xp-UPH zQS#hhr>^p$+vG~t+&o+4k)TJ#Oy`D?+Bp_4>ZyoVATlqX`CKm^6$F;2#{@R?G)?~* zH4-wbMNP`8CYXWEDE5VI=s{NzuLs% ztrD}<>3tOEkK33~-z5YXH8J{vZa>1mur%&2{PKWEx9Sq$eqli^6yRQHt(*YFYoa|} z{Ewyrj|%qas4%AQn==iP+G_}ZN@74b$2w{4ksI%ICMlP_p)03mERV!x1Q zi}=F0;T$@8X`li&_|Sb#`3i?`_~hw_L_~e6RrYYFAN0;lz+wlI76L69Rhk~P2b zezzL;e&h-Yk(pzAm3pTd4_)`SS5+vIrvhu52?Ql82_DvKQBvnWRc^6Z~b8Jqe1(bw!D@kJ{RA3 z5k_YUy`bB^+V`sZQbCOh0lUQQF{HpgRC4N-Q}bE>bvjtrd*wy@hvX^%v-|fibA;E- zYRq|gFM<~`8fU+&Qvy{M-HlfvZa6wY3SeIM4#FLx&v8}Lc4#A~L6=?+uB!Rp!hyC& zi7D>q#=xolnRU{1#VB@~rq;~`8JEkPh7@z#K@-RxP}@y3!epcdtMdUsXLBaV&FEYk z4aeP&0-NtwnMTlZNHm*$Cti>?dbhv1xUn`p5z_mxFUhvpqH0V9W}>=(OZrlB0Vt#` z0a11Z`I6E*=-*$DzHnmxlQ+SMk9JuZwt2y@lL`qpRRRdbisx@hhu z_PmdMI={>v1%3JPZkU`m0}VX>>RZ=qTtz2FZXR45Y9{jH;mxp7GCH69N)>#qXzLj1l(xbt>ccH#qT3hxtQ zFB&d=&M(D57Th+n;&Z~cbmxFW5t%zcs99IW{)i_Yx$k|Y6y;4Z;+brXB6W8b@^kr% zb;_q3{GD?D0QP_`IB>&eQO7H4=A!TXsw||n&b>zt`shkJb(5b! z>DOLzZ!+T0*4E4%K)=SJ(Pj%#b1(Q;RbHSEW=-fd}q zOCFhTU@Tvgx}1km)sNYD_k&331?xvnK#E@`P0zS&dp|3D1)O4f2;aN%V^lb`T??yy z4m)$Wxa#?n(m5l?$fza`hX1IO!bGh5rF0h&`KP%GMBP#iLd~~#J{0cD+^}oU)HIhv z$*>xLI{rSz2SGgi1U4)po&N{#W#b#jAfeC){-PFnqH^jk?PKBq2LCd>hK;xd#L z@beJ8=J6s+bYdleY$}S{_)U;d0wd)SDBF%Wmy#{$R9j?dP7GS>da5A=3Q!?hiHC7P0#y)eR<|MDi@>xi@7e2>f2#ga)8VhNJmNagS^v`sJm3>f;9c*5<( z2}f0Ytqb2eSdl>^0Vsvc{|3+*}@n`g} z=e;GQ?+m_=e7sfVgH~zjkQB4iTE#^-A?;dL{3jx7kFi=UG$+0;4Oe@cR#mo1?8mU3 z7n*#V>86p$GwOv$+X*&HGHicJ8<0ej$*>6v*^U6#tbo6E2pHg@7y2L{)Kd4SAoxV@ zUF;N+zBhUGG#$`%R4as%_X8b1Z;$MqQZpmR_)e61HWNIf-`PqsT2r&*cex!bK$nEk zIa2xyJEq-2%vvqBP@5R~=FKRri>lQNx=+#Xg$Q4(hKYBv9RxmEy>+E+Ly!WP36;2E zqW298bB`5F+g``#ZFQ@g|D1_L>ERl#Q29!!yPwS>J1h6X=J^REKP8%^kN<)`MdO-K z4Z&EU9*E*i%`G}tgTXi=^EF46&#!>T$?iv)(Rwc?0sEnC%LH3+%;JZgwE51(mB3ha zk?BZu|MrpRbaacTKHHjxhE)MLGK}+*Bx3hfHAO|UcCR48>`;mScf%+UEj#V`i++9L zQ-BWe&-R%wn+=O`pSCR!zOjVmJc{e9J(z3Hf5>6Zd%;5+W%O1!nr4>CsdbNaP=ve5 z&dY6o?Y_MB1|EwZONK@7un2rJLvevot1{^L{;}1icu_5?fz6#tE zjo*L*y#B};^O|$X8L|SBLsm{Vh{GI6jWvV7S?M=8;u_8Vj=eCyM zciB(5er{s$z4a~CZYiD4BdzbAHV=*s6K@tC@6n>8Jl26uj=R>y)V6+i*YFP#VaQ9v zIZBTKi09qt!;!$UZW(&kG@0)6f3MRCSCc(QL*twANN_U!2C81< zd*PxBx)SN;lWY_@Z8vPp;tBzivRt=+T3R7sYlFEdPcfViv?z3+%L4$-AE!;Z;Ns?lPQwNYijZeS2 z>AMNX=pHMKCDvVwcvKgnH&ZoKjTrhwA=UM2tTIxE|Hoda$PUz%_4DUB@pmM1Q= z##s6DD}J>1`*>krk7~y6q{s`2gF5>~!bQ@No=*7Znu1@=ow1Gi?a6e{0$TN$d zYPzRr67p-DlZRTU{~e4jI6zSH?mj?}B(q%2yIDXL?t`p_12v+{eZeal7rO_Y?!l|y zOA7JkqJ4q4pBOZ6@Im*DR1 zE@yTuL`Xlj_gS^4PsM%kl@ zS3f1#5_#rgiKK8gdON_oYP;&T)OK0*2OK;ne0!-~SiAjB*@8dihOvDGW~T_a(Vf+8 z#!Yx^#D{x^#p=Dr-;(=|vWv}nMq!*Vw7fWG<^hs&2h-C8yiJF>k{P#BpTd8vw+yQe z%c|TQDDUBN8o;yQ_7@^q10vhsFxpA+7QeT*nEzN)hj>izUB0kX{)pxPt>{a6TAMgXsz*J$)qprb&aHmh52a{-i`~=rDjV1?Le zQb#uPV}>(X=ts7AnZdljsUBFe1W!1 z=*V7mOC)Mg{kpiO-K8x>y>JpBC9CmS0GdZppB&^zAbb|+`5p)Iu#0B00np8gED)ed za^`gOg9$TqwLmTErI@xHD<~BX7?Ml@C1>czxNtdqSKBxyyi&y1^w2h%1YrEm?`>-g`1^hz?wS2>}|;s(V?( z%%Y4ov_`k(s5<@?mL3<8lgJt3*EZ_4E~o+{V{w(VP9TvWPSo@H3bY>NtrDX5&RXV% zEUZOqU98~{p%>H}ay!JeY|#egp|)r+OXm4pK9wsmSr?67_K0+-h3qg|7!32vDWS{I zPZ*-O)6zE8K#P1>Jv%Li+1)E>wuiq;@P%9gPALNnp;`08LjGeowdaN4JefzWW8+JO5)Ey}_Z&y)dPWS`uzs_Au^o{4o zg^MR3#{0b>x?%SuI27!tD_oVeMaG{wmIE*P*7vlLyAowONt$FL6B&_{%Fq~Ot*foI zMj&<8=g>Ymo@-h^LiU5 zrnzughm3?@f48Z=JBW?;(ml()XSisu#1W0THoO^pg9Ca5B#23~kh5MD^b{hWq_WYy z_DqUFiF@>(PPbOZi|*U-&rFa=yxnU}Ltmc7G*`cIn2%m<^W0#lau4Tql(PC;aJr-@9ZT|t zb7p|kTbD}S@88TThS}_(&jl@A(P!0(Q-9BHiCfYhXh#by5)MXgx&@(=e<=~mc$;b( zrl#O8$GG`a4s#za*HywlH9`;1d+yoGeWRAIuN4vhg7zx>2^85){0YM?{~W$YUYxKg zyoV~Ytpv#6F?u?U;zHoc%1{q>5+ukJNjN1^D24}w_xg&ZAHM0E^QpKy;V3ZZ4p54`pr6Qi zsE~Za9!${WPFL3JN-D_cU!jfDedSeT6klq;M56O4bp>iOP9oOm<&bb?mk)#wI&?K# z|3ch_k_gx~Z);tDiEEw7lzoMF#aV>nW@5-{?R+PO?1C6=SXaFMR-j?8GBO5hjL+|I zl+tfIGM50nUdbaR()VA%kDmSIPdkLPRBU!G|3>+wZdrD~>5-?---JJKWnI={N_cUN zHw5NXVR1Im1!#9Mz@=fN1-&m-S^|p>R@VXhhhz!M3vX>4$>TDzA3Mq;GGukGQh$aG z!K;k>68Fx`ddlTLV<4MW?mszg%f85!u8j60|B%+{&55EBd8(k3`s43Th+Adp%prl- z>f-&Tie{=KDDcVIX~minOh){Ct(VVJbZ5A`F9K&^b9a{OCVlQ1`Ag=lGLOVtRa>Ro zcug<48-5aaBj+mg_Zo7I?OCGCf}eg5Vi2^&;#RVZLSNe`>CCi}luE2To_}1axQBkq zAa}#)73whiP3zX8d=tl|~$~$SWHG@NXw(U-- zPMscrgx6Pf@3x(Mdrf=gjwj8NO}fbq$|Ym75i-Tr9n&0GhzC^Fw09&*5=cj)eN??n zh9F!SiOfFY(qo#}8zp~lxu`JISRS-og+QV&r&UEz)Pt`iw2SflI*j37NGRgx)4Ij< zVJ|JXhrbp>pgd@%4M+d!Y5T7|(^|N#e91Tkc`hp6Wi(p@BBmq|JfpCB<3LNV;ZXK9 z^Ts+v@#J&oc(!w0%cl9v);#~#FKo&w*qvk~8VgO}?Ck;kxp^`WM=gsw-ah)>P$jSv zwQQ5(7CCfB+ghPEk$vnOOd$Pk{DO@E%L1lIcnTevg%i zRpB{$oMAd$^Nt}!gHzwLs1}ayPbn&~M%PE336wvHQW(~3u%&0B_lw54Qx#cg0U2c* z%@&}cVqxW=j1b>&UAb$t>6aYLW)N2Pv$*AyA2Jp@Y{iu{7T-UDuyHrja zgKJ|TxNA!zmHrayx=A?|moQt$K<#6>CrvH@tJqks*vUNO-b3j2c!Li5+Wj=ND2A*O z@os(%e%0cLy&WhroPTz6vySGR3;@q;ZW_!HYDJTnv}|N*WnH`oN`E(k{5Us-c(Ej= z?M|M*__%t8cgvlNsaX8v^jWn`JQxWe>u!2x{@A;rY5gl#_0hF`?1-9%o||6M(Ul_seD z4X)i~j-JU2+O4rPQWd+rB>k#g&eTIVrjr<>=kv?~W$lqn}%YVCe1 z+VlO&N^hn}v*Y9Z%{%fXpG=9=D*HF@S3%@M6{AROfKe+72jx0r7iZg>NsYeQm8V9F zMuxM!WQet6`K!4f;PXee#8YVG4sJj7v#h_&GEUmlIoSq}|J-66O8H7%5#@PH4E@wE zV4l%1n*>j77Jzd}qk^n}GrQ_p=C$U=O^-7kdB!GTsv>1s&rGJigidX-#om=^L}!}; zumQzSc$skyB)F6wiA3{CcU9JTr0TulrX7}!Pcg^f^D65wg=a(eL;nqHA@$8YW*vQm zuZgMo`Y0*&;&M&W2mUj4tWi$?QDgN8;M=x|is+v&Q|z~oV*ltDCboQ z2Fwsw=6+GbZ7An~n zr|D2{AURBWZnTX4p$m5K5gu#NaI<75zMs;fc@=>oU3Sqf-}61z+yC%)8+*h5!FGIR z+o1V4go%r$*>iS`jo^^oH`L^ zSa}B#Sbbe;iB>~@-ZMOH9-Fvf!GWQ`*3-I68JfcFuP&hMzYmxe(jBo3p|*>I#4QV- zN`hTRc9t-+Zd5l{Kf}yPIA0asO~#e}y=?`X??1YYhra=8ZR6R8&1Zt$VcR)*9kRr3 z7{ohWZ6Qc#-Vd>h<*(;V^ux*Wt|-j^n;zJ_5gH!~wwh^_sSZ=r2|gb;xk)tYOA4W> z*oCW#=vnB&BTLNEUH@zY&bdF?Q$o zJlF#MgLlDk46gG;l&!^`+m6F(aASIM(afvB+|N3Bi#3vmQ83QkGyU9or9}7(kAEHQ zL^e>vVPuX4(WE>WCHGi%>ZwC85rvO zF7Qddt2W{;?<`6}`8#e6iVl)P(gx+WY&vG)CMdfyI8WTkMGY-%+n{5=_6^<_hq`t$ zv1@qp?+|!o0&rI9^yeU;f#;t}I74k#cp%F!ruI&>{c8rDa$eBa%y#FNr64OyxB7`F z)$l18*$J=noz}W;jHBjvdC+++IaL%;-tO^=PGW|6jok`E1HJ?dxo<@-f|%p!xgi5r zfzao`xA>be6VBq~O`s6XEs{j4=RGn>j-(lmKmm$fpyg&e(L zbfrN4#t<#}MP8wx!weCkxs{CLiiQ|ConZ+`63ckuz^@-_xRa`Y^eE@{OMd~j)mDzq zb0=LPhmRf>Xcb#8nMSxRu+;7jz|S_U-Bd!r6a>$Y)|>TP=X*Z!Z{MlGPtXaTwrSp4 z3;D2|eyb*{z*m$mJalk_9Pg9gZeR!>rXn=Ki1c}!jqdMi@g^$!wH>OPUM5V2>bB|WEz4n;c5sg7!ZB!V1IN*%WnjQV| zOCLPO|FJ;L>QwXF>xvAn&d6MZEwYlXVZ2t-(QSdyuD6jB3}^QDo01{m?!U#URLJ!A zLDg+*qzwVV=n|>M8^41TL-pgP!@(o_CL8~imJ>u=AuRRZpt7PdLJT!>MjEan69P7mhORRpQCbaGVv1eSk=6orF_QuIy$0dS8xA+2$QCDYcAeCj^ z^+d%y&pp#Y!_^e?yu7zdND1nTlZBV~j4G1`6^%1Va414{Oy;32mr08HJ&G?1Z8{`6 zV0d#NZHWq|1saKOJS4slYCG?U2as5?PN$!X84D=G8~XIpH(jxgrhVuywANTJ2_}0{ z)*0;>b{ryIPLHc=O2Plb(N(ZT*)~xc2|-C|c2B%nTpH=_?w0QEF6ms5 z?p!*)XTKltT)TJ8oH;XdW_)_N({=tog0MuTx~IR;Xk)H=jj}19KrznK>`g-mLsE@O z&{^O|_-W=zS4&nCHhC2)M&z+SPD#RX+Ay9Z;0ZPqNZm}yhka>kk=JYC_Czd`ttPnV zpHk)%<1nM!H$LJKF`^lz{me<$Sn5G%gof_X#e%1{Iw{iw9`y&tm?&IlKMzknzxl13 za*_}iI>YSrPY&y-{ZZOfyt!xig%5Cy4@1M*O`q`z6!X}Hxt->}t8YlKaG^d#XbAGo zsQhLBO(Em0LIB<_!T`11R`N-H1PsF~C7bC{Z-O83(-|^TsshZ**|)_^+Q)7yKD^Xr zHeU+bUoA((HAVsXvGvUpp3rvf{9>E5viX^u7#u-`6+@iy^HFY%UBz$};-oi&qd9r? zo3R?+pF3DQ>!X$`B?AD5#6&(_xbs&&2pJEOiA(wF|JS^!^S?_UCNVqS?k5A`Ez`fE zd>lO*U&ej?-Zo@EknsNLEL~F5$3o!dyHb*|@Ez*UxXs>073oTM6ccGc5_18urzB-} zBUVLy64&R18ufy^+N)jfwQ5@NpOAiLtoA(5c@t+b&PMBM?e672XykX!$dz0Qx!s>q zKHf<90av8LoCo}9;|sfs>qS;^nGI*tMw5i};8|lD_tNq;8wusQIP&*%yAa~w!nax! zD*2Bj8n=_{if5K@-N__n&&z*_?S#SU6eH0OpPqE0tJ<0t;CI$-);+O|Mil?$AC+NI zKre2mQaJG;HAz+k$;yLf1DVq!f?Hyk_Ym_hfe%9FbCT-p1=Q!)NAl!tOPBtT=IDcA zi$Myu{kb6+9YGV^)JeEE%A?Nh($}}4H%Gfk`zU*kX|BHV1dZ>4qy*yd^reCSCI0-+ zoG>+3+L%%5cB5^d{l8k%+YJWFKrsm9L1!a+|J>nn3gXbFt$pD{8vV2$6kh6Gp+=n_ z$x7{^sWQL&skgO`_J-que)`vyl?`1cwEBs3vH2+l75<9pf^1oT5Q&IsOnm5$(;!;o z&kw4*JNTXLjDf_@M#gSZ@~xshae$Y9c7_CRQKFJ$S$fY=&vhelS9ng-^{)B`y{-IP zcdJAuCnC`_{b=6B#X`2eOU)_;JcQ1RkSZ;1eQQ$BoF6Giw5Z&sYU|w1@`IeWBkknH zRkY7HpScN6FaeFp(+8496^D`}*%0Yx4v`*nUd~8xN+;R^`u7xWD?@qhUmZ z>ZN{AeI_gd;9o9xyn89ROjv{0Fm>N~rgt6oFBKFD_=CdUR|ZdObX$$;e`)8Nsbhu( zCipJ`0mG-^b92x#9)PoC`FtKLDu9iywO9S1S#0F7s3%w-GlVk6EC=Ci&+E>_eXG&l z)lBDpU5s_boxFI5f7OfXXR*h5h^yc2=qbHIiBPT-HI-UBLG`>K7@Xje2zMUtBiPE+ zz}59uMHvn1I=!+STgf2TON-YO^Y0Mx3EwaOHBQAidT=rb>$^6?cEKZ@1vk-0SkyiM zeb1o%T8Xlo+1wx{QUBgzlMioK=91ulM6$)Jp9^~FGVKoT35GD==wdu2b|+(@RkjYp z^OgL2l>`@S(^ZZVkI6mAw68hnQD(BE&raK=rm2BarR#r+$&@yOZoFuPWuSCGm7c0d zEi3#hJn94uS<0rZa$^2;k(um7;mz+(Yl^MPya0BFs>Ljc$6$0L1>l3LHrmLP@Xzo* z#<;D0-^q|#+xBhJB^r$gTF+gQb;$nnIu7zX-A)_%4`WlXoj2o zi!50kj7k6#z@MR}cbV}vSe&0`z8^3QqyAu{DAUU*O;a`tNeoLhn;Gv#C z5Q5(ZFV7oQ*KF}Ys^NJ9=ikPp6Wt~K8nYbsX=%&=A5mvJ;y20SzBTkM*)K%}3w>Yp zZhTGA&l`WDV{vZ@BZf@1hHgkBW^4MQMnGH?$|-8A*bO`w5bpeY%FXeLN0UQg zid28)G{sco>~8U9Wg6e#hR|j=ex?OJ;MlLWdz^SbGSA!c^@QpZp;BV+f^tB^H}6M_ z+;#XEmL;}=h^8OpPq}S0Bf?Nu$9A7JOjK@3Hg(jR?p-STq3VN$`Xw92wnw7Jsnvo+ z?^)z8M6W%Z;oR+Edr4@2Au%&a`-B5Gd=edJ*@a#Dmg>mo<2`&@a!v)okDJ}j29_tbig?Yl;oXdD4X@R zvhzMZNAIuf~JhZa%vN+YGr~hw_t9fAa7K^|~ zKO9rwV;onyJr%&3@{9p7D%Ep_xRXUs5SHq>r)#{n8NH%0=FJV1c!Cbdwm1 zyR--HAe*3>f^;Djd{{X8%_)Cqz{v|{bpN^2;FXXbrrjD&C`G`@1S)k}O}B&R66#rdcn;}kx+4KV)CDiD5oX;tm@AM;W$>~&HiGH+pzb&yrD&H3;eSM7YfTa zNI&xV{LDlv)4@0c^UL@f9vSQ@4A^aEX|Dcr&O;zS_pG)UbBRDou1*0Jr$eI=-BO|0 zH&nMAiQe+1_pk^zlVs$)@wZ7Y!DC;-!DlfVxvRXSLbQ?|j5v zUXiv}J#5p$c0(Qa#^krRQencU(llGMju~R9Va9HTJ`9&NJiy*QT%;H_f(TeLCJsMu z9#i%3mT#j5M1reNwUYDC=h0zzuqaN8pB9uh&qpzu`u^{-ajMKUF0uHYJ@c|~IwMhR z{!QAWJG19V!xJt=G*+z4j$sV#8a*|AfsD4Nt(J&>k4RS^&6A5~^}q{uSd`mA3~q8- zUvY}X&KMJ@%4I`weZKyhhJR+w`cSFdgRuJdd~kBWr+e~*nXsHMM&3=td{fGe08#$c zomlQRA0YdLpILF7cHrQ%u_)m^Mg`-nJ5-r#Kq?-kZAx#y0r10J*{HS_0Gubr8V?0 z@E`$v)cnm`9ZH|LUHsnbF1e3w3M#;U`Ea9*=Nt|*oH6vabMIButCs7TJW&U=&uYGA z01L<6E?Y#Uw^xCH{gEEYQ4gNA*^JZR^ghMzN0i@#ScmMFXBOF3qow47VeM?svjV*4 zfd9nP!O_Pw-T23Ta-PY^toX(6^Gs`zQ0ieD9>eta$1;gf*jc_14a>>w%FcR=i@2Y9eCw&#ws!?s=5^#}!`^P4Gmc#8)Ld zQ8E7DUi}s5t*9IcwJG4#lZXOn$0p`1xTbRxjLi~-rJ*Qd^-4G#;*W8JYC@n+3JxvSW3OhwW<3Vm^qfz#!5y{ zf5`4((02?$Kv|wU^u^no9(#DN3k+uwhMb&1YjC=TU`UJQj9;ZtiKk_g137{SoLr z^8$$LBPrLr&rQe4L1diyw~`VvA4rz}UaZfFWpya#w}0!Kh(XEv&eK%2iXDErOYP7a zjgQqRU`i>}$#q8~&A1z^T>xCc=&=L_!FiKz{z){WJks#ZedFhr?T-+B&$}tO&=yVf zmX>{B&<{Pvz3unAuigUCJQu67u`MPeZM&ybf_?lQrQ2RhPVwOzj8XI8-VqpMFoujO zeN5wq+80(LS2Xt{D33CEeUshikPHSv2ZVzz&JwUmO#Z1`C(JzUZ*o21(Yy4PbH)w= z(cqA#0i89sK;Z4QU&ialj*#loB|iIepCY69tZER}UdwSd3TYVZ#c7g>_@EH%O_BZB ztizbONfihDy~A?XR5UR9aav(dZ^4I@rh2Vi;b=t~D=EERMT}KA`J%Gkn#APP5*#v0 zLu;-IB~50MhdM#p>6jB?xOrDQsX5CBfmhQ#R#sFU%dZW3CqbX$jr=8TZoJC^Y{6glA*}6JSh!~lBtC*#HH|C) z?sSy}-x#ls`8w+Tt^L{|6;tKpaJB09Yy9vE*CcXP45sC zFM8JQycuXmHnNP@jsJ-@p+Ec@_(RBadT7o(T-^`+tykA1|l&;$rA-bMMy#_Pn7V(~X_+p9qOyCbj_U(7v!#=-E4`RhtV zx8i2Ty|R_(1Kc#GK@Z$}+Ark;drP^P?12GiMA`1?jR^I{eHJ+4s=uSww7+rpQK0QW z%DOV^;}NDJ?Hs`b6@wPD@w`!=Z{cM1KgZ=xCQg{9!9lsZDJGv~p0&Kbx=Knd zC(P;|4@%l67C6Y#mVAIgY!S1s7cZ~Q%efA!m%Vwq+z%pXC6MP&NZTVdpTMy5Hr@0` z|M=^TkWpuPw`{WmJrx$+-k{JU3A41H7dS(ypOcnofSytX#~3-|piTJ)lJ9lL!&ZYN6!AfytHjS9dMnoP%3pdx++Xo^nG!u*_(+T zE`aUjx&r&8Q#~W~UdL8~^xmkT!O2n_p%rTPYdlqXs)-^3^V&yq>A~*_{iIT*MuCgv z!iMdyB7O#|U9*2ot1^k+j)zUhS9Eyt7WT$jd#ZI3t?b@5v%`MRX7}hZx9FF9x55zc zdubhrQqo!pl*PMn`T_X1-8wo{`U(|ud@F;$O;i`%C(-?97H;Q9g?2;jf&7-Ni?a!b ziN(&buSx-ro4$xBd6b?_h7#_LGGZuCK4H_DCgc~7?%kD7FX}!II_XtG`GLHe8*2Cx zb)vGS%ESK!0uk(ZRnt>9M43?b_^@%8@ITSW(NuKLd_GxyAENz_Eu_BByWjju=egO| zlyu^!9wUHA+^XN|{%faf2n+Qx4o5Ugzy@0Kz0jv8!|ave8W4BF2Ny8u+k{mDy50*u zjmOJ-0Jdq!#V)%DN8uM;7jZmV(e|{P!X~Q5Lezf@V!sqedc(AE#MtU`{IVu1$TGtc z?hgex{f5cM!cublxe*pUm&2sMFxCGU635N0o`96Y?$?)3wQ)Ye=@ati_dO7I(>q64 z;9_OTZPY)7#lW?5~%*N_Ho3(sJ7&oF(#_WYOq+vd|u>?}5> zMHqKGjN{%DM`1v54{~}q$Q!G!re%uuI-5j}sy$rFa#5fk37$`ti>1I0pe-HapOuY^ zOE2WZS4HO=I{t2wvv}S`JB?4IC~$!>X~);Ak_?lj{5n=axGjXxKC-8zO!PF|PciTg zUZFJ~gHSn38FmynyjCN^!}4Qcwx(uVhm-`34Sa9995EdJeUn(I(^q(=rg#rOUzbf? zf(y%&?wtmS5-z#@pp(FJhbpGJk&D&4i-$b?F};zrkMaw^s=3r4T2)2DeDwk2rG-hx zTG0(8KQ11w!Xd+B`8EOeYO8#^wi|Gl4w~=3G=UmLLM6#RsC6Gq(dRiFH z4%orMMsOoqCwI>E*b9-YJV&`hsBddu=(V!@pmqH^Pgl`kHWDuW;8WZMik^U22_KW^ z&oHY6C%8dJ{xDZ^;lERM#pRdOlJGy{wY$haS5YebzVWW^8iIEfE=Nxhknp$Nm{TKi zRWneNA)PDFI)@#`T0d1dCoAlJFvWyFLWNpH_tIjk?~w;~C$64oRmPZ0yqnE;9u}1M zr23Cp`>trg6+`ptH(T3S!!nD_OFynK#Yi6Jl%{~RHwGQc+cg*i9;>1VDHYYndH}8w z7{e+_3^TlpzRwS~9Eq7TgTgQ2ctx&@SoX9>lh-xY?Tx@rx!loW1@+@GRni+AVdxtupy+A5nE zHwa^gtNeGFqkSildWMN+G8a2ReOB4g!XO-u|N8IB9?NPmootLxGvH+@^C#WFqUaLC zvDC4;C;n2;lD?zWI)KH7oGaBEczt|-)Ah+3EjB#tSBmu~N8_dpv7hzJz1M-!I2JIA zH3h0edhsif>Y!VN!bFD0zcIa4k*Kq1)PUQqwyaTNaTxMYn`EP|J3(1N6(cosMA3H% z$O!A$P6H{P&E(kk1cIluT zaxvt2oPmsFVPK43h=5vjfC;iYQI`#4E1#=MM@>Yo*OKwTD-(>g%`~N_`x^?Z7-i5F z??^ZO%8LEdUXL}9xKmlYrmVvH+WV?%2UPJtyb7kP3b=S!3!$$+Zv7_=?ZX|_5F?Ty zMN&3IaLronMxq|rx7q#UqR)F)x*okM0b6VM-(q^AJ8Hp#;AWR*4`6uOqYF5CdnVss z3WQ4gIb)Mw9N9=HME{C-I)+`%7!~SGd9Jgko)^7{Id-154zUN+HGiZY9Jpp93hlRy z=etzGw6T9xn3NkZD#fHSBxw#uv8?}>)hIj?qvxi6tIGixLwA)cD|lNt7J*-h#m+}_ z5*LmlkPDNfF?GX%jGLehiBDJW9=t6yl>{!TEYRFXuw|Wgy07cV5~_lHC-21mfSjbh zy#0J>dLBFXMR`L^$|+BT;Z+Fwljk0dWa~(6CR;g?SVBpZiEgE1JM!MTaWartvkC6s zT|~h+&yCS_gJ%lKN`4^x(s)y-a_lC!j!kR1oCi2?3Y8>Xjv$l2Qq7$2~ z;vJwmZ~AI5ti0_2ju6r)seDZ|F(O0*NT+^t+yNU-l;P%|ZYNP5i0Y9HiNh|S;6eo2 zz_~S02t{}V7yDGGsc-QvhOQSFP(jJCzlG0e#l`3y)DU98h}#_Nlc`EOkV{!^iZ73) zc!6>6DuT7vh=M~y?&xK_f?jkj;;wJcY#ZD^OgG{Fhm7kVReH&-!ItTC*M0c(~9^UkXZ`E zO9i*;jJl?KL*vDK(}}sxfr^fe>~iqhp9>P@aeU$A=)?Y2F-qRNM#zT+`M0*!W;0kj ztFbS~{H$V5JCq)LEaB(l{xs|P6r=o0q6c zR19!0XP81MC#mqeZ_9^klaxIjm9nRe2`rnZvjRH59vFR@a;I7qUDA*+)y+66ZlS@u z3WQ|CH2J!_C{E^QnY(QFX=il8&>M=Um-df~68ZkjWXhp&pL!a5--0-nsJMg{RU!}-4jjaGro4P)g6JV#1T3F=Y zqbqJL-GMr@`y~}~--ZxRb>63#c(^oxXMB9UT6eceR_IZc$GS#IF4F;M(eAXbb{fUT zmjIrK{a~ZupU1D!;p|fA8=xVd?aFHe^KkYcrgq0Ut>5cIdGdz_$`A;DE-EXGM=qn9 zcP8D#^}BPISro3*9>i$24?SVoqo}ZQSgV6%pwF3o`HQNw1Yjxw{9=$o?pI<>AM$<8 zBXrnUyThVNSEB0qvDg-3(#SxNnj9uuJAP03ePsi&ixHp~^Q(?uRe=C0Yw;`FUTw-| z#D+Qbik*O)GADgC_!2jmnAGLYZG{t6yXzY49MlI5gyI!HvI|Z4)|iMD&P$JVkEL;c zGgTr|{ZQA&J?ZRg=QJK}`2u?LYx(L2A_#3~B+Hi+q2@L2Q6y(Vzo zP8ohp%~-D5EG@G3T!?M#OodtA*_kZuB-U&9a&sp-o~jph zYedcszvvwTH>$1blBBfBuv`DQD!y?fRqvkQ|~;i7TncfrqtW#1UQ83`uc*FQ%I ziUTE0q=k%Opw&U&Gu2*pwa0{Fo- zX#_H{XId9SC)9kyH=*r8;KXD^U~Jqq;48A;QW2PWo{E5E?@vxteqq)`PMsE>E-1d*uf! zuhd%`Yq*05_+%UnVY|Qd``R2F8&<+m&IPoGHg!GE!if2AoBOAMz0$iRyZgX9>N`2K z+RFZl4!>A1RG@dBRs$kq-;?WIeP_w`@W`z83S(`DSrP-W-Szl+vo|Jnqy|qCYTSOT zn#WYys;Cs}nZ4mNmxd6ZoEt4d?m(otI8OG{vB z$SL?ECSGExCZ4PIJ_e5R)A|N|J8;vD$qH@5gV)gSV?3^3rq;*w??aSdLnq7uP2NE3 zL5g_0r}Oxqb)1&_n2Xx`D)`X66e@?wJh#5cjI>73K%jW{DBk7SR8zG6-=w2!C&6Hf zH*}JXg%R5@b9f7U z4whB4U%cC_v{1;Sv|Jpssm>qt5881fIAB6rM}9B(4_vnuJ#Q`l<}oI5KdJnyGCYF` z{VG(^Kx+jMe~ICpzlnR+sUDvJ{ct-K!nI$;Y5OAxYec44oZ-ko)vihP(&=KYXVZ~< zC;uf8N;>T>+%odkwA$aDEqg5ikoljPc#OGd7cOq4}GN-Y*tWZ4yx z4J~8NZbY)je4H^@VsV6=LCfLsz54jvHE-cYpYgA7TKWvQ{zCQCts=C85JL zrqa@bL_3B6ZT&VB^RDisG?kMWX*iwqEvaDax`%cZvt5~!cu-M-t3A=)QKRgG*(yG$ zPF{UgiMbsEBNBbc=68}^@PRQ_qvw=;ggj5)v+UTz3F5yP$Ahq*|9yF9aBOMa#b-MAARlL!28MmqMv}RrIt}D(xmjm-a@?+C0i4FgGD&^~pRTc~$L#?jtYt>SFLzwyYE=_NI zYlwoy)Qvwuz$~JTRxlvFS3-3;(Ch@)PLw8VxN8E}>5oa17^a~P%#;Y^$cF2MU-Z#Z z-^lO2tirRcgt8|*)Lx{U%kLAYp?yfBIZWq z(gWYLm4^a2XFNlXn1#~52OMQm{NJqP#qZL%?6WfuCb6}}%NG!UYmenZ7WImUzYO15 zozCDuSD_@~MFoN*DY6Z7y-3$-Ll%Ba8fzOe4ED*^YWVaJh=!~T;$w=>-PK4Ry%mC9 zLh%f)-4b$mj|Jjo7rWDzG3qpu4Xp=QnKx_t7ggqvi}vSB;$iuqe>c~Ezmh>;(l)#m zK@|&|ejI@cOKAo|$E$R*RV@?z=s@jM-(4V#u|e*iNVQttT;ln?%N9K7Pwa_y4G0r8 zZ}t4fH<9TK`yyi6k++a#FUum`{c7FM5X=-^EOdPk@Ar5Fb~_I?#UdflzMr+kXGTxN z%SzXlw?xo_ux_(Y{7Ct7Sf6tg>V(cKr~jOYPmdfUn6h56XatFj$ ztG7gf3Z}rO-Bo>pt)M4IVIS%rn?*BWx4dY8HNRr-XnV?dJwJcNv;I|F%rBbhx1JwU zC-+H$HFWXP3*Lap^DQ=D5#+ZRcXLEZBoP`l?wZo&LuHRZrMFHXX;|Ak7b9hvZ~IE5Bvg?n#+0TWrdH}nEmO2j^{fNT@?|dFJ0=9kqc$p z8o7PK#oBwP8KLG((I>W)n_x!<9L800C3-jw1yTjm#H#ml+Ix9Mm1*L`27Of<)l*G- zykM^uo(_qE0Hp1He+8l?dmtCygt*`E+BS;Tbw=Gb{%g`VcE4&{uc^tfE3N$%p^N0d z3L?)@6Y!(BU0O|!PWl~?meM<|w^8GF6p2a%m$l>eZPG`Zr@z$v9M9uCw@o@V?HwTG z9%$!D?f%AtuG+2-6buV_K#~qd^f5}Vrn9^ygAwMzD`vez5PhlJa=(*US@hJG&>X`D zA^H1*hE>xUd+0J`;30AF;%n14X3OFu&*I%bUA;?6*$^|7-F|Jg0@_QYFZO$r#|;ne zg4s#x0Sr)ne_kzV@u3+YLYjlc!n)pp!% z5}*Z`Tx^FfBs@uZV!Pwxtn1Nz9#LCdW$z3Y5w*FOSt79T1itX}Ic6bXmeB1pr#k@D z9~vuaIubEY?tJu7qpBzu&uCM#L6_cVmjaf>gE~E75ufdcG%G8yU;|#%cDVgg;2s*D zWGQ}*!th)ojeY@IWV@ND+KS0>kExwi1_yko1gh$qyp%&))U!&$P z`d7Vs@Kro1`eXJ_o~q7OH47Ug8cjl`AG0F7tZe(m{Dy{%Uyj(J@C%tOY893G;%gA? zjr16)YIC8b(njlIqB_i}k4do^zKFc1;J@zYufbC`*$le-&9{6ndJ?yJ7coD9R7h1v zu~Xq)O^>5Rw%%xxs?oV+Bb`^&0m86Da7P;EGyO%5pZj7D3e?eTDChD+cu2~s*busm zKLeZOeGViPZvGMN29TZShCrF zRzdtNFp?W7tY_O{@WbeAeS7!fgyTGpru|+SP+FYuGTOAz9~nbRl@7n21wQ(AbLHj* zW63Nf`^~QqGjPb}`^;_ikFB%Yid7wSW&pA6ulwjs?xLr7yI>!>FR`iPyZX5ovEYZh zwQ0Q;o6;Mw@3$!+-YjiW0F#XOilLet`+7^`nvK&2K_h$nA6=-H)}|clQUqb!41~tD zNVSn;0y1_!QyU*%m}^DXRzo9Ehrn0*yE%RV#j8n=!9n&@k!~tTveletwM_26Z`H&6 z=noeyo5qgIzwE}oEzye{VF&YFQTn`}#9w9a8K`OyDx#;lXS}#mx~PD4oQ7!2@dKPS z_#N@M(`-(+U-o{8&|4uuvt1W(BMTdD`}Z<;xmK)pAUN%mbtLKS!cKXIWj}`eW8Hzt z-RB$=C7#~u@51EI`T>L+pH~w{{k_blM`(E=L{n_~8z?BIZyBKzF&GN!vU?wdR9!@b zzJu23qDBGG6GS-m#&7$wQS529_ZMAYSN9vUZ3Abo~rWG{L{w zaVL3${|}3KUB|-6f9r#W7U^cF&U%>ye@?bk^XM&8^6knR+p}!<^1d*i{LP#DgIsdM z;RhBk3o3#PZZ;H)$=Ym!Pd2^($+6g1yWU}MOpLr+Df^3pPV};v{1+Lh+nJ@ja?_fi zn&wHd)9dsi4isp1(O(>#TFOLY-vBQ&pd`-*=aYSp_D#(()!C`007B#sYxqP(JQ%tg zI%Hhy(*7#NNBH@&mes-uMuY5$9WX81GrHl_^r!;K{oR(Vz~j53lzCNLMRvNs^C<&m zT%dla9d&ARYQT+uIERDCj=*d!A2hp3<%0CRhRWu8im8B`Uev52{SVOFKm4}&)sz&) z@W;#Uxk_2}$8Btiv>|?2hksr=X-$ZTX(m?WnAA#u;W4e>C}_6-yY-lq8;_{9ytOMM z)3?D=_C-!ud`AA3*;gP(#q*o>X{QU6xh2;j}4s@*PL@sLR-OS%MahAa_r(jP!N zMH;Y4J>}&B?)HHO7V$q;R~${F0%Mh{pm94lH>hr@aM*YBr>D1F*t-hwkNW-=s^7Mf zEL{~ibpduw1Bd$C9vYtt`WCVDn8clSoI|F}PdGNvWKQ6iAo8*LWgVSQ!|H_7n<<@l z+Nanes#51Br+KsbvLj!{&?5o$<5c%epWM7pEa>s84Xw;>2KFFbm<+&F z;X#p0Rp? z;KN<6xcHi{Qb@UMK_y8dlaX}%f-Xe7fN!{(4ih5>8OZdQ;K`lN%*D#r1pIgH%GNc$ ziLPB=_!yQ_y1bLWRCyP})P%KfRGM}BOS)I@(86ltu}gJdSAI=qG&NKqr>UR%^wX}+ zD$DmbC!+O1-z_{_3Gh2){k#b-x7HE=i+|VTE$oIhA{~nZrp7#kVkGWVE%PO{Or%WO z_eHdZLkPByQrSQI;8??Y&AdZIF$^xZEmY2hs=U30l1{F!ppsm73)ge$S%%$gi1}MX ze`LQr3eiv6ERqk}RIb?{FYy=@H_E^ZMoV7I-~MGtro#XpMZ7;@#2~eNicV#o55F0K zm+&p){z|T>?5+R9*Pa0T-W6D7*9I-BC7we~dY52ms}tmF*To#Kd`X^({RpQcY{qlj zwxaG&Mwjio+W3D1u)S>CKJ39nOF7*H1A$nd0U2?JjjRz`&v5hU7V-96oNCc@k*>-X z#>y0UVdoo{t`jjog?|`xy;%rb^q$D-W0Jb(0=T-A$5ZN0rsZ}2+jGr; zRk1WLB46}D*a+D!Q1j^0DO}>?&W=yK%g2Ym*4}t7IClv7{TRX76q?E#+yuMxkKgM# zb=`Ov%bd%-*B=PWv<)eSyrc^IhSMh@ldo2ai=0D|_H~3-zm_}xuy(3vjNO0N(ah2=#(m;zo;G(!aT}^M=!~j8~ z{p}{?6j(^l+J80X&sbl6UUxYpFPqrerPp`5xlpObH}G)Ra>v_w^}EY*9=!Ry8hJ4G zKwGd*_U9(!K!LDgRNug_8>0RzLE>=fkqdh^yw}K&YD%!RzcoWr23ZNwz0R8%-H8As za`lh#z3oSO-4tzo@6Rh<2ne?EoQW%%!G#32%fAd3B=3>p&)x4Q5vS=u^zxjRfV2*# zjd5*z3<>Oi7-U}(d3~BMu|UU+xsmtvr>PgRRSx*f`z3~U6j#cmLg(zE%Es^TwVvASe9INfiW+ifD@@pIG$u1-507K3qjkr1}F?YSV(+;r~h>@sw ziBDs~t{>YltCblZ3=C`b+1P-jR-093fPg^!XN8CANuC*S8jH#c$=RAu?QwMyln|z0 zJp(bzl{7ymQWo{ySHoV&4enkvIps^k$;YG}IH`BYW?~_7Zt=J-v0FQ5RYdX%k^WU! zM3srR`$iz)!QU+j^H{Iv$(ezJE;NeS&p%7P@JTuC@KUHP58sf9uswK)b@X7VSB57j zhlRoxI%QUZvZ%0prakKBErQ`YTd(t9=*XaC@6NxyXx65~FPo`rGT{e4-OK+;Kv>6- zG20c~(TR$T0^7bu6TjQ@{S5!!nO1%l@H8WoWLCnwtomc|C>V9g#KDYbEMZ${jcb(IBM&ajr;E))$x~1|zNpSib`@GDrf9@@593^b zR3ImuoA6uOrZ4HhexY?79k5ZI5)FtQ=hHdjJp7q#eMp}(*lcV~t-F7{&3hc`9s+}= z2-G@Xo8|qOS*(PFQu6_%8bW5MBzd9DzwhU}r}ai)cflxGlYP?vi>a~A9XSe1h^=-B zm+g^AJJk@yV(dxAX=g(GW1LGBFs~uxJho3>*6wVVL1~Pfcy*zDtM9p0p!fE<&Xtn% zM~+|HmgVUX^tdMjEb;`n2`>8ieYRI3Sf{H@2-_SzNd^fRbYhCZQYlv)7Bkd!nDyqi z+f9PpU!9C;7c$wNQj|9J(H1+~)KYz^t&_ED$3G;MyD)R?oFW(yF&b@sW#u|x^Kd!2 zx@!=80+H~ph+S3N;?kmTRGV)1)d*e4Nu_>!eMCALvs$+zi4$=f0G_*$vJ@L37iNovvF_*k`*pyVX;h!Y2vbLY7 zg(a@;EHsWSesqai=Hho~#+7u&05j<>0x97zZo{JFItiE$8~mpxyeOY^@RzC2_WkKc z?f0`rrO_YO?4D0HNKQBJX0cr>@}P3x&QH3e@li~OX+MV&Av>v?i>Ho58kESa@!&j1 zvKsqdg+J|M6h55?ws+)^qB4_fH^rmp9GQQq4fbk) zK0V_76P?|$PV`8Wt1@t_h8Bg12E`AmpU2~;%M(dN4C9vV~MJq$B)}=Dy6!VEG3KpbM}>T7h#hN+pwmpr_1Y0cTES_AVNdG^{(@m`D61h zzkU8C>Tk2(edkR{OzGbN-uSUW3k!#Lwy)PAlv7)vJA; zn$XjMMRXVL*I9k6nLIg~%igi?J$b`2XRl}xb893 z^w?CD<*eVJPS@-Zmr)Q!QgjV3A2J2 z)W8s2Q~ky!97;ZXyIyO&=*h%F#Z7d*vj^J=s8tWaXn44FLaM0MNhoiwML)UO9s_eC z>Dx{wGzZC#S?^Njlf;);m)6~KG{9FF#ie}8^7g1 z`^5l-Je%(-^HIQog@fp+)7G;RDv@Lob${B9BekULxj|84PS{OE8-!PNW2kbOFWgw7 z@F6OefbgNb3%%9#k8Je05fJpAF`Z2adL*O16t;Hl%GC7KQD?1fgVI=cR{|{li-Lz) zW@CgLn4u9^9LVxWAV34_*#hFTd*S@P2C13R#;o^A1Y~Z1w^o0vGz)cGpd!OuojsjT zzTo7G+)ln66@~)uZ^!hA^wb0M@IrE~)A~(3CWlh!z@kdizvWetwb`{6o?I>4N>NRo zx=)`gvbhff`eLUlzu%mnA1F#poj(?x;riALn@DGm47qrL68P?l;;J>8{T9a=xrU2I zdoEP+0V4B`_%ZoGB?OJ;R2a8z*#+)iy_rkqkjscD3Zrl}#sg()jL8Z$<_LKw$20x< zMB;Z8lj|B?Wt}lVb%JADhNjUuN5bwF!U8P&EFn(_vkGx`z*h!^VQ$q`k zv+?XgH~Pfer;DfUny8qhbKkTBEjMr-Q62J_&%c@Vz)BYNq>EJcp3B-eUdCJi7v#E8bkvA*y8y7(WTS<(H#<<0m9{Y1*U7E~g# z&rRALzx+~&a&gUOX@;-HzQ-}kw^g|+-%LM!rHsS{kIt<#*V&f=%-#rLelo61q*olX z@A6|eA~0*!<>{~@2?#wRo;itn{no59^yh+;7WssQ;9WbB0+g>mtlnt73nEJ5Y^}}= zJ%qr#~6f~kXkjc5NVp-9>WP+t=A3S{8wO5hf7GqcINLr$({u=Cbh_yzNP~DfPTh!H_ z;-B=LFt3%DW0Rl9PJ?#xXw%< z@6Rqhg&nprU0uWvRMc;O-RoExgWkdA+f0VoTc;Ax!B~fKybU=vjo`uA&k&Q6Gq3i< zo5l%MWSWO#DE7%-vepE?EXPAsPD<*LQj(h2YnWga=3DcbexJ!+EO) z!wh;Xe71IyaA_mAUOT)j=*~M@Z{TwkA=nBcer>q|)$Rw-8M1^BwIM}8b4O!!%Ee^v zzG(*=z1{9mxK5G;Gz~P;gt$>qVJgxk2_n1G$9jI*^ehN7K*W2?y{&@elKP&s?hZ!T zPc+;)-VEn`PQ(T(`B)hqhS?&~@S3UZvSTTG%EZQwG3_}F`yM`fXdWZOIA|`6j1#;^ zZKp6>^NI+D``yrsZO!b#(7*{eu&>5F6F)!0I{wZ;K}n zYl%rfLaP{m-#hOL{uWk{}s+8?BO4vCiMhG}ww?0_>EL zL@O31?#w21yuxaL5&2*kbJ@Cjs5b{+Ov2}R=_T799ml5``Iv{vuM-o) zx)sg6bCs;75L++k`h!s};MTy}-$h1#R}?djJT_cCQptazKnUQ9hw-DE5nmU+n?nQ4 zdOj(C{MGqYCW1(H4Y$Qr&mCRgwc8=Nxr%f+Kfd!@>s6@Nm?i7PPP;4a3xNMeaA{Aq z^s`otNA41vZgm{LpDYDF#+7hTCWXnq*Dc*OvIQ1!OgoXNNrvg{ZaK%r_q8&oRA&5Y z_m1(h@AvFL12<=fKEC6H2@CVLiRj4eS(#-rIY10FRh^}M`MIF4CV4DOPhGWJf)~>- z4s%&O?;p3(MxtRads#~VZ(77NbC&h_BdCt3;ED`&t^-m!VBibQoorr-R^JH1XQeLGbuLY!?mNq&;S@9a^@A|36S;am zIfT4j;not*_1unhd{xN0)$rbP5V0-5m>8HF2hYx@nl6-pEnVf=Bf_S2-$I8a8&Dy~a`7BYY zpUc#u&XF+m*(Fl>yrV(?0lH4IarRVQ`4 zRrO8_4=X<==5+n@eJQAZ`aNO&`u#Ni3GrWInHJh2X-*^IhH0tmz*!R8@7iPs93ZmK zd^MLc`)G1gfUoX{wRq&f11!3}=oq;XA|E&TL7po#KHPg}O$xXS$Or$5W;vQ!8B2a|5lP*mo{*VA7MuDpyumX z5#L=Zfn}7$UU;s=dO5XBEp&-uoV}=xF;DQZ*2)At60U`}+Q#o1cd=l}^pBxEOVH@s zaG`jvh?WZ016n;7MEjcIg`vUN?sh-`Pya6mkN!hE-J?`I*hgtoh1OIF&Dzj(s}EW+ z%={fiQ!5J9=t?)&$e$cOcB-Lg{j*ESkp{E9zP^msZh(S(7hY3wUXj>6nD=vt0Sc1Q z4vAMe>NWFAZk|(76m>S0Wqjos3_DZ$Nl`;w6I`XJg_zsNpj|iTxqYeDOeB zD0YB3MmT!*`7kiymeiKE%RuT)?l574kEh-LxROAK)WbZ}=QbVl$rxW%pwj@<^BesL9Kl&25Yq3!p>C8d6o^}p(ihx%TM&TJd6j)V(LO4t4Ir%5{0YW zC##;j$>R!j9Cj(&`Ss6&1Vs#B=H(Tbf7O^u!zFty3*hSkfV%AVcgH5ZyBZ-W^`0JE zH}3q}&}%I=Mrm^i_y~CC`>oIYbc))uLQQ0w5UP8rqysOqDn6!BkNB4V8U97YfFC*R z{5)%t>N7|ZTriXCRCS3>dJ!q~)n4NEB}((Y5GT>d#JE*={>AG?4N%0aPC6ctYE>x{4H_S@j;vo30d@@;I(C8u5^uSZB_PA6V3kda7G_gF>}#v|R| zHjf0Q*|IjUdm39iYt}O-EU%urz7Z@w8AI99%S92CwSBXCKg2$sFF=WQ;yF|X85_bH znjC!`zLgcDfKg)P7cMbq#~tUp%v{;ru8H^(u}XgvL;UIeZPt)WQMzMbjI||}WG@s_ zo7bjK*3?h*9F{2&BV4qeTxMQ9us$2nyQjK&(}tJFlOhRN?1~}%o^~q+pcsMUhyq>- zy%f5~$+EAg*{=U(YgM~ihNn6IrAw|9K3;ckE@fg1gDmeha~yspLUpM4eTl!(H1>&G z7`IFD5$TASYF>gOen0`=JJ%BUcN0YPcqm4F@afe_^*wFGR;{kDw7ihOXM4c=cJS+G zlAa$<+>gGbWx8FzDe=E5`%GJa?}RBqiPTH==6Ai4-2b%Lv*t@UOGJE6WK{e5!!C{6 z?e1FSh3441RhrMOH6~Bwbl<>7=y@k=K*HX!l}v)Mcb-d?gJEN^=ioGpC!U-0!c)WP z2^e=3uzpo+0Ruxw>L)FR65qHLsWv35x~(cyu{@qN*R;9HHEq#eRdH9>MmvJw)EiA| zXA>Y<%(r{F%>18pdR^EpzSg;oQ_GCEcAP}7UIsAx>d`uNL9m-*vRK`v`O&W$&k7h5 z(X6WLomuht0KS_$vVMo0u~$3~!G^FRri}~Jbi{{@wIGz3w0a?Oa5Oy7)a?VKVwLKj z8GScAfXcRfS9tMCJ@$>&kNFoCEE`Vy)AH5PRpv8B={*73oDP@!2U%)PBjP%9+Yqxy zH?w9OcYh9Ltt+QTX^Dk{m1+1%*%$(il^hcI?<#d>YKS|JG6#eZ1E2So{*JLNI_THb zMg>2VH1z7Ajr@+vC%YvUw_Yz%{3+d_PA7qH1R<^!`usHi(VC#7u=SUvJFWPtQUacP zV)ROrMARh(7^JhsW*3fb@*bJUQ&z=M7Q1?ak=0_V=M1eT4xv{?q3Gu~rxfS$&@u|t zUh!-4S~NM+EG9YmG1*3B0`}@qLDA8~XlW>Qfkt^mTrf!+g)zDj__26g$4wu&^t7&l z5t2$!-Rc7>%EC1Ev<17_eAOLFuL_TYbv8fm_pEyMOc!nQk85-K)@LFja~GB|tNdiBG$fz53MhP$T57Syvn?Q&YP%uuBDk=w#f(_I7MV#1r%i zPg40B?%5NN^5*4rkCB@>bn$TsWNg%CIhaVv-q@Qx{`I}z!dxRN$ilhLMU1$FjIh1z z;5z7N=f`CrIZs4sHs-iF4Y?s36f{Vd7-Tm&C)e;@@R)bNfvj8gaj)e5%XWW+x$?snB_xIC3;1_kNMc$M`9GvXI*!94viv6 ztgH6-UhSP`RWF*=Ir#RW|EadC5~S{K9SZO{>#^P2ofbmN<5oM872W)*pz4p6D^9mA zOH=-w5$#^~74555t&1kWN2)(6X39Ps-7rvH?|6U`V!4!&K6;L#(O>_9Jr<}cI4P6Z zz>cI4zo7lnlt20luiRDpvO@357Qt?{Uz+o$TsEvf8iLR7-@>p;(U@N#WE`|g8kmFJ zfkwuord7b3+H`9E6x;svm4imZ;ug%%CnxOQOP|M02}5556GJCQ2Gd6+T2d@D4o~F4 z6OWk-@CkBdlV29BAGP8#3Q$ScqM~uX>dwVz_FNrP5?rPwBgQGZY~w6P^_`c@BgWNH zw{BLdc5Th`r*d)SyE@*zbO-hha~u5Tm=XHnh-6FzpN2{$H8H>4haatv*wknKY zCn0%052~GiuiW^}$m{WZHUT8Kq;P~iWkB@|yZiQRTELUz`RP>_5o_>gTHRN#Zh%$f zLNlV3qjHc-A}J}5iYfH?+YH6tvFn6ow&7A>6*mu6x7jTQJ8+SEn`q&<#SIUm7^N1% zk-BOi3n2-&9Tc7^%PWr3s9}u=``h({69NJ#{M+d*1gJ>2uYA$b3byX>_~fBfcU_fkN9UP4j=yUi;bw1%i&t*!3tX zt>pFXd2t_fd_^{fjBRImL{`OzR2^?gUFjwwbg+DJJ~wF3T*O&2O*-eW*(OaB>pDRAQ^Q-Y>+%~uJ_+6arYGb9i!r;EV#!~46*G~oYs!O_ z$TjhN#L&rqWd9Lp49akV`o;K*MspS`=REzBk z7Z%!N;`13z6ytwG0uIgxdlwcI9}m-D|CX8`Y`sbD4b6E=9Lt|M=(;JeS zInBCBpd7M~+15dh=E#;b_i$Q6RQc^te0H9+$~!7@{q3_!Gn*0dKuyO9{hPG{)|<8G zZ@Noph70&r(`d!}S~+#AQxYu9N2vK;8i3!P*o?9lBv?DMSj)E>e#*xuk2vUBEUXc% zw2=%EfrouAOb^C$0~YI=**u!OzpWjtQ>2G6(dg_3XKirGNxje2$6q_=jBtS*{aI-i zwt9@Nmm_N=YR)w|v@E{<_r!0G;D`L4g8e?3bnU%Kd0Gn9x*%}eb%?X8eoY|XX9Y>7$y}z^0nsUlC*qaoS0Zr=Gh|qAMJ)rnSQgFaqu%0y?mlb zwDSTXW;_o}Ju2(GYrl$46wk9?>-#{IIko@D}(V4&F|OYQNPIvau41c^TQfB(_2c z4=%zi^LVn3KO&3riNc$vW==d`$#;L-?Mu{B;4y}~(u?&ZH8V*m`=_dLZF8S{Ryi!G zX1uQ?L^PvAOp@UAsK&|~G4gz~(BApbk`Qm!6g=PP)&Jg1{7{0S{xwi{5;T|nbOS`W z0f#P_pX_lZT5DS|!E!1FY8On;`_`rLy_P*m79FA)(Eq)l6c&7d|W z=Qx>ArQbOOODkK z2KX>ufMU|>*G)9FTSc3t5wG$|qiS9Iv%c1)>n0;>>wgOfA8B5(cKv%4V?AXS1aZOw zZE(UrT>s|Y0EQABU7KJjY0@8@t=md7;RkQ*W#IKQghlpFR<2LAmQ; ztL6gmCM9Ae)iGg`_3Fg4mkfL5MtY(3JVWdfp@8b;wQWKB(K)1Mj5lQ4N(wLdOe=F5 z;v){d{A-rk&IU>PDc*UdbIuiQEsrgic&Kpmx-dVlUk}w~quW|`Sr3Bq6$D1Sw)l+# zoy($dah7t54Z$<>ZVr|DMHA1`d*mi^T9s7ixjk(Wsj|3`T+)FH4tA@H?y%LBw9``GUR2Q z?@A!Wy@$|;>-#4J@~1CN4PVdOkB})_KM_kzw_o}34TrpoSMeR%Rz7x+T6Moz7p2n0 zF=)C!M%%Mn0+qjeFH(U%+fe?{%Diq{m|`g3zazT+ri3}9q3i+2bqUQEsl0YB>B+c` zGLK!$UNs4^^JTt}T>C4MYy1paJdCi4paQ$g!pz0==9_O1M0e0LZQ zHrlgDi6R=w=63I_7P)tUx=Kmm6T9)Px^VN@UH9^SgutsWN@^nmn*qFgg*bzY`;%tq zA`=Djq>y;xMmy6)v+bXqwajvO`m}@dQl@XU{xjIe>PMAI!r~hIF8U5Z_qAl*@1QFe zNYdMyYd(b`1O}Vb{FblEZmwXWnrXv3<%&oBcQXBUaE~@Fo&>?BE?*w*gAY#Y_JQ$K z{7JLM`q4y*ZpOoKYtH+Mr%kV@2X_zVHk_g@F_Y`Jco@C6N7qgX#&=&-AM8i*M>as7 z83$f*o8QLQFAVp@H=)GoQgWd3S)5vq{4y+xaHoCvHw1As@B#T+)mXBZUbKhdj@gL^ z<6Hj7jhy_OOpRb>zL&w=y^|GWiHT!2!9$y`952i#0I%{Z`22+y}$58H;k!F7*j^iRCSRQvhk8HZMzwOML7orrv6%(thqpNTCYMEXfmo zg10+d!5iF62bBY9?5NdMwS2-5@Rw;4`KTeCm6{M|y%ajG#@fI?trmcFGyXwIy~Vew z9D(STi+)L27PeZ>jZU2EsbkfGcRjy-HIsI0-SQrNaD(LSy<~yGMbU5LD+dVrpq--1 z;x4(u*$O|em@Hm2Z6lwPaAbrH71Jkcfyjf$Vh-TXi}xJ`lKSq-Oy~b7Qo|?NDvuu8 z94k>5w&aLf%q8{dDJyS)X5agL`q}$ehx@K)Wz+QK_fhegroVycDpV4Dgt;JCtHoI~ zCjAewm(rA<@7uMXtTSA3Uw%_P^*2M3gSbwcL*0h~)7+{LUxR<(-B!<+gS(sjKWMa5 zZ1?Uni@q614@9s>=9Je;V`V0>B8i7zeV>W9d?2=R_QVfwZ*-4FAv%1{&nUD4>sqER zL1pkv=)I#jaG+2&BK-P~qdM<|gw{A5 zv%@084IuOjD)*K+LAr_hT;S^nKTlv9I$9f*_f;aV_0ynBtR5mtn>Dlr{R$+7!3;_xedsebj5OP})O3go5eoe1xXde>SL;Y92E z4fN00a>%9{7rJ}vcK}bdZLMvQ5~kF|Rg@Zb|A4G9!^fY@0^zq8#Em7x?JtVNhdT~e zp?)uyu*$ae>aqCRK?b;G>zT9nqzL|7R4{KFVlHX{Y~Lj<01N_9y>}OP4yohd`D6O}dz7v>6kOUM&N5>=W#Pkp+|>_(aoL z&rR9N+{M%O0maAEv!+%NRC%&@E4LXl|y)FOM&u zeCc=TvkGsuI6>$?haOl7KQ;VQIB|K5S{uY+% zFId=XMev@ZaaQvSEOYT{{oi$}GL+5y zN$z%Hw9>ikt#=IwWYDZG2=&Q+>)R7OOp-o%+x$4zJB?>>)fl+@IuIWW@%Q-Ef#t(0 zKUGT(m)_+dBHnZwXS2%`uTO5<9R3QSZ%u=ET5RhjW_R{1(h$$$FL%dd^gNCB%;q)V zsXh_$9RL78j=$dp)Sr*G(vblGEUW+kHQ)}w+sDq;$JNd|K-Akei~w-^KOf+a1l$~S zvz6p~>ExQR#Mp`GTLw(YFjpq9i->$`c}p2aN0&h^KyO(5;iXZfZue-BrnKB+$G4hl zg>U0^;x%7=oo>-*kHG5Wz<~m zP4P#Gd3q`$Jvtjdm5X1l#tv+~8DOZHtKZ-LVrNvtUW8i*DM$S=m`lP+38b}21I?L_ z)EdE|+J61qB-iNGMhT_AP`OfyiMJc@D{}rNH8B61thz3FP!bLlL>EaOIdM5yN1i*_ z5N%T&y>B_yufO}mm#&-Q#I{)!z%=N?)I++&O={$y_Qam`;s{=*j-c+d@f73r*`Fg% z?E|5+$RQ3Yq>&`o6bsvMDcUmazK1*i{Gq%jHS*C@;Ur21O{GM(uF=+)Bf1~YSEu>R zlT_zoOBL48)RF!ccH7-#ojKE6;X$v}HiCC@dE1oL-mCzPZLN>3HVA!r8pn%0{*^rj zOP`iL4vE9MABM7A0uRLiX1%E!Jb_m)(80%VH*Ouk;7ajauqJ(#Q!)$aHb&J~q7kui zCC|MbRCYygyuz2v35|`WQ{Fyefwjf8LneVJKb&a?Tb&L4@I!txFcr_ZOZq_9DCS;NumDFB?C)pL63W*7wr4d^K*+Uhb zxO=FejK~iW`!yW!#8FuIf=^>*Sa}(jz}D4==4-+W9ko8~2<)f|&BtjQxRiz2at-0N zPBd}U;-(XKtMMLbPzMb<`qGcsYN>5{wXCj&?@{l3c^Y!uc1O9%yWE&M5>}E`j=(3r zJ;b&VZgBPr@JE%{Dea+-vxtW?Xo`ab5bp&|#GX`I9ZL;d?c@5tH2-$cS!5y*`I$b# zc0TRon`j6LE{eK1Auaf+4|<*>a%IzM$nrW(!>3HPEWAX_yhxkR;%^H|*3R8Rjzs{a zaA6~hBkVb1b_2iPpk7dlow7s4{wW8`o5>p=wnq7TbIPhw#!Qibii>uIdVzV}wnq_g zCr%v_Tq8H@xyLfMEjOG3DA||=40_Yq^!`F&OWB7zCaUnFW2~nbBpMr%qp%kC6dXbl z%w7d9G-f;j-G`(U0VleydI%L3H+-;C4TVx$=e1N~9Y!6_(M4REHw)&MjM)&wH+vW6|4mDRky)CrU8m#E>0;t&NCImx?TvP2c!#-QXf#4-=pI9H2 zCehMcI5Gw8T*8(j?yaUCu|!7{TI@B>z~c4{bRAaYDCem$j|pLTpO^I+nC>lLh1Hevivf(2HE!;4dA;j*r=ih_T0I0@tfnQj! zSqb!OomyYzW^@@3_i(ZgQiv?7*GKLV;#v#&*ZyRxFu}VrY@h=RQTA1}`<;Z|KX+L` zRe1IK@TRvX+YY@yhp_%DQoyasLlc4yxu5D25Z)pBFQW1+wQgHz0suOC06cvDcZ(so zdHz56>gD3_zajSjm-ec%__9#|04%Ko0JQ%V2E-5);lJ~Lq@8?%|AWu}zwrMH=KqzB cA?SwuU*Z4LE(z()0Yvy)D}H}#@8;G20y4^w8vpJ$(V(o_%-=nz;CcJ}&a_GbFFriOM-jCMc| z$j`U`&HXq2`|iJy^UIR`r+q7zcqkm}57FXyGS+0#I1~9FSl_V{;fyU(Wk>K5l54p# z`URzUu*>2_$sDpNoG`zbhMROw`>{_;z=%oK~Lu_)UYerV=e0wmhdH6=T^5aZ_SF zVOsOlSHBmU0Ogfr6eN$+FOPfYss+P*lt}I#FWWLIH2mQO(YP;8Kmk2;rxsQfqZTz9 zNr2QRzjuVnM>Cu(Y%l1)VM^Y>&N2U*yO^Z4AIrUWe?9i}?4gR`Yw*rbX`#}NV~>S5 z)zckbe*Si?f;cPmQT@@y*5|Z8{CbOyRJv?Vf(!@X7P57iu;xH%#pFY^uFbfbyI#y) z#(_$dy~k6K%qoIWCAv%GrNB^D1n9)A8Jn%$i-TIB;oG+ z2m`Qu*Z4T$C-?U|hyd=f^8Pi8+?UNZ7v0wke}V^x{eC6u`mL25>=lbrzj;nS($+q5 zQYwKL-06AV-4zYlE@?S$YtESr&iO)PjNQA!F?s<@z-l;Q;^s@^>no)ePtBAAAt+fJ zdFP4v3^(sPG|6gs8(-a4!VQS{xfHM#0|(&s1lL_=T#5WxUeM!5yw`i(qdf2TFB2m` z4KA(QnJ95r$JsSw`n#oEqZp*srx9hVol$FW-8s<93DrMmrAP&0?WLxDP*43v5KUa> zRLLVFIxS}`*~EwPz56E>zl9(IVl6L0`7cu34H26l2U_oL^?i_Q8+hWFQ|V>aBjYr?R4GIB<$1MGG-J z@6EMhHGRf8z2+d_mN8rDmZm9DKFnOD&}k1$f0a&PzcozSJIcVGKbZ+t#*ig|^1;$) zq@OOWg##%!=F-%NOpE@n2Rw7ggz4;7?%Oj-B|@`#%*fBko(j`u%)KK!Rr3>6oF>v>FFB4R;Lsp_IofryZuizIG`XSg1?qjnD#QiJ=oP|o<6nfz;uy#p@6(=|3?A zcU}>Rb&FaPUog4j1I7&{xaOJ5T`LMo3Y78kLgKkl5C1;ve3A3bz(p~{EQNrGvAd_p zg)J7q3OVGuC^tYFD|Qz2iwxQo`%khsnSQIRT2Yl#0_Z1KcXvXGNN%~R3ezA=Sa)_o zy)V=Wj*?Wk*KFU6e(U=T2UTf`!T~W0+4l9-Oak3ImV3tj^t}QzS*;^lOCT|z!k5wY z`5_qY_W15!^|kznx~eR*$`tf-ZwXxq-JBum3-c)zEb{*rdJ1TZkvkp6GPGK z^QZwyO30~t72VuatY86x=#{uf)=Arv73{{QGuzc5 zVK>?fr&oBE>T*jcqmHp(uKBr95!1M7`MIYtt+p8hZTqon*6PQ~K!#)FJ<6M?gJ!PU zwiy4xE%^{VmmRQk-|qCIn`u?`Yv*mW{}_?F9b7pUB{$kB!uI-b9xl;$9n#*HgN@Q~ zSVULG>=xZXUgNKFPH!cr0IPn2Ds{rPxn(l=ll? zOyt47qV7&89k^#Sx-6~3?M>xEoZM;H+YD$PFG;dFN)O9y>4=XD*@__`o)P}p_@YjJ z0_-vKdaQSvrZkk>vvnFWRq0?6#)!}plW$mO1Hu2usi08$l6n1xx$DoT~ zFg9x3wooT6q39-?OdUJi1g$TWhGWmb=Dph!(pOO#ot!k zt&(lZ_Skqcy4>gcZ=tXRf%;NYb%q2q~odW zG?NkY2toQ_n#o1M)&QI`C-kYm?u4j=MzYr2fP zy(tCid;-nir|}(I6%Yyyg1h-VV5CrWt2z9h6NCI>Gp@Ti7%q-b?oM%+Fb$un^ki`Z z;%s%r1V@&JU}iypKM6yaxLVW5r&9T@Nt-}zF$pA`b=n^GR%rtY>kC&f|I_@ zPNV%aK##jx&Y4m~I0nJC;l*WSr3s{UoLpShz$bn5XQ}p#MdiynxJzVY7P$zSa7h}Z zM6hYndIe$=!MS1qFWW|8uIp|Oe!f!v!Ft52+Wy@aFtrdD2~?`D8gua_nFzvWR9W(& zL||6fzdLvw47C1QG|TJg@mrv=&SCZ#nR~Iqy~j8nmS7-Q63d$PcYgwxR}cmfj;~Mo z8{TMeQ8y;;-vzM$_tR`*j|9|6H4k+}V|tpJ!aUyZDFF4iD9MRfbmmvZ*Y-7B9O>6s z`45*Yf2FyF`VOA>ILPMeEQgEr;!6qFtw{f-=`Ala9Jb%}R!`aIf}H$Iz}3q^xj?I} z8j2zAt=gm$ZzS%t+&Xj1V@JxF$+=`3LW^4Kw{BbVnDkRKUm;3X1kFa?#ivOt#9w;w zL^Hi_Tg7%Zz^QcqNxNt+#E;|iv-^uSiK>~J)oDbO;Ro-QILtR)7={KUS68 z%!oFJ(d*LHwRh**Z~rQp23dDTzIN|4pdrwl$B#dC;k(#J{rUavmOyKmk&A0yZA%e5x^9AgAkW!@wp zH?%{mN6j~OyCb;Z>ehVMGkw4#8jamPoe89^a6j`gJHTiW=O*eYKF)HHh&W1Hr1{%* z-8nDD5AXX_JzuFXl0ZP(*8zu*Aoe9V)8Zg^aOnfb1e=JHP;)F&Lw@a|XLbw^*+g5L znsh2$UCE9j^vS52r1xyY1TtQkOs>tcSQznM+|+fSJYEED(%P@+&TyU;-qAn5cg8UX zrtBsHv|iREnMtTjJ%{gM)#5oF7tXhps9I}OTpas5Gjmm*$$tgIb#%%7xJ!uJf3CuT z{sJ@ef_AAclB0wo-BCw!r!e!!BNz8>@n9=Ri*a7tDQqV|H(crU*|6Y}_%Lsvg#XQi zg=E#@IP3R&B`@*Dmur1RIqsHk2w*4L2J=D6?%{a!_m$gpe_b&^VCLgH#U$=R<(0<~ zoI`%T0aU+s{Q-j67xDC-TlGEbkQ_mx8)_9Lb^NBQ_NzHVBlo|_VPP$yyr9jknuOU0+>*YHEc{fm{N zvF2)&owg5aYEiG{T%_=f_N0B*+i#kP-CI&a@v{N%n}4aERnvf5BE2tNI(`Nmt4{c*;p6f4GP&}xaYo>Z?dUUEH9`iaKn-o#AS{u36e zAAx49!|#2_;0sMhcvY?_e+7jHL82Iv$ft~S=S&`7{flY}9PA4{OR6~}P$Ll?*i2jZ z@{(pw!8qxd8x1U=*Uq+T&A@M)7GXT z3hn`xp-YoQInQ``^P~17l}6?%h)V_m_s zuJR#oo9kqa5%-SW(pj{}@|d@+5NQ&QX8v1^?RCa~$jo+yIV{JOybT@cV8t za>(1U3NL{RRj_vAyDc{0D>NAJEF84YpA>_wz+EFeAht^a7-?(h=>H&r&0I=KJ_Gt; zy+29=9}Iy_vE#o zU+O2#75#pEet&y`p1K4B z8PbrtabCK1?b}IOyCb6pX;vLpSHn=s+C znf#x>Z8G7Amj}$NK|bY6EOzam$;%(GXKQwF$=)eX-g|Mc&O(C&SMD&idxl_-DRH*) z89O&-GF(s(I{~Ld!;a}9fx@se)RbTp??HD|V8+sALmEZyhu(%}n=}&0h}O^~;NAWG zM*4vvTMi=5do2hO>eb^fmtJr7dS2uAPGZmnmBAdgXFAMO$WXJxgmFJhXejWp%GFOPcw1Ns_pK-ad#Z|4pJ7bF57V0UW)5q3e{jJF{gk zuqU@B9bhk$9tL+31h#llgZ@-KU5!tjrH)p}Q13EgHDq>GJyd~))Sw${s;F}lLha@@ ziSZHy;ht941U+@6dO0r!q2jLB<9|&{2iiJL!^(#|pN~5D3;XUusV2}>eMn5Xe3gsE5d+raFf|tod+%jes%S{{|Fxnb_wN~`_!pZ78Ofp*XM0iK z+bFK)vgZVq&DH&CVkX~bHkZZj^mmKus%6D=UV!3mPse_c20f!O=1^Qnpo*&mOGP2@ zUs{1h04Do3(-mTO(jW}+URl=1CPsY6-;Eu#LmYwA;=G&3Txz1Fj#pm5%(_Y`qBV=Y zz|q5RGCNtlED~E+^8C~B1of>oXN1O%(jUGAPW9HuVUUa%{Bnsm>aG9!KCW~!H&Ce7 zIh=a>g+ES&n%%uaSW$et7S+0g+7iCmzb-e21`7?RQ6ZWuZ>R9Obs@ay!p_Y`gbJ{` zcd#tAG^G#2eC!j6W~W^E7KNQlbfxeOjJotdh(c+dVxl$mf3sXW@thYZY};ruyWxKD z?+U$X{Wuro%Y2Du>r3*i`|wxA`D=rsv$5R|<%kP@1`h%8Xoy#Hqux`DYq+hEY%FfD z4v#9SwvFl}C1lWHjpJVO(0+Gkz{Y9P8g^$+@!_gB2Euuhd9_o|`UN$Y_+qV#^q>Fq zEQmPDVhpMCR=rg5`|6wP9p;PU?b*gQ(>#O+QS-2VP)yn2wD}lJxV5*WC zEwsD+%if^Vaaat!%$8FdNWG(C;@sefeSbtNu#>aw*T9WSEv|+I9A1}RzE1(*zy<*} zI4K`N*D*DyVm=M4?jmGCfM}$jdnGsMpj0&q+4PS3R_fTsUA>=YLRnjkQE!S9IdyKS zaCX;W#IE^q&czl%N=%TycrU3Y6H4yXzN+GsY7iU4;s{;o`J&S4-V|DFcm4qnK-`-u zy-`;Y0StixRp1$A0Q92UA<1gAK-3errKSdg*W#?nG}c*)2$I(UMy*EoOn2#r9W9`a zH?1n{kA(qVz9$!qgEp^ks4uJoac;UEDRUV7=CsSCXfD-4Py6=dNU#t-Kl(=z`VD>4 zJ~{F)kw6*MF+%5FwH?M^>+>~nK+&*cc@8AXz-Q^3dFMew&b z+N>V^u-v;eu0Q-{y00RjD)(ieFH6OT>JDs1B0ZeHp?W2$ zFaPaz+V41Rij{QXH*e}!A%e^O=vLjwv2;P4Izx7^3IRRgcg}%^aiLt+J%PWX;Yz5J zFbdI04!EOgOSEN1s<~Tv|3;vieH(qaWdT(X$|L8lN(W9ny!{&xVLx)dvS5+wQvH!q z;kXg%>mZ!5)(QV+bgNE|B*e7HpgZ>*0}%jCDO8n?Dt?}khQF-M$3~($l)P5}T?Te74aF=s^l?xZqP{zB^q#|3u-U>&V zfDaGQhgna~Y|sbKgJy_JEc*G$zjda*vHOsCOl8vo>z; zHcRqUp*7Al^PArP<4E;ZDsc8;pMOe)N5VL6oeJ^K&u_V`@%nCsk*bcUQo{GAX`9w_ z_*bY)`l3N7{FY+V`=$lkH+Q!*#Z1rz&U;H7Rbt&W=t|28!lHL`pdL`{oPl~Pcyk__ zDwseaGQ^meJHCCOQXwO-*cLxg);*V~Xw#=+W(h`#qlsHf<@dW1lO^3D=5s;ynCa2w zu+R57;%S_|so5mrnB^DtL@#R}SQ$KIQ_Y`t`F%_Nq;q6vu*DvB0GagDvu7R7e>b$t zK+QeHP233rts9LK2YsQ{xOwsM8DS>FG#a9}5izeKwLd?pG_!K(UZimPk4HQRyeiZm zJ?*Cvq_6=4`4uOKBPbDy_?@DdNU`kcXTD8p+N_FA3kV%UjKgW)_yzG z4q{Mbb7yM2rxS61&uaLN8}gWBs0$Vf`T3Uu;c{AFo^2p7J)PcI>^3B6K>xs|wrA$4 z*^WarJ8mhbSnw(low#U?xmq~LI)uWzp%e{VYy60i0_n+;SZGypM0(#lpWzb=7;3uq z^s+|yOGnLmDFewrD&M+$`VZ0XCggS@3UGy>)~#+K2C49?^aya6%>+ojZpeiJf=va% zYx2;Z!FF#hXQnCoHAr{6KGwtxmVPgxfh(X(>^3hI_}w9o<#aYnA=_Ly;~JgSwzhrP zldP)8<}0BiwVHobQESXh3hO(E#9|w@8bCi!9{>QyMdU`Hz!@F+O3NsPyzd!#L`aVKbUP@zk=?|A)Xh4EHlw7|$WVL1r*(vmCD^KQzq-=dQcJh9{Z zB$vwmo45L(fK$c{N!dh-A2so&bhM?c5`QRo#fp#8uYNn(GH{;y8^+O|49K*>^2+=& z81;c@LPF^s`6{8PZlTF_bHfqKBP<-3Y^^gt)CercuWcv)&s-n;sP_;QOf7Yho*{f0A@!YX)2<55Zzmi0JRus zp+vhZBj~jmpTdni%fQA6nYWw#K-o-4ztT+vAN+nhB$5-?$_@WNQs0*_qv8R`n z!R#3N^ppxdGCT2pkvWgr(UQI)Il+f4JC=N!$MJLAqqr`{xJfJkV)B+-(<2JANMY0b z4`(tcU;4al+qX&o)=N%0Aq<;Ge(U%_iWC&RaaKDa5-Nk19yNqvDV#s`-E~Lwogd2^ zL7wf-K<)3PjDfuTEnD}Z3Njd)o#9C~@7D;5gMt=OZ&QH_Ztgtr7%aF93y%Ek>M(VP z*13n^=Kj>*47N6$&*A2$XkX^xeYunZ*w?`#8}mI?Hc*@{%ewD_azXKVXr;u$8YvbD zFN3?H|9 z*fy-;(AFD`hG31UpKzf?b=SKE1BE`X$mgM--{6bRnfW_2l-0e@wQV8Zm24y1k2P$s z7HDwe{yl;_$49=Pek^1XW`e!DUY-B>a}F?%yf9_aY${(6+46a#HITOu zZ>-0yH3^Cq?FrjjW%y?7O%K@|efuh*7$}wpB`8&Btm6L8wZFkJOfwNvc2ZJQS%*u~ z{D>3K-nZ)Q5cg=By_e;%h_~BG^DKXkeMV%rc>)$mZ&5gdX52T}bp6=s?Ap3+6IJJd zv}%Vwt!JP;+Vax0fB$Hz)yJ7H=2Y> zEq7^kM8%pP4dw?cc|g+aYcCwtj0STIv6ZEkLQfv|M2DUM5H4jky}6PDnZ{1ckoM%c z@yuK1kw7$MU)y<|QBXEtFF!ukH4G*tQKk6lm=*z^X5^&1UQ<5?Av1FSmNS;iB{TN-4^V z3ZG4h$yv(elO7|e=8S?O)g7lSqw-fQP4b+f1cfF#<7e^fHiXA{_%uCISA%kq09tRf@UzY!(X6Xx{UtDBzF(Gu>FXc|apFr-f{l=TJEZN@r*!s}S>o zQAsww@O*Voa2Brc!A*-ttvmy9yGFC5^Zu=nu^lHh9x2fW5m~$rqT@p>)M|6u@+9xG zW^RHzvX-?uC-VIhoFn6A$Mrw*@S_oZ33>bDCttX%Ou0SL!g10aE2RqcD!RkbZu`y; zO&Y_)>ocaJmW*wY)TA|zKeXH@BXlYeL`wWCJBw@AX0*OO2IqDzsfuz$#e^HX53BVd zS2DaEoyqi`+^Ul}W8|aJg|V;Fa-}D;w49n_3O+r;d{BzP^Q^8MAA_#Oxfu6ro(RzS ztSt{Xa@)oc*=G!)4h0lTiy954OY;7vxv$i=X5=#kGDQb~fu4t;)usbWonYMtdn$da z_`sAN!7UhG2eG?EpP^Kdef7NphEYFQ{E zJFdbuuk-L&8{$sFVr47n;<30D*(^kn@;0}Qbq&tfAqHc;d>O(1y))>>XLC~nC4R<8 zuLukxp34%?jNn7a*2`{}xf~r{&EKIsy}Gc%jy0+?;pLdZg2!|j&9@229ZMgbV;8@- zODSH6j)}WXClIqR-*vjuYmxgcl!i2K)Q!3~Z7nIx2@sGFO>)wy6SjE-58@^PScEPn z`8TcgM1Ctf{}S>O;|ABOR7rma+wJl!K=$a4kZs1x$t2dPpSAN*@7;_^qr4*+y zRuzgiZz#KbEv@Twny^yc<=Q#Th=1#+Ib}cY#;GPA?O4?NLIB?lWdS6e|G7?rk0;s+ zmfPUC*Yo8r3~y$0=lBTo5W+6E=(6pHwYdBB0$&ClIg4=H++ar!6QUSVn^5~Ou>h|2x2IRX(ZGrjWKOHD{Ddu&ijSzE`#knY}=kGit@0~ z6v_KPlD57`56Y<9N~Jh9?~D+@OXhrbbL8)z{L}o0Dk6RR!JoJ0%+q{8O7Bs2xi#JZ zwU`?BOnB}cxzKsP>0zQxxr0H`r;@@;%B#5 z5F|mX^A1-(;Eh-zsAVwXX;hX`=|FkJ?|7|hgNZLiv{G6wb-rY$Zee%y8v4^2jeW7! zf+>CFFVs&(cGp{a2$Szwk8}QVUORmlA*fmA-k)c?;#z?plm=sX3+~QoIXN<@KEqy{ zo44@+?VP9w`h z{ua0BiIp|r5svkxq(~nX4mj{xG2cY2{X~^M%Dq?4VkY|@d4k9cv|2)XG(my*`w{V!vr?zuD zC^2Ga8bH_m)i(2~ABJnM*=S zpzjbB9&b6dqlqM190k&yLl#i%ZO}SD{Sm9}nG^+H){+w56#Av94u{)UIr32Z1!pnO zEwq!$_|bB!($s#ZB$IYFS;&+VwPSrTknt@J-huYyrqz&l_@nM`nQ@Hi=2vVu5-OC$ z7yOInDr)3KF0D!vIG>QUY0hc0X&A8vbaJN!fXL<;!Fn<{a~8B!P(&2=+P zOELg-{PSgqQtQ*gwmSsGVA3Gso5i-Ib9cN=b*gyUI1lx^P0Z!;E=&vJiRtG;C4UI= zr6=uL<;j2Ua2TyI=>XdR93p+L(pJd?8$n8yy+^va7vtp*TYI!0>zJmH` z18fvOLsrKvZCsO^~i#ZT$npYbJ)4k#e5J>|AW`U(}|EvU{Ht%JLH~^ zxRhWfekF7jmH)+Ac%=6^+RW(v%cx=>$e&YA=A=MDE2##gm)5slYIIq1KU$FieOu_s!yDxbm0G?eVNAS0s_dE6OX?wB)C zi)<7mu6Syb8BDAyCvP%CK}${7@N!BTj2MRz(E#)d12zlkp3YH7m_Ju#H(6r*GZq4b z*PjbAWrTRfMVlgd#6YvaWpl?q31Z%#l8ZpI*Eb5Tqr+tjUH*$YA^;cE8K(vn4G+!#Y z)~Kb1;BQwFrDe4NbR*V0U<;XnDQMoMdI|CH*t3GaRfC(YBo{q5R~#*1taKiG&}u^s zY{ica2Tl66yepB|%j7+8r0r(A*815o-q{2s%5IW%qY(tOi^e8;#XnBWS+EQquBrrIrEh#62~h!hQWx~=7e&WRR3;>{X1u&;}W5d@DC z%j@XtsIKM6NMT~RLS$jVkGy^|9S@wmT;^g!AIteE&MlKqM|fca#iy|78`o(`f}aurjw{Kg=|uD!uQ}K5PsUC`%8gZrFp+s1W2_$%q|p|_~$EXDbNEo+ov;Kfk`}j_lxd>Roaw;JZM9MY~}q%==so(>X~!3EMVmZA@zPpMspR67IE0mJ7SdtL3%T;P)jw z;yR6sJ}uCTSZTVw0n2d2_6fI9_k&qv&FizU15W>36|}wM%lBes!ve>sUp1-Bm9Orb zjH;oKTQ*Z37&D^^tv%x^H_Tz|mGR{Q`G%z8&L*<+x@%r2USwi_2kE>_rG&SODn{X+ zkC#*A%rr)AV1tjBp<_ErngjjQ^-qK(IzGd~@550j>WsA2Yp=w>YaGLZGqG9dfd-m6 z*V;RXh01UwkxZ9KNzWi~yuAMbfw=FhlmfpG6Rm{b;<9Hw^YL>Wxf^6TIIzo;_{R#TPG2dPcFFfj;)4+SqwWn0CK zQLO(qOCb_A3-1m2J9a51hE}hL>d+)f&?Vz=yzj3}wGTjjyVt6vht3~Hn~w#tl%Fcp%}!-i+KhV!bm&B_^G~A90)o zZIC~5yp%-kKzxQqy|voUO@MHqw*uBANE8a_a~1gGu?=N{vAWG=$qr-3st_>;&enn3 zCuW~%unSv?sI9&ECS>VFmwAEH$DFAQk2|ck%gn-UZExAG6)=-rV`ht`wvgk zhn+ccd_zz*dza5>2x$IUD1NDpzLcK_q>wxzBOoW z0I!1zvMV!dD|8WA`Ao(Wc(~Z}vg}4rUSW$ara0yclm~I5WQUUu6AMoJ7se6_fd2T_ z<|51GS(9wY>O*1aql(-3oQJyb-zG9UIrhivSD&j{A}KR%cwNOY=yhr%Z7au}ZaOxLp5gx&)?n~E zO`!7dr~zh9X<1_p5~ke=Gy2yQrIfxM))!!W*`oFt7A5vkqa4x=Vw?7>i?uzz{N-1#=xb?^+(<_O4D0-9v#z zD$_l5%K02KYk>wQT|ET^+a_}zII)7fpVIndm1*oaVUjMKdWrOhF^J)kwVQGH2_pAw zJ;_y2J-Fqv-J5ze9dKWjku0N||Cyk-d;`1S&DV<+5EN;oVb`4I9pKXl}%A655G~&?paA$iE;i?|HLRdMJLy zD0e?^BM~lpUP!`S-FHw~s+-(xwnUyC)|tgeSv7kac3zGQ2cOlP`K1zU!@uc!j8OhxLj^! zCGN~jigxE2{g;J|xMGx@&=5o)9$=~TG(%-aw+R4Uh3NM&<=T6ear-+P`sGy?qOY_y zUX(8RSwF=x|4k{$)YP>!qv75Cb(pm@-We+m`zi9Lf&f@x_$sK@^$PkV6_v_8yW@P9 zLILqp{9e0A?&Df&2T+yRLTOw*ORIdhF2>J+%4SnKq-yIIfEU}uox7Lo);^j~ z;CkFe=up3@yIQyo$Spa#d@)#RRFZ8-4sv{=zlrw#655&ED%);94dZj>Ek-;1UyL(F zVy%zs<@aiAgLPZhx3*QPyhqO1n9i~yoTi;-A^M@<)A5s9z6Gs4u3u*%lSIVIQ+OTO z{MJXeh&l4B~4I=}Q;w^a?xjN^`9Gwgv>IcOzK%=u~^+lhMaD^iCNf)W{}&VFTE6 z;QAgebr;O62i&Qd1TAxkNY}B%(n_vO0p7Z8e>dNv;Xb!9<6o{=P7b&SWv@Gk2N6%{ z-=e6D^!HBOkceDwE#lpj^-ZKC&6;pie9&d=Y`sCc?El*IxxoK!!@P5Iot+aG>K|5G z2N;O8vRSqqH43dt07@7@_Ug{E z0PAstQ!i@-QDpFlo!|9+hY^SvZG1P+CHhsQI4x6O-lkr*+FP$>%9WZiO0&Cj*&R2& z5b%t${MrRcan~N(#s*um#t+lmRQ`evk6pLh~Zo&&Ab0s@Vh&Ob>AkmyB)Cd!(YwNr_s<+DCI?UTm79x9AnO zW9*%8+gFkT0f5v~fn)%h!KX6>Wj-cG*rE~hRI)siOQQM?TCb>=Qu|q|lFxUYNZ6S7 z1upeQ*Xqpz@f!xwoS1~5<`d{RMmQDYi~~CM&u!JU0+~;*w(cr^o@)9Wy(O%{RR%xk zb=3RCfkiac4lqX8`oaoh%HM7UgSK zy*}vJ74nlt)B|j>?*lQEopfh^@Oytvo)9`=+9&8`ZR2{&^+HC!$42IsJk*0S{&CcU z$0_E#zZ`l<&Qz^6<2vlU>3#{}&RR6xx2zhrkcB=ILxDGJ|rAK`&+>qT&PeWIVCpy>Y=hWXzH@9aNV+;#JDMtE_*q(Y~ z%j&0jw$ZeX+0dFJg~7u~T61%a?sM7i&KnmJ{u2$9&pV(k=qnMnsArZ;U2&;yJE5vg z4sy7d_NL9aHbk+hBMRBDT$a6QDa#>2Bjn(ivX`eY)AuT|RL@lApJW9Teoriqx(sT_ zs%G+j#+4%muuLbiD(C^B{tE-^6iYo6G?I)i!D8eKdxXAA@3a24(AG z`)oh41ZTH!-`cZK(YS;jx@nA2NVi5-w6SHFAdNxIwa1$0RJ=EHoEMm5u?4{4t=IK! z+b{zyp`xSx7nrl>Q|*nxE-}3N-nch45Q$9x4*c61V?ygE7fQLOElhF;8AxvS%MTG&Gd=MVEbqVqon!jbQy{SD%BIU-a~%>)BuH=77yxVp6wbtwu^6IQ{n3y9ycl~ z60jH8Bp~874A{3{L3GI>Q(I^tEnyk>S^MjJ^w9Q&XMlg@&iJ7Cm5plFZpFNXG7i{5?Lx#Ih_Z{)IX>+5%{O_lQHy{805~Q&!o?U)d&#Esv9!G0e-OWo-OyBm4 zs`)se<`Vf~MZXaNQArl%IHL-aC?lu)r|&fvkuwHm3q6$*6n0Ikdt4*x#IVy+!S<<0 zzqJIe9BdPpe`C6&z_OtZII zx9hnDQ(&DZ8~K27{L#pFV!;+L6})i4iD%L8??m#KSU>XU-yv3GnR(l4-{D3|N<7wn z1=BEt?p!tUAwCbPKF7aLZkod83T%O?Hr3!U1H5XFCnzQj0IHah}Y+#5CU%&Zk`%parRVtOpzK)73U%pPL^o`kUGA32a^Ev zSGmRK8e{2~fB0&~h)w8C!(#b5i^B8imbX7gN6DRk^O>dE=LAx;?VR5l)%Fp1hQ zolQKm_2G$rY@lU(5eP36&2?3-OQc(Zf$B>!M*X|g6!$>9ssJL|O4!|B8{$&UcX&R^ z&XurOw&2YQ!aOwTHE+epE>vg&IH8t2exf)sFe8nIE%*`O$|sOierQe)2Ev##&2O3BYKHoD(Vmbqar zti)c`ZEx?18%q7K%U|*y^5vPe-tOk3AwMzIR=?|g@QaX-o@KL+^iTp`!81iaD;Wp! zX;r5Vo>c^|epr4Hc2*HFS@7V)T0ZF0f+ua4)^2tPbvYj=-oLG{N+D68>ai28=0SYDqnC{P zpSr#QII<|(HpawGCZ2dQv2D!6wllG9Ogyn|+qP|WY)ou*@H_AQ_g}qN^>0_*uCBhj z`<`>p*;s3zeazn>MhN*5#qJ%9;cVe;5E61h%{b+gM&~XYfx+`FvxRy~k6-%RhH1H0 zR%3XHV=bQ(eubi9F&94uEof2Ct@E`;)@lEQ(x$pD9nX_2g`wp&P9wjz3Vu&Z z>s3-|S^7zSJt(XskxPC#N4;*0QQXP+;)kB*;w4$m*)m6#cqN*h5K|dX84J8toZCSO zTe{FwK-0Zo5s-Pr5b=@j?>ad*bGd{3KOZ8PCvqCb6X}2CF|tk3`W*`q&!sTXno*Bv zn+MbF*3(DOH35~ZXWD}xU{QxBKHy-JMG#mO)hL}zGxL^Jp=q!fbuD3dDzkYWIDPjQ z)BPp#&q&c+dpk=o2-|4oJR(eGL+&HPPhq79@10*w!JC%z$jLquEp$pj*tr;yV*yHI z^y+`8bSmvM;hu~jbLVpTLjCBSXS4}I10c9GhN%uDuo?Uo!%>%;zC&Hw8)wtF(uDLh zCp&wbnE+8mz?Vs)fFkItz?C0{+J<;{k>`_bJ;{NU5m2*oTm|Shx-BiPZ5dGAH4{yn z_MgvTT!c?^a-4v15~nOZc)k~(Ec^#)y}O{CG5LZr8y<<)*Yz+v9^qi0-M`~Y!1v1b z5AK^O(aK=6Bi~b0W^6GnIFXebQTHO=FI|>nVw=}5s(sM$Cr20?1qR#xGK8>r3VCFf zxJ+J|Xgpv+vMZOS?HmvuEma2SXwCp?zTu7IHS0jrW+GfK>qap8mey*4t&DHnH)fH~h0+={%BiAr3spQgc~rGV>l z*aYI5$o*-qEibz6t;Cgb=x{i11n>Jtu5mpVBqrbXW6;-z0|d6*5cbx+j}lPg5}oCI zEoOnfAjoHR(thTUARH|WyS*Uu;#hbw(q83lDHpX=+-d`{#xl9Lh2e3CS6h4vit>@j z--EMLf37@%yPP+2{g8h~CP~K&5@TS9Gg!WyppJd~^ok5}tESnTtY#LK?Z#T9kjK{P zUTNww@lGbQ*4nA|ae^y6o`IUvXd2XPc9We_Sy{&;@57?C#vEuRzm*H>=M#}(I2-iP zQKq1?Wfv;c*Qa1cVlN3#1xn<%g%u0W(&>JHViFwUXPmRGLF5l(LKPpSaPYLW?$X5E zDL}2M#IE!g0fP}?I$g&|dj);=4~L;>O;-@K5&Cp}_7@&%LxaI$x)Uu}%gNg>fDn%% z)^t_jviHh2$w(SkjYG$t(~hMtGPM-lZojsuhUk94=K0J( zVd7VBjC*Fd6)-5TH)1vLG_?dQ598gDbME8;C#J|@gqgybKs$U!kE?GcRA=uf`n~cl z`KsPFeB%CZXHRYD$KuhfP#&2hQ+8xJVj2W*qw~T-ayW_W(S}2ANGXY%#vR4-ktm{u z*n+G_PBPk3=MsSCL6-WrWl*jJm^uFZb zpB8MnJlQEW8gi%@CD0OACO}JQp2zm0vY*%EOS-DH2V6Um3XSV8Z7B1iT}ybObdbl= zF-pYHo(=!KZe0!90>aLCN~u&nGtd24m{I%q!Tzf?>h1qplxn4WyR4eu@{R z&p}*)OD(RoVH%WlGVZqVg#|{7|FqRh+$Mc}>S1BB2*+H%u~4yp=mZ6z-AhlAe2;6e zmcIWkRYtVIE2<=pncZ(|ijPoiZ+D-?o>t`Em>qC2_E!vC_zyTi<|vhqHs<}**+o5n z>^{Kq6f6Z@HaF~9F)~pdwvM&KhO(m4*x9#RUI5_4yoPS)k#IbsKIE;E`Ht6Pkl{V0 z*os>rb{JmR?qL9bx%X#`*tahx2thcy3d^qx}_iJwy0AKq!0?iJ_1KyUT{JnCby0p1-=|Y8gqoO zU{?7aK@hF^>pf0Y+EMo-BZ}nw!{jRhpj6Qt& zxk#Lo1xl~p5QDjIq>77emlRC}3*in-^6{vo5wS64R>r~*<`?cXteU{~HL0rIR=i|e zrrM@t1ZMnmqatLEBabEu!OF&Sa;6w`-4<$kVsw3=!;N=!8P;k+3mDis446!kf_*ey zH}M^QfnwF@|m&R}C20INga_P(nJGx%ebA(N4Sr>TL3c-^4?M$e7mX z%G5laDHu5){4Xu>HHZ<#Wj5VBm;r=MdFj8s(|)$>)(2%J@xa$f`T|rxB0xiGqN@9& zE0_UxpeSF~Q4TR6vzSxermM8?Z`H3Q+Yf*=An>9d5aoO838|*0`Tde)HWsqL$V}9m z(hsi(;yXDGC-sG^<Qv7(H9EB8KAXf%< zR$`K`MQS*>CVsaj(t9%)m(2P5MwS7ybYbif_xDdWCW%8D$#&czC`E5phvob?$qyo0 z3%d&*7kIT&Y>W%!twisf4ET#uOM2h%PZCN1hQI|#I|WWBkoI@;gB;>_J~pk<$9a5( znzx0u9uu06Zt|nsyC3;0mTST5l7c}V85MT{uVfTXNI%sBo~L647)8kAQfZsNx{^Z8 zj+xJwokpF`F&jE^H>2^ki)&lZd^KKD{23o0$CdN%dVKb|dI)^kHPxspTGv4FdflsF z8zm5l+(E2WMYX3x`|kZdjBq4Q1jv`(J)F z+Sc!A2LyOeWrF%GukpCEv4rf}Kd~VcQKvC!SH{>7H#cMLoLtNM)uo~Z#;E^&iy*xD z8mDv&E~gH$$>)Uojk~V!)oxsG*&NkX*`+AO5f5-~V~gnd0?xA0@#K+yMb-EFBEW;F zSd#In2t?~Hz~F&J?5>zBH4uUQ+162}iyht5h2~#%C@={2oU=NsRxL6z zL!Ysa-7f@sdb%?D35_x)LEKET!%0qun{zD=CkZm#`5y$d#e7ga8z#uy2Ap~{xX>}afXaPos5B` z?6k#HN;yYLR(NvnoHgC<+Bdm%6g8Hf>mE0)Y{BbG3Jue9*3gm?u||qWW}p$3oiIG7 zV{YpAm*!I9;!PX;<LSu}QB<@VLRpVN!Lv2-(r6nrcH%GsmQac>IO)NXl13UgP1?qau|=b{o({K7o{=BN;@ z8yQullZj3)n7RpiA0V|i4}GMc#Bc>Ev-PI0==FoUdgI2M=RbMMA;Feg4_aDY@?PA> zoh@$6O_9^mCIN8jA}*{m*CDXFd$vLzi830-i(}`B7fggGZe|9Gwu&xLI`}D)WX~pj z0KS^7!&V8?;NDW0(pgp|U^Otr(3Z6V1^wIy_~N?39qXQd<`#mDTo0szm3U4MNLrkE0$F zT>c45Iy%(5E-t6I zQ|vxIYqMN_+WHNb=D>qadDXiE8E0>PkhSdS)_warAv`m&eU)|Ta96XDf0hZ=h}-ak z3pP6;3PdBCTG_WI3kL7~V^$OQECF@Z#$S}1GV7Jxb^Os@%`7y1FOmhz1F?VIm+lO* z>GPsb(c-5&}rde ziVgJ}AMUkcOuVK+fO43dPsd0D}^XuFm%KlE2Saqpumdm=0`6 z?#I3nI=-mH;k{kgQfDR_r7Xi^QJb9qOUI_x&t)w} z(KP-eo3ptO=H5DLh5`@e&k#@UbFIcCz<+F3mVJf24=3ev97!(~8mR2?HrGN0N@h)? zb!%$3MUQa>aM5Jt1bA4hF=3mUVs0KVbH z;Q?e=&g|syf7O0c?TrKwn20q>Mgo~CXMONE7Y{^|I8;KF!5$*NeLi8=$%)i0L=Gd=XX}sd=w^^k22({D&xxXK*;HiVaEWPEip>qD?lkqqGTi$=ohRe>f?_g!F8CRQ?&}aK8!A^GQU`>uyQ3#Za=%2(-oJUrV>7-8iZU8rs$ z&+55@kADwE5(6{yU1c7#ZNNOWfD=9r&ZvZ~Px+x)1|9-e;c`Ur(Rl$)8vhm}C=B$y z(%jXBZ&3s{uk_H&=qdXPCkF4%CqHfLhV9@#O^FqQVk-~A0v_gl+CCiT)+=WME{yThLn@R8AL!Y^Doi7z*_c)k4kgdK}FJ!bSpUA`Y&aYhIR znZPMq$gJ636esxKnbnkGQ5h>noWF~i!FTJ*e2y>9U|{SEn%c6s&zvtvujgm)1CeY? z($aA0Ax{?R7`lvQ(Fj-OY4e0K>|sj8puBz>tAh(4w#slh^lr->E{+ntyY-z;?4DNf zN5rJxI7bTjgLv$-*Y^GSeGM0C?QeALxXo~8|N8kWIS&8CN=$4rv@#*OcRrVk2N94p zq!qeh!+)kWY8jC!mP64n3LPiCL$h$F*l{ZraI>J9K^0iv-c7=ec*3q9ub7qA#NJ!I zX1jhO2zP(nvP;-`ymFjdE%NfPLZ$ybwcB?L@7CKWHe+!a22%ad6;oRVgIC=|aeJdBkCGpnvQj4>U01Zehu%^(i;!t}$ABeN*Q`B9YR_Mqhjv34VX!Azn6lU6c4Y z9ZBMBlkGY6|bWD{6uma$`792)tQp(0KLmY`t@cpBtqU+@D8pOvl%T;=e?TE9x zU9neYd3Z9l6dW}>pUZ-)W3`ZSPU=RGwyz`1-ofERE~T#gZT?=wv=EEMbpEgWBwSGZ z(Nsuvo3*8O+Z)i*0nU?Z@_eeJ&#*(cd?b^Mg##wjUk^*bekv-l$uCkiCS&Z^oIh1S zcdiY7kJ8+XVpVv@z)#xC809hz_23Hx_!6#YRoN?~Cqn)@YA;Cl zgzE>JH6}WuhRG1R7s^%^z~6akwwZM(F4)#lJxuoe4HX(C{bE6N^VW=u7@6dTgU^Rj zQTCMj73NfEv^2DPNY8@FxM?xDwU2N@erLZ&{n+zUxix0%!hlLkU7aOK*v7XF^`dT^ zovrPBt&lzjUyCq>-T8GfiotQ@(Q_QeF$AM2A}V2HFjF7H`0i?ht{;^g*R=tXcb51)R2?<|a-2IpUgKQEvo!qoR6})AYxwR)fyd3e) z_pgnz6I;!lQQE@q6|X*~sk-SFm7r8PY_~~^1jnH$G~ay77u*CA4p!u%0!v(lTzOiv z80Gp4R;%+fNruuylU7$jFr-EQ%f&!Ct5+b_ z<)j~&{Yf^97EEZ=gnL?Z*@vY7uC`f~Db6LBXB#2KCB>58tY9ZxQ;-LuMnECuk>dsW zh%~=@`N1+}Fn8UO)MG3tg_xQIk0l-;2HWo9#hFi&g^;(V7nl}G1#ZkSSA3^o&75$u z{G)4764bF(Jp3ehzs6zAdAXV`5}hH2O)(H=*}LB-Enz&75ef`PlFi*zR*+@=aTYIz zwW<4YPe#HKj*2*{9{o{M-z>E+fxQ7$Q8bONZ0hNvMHK-;JUhz_>*lV%?)@NPtqGv4 zf|Aiu8=z-C~&j5zi$U3zAYF9=w{0>VSw z>)tjl6ors+z1mJ=wM>yYORQ4)u}dJmiVr%^yPow&bT2|MJX5;;Xn$wAbJgX7Zi<_V z%IW|h0O27Xq)>iIA?T!OBK>^=b-b%4VZ8nTI@oJhusH74kX2H8iMRsC2SgdXLGS&o zVuH=NwCnlh5QjZwu#A3b zS2w3^;1tb;cn*3N2dCRy;~RVfW!T#lhSWY6i_riK|GAniyMv%hPn_|OLY!4tEl#s? zuP#4h9{ri754$y5%rE~tB(a!6=8nsw z#{y2-A=bQiWL9X)+VBMqpL#@~qhKCk3J;(eNk9Zj6DIs>{!s>io>7l+e&}fBRHijZ zkq_`?dfnoca!1PYgcz^WLsewSXiO`~f82r+{ZiQd@a zASFP38~uY+VF1`lG1b88~Tj-{h_I zrtUMJJzLfJ4CbC}BsQ6shAVw(Gg{X=`I+mmkvHX{5JSAAs_p2e#sk0o77h_Ul&P+9 z)&oF3FzB0A?0myd8_)5cKG~l^(*!x(OWB!QDwV0ZC=AIXb4c7zU4vw?BINk$$)gh% z6@}pYQr}|%9qiCB^*5GL^kmXTK`Om@IG;*}6R?9nTJGwzcn=mC=*pvlf6A1vRC89WjIk5m zjO~WpSQ)_PB{D&6`uBLGy%ldg!fFW2F?u2hQj1Ek`R2M`uI^p`JCJRhvn34x zZ2uT0#N#+6Vh9LIp%gJ$8!R2)BYFNFDSi+|%Gj~ZeBqY+)pNU?oPSa*u3BHbBgM#b zpcf19gK})EY^nHPc+a6>3tXDyi1Pxvoq74Q)865=9f_VPy&|DU82TR7+x{wUzhH0W z+@pLVf6Ew{zh=4E&HnKUP@gry4M`X}Plc#}zdu|P8`fjtI_L~{PWwJE_f66`Z|BS?Y@AUw#yPiFCVAUA|0{)V9>pzhe3$UG3%RJ4@AmhYAF^R8a5qHOIQ zeq3Q>&Y0wqBM${DF>J+mg)F{z&@yD-p^LD8FUi8d4~0;J3U;?%)I}%M0M*$`pGq|; zGc!N}>9wqqVTJ(By?&8h?e$q|CxIj6(Ij=b_2cI&kGv0rlp?TSx@02vbq8|_njd-ZOt!p zYkkOPERM2KE_;ZN0yGqB&EmqY;9S> zBq}Ti%AF=*q#WAp0EtZ*e<^|{k7B-0Bw;xqUiOS16qVGttEkA7WBsXLBva^9yw9orEDl_$FN>3xWvRsk3#y5v|Bgd=2rYx~1i;+#c$OFc?A=s3g5VZ1iu!RJ|FI9HDLxF&-4C&fQz-QFw@v z#2^z2)ACWft=-C${OOO$%Ma)MH8o7lpm0FW48@}CJ20Q5|20Z({apJD-@HzizCGdU z23`{${=wxcB}$|)za`{&gykR$!w8*ho4|FmIl+Z{WIoTkm+zSa@WO7TXM2U?_iDc< z_mV%3S<*>ua9{Bk1jW8C9rnJp$+Mdw&0WyVMnR;)S2O)6h0?lM?K?M7mjdidI1L7i za!?CkX_5@H3pyDOhvpupwb{pf2-^xXnM0?rWINDBGeDg@)A(u;9~z7lXYXp(BS_nw zO@(h0+tPp@$PdHP(>9;8na;lBvEEk-`M3j5Qd=!3Rrd1f7}iu#&Qon}wz^=b!EE{^ zMjnMvWvHG$h`zwNT?*L7&M?9ih4*yiy0{qn>jC+o&GL`T3cuduc)A-RVd+<%3!O9u zp$3`jI1x)4-nMI<_G3mX?)ow7&XcD#vQe%1qr5K*M9fADqN%FegW%$-*81K_2k4&E z2!4G{H*yumiZ8t-b?Db$k6~|#EJSupv%q~&wx!etE{W1Yr$el+*=9Csan zB`(4}?evsOQrG&=f$J0fJ0UZEWn1<= zEZ-r~Nxsf1H}O)7*-hJZe7DtyUywa-%k}sO<%@D-GzAs==NdI7t^s9ya=y{;jt+nUlfCzVEfXeMR(M$G~=fIW)QP0`H!4!O9WBAR*RM50fDgM zgMuc-i4*1ZaL;QP$PP(zIU9x5{(QMkXn9?F=t=UKG#g$K2B-H0KVqW;tDu()>H*u^ zl$%RFppiIQAp5l{{A$QwC-?|0nhAv(^#KNGBOQf6k zD-%B>Y#TYPW)m>uhfHUUBo9n##j0dV{{MjL340PoHwIw1s7xR|qHa)*7*dV? zac{zY6>v8i`J;EF-OL*a;b1wfg?QE(8udEByQis~NEOO48SjW(4fD>LR$fG#&Ggpc z*St9N*d4HFcmD=!#S4mHZJmaOe6Jx}4EXOr%jQtcin=?_d(Vi^MB|>V z(`X|D1!567odF*ZmNYIvzZxIV0wFqgoecJDF!NcPrQx!FIqzKWd9XRC+j=%NGxh?* zF?!NOx-Xkj!N9F_*{xS`koQT{(d_MXywx?PoFq`HDG4jqN9c)7j|sN4kK9UtgYP#% z73X}K$A|ac_RZ_GLg2G^{T-BkfS%QQC^^0#qF(9zC&9~}| zpBcqW%~g)LS(}X8A&h2GFgz1{GcQbzkxmCj>5KNCe>g}?x1k#znqJ_6gkw<_D$Q~F z=^xbsCZ(UDK0eaMBlt8|4rcU3+{qKV+qYH*x@!w0^;3S5*2>ziBK%K|SMj5S=nWcj zbA}y)pbS-d9^6uBV~w2HR-59&y)U5|ZR?8a=!jpu*D!CAA(-|rv`90_5zt?+DX*qF zI6fO8sQJB~;@Q`u<<_jMjo)u?DBM$~Fb{QbUWL>M?`BOgR5VO6S~P4-{yJem=@)Y} zlBAeJIyKtp3>R~ICth5H*qm6HR#DZ=sm|%f(e(7oyW^7X(OJFkX@zq^Y+822o#C)c z%*MxlvCAQ$dbyfqdZ(R zR`uTBlZ^VbVJ-{%7WCq}VK5ch!dvj`wJ2GtvP^F}NGmpZE-SZ>jsqD(<%JSuJvGui zlrk*PHEPtZbo|;R!A_!bP+Xn)@hwKSOg}TybjbbJr?CVUXpedWTCNhZO4A1(E@l!| zz2#_%k-6VJAEV*o|eJ%A`XsP{eLEzBVm#O%8j}h_<&tRib zBq0d2(Z<&hN|147KDJ-RU97d-U5>)WlIeL)TDV6J5|M8vllk8Dj4kc9cIP>F3x9T= z*h?XWXG>Z*arp*&%>i`*P%Ps4Yl07`p%QGOOqK(i#f;V_nkf5|46|+UcEGIfiswde z82FcTF(G0Mh=5Ce0r&;(>*-w?D>yHKES5oV0Y00T%JQmJ4!5`USnd7SN2XQJXjaSR zkTYTI@{8T=lZ>;~`1n~1+SaqXCt?OBr%j>cI;oW)cQKJY6%b(@HF6 zGh1&_S2ALN(DV6xp_kBPH?(%%2vh?98{%7y;D(7aDN((5i;~^sJFba3c8a~g@kZA-mf#aKJ138tj=pEc)v#y zNSu42G~DLfYb6`L&2sBk!4p;U#7gVCl3ydwI}OP1v^uf~93A1W*NUNA5nK=^h)TS% zXUhM=_h(MJeiBcn|MpbuRrH%Vq^^hz=(z&G)ULmTW7wLM*p2cYp=zS&5rXnD1;3m~pl_>)k9HQ9SxL^OI z1|zaTVk3OVUBfaFAyVL)EYom`LDpm7`HZt(*v2MJPn_`&j!4+ZlHe6?5xs$Co>55Cf0dGH3> zcsCa1o1u98rj4d!HF(z7(m8B%;Zl!*^6*blb;#ZmrWrWNDLg1M6+6k(XdBL7XUGvNz1P00{?svX*u?B&!c!#Da z^2o*(>`nk_;bgZWZag*#XRF?X_8SpH)`T*KM|smzz2n=;#p?=K*0||5`=O6#;vVD= z*=(6;^^mlTr)T+??~ApL?%%_moEH?vlM5>5En!Iog`4&9nqx|cJq`pO8&Yo;`ogJf zJU$@0*DmQhYH@S8n|6LWR^}v;Zcl$V_4^>ft(TJ4QTZN96cir!=RGpvJh78mz(Ldh zP3!tg$Oq(NZSp=Y{zmHzN=74*S4ZPmNsBd5GJcAA?k4KbK^Qz`m^Wvoj!d~F6Z$=O z%-p>+^iI^di>TF{M;P*7`wqI541OpfccgsT$VpM*?zBmxZrL%6W|cVGTMr>B-pxNU zd-8-@Zo3oKkJe=JZk9C<4sp!PXknXck3m9JV_&IfViI$;d2sDy>22xCTIh*tJET)j z08M;26PlhXv6{USOtz84F*;g?j=TqS2J5bFhbX5Q2YbYDlNYr=0pz|lDthiwCx9ac zJnRv8gnYKCZ{M^Im)ABVc?>;%@-bal?$7ZGWE=T5vTfBS0?}HK+y9Cj2q+PHHiOp> zwHm^G860}}F{dJSuSvQ%J%=41jm%R|(L5rrs#i3>`z(Xs%E?Npm#L?>UP}gAEk1hi zm73b{(U<;xTcQ}<+UIUuIiOQ+ZjxYF6k_dRX2RJKn!By*FID)o@qRva;pJt*?n;=eESqK6-M-0%?83_#ba9Y_Sc{tjcFZ zfr`G1!$0fT254%_BU!6W#wzlvP>btO>?lfqm#e>-mKjwu@V450H^XfJh(JCf%k)zU z&`!@}2!FGid5$c#q&PSeWB%8y4K<5W-&y_WJ}N#! z`{hnpenOC%cnLPmtN#+l${~LBq$1&(q)6+e{w@mj>RG0JMv@r3NtoU|b5aa`%EK&5 zgPR{=Yvq)Lw+WLb&G^_9!;{!{)EocsqZr`SrbKa+$!nz_T8h7v+d~h*eygGr;QE{R zAgie|lU6{cukJooRl?|~B#O|IwB(*u71y4?A-e!aT1e=wv&R=lwFemI`5fW<7tX4i zjVQc+%&bJ=Ufu)HKpn>8f^hri4xiTESRvWOCTTLjdo%R{Vad3!ccT+lvx*!IV4sK( zj%8wIrjaY={`UGz=xW7ae!AV#T`-%TqrNI(OHa+O{+7PH@(WI?{hpuaCDlQDNP{Z3 zJ>HHy@gUaIE9nFUy#>x|Uv-gNvm7N2f_4H;;B2Y?-eEwX)oJ5v+jEsId9 zxOfqFK08)z^o2|{LVW;^d{F?0K;C4aQ+ziQJ#L%xK{~B0o&exKABk@3FsgPbJf>rb zIa@`3_%gsnxN#Gt@xdIxGW-7U1qPY57;T(o@rgd~J-cQJuQSO{y-sB-uz-FZbqlHM zFq@LZqS4ZO3<(+TbTq-ssFO0(47SR2o@b0cuTR#J-C5-1@62AXk+~`^?mo)PJP(gdZT;K*4+u*2xJ@f#>Q3j^w(D(weooO>clax=qj?SbN{aD*+D*iE! zH|0URSU$S$b}vPjh34Af=n%@P%4Zb1G3x<$ZR!h6#?mWzD0iBTI8Vs+-}Ef zn6}%KgyXvJf1St3l3TG>Y~2}p<$oy{XZ8_@l--RYtT~O7-({yUHf-2X_`~DN_noR9 z1~VJ|y(&DQa}!IE-)#T*s5URg*W85DkVV#*KTyp;_HzIHg+`V5$|L|n4spfm& zF-@J+N$g{o3vzoDRPO@Dlq9O!(@ zGT!t~uhag1o}e8Mr?}?jJHIvj>HSf7qFf2g#*0U1EN=QRcYQmgtpL5Jdps>DW2@R4pucWvbl5-Kk+deO*p~ zczBuI7hy=ljWf~urQAFZ>fB}Qp`i?I@-X(G#IJ75(6c;;7P+smP?DoC+z3(pFjiBU zj63;Nh9$0msl|&=1Kgg$bmL)K0JW;*I4hy#hRS+@GElnAhK{D`>_8gAL!B)*#-Lhr z9x(Y*T)n}|A?a+T;wX@q+$+$tvU>jJCy5v6m9>$}b_(mzRUVwh^a^j4{{nf018v%$ zl%a%RW`qXvlld*Mq9rs%dYqq)y+>idm5=SV=d2fT?22d0pKt6a^p9+G>2T^}qY~Hy zPc}M+NbHBBc+m_Eo21cyHau{@{lXBe;=z4fa>eooUnBRPmZaA|1sqbb{S3=3#R`5= z`3q9~R*w!Iz(TX1`*(+hwkyYA$1V>v2jWf`5v#mrahLhpoHTqlPFwVD-H~+5)(~mWCWB9j zF3LaR@^~bD9~h6p!4(nnbEt<6G9)zYWT%;zZ(&(C-h9f#F12A^)R;q}AJG4^U|v^+ zs4Ey07#J=R7#Pxj7tH(bT`WJp_>Tj0(dUtwBqyn?fH`E^P$V=VJ^AfN5%sWf3~1Q^ zo~Y znBn;CfDk+wgqd({R(1bu`?J;9>eh-E3E2RfSDNnVY-jA6}{ZYHv1wom!tJ@FZZYngcSiFsIL*7C_w(3)WGcU zO^8?2586Nx%Iz3fkEWRs~U@)8}a zci*;QjuZ%Qw##ki(=c9($mE7)k5KZ71&KoV{dE1i{&b6-gCBpJfqpQ2jN)X-wd~=Z zB)ev#x}`7g{&rIQJj-RgmBT;p({Ga~tXfVF$dq@zcZ_=gw`coM0R&yOA2(!q;=VhS z^@`kRD{jm%kWCfMr$xU{Q{A(?626vnkBw4AWgF}U#mKc*Jc+$UZ)A;^5!Wt~VZDTU z-y*%Cq^f$z0qHij|2}+mK=Ij~@T7SU0IwAomIsY%1KLT$OXZ zPeP;n35dLtod`U=T{YS!J=qf7V_h%GQOrQ^=kqUiDnSq~zXfK#xJutfe0YVhO%vRy z(f5YP4%$S0G!GFJ`L{KHYwFS+q!-+5yCj$?`vAXRZ{Fxuy32pjd8K=e@H9MF28Sc0NG61R$3SEav08)7dMx|5>l|Q{q1lKkyXLuDSnL s`oF4o{%_&`sk{D5^z*Mr9sZy2e`+#$DQK9_3m`$SCeS;a>*uHc1K^{mbN~PV From 87ace40b92dcadf8eca6a5d35e55190ee012cf8e Mon Sep 17 00:00:00 2001 From: Amal Nanavati Date: Fri, 1 Mar 2024 16:09:15 -0800 Subject: [PATCH 11/18] Added filters, retrained with only the new rosbag --- .../depth_post_processors.py | 22 ++++-- .../food_on_fork_detection.py | 58 +++++++++++++++- .../food_on_fork_train_test.py | 65 ++++++++++++++++-- .../ada_feeding_perception/helpers.py | 1 + .../config/food_on_fork_detection.yaml | 7 +- .../model/pointcloud_t_test_detector.npz | Bin 59096 -> 27132 bytes ada_feeding_perception/setup.py | 2 +- 7 files changed, 141 insertions(+), 14 deletions(-) diff --git a/ada_feeding_perception/ada_feeding_perception/depth_post_processors.py b/ada_feeding_perception/ada_feeding_perception/depth_post_processors.py index 82ee9f1c..1a68c716 100644 --- a/ada_feeding_perception/ada_feeding_perception/depth_post_processors.py +++ b/ada_feeding_perception/ada_feeding_perception/depth_post_processors.py @@ -7,11 +7,13 @@ from typing import Callable # Third-party imports +from builtin_interfaces.msg import Time import cv2 as cv from cv_bridge import CvBridge import numpy as np import numpy.typing as npt from sensor_msgs.msg import Image +from std_msgs.msg import Header def create_mask_post_processor( @@ -58,7 +60,10 @@ def mask_post_processor(msg: Image) -> Image: # Get the new img message masked_msg = bridge.cv2_to_imgmsg(masked_img) - masked_msg.header = msg.header + masked_msg.header = Header( + stamp=Time(sec=msg.header.stamp.sec, nanosec=msg.header.stamp.nanosec), + frame_id=msg.header.frame_id, + ) return masked_msg @@ -124,7 +129,10 @@ def temporal_post_processor(msg: Image) -> Image: # Get the new img message masked_msg = bridge.cv2_to_imgmsg(masked_img) - masked_msg.header = msg.header + masked_msg.header = Header( + stamp=Time(sec=msg.header.stamp.sec, nanosec=msg.header.stamp.nanosec), + frame_id=msg.header.frame_id, + ) return masked_msg @@ -176,7 +184,10 @@ def spatial_post_processor(msg: Image) -> Image: # Get the new img message masked_msg = bridge.cv2_to_imgmsg(masked_img) - masked_msg.header = msg.header + masked_msg.header = Header( + stamp=Time(sec=msg.header.stamp.sec, nanosec=msg.header.stamp.nanosec), + frame_id=msg.header.frame_id, + ) return masked_msg @@ -234,7 +245,10 @@ def threshold_post_processor(msg: Image) -> Image: # Get the new img message masked_msg = bridge.cv2_to_imgmsg(masked_img) - masked_msg.header = msg.header + masked_msg.header = Header( + stamp=Time(sec=msg.header.stamp.sec, nanosec=msg.header.stamp.nanosec), + frame_id=msg.header.frame_id, + ) return masked_msg diff --git a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py index 86226d1e..3a3be9b6 100644 --- a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py +++ b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py @@ -32,6 +32,10 @@ class to use and kwargs for the class's constructor; (b) exposes a ROS2 service get_img_msg_type, ros_msg_to_cv2_image, ) +from .depth_post_processors import ( + create_spatial_post_processor, + create_temporal_post_processor, +) class FoodOnForkDetectionNode(Node): @@ -63,8 +67,17 @@ def __init__(self): self.crop_bottom_right, self.depth_min_mm, self.depth_max_mm, + temporal_window_size, + spatial_num_pixels, ) = self.read_params() + # Create the post-processors + self.cv_bridge = CvBridge() + self.post_processors = [ + create_temporal_post_processor(temporal_window_size, self.cv_bridge), + create_spatial_post_processor(spatial_num_pixels, self.cv_bridge), + ] + # Construct the FoodOnForkDetector model food_on_fork_class = import_from_string(model_class) assert issubclass( @@ -106,7 +119,6 @@ def __init__(self): ) # Create the depth image subscriber - self.cv_bridge = CvBridge() self.depth_img = None self.depth_img_lock = threading.Lock() aligned_depth_topic = "~/aligned_depth" @@ -129,7 +141,17 @@ def __init__(self): def read_params( self, ) -> Tuple[ - str, str, str, Dict[str, Any], float, Tuple[int, int], Tuple[int, int], int, int + str, + str, + str, + Dict[str, Any], + float, + Tuple[int, int], + Tuple[int, int], + int, + int, + int, + int, ]: """ Reads the parameters for the FoodOnForkDetection. @@ -146,6 +168,10 @@ def read_params( crop_bottom_right: The bottom right corner of the crop box. depth_min_mm: The minimum depth (mm) to consider. depth_max_mm: The maximum depth (mm) to consider. + temporal_window_size: The size of the temporal window for post-processing. + Disabled by default. + spatial_num_pixels: The number of pixels for the spatial post-processor. + Disabled by default. """ # Read the model_class model_class = self.declare_parameter( @@ -279,6 +305,30 @@ def read_params( ) depth_max_mm = depth_max_mm.value + # Configure the post-processors + temporal_window_size = self.declare_parameter( + "temporal_window_size", + 1, + descriptor=ParameterDescriptor( + name="temporal_window_size", + type=ParameterType.PARAMETER_INTEGER, + description="The size of the temporal window for post-processing. Disabled by default.", + read_only=True, + ), + ) + temporal_window_size = temporal_window_size.value + spatial_num_pixels = self.declare_parameter( + "spatial_num_pixels", + 1, + descriptor=ParameterDescriptor( + name="spatial_num_pixels", + type=ParameterType.PARAMETER_INTEGER, + description="The number of pixels for the spatial post-processor. Disabled by default.", + read_only=True, + ), + ) + spatial_num_pixels = spatial_num_pixels.value + return ( model_class, model_path, @@ -289,6 +339,8 @@ def read_params( crop_bottom_right, depth_min_mm, depth_max_mm, + temporal_window_size, + spatial_num_pixels, ) def toggle_food_on_fork_detection( @@ -337,6 +389,8 @@ def depth_callback(self, msg: Image) -> None: ---------- msg: The depth image message. """ + for post_processor in self.post_processors: + msg = post_processor(msg) with self.depth_img_lock: self.depth_img = msg diff --git a/ada_feeding_perception/ada_feeding_perception/food_on_fork_train_test.py b/ada_feeding_perception/ada_feeding_perception/food_on_fork_train_test.py index 00b8ddf7..5eca376c 100644 --- a/ada_feeding_perception/ada_feeding_perception/food_on_fork_train_test.py +++ b/ada_feeding_perception/ada_feeding_perception/food_on_fork_train_test.py @@ -33,6 +33,10 @@ FoodOnForkLabel, ) from ada_feeding_perception.helpers import ros_msg_to_cv2_image +from ada_feeding_perception.depth_post_processors import ( + create_spatial_post_processor, + create_temporal_post_processor, +) def show_normalized_depth_img(img, wait=True, window_name="img"): @@ -90,6 +94,26 @@ def read_args() -> argparse.Namespace: ), ) + # Configure post-processing of the depth images + parser.add_argument( + "--temporal-window-size", + default=None, + type=int, + help=( + "The size of the temporal window to use for post-processing. If unset, " + "no temporal post-processing will be done." + ), + ) + parser.add_argument( + "--spatial-num-pixels", + default=None, + type=int, + help=( + "The number of pixels to use for the spatial post-processing. If unset, " + "no spatial post-processing will be done." + ), + ) + # Configure the cropping/masking of depth images. These should exactly match # the cropping/masking done in the real-time detector (in config/food_on_fork_detection.yaml). parser.add_argument( @@ -253,6 +277,8 @@ def load_data( include_motion: bool, rosbags_select: List[str] = [], rosbags_skip: List[str] = [], + temporal_window_size: Optional[int] = None, + spatial_num_pixels: Optional[int] = None, viz: bool = False, ) -> Tuple[npt.NDArray, npt.NDArray[int], CameraInfo]: """ @@ -282,6 +308,12 @@ def load_data( If set, only rosbags in this list will be included rosbags_skip: List[str], optional If set, rosbags in this list will be excluded + temporal_window_size: int, optional + The size of the temporal window to use for post-processing. If unset, + no temporal post-processing will be done. + spatial_num_pixels: int, optional + The number of pixels to use for the spatial post-processing. If unset, + no spatial post-processing will be done. viz: bool, optional If True, visualize the depth images as they are loaded. @@ -298,6 +330,18 @@ def load_data( # pylint: disable=too-many-locals, too-many-arguments, too-many-branches, too-many-statements # Okay since we want to make it a flexible method. + # Set up the post-processors + bridge = CvBridge() + post_processors = [] + if temporal_window_size is not None: + post_processors.append( + create_temporal_post_processor(temporal_window_size, bridge) + ) + if spatial_num_pixels is not None: + post_processors.append( + create_spatial_post_processor(spatial_num_pixels, bridge) + ) + absolute_data_dir = os.path.join(os.path.dirname(__file__), data_dir) w = crop_bottom_right[0] - crop_top_left[0] @@ -320,12 +364,10 @@ def load_data( ) # Load the data - bridge = CvBridge() camera_info = None for rosbag_name, annotations in bagname_to_annotations.items(): - if ( - (len(rosbags_select) > 0 and rosbag_name not in rosbags_select) or - (len(rosbags_skip) > 0 and rosbag_name in rosbags_skip) + if (len(rosbags_select) > 0 and rosbag_name not in rosbags_select) or ( + len(rosbags_skip) > 0 and rosbag_name in rosbags_skip ): print(f"Skipping rosbag {rosbag_name}") continue @@ -367,6 +409,9 @@ def load_data( else: # Skip images with unknown label continue + # Post-process the image + for post_processor in post_processors: + msg = post_processor(msg) img = ros_msg_to_cv2_image(msg, bridge) img = img[ crop_top_left[1] : crop_bottom_right[1], @@ -571,9 +616,15 @@ def evaluate_models( for i in range(y_pred_proba.shape[0]): if y[i] != y_pred[i]: print(f"y_true: {y[i]}, y_pred: {y_pred[i]}") - show_normalized_depth_img(X[i], wait=False, window_name="misclassified_img") + show_normalized_depth_img( + X[i], wait=False, window_name="misclassified_img" + ) if last_0_0 is not None: - show_normalized_depth_img(X[last_0_0], wait=False, window_name="last_correct_no_fof_img") + show_normalized_depth_img( + X[last_0_0], + wait=False, + window_name="last_correct_no_fof_img", + ) if y[i] == 0 and y_pred[i] == 0: last_0_0 = i @@ -632,6 +683,8 @@ def main() -> None: args.include_motion, args.rosbags_select, args.rosbags_skip, + args.temporal_window_size, + args.spatial_num_pixels, # viz=args.viz, ) print("X.shape", X.shape, "y.shape", y.shape) diff --git a/ada_feeding_perception/ada_feeding_perception/helpers.py b/ada_feeding_perception/ada_feeding_perception/helpers.py index 98dc3aa2..81cb1fea 100644 --- a/ada_feeding_perception/ada_feeding_perception/helpers.py +++ b/ada_feeding_perception/ada_feeding_perception/helpers.py @@ -15,6 +15,7 @@ import numpy.typing as npt import rclpy from rclpy.node import Node + try: from rosbags.typesys.types import ( sensor_msgs__msg__CompressedImage as rCompressedImage, diff --git a/ada_feeding_perception/config/food_on_fork_detection.yaml b/ada_feeding_perception/config/food_on_fork_detection.yaml index 0cd3b824..d832bb76 100644 --- a/ada_feeding_perception/config/food_on_fork_detection.yaml +++ b/ada_feeding_perception/config/food_on_fork_detection.yaml @@ -20,4 +20,9 @@ food_on_fork_detection: crop_bottom_right: [436, 370] # The min and max depth to consider for the food on the fork depth_min_mm: 310 - depth_max_mm: 370 \ No newline at end of file + depth_max_mm: 370 + + # The size of the temporal window for the "temporal" post-processor. + temporal_window_size: 5 + # The size of the square kernel for the "spatial" post-processor. + spatial_num_pixels: 10 \ No newline at end of file diff --git a/ada_feeding_perception/model/pointcloud_t_test_detector.npz b/ada_feeding_perception/model/pointcloud_t_test_detector.npz index 860a9cf6022dbb5626e9f82ba38eaa9ff04baf37..b7a79c2aecdb0c4f085c2a2953bcad32aaed9375 100644 GIT binary patch literal 27132 zcmY&fWmH>Dw53qs!z;L!;_hw*iaQi2UaUxQhu{<_#Y%B^m*ByJySuvt4IVVS^v`?i z&06MN~A znmVR?wmG9PZd|UU)PHfpiZ*XFxj%=N+_6Km&uz%!IfKBVY#D!U za_%sWsms~h_CW@w znj`B2g)nXkQE7_LO$pcVP%~eeSY;rXm-TM!PdEJ(3=8bcSZFtBi@t5=>dt%#F)M*4 zxIqd{$o16)+g;!Sl$GM;RD9goG83;&V*Dz0CRfP_r*7Ltw?l^VfscyV>7q4;?vZUNL;BRKE0)8KCTTql{iB^&Vbcfedoe!#h zcO1_q!+zG-=x8#PNEQVs8S3a>4(9Ip#I3mzs?=FGaTiBQho-WjQ+i%l>)({YTGcq~ z7ZeV*{0P`>glJ!%OB}@QFKRzu$&oyGEHPWAb0+Jfyw2CzZodd9Rfl6rhw+p5R4yCZ z65C;v`1R8?6vrio=acwwj_vnE=owzB`w{F+>}aG-vxNM#VI}1!9*j@!apOgJAT50DG9K#%g17@mTmj9Vv}krc zcuDbj*otS|gj409AH%hntl|l*Rz2(z8x`4;eQ)~X56c@m4sYJ`bU^89S}qpmad`Jh z)9#fg(7}W)mUP-7VD+bOFNIad(R~+nUqYE!P^RcIz|=usm-#&BY0aY$C3$#fzIZSX zYA=u(EmjcNQ_W+qD2j_}@jLk_*TEpxmNF$&Soz8vFOg$g^K|0KB)`)e)|mHz#u270 zF#n6s)@jJ2=M_+`5y6Qq-;DAb+kdNH@oOA3<2hVlu)eiD}yB!9oXz3LQMTk=! z?@rd`{AvmH(v|u%7NymJ9j*L4oLrZpWMGng##6czXB&O-d-_}0W&G~zhXWUdyF-h& z&b@jM@`p8BTWqnj;x8--_XH{xD92{`Kz_}d>-t$AZ$dt>7xx4xQ(A}i?aOPgMnTx- z#yuy0Gr^6F-}GosGcL#%ZE_VzePiTM+Wcg4_vnSfJ3$;oSNtMw$EpYp*jxM`+*obv`61ND-CA`rP zpE_ViHO_uY@sg&1(ND0N5F?8xDcP;8UnNSvo2qz4<}2Y?lGllGv!#TwaU+nRq~!lo zI4URBs_61Fn94K`^zw94Ir%<2Y+vNNpg>Y;4abh1*&nweHCYnW;!mccmx?sSVndAeJ3 z93D}Ci z8IP_9WOv?QN`@(JG-Lara%9kO6Qt!%I*`PHINABvId>LmzzJTnI zM?V++E=ezK_;e;~6_%DotH6z&+;{`Vi18oIUtaMx9narCC{b;+#hY#-Tg$j1I zno?pf%lfmnxllQWrh>YhgB}SVw%s7~E#e&(hmsdNC?OvgD!WmeVB;!Mi!SwX8r|Zc zdhn-<8hd+kMZ+Q7ST|Jiq8GLG`Wvc z=j;)$TUPyUq1HGTua%km5WWz**zyo)0{@{gpTn#&j53`Orqce{#p_bz-V|+<<*VKFR zgfoIYO?mIKl_E`3S#x5%>k^a;pGX$=&%=GMiXrqAJkC+-swa}1En~)(8Tqrrb?c;a zNRj*tBvlkYb|+n4(M9w?fcIwh`3s$~pd{lHmCer^mci`Q0T+j2vHUx}n;PC;hX%Or z!uJ#j1NWI-Jb8&JCVm^)0R15+CV}BOQ?#S}H~6(J{)CaL9k+iUqwmGNmHc-}cbi$n z#guTp_!qT&naDR{71SJ#I$`LSsub|o;0x}64Qqn^*~H^@JHE{TmJtgp0k>~6mieQZ zV4?ae%Vr?%Lkg@-w$vk#nxNzI&s{dTZS*|1(a$Rv1(mMik_nZ25h7z`M@N2xUljxG z=%Kwprt!dWyUXPOLN9f)DUGC_`}<`6?1L^M45jropVo9~S+l*7pH5khWG>36S80{4 z$rj=+5L6u8o2~Y+u2FgYl*ua0XL0x4iVPN=20*usj-a;C>~0wMZylHN&tGR;jZ@h7%fSR8k{<(GtivnlXu(b3PYKJUHgsvULnN8SgYuwexYDhc_ z{B%<2QhWhX?ccD}9j1@u;th4w4O>ZrfN7+s&I16{FRGy9Ai2JLI(i9CBH2vCqT5&D zOlD83a_34yN86Ob22BN}zN;20II)H?)dA0$op}X>_B3D)^1mir3(V-wztfD+R9{Vu zIh&GIZYHa`n(2t4j-#B0SM>Q13kO`C>)2mg0vZQ$u^=Nyb7+!RpV*(GG$6jgZFLq?mg`4`c=OfnbR;rE0J(gr~x#q+h{7VRIE5JwN zoEj4o>N+Ych@a36ccJnf@=v0&_sGm$4S6dn2?-ghB7*)@2UUefNF3y6c?z7DS0az! zP>ntng^6zXG_Z=|yu8u5RQ0W*J1Uyklg)RyH0^iYd*S@@mcYFN`RW0TA3p7JJu>y& zonTAHzxUn3hcYWeh1!ZoOG!EhW$gDWfciunDM82^h}CRu+6h6E=XNnqZa_{r&TT}t zaE{~S1VhE2&<^hcdx>fcQJiC5A7OO(d1UnHcKq5DvFX!lw?95@o=-@U4P z67cAdQM_)Y4bWR8(&@OZ0a*W){IL}BQc7-JfX6Hr$%oPjyo(w)1+W{5LqvCYt~sG$ zx>ZznD|egc=qiwuo`MYdfX#rdStSo$lj>5Nfeii*43aO7Fs(~oFMQhexld=j(rLyt z(4)#Gx6?Aq1U%nwSKxzw))OL=Csf)PdFP=vt(gs^jy<#WJ*)M})NSsDUFrOkk($ar z&{p=?iE9Ci6LfXo_=OmvFf-#m>=;(HF1q`8^t~>|3jR}Wj_zu~IM~6U!;3pj7{v?MFH=AK-rfED;$rk8f95&yZ|Kxm zj@Yw)Y=y=Pp%EBwVhW}$l&(S^_j1x@wZ(Og63yOBu@XkC$m7a!k)0vaXOBulFzDK@ z-n%0KCboScUE7C~i0?wM52H(5Tb_od@+YHj0D$~8uHyX+3DYj=HDOAN7L`!rcF!~G z)Zfhk4^!KG+MPmx8c$6dTIsp_g>bNp>ySL8|98mXhT95^79N6)IzZ}n@op;FG0W2` z$rSihyJov2MMzMY?&?h8rXYS2_2SVR(0Zg(LU9RF(|=ovwP9>SvHuan_(X$|H9EBF zH@RJkS3|ILkY+?}{wDP2+CgRJ6b$0BS1P^e8RdYfc8TOa@8%#O(1F*VsYQ7d3{}LF zPj|#>8xotGyc3R-p*BM^4Nft6IvB^t`y}vyc^1i-4?PP{hTDW2^HJRA&A+A+{F+Fd z5+Yu7qktuEX1vI&u;9=QSlBxyu1f9B%K>VnwU?-kP3?-ZkAqepng8IxRU2Y?RbHzu z-+PX0NrRIBf_3h1D886B2LzxgBz$ zx^gFAyEvrey_90uFbw!0b~b=XJc0`uis-qba5PuDNPqK4`|idK7^5kKEuoVwSip$s zHz;cSeEw#eBjvD6Jj{1L5hxBs5xaI^KjK3V$ft*=>*0w0$07Qb9r+n=lK0_~@}USa z=>~Eqe%voo*N<*)Y$^+od3}^Ia`9v5D#W;Se3FNb-Ca*EOKqS-CugNE9q+lVsix5c zLsZ+Kz#mF_l)CNH+wer4zQ6P`<)Jx}^L5XWDzthboukEQDZ=+J587eB+et3v#On^~ z?D2+nDT9#BW4i~Sqx;t1fWqKf5~meM!8vCPw@b&q87|Wky-02fU*qk^T)tAzF=t>@ zsyX06X>{XZ_zPh61zwLQUABe278!}ebQcjutPYIs5oi(Ab`gvq)i`G4Sot;nSN2R$zkKI&9!s&bbmgN>$lvy$1 zEpn)Ww(#P6GEY#ZZgA|f@Poxh!K)KX+$pgz$b#KmSE{Ef*O!K8%^u;=$nihNmJ1hE z(wLz(CT1kd_LjBRROd7;>YjUur1&jyVu~rIJG3z4iz!BBd|Y^pyj~+~dvqF4tZ68& z)s1_VceXPc9CPuk?{j-~K#4u~bR@CKHc_aaZb?G`F+YyVD|HzRxJ;e@$+BpG7wsMy z&;$FP-uU{lfU{nCo1uBxsdSO{!58oDPT4!l`$;0~b}44n)o+5jG)ZK8Lmd=m6wH1) z`D#w3P&tk4c4OaMYcxnre4zU7EhNm`bhm-_uJeVRLlE@e&FXxLvlNE+yrTQb7j#^c zAH`(iD5|WDEVhX+KeG;sl-7c%l%fZ3QlcM39luAicLNAQ_XVA=o826;y5;n)1?q&B zTnKJwV5bsTYg?^pnrbVtkNq^y`Qws<3~P_jL(EZ{K5dV_vJ|<#$bH?`((VNnH=pyj zK4$Zj3r_zvu~oxq$?3ZC)Uc`u*2&Q*Z@m(qJ_Rt0ex15Rajm}m6gQtFeD3pNz5ni9 zWALd$mhUXFDY0FL&}(pRffFW`r9YhXcIp?+L$O%{`o3!1&=L}LZ*~AbX#W zl;*hcXDF`N(Y#5txATNlTWrTXZf%Y<^4|PpD3MsGZ3kc-nN&IJ&=C1zc#toRzgmAl zcM;e?rR1L-@o(B4qn{ebd>-7y7Jimf=;^D9tMDMAb?zb7Z1Q93LU#9<8CC~MX4=0? zY9q_+|2X#s1IoO6NY2{b9Q@E*cwR`*LsK z&zxK(GG|TPz8yE~Fvdspj^vV6%@+tlYV$WCD#3f&Sdf3dA@F5t)i$Rn87llx9K>Y1 zxlkc_abwho?U(h&-Svi=y_pOhk{M)z1HbV;liuvA{Cu>>rLiew?r@SNyZORA@vuq| z76V8wlj+n|YXMj46T5q*AG)p4rR0`4Ex2!N&TO}#`uV6Hz?U(m-6;zS^t5>ph|3(zdRJ--EJ>U%&TU+ZfjT(}O;^-}e&k5%iUyLqV(s50%0 z?X9+{yB7|JGAC}9ceaC#PVx5~dFty`N5O#i`-k`@B;t_35z@?5+Z2wgzn%s-IZ!Gp z_;U@_LF^so$VyJn@p#oc0J;%D`N>uNC-864vfc0B;6)rU!xTy5MRXx@xFnY65U0Jm zKjY3+X)mi%#TI2tovLk>O z_87zqbE~Hz7lySh9+f}1pA3T4fEGe-fe$$2gx^d6i8KiYHpR!7PK3O%AVe1#7NQlQ+Y5m>gK~>;5V|Tj*L@sSm_r~4Q ztc5mU+a#8Z+8AW05OMs3KF0^Qvo4kF3Ovmrs}{JvHz9;SKcXOu=Y#J0RZe=uy>^E$ z^v=n))bx`S^T8M*#bF2E0%HFopz4}^g${)eVI1Uwv2{S zXl_Wh9cs>%G_&3Gk8@CNsOlKjWjCJr_nKZhS0|?9sLGAQg#LP;Es5<0Fw)7H;W?S* z9W|^H06vf46#ooq7hP_ff^Jh@uYC~_l_l!Rzu(L~ zAA2Pz@sP~oJ)Ta@g{SZqL*Ybk*mg#?Gao;a2q+;LP_=5Cq!T=TV&~6%914KV+l;eQ zy}TrZmIV-W4b(?HCN)AFz5aHY5zTsg_f;KXjxO~e{}84}#uIbY6_R1BW*pgn{jzC3 ziiJuqS4$=O8#66{_SF?^#c9Ov{5bo-aY6C?2Yiv$SqO4&_jr|khQhGY@;Vmv<3w$1 zWR!93;+J;yzPVF%w9vB_vMKWwdD8LR){thqG=4wz8;}#)bM563MJVn@g>tnZzj$nt z?m(8~{^W1}kiYp5=uWQw6jMpa@R)ss&?HOxjSyDoxv^d*N~5<|@)WSoe?=qPoed`N zECsiUIZDHl+GsqGh^XP;nqCM78AWy;2ht~Iy@hythbzs(sc}zneqpsBi9usrVhCPs z@c0!Nc?mksj1f`1P~^aqM?Li*6Bsl^iKQttV~QewXU?mT>#~vuYJe1}GnY!QAHEUa zIane&ZP&1`!i)*hZ4EkjQ;03p2PRe=f%*c|hF4GQHvWVS!!Hm11WkMar`vx7;H_^w zmyoF>N8@?>ueLOwUG}~#T0FoO zA3j`Qm(?wvcTE?@9Z_Yq zFWu`jnAe<1vj~fNw0ln5GDi`RB?eY(PdVAy?(|{bDQ7QsC{1p~WDP0N>tn-iZ`UV2Vl+HZDV_w9+uaRbAh?Oe&%+bH= zqT5r$@k~aZ(5Z!8b@X^<@;gj6lI~7Y(A4CjY(_SWLiJbPV+&E13JbqB5s;hY6ru3* zO;-nS5KLonY#ALLi?fEYYacpS*>;DQ(85ry#P%lP(aTDW zfw2QgpWPVD!M|)U-{=SW33WcrFuy-91UOm)FwXDCzVoi*KgJFDj!?vT0ohg%{YM5A z*0Ig_t6f<-An2iqU4`r64Z(k4;RD7M)pso#=M_Juq&A(T)%IZF;K;zyXK6@dFxvR@VKg4q9EmOybccZSI8wh*{RM!m?_3_FI!Wnn%jpnaTr4nc+Yv z9_v?aHFc{xGEeAzo`dQdyMnf$=M0FKuonQEdt#FKb+4IG*>#1CJEG+Y5$|l50OBTA zkOB|HP2(Gsnt8>X66I-}@;vpKd5~Is4!>u`5#zP}Cz6m6@>IyrTM|k69b$SM!bs?Q z*N}!f9yb}iY7@iIe9<{nr)5NVe)=xJ5mpfWV$4hZX@|0Ba;}XkA1jyV@dac5N6!oX z>Us9Tt2UwLxmBYWVOENis@d>|<3joock_<$4SOaZ4urid=qQW>b*YhHC*g&Qr2J?& z@#li1tHrvBZX2xFB_6?h{`|^{)D8>!mw=*j{Vj z9B~AlGm4G+m8zU!@zfM^JnUcIpq`1nZ*vP#7fb)$vEVUAxiiVFV+-m-r#!8Qp5c=X z=mE-Bmj2!OdwdzWv^HqvVHarshwS{`Y}0vHdDH}u`A2EcDtIGoH$^h+GL9LX~DTw#ruLfjMSS&b0@edp;>oZPWTRRF}YJU zHyO>B+#hq@zWpa>r$1P;cZ(hZ-2KMB8o>yRG#M-eTuw~-E0 zNO~%}_YLe0wI456zaF*1UvDcvX>Kq_iWRaR52I_}VWMZx8;MjGdxkwGwS*8oCbym? zNI&s8OoU}zROMO2V)##P^n%034F_6Xjwtssk*L%}jw8rlJ4B23iyYCw>mro=I`DfA zTz?i31;(lXjb(8|IM#j}yxYGGl&kR!7`|~T`CRb?Yob#3b+z3o5s@Z+=h@zEwrQo0 z&%esiW9ZcZ*I;{!l3E@mbUi_hhx^sre4?nJN+zxzUUIvpku%%r!sd4IycFm(WQlj& zFw7d6Wa=uy0|p+z)+}RGHqEu=VooGRGv&8vo?Iw8bLBeW9=rDv>i_Q?{43J@skST< z5~n2+65juvgPS{g{O>XNzgz#tzsLTKj3t=F9Q390!aQS(oZLoUsYjVqmbywwv4`;^ zPJTjOK|v|61+Btw#ahjGL&g!umeBUU?V8Li8S%fM_p1)j;~R9})|-*F{MGG@1$VJ* z%tb)w;2kH`9_C(H#_3QbL&hGj?yya!X0icD^K91pKxv%+ASTPRQS2TZ3#}IdT+l*y zh)(S@R4-Y9c|{!#g_uxKcT1vxECuoZ}?dh6d z+)C63!Snp~ESa4Y0QvCe1c#xYv;P5SJ3rtyEw)X03bRqLP2rQbH@RpeNN@_$ehD`BQFrXe7SL>dY9YXp7203)(9EU%ce};*Wyg z2nUJW?#5(6vM*V^^c8P<6;*J*mb-i#=~~N@zv!Y)gp(;0w31>5*omlx8_s%vZ=sd6 zlMvUO`QNqF>@C)a*5-7ZptF0cOG1^;Zow6hKQObXBYuTdE+ioNWJvhq@CT;>-1fa0 z?$1_T@3}N;)?x!t`T~-Ej0EdXtyPg-SFyAgNFRi(R6vm@JuM>B<~08;JUyf`bV9Y} z+w=%$hk_*gA|2p|jabyDa#?-{YYYYI%!|g4DK8=viV)k=L!CpKIL z7&j%T29?3g1b(nhNNYn&UrG69ziK@0_;}IgMp_THv77P9l-!KT{E`4>z5js4e%dtO z2oXf>@Tab-H7>+m`%3-XZS5@32?sPtcK}i_Pw_e2t6l#^O5_=oX0K}A9a7toslAWy z^}W#yx)W~+p|JI>XsJZ`7A}~&qI)&}@Ar${S4^M01!hzJ~DkT@{QC?d8FgMi!ZG(Id3-^<|`LQ3?@<(GX5ZI;jU z0>=H<&ZG)dt|cmX#slbNtWu2`I>m@$`tj0~n4~rS6O-M<66COjtX3xo$b|T~2@H0a z2!Io>X`%_Puk?BEq|U0Y}h(kR_Ch#x7iGSCd-_e?fSQV?eC^H z^3{?L#wIsW_P6DF-_i$(G|C=5ScUTCP0HGdeOA!^1(? zXk@~*|E<a*GJj2R0b4;V^4~NFlW@+mdpdtPOoms2A_9ZUaXdB5gW0sfe z;3jkQ`p2TXh}v(1+>b;YHqkkg3PzLhnph`50a7PWB8^>Pd8Dp01zP7+)hO2Llj=_q zk8=R%$UI}>lSr+W<}MdeN()!f(}7IxBEbcpe|nw#z#?|$Z&;x;aK5^Q-JB2+*oc;i z%S3~|Z-3IQP2@z07{zHiGPm~g{+>RH1si|)>tCT)2RXqb_03}H5jWh@0$a)ka5Ax+k3G44;UvJW~+?b}*BEZ%FdUdRlH1SnE zsNn<+#AiR>o93ORm(({j0vlsnNRMgUP_WqyGD~sezxY z&9%u!*z8^om;Gv4IuW$}-&0AJR0;xgJBDAXGtqvi*|pli6n`NKe7>W1zP~bWGI!J6 z(QJd<>kISBJ3j3w{!)@#wx%UTVaq|fn)W!fSYTm`nD7{)GGaRFi=a$UA+`=9!#5;- zuWnTU`?uq?AC^-oG{c3O3p~?6WE%nU;Ya=4DxOIHFyuIh>0x}%ta@|l2pwIsDW_&- zZxnP(Ue6;w{ix!Map>t!>6@v*3vv0u2wfFIWG#OP1=#n|lK)F}?#aeGZj4}6o3Ch$ z?zx5W)MhclCJMj<0db#0K?z^(=8xi^LKHV+C`^zk%Lg&KU??JN?sxQ^saP!Vy+gkI z9n?Jf);)l{)mq}pUd}KcIu+{EuyX;TTt|%BJnwvh-du}Z8bay2UVUGhkO(g;{s4ta zNMz#<(b&W7=PL{2ae<#>*f#FtWDv+UqbuGrtAcI3xspO|H;gJ4XDr5I_V zPy7%^;xp7*3&JVpds-E4il~i~0%vc@n^wC!E7pjI$_Ok&aetE(`U{NbAFJ3S`eqVlKRI-JkguP>&Fca`T1eO z{}xesR1`gdP38~Iep8b2jBySc4RSXY8g%yo^b~lAck3*gSOKC|aH@*0ZFC&YP@Bv} z%Aalgc!5;)qoRhhn#w`zdJ$N_7yHk;bmMSg-X*N+jcX;P38;p zkW$VlJ$3hiE;xlaMkklLm4Q;7g!R+m&UwWwwkZJZ$HwetQLt_zcTKR-(0`tGk#wDQ z-kz9V1Q>(1^|Hkf^PlG{qzW)94(av0Y~oJCUYPizSOM9>WLA7LeYvmv0bnIHVG1#%7ZbTLo_mJWfk9= zwXf8|RaD42znerx1B%o_G_#_thJScvAAn>0{EkbBB}fPhyg$pq(AAK7D+ydI(v` zXAkt7Z-dG~q)2`Jv<^QVs37RoLsFjtRHpl%PsH?se@pPE3C8CE@hT$Bm~;uK`aah5 z#$RMIUhxBzgNh$>VVs#Ki^K1!qI%ul2j0#uNlD7!-o-U^H_3ti<6{=Kn@%aATcfwR zHM7UXfeTkZL9}`JWV~%wrQ(6F*uCH~HSlqj$pfCgr$ZltM4E z^TZ-M{;?$ppI!Wu-e9nV8i{?9x z@is9j2Isv8uc7FSS31_E*jV;l)9wdAgmFxFIrlUymLt|JAx9d}S`{0?i{Mue`?!rd z3?Z&{N>}gA8V1ydQ*2Kn=2FS``edy8KCMWN^D_=B!s}NzIA3V1J-HCN!m7_f%1VHc zcm39D44{JfL^OF5ep^F4Br)m#Rp^1_n-U`-yJB{JHwF5Jp~=+0Opozns)s3ay}wO% zC2*wJ3!EgLi+1rfg6xvvy-&<|HBC?@gXd0l)m1=}Y7dsc{6`uG#8eUZ1i|JE1~$LZ z8J%_#B7ck~VHP;uOtZVylYMhc@~!jB-k}4`AI6 zkxa|y&$?FRz3b=oy0j7K)bUJbeScKY9UD$>`$+)7`YYg1Dzd6ssEMdX+xuqpftcBY ziuoemgC5H?A96cV-NFWeRsv5}pVWsuGUd*m5GgWu3q_U+CZ0ThHaGQN_huCPll~mc zL3FB;Pxs8{h`QJe=x(Jf&@^59wFczJ`_~54JB&N05-B%D_}OHG)&=kQMDX8Uu@L>& zoEA2u+D~($)8&an*=iLOx+#1FX7xuf*)s23S5Kc?iH5__8h=0PI?9=?_>ZeU0}5|d zhd!eoW?y}0$ikf3y8ZctB(g60OXN1}{&UL%0e@R#z@=x@JE*wWouzA;EOoHMVWU*O z2@?M==zLn+=a7KB9~3lRk5p%iRu3DnkZNd#fiY)F9P zo~|T)8dA|8EhPt&4hZt&=UvENvL6Y)nU<>!4io$a`;&e6-1x2D_OQ!)c*R8?0GV$% z;V71LO+x;Ugb1OAZ^0|>&%rT_30#YlFUG0JY~y0W=n237T!HaUDrP+b+l_KsJY`4; z&T!$Do4!}`6}i}@p_20O8);1JAh#o*dvFOpe~R8qK9hD$aY)-s&b zu{yNYjhKVb=x*0)S&e_Sc@Xd3r0TV2_L+@Er2+~-1$Sj`xR3fotJ^QX;o#7Th;7Km z;@3YRV(#voZdgvdIy-p=Dl#Rcy`g_jmCy7;Ls)Y{^maZ`V$@(46 z8eo#RU6c1?gJeYU(g#TwaN$7Cs{uYi56u72GcoO{d!5g$+9NX4>)s60VtotDLtzvwzV{3$ zvR}omhGpqOrml*maJa0>#Pbk11t^LZjZpt4iJDw%7jDa5ZDQH+Lt<1Wm!Tw~H-4`` z$c6r_U-$4lr~BONL?1E3ZF8j^m52gYN%bg~X}}Qq*Q=en%Nf7sUz72|#2;XxZp;2@ z&hre+t93lr=|4FCwKJP_P<3Tf3SSZKJVjj$)=gr98_0yB zukit?yj2m9KE8N+vX+j;`gNz*pTa){nTEtS{}`r|^Q)!~-FC?c36SX+`E{CtG>Vn{ z(R(sc^3St`62sbYz+)V0fS*xaZi>LmPfD@-gQ+Xh1YgV1l?0H0nGzal?@Gqbsfc)p zC+OglAXT9t*!;daD7IGwa*l4HC{rmMWlVMq+^wfHlw3) zKLvneuLGzh^nRJPohyN_ptFCBya9P#jOMW3J-z&zDA35LoGB+wE@Y;mN0S>kPuS0->c|^CL*kw!8MoGWprjerKD?DPY(OYvDm9 zG`!3O$CpW~mLDWVTHhj_Y(__LHiu(Q061$=#Q(v_$=h#|YiAT9gm;=bRXPSi zS%Qux0^SYnw;BSS;({E9$DU%$*DVrR=rI@K69E(}JujFAV5{yjf#a}ShVh_+40HC< zLrciiOqRe6+G)YW1Xb&`Vg#CjgM<8X*#H6-ZtabZNIjELTUCEty}vMg(^1<0xrr9d znIa7ITr*6E_}fE(zh)#Z)pf-@iH$izTdaWbSC}>W!>A);3=MO{Fy3+KoQQZgV;dQ} zLl(h{9@CVzST+Fym5NzdQSxtg#rI^}GxhKk+eSSxf+1!;d4=;WWc-*j0`$Ao^@&+Q2L zN11(uS2Khz%6E$ep76aweBu)8CjBj0)Zz4I{X)M6tZ&Ks+F$TuHMjKV*pRRG|Jj(b zzcthGQZDz;RXi|fON1s%4}S=8Y6j9ye;f%H)>l|z8OS=@&hLuyEBDM`%Ryjnc#F~c ztLM~n`RZi~jbXt*!}p$=Ax6G^HYoqv+xRLWFG&0mq1OEIC9;a_b zBufIUL^PgakQ*Gxc~_@(L*~E4wCRKM(7!EU{~VO#)yhQ`fPPdrMKqXX@I97iHd^c# zmlti&k;^CA1;qPCM(@hTMP&J;n+vGq4Fu9E^LzGEbz z9lTc6nY4a-Xyz}|fdu}1*D+YN_EHUX3ty<}e~XRy!e%JucgNOH)0@GGFn{=wT3`PWtnG@8jJ_kSr`{dW}fj=fCI%QknNb0^51j=NS<3ckOq zT}r4Efh;jhS1qgq-LVU#>7X5amTm1go+oe13BFNjVawKi54-MZ{_xy4s@h~S70vA_MG&}oe?X-J}>VPt=dW?u{KGcPvz#GQEB6p(yt)+|~&P)82 z7yfE1Gk@zKoDfjpb~+09N6Fy6X$lvH-Vdf*+6lf9C=TH(EagcI`Qu|ueUGub@r`&2 zm>@`jGy@yqn(cdp6j`Z0njJk9fKvLc^yw)PjO1f{2z}ifU7YUzelfF+h(kM>ei$epA;Days8Pnsn z$lzuF3JIXP2TUd*4Ar6!c>u`?ZZd7`k(2ZpCb-%ErS>YxaGU#_Nh=nK=80pqcEM$d zfHgejBf})kZ_+!*QXJ+YOil~Sx)SgccDXz>!leFmVI&XJo?-j$^3qAu$Y9l2lgVPQMV{vcLuvm-0MU_0Nb)7P#1+sTQ{Prr__nVq>BAI_sMl=r4N#9J|J z>hy5vt}o!F}i`uySjL{R>&jqK)mga5Pvt`7TN31&BRy;Ql!A(Fp0d`Nv03cM|A{zI5MfRnA_y&zjw z>y|lf`mbW>ZRJf~=LuhE7lBI;FpV9IpQmMZ4>Z1w|Fs1`_SirlaJFJ7#4K)pj!>b{ z+Y?gxHt*qm?OM)hz4U#B8Jl3eQfRE^Q+fJnMO=>Au&u;ES^VGOi4pV42a9j)$OeuZ zj#g;SNEO*s4Q=cgLg@qzOu%89%I_<}H)6@S#}ZT$e#fGSBmpc(+YBz!qRpL+@K)BQ zqA+xJ#B>^<{_=NsUKd`NC>V*Eqdc^l%u&lcygD#BM4*&a3^bvwGo1%##u2tLQ{3sN z6>9Ec+#r9q=9(D9vxd~_p7`XJM~M?A3qiBn{%2AFLXD@RY)!ixBOkwucRGLA@)H$3 z_(WgrpRm5T2#Kf$wJ`!RJzUW$_`%-!2f|c{=mrOanWX%_eC2WSKH$!EuD*y^jNo53 zpxtQ``f_6a_7E#h1Sq1S98@+{CbrJ+YB50QNaAu^_dZb7m-$Br)lOjdfsWi*avKtq zDuClch)6;I%%$0}lAD5l)=#jJ@t+gMHbZ@x=@W(ndwiH7Xyfj>?BKAfmr)Jr-0QIc zFK5Rmy?puO*^!I%*+}SAP%tCHX@C;?;#pD2ggRRk8p$~yi_%dQK3^lyIyG$++c67% zRBX|g)^(B#MH(#>pG&vPM}Xmmi++i@_`uH{aO0~6e@sK43D)c3u6Mj_loxl<2amw# zP4m#+ed#YHZuK4WM;{R)SHv#hs`-(+t)2Vj_<%zbzXW{_U_YObk8kvNg!R!L=~1$a zzrC`Nx8z2wr!W!(+==mf92zW%rN*L^8b+ydb^WkkG!d3JYl`DYNQ2-e7oWPq~$Mf@+H(uJzOjen6aDSd+zrKy{F^Mm?ycUefEK`KP7 z!W~6C`rnCaC>oQoKC1HFlQNt39#oLHNOsQ>qaoKiguq8@r@bJ%H@iwh{vdo5a395F zi6{<_uickDA2XE~+sbS=gSTm&NP=X@@Rz5?zY|QADft!LL?b&S5MK2pms6bKO%x*n zrRE($l)Sd%mrW<*TUzJ3In#$sr`KbfaJcH%!IqbKeeWe$qD}_l-6vlal~=A;k1-6sK5N@5kD&Nto_#RUjaKXlNDkq2i|n~ znZ3WI_+@MCKNSqjuGj8pCwam1ZxZbuZ@(u>L}Zja%drNr?tlGc0V*@~d7bz#T@}5J zKGzDIce5>8Vn~3ym7;bMIPbc@zeV30N40K>M??J)TrC1ZWh~d-ipK!}yXagmw~yE3 zWAT|_dz8a8-agyp4M0AWxqk3nBI`OFZZgopW7sZahlBM{r(RUZhHeM{W&=H({xgfmZ19VzEMBE!slY z+5HgB@aN!o^cTZ_hXS4e!)E91zoj;1~gX$s|pcMear zNtktO*D+R2|4hRPd+arBWul9Tv6kNqL6B#VHwFIwfCT6ZNd5v zb1PqRYoNu8JHdh!rx4uTrMMHkxVy_u-hKDoxp(IMnMo#-|IB9p-97Ss=j`5m&wZ`? z-KV4`=Aw09YN$tH*TFu;O{RnAGh7))?Ogu;uxkS@BT8L|vSSbf6%@UGtN!GKE}|Lp z@Jr(zH%vObp2!+w9B%^MX9_SXO7W54M1&aONq6Yl;%SNtg_g#383Y~B z(*H&_#SH#z;WSi3*JP)I!QiFpyzs4v`lPg($&7B6kHy=by%yR|yBu0x;fq3a&sJHp z^bM3if!e|JM4XjYo0H$3CJKgF7zcxym{{E2C|HC;;}y=w($Iv#S0wWaAv|SmBP>*i z2&g30{iyKRybItXXs7n<$U0}eAfNaUp~&6aiX*V1pu=6flDpA>)T}*}%q5nMaG>*T zcjw;@_!AhI_qJp@btu9e$atwtntvY#-j=3+olxC}Qd(=tg!p^f&*bqS+?P^oGIRgN zc?S^63$ePbAKU23mx3i}F@^&n9ji^C+zfG3*_%I}_fc+1O82<%NaJdqlY<6_WVzMn z{pZ~VI*fz1ehAiGLa>34<1a0acqxA4(S*MC5B!`Ghb90qE%;C{G;JL-UcU*r9EqZm zs3kBA?~ay$RA$i4-wxtEMgnEN>EkwiXCnB~>C_$GtI+(o-WJuuds~pTXY`pOfnMNr zR|t(58Y*)>TrAOpwyk%V>56&~S=^?>ygg}1b1L$1i4C^_Y1YfAZw zXI%olXOvan#2(fCaOju3V{o6YLa$aSRDvO7klBWGU+2XERd$6DjW-_PSE~ zaK}f|oUPWB=7Q3b=x%$`#i4FbmG>tPZUdw$?yW|9*s@(g`>2Q6m<}R!PF>J%rF7x( zxei^G(HGgBEQ5p{cwM~)LeY*{@ZlDw#**XIrh9?s3m}!p$rbVKaYtscE_oeaQqJU2 zi)sk!xGmzQ;I7g3m{txZv6e+xvyJ^7UsGBvVnGDdgBRWp$8 zW!qG6wt0^i%Y`aXdk~=mhTSvkLm>+`?N{4sD{hr{HW{h07KLBq@W8J|GY(Pa_6FUl z9uD(5hq|247d*Z3kLDtcEj8!anRdVo6?$1V> zG&GRUc^j`F)8@fa5ui z9caD>u62SpKRW|{Yo91pXs+dG2?o9m6Lu!U0n;6!H{} z$DwT2RPHr6YoTR%jTJ{wZ%t&P z#v2v}wb|E*ydeHN-H!9Lmue~3O`Sr?D7wJ97Uq{l5+qz+#rispNVNe4gWJ^noLVuC z0;k3ZB1?Dby07%jvM)oU&O_QKFj8F`Elz5ZpD5H`YKHCkD(*<9$gRpr8EFA><%X?= z;Nz$s|2a|W8FdWSA7d90RtblCnEAX{O8i;QV>aZPE1a=7u^+t3K))S_GKz zVyWoOwtA<7ZPUa!iZE90-kfhzafzr|(W`L&!6syG{jI?E3rn)*@(Y{KZwBC_=lkt( zR?R?$^l3uJfQ4E5rz&!e&weG=ScnJ@sAiY=$6?nuU9K@%IKeHOn3T>DEkcd6@S>O`aX6gbEy^Xwj1-LPQVRQ?EIj)wF%ha zxr$MWPzCe#x7Opzb9Jh{Hm9S!o>qnll6=>~20pbpb_Yd;=fv0W1s>BnTy$BK_eEY1yonVTEFoMy0D8yv(e)QmFSzN9w8^jBjh=u?!w|EY9jx3nx9?G*OW(d_DA@i1s1i+%{pck%<;EH z`kL(X#sxP+nQzzi8>Izy?VDPn{6LC90pISEZ<@y8ZCsN9VPJ=NOofmG&54lD9eBM7 zldO!G^msHqK?@?avv&=Ia=FAZQXUm2~q`146i2~3;$R$a*PCs+~10vskjA^?-6Anqm zpQu#9{2LeGQa@{qld%>Bo<#gI`RfV_OjGVqrcI;Oi%+VCUFJy(fq zqE$yS$^RfaI=OCS^pk+wYPq_2cehlG-K|xo8;n=$uD^dv!=yXZ8+SVUi})^q*P9k3*!PXTAOLmI zNtugnLnH!yXwp}37L`MLwfu{Rj|wLGlb*V+Wf%kuaf|E`vVQM{bQL^LQXGs?$O_~s zrNu`~DEoWKD_$M8H4L#o&Df4VrmcrK<|{1=r6qkObxT95v-G9Aw>4d~w&E{+FA!N; z-kLgH9x#43F!SU>!e$@x8u>Cc=qT-H0yQ0)>}FCN)k~680pBECVMx%dxgQ(6g$&7u zEnM^RZ2$V4yHY>B^2W{!MH>s^g_D3XwQOD4h1O@I%Tie~Jui>TL05AyT(4mWTi@Ot znRUq|#>}5a|9iIsQC}xcaZ{r+`mhR_kn*~VN$|YILZ)-pWsO0zfD7EOK)oc|Mgo0M zd~EehaFzXtE06e8RfD{?TqkEJlrTzCfsbAO904o##(Sd z7`!6ecGE5n1`G@})NOZJ@1ieQ_Er+Mk6a2TT0iNY;KRGEt7@TKuv$n;2mu*PkoFl1yIVTGr4Dd<9P~YTJclEozls1Y+w-T#>$KX z@aFsby`P}c?z8t3qQCfYHPBp^^~}q!>JXe_lLO?Ln`YT_&ZToI3un_`3TS4n_%Z}J za>dW`Sgcgq-q*`*%T$BtHHi7X8_G$&7Nua?9p(Gw4pYk(%YL6QOXR4@tYG&D|6;xW zJjE>&PCHZWOaOQ%vMj?ExiUT>^x&UxUl{)!lSk=MSn-t()?X*k@9K4RB8G=C3VNYQ zoN__PwmB6{HfVmicY9?Kk(dxp3u%?@uY4D)vXyJmiw1z6A1)_Ag5no){znob%h9qzix2FndK;_$&rnGEiBE< z?nnvnHV_&yhWmGul+#bXbVlMWJrlDZ-};Hz*abmndVE}ZZe6Xmt{En-Oq-l~r7V@} zoZPkLg%E2SHu%K&mxenc=Yg}TWECa(qHsO@>a=j6iAH~kA>@K6jiB~zbIX11us0vZ z@_vNCmGVQ-EZLSZtIPS;jCz<~J2ZGeSBm;W^?R=Tt2G-;%bsgF;M=~jEcMcX#f|@y z537Ha20K@ncNjERnwY%QJE>{=HYpM(k~8W$EUY~nV^{8gg-4t%iuy!fT%Cqcvx)w# zYT1o+*dud9py6cHze$3=SjdkgjOljSZLEi)nV;mO;!Dp1;9+tyOV0fo(@fvPsSf6Nd{lLnocbdwz zQ>^4+Gu1>|+4KP28D@K==zdFa074(gMd&m_fF`1tDZ6Gr8TAbHEvXyn4?f(n(6kIp z7bH}l2VrL`6?krQd>TI7azfD5zs^&FZ&i&?4)a74fjzx>L*)~qY%pIg&>JjJ`M3YsZ*5W5(>)IE~rV~eV~h1G@tPSgr+ zGtzs6+RWHbZf2G-6K|^4zLQhJ_2BBH668+z2ebbox&AXq+X96~K3V}Nb)t28|7aja z0#6CMj(M35z0Ri!_7@=kGy3idXqQ#%mEJ8a((Gl?|#!Myos@=uzKNXP;+_o(Qf;PJDoO}4)I zudx~?EvrvW9?29Kb6lIULce^1zRsHSfzy27XSk_MZl8GZPgRu3J{k1EX^kU&P*GF( zwb$E&2-)F(Cs!RAPi^`P)~`1s^6!n76n`+2?^b}J5Gq29_w7Ca7}?4WN4RTCcOutro6p&^89$ti zd17%2P;HH$JB790zUC z&Fk?DS}6LV@kr2$c?k)oXk%WWLrQc+S6fy}_ZzOEIU-7^q{7QrbJ$KfMHR5*L+8vt zQRoJQ5ovOZ$SUyvMcb#bPJIJeJtK^X`&vM-ZP zD`K_vbBS!e&}J5otsX{};E@8p!(pHh*P6r0l|g?wV1i$$?DmhQlDqVK)A(`M>}6M& z*ts-bL&&u|>#hR}`_#G;GJ@R=7regLpeHv2^SF@It7btG&aDAC*u%m~0YkWkl0!r7a@86=7NJX9Ht!D zsW)ro;#+aRL^Zg?UP&uK7?)W2i?7K+VCSFG(U#-t`!Vd8VwdqdQRSH zGJ@p01VreXU-3ASYRvt`%lq))jTFo4Sr>}h8jKouReTUy zOl$T&QQt_buySJwi^n!VIns=wQvJkx{Ekv14~Mm#5MjbQ7yF0&{N_$HHh)Ci4(chN zGjIICYU;LCAVi(GDs#^c@@+3U!LGd7`7VJ1SMeQZWkJZ)?P;i}A!=YBW%cqk8i_Wl zmb7c_hcYcdy8-{jdeb*FoSd8D8ggq=_;bZsC}6-K3|tFIkq8>+;T5Ta&TRxsqj+(= z_p~4fQte*%oSA&LYM>Eh5TLv zL@{<%eodtWV{17dX?rq$BV59VK39&-Nt>O=B5o&%7bGt!zJRR6ow-tlKD8|Q<^QUd zG`1A`5Q3GM_zJ)%g$38pfOPF5y4??0MYMmTO9h27D87<|HQfl`d6&e^dY1^tL$3Ah zEZo3YB)U^dvQj5UCC~g<_qWAyt;F($C3kM2UV$j~c1yEwW7K|h65sVpmF*zSHGF<5 z&x^t`*{<@-Q$*ys97Z(5QYp2SclZ3?$&s_%aM0xZ(T@v>ddurqUdlu}{APt@e?u|^ zb(`~R7abFP9SQhWB=JE; zKXp=i|C}*CtY~=8x_r^JXM0KUgFh;06H;Rl-mt|Ejj@}cc`Nq;TS(ccr|Y{ipc~#q zlAB+n6k8P9xog^GFb>^VqLc4qIDn|IbG_E}s{?KOQ7Z#gh9?+n7NF(jwMPmE9-0If z50tEt2xg{jcFHHSL_AMFpvf^Z#By0}=#d_y%#nkxnGGhTgOt+BC|VCh;o-XC7nmBG zO9*C0xc0a|JN>FeP|}}kYx@g5p)SxObEwNkap9qRz*$F9Plh&CB=ta4%Oyoufww1F zd0|ZyUuP4Bt+t4_#HgWEEt%#t0hFVtes)+-V&$?pHlF>Qygvp1XnFD ztHFvJNT_d)Q2k`z?wt|{=$usjx=3yqVgxW{caqXi5!fMkhT3PYw^j>`*lC?Mxpt)# z7}@rDVIk~oS+i!1-ig;&alQ@eSMHYaNPkJ1-*2%^2_PVGWE{dV_LiWsaUMGy_kpXjC{+t<|Pi)=|3k9Ew6Y7rV)?DH$Bc z2TEj;g~O4Mv&pOJOeHmNliWgea3{Jk<6Z z-i(nF-Zg)9^t!L-#p)AgNSpW77~Cy{1yJjjd}YgC=Sv~RA;&u4;#;k+&3~OTu>gfM zEMk=x%ww$k?o1jUkKI3-!&AR2pSKGK2XS?m8$_%0;>?b_(bQjB+G&9!IZ?x?R+d#| zy#{VmAI+Lu(rjmVlso~5U^n*y1}{ft^Dr?qpYg%Oicov7v>(?Cj0oe_^3thBIhg#) zbU#Q+6m}4uw&{jgOW$&#jLekZJ8gnEz736iWc@MSFM0QRRM9F=TDLcUo>UgD@Bc(x-JWg@(Hs@Kfpz9`Md z;wO*>t~zx)9@5uleYmHvi})$ajqyDMTF&wGCVwUMWuqz4-pNphJ#7fwrQxXp^wQg8 z(&0r)=5qKGXw~w&N#=3NAMqz&-KtrZe`q@XMtJ<_ zFL1SLG@s>!OuXpr3i+16g~7V{y-fwZGFFHDK9;!@TzxR7FMAH+XVQXDH!G$i6d^IJ zx*;bHCnQri5tPD%0l^9nrzB?)?HXKh$|r(JA0J&cKBg;#__2&YurG}fG!bLJJ*WnZ zwwXl!vUgB*RX*SN@*aYp>zO?_QJhN@11aIIocb*qNtf8`If$@GdjthNe{i%<)Z`5= zXi_khpR%lEti)dJDGGt_-`A&A+bqh2&v_sh>Mpuu9U;LBL164P7X>%q*FM%3v9Hh0 zcwTE)J5;S7ef~bv1qJ2jgjfHmn_S%g;I9lE>~{91Lonus9t0IiBBZT}yMoDry|Co% zxG)hZW}V8hEPdUCI>7UGWl&Rf64$pi-^dU~u|@<0>sP8{b5^4rQ{-r=KkbVpFPKD1 zon#R1uffZ*@3n|l9+a=GeIDnzLj4Hq5V}Hi!~mw><<{I{8RxmPUv?_Ps#NyxK&Vuf z^ICfQX|<1KBKd|8>+v0$B9uRqRZuAg{&sP%3cUc?M`u)gJDs*ca$E7!)oQ3E@tAihScW^3dHq_hX4$!>hrQt7$P z{1`#fP7B1{>Iqe@ivEhQ${u$#tgn1@`0K!!dZw<>qPZxib3U`ZP<-xxg4CfcV2j8C zt~CJNh>1dO?p4uIdm$`*G9M zAKpeO?A|}A6_LPRWOIN0glfs~vE~e)@jt;{6Z4(#y}t`j82X*-O0}>dig$yE`Jf3* zU$e7kCpxp;un5nddry~ELZgV59mcr!QRnJxl7pH4=87eEn2L@!d%lGeET&6utQzD! zHmV(StY$uj212Dm)<^x>LrmB3y4Izemc!+2lC#7!VxIRK47#%A|M5oQoqjQaSU81_ zU^E>L$`;dGH`r4qFeR#CQEEh0=`-kM5CmD&;O4;-_gT|osudMnSJc8J6(tzI2PTB| zWECDX?+62gXRi-If}_vodHQoKSz{gO&a@xlB^m3%*T3tgv2n9b+UBK*UcCz49&}w0 z@3>a8yCRBy9QfJeeLlLQqmD)AQXYAk?EBdh+igz3OEm`*Z}RdQJxNY3G#$$2YwIb9 z^2}kkQccOj=_n5MbeHCo%MPHd%#<%WAzuBxavAuko^EU%WXV@&o7R89r0KUeQS8(| z6w6$pH03C^ny-zn$w}|RI{JO3tN^3tWach^X6o0MbS_@dFDXMVzWQ{Jy|=aR9K_aj z;uGSrsfZjq!VcEI?HJzn&vI}mI`G~ov#z+hz0u*81blM)NobkwF7r<&?}g10sB*oG zEW8VDvT{w(2>HPcmkROTTZb#e`c8`Y3r#DBvd-1|<~uK_pYmGsJ$upR$gdJ_MYUy(Tl$%t$R0h% z%S*WeUMxzRDdm6v3VlZRxXx>4@J`Dm+i{<5U|19ExmAuI*FT}G5ZMD=Z9WIc{gz#< z#jb$=sr&x!F+7yTb>FXj)_8b$kjOjR5<>J2sK9%jqdu76(2@}_b8%pU8I z_%!X!?nhv_8>V2npWxls_QfY*esy*OvSk>=C>p1=>1gYc6s1#boE-al6T?XEa$n;_iD3vYoN{q! z>WAK1M+G+qos>IMz_XR735=VonYL96DSqOZ0aFAN;2YNsS*Oej!MlC)0FW6Cz~N=e z(QlAiq+ienOsfoCe{#z%=r;Q+kw{|77Zm-9K|+T5-lfIlsE}Xl%i4?%{fLB0D{KfR zIPE|&$^+z97Ek(WI`ieFoy6)$6-Ev|D(5NNw|Ud1k4a(}qptl0{Y#+HSKjfWU;B-N4pE zWDtYF+%{$!=3Q04Sd3M}=S;}&Ve!+XyOB#wuleu8QJ5i>+g+6>7SAQyue#}f0%f)$ zt5N(%^-tsqHpbShPK6P9V;!bK1ey8OFU!rrCDD3Q;Sh^i*^Paw_<4fi;_J#w1_5=m zyuNR)6uYbVdahCM$tTDB**%DXH=S}4O8su#Xr)`=X6?be`*Ysndy`(q7b7qe%JJV1 zKqkW9&hbw0aj*e@a(aSF{g~|e1!(@vI5r9HXK&F2NGGpn=s3BR3<`%nY;nyLo9rK0 z)iH8o2jL1qzAWyR`Ggo{$kotZN4-0jD~pQ=W>{CRG@SM=(%a;VsszI`#*eYtEZ_gW zCFGy$&sG>7i|U%88V3BGCCr&`L4JEm8QVW)gNn=l_G|l3#>_oom{!D{Ew&97)A>sm z2a5+vYCxM!?tSr?>E5>Q#xh6eO7Y^Ow{$?Tu4v6*z`U(3l_XOX(a?qI6ABh3#foyX z*S7*(Dt63>2o_RN{$FHqM-Q?&toPHiyAI)l&Um-;yJV~$N2t%tjNIpN%?INlU1Fk$ ze8%{nyV8VQEVX?@MM5fng@lCj-@DTM_t7kf9}pMfCd8GIG$c2rLfGdwGkQASWniVf z0A7HOtI%^%TW%VfQ&?M}FvvVU`vUH{z^}~rD(QM(H6&KNkQoVRHE%q{y>c!R9 z9(HS?l~wm7_$eBmi_XXC-XjfdC8f5^-u(FK93!4kTK+}Kb1Q#?!&3$T#f2A!NrACG zEiPWKSB~FBq&{lbxb~w1a8}tx!$4C*g$Oq&fF$7gQ7*$Rqphtumv;!&k-tCXm*a?p zU3)8O1Hm=ZhGw@wAn+v!T@N$5UCblgb!85U3u19(X-7H;3_sC*b?gN3Jz!=Hs4uz! zNsUM>2LnI&40%F2A9t=hC(8++*w2vXwr`%zX`Fbj*tB9dfPR^vM5z8};J>;1HHHhy zZl#YSlJyk#pAQCSHD`Fh_k%w(D`**&PV)DooiQ3xcyEjGHkkV_`_EksHj>l#QO`u{ z30g=_VB!uO*!TeCVj*{v%;1)jf&n=)ChkkJpCv}0Y-G>+)P=|>{l4@#8s+R|x@u}& zzcw=-?JM(D^P5g_9t|jN3*Ftuzd+q1DfD94Y%adXamXyneCbPhq41*RNWzsra3yf- zN6`?kORu;YZ=V(Y5AROh;xs4s)QX#J_=|5BxP)Z6yzoTHwfTg{){Hr^h-lG1+`O4%t{GdVC(zO3w=Qi#nKv+7wAKw#eqGq$w0Dyzck+uk&T}R_#`A4R88eUa9kl`u*%J zFTANm!J$T^YxNPYO&MpV(dG|Iyaji;C=Ahw4ly@!!wqV9sdal*g|XsW1__xi>v`>H z;>p8JOz=*E(v6P9ots}2`y~P{Q;wvZWgqi>ERQUyETdZ64NTAexGO(q zxr;wSf|^mOBLA&ihu*1p+D!-`7yNaPcu0B&d>?f;!gZ;2e6u+_H7@X^M7D3-dz_NO zxM#n#&Av{U>NR=)+sC8d>)LPi8k0DCHa%5LSjJ~l``E_6=)+-hMB7%l^|Jdg>U7K2 z2|0(mUH2N{KX-h)X^M#lGvR5^5>M)!s1@M3EU5Ikr2Z~S1+=U0(|)VxY>)vwt~Y5V z@kLdZLq;J){r{bq^qw?r07yyz0000009ix;000000GwO*Kh^L1w?zqA(I6>FWJJoi3K^9YqM%S2LW72g?De@k9^b#<+i$%d_v3!u_jNt5=Q!txK5^RU z+f4VQFWb4=-jY5jA+2GrCcQ^O+TQ7w+b!#xmz-{0wp)F!XYJ@}htFNFSUcO{ z|99thE?^8-3$9CRraTPO_ISJKZ|Qd3Fr;IKB! zS8)nht^JpIei6^3XZw)$j|9W^oRb@NQQ=Ru+OB6EbYNS^HCEb2z{AZ~?Iy*jaA{+2 z6#GXy_~~?~n&uJkf!LUH=^YugvJ*ny;{J)oa8$&M0L}2QpwIiMuuYlM_U8vWIH(tQ z^hElDUsCV+-$gW#>CHO7->ef9saFJC21%ee{Ko#J5*30HjmALu^&R0TKA+v=YUy5SRVtjMy)m&>>(i1ZNBj;D-~vj!nh*wzG25N zbcuf^;EKOe22(m2VsdOBaZb`fY|DkgpuGeXn5YJ<7oviF_0iwE=yZ^uRpUQ8KtLKZ zXJiP40<58rBelNJp~QuBtx7%+))*_ftxt}C(ETugXNF#%) zRn5L!o(|C4-Cgu_g#-o4jS1;YR49r4@@l-34p$H7n2c;BK_GF2@ME6Sxbg1vxi6h4|c%MwO5s z`T1UczDW|ew~ZE;s8E47R!it`8yy5sUpo3Qmju7kg2wOS+?BrEZF=(;9r8bY@E)us z!2Ys&;P(#>oeugNw8H^Y4aN+ z3Y_{+AocSM9ny@7+j{Ukb5EQ4e!ApA7T2j*w^%xe3bgFV#r;2-ZXlK@xxs|_DFP+@yklF}K(^Hx5w2qg*ZhY72lq#zZT z1{7#t@cGs1_7gnF1H<12FQj`?AwBxy!N+xUNMPT8RhNx`KL3FY_3Tu5!AT8z)YB#}X8i`}ukxQ`r^cx}eM^D&-rHO*5% zjkWipF~0ZkIqsR~DtOLIZeR0xsc#y^g<1usy zjh)KVL!1aob50A}P~l%V^%=cLTN#lEe z#n>Hvv6%|jic-`?SMk{&f8IDI70zrf&-%NU0$cqxEeD(E;8rhux+gyyE}XR2%9c$9 zxwo$CFMnkK-$Av}*!KjS?V{$Cm&d9h`uJ^Qm8NU zmG@*&e?;+gMSi%Nl1%&6Kme6}{k8SQWXPcxURlBUx+e2VI-r06xqh=Z8^~n%^2?7| z1o8j!?gOIsLN?I)N0k({Q$a>g>$(q~lXhk4#`6#Y-p47i*celx{D+-wcOxANw~nA%pmlh`x3;S&9G$N3rLI zK2+c`u)0k_{PRrS&U;uxg3+n@6_O?e+!8aa)8^@LW6Jr$4P?YsEnw*zQ!uHb4Y zvs@?i-(NUua0_*R=rSV}@sn>ZbGiU|hG}mLpNtIwExyf{ZaGuI>g$s$5vX5e)1Mp< zTnLD^3o{w~hWh+6Ay}x50aN$y=?fkrz~GG2UCmW~NGi}{$NIA#`5<5%6$s+5KRBf3 z)1c}d?~)1XY|_52&wFrVZiAVEWVlU?dzDm3)Rxc&DZ9UL2YL~MGpf&Crx1+5PRNYsvOi)m%RT1DF5 z&?Ew$kT;$WXd**CYpZl7@}7s`+9-CMM_y0z&bf1W@cNm>E4g5NF7hTUz91Dc@(i91 zWsZYPe*tLzaBnT*%RJh2S2i;8bfltu?JPpXC&rt}79kcW8LBH|-g5%G4 z#7Wv+$&ly&5wLhsF1ir$v+Y9f(hk(A=(uH5iX8f%m9Oddxv3yvy>j$A-dBI)fv^0M z1h|Kaoqi`zg~+4T8kH?{;OG$gwILhl-RPK%Zvzlufvk z43GWNasm0D=dDC+q%;8o!OZ@?9LS$dvs@2QUp8I|=?N?+!NbVA2iy@4W%SP*rswGJ zX3cHxSBxCEv+1dAj(jRi=o)AFb~E7Hz4`hYJbMnJ+BC-P=Hd zkH6X$P6|^%;%!3l1*Q%lDt+Qs~_hYbo%{s`bQY+<#C- z^R)^3s0q7^Zf;wtP~_5icMIb4#(Iiga5o90Q)kO<=O~~qR!z-EeR=Zyqi^`{$Kbo+ z@gDoRB5?V!Q*li$1D>`WtI`W4LD$XAnooF<4;2g?>X|#>rREz8q7HGQ`nj~F0{!!S z4bCj=ms{0IRw*?CHvZzYoGYe6-n`6KYxE)S7v!6-J5^K9m_p0%LJ) z@^5Vltp9fBLp|zm6qES0;nP%z9PF#mxk3h)X}Phc5jw~++V5APKb(;KcsPWG3a@#% zzOU-98-*jEcOLYNC{B%h=yb6I$SP;E z3J|wf&JBYo^4ML$-1z6nS3k&i#$<4QCTRLMJO(Lnb1miev3@$Fu+-IaIfMf_Fn{n~ zY!P_9PpH4t!+=W~eIvi}NO1mboyKQH3REO6hE^=lfj33skC;y?IF|gY^x1^|q-pgZ z`taRiWnIV*;~OQGGn}Z9>|DQNZz>(O{Sa_yOecX(VQRnERtl{7INNKrg8EhWpisM? z1iQ4Rf3Mj|h3DLJrcd!+uuI#V?JEhsi->vjOH;wHH0hfoK6fmB%(f=RselPsk#MGAzr56^5JLVW*sCgx{X@&&*qjdd+co64j-l$vP zyx1*GcAL>iU}@tU*@eDn%Ypq4nm8}FL<3yOPf4I$7O4}VMgdRZ*jw4itEC<_9UlCd zF#P4w3dfmb$WzUF^xz)@2JRUwc18q(t=5GomS;5h60P+kTB{QtpL=@5Sd4%&bpg+S zmsGfWe`nQ16&+S4K4o1-K2&6EH>+mJ1A4FgFnb94u4f#~KcY!s!lQKN`~(@oq&Agg zadZGju!!(()cr3vdnDV?mku2bH&a2reKC0SX;?Y|L32smIz?nKz22m{g!7nIczRd8 z5&=CnMMieh*kAS20V#Oj(xKno=~@IdwNwEc`j!Q)IH|9QtKpWN9=FjaTaG_GErz(w z*mER!RR{O&+Vw@MN3NKVf?k zG;MuqV$`1plXRC~dg$AG&oUa_yl&<8uN?H_QgK%E_=bF3rmr=PuJePQT(d2`VzIYN$|2z6ys-FyN{!X!KuI+#`&7omcShuad=Q)!xXUW?*HJ-!$&3^iGW+#y# zI(Ihki39~iUlt^HVs8DSGPQp>mIT@2YTj-@fqA#?J?{}ek%8xp?=RxL-mv!OPf?&V z|M8wAzLUJzKV)#(UXNtMnKtRET%@(O>qI4l|3T zl0VR&JU#k{NfGCFHugaFFxGQep*!Gs4hg&h)=I@4qQIsvPuT=#=^!4^V$$-91SO9b zgc#@_+;3YXJ0J77SD!P^|ZciVyUqEhDGtQ{}}LJkz~^E2&|jN(Cn^t6i6_TsGUb%wT;|Z z)q``?DfxY?-2fSLo&D!coE@OidAxmzl>iIzMT51wsqj?2hW-`z50(j3FZ)Y^sq;)p zx$0D4Eg#kQMxHOaHS-Si2(Yz#%_Vv?9;n z?K>pV&P6~uSM-hT^;A%9%qKYB&_VCP_%Z1}B$&^<>rciUw8r~n|1|Dz6s{4P`GSCv z+qe0~dNBX;HAdK??pw`Xo6ZqOAF{9IB#$T+e%@V|vg-e}h5G~Jvk35aTw_CdO$Oh< zwr7Am!2d^#%jG@+yC;%Hd-mKd%divdipnHx?hvr_ zF4`ddDivr==POlly{%Z8Suhrg={xLNwlYz+NR8|OCX=jiL=^X;Qz zkykI6*neBWT38XNiD2;ZOAe+x z(I8kQVn^GKPB6c*-y_?Afcv|BCesh(f#it6w{3BBIDO`|RN5O7>{0o#Bi)b!!>2Cs z{lK}tey47;M>_!xP04Ogu+C+^L*E{+@{G2^!ySd$@Y?3cnByJnr)YHi2F#TL9%EzO zyD?`?$aM{cP=P3u^x~_h!zt(O^fn($ATF2LQLSB5@=FBA$ z2=U+UN#e+Z5EG~J4?c95%TH|Dvx$JUd+j%kr&B>Lr2EAP>KD@*0hYP$063bjBqz0< z29XiGo~k(vDE^#SV1V}(4gWKuf%#%oD)ZYA&UJ*$DCzri5=dOS?%=$Q0((y=sq5mL z7C9F`=IKE`%w_QZHKc-T=K%{*^uv40qy73Y@BEF{`|I9_K6yFpq#pY4e_4F$a`_~% z^WXI-_XGu~TlvVv$a~!Xu?_Jdt}atguBlj|!0g>wr&Ya^6~2;gtcuSsX0IGXpZ2MZ zx!?#sPdX4yO4v_8UfaEcig-@lhp*mg;vDVvbndH_N1e4fRd{(l-naBg-CkV3!}ELH z=}H3r(-EybQAUP-(Tr``=%Z?ajHNu$H_AA3?jAwEYBo)_+k!lh?#?HaQAWVr9+=+`_P9RS$>)7h`#IJ^N7uCs8ds6x1BeMBd_YaCfeg1EeD@%Rx=`C z3z_{S)6qQOGzcqe@uova<4Gk;^cz9)H6ub|n7{69+8~1WEm6}}E=5099REJu7jYgr z8CjcvIPd*LFD42J(D|!*FeaA_WP3jGF4Ud+&*V4LF*)!^l(h9pY$^;hQ>tCxGvK@x z#av{J1lnA07e+;>FwYh;+=O*oOz1SrM;^Wv%X6qUj|`ivjkYZ#o_C*%elV+u`R&{3 zt)uQ#=(Vu>sGo%Tc*_5Q+L;X4$>Nh7W0nlsCyrV_pJYJe?@F~v%yDyC4rhH)_xF7X z*))Z9PVtVL%Jol$g93Wf6E|@GT~(8BcXWVYlYH>xC(Ki=219Fh;dzvIXS~AudNL)h z^~d?T=Quv)@CN7iQ-$1fJkMfW6kCZ90mXWe>o!DFK_sQ4{%8XovP2eny)saDjs~4; z#hfVarDpJWf(~sC{7k)=yYJ=itt@hmSIU%g34TlnVPJpWoc*T}gv5;ZH3y zrk!wiI?_AyEdgA57r9h1cl;{jN!X3=b^3TiK%KyxyE}A6|0m+=d2ypM>Sl=@OWy~~ zk6L9b+nIMz;f2+Y{$89Tl|^ROgF^nWZ1A|jzla8Z-TwJ_nsmbA*&E)x+~}|51ls*B z=fUTJ;GjC3mu;j>ZUfXccIFFeyomF8=e~VmShvNQQ3pzFHXM=mSs>Y`LTR#XpF#}- zh7Ht$FTNx}#Cb=_=eiWojZH8vLp*57X=~ioM*nO>tCf;PoGc#hUt;TkycpgXlg=FY zwd?I-JS7p@)k`R|;+=5gTWHZ-`YJ# zBIP*=&=+C6`HTL)dVN&so@zQsRz+#t$NQ?rKV~&}LWNGI;bf~sIy~zZxouNK!1RHb zoBOND@Xh;6&mHtFBc^3BCoxa$DY!y?yG#X-9}9G&Fx26_>nrNJi3+uA-*TEDPI4~oSobv-d1{+gKihirOQMOfYOEbF)&3@KZUOVA*w3a) z^l57TKNUGq*GA-dooe!t$M$!uNzWle;AOiW0_#6{x5C@jEC9AYtkVYc520`3D{78( zLXLHE%U2%)^hz$vemAGW7z=Nhz4G9p;?u+6Q+NwOUIhz!qbjOuXh5;&}rS)`k1W~#J3whohc*1UMo#k zCou|~RqSLhN8R}xIq`grI{IO8_rLPORPbxb?lnZbyTEn7p(1)}HnIIn(wRX8JQr-8mbbFZ5j8F{!&V(-`-?$egKX!5F! zfYhiQR{wWoh-v!z9~aiaX|t6^$3QB`pAofWUL-@((C=!8E;=|!gff4`yiX0xV@@Kd zurYpSbL~4ikgT4@>;3eH?-~O~?xfJ*kVV~=1=UWVaKXRTyf8bJx*Ww#g?BqcBsL=d zYcTEw<)9DeAD%u7%ZNiFev>_g1o{bbx3*x;Excs#H4uI28i&BggECl$ zXP=a;5dQ|jgDO3EeyJ0F?w?u-F!W(1-zp%(tKxANK|H_2s~g55UdUq`-&(S_QsI|H ziOl6PI*hL~O-@7p(Rjh%po;U=?{=n|3(w>8>8pup8Uf4qd1Y1TWH|SIIN&Avx4`g} zqzGLC2orsQkhSRNZyK)eLcEc(Rz_Q>B%qtKUhH9}z_hu!fh6K>d;i^*Ow=g@{Ybvw znBz__nj07(9=devGxGA#ZxBttTp#yE%m zxtegN#&;6%{pPkP1>}EqH~x$IcrVY%1DSQxByb=bjqKk>1(`*)_FSw3Ltu$*9&_>f zXpwv#T)$tvd^8Mo++~m6D+2vMhaLCb$CYGwDD6e>#rNL0c)m$Q0sY~-4-wYrHxf)5 zZVDq`(cTF@()@@%WaM+4eZ}hMLNWcTpC`X*%)5ShODY^2W*gVDBEjf;VLzK82GrB_ z`F;G5A7FS^B$NXEW5*_BMlc5%IXZ-3Zc=PfzxbV-0=~U#Y3C5n_k%VaY&i~O+EYjdmf!!i z590ZY$6j$4=cd53Y3mPrH1j|`*yRPY7veTr+}e&sH5|IK^S!O~*bC?;+b; zqTg;gE%i#6L^|8BWi~wXA$pxUz#YWdQL|HP3ONFOz`VdZcRR z|HxpJpl5m#`*PUu#vf*!yPWr={ofF8zk?f@FRp&BsCP|XpFIbvFTXoi`k4ffpgsNd z2Ll#=6i3$!65t~_KzbcUh1C0^)&J1{r(Atq^Wb#=^qNu3oFgUxl=KZ^{kG-QUiS;(bIj;~q7eVV@5CsyD-^U~}3@^F4H&xhQT#C|^+N1PS9g?jXrpNPLCOhC8dzn%wnRA`{HoH^P|ht{^8R_q6`@A`GL zZ1e-Ah4G$3xX&7sfwpk;!>_GOc*w{n>zxHRuln#_np7-5`lar&9+AZg8Z=zawlYJ% zRQ1J=Zvf}IzF=KNm42*8rLS3Rmp9gnXP!$1!#*D7nX6*Y3Pc9*xBVhV)H}x9{qF?P;dj@gx za1Ey>dp8}jpS@~+guHa$BUgy$EY zNalUVML=B6%|jb77o6=CEg++>C@n6fuydzEh6;6}EI19c{@W~7wT}U3GD;ofj$-a8 zV~wAcp~94w$5dG>;@tD)#o;d`u&m5{@+b%M*R{V&jA1(LsnoqM@R0=hajia8Q50bK zY`C-;eXJ?Z$2UD1*e{XdiBH&Hvwv#OM-YdNlc(SP#QG2YvCYrFK!rBteFcfwm%i(= z&-VM0K;Hgnt^ww|lzL~o`^eAPRqOU}q0W{YYwcBHr^1esndW8GyT}xJfLbl`e~a9w z1kAa^5sf=0v2JIFz23cegLvS7`Dphd1xUY!O*i6t=7Y@sjSon$OHbit(Lvh&7FsX(Vd$Pc}{!782x?1rYhTeLdC+|XyM6xPA$t25ac zb7d;WwKL3k9y|I%yfoe`WasV=?Kr>t9aG%K5Qhd2@}2dw1EJn*$f=7$gSUdczRK2} zz^*;}WUh_`8S88<{^?Ob&8Y3ycFe8B;RB}r&e_l@xt;f-$*K?9-Xqt;01tUf?k~s# z<{EoUdva-T zJSVOw*sv4EQm^+~XcA!DvMawI@u1U~@{Ds84}0}WJ2BtYjES;Nl#pRA)wst1^T;`O zKc#u}!_M9p4|C(a)>S;*oP#*rvZ?*^x5EVN7wuC`SjQ4=OxUKHl<&NxU11G9e(e*Od~_*j8gRv z#410Ej=#(>1@F1`Fe&x7iyQa47lB!#yo2kQ>D~bm<2bIP|~z=VQOjhqkPp z$2|3nr%#l(h778vC;2zv`SZ13lYe2}ynJbAzf%SoR#KX(oX1vkI!E(U-&|Nb^mfhB z_GGAVWNctCbwVVo&h*UJR9GU5-dj+mfK@?Y!)BIzB%B-^8z@Q_^iICsRRBB&PmX0 zbAW}A`cL*f0pZ7=R9_infW`Nh&PET0{HCtT`%}hVef)6CW>bku742WHWrLbQF{9p}Pp z_{pkBmPzWx+Bg`WW&L< zT&B`l0_wV*Pd1=m;_hlbc&s4+{j`dbX#x#Qx;NdoR_cUn&BdOdke5P)rqX!@D8QEX zem~a=`ieT+=Re&EIMeIzA$JJ#m*%^FH!*hvZToV9Gl~RTxyEPeHX@I4D(E!h`XFYu zl~ahTT7zu;b9H10s{CoPIxpqQ_tf9>pnu-yW%PRs6*L27jcx=pP1BF=kejAE?;dbsKf>&F63h0?dgkwsMl<*SJlqgiF$gzjNF`|O9Ga(lpRk!D3Cr~z!xw@heOZ%m%3kJ?k>%r{)PT| z#B?NE9{YQwNI_QdHRc_~icfml6xe^{2~{8Yioc78$qaL@zVf!w4%CG&_s#AN<9&Z> z96l&DNq|Si;X`ZE$w1sYdG!m<^>2sIJvQM4j0ZHidf%tQIE${WYBC-C229f2QAf5H zdW5FqInP~XALzhywqI!CG+plxhQ&EO-N<92i`?f8k9LCmgKG1`wIrbIR=?9KNdXVb z)5;2ne_P+~Z(ZWp7l-eswk4q6nSM!6s9F8o@7;g?o~e*`CBn^onG7$bm^`-N{!ZSz zQrz_jILG8$*fm0cf?8k5Y4nF@t#wSdng;-PD|-e1a~fRcJ9D7OpcB+C^*r}4B|ze4 z?Nu}6E2)>3{pYbhuVo(Aw8{}+Z=1a@8GYS!9t=0P(_vcg*!`L(1YG)@K?rGzWSUS|XKjGtjj`KLzsx;DuIqSv|lgsFr{;O|Y zDiR^Uy*AUWl{XJOE-3}+M4)ail`NmZ9OPc}C}96SZ3WvHnaR@M=Y^A2k_}uHJ*u%C_5}5yGZb_9uAIn!pd`8_jCcioRMJ*NL`+u732}y&uQP(Q{k0Y*J zFO;1D0^$ptYzJ^&oEwH0oA5julf{xnsDqD+bS-B}$uQI-!qn-ow^&`v|a_zWBXl0~PA71#JC|^{*XxW_GhG6{0Ou63G@6c)21}G>!Zt{Z&lw z<4Y2(jqf^p#4-;AhDNjR1=8V}Yh*e9KN1}K(71jl^6(wm2P$UhKc{~^lWRx+e>C9d z$1S-30k$Lw7rfUc4t9wBLjop==Y0yx6mWjD@hUs|CB}B`LKDoJ|E};v^QTb2F=5G% zy!!n`ihA%#T>qM2HQMiy2cah<+Hd*OVZ&Fwu(YtpAUt}t^^6Yzql)y)I4 zpUAMAZFd9<&etuz-<(~F1e^#v`~DR6cQGdGwhylNYf_#WnN5Y5bBhzHGZc7~vv8y- zhYlH=tC|BFNwB!?=R|TK6)J9Bi5z`{`Rg_Ld@j!2jf(i-K=g-4S3FGC;eCgLcClnV zi-20O35Bgwh2W9CM`!ad1{~MO_6|_S^Q?dDdKGi1$j@2>=r$Rk^fTR0k8k;KAcC(J7(9O;9Sc`yNTK&9`5>Szq5A8ga70uRAU3^ z5TU;IPz8wu%wNQO|4ouXOOwvujW~~YTzR{wLIBG#b=!lOo3vX7OHUylJ~~~PYihte z*id*ag=01NW6vl98TtxE`THY^@-}^I z-)k}~%~O9!+k|2g#AoCE=Vk(}|q6d2kir?-OsDo%gDk0$or zdaAB_6!*Dt^W5fC%%@+TpB!hxoIC2fF;jq<3MV8kcJ9UV=YF@Z*9{8) zJbs{=hxq9%GYkGe2H%9QhWD|*JRg$83B>sW32v8<98|E_#&hBk;`}QMKWiuYOrPK_ zmNx~cVD!7+>AU0e^wGDk#;mcb)S*y@D-erDg zx1Iv?^*f~`P><}CMJ$7krGk;(-B)u&F5C)QK4E^W1MYAY|2D-u@^#~hC?52C*Nu+c z_=9z58N9pc%^%bkM^{@DocFj^uI*A-|LfBY_HBrt)~6XuPYkH=p*$pg8htN^p8TWd zKT|;|x!!DfiVT|68#;2BI|_|y*JaUPvFR<=TxC#zD}XQj`e)Qrsk3u05uYo23^i57 zs1PQdS~i7q^nO}BR!bH2ku5fK9`DOmRrXC6=ZN}4Of%*d0YXLw+d0>uk4iG?vE%Fj z-%G>iIFJudt}zrf#M~!5xk9Y|{Y78dt^c;*z201H&Ukl{3fsaiZB5UnL-h|DL~0SR zg`ZFN6;~eE+wC9Y4Wolec)Fqv=6b`c3mdpAkjJtd4)4N#B|fiWReMIjFXk(|mT6SD zvh9rnXF2xkb));kd;$hJBV6;bZuV~^Bvr6(4YLP*vvHnvwC}II{eujfnoC&-(6y$pC!FIq@0B!Oy6 zcHbP%HQ!^uN3rN*rB8pGUphj7Wz_DXTkTYcI_r8*1O1g%$CKo>$g2%&pZ#7GM?Zg> zQtONOABr@LSacu(>zdS3=lxX33shp>my>xpc~oTbv_%;$xC;*%rxF{BoKSHUmG zJj~0-RCUijM14shw`gxhyonlUkN07nqdx5M^hP`kuxm~B<8$#QPHz4J5+qukp=~%y zff$|(BWg2r_^dNgetb9;JlAU!;RDbPh1`Te;WJIN5 z-k;G3sWw%b5*e)6 zIBl+AuIJUVw)M&+K+I-`op>YqE5lo-!jSiPdDF&|D+x%9KH{?X9p*tAKj#g6ezqip zeGdKSx9Ybi9%AkY3++qM!RL=kkNWeYu8+h?S1F)goWE#N?1Os!X=7Qfd^YOcd`cWL;HG-Lv84z^v69}6qCtt^^V*&@qct!`r;_RJ{IvGnl)A1PKHYrwC;Df z&rL5KujV)sn06mrqOGMs*+S%{6y((+BBE)Jcn+u=xsUQ8-&8I)v7BgUfK+kcA2rm? z$Ql-jJ99X9!wPE^(f@qUDE^~?dNJZ>%kyzN1y1y;7!)Dj4lF6eJwkn~bm(gmHp~O| z^N0RvK0#dzXt`tS_6!m~9i5ssEdY55!}NVK3~>1*Zp8bP1iViLFXU)Z;6l37yIAC_ z;395va?R&8Y=Gk3wdrwNLQedmBSP2bvFurP=Z84rx z;m*)Z9OlrAj;9Q4uFg41M)B zzo18l(KqUAc~x(jCSbmD<8jknRLIvjeee$QNma0EW$8`yAul!_PF5j9!Kp8yOqd^= zSP9pm84}bro-cA!rb7D9<=lVx-aAM95A12hTw~2^WnM-B{Xa71=ZENESTD0X5bHa4 zwd>D8%v0)XmW0)iAJoQe4lGegkTGel@D6j$qnO*YYp8?IRtAj7=m#YKZsM2Zq{1b~ z!U-efF(dwEcE!iYd%fQmHj}6zS9ao5+*8aow?%}PFc%zcE1gOVpu($6#S=yisE?cn z2P5yK!a3FtEMEBDqgsd4rjb8i^m7%gF(Dvf_+BF|f(pCa&9iNBew`ciHmo_841XqP zF0A#=gP*1wyS8rXgd^TRbJH?VuO0le67(o=-hWT3JI-mtzCXNo@cf5TbfS;Xkb&E3 zea8>1v$MrnFMS<)6#@0oF2 zAIfGTphy10A>BJv$f({ydEQ8eH;*kiwj$4`WY+!5+(?B5*B24BsGA(;%OX;82srTH z_Rc4$3*i+hVtf1Ouq};`BNFF={7xXpok9V1zpG=}Uy!fVmZSsGpGXgpL%6R}fh))H z!Lu}+qYZ6geG&xR5)X8~a5WozS@(*LJ?wyExgX~!yr@$$ujA)ksZhj6XVt;;_&mFm zsc4r5a#z#`51WudKrlF{7w5NZD9Fb+i-0P9`6Gw=$j~<)xc?yPxVk0lJi`2UdTN8hg9OUIg!DdvM9bwFLKZA8S}d zoK#M$nvm{9fkcLlmat7BM4fqH6uiQK=Xn&XV9YN=m$ZUCQ1@NmAL<3{i>c>@OZ)r@ zSX2KkzRraTXEn@Rtnt1M3L(2jd(b~vBpSWNoW)!r8(M?9u=HANegyH!Cw{r1xf=P$ z;641qzI0lDBiYWPzoIae>_B}Syn1BY(yGs&{l>$OI{sXkH+g?D6^^j%Z7E0otVpX> zIFn3*JEg(bZI4r6q54BQFYa%WD;ku9{JgEQ>cbt>k>c!ZSKekiP{K-EHP9b=%p2G{ zqCaPi?zy!3yQ76?(SH_jegjN?-UzM8gR>m^jXAE^_dWNX%T}aA8h8ED*`O4#(to&N z`3nQmLJJ;-lS!cDKlS6aHU+F7^|Z)g9aiGRcTZK}yn8+M*w{*jbiT7xC%o5uxW_+7 z#KVTejWf~6pI%nAXSI+&{WRhzD#*hzwElOk3^F)&DqEKz-+o`v-6G72xD6O!I)r{e zcHm6-JnF(W7ju!xtpsHL(RqBzkcvDOQSm(seM`DXlmhzv1w-LozCxJGHgdLwqfa~N zTH#i?3H2AI4(>af2VG|pU3!owofqT!+`=&b+KJrZ+(-fOd4}+F^j+S5e%rpH9`&o# z8t$m2!j58pRhv}Il{Tl`+Pg@=`Sl3j+dkxt-B4OKTGqWbDjY9np84v#1Rz#=NX@`toUG#366Lw;AWX2*m$uMc4X%%$ot5eg>7H zpZQ_+ML8JP|N1S`C#R4K3H162BO3}_53<&Mh4-?#A-C-Q%@1_VT|HkG(!iFB)VbwE zCpQtcbS;635Igd~eBfkEK4$7oLk_k>=P(lj5IAEExpE za;KS5vdIu>=JjL?eBBBv?9esczbe0ui?DA*RUl)!i9Axw)8w)KBGKtiid^;@eb-`}?SL z1!cz(kYqK-ci(~vtve#k8?o=NQU;~MTlJzd?X5Ay1lQrlAK`QZf zLI)YX{&mcVMO;k~SMGl*B*4Cr)O9P93|*X$)x0L?;6HjySO9a){%^i+tUGaz_?`F# zQD>jo$p*BbFP*uzm@HUNh7$)=G!C!&#{Ul8kiqwg*j|ZL#(cqKy8QGQ_R+dYLt8{A z8w48K^;T>NC-*SrxC=p7`?| zERPRY=dbgecxHJp8)WCD=HFAWeuSgR3zklJ z#<590{~7_qIZt|<`SajbJ%gjxC2{=B&A^1+13TtmY3o^j@?KW z(D~)MbhwRx!h+M+S`hzlTleNTp)QmUT5LI`M1Y!8ZqLG6Dr`)$eKx=P{qOXH`6s9^ z*Ii79QZ`UQ*=4hAKAykH+JT@Ue>o}@+CcQ^Js!!9S;{Ky= ztM{(%|9PS`DH(l!o_><_3B>tv88a<`7CLO;Y&TY{#$0e*VP0}S=Jbf$rnj)pcXWs4 zb@NC->TXI9<)HxYFRPv{OdY_IN{F0rNrl)Bwm6?q3b-{*tq;Q-9no0RE`2fssuW*r z9@;{JHlkLZj(ooVdG6tqA`*0N>AiVfmjb&a1lQ_gf8}cLM_Esk;QcAtzMZHS5$j6V ze@4AX(e==pN+Chbk-o_I%@oiWIq0$#=f%h}#Qg~i`eg0pt69EzaEMVFqUBGA5)RGgy&hHGN9$6_);RPEWZ z*|KDK{`6M9@*f5;{F(0VI}ixlOH<`k<7p6BAkjD=(+N-I4vjrVKD18eAiqN29{D#` ztsePs-&99}9P+z!tmh8^j0bz<#J@ z+#dUTWzpz(@C^DHYLsv`_BTG59QX24Af#7U+z?Nu!TZ~*2B;GZGuKUizsN;BSY$gvxG3>Z19uMS+MV5PCz}e3%)tg}Lkw7}+rG^4 zn*UrNWP>06fC z&jf#6Aw#w0wq_yZrMsH*Zem*q&|)_7YuQSLhDo_?YmpDf%ol_Iek9-^_;U2W7ySfG zr$`Vjd7GIfF$cWe7&6i4J0QoJ#U=a&_E$v2XdmV;HicBjn>g=n9$uefP`{M7AIyty zAw!76sR<_3wT+TNA?iaU2rprLw~?m8)S|_IwWt^QfsPst7X!h`bbI2(BpQrt$rv$^ z?}SqgGzHaV5^()gR#K0m!lwf(_M@2hLr-ny+$k3iyI8J?Z~BuDS8Yw(FR*n2U$|N~ zzd8Z0WepExvaRm_nz5=cYW7^mN>35+&ZW#tA9LBw%U0Zr$XAt$&llLt31F{0E3|<9 zRladI{63!NB$d}ZAN@~)*TJ8%i2u6oxVXK@ldT(__@puKCyM0lKV3-%{&kugsi?C> z1>N0reD8DmqGB}qCAF39(pPaGSpiQOt!@&eus^Z>in>40Cvi@;n-1x{vPo)t2=Mx3 zbJh*_S282VJ0qTVTyKsU8hHt4?f;PKj*%di>5t6p2m^ZeYaS$Ho@#u3$=xWmH>Dw8a9&ODR?yTHGnF{gB}9?(VL^p+E^%+-Y%#;_ePDP~0t82vXc$`19U+ z`3qT-JID6k=gi#kQez5HOjl)@{1Y5f?^w0q!13*mBzYU-{1fh|o@0?(9XCi9VjdqA zYJkG44orB_gR33`-g$A|C`V}@cWdT{m72b|SYG*8h~y6EQLiU0V4<8ycSNw96G=MJ zi{}ebH|%Lq{8L~G6n-D`eBGYggTBkT5;;d= zwZ2u<+q}LCUQJZx!)9j#v6Ybe>UGYP?zH6n?-# zes6ZA<5w9~jfDYmgy${0Uq!+L@EyzVBk3sG%gy81P{bl&y0@FCQJi>p=ac*p&kq3% zhd^qfx8I)HidW|@0j_;@bw=}5F<4FbhuH$R>r6K>Q2HI&v#g*dTXG^mCev{!!IGc} z#J}kK14epQ>O?y0+bBWQ1wSV>CggvY)AJf8kCQsMQHYLzf_V($F zKojbmoFK*0l0hZnER0lIq&_GEsp5o(IWiTZZ^H~bg;oa-7}^@cKHL|4PY&xga8tfygJKZQXN%#)Wa zu5cNf%7&V;w>F6=aq*LxE}oWxwNL6D(cX?*eh+SEqUX%lSn}&Ro_Sq8&k?oL_)WK- z*O6F+Yv(=B7l|Y5GJrIKYe4gJm2ipZw9#rLWc)H};e@IVW)@YDWl62ZqiZ; zGz69ZcQuJ)k#5;$1_Hw38Uh0D|6NUD?(FryHGkvaZ?B*1#T%i&FE2f=I8&d& z7`BQpB zj4BHn7@?;1r;GEYIEgXGPUe^>i<0_-V}5{7{I`Fu`i}%V{r3=uK`zu&7g%!v zyB{>AI{Jz_-T0=Dy>a?$MweMwwmjQPS~~^5dfyOpw2+o^E%`pO!W>J6kf9DNM%Vk8nFl3{{YxC> zaLUNBj+0Q-@bNP#4TH;1Zl=3dGHf8ZKpyM8vLQb5n4b^PRr(d8d99K6ktORsp=+_x zmMZtwP|o3kw)+IamRMMgk@X9;;6=(f^%XmpwD{S(iA&;;)xZ|+BJuQ(<@TNI}WiE?Wa?SkQpDWo2 zUvd5`-~v`gDl5gi{<i))q$?4xYkkk zbnp07Ft%{}PIvd_kScILVaR_E=e##C@k<2toim-AOrO43jln_x zX9JalXIIln>knYTi>khvX7lztDw(CHNbWp9i_n^yM9qM?m?2-JSM~(;qte-AGKVF` z38*Odswe{d18fkazONwli4rSr=+yaMISP!eb~!Do@`>v32}rT>6a#UliFr) z5GiJ?rk-9L0gTvX zgYPXabBXjGc5I5WT$|Sxs2MvTp07k}*OtaMZ?4z*nE(8DjT9;TpR91#%{kDer=yIk z;t}vCu|#mHVYU@1*h$*QK7s@@pquL0iXtmam3P4%hR5)!Bi~u$Dlh@_epZ??C-28r zDQ&D##@fFpZb}Eey&3hO9260D9_ZAgcBJc3PB+za12$Efy#JUKd(swUie39uQXTHN z)+k0b&KIWQS!J~6C;HYseFI54y{(9q;ev&K2(Hp<6&^A1x(X9FoGf`VE}-YnBK5;>0pm4P*iunJy*)Sk6W`2 z#=De||KKu{%y-h5o|;vOxcVDAAuEjEIh{q_WQJdK8LH5)3Ive{%=^-BMs_&Izgd6k zL3&6+dB1*HVye}JPQQ%d(&ztNwU3Seqt9w1-njC^IucO$O16!9m zJM30aKF)Wi_!D7r{aEVDsfXRMU#bPwsxN29Z&Be+_=jvGxu)i#cS#qJQVt>J_u>xv zPvkESOWpTdc9)L+ga!%`VPU%$yvpStq;AExjFE!%vJU5=`I5vV0jy4jQE{OPO@yw292(!+m%17z)GAn6mY zr{~+G|89rkYY&OtxyblGNh%WM@08N&2kKlx>v<^y3cIJfxSH@K4N@Id=9mG;&e(u) zElcx}hD<&xTIcs<=PC&gDNFGM;Kx?0OP3$+MCs|pz|3_DRPX}Bsl^`}1!fd6lX7)= z{tO6Xc)_HJjcQvOb5-oY2xu&uY-9I1_)~0c+3g}z?MsaI)f68)N2YXxN`dkF$PVby zHOz~y&g3Dj*>+;VR1$biEGt5#Pk=5*SF&qqiHdmac2!n6pm#Ee+{&ahY1IcR#(7pt zv+6a55l2S}(n`N7DtA;ah^J*`xk!LvrfU;!aF}Yi{r4^ zg>d`Oa$lqSsYLr-P_C8ug(GE~I|*9H#m%Ix`41}vBNo>oj#eV75|2-gY+8l?#R{Pg zch1eS z^@gwKTajVkF>@_abA@|viek8@Ga2*ujy1plRNAR_4DBnp<0@;l6Y;{>cZ7tKS8@r*VFWKZn^R@F%&xZ-8 zKm{cWX?pQ%8vWAnHkHkBXpMIVcQJg4mv*%VFDo%VhbO+yFCrl*rXx7flU$}I-*NgL-x3+5*w*y3c`Ncdec91=HBJ7cPjBX4>$zsn@+B?t| zTZ>|PO9sn+-iO15VPs&(KAB#!?pmdMEY3&2rvR*z6 z=Nsw;j7r%DF9JKWfPFiEL5)b~ZpyFbh)_qqFdXzj6TdR$;v?FwccR3{1g?q^NF`-i zjsC}nuWQiQ>GQCF3 zf+{8f_y-(fgIjHScVsTSdt$#&Uf%Y5d-*GI7ovAR>^I&qNQW4CXS278T5Xon63uy^ z#JHLD8ILl4$&HWf%_!{JIv64%X8+{y^Ir4aR-_82?hU2;=2)9(@vto~JX5(+U7u75 z5&c7kk)1*ak(!sQOp}`f>y*LGZJm3eZ{({=+&)#wA$i??U+0|CmIPX@{Bren>5>2a zv3>^Ni^{rbVuvn` zAXPxt!yRsx(5()(vM|>N@RS-Jo_<{r0o=4#gLjBtBOJT1nHUp8LB|cGyBA7|d7A=T zr(Wtt|28(t&pacB$F};Qa-x7kQvPy3d%YSBhio0c#|TzTC(&}kmi2OspHO!#f0z!n z)0|-6`8*ir+VyFNP6hZum(i~eJ_d~BKxqXp($~15=377VpERQ^mPUjZlen`Q4*x2j zoRu!Gys_gmJ+@39BJ}p+AI>@P%89}RlKaA@HViZDJc#o>=6>~UvA2*^u8WSUM`n=n zXiDjN;ejAa1<7nP=vKK#`SON`w1RGXv5VJPbFQ@_9G6wuS7eLb6EEp=Dc@MX3TKKW zWy;?E8Yom-lE?7K!rgg<^uXhFzloD#xi$`c+^q|K#Nn~)qI9;uFGN7+rRIBd=z(1y zebq7>k*iCue-7UQdbVuR?tjk1`=7;B`#dyP z`ipTtn_jQ|;98pA`wAv=tIaj?k-^5OZtO5O8$vW3xYdZjAg#me{7gBKk4BXj&|pra zn}!sWFcLXl_FDX|!pxV2ud!q@_jSpOmJw&LBNbcrFM0)<>6GP6aUv@@v)`*Y{uhE{ zaa84t2!}fLafMbUxh(jRtcI~G#cH_qyl31*3n=EH&XGKZPL^-M_GRep_@B`u*H%0~ z=0KvsmBkYzOtn3TcS!c88;zizMET@9iJBhaF|*(tDZQv4m*gE1YGh zF%;b3co4$uWw%s=p-wmp&TcFwvi{XRyE^-(BmBniY{$frc~^g}+?Fbn0m<)XAioeN zbqQLalwO4e-g`zOb#*=a!`3HL)&KofX>{m|jq!w}#H*Ub-`VuWatgv9+hFy+Pr~?a zvyAOBVauN@K}>JlWXF-|RAhkn5o70LKxRSx{tYURPQT&s(~uAOpG5O+oS(39mEf8? z-uL&2gjCR#^=>2KceB3zX*&u^w5x*kb&-BSmZA%XDQzycK-~Ub;5WNZ*vsq#AdDJBL`{P-07a3Oc>o6t zzcAEm2%nQx7SR*%{Tf9&=GCaKjMBlXqhkWMHMFpr&suN67CqAs4@4qLNmOeb9V4DW z0$#QIx(26E-e89hlNkcpG9g3$T%UkqGjQ;{qQn}$kL}i98qLVdNrz^@>S1$w(@Lpx z?sJ`D-$#yc_bU#c_KqJAlQYmB;t55qs$2Z$KZ%rS4$xhl5-bQvzyih51aY>K8*mL7uZ{1q4RZ28 z+ftURk9s7N<#?LJtO8HJ=H~xKtVX2wLz=awnPZcLdi%4Pm1ea_Ij(xKYpmP4@W76~ zY{Ly)%>%G?$-ABUditk@M8~v&ZJ*1#d}i+j0CX@#z@%kj(*F4qA%CfV){QmBmf37w z^1BZjI;LcIXLDr8K=O=K=fCB!;c(+jO-k|@6U4j%?E1QT!$s3Qj0)tqz;Kenu@1mB zS%SLlKPbqY3yu-e0kXTD0CKsqVTF$#2_{jJw^PV5tyFDSr}n@>$>4yz3trEQx7c?7 z$QcBBU%Ah7*+R{8W)4xNt#*^u{1Zwhl2dM{B6}UxL+CcWASDM}gDI)_3rP~+0r@=l{nBS8MR;J|hDf0LN@-XR*2dej*Ogm@sA{G{K*!0YO&74A= zN83O_WcUR+tDKt4SVWXrQ=;s4{p+d?4Y)iCCL{3=mA6q8WfEaOH6xeUk|lxb#GkRU zEPv)Bdzb82j|!ZP?n9%k8}QQOJY|=Rr!@N5`Ho{V##KyS5@Rr}S?v;cSmjU2yrK)TfgHWT67b%)@%k=D!>^Cm&O!S>eHC6>4&D>!Wq89EZeoehAb$C2$2u&fk z$4mg!XY8V-luzrm~6Ba_YLladtO9Eb4ZD2p;Gugx6p zfMM~rDTtDoGfL{s3r=cmI_016kaPP~(o1LRt)&6;E;@X2*EhUS(D? zBgdnlEU0gyuc?1<<$@!03&8Q{BTrh3=|JP1+r8zxIr)IV;w>ivI=#FX9?=41Dt$|= z_hT{Yo4b!8>Au-;6|dv1NAW)(3bK*Hr=XR!5v0*i7wtDhbf(hHSbwiDF5g_*AZW%D zV+6PjD4A1bhQO7I)S8gTC~@Qz@=h zm#6ybOeAvn-d6jVUW>|#F5Yll_0(Cst8}rqUIT{j(2cZ~%vWIh zP8yYt2RlIJwpg!czT_i+y`c$aJdoFB<#EsNQU+DL$#>69kT(Rif=Ia)+t3mYJJHC6 zD4!NWh`=wu&wqOup^-o+nw{=OVpp>HS?iq?vd`Wai?u^fv1^4W()t78pdvfXT(8>C zL>B^?)qP`dvpjmwL`Cj51D2M_$vfP^C!{WS-4~B3XD&Od3q-5 zmW|xS6I8;!Zybib*5%pv;6*P^ICV}^P#u6Hzr5VnC}{(KZoaN{uFSjMV54>sn==5K zga1?C!%6#RmwVU8g|u^91OWsHx_4&rmpx>lK(X~J&4{2UgWa~Ced#(C2eS|n^7}RU z9`kLnIAor89@3^N>#T_n1OJhd6dS<&{O;)C1{bg?P(5ry#CPKzVQ1Zo4`ICQb2@FF zT(nquKpRpD3>W#={lTZ?3ArG*uCZG_H5yE|qvo>ifkx8g$dsM=AcEG!hpv6w;Wfmj z+C|T=+JL^Iv-I(LF3Gfh<#2KHBOFz53E8(J*eBt(F=Jyq)CA;x5IX!w4#V!1TyV@8 zVSN(!Sx74y-9_Z8w5>CObk-~9g9BQ`2VBQR>Asg5+34Q>Bl!93ds*1QP8Pd#do=gw z62f627E@;m3cz^l`kBSm4)denMe2sbJ#LpU5~;(Q;H(!oY{Ir_pR`23wmAMr|H&S5 zxCp@DjnDEQog$gIK8($4}lh_mKYR!slFYZtCJcAzl-U+k5=r(dZ z7f)IpXiEa^!m6~#uB}^-Cu@z-Tc6GS*5hQi-&cQj9yPDGTl6c}yI7_@!#_o;%{H|2 z{ui@)oZ)|R91Z^F{VDl^k+k5!wLf9$S)jIdpzT8d6Dc?6I@@JwS@;A(z!%^?OUNk%u}gCD&e}Do+@0u^Jo_rtw2gDA)2OD#~d&39=1Ta)LIr zqD@ehS{Dl)6FM<~MtWi%6{p{+H1hJu;U}IWC10jzTjK~_C+&WBf&`vL>Cv0KPPSAw zl2D(IyraiJBd8-pzSd(XY%`lk3%$>MDI(~ey9aWYhR$5Rn^$!|ha_eU#V0=5JG9F) zH2KNHp30+q!(V#NE2#5Ywf1H7ek_x`2A_c!i$Oq7co0PjbfD_~%aur3t5KF8mYrvS z<{Q|@fJFz$j=ONDiKFjhjkA=5BvAChRyHWW2E&0I@cuZ;T)b0AKt{TTV4OtRPJmWS zrbUBh*+liB?~(}>i|zjrgws5nYR|EhPw5jt

$}Xm{h%fDbQ!RR)jN;Cx>vv)jfHcj5tL$<{gt%Kj^!Fbz^M^`x0;_fYS7tmP z4O(3Y`bKnrvNQkr)GF$EshJ`R4H8!2<<0lB2f|4xvlnG^r6}o_jQ<+OllQ72#%<4)y56@DR{{9X@ zElo6)*PmNdNwope8>#BfFi;2y(_K|t*%h7y_;E?6gOLh-ZdoH!*aQWiT)=SQ^zPKU zCIn?+9L7|mOJx&R9wVjA=hZ^@^D$zBvTvIXxkBVbHsP>S>eD^TD}2r`>Q%0z|6CeL zo~GT&ht!r=bn^YIVu)90op+h#CDx@^ZM)l>9D5TMb&M&{UnL22YUz9kXmn#|_#VA5 z3MEEsU%Zt&TobF)=`XISK5j$z{(Sn}SZ$B`)n1B3NJN)L@FF>f?1QXwOMdlkk7<<- zVftf0M8C1{2Xk-L8gzL%T7zY_069l|0N0#G&74-%gyM_mZo!3=aF%xp-UPH zQS#hhr>^p$+vG~t+&o+4k)TJ#Oy`D?+Bp_4>ZyoVATlqX`CKm^6$F;2#{@R?G)?~* zH4-wbMNP`8CYXWEDE5VI=s{NzuLs% ztrD}<>3tOEkK33~-z5YXH8J{vZa>1mur%&2{PKWEx9Sq$eqli^6yRQHt(*YFYoa|} z{Ewyrj|%qas4%AQn==iP+G_}ZN@74b$2w{4ksI%ICMlP_p)03mERV!x1Q zi}=F0;T$@8X`li&_|Sb#`3i?`_~hw_L_~e6RrYYFAN0;lz+wlI76L69Rhk~P2b zezzL;e&h-Yk(pzAm3pTd4_)`SS5+vIrvhu52?Ql82_DvKQBvnWRc^6Z~b8Jqe1(bw!D@kJ{RA3 z5k_YUy`bB^+V`sZQbCOh0lUQQF{HpgRC4N-Q}bE>bvjtrd*wy@hvX^%v-|fibA;E- zYRq|gFM<~`8fU+&Qvy{M-HlfvZa6wY3SeIM4#FLx&v8}Lc4#A~L6=?+uB!Rp!hyC& zi7D>q#=xolnRU{1#VB@~rq;~`8JEkPh7@z#K@-RxP}@y3!epcdtMdUsXLBaV&FEYk z4aeP&0-NtwnMTlZNHm*$Cti>?dbhv1xUn`p5z_mxFUhvpqH0V9W}>=(OZrlB0Vt#` z0a11Z`I6E*=-*$DzHnmxlQ+SMk9JuZwt2y@lL`qpRRRdbisx@hhu z_PmdMI={>v1%3JPZkU`m0}VX>>RZ=qTtz2FZXR45Y9{jH;mxp7GCH69N)>#qXzLj1l(xbt>ccH#qT3hxtQ zFB&d=&M(D57Th+n;&Z~cbmxFW5t%zcs99IW{)i_Yx$k|Y6y;4Z;+brXB6W8b@^kr% zb;_q3{GD?D0QP_`IB>&eQO7H4=A!TXsw||n&b>zt`shkJb(5b! z>DOLzZ!+T0*4E4%K)=SJ(Pj%#b1(Q;RbHSEW=-fd}q zOCFhTU@Tvgx}1km)sNYD_k&331?xvnK#E@`P0zS&dp|3D1)O4f2;aN%V^lb`T??yy z4m)$Wxa#?n(m5l?$fza`hX1IO!bGh5rF0h&`KP%GMBP#iLd~~#J{0cD+^}oU)HIhv z$*>xLI{rSz2SGgi1U4)po&N{#W#b#jAfeC){-PFnqH^jk?PKBq2LCd>hK;xd#L z@beJ8=J6s+bYdleY$}S{_)U;d0wd)SDBF%Wmy#{$R9j?dP7GS>da5A=3Q!?hiHC7P0#y)eR<|MDi@>xi@7e2>f2#ga)8VhNJmNagS^v`sJm3>f;9c*5<( z2}f0Ytqb2eSdl>^0Vsvc{|3+*}@n`g} z=e;GQ?+m_=e7sfVgH~zjkQB4iTE#^-A?;dL{3jx7kFi=UG$+0;4Oe@cR#mo1?8mU3 z7n*#V>86p$GwOv$+X*&HGHicJ8<0ej$*>6v*^U6#tbo6E2pHg@7y2L{)Kd4SAoxV@ zUF;N+zBhUGG#$`%R4as%_X8b1Z;$MqQZpmR_)e61HWNIf-`PqsT2r&*cex!bK$nEk zIa2xyJEq-2%vvqBP@5R~=FKRri>lQNx=+#Xg$Q4(hKYBv9RxmEy>+E+Ly!WP36;2E zqW298bB`5F+g``#ZFQ@g|D1_L>ERl#Q29!!yPwS>J1h6X=J^REKP8%^kN<)`MdO-K z4Z&EU9*E*i%`G}tgTXi=^EF46&#!>T$?iv)(Rwc?0sEnC%LH3+%;JZgwE51(mB3ha zk?BZu|MrpRbaacTKHHjxhE)MLGK}+*Bx3hfHAO|UcCR48>`;mScf%+UEj#V`i++9L zQ-BWe&-R%wn+=O`pSCR!zOjVmJc{e9J(z3Hf5>6Zd%;5+W%O1!nr4>CsdbNaP=ve5 z&dY6o?Y_MB1|EwZONK@7un2rJLvevot1{^L{;}1icu_5?fz6#tE zjo*L*y#B};^O|$X8L|SBLsm{Vh{GI6jWvV7S?M=8;u_8Vj=eCyM zciB(5er{s$z4a~CZYiD4BdzbAHV=*s6K@tC@6n>8Jl26uj=R>y)V6+i*YFP#VaQ9v zIZBTKi09qt!;!$UZW(&kG@0)6f3MRCSCc(QL*twANN_U!2C81< zd*PxBx)SN;lWY_@Z8vPp;tBzivRt=+T3R7sYlFEdPcfViv?z3+%L4$-AE!;Z;Ns?lPQwNYijZeS2 z>AMNX=pHMKCDvVwcvKgnH&ZoKjTrhwA=UM2tTIxE|Hoda$PUz%_4DUB@pmM1Q= z##s6DD}J>1`*>krk7~y6q{s`2gF5>~!bQ@No=*7Znu1@=ow1Gi?a6e{0$TN$d zYPzRr67p-DlZRTU{~e4jI6zSH?mj?}B(q%2yIDXL?t`p_12v+{eZeal7rO_Y?!l|y zOA7JkqJ4q4pBOZ6@Im*DR1 zE@yTuL`Xlj_gS^4PsM%kl@ zS3f1#5_#rgiKK8gdON_oYP;&T)OK0*2OK;ne0!-~SiAjB*@8dihOvDGW~T_a(Vf+8 z#!Yx^#D{x^#p=Dr-;(=|vWv}nMq!*Vw7fWG<^hs&2h-C8yiJF>k{P#BpTd8vw+yQe z%c|TQDDUBN8o;yQ_7@^q10vhsFxpA+7QeT*nEzN)hj>izUB0kX{)pxPt>{a6TAMgXsz*J$)qprb&aHmh52a{-i`~=rDjV1?Le zQb#uPV}>(X=ts7AnZdljsUBFe1W!1 z=*V7mOC)Mg{kpiO-K8x>y>JpBC9CmS0GdZppB&^zAbb|+`5p)Iu#0B00np8gED)ed za^`gOg9$TqwLmTErI@xHD<~BX7?Ml@C1>czxNtdqSKBxyyi&y1^w2h%1YrEm?`>-g`1^hz?wS2>}|;s(V?( z%%Y4ov_`k(s5<@?mL3<8lgJt3*EZ_4E~o+{V{w(VP9TvWPSo@H3bY>NtrDX5&RXV% zEUZOqU98~{p%>H}ay!JeY|#egp|)r+OXm4pK9wsmSr?67_K0+-h3qg|7!32vDWS{I zPZ*-O)6zE8K#P1>Jv%Li+1)E>wuiq;@P%9gPALNnp;`08LjGeowdaN4JefzWW8+JO5)Ey}_Z&y)dPWS`uzs_Au^o{4o zg^MR3#{0b>x?%SuI27!tD_oVeMaG{wmIE*P*7vlLyAowONt$FL6B&_{%Fq~Ot*foI zMj&<8=g>Ymo@-h^LiU5 zrnzughm3?@f48Z=JBW?;(ml()XSisu#1W0THoO^pg9Ca5B#23~kh5MD^b{hWq_WYy z_DqUFiF@>(PPbOZi|*U-&rFa=yxnU}Ltmc7G*`cIn2%m<^W0#lau4Tql(PC;aJr-@9ZT|t zb7p|kTbD}S@88TThS}_(&jl@A(P!0(Q-9BHiCfYhXh#by5)MXgx&@(=e<=~mc$;b( zrl#O8$GG`a4s#za*HywlH9`;1d+yoGeWRAIuN4vhg7zx>2^85){0YM?{~W$YUYxKg zyoV~Ytpv#6F?u?U;zHoc%1{q>5+ukJNjN1^D24}w_xg&ZAHM0E^QpKy;V3ZZ4p54`pr6Qi zsE~Za9!${WPFL3JN-D_cU!jfDedSeT6klq;M56O4bp>iOP9oOm<&bb?mk)#wI&?K# z|3ch_k_gx~Z);tDiEEw7lzoMF#aV>nW@5-{?R+PO?1C6=SXaFMR-j?8GBO5hjL+|I zl+tfIGM50nUdbaR()VA%kDmSIPdkLPRBU!G|3>+wZdrD~>5-?---JJKWnI={N_cUN zHw5NXVR1Im1!#9Mz@=fN1-&m-S^|p>R@VXhhhz!M3vX>4$>TDzA3Mq;GGukGQh$aG z!K;k>68Fx`ddlTLV<4MW?mszg%f85!u8j60|B%+{&55EBd8(k3`s43Th+Adp%prl- z>f-&Tie{=KDDcVIX~minOh){Ct(VVJbZ5A`F9K&^b9a{OCVlQ1`Ag=lGLOVtRa>Ro zcug<48-5aaBj+mg_Zo7I?OCGCf}eg5Vi2^&;#RVZLSNe`>CCi}luE2To_}1axQBkq zAa}#)73whiP3zX8d=tl|~$~$SWHG@NXw(U-- zPMscrgx6Pf@3x(Mdrf=gjwj8NO}fbq$|Ym75i-Tr9n&0GhzC^Fw09&*5=cj)eN??n zh9F!SiOfFY(qo#}8zp~lxu`JISRS-og+QV&r&UEz)Pt`iw2SflI*j37NGRgx)4Ij< zVJ|JXhrbp>pgd@%4M+d!Y5T7|(^|N#e91Tkc`hp6Wi(p@BBmq|JfpCB<3LNV;ZXK9 z^Ts+v@#J&oc(!w0%cl9v);#~#FKo&w*qvk~8VgO}?Ck;kxp^`WM=gsw-ah)>P$jSv zwQQ5(7CCfB+ghPEk$vnOOd$Pk{DO@E%L1lIcnTevg%i zRpB{$oMAd$^Nt}!gHzwLs1}ayPbn&~M%PE336wvHQW(~3u%&0B_lw54Qx#cg0U2c* z%@&}cVqxW=j1b>&UAb$t>6aYLW)N2Pv$*AyA2Jp@Y{iu{7T-UDuyHrja zgKJ|TxNA!zmHrayx=A?|moQt$K<#6>CrvH@tJqks*vUNO-b3j2c!Li5+Wj=ND2A*O z@os(%e%0cLy&WhroPTz6vySGR3;@q;ZW_!HYDJTnv}|N*WnH`oN`E(k{5Us-c(Ej= z?M|M*__%t8cgvlNsaX8v^jWn`JQxWe>u!2x{@A;rY5gl#_0hF`?1-9%o||6M(Ul_seD z4X)i~j-JU2+O4rPQWd+rB>k#g&eTIVrjr<>=kv?~W$lqn}%YVCe1 z+VlO&N^hn}v*Y9Z%{%fXpG=9=D*HF@S3%@M6{AROfKe+72jx0r7iZg>NsYeQm8V9F zMuxM!WQet6`K!4f;PXee#8YVG4sJj7v#h_&GEUmlIoSq}|J-66O8H7%5#@PH4E@wE zV4l%1n*>j77Jzd}qk^n}GrQ_p=C$U=O^-7kdB!GTsv>1s&rGJigidX-#om=^L}!}; zumQzSc$skyB)F6wiA3{CcU9JTr0TulrX7}!Pcg^f^D65wg=a(eL;nqHA@$8YW*vQm zuZgMo`Y0*&;&M&W2mUj4tWi$?QDgN8;M=x|is+v&Q|z~oV*ltDCboQ z2Fwsw=6+GbZ7An~n zr|D2{AURBWZnTX4p$m5K5gu#NaI<75zMs;fc@=>oU3Sqf-}61z+yC%)8+*h5!FGIR z+o1V4go%r$*>iS`jo^^oH`L^ zSa}B#Sbbe;iB>~@-ZMOH9-Fvf!GWQ`*3-I68JfcFuP&hMzYmxe(jBo3p|*>I#4QV- zN`hTRc9t-+Zd5l{Kf}yPIA0asO~#e}y=?`X??1YYhra=8ZR6R8&1Zt$VcR)*9kRr3 z7{ohWZ6Qc#-Vd>h<*(;V^ux*Wt|-j^n;zJ_5gH!~wwh^_sSZ=r2|gb;xk)tYOA4W> z*oCW#=vnB&BTLNEUH@zY&bdF?Q$o zJlF#MgLlDk46gG;l&!^`+m6F(aASIM(afvB+|N3Bi#3vmQ83QkGyU9or9}7(kAEHQ zL^e>vVPuX4(WE>WCHGi%>ZwC85rvO zF7Qddt2W{;?<`6}`8#e6iVl)P(gx+WY&vG)CMdfyI8WTkMGY-%+n{5=_6^<_hq`t$ zv1@qp?+|!o0&rI9^yeU;f#;t}I74k#cp%F!ruI&>{c8rDa$eBa%y#FNr64OyxB7`F z)$l18*$J=noz}W;jHBjvdC+++IaL%;-tO^=PGW|6jok`E1HJ?dxo<@-f|%p!xgi5r zfzao`xA>be6VBq~O`s6XEs{j4=RGn>j-(lmKmm$fpyg&e(L zbfrN4#t<#}MP8wx!weCkxs{CLiiQ|ConZ+`63ckuz^@-_xRa`Y^eE@{OMd~j)mDzq zb0=LPhmRf>Xcb#8nMSxRu+;7jz|S_U-Bd!r6a>$Y)|>TP=X*Z!Z{MlGPtXaTwrSp4 z3;D2|eyb*{z*m$mJalk_9Pg9gZeR!>rXn=Ki1c}!jqdMi@g^$!wH>OPUM5V2>bB|WEz4n;c5sg7!ZB!V1IN*%WnjQV| zOCLPO|FJ;L>QwXF>xvAn&d6MZEwYlXVZ2t-(QSdyuD6jB3}^QDo01{m?!U#URLJ!A zLDg+*qzwVV=n|>M8^41TL-pgP!@(o_CL8~imJ>u=AuRRZpt7PdLJT!>MjEan69P7mhORRpQCbaGVv1eSk=6orF_QuIy$0dS8xA+2$QCDYcAeCj^ z^+d%y&pp#Y!_^e?yu7zdND1nTlZBV~j4G1`6^%1Va414{Oy;32mr08HJ&G?1Z8{`6 zV0d#NZHWq|1saKOJS4slYCG?U2as5?PN$!X84D=G8~XIpH(jxgrhVuywANTJ2_}0{ z)*0;>b{ryIPLHc=O2Plb(N(ZT*)~xc2|-C|c2B%nTpH=_?w0QEF6ms5 z?p!*)XTKltT)TJ8oH;XdW_)_N({=tog0MuTx~IR;Xk)H=jj}19KrznK>`g-mLsE@O z&{^O|_-W=zS4&nCHhC2)M&z+SPD#RX+Ay9Z;0ZPqNZm}yhka>kk=JYC_Czd`ttPnV zpHk)%<1nM!H$LJKF`^lz{me<$Sn5G%gof_X#e%1{Iw{iw9`y&tm?&IlKMzknzxl13 za*_}iI>YSrPY&y-{ZZOfyt!xig%5Cy4@1M*O`q`z6!X}Hxt->}t8YlKaG^d#XbAGo zsQhLBO(Em0LIB<_!T`11R`N-H1PsF~C7bC{Z-O83(-|^TsshZ**|)_^+Q)7yKD^Xr zHeU+bUoA((HAVsXvGvUpp3rvf{9>E5viX^u7#u-`6+@iy^HFY%UBz$};-oi&qd9r? zo3R?+pF3DQ>!X$`B?AD5#6&(_xbs&&2pJEOiA(wF|JS^!^S?_UCNVqS?k5A`Ez`fE zd>lO*U&ej?-Zo@EknsNLEL~F5$3o!dyHb*|@Ez*UxXs>073oTM6ccGc5_18urzB-} zBUVLy64&R18ufy^+N)jfwQ5@NpOAiLtoA(5c@t+b&PMBM?e672XykX!$dz0Qx!s>q zKHf<90av8LoCo}9;|sfs>qS;^nGI*tMw5i};8|lD_tNq;8wusQIP&*%yAa~w!nax! zD*2Bj8n=_{if5K@-N__n&&z*_?S#SU6eH0OpPqE0tJ<0t;CI$-);+O|Mil?$AC+NI zKre2mQaJG;HAz+k$;yLf1DVq!f?Hyk_Ym_hfe%9FbCT-p1=Q!)NAl!tOPBtT=IDcA zi$Myu{kb6+9YGV^)JeEE%A?Nh($}}4H%Gfk`zU*kX|BHV1dZ>4qy*yd^reCSCI0-+ zoG>+3+L%%5cB5^d{l8k%+YJWFKrsm9L1!a+|J>nn3gXbFt$pD{8vV2$6kh6Gp+=n_ z$x7{^sWQL&skgO`_J-que)`vyl?`1cwEBs3vH2+l75<9pf^1oT5Q&IsOnm5$(;!;o z&kw4*JNTXLjDf_@M#gSZ@~xshae$Y9c7_CRQKFJ$S$fY=&vhelS9ng-^{)B`y{-IP zcdJAuCnC`_{b=6B#X`2eOU)_;JcQ1RkSZ;1eQQ$BoF6Giw5Z&sYU|w1@`IeWBkknH zRkY7HpScN6FaeFp(+8496^D`}*%0Yx4v`*nUd~8xN+;R^`u7xWD?@qhUmZ z>ZN{AeI_gd;9o9xyn89ROjv{0Fm>N~rgt6oFBKFD_=CdUR|ZdObX$$;e`)8Nsbhu( zCipJ`0mG-^b92x#9)PoC`FtKLDu9iywO9S1S#0F7s3%w-GlVk6EC=Ci&+E>_eXG&l z)lBDpU5s_boxFI5f7OfXXR*h5h^yc2=qbHIiBPT-HI-UBLG`>K7@Xje2zMUtBiPE+ zz}59uMHvn1I=!+STgf2TON-YO^Y0Mx3EwaOHBQAidT=rb>$^6?cEKZ@1vk-0SkyiM zeb1o%T8Xlo+1wx{QUBgzlMioK=91ulM6$)Jp9^~FGVKoT35GD==wdu2b|+(@RkjYp z^OgL2l>`@S(^ZZVkI6mAw68hnQD(BE&raK=rm2BarR#r+$&@yOZoFuPWuSCGm7c0d zEi3#hJn94uS<0rZa$^2;k(um7;mz+(Yl^MPya0BFs>Ljc$6$0L1>l3LHrmLP@Xzo* z#<;D0-^q|#+xBhJB^r$gTF+gQb;$nnIu7zX-A)_%4`WlXoj2o zi!50kj7k6#z@MR}cbV}vSe&0`z8^3QqyAu{DAUU*O;a`tNeoLhn;Gv#C z5Q5(ZFV7oQ*KF}Ys^NJ9=ikPp6Wt~K8nYbsX=%&=A5mvJ;y20SzBTkM*)K%}3w>Yp zZhTGA&l`WDV{vZ@BZf@1hHgkBW^4MQMnGH?$|-8A*bO`w5bpeY%FXeLN0UQg zid28)G{sco>~8U9Wg6e#hR|j=ex?OJ;MlLWdz^SbGSA!c^@QpZp;BV+f^tB^H}6M_ z+;#XEmL;}=h^8OpPq}S0Bf?Nu$9A7JOjK@3Hg(jR?p-STq3VN$`Xw92wnw7Jsnvo+ z?^)z8M6W%Z;oR+Edr4@2Au%&a`-B5Gd=edJ*@a#Dmg>mo<2`&@a!v)okDJ}j29_tbig?Yl;oXdD4X@R zvhzMZNAIuf~JhZa%vN+YGr~hw_t9fAa7K^|~ zKO9rwV;onyJr%&3@{9p7D%Ep_xRXUs5SHq>r)#{n8NH%0=FJV1c!Cbdwm1 zyR--HAe*3>f^;Djd{{X8%_)Cqz{v|{bpN^2;FXXbrrjD&C`G`@1S)k}O}B&R66#rdcn;}kx+4KV)CDiD5oX;tm@AM;W$>~&HiGH+pzb&yrD&H3;eSM7YfTa zNI&xV{LDlv)4@0c^UL@f9vSQ@4A^aEX|Dcr&O;zS_pG)UbBRDou1*0Jr$eI=-BO|0 zH&nMAiQe+1_pk^zlVs$)@wZ7Y!DC;-!DlfVxvRXSLbQ?|j5v zUXiv}J#5p$c0(Qa#^krRQencU(llGMju~R9Va9HTJ`9&NJiy*QT%;H_f(TeLCJsMu z9#i%3mT#j5M1reNwUYDC=h0zzuqaN8pB9uh&qpzu`u^{-ajMKUF0uHYJ@c|~IwMhR z{!QAWJG19V!xJt=G*+z4j$sV#8a*|AfsD4Nt(J&>k4RS^&6A5~^}q{uSd`mA3~q8- zUvY}X&KMJ@%4I`weZKyhhJR+w`cSFdgRuJdd~kBWr+e~*nXsHMM&3=td{fGe08#$c zomlQRA0YdLpILF7cHrQ%u_)m^Mg`-nJ5-r#Kq?-kZAx#y0r10J*{HS_0Gubr8V?0 z@E`$v)cnm`9ZH|LUHsnbF1e3w3M#;U`Ea9*=Nt|*oH6vabMIButCs7TJW&U=&uYGA z01L<6E?Y#Uw^xCH{gEEYQ4gNA*^JZR^ghMzN0i@#ScmMFXBOF3qow47VeM?svjV*4 zfd9nP!O_Pw-T23Ta-PY^toX(6^Gs`zQ0ieD9>eta$1;gf*jc_14a>>w%FcR=i@2Y9eCw&#ws!?s=5^#}!`^P4Gmc#8)Ld zQ8E7DUi}s5t*9IcwJG4#lZXOn$0p`1xTbRxjLi~-rJ*Qd^-4G#;*W8JYC@n+3JxvSW3OhwW<3Vm^qfz#!5y{ zf5`4((02?$Kv|wU^u^no9(#DN3k+uwhMb&1YjC=TU`UJQj9;ZtiKk_g137{SoLr z^8$$LBPrLr&rQe4L1diyw~`VvA4rz}UaZfFWpya#w}0!Kh(XEv&eK%2iXDErOYP7a zjgQqRU`i>}$#q8~&A1z^T>xCc=&=L_!FiKz{z){WJks#ZedFhr?T-+B&$}tO&=yVf zmX>{B&<{Pvz3unAuigUCJQu67u`MPeZM&ybf_?lQrQ2RhPVwOzj8XI8-VqpMFoujO zeN5wq+80(LS2Xt{D33CEeUshikPHSv2ZVzz&JwUmO#Z1`C(JzUZ*o21(Yy4PbH)w= z(cqA#0i89sK;Z4QU&ialj*#loB|iIepCY69tZER}UdwSd3TYVZ#c7g>_@EH%O_BZB ztizbONfihDy~A?XR5UR9aav(dZ^4I@rh2Vi;b=t~D=EERMT}KA`J%Gkn#APP5*#v0 zLu;-IB~50MhdM#p>6jB?xOrDQsX5CBfmhQ#R#sFU%dZW3CqbX$jr=8TZoJC^Y{6glA*}6JSh!~lBtC*#HH|C) z?sSy}-x#ls`8w+Tt^L{|6;tKpaJB09Yy9vE*CcXP45sC zFM8JQycuXmHnNP@jsJ-@p+Ec@_(RBadT7o(T-^`+tykA1|l&;$rA-bMMy#_Pn7V(~X_+p9qOyCbj_U(7v!#=-E4`RhtV zx8i2Ty|R_(1Kc#GK@Z$}+Ark;drP^P?12GiMA`1?jR^I{eHJ+4s=uSww7+rpQK0QW z%DOV^;}NDJ?Hs`b6@wPD@w`!=Z{cM1KgZ=xCQg{9!9lsZDJGv~p0&Kbx=Knd zC(P;|4@%l67C6Y#mVAIgY!S1s7cZ~Q%efA!m%Vwq+z%pXC6MP&NZTVdpTMy5Hr@0` z|M=^TkWpuPw`{WmJrx$+-k{JU3A41H7dS(ypOcnofSytX#~3-|piTJ)lJ9lL!&ZYN6!AfytHjS9dMnoP%3pdx++Xo^nG!u*_(+T zE`aUjx&r&8Q#~W~UdL8~^xmkT!O2n_p%rTPYdlqXs)-^3^V&yq>A~*_{iIT*MuCgv z!iMdyB7O#|U9*2ot1^k+j)zUhS9Eyt7WT$jd#ZI3t?b@5v%`MRX7}hZx9FF9x55zc zdubhrQqo!pl*PMn`T_X1-8wo{`U(|ud@F;$O;i`%C(-?97H;Q9g?2;jf&7-Ni?a!b ziN(&buSx-ro4$xBd6b?_h7#_LGGZuCK4H_DCgc~7?%kD7FX}!II_XtG`GLHe8*2Cx zb)vGS%ESK!0uk(ZRnt>9M43?b_^@%8@ITSW(NuKLd_GxyAENz_Eu_BByWjju=egO| zlyu^!9wUHA+^XN|{%faf2n+Qx4o5Ugzy@0Kz0jv8!|ave8W4BF2Ny8u+k{mDy50*u zjmOJ-0Jdq!#V)%DN8uM;7jZmV(e|{P!X~Q5Lezf@V!sqedc(AE#MtU`{IVu1$TGtc z?hgex{f5cM!cublxe*pUm&2sMFxCGU635N0o`96Y?$?)3wQ)Ye=@ati_dO7I(>q64 z;9_OTZPY)7#lW?5~%*N_Ho3(sJ7&oF(#_WYOq+vd|u>?}5> zMHqKGjN{%DM`1v54{~}q$Q!G!re%uuI-5j}sy$rFa#5fk37$`ti>1I0pe-HapOuY^ zOE2WZS4HO=I{t2wvv}S`JB?4IC~$!>X~);Ak_?lj{5n=axGjXxKC-8zO!PF|PciTg zUZFJ~gHSn38FmynyjCN^!}4Qcwx(uVhm-`34Sa9995EdJeUn(I(^q(=rg#rOUzbf? zf(y%&?wtmS5-z#@pp(FJhbpGJk&D&4i-$b?F};zrkMaw^s=3r4T2)2DeDwk2rG-hx zTG0(8KQ11w!Xd+B`8EOeYO8#^wi|Gl4w~=3G=UmLLM6#RsC6Gq(dRiFH z4%orMMsOoqCwI>E*b9-YJV&`hsBddu=(V!@pmqH^Pgl`kHWDuW;8WZMik^U22_KW^ z&oHY6C%8dJ{xDZ^;lERM#pRdOlJGy{wY$haS5YebzVWW^8iIEfE=Nxhknp$Nm{TKi zRWneNA)PDFI)@#`T0d1dCoAlJFvWyFLWNpH_tIjk?~w;~C$64oRmPZ0yqnE;9u}1M zr23Cp`>trg6+`ptH(T3S!!nD_OFynK#Yi6Jl%{~RHwGQc+cg*i9;>1VDHYYndH}8w z7{e+_3^TlpzRwS~9Eq7TgTgQ2ctx&@SoX9>lh-xY?Tx@rx!loW1@+@GRni+AVdxtupy+A5nE zHwa^gtNeGFqkSildWMN+G8a2ReOB4g!XO-u|N8IB9?NPmootLxGvH+@^C#WFqUaLC zvDC4;C;n2;lD?zWI)KH7oGaBEczt|-)Ah+3EjB#tSBmu~N8_dpv7hzJz1M-!I2JIA zH3h0edhsif>Y!VN!bFD0zcIa4k*Kq1)PUQqwyaTNaTxMYn`EP|J3(1N6(cosMA3H% z$O!A$P6H{P&E(kk1cIluT zaxvt2oPmsFVPK43h=5vjfC;iYQI`#4E1#=MM@>Yo*OKwTD-(>g%`~N_`x^?Z7-i5F z??^ZO%8LEdUXL}9xKmlYrmVvH+WV?%2UPJtyb7kP3b=S!3!$$+Zv7_=?ZX|_5F?Ty zMN&3IaLronMxq|rx7q#UqR)F)x*okM0b6VM-(q^AJ8Hp#;AWR*4`6uOqYF5CdnVss z3WQ4gIb)Mw9N9=HME{C-I)+`%7!~SGd9Jgko)^7{Id-154zUN+HGiZY9Jpp93hlRy z=etzGw6T9xn3NkZD#fHSBxw#uv8?}>)hIj?qvxi6tIGixLwA)cD|lNt7J*-h#m+}_ z5*LmlkPDNfF?GX%jGLehiBDJW9=t6yl>{!TEYRFXuw|Wgy07cV5~_lHC-21mfSjbh zy#0J>dLBFXMR`L^$|+BT;Z+Fwljk0dWa~(6CR;g?SVBpZiEgE1JM!MTaWartvkC6s zT|~h+&yCS_gJ%lKN`4^x(s)y-a_lC!j!kR1oCi2?3Y8>Xjv$l2Qq7$2~ z;vJwmZ~AI5ti0_2ju6r)seDZ|F(O0*NT+^t+yNU-l;P%|ZYNP5i0Y9HiNh|S;6eo2 zz_~S02t{}V7yDGGsc-QvhOQSFP(jJCzlG0e#l`3y)DU98h}#_Nlc`EOkV{!^iZ73) zc!6>6DuT7vh=M~y?&xK_f?jkj;;wJcY#ZD^OgG{Fhm7kVReH&-!ItTC*M0c(~9^UkXZ`E zO9i*;jJl?KL*vDK(}}sxfr^fe>~iqhp9>P@aeU$A=)?Y2F-qRNM#zT+`M0*!W;0kj ztFbS~{H$V5JCq)LEaB(l{xs|P6r=o0q6c zR19!0XP81MC#mqeZ_9^klaxIjm9nRe2`rnZvjRH59vFR@a;I7qUDA*+)y+66ZlS@u z3WQ|CH2J!_C{E^QnY(QFX=il8&>M=Um-df~68ZkjWXhp&pL!a5--0-nsJMg{RU!}-4jjaGro4P)g6JV#1T3F=Y zqbqJL-GMr@`y~}~--ZxRb>63#c(^oxXMB9UT6eceR_IZc$GS#IF4F;M(eAXbb{fUT zmjIrK{a~ZupU1D!;p|fA8=xVd?aFHe^KkYcrgq0Ut>5cIdGdz_$`A;DE-EXGM=qn9 zcP8D#^}BPISro3*9>i$24?SVoqo}ZQSgV6%pwF3o`HQNw1Yjxw{9=$o?pI<>AM$<8 zBXrnUyThVNSEB0qvDg-3(#SxNnj9uuJAP03ePsi&ixHp~^Q(?uRe=C0Yw;`FUTw-| z#D+Qbik*O)GADgC_!2jmnAGLYZG{t6yXzY49MlI5gyI!HvI|Z4)|iMD&P$JVkEL;c zGgTr|{ZQA&J?ZRg=QJK}`2u?LYx(L2A_#3~B+Hi+q2@L2Q6y(Vzo zP8ohp%~-D5EG@G3T!?M#OodtA*_kZuB-U&9a&sp-o~jph zYedcszvvwTH>$1blBBfBuv`DQD!y?fRqvkQ|~;i7TncfrqtW#1UQ83`uc*FQ%I ziUTE0q=k%Opw&U&Gu2*pwa0{Fo- zX#_H{XId9SC)9kyH=*r8;KXD^U~Jqq;48A;QW2PWo{E5E?@vxteqq)`PMsE>E-1d*uf! zuhd%`Yq*05_+%UnVY|Qd``R2F8&<+m&IPoGHg!GE!if2AoBOAMz0$iRyZgX9>N`2K z+RFZl4!>A1RG@dBRs$kq-;?WIeP_w`@W`z83S(`DSrP-W-Szl+vo|Jnqy|qCYTSOT zn#WYys;Cs}nZ4mNmxd6ZoEt4d?m(otI8OG{vB z$SL?ECSGExCZ4PIJ_e5R)A|N|J8;vD$qH@5gV)gSV?3^3rq;*w??aSdLnq7uP2NE3 zL5g_0r}Oxqb)1&_n2Xx`D)`X66e@?wJh#5cjI>73K%jW{DBk7SR8zG6-=w2!C&6Hf zH*}JXg%R5@b9f7U z4whB4U%cC_v{1;Sv|Jpssm>qt5881fIAB6rM}9B(4_vnuJ#Q`l<}oI5KdJnyGCYF` z{VG(^Kx+jMe~ICpzlnR+sUDvJ{ct-K!nI$;Y5OAxYec44oZ-ko)vihP(&=KYXVZ~< zC;uf8N;>T>+%odkwA$aDEqg5ikoljPc#OGd7cOq4}GN-Y*tWZ4yx z4J~8NZbY)je4H^@VsV6=LCfLsz54jvHE-cYpYgA7TKWvQ{zCQCts=C85JL zrqa@bL_3B6ZT&VB^RDisG?kMWX*iwqEvaDax`%cZvt5~!cu-M-t3A=)QKRgG*(yG$ zPF{UgiMbsEBNBbc=68}^@PRQ_qvw=;ggj5)v+UTz3F5yP$Ahq*|9yF9aBOMa#b-MAARlL!28MmqMv}RrIt}D(xmjm-a@?+C0i4FgGD&^~pRTc~$L#?jtYt>SFLzwyYE=_NI zYlwoy)Qvwuz$~JTRxlvFS3-3;(Ch@)PLw8VxN8E}>5oa17^a~P%#;Y^$cF2MU-Z#Z z-^lO2tirRcgt8|*)Lx{U%kLAYp?yfBIZWq z(gWYLm4^a2XFNlXn1#~52OMQm{NJqP#qZL%?6WfuCb6}}%NG!UYmenZ7WImUzYO15 zozCDuSD_@~MFoN*DY6Z7y-3$-Ll%Ba8fzOe4ED*^YWVaJh=!~T;$w=>-PK4Ry%mC9 zLh%f)-4b$mj|Jjo7rWDzG3qpu4Xp=QnKx_t7ggqvi}vSB;$iuqe>c~Ezmh>;(l)#m zK@|&|ejI@cOKAo|$E$R*RV@?z=s@jM-(4V#u|e*iNVQttT;ln?%N9K7Pwa_y4G0r8 zZ}t4fH<9TK`yyi6k++a#FUum`{c7FM5X=-^EOdPk@Ar5Fb~_I?#UdflzMr+kXGTxN z%SzXlw?xo_ux_(Y{7Ct7Sf6tg>V(cKr~jOYPmdfUn6h56XatFj$ ztG7gf3Z}rO-Bo>pt)M4IVIS%rn?*BWx4dY8HNRr-XnV?dJwJcNv;I|F%rBbhx1JwU zC-+H$HFWXP3*Lap^DQ=D5#+ZRcXLEZBoP`l?wZo&LuHRZrMFHXX;|Ak7b9hvZ~IE5Bvg?n#+0TWrdH}nEmO2j^{fNT@?|dFJ0=9kqc$p z8o7PK#oBwP8KLG((I>W)n_x!<9L800C3-jw1yTjm#H#ml+Ix9Mm1*L`27Of<)l*G- zykM^uo(_qE0Hp1He+8l?dmtCygt*`E+BS;Tbw=Gb{%g`VcE4&{uc^tfE3N$%p^N0d z3L?)@6Y!(BU0O|!PWl~?meM<|w^8GF6p2a%m$l>eZPG`Zr@z$v9M9uCw@o@V?HwTG z9%$!D?f%AtuG+2-6buV_K#~qd^f5}Vrn9^ygAwMzD`vez5PhlJa=(*US@hJG&>X`D zA^H1*hE>xUd+0J`;30AF;%n14X3OFu&*I%bUA;?6*$^|7-F|Jg0@_QYFZO$r#|;ne zg4s#x0Sr)ne_kzV@u3+YLYjlc!n)pp!% z5}*Z`Tx^FfBs@uZV!Pwxtn1Nz9#LCdW$z3Y5w*FOSt79T1itX}Ic6bXmeB1pr#k@D z9~vuaIubEY?tJu7qpBzu&uCM#L6_cVmjaf>gE~E75ufdcG%G8yU;|#%cDVgg;2s*D zWGQ}*!th)ojeY@IWV@ND+KS0>kExwi1_yko1gh$qyp%&))U!&$P z`d7Vs@Kro1`eXJ_o~q7OH47Ug8cjl`AG0F7tZe(m{Dy{%Uyj(J@C%tOY893G;%gA? zjr16)YIC8b(njlIqB_i}k4do^zKFc1;J@zYufbC`*$le-&9{6ndJ?yJ7coD9R7h1v zu~Xq)O^>5Rw%%xxs?oV+Bb`^&0m86Da7P;EGyO%5pZj7D3e?eTDChD+cu2~s*busm zKLeZOeGViPZvGMN29TZShCrF zRzdtNFp?W7tY_O{@WbeAeS7!fgyTGpru|+SP+FYuGTOAz9~nbRl@7n21wQ(AbLHj* zW63Nf`^~QqGjPb}`^;_ikFB%Yid7wSW&pA6ulwjs?xLr7yI>!>FR`iPyZX5ovEYZh zwQ0Q;o6;Mw@3$!+-YjiW0F#XOilLet`+7^`nvK&2K_h$nA6=-H)}|clQUqb!41~tD zNVSn;0y1_!QyU*%m}^DXRzo9Ehrn0*yE%RV#j8n=!9n&@k!~tTveletwM_26Z`H&6 z=noeyo5qgIzwE}oEzye{VF&YFQTn`}#9w9a8K`OyDx#;lXS}#mx~PD4oQ7!2@dKPS z_#N@M(`-(+U-o{8&|4uuvt1W(BMTdD`}Z<;xmK)pAUN%mbtLKS!cKXIWj}`eW8Hzt z-RB$=C7#~u@51EI`T>L+pH~w{{k_blM`(E=L{n_~8z?BIZyBKzF&GN!vU?wdR9!@b zzJu23qDBGG6GS-m#&7$wQS529_ZMAYSN9vUZ3Abo~rWG{L{w zaVL3${|}3KUB|-6f9r#W7U^cF&U%>ye@?bk^XM&8^6knR+p}!<^1d*i{LP#DgIsdM z;RhBk3o3#PZZ;H)$=Ym!Pd2^($+6g1yWU}MOpLr+Df^3pPV};v{1+Lh+nJ@ja?_fi zn&wHd)9dsi4isp1(O(>#TFOLY-vBQ&pd`-*=aYSp_D#(()!C`007B#sYxqP(JQ%tg zI%Hhy(*7#NNBH@&mes-uMuY5$9WX81GrHl_^r!;K{oR(Vz~j53lzCNLMRvNs^C<&m zT%dla9d&ARYQT+uIERDCj=*d!A2hp3<%0CRhRWu8im8B`Uev52{SVOFKm4}&)sz&) z@W;#Uxk_2}$8Btiv>|?2hksr=X-$ZTX(m?WnAA#u;W4e>C}_6-yY-lq8;_{9ytOMM z)3?D=_C-!ud`AA3*;gP(#q*o>X{QU6xh2;j}4s@*PL@sLR-OS%MahAa_r(jP!N zMH;Y4J>}&B?)HHO7V$q;R~${F0%Mh{pm94lH>hr@aM*YBr>D1F*t-hwkNW-=s^7Mf zEL{~ibpduw1Bd$C9vYtt`WCVDn8clSoI|F}PdGNvWKQ6iAo8*LWgVSQ!|H_7n<<@l z+Nanes#51Br+KsbvLj!{&?5o$<5c%epWM7pEa>s84Xw;>2KFFbm<+&F z;X#p0Rp? z;KN<6xcHi{Qb@UMK_y8dlaX}%f-Xe7fN!{(4ih5>8OZdQ;K`lN%*D#r1pIgH%GNc$ ziLPB=_!yQ_y1bLWRCyP})P%KfRGM}BOS)I@(86ltu}gJdSAI=qG&NKqr>UR%^wX}+ zD$DmbC!+O1-z_{_3Gh2){k#b-x7HE=i+|VTE$oIhA{~nZrp7#kVkGWVE%PO{Or%WO z_eHdZLkPByQrSQI;8??Y&AdZIF$^xZEmY2hs=U30l1{F!ppsm73)ge$S%%$gi1}MX ze`LQr3eiv6ERqk}RIb?{FYy=@H_E^ZMoV7I-~MGtro#XpMZ7;@#2~eNicV#o55F0K zm+&p){z|T>?5+R9*Pa0T-W6D7*9I-BC7we~dY52ms}tmF*To#Kd`X^({RpQcY{qlj zwxaG&Mwjio+W3D1u)S>CKJ39nOF7*H1A$nd0U2?JjjRz`&v5hU7V-96oNCc@k*>-X z#>y0UVdoo{t`jjog?|`xy;%rb^q$D-W0Jb(0=T-A$5ZN0rsZ}2+jGr; zRk1WLB46}D*a+D!Q1j^0DO}>?&W=yK%g2Ym*4}t7IClv7{TRX76q?E#+yuMxkKgM# zb=`Ov%bd%-*B=PWv<)eSyrc^IhSMh@ldo2ai=0D|_H~3-zm_}xuy(3vjNO0N(ah2=#(m;zo;G(!aT}^M=!~j8~ z{p}{?6j(^l+J80X&sbl6UUxYpFPqrerPp`5xlpObH}G)Ra>v_w^}EY*9=!Ry8hJ4G zKwGd*_U9(!K!LDgRNug_8>0RzLE>=fkqdh^yw}K&YD%!RzcoWr23ZNwz0R8%-H8As za`lh#z3oSO-4tzo@6Rh<2ne?EoQW%%!G#32%fAd3B=3>p&)x4Q5vS=u^zxjRfV2*# zjd5*z3<>Oi7-U}(d3~BMu|UU+xsmtvr>PgRRSx*f`z3~U6j#cmLg(zE%Es^TwVvASe9INfiW+ifD@@pIG$u1-507K3qjkr1}F?YSV(+;r~h>@sw ziBDs~t{>YltCblZ3=C`b+1P-jR-093fPg^!XN8CANuC*S8jH#c$=RAu?QwMyln|z0 zJp(bzl{7ymQWo{ySHoV&4enkvIps^k$;YG}IH`BYW?~_7Zt=J-v0FQ5RYdX%k^WU! zM3srR`$iz)!QU+j^H{Iv$(ezJE;NeS&p%7P@JTuC@KUHP58sf9uswK)b@X7VSB57j zhlRoxI%QUZvZ%0prakKBErQ`YTd(t9=*XaC@6NxyXx65~FPo`rGT{e4-OK+;Kv>6- zG20c~(TR$T0^7bu6TjQ@{S5!!nO1%l@H8WoWLCnwtomc|C>V9g#KDYbEMZ${jcb(IBM&ajr;E))$x~1|zNpSib`@GDrf9@@593^b zR3ImuoA6uOrZ4HhexY?79k5ZI5)FtQ=hHdjJp7q#eMp}(*lcV~t-F7{&3hc`9s+}= z2-G@Xo8|qOS*(PFQu6_%8bW5MBzd9DzwhU}r}ai)cflxGlYP?vi>a~A9XSe1h^=-B zm+g^AJJk@yV(dxAX=g(GW1LGBFs~uxJho3>*6wVVL1~Pfcy*zDtM9p0p!fE<&Xtn% zM~+|HmgVUX^tdMjEb;`n2`>8ieYRI3Sf{H@2-_SzNd^fRbYhCZQYlv)7Bkd!nDyqi z+f9PpU!9C;7c$wNQj|9J(H1+~)KYz^t&_ED$3G;MyD)R?oFW(yF&b@sW#u|x^Kd!2 zx@!=80+H~ph+S3N;?kmTRGV)1)d*e4Nu_>!eMCALvs$+zi4$=f0G_*$vJ@L37iNovvF_*k`*pyVX;h!Y2vbLY7 zg(a@;EHsWSesqai=Hho~#+7u&05j<>0x97zZo{JFItiE$8~mpxyeOY^@RzC2_WkKc z?f0`rrO_YO?4D0HNKQBJX0cr>@}P3x&QH3e@li~OX+MV&Av>v?i>Ho58kESa@!&j1 zvKsqdg+J|M6h55?ws+)^qB4_fH^rmp9GQQq4fbk) zK0V_76P?|$PV`8Wt1@t_h8Bg12E`AmpU2~;%M(dN4C9vV~MJq$B)}=Dy6!VEG3KpbM}>T7h#hN+pwmpr_1Y0cTES_AVNdG^{(@m`D61h zzkU8C>Tk2(edkR{OzGbN-uSUW3k!#Lwy)PAlv7)vJA; zn$XjMMRXVL*I9k6nLIg~%igi?J$b`2XRl}xb893 z^w?CD<*eVJPS@-Zmr)Q!QgjV3A2J2 z)W8s2Q~ky!97;ZXyIyO&=*h%F#Z7d*vj^J=s8tWaXn44FLaM0MNhoiwML)UO9s_eC z>Dx{wGzZC#S?^Njlf;);m)6~KG{9FF#ie}8^7g1 z`^5l-Je%(-^HIQog@fp+)7G;RDv@Lob${B9BekULxj|84PS{OE8-!PNW2kbOFWgw7 z@F6OefbgNb3%%9#k8Je05fJpAF`Z2adL*O16t;Hl%GC7KQD?1fgVI=cR{|{li-Lz) zW@CgLn4u9^9LVxWAV34_*#hFTd*S@P2C13R#;o^A1Y~Z1w^o0vGz)cGpd!OuojsjT zzTo7G+)ln66@~)uZ^!hA^wb0M@IrE~)A~(3CWlh!z@kdizvWetwb`{6o?I>4N>NRo zx=)`gvbhff`eLUlzu%mnA1F#poj(?x;riALn@DGm47qrL68P?l;;J>8{T9a=xrU2I zdoEP+0V4B`_%ZoGB?OJ;R2a8z*#+)iy_rkqkjscD3Zrl}#sg()jL8Z$<_LKw$20x< zMB;Z8lj|B?Wt}lVb%JADhNjUuN5bwF!U8P&EFn(_vkGx`z*h!^VQ$q`k zv+?XgH~Pfer;DfUny8qhbKkTBEjMr-Q62J_&%c@Vz)BYNq>EJcp3B-eUdCJi7v#E8bkvA*y8y7(WTS<(H#<<0m9{Y1*U7E~g# z&rRALzx+~&a&gUOX@;-HzQ-}kw^g|+-%LM!rHsS{kIt<#*V&f=%-#rLelo61q*olX z@A6|eA~0*!<>{~@2?#wRo;itn{no59^yh+;7WssQ;9WbB0+g>mtlnt73nEJ5Y^}}= zJ%qr#~6f~kXkjc5NVp-9>WP+t=A3S{8wO5hf7GqcINLr$({u=Cbh_yzNP~DfPTh!H_ z;-B=LFt3%DW0Rl9PJ?#xXw%< z@6Rqhg&nprU0uWvRMc;O-RoExgWkdA+f0VoTc;Ax!B~fKybU=vjo`uA&k&Q6Gq3i< zo5l%MWSWO#DE7%-vepE?EXPAsPD<*LQj(h2YnWga=3DcbexJ!+EO) z!wh;Xe71IyaA_mAUOT)j=*~M@Z{TwkA=nBcer>q|)$Rw-8M1^BwIM}8b4O!!%Ee^v zzG(*=z1{9mxK5G;Gz~P;gt$>qVJgxk2_n1G$9jI*^ehN7K*W2?y{&@elKP&s?hZ!T zPc+;)-VEn`PQ(T(`B)hqhS?&~@S3UZvSTTG%EZQwG3_}F`yM`fXdWZOIA|`6j1#;^ zZKp6>^NI+D``yrsZO!b#(7*{eu&>5F6F)!0I{wZ;K}n zYl%rfLaP{m-#hOL{uWk{}s+8?BO4vCiMhG}ww?0_>EL zL@O31?#w21yuxaL5&2*kbJ@Cjs5b{+Ov2}R=_T799ml5``Iv{vuM-o) zx)sg6bCs;75L++k`h!s};MTy}-$h1#R}?djJT_cCQptazKnUQ9hw-DE5nmU+n?nQ4 zdOj(C{MGqYCW1(H4Y$Qr&mCRgwc8=Nxr%f+Kfd!@>s6@Nm?i7PPP;4a3xNMeaA{Aq z^s`otNA41vZgm{LpDYDF#+7hTCWXnq*Dc*OvIQ1!OgoXNNrvg{ZaK%r_q8&oRA&5Y z_m1(h@AvFL12<=fKEC6H2@CVLiRj4eS(#-rIY10FRh^}M`MIF4CV4DOPhGWJf)~>- z4s%&O?;p3(MxtRads#~VZ(77NbC&h_BdCt3;ED`&t^-m!VBibQoorr-R^JH1XQeLGbuLY!?mNq&;S@9a^@A|36S;am zIfT4j;not*_1unhd{xN0)$rbP5V0-5m>8HF2hYx@nl6-pEnVf=Bf_S2-$I8a8&Dy~a`7BYY zpUc#u&XF+m*(Fl>yrV(?0lH4IarRVQ`4 zRrO8_4=X<==5+n@eJQAZ`aNO&`u#Ni3GrWInHJh2X-*^IhH0tmz*!R8@7iPs93ZmK zd^MLc`)G1gfUoX{wRq&f11!3}=oq;XA|E&TL7po#KHPg}O$xXS$Or$5W;vQ!8B2a|5lP*mo{*VA7MuDpyumX z5#L=Zfn}7$UU;s=dO5XBEp&-uoV}=xF;DQZ*2)At60U`}+Q#o1cd=l}^pBxEOVH@s zaG`jvh?WZ016n;7MEjcIg`vUN?sh-`Pya6mkN!hE-J?`I*hgtoh1OIF&Dzj(s}EW+ z%={fiQ!5J9=t?)&$e$cOcB-Lg{j*ESkp{E9zP^msZh(S(7hY3wUXj>6nD=vt0Sc1Q z4vAMe>NWFAZk|(76m>S0Wqjos3_DZ$Nl`;w6I`XJg_zsNpj|iTxqYeDOeB zD0YB3MmT!*`7kiymeiKE%RuT)?l574kEh-LxROAK)WbZ}=QbVl$rxW%pwj@<^BesL9Kl&25Yq3!p>C8d6o^}p(ihx%TM&TJd6j)V(LO4t4Ir%5{0YW zC##;j$>R!j9Cj(&`Ss6&1Vs#B=H(Tbf7O^u!zFty3*hSkfV%AVcgH5ZyBZ-W^`0JE zH}3q}&}%I=Mrm^i_y~CC`>oIYbc))uLQQ0w5UP8rqysOqDn6!BkNB4V8U97YfFC*R z{5)%t>N7|ZTriXCRCS3>dJ!q~)n4NEB}((Y5GT>d#JE*={>AG?4N%0aPC6ctYE>x{4H_S@j;vo30d@@;I(C8u5^uSZB_PA6V3kda7G_gF>}#v|R| zHjf0Q*|IjUdm39iYt}O-EU%urz7Z@w8AI99%S92CwSBXCKg2$sFF=WQ;yF|X85_bH znjC!`zLgcDfKg)P7cMbq#~tUp%v{;ru8H^(u}XgvL;UIeZPt)WQMzMbjI||}WG@s_ zo7bjK*3?h*9F{2&BV4qeTxMQ9us$2nyQjK&(}tJFlOhRN?1~}%o^~q+pcsMUhyq>- zy%f5~$+EAg*{=U(YgM~ihNn6IrAw|9K3;ckE@fg1gDmeha~yspLUpM4eTl!(H1>&G z7`IFD5$TASYF>gOen0`=JJ%BUcN0YPcqm4F@afe_^*wFGR;{kDw7ihOXM4c=cJS+G zlAa$<+>gGbWx8FzDe=E5`%GJa?}RBqiPTH==6Ai4-2b%Lv*t@UOGJE6WK{e5!!C{6 z?e1FSh3441RhrMOH6~Bwbl<>7=y@k=K*HX!l}v)Mcb-d?gJEN^=ioGpC!U-0!c)WP z2^e=3uzpo+0Ruxw>L)FR65qHLsWv35x~(cyu{@qN*R;9HHEq#eRdH9>MmvJw)EiA| zXA>Y<%(r{F%>18pdR^EpzSg;oQ_GCEcAP}7UIsAx>d`uNL9m-*vRK`v`O&W$&k7h5 z(X6WLomuht0KS_$vVMo0u~$3~!G^FRri}~Jbi{{@wIGz3w0a?Oa5Oy7)a?VKVwLKj z8GScAfXcRfS9tMCJ@$>&kNFoCEE`Vy)AH5PRpv8B={*73oDP@!2U%)PBjP%9+Yqxy zH?w9OcYh9Ltt+QTX^Dk{m1+1%*%$(il^hcI?<#d>YKS|JG6#eZ1E2So{*JLNI_THb zMg>2VH1z7Ajr@+vC%YvUw_Yz%{3+d_PA7qH1R<^!`usHi(VC#7u=SUvJFWPtQUacP zV)ROrMARh(7^JhsW*3fb@*bJUQ&z=M7Q1?ak=0_V=M1eT4xv{?q3Gu~rxfS$&@u|t zUh!-4S~NM+EG9YmG1*3B0`}@qLDA8~XlW>Qfkt^mTrf!+g)zDj__26g$4wu&^t7&l z5t2$!-Rc7>%EC1Ev<17_eAOLFuL_TYbv8fm_pEyMOc!nQk85-K)@LFja~GB|tNdiBG$fz53MhP$T57Syvn?Q&YP%uuBDk=w#f(_I7MV#1r%i zPg40B?%5NN^5*4rkCB@>bn$TsWNg%CIhaVv-q@Qx{`I}z!dxRN$ilhLMU1$FjIh1z z;5z7N=f`CrIZs4sHs-iF4Y?s36f{Vd7-Tm&C)e;@@R)bNfvj8gaj)e5%XWW+x$?snB_xIC3;1_kNMc$M`9GvXI*!94viv6 ztgH6-UhSP`RWF*=Ir#RW|EadC5~S{K9SZO{>#^P2ofbmN<5oM872W)*pz4p6D^9mA zOH=-w5$#^~74555t&1kWN2)(6X39Ps-7rvH?|6U`V!4!&K6;L#(O>_9Jr<}cI4P6Z zz>cI4zo7lnlt20luiRDpvO@357Qt?{Uz+o$TsEvf8iLR7-@>p;(U@N#WE`|g8kmFJ zfkwuord7b3+H`9E6x;svm4imZ;ug%%CnxOQOP|M02}5556GJCQ2Gd6+T2d@D4o~F4 z6OWk-@CkBdlV29BAGP8#3Q$ScqM~uX>dwVz_FNrP5?rPwBgQGZY~w6P^_`c@BgWNH zw{BLdc5Th`r*d)SyE@*zbO-hha~u5Tm=XHnh-6FzpN2{$H8H>4haatv*wknKY zCn0%052~GiuiW^}$m{WZHUT8Kq;P~iWkB@|yZiQRTELUz`RP>_5o_>gTHRN#Zh%$f zLNlV3qjHc-A}J}5iYfH?+YH6tvFn6ow&7A>6*mu6x7jTQJ8+SEn`q&<#SIUm7^N1% zk-BOi3n2-&9Tc7^%PWr3s9}u=``h({69NJ#{M+d*1gJ>2uYA$b3byX>_~fBfcU_fkN9UP4j=yUi;bw1%i&t*!3tX zt>pFXd2t_fd_^{fjBRImL{`OzR2^?gUFjwwbg+DJJ~wF3T*O&2O*-eW*(OaB>pDRAQ^Q-Y>+%~uJ_+6arYGb9i!r;EV#!~46*G~oYs!O_ z$TjhN#L&rqWd9Lp49akV`o;K*MspS`=REzBk z7Z%!N;`13z6ytwG0uIgxdlwcI9}m-D|CX8`Y`sbD4b6E=9Lt|M=(;JeS zInBCBpd7M~+15dh=E#;b_i$Q6RQc^te0H9+$~!7@{q3_!Gn*0dKuyO9{hPG{)|<8G zZ@Noph70&r(`d!}S~+#AQxYu9N2vK;8i3!P*o?9lBv?DMSj)E>e#*xuk2vUBEUXc% zw2=%EfrouAOb^C$0~YI=**u!OzpWjtQ>2G6(dg_3XKirGNxje2$6q_=jBtS*{aI-i zwt9@Nmm_N=YR)w|v@E{<_r!0G;D`L4g8e?3bnU%Kd0Gn9x*%}eb%?X8eoY|XX9Y>7$y}z^0nsUlC*qaoS0Zr=Gh|qAMJ)rnSQgFaqu%0y?mlb zwDSTXW;_o}Ju2(GYrl$46wk9?>-#{IIko@D}(V4&F|OYQNPIvau41c^TQfB(_2c z4=%zi^LVn3KO&3riNc$vW==d`$#;L-?Mu{B;4y}~(u?&ZH8V*m`=_dLZF8S{Ryi!G zX1uQ?L^PvAOp@UAsK&|~G4gz~(BApbk`Qm!6g=PP)&Jg1{7{0S{xwi{5;T|nbOS`W z0f#P_pX_lZT5DS|!E!1FY8On;`_`rLy_P*m79FA)(Eq)l6c&7d|W z=Qx>ArQbOOODkK z2KX>ufMU|>*G)9FTSc3t5wG$|qiS9Iv%c1)>n0;>>wgOfA8B5(cKv%4V?AXS1aZOw zZE(UrT>s|Y0EQABU7KJjY0@8@t=md7;RkQ*W#IKQghlpFR<2LAmQ; ztL6gmCM9Ae)iGg`_3Fg4mkfL5MtY(3JVWdfp@8b;wQWKB(K)1Mj5lQ4N(wLdOe=F5 z;v){d{A-rk&IU>PDc*UdbIuiQEsrgic&Kpmx-dVlUk}w~quW|`Sr3Bq6$D1Sw)l+# zoy($dah7t54Z$<>ZVr|DMHA1`d*mi^T9s7ixjk(Wsj|3`T+)FH4tA@H?y%LBw9``GUR2Q z?@A!Wy@$|;>-#4J@~1CN4PVdOkB})_KM_kzw_o}34TrpoSMeR%Rz7x+T6Moz7p2n0 zF=)C!M%%Mn0+qjeFH(U%+fe?{%Diq{m|`g3zazT+ri3}9q3i+2bqUQEsl0YB>B+c` zGLK!$UNs4^^JTt}T>C4MYy1paJdCi4paQ$g!pz0==9_O1M0e0LZQ zHrlgDi6R=w=63I_7P)tUx=Kmm6T9)Px^VN@UH9^SgutsWN@^nmn*qFgg*bzY`;%tq zA`=Djq>y;xMmy6)v+bXqwajvO`m}@dQl@XU{xjIe>PMAI!r~hIF8U5Z_qAl*@1QFe zNYdMyYd(b`1O}Vb{FblEZmwXWnrXv3<%&oBcQXBUaE~@Fo&>?BE?*w*gAY#Y_JQ$K z{7JLM`q4y*ZpOoKYtH+Mr%kV@2X_zVHk_g@F_Y`Jco@C6N7qgX#&=&-AM8i*M>as7 z83$f*o8QLQFAVp@H=)GoQgWd3S)5vq{4y+xaHoCvHw1As@B#T+)mXBZUbKhdj@gL^ z<6Hj7jhy_OOpRb>zL&w=y^|GWiHT!2!9$y`952i#0I%{Z`22+y}$58H;k!F7*j^iRCSRQvhk8HZMzwOML7orrv6%(thqpNTCYMEXfmo zg10+d!5iF62bBY9?5NdMwS2-5@Rw;4`KTeCm6{M|y%ajG#@fI?trmcFGyXwIy~Vew z9D(STi+)L27PeZ>jZU2EsbkfGcRjy-HIsI0-SQrNaD(LSy<~yGMbU5LD+dVrpq--1 z;x4(u*$O|em@Hm2Z6lwPaAbrH71Jkcfyjf$Vh-TXi}xJ`lKSq-Oy~b7Qo|?NDvuu8 z94k>5w&aLf%q8{dDJyS)X5agL`q}$ehx@K)Wz+QK_fhegroVycDpV4Dgt;JCtHoI~ zCjAewm(rA<@7uMXtTSA3Uw%_P^*2M3gSbwcL*0h~)7+{LUxR<(-B!<+gS(sjKWMa5 zZ1?Uni@q614@9s>=9Je;V`V0>B8i7zeV>W9d?2=R_QVfwZ*-4FAv%1{&nUD4>sqER zL1pkv=)I#jaG+2&BK-P~qdM<|gw{A5 zv%@084IuOjD)*K+LAr_hT;S^nKTlv9I$9f*_f;aV_0ynBtR5mtn>Dlr{R$+7!3;_xedsebj5OP})O3go5eoe1xXde>SL;Y92E z4fN00a>%9{7rJ}vcK}bdZLMvQ5~kF|Rg@Zb|A4G9!^fY@0^zq8#Em7x?JtVNhdT~e zp?)uyu*$ae>aqCRK?b;G>zT9nqzL|7R4{KFVlHX{Y~Lj<01N_9y>}OP4yohd`D6O}dz7v>6kOUM&N5>=W#Pkp+|>_(aoL z&rR9N+{M%O0maAEv!+%NRC%&@E4LXl|y)FOM&u zeCc=TvkGsuI6>$?haOl7KQ;VQIB|K5S{uY+% zFId=XMev@ZaaQvSEOYT{{oi$}GL+5y zN$z%Hw9>ikt#=IwWYDZG2=&Q+>)R7OOp-o%+x$4zJB?>>)fl+@IuIWW@%Q-Ef#t(0 zKUGT(m)_+dBHnZwXS2%`uTO5<9R3QSZ%u=ET5RhjW_R{1(h$$$FL%dd^gNCB%;q)V zsXh_$9RL78j=$dp)Sr*G(vblGEUW+kHQ)}w+sDq;$JNd|K-Akei~w-^KOf+a1l$~S zvz6p~>ExQR#Mp`GTLw(YFjpq9i->$`c}p2aN0&h^KyO(5;iXZfZue-BrnKB+$G4hl zg>U0^;x%7=oo>-*kHG5Wz<~m zP4P#Gd3q`$Jvtjdm5X1l#tv+~8DOZHtKZ-LVrNvtUW8i*DM$S=m`lP+38b}21I?L_ z)EdE|+J61qB-iNGMhT_AP`OfyiMJc@D{}rNH8B61thz3FP!bLlL>EaOIdM5yN1i*_ z5N%T&y>B_yufO}mm#&-Q#I{)!z%=N?)I++&O={$y_Qam`;s{=*j-c+d@f73r*`Fg% z?E|5+$RQ3Yq>&`o6bsvMDcUmazK1*i{Gq%jHS*C@;Ur21O{GM(uF=+)Bf1~YSEu>R zlT_zoOBL48)RF!ccH7-#ojKE6;X$v}HiCC@dE1oL-mCzPZLN>3HVA!r8pn%0{*^rj zOP`iL4vE9MABM7A0uRLiX1%E!Jb_m)(80%VH*Ouk;7ajauqJ(#Q!)$aHb&J~q7kui zCC|MbRCYygyuz2v35|`WQ{Fyefwjf8LneVJKb&a?Tb&L4@I!txFcr_ZOZq_9DCS;NumDFB?C)pL63W*7wr4d^K*+Uhb zxO=FejK~iW`!yW!#8FuIf=^>*Sa}(jz}D4==4-+W9ko8~2<)f|&BtjQxRiz2at-0N zPBd}U;-(XKtMMLbPzMb<`qGcsYN>5{wXCj&?@{l3c^Y!uc1O9%yWE&M5>}E`j=(3r zJ;b&VZgBPr@JE%{Dea+-vxtW?Xo`ab5bp&|#GX`I9ZL;d?c@5tH2-$cS!5y*`I$b# zc0TRon`j6LE{eK1Auaf+4|<*>a%IzM$nrW(!>3HPEWAX_yhxkR;%^H|*3R8Rjzs{a zaA6~hBkVb1b_2iPpk7dlow7s4{wW8`o5>p=wnq7TbIPhw#!Qibii>uIdVzV}wnq_g zCr%v_Tq8H@xyLfMEjOG3DA||=40_Yq^!`F&OWB7zCaUnFW2~nbBpMr%qp%kC6dXbl z%w7d9G-f;j-G`(U0VleydI%L3H+-;C4TVx$=e1N~9Y!6_(M4REHw)&MjM)&wH+vW6|4mDRky)CrU8m#E>0;t&NCImx?TvP2c!#-QXf#4-=pI9H2 zCehMcI5Gw8T*8(j?yaUCu|!7{TI@B>z~c4{bRAaYDCem$j|pLTpO^I+nC>lLh1Hevivf(2HE!;4dA;j*r=ih_T0I0@tfnQj! zSqb!OomyYzW^@@3_i(ZgQiv?7*GKLV;#v#&*ZyRxFu}VrY@h=RQTA1}`<;Z|KX+L` zRe1IK@TRvX+YY@yhp_%DQoyasLlc4yxu5D25Z)pBFQW1+wQgHz0suOC06cvDcZ(so zdHz56>gD3_zajSjm-ec%__9#|04%Ko0JQ%V2E-5);lJ~Lq@8?%|AWu}zwrMH=KqzB cA?SwuU*Z4LE(z()0Yvy)D}H}#@8;G20y4^w8vp Date: Fri, 8 Mar 2024 12:16:00 -0800 Subject: [PATCH 12/18] Have a great, working detector --- .../food_on_fork_detection.py | 191 +++++++- .../food_on_fork_detectors.py | 407 +++++++++++++++++- .../food_on_fork_train_test.py | 35 +- .../ada_feeding_perception/helpers.py | 115 ++++- .../config/food_on_fork_detection.yaml | 15 +- .../distance_no_fof_detector_with_filters.npz | Bin 0 -> 12255 bytes .../model/pointcloud_t_test_detector.npz | Bin 27132 -> 181044 bytes 7 files changed, 724 insertions(+), 39 deletions(-) create mode 100644 ada_feeding_perception/model/distance_no_fof_detector_with_filters.npz diff --git a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py index 3a3be9b6..d7ec1960 100644 --- a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py +++ b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py @@ -6,20 +6,21 @@ class to use and kwargs for the class's constructor; (b) exposes a ROS2 service on the fork. """ # Standard imports -import collections.abc +import collections import os import threading from typing import Any, Dict, Tuple # Third-party imports from cv_bridge import CvBridge +import cv2 import numpy as np from rcl_interfaces.msg import ParameterDescriptor, ParameterType import rclpy from rclpy.callback_groups import MutuallyExclusiveCallbackGroup from rclpy.executors import MultiThreadedExecutor from rclpy.node import Node -from sensor_msgs.msg import CameraInfo, Image +from sensor_msgs.msg import CameraInfo, CompressedImage, Image from std_srvs.srv import SetBool from tf2_ros.buffer import Buffer from tf2_ros.transform_listener import TransformListener @@ -29,8 +30,10 @@ class to use and kwargs for the class's constructor; (b) exposes a ROS2 service from ada_feeding_msgs.msg import FoodOnForkDetection from ada_feeding_perception.food_on_fork_detectors import FoodOnForkDetector from ada_feeding_perception.helpers import ( + cv2_image_to_ros_msg, get_img_msg_type, ros_msg_to_cv2_image, + show_3d_scatterplot, ) from .depth_post_processors import ( create_spatial_post_processor, @@ -69,6 +72,10 @@ def __init__(self): self.depth_max_mm, temporal_window_size, spatial_num_pixels, + self.viz, + self.viz_upper_thresh, + self.viz_lower_thresh, + rgb_image_buffer, ) = self.read_params() # Create the post-processors @@ -138,6 +145,30 @@ def __init__(self): callback_group=MutuallyExclusiveCallbackGroup(), ) + # If the visualization flag is set, create a subscriber to the RGB image + # and publisher for the RGB visualization + if self.viz: + self.rgb_pub = self.create_publisher( + Image, "~/food_on_fork_detection_img", 1 + ) + self.img_buffer = collections.deque(maxlen=rgb_image_buffer) + self.img_buffer_lock = threading.Lock() + image_topic = "~/image" + try: + image_type = get_img_msg_type(image_topic, self) + except ValueError as err: + self.get_logger().error( + f"Error getting type of image topic. Defaulting to CompressedImage. {err}" + ) + image_type = CompressedImage + self.img_subscription = self.create_subscription( + image_type, + image_topic, + self.camera_callback, + 1, + callback_group=MutuallyExclusiveCallbackGroup(), + ) + def read_params( self, ) -> Tuple[ @@ -152,6 +183,10 @@ def read_params( int, int, int, + bool, + float, + float, + int, ]: """ Reads the parameters for the FoodOnForkDetection. @@ -172,6 +207,10 @@ def read_params( Disabled by default. spatial_num_pixels: The number of pixels for the spatial post-processor. Disabled by default. + viz: Whether to publish a visualization of the result as an RGB image. + viz_upper_thresh: The upper threshold for declaring FoF in the viz. + viz_lower_thresh: The lower threshold for declaring FoF in the viz. + rgb_image_buffer: The number of RGB images to store at a time for visualization. """ # Read the model_class model_class = self.declare_parameter( @@ -329,6 +368,52 @@ def read_params( ) spatial_num_pixels = spatial_num_pixels.value + # Get the visualization parameters + viz = self.declare_parameter( + "viz", + False, + descriptor=ParameterDescriptor( + name="viz", + type=ParameterType.PARAMETER_BOOL, + description="Whether to publish a visualization of the result as an RGB image.", + read_only=True, + ), + ) + viz = viz.value + viz_upper_thresh = self.declare_parameter( + "viz_upper_thresh", + 0.5, + descriptor=ParameterDescriptor( + name="viz_upper_thresh", + type=ParameterType.PARAMETER_DOUBLE, + description="The upper threshold for declaring FoF in the viz.", + read_only=True, + ), + ) + viz_upper_thresh = viz_upper_thresh.value + viz_lower_thresh = self.declare_parameter( + "viz_lower_thresh", + 0.5, + descriptor=ParameterDescriptor( + name="viz_lower_thresh", + type=ParameterType.PARAMETER_DOUBLE, + description="The lower threshold for declaring FoF in the viz.", + read_only=True, + ), + ) + viz_lower_thresh = viz_lower_thresh.value + rgb_image_buffer = self.declare_parameter( + "rgb_image_buffer", + 30, + descriptor=ParameterDescriptor( + name="rgb_image_buffer", + type=ParameterType.PARAMETER_INTEGER, + description="The number of RGB images to store at a time for visualization. Default: 30", + read_only=True, + ), + ) + rgb_image_buffer = rgb_image_buffer.value + return ( model_class, model_path, @@ -341,6 +426,10 @@ def read_params( depth_max_mm, temporal_window_size, spatial_num_pixels, + viz, + viz_upper_thresh, + viz_lower_thresh, + rgb_image_buffer, ) def toggle_food_on_fork_detection( @@ -394,6 +483,17 @@ def depth_callback(self, msg: Image) -> None: with self.depth_img_lock: self.depth_img = msg + def camera_callback(self, msg: Image) -> None: + """ + Callback for the camera image. + + Parameters + ---------- + msg: The camera image message. + """ + with self.img_buffer_lock: + self.img_buffer.append(msg) + def run(self) -> None: """ Runs the FoodOnForkDetection. @@ -438,6 +538,8 @@ def run(self) -> None: try: proba = self.model.predict_proba(X)[0] food_on_fork_detection_msg.probability = proba + if np.isnan(proba): + food_on_fork_detection_msg.message = "Could not assess food on fork" # pylint: disable=broad-except # This is necessary because we don't know what exceptions the model # might raise. @@ -447,6 +549,91 @@ def run(self) -> None: food_on_fork_detection_msg.probability = -1.0 food_on_fork_detection_msg.message = err_str + # Visualize the results + if self.viz: + # show_3d_scatterplot( + # [self.model.depth_to_pointcloud(depth_img_cv2)], + # colors=[[0, 0, 1]], + # sizes=[5], + # markerstyles=["o"], + # labels=["Test"], + # title="Test Points", + # ) + + # Get the RGB image with timestamp closest to the depth image + with self.img_buffer_lock: + img_msg = None + # At the end of this for loop, img_message will be the most + # recent image that is older than the depth image, or the + # oldest image if there are no images older than the depth + # image. + for i, img_msg in enumerate(self.img_buffer): + img_msg_stamp = ( + img_msg.header.stamp.sec + + img_msg.header.stamp.nanosec * 1e-9 + ) + depth_img_stamp = ( + depth_img_msg.header.stamp.sec + + depth_img_msg.header.stamp.nanosec * 1e-9 + ) + if img_msg_stamp > depth_img_stamp: + if i > 0: + img_msg = self.img_buffer[i - 1] + break + # If img_msg is None, that means we haven't received an RGB image yet + if img_msg is not None: + # Convert the RGB image to a cv2 image + img_cv2 = ros_msg_to_cv2_image(img_msg, self.cv_bridge) + + # Get the message to write on the image + if proba > self.viz_upper_thresh: + pred = "Food on Fork" + color = (0, 255, 0) + elif proba <= self.viz_lower_thresh or np.isnan(proba): + pred = "No Food on Fork" + color = (0, 0, 255) + else: + pred = "Uncertain (Ask User)" + color = (255, 0, 0) + msg = f"{pred}: {proba:.2f}" + + # Write the message on the top-left corner of the image + cv2.putText( + img_cv2, + msg, + (10, 30), + cv2.FONT_HERSHEY_SIMPLEX, + 1, + color, + 2, + cv2.LINE_AA, + ) + + # Add a rectangular border around the image in the specified color + cv2.rectangle( + img_cv2, + (0, 0), + (img_cv2.shape[1], img_cv2.shape[0]), + color, + 10, + ) + + # Also add a rectangle around the crop box + cv2.rectangle( + img_cv2, + self.crop_top_left, + self.crop_bottom_right, + color, + 2, + ) + + # Publish the image + self.rgb_pub.publish( + cv2_image_to_ros_msg( + img_cv2, compress=False, bridge=self.cv_bridge + ) + ) + # Publish the FoodOnForkDetection message self.pub.publish(food_on_fork_detection_msg) diff --git a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py index 00bf4180..01279d2c 100644 --- a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py +++ b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py @@ -15,8 +15,17 @@ from overrides import override import scipy from sensor_msgs.msg import CameraInfo +from sklearn.linear_model import LogisticRegression +from sklearn.metrics.pairwise import pairwise_distances +from sklearn.model_selection import train_test_split from tf2_ros.buffer import Buffer +# Local imports +from ada_feeding_perception.helpers import ( + show_3d_scatterplot, + show_normalized_depth_img, +) + class FoodOnForkLabel(Enum): """ @@ -26,6 +35,7 @@ class FoodOnForkLabel(Enum): NO_FOOD = 0 FOOD = 1 UNSURE = 2 + TOO_FEW_POINTS = 3 class FoodOnForkDetector(ABC): @@ -377,17 +387,21 @@ def fit(self, X: npt.NDArray, y: npt.NDArray[int]) -> None: # Get the most up-to-date camera info if self.camera_info is not None: self.camera_matrix = np.array(self.camera_info.k) - no_fof_imgs = X[y == FoodOnForkLabel.NO_FOOD.value] + no_fof_imgs = [] no_fof_pointclouds = [] - for img in no_fof_imgs: + for i, img in enumerate(X): + if y[i] != FoodOnForkLabel.NO_FOOD.value: + continue pointcloud = self.depth_to_pointcloud(img) if len(pointcloud) >= self.min_points: + no_fof_imgs.append(img) no_fof_pointclouds.append(pointcloud) self.no_fof_means = np.array([np.mean(pc, axis=0) for pc in no_fof_pointclouds]) self.no_fof_covs = np.array( [np.cov(pc, rowvar=False, bias=False) for pc in no_fof_pointclouds] ) self.no_fof_ns = np.array([pc.shape[0] for pc in no_fof_pointclouds]) + self.no_fof_X = np.array(no_fof_imgs) @override def save(self, path: str) -> str: @@ -406,6 +420,7 @@ def save(self, path: str) -> str: no_fof_means=self.no_fof_means, no_fof_covs=self.no_fof_covs, no_fof_ns=self.no_fof_ns, + no_fof_X=self.no_fof_X, ) return path + ".npz" @@ -418,6 +433,7 @@ def load(self, path: str) -> None: self.no_fof_means = params["no_fof_means"] self.no_fof_covs = params["no_fof_covs"] self.no_fof_ns = params["no_fof_ns"] + self.no_fof_X = params["no_fof_X"] @staticmethod def hotellings_t_test( @@ -506,6 +522,78 @@ def trace_mkk(a: npt.NDArray): return ps + @staticmethod + def test_hotelling_t_test() -> None: + """ + Tests the Hotelling's T^2 test function. + """ + # pylint: disable=too-many-locals + # Necessary for this function. + print("Testing Hotelling's T^2 test function...") + + # Verify that two samples with the same mean and covariance have a p-value + # of 1.0 + m = 100 + k = 2 + n = 100 + samp1_means = np.zeros((m, k)) + cov_magnitude = 1.0 + samp1_covs = np.repeat(np.eye(k).reshape((1, k, k)), m, axis=0) * cov_magnitude + samp1_ns = np.ones(m) * n + samp2_mean = samp1_means[0] + samp2_cov = samp1_covs[0] + samp2_n = samp1_ns[0] + ps = FoodOnForkPointCloudTTestDetector.hotellings_t_test( + samp1_means, samp1_covs, samp1_ns, samp2_mean, samp2_cov, samp2_n + ) + assert np.allclose(ps, 1.0) + + # Verify that two samples with small/large differences in mean relative to the + # covariance have a p-value close to 1.0/0.0 + for div, target_p in [(100, 1.0), (1, 0.0)]: + diff = cov_magnitude / (div) + samp2_mean = np.array([samp1_means[0, 0] - diff, samp1_means[0, 1] + diff]) + ps = FoodOnForkPointCloudTTestDetector.hotellings_t_test( + samp1_means, samp1_covs, samp1_ns, samp2_mean, samp2_cov, samp2_n + ) + assert np.allclose(ps, target_p, atol=0.01) + + # Test with realistic values from pointclouds + samp1_means = np.array( + [ + [0.03519467, 0.05854858, 0.32684903], + ] + ) + samp1_covs = np.array( + [ + [ + [3.10068497e-05, -3.51810972e-06, 7.46688582e-06], + [-3.51810972e-06, 4.12632792e-05, -4.49831451e-05], + [7.46688582e-06, -4.49831451e-05, 5.09933589e-05], + ], + ] + ) + samp1_ns = np.array([1795]) + samp2_mean = np.array([0.03419327, 0.05895837, 0.32637653]) + samp2_cov = np.array( + [ + [7.00616784e-06, 4.17580593e-06, -4.68206042e-06], + [4.17580593e-06, 2.97615922e-05, -3.61209300e-05], + [-4.68206042e-06, -3.61209300e-05, 4.50266659e-05], + ] + ) + samp2_n = 1960 + ps = FoodOnForkPointCloudTTestDetector.hotellings_t_test( + samp1_means, samp1_covs, samp1_ns, samp2_mean, samp2_cov, samp2_n + ) + # Get the mean difference and the determinant of the cov matrix + mean_diff = np.linalg.norm(samp1_means[0] - samp2_mean) + cov_magnitude = np.linalg.norm(samp1_covs[0]) + print(ps) + print(mean_diff, cov_magnitude) + + print("Hotelling's T^2 test function passed!") + @override def predict_proba(self, X: npt.NDArray) -> npt.NDArray: if ( @@ -528,18 +616,325 @@ def predict_proba(self, X: npt.NDArray) -> npt.NDArray: probas.append(0.0) continue # Calculate the T^2 statistic and p-value + pointcloud_mean = np.mean(pointcloud, axis=0) + pointcloud_cov = np.cov(pointcloud, rowvar=False, bias=False) + pointcloud_n = pointcloud.shape[0] ps = FoodOnForkPointCloudTTestDetector.hotellings_t_test( self.no_fof_means, self.no_fof_covs, self.no_fof_ns, - np.mean(pointcloud, axis=0), - np.cov(pointcloud, rowvar=False, bias=False), - pointcloud.shape[0], + pointcloud_mean, + pointcloud_cov, + pointcloud_n, + ) + closest_train_img_i = np.argmax(ps) + print(f"pointcloud_mean {pointcloud_mean}") + print(f"pointcloud_cov {pointcloud_cov}") + print(f"pointcloud_n {pointcloud_n}") + print(f"closest_train_img_mean {self.no_fof_means[closest_train_img_i]}") + print(f"closest_train_img_cov {self.no_fof_covs[closest_train_img_i]}") + print(f"closest_train_img_n {self.no_fof_ns[closest_train_img_i]}") + p = ps[closest_train_img_i] + print(f"p {p}") + show_normalized_depth_img(X[i], wait=False, window_name="test_img") + show_normalized_depth_img( + self.no_fof_X[closest_train_img_i], wait=False, window_name="train_img" + ) + + # Sample from the mean and cov of each image to see how well the + # distributional assumptions match. + sampled_pointcloud = np.random.multivariate_normal( + pointcloud_mean, pointcloud_cov, pointcloud_n ) - p = np.max(ps) + closest_train_img_sampled_pointcloud = np.random.multivariate_normal( + self.no_fof_means[closest_train_img_i], + self.no_fof_covs[closest_train_img_i], + self.no_fof_ns[closest_train_img_i], + ) + print("ASDF") + print(pointcloud.tolist()) + print("GHJK") + print(self.depth_to_pointcloud(self.no_fof_X[closest_train_img_i]).tolist()) + show_3d_scatterplot( + [ + # pointcloud, + sampled_pointcloud, + # self.depth_to_pointcloud(self.no_fof_X[closest_train_img_i]), + closest_train_img_sampled_pointcloud, + ], + colors=[ + # [1, 0, 0], + [0, 1, 0], + # [0, 0, 1], + [0, 0, 0], + ], + sizes=[5, 5], # ,5,5], + markerstyles=["o", "x"], # , "o", "x"], + labels=["Test", "Train"], # , "Test Sampled", "Train Sampled"], + title="Test vs Train", + mean_colors=[[0, 0, 1], [0, 0, 0]], # , [0, 0, 1], [0, 0, 0]], + mean_sizes=[20, 20], # , 20, 20], + mean_markerstyles=["^", "^"], # , "^", "^"], + ) + # p is the probability that the null hypothesis is true, i.e. the # probability that the pointcloud is from the same distribution as # the no-FoF pointclouds. Hence, we take 1 - p. probas.append(1.0 - p) return np.array(probas) + + +class FoodOnForkDistanceToNoFOFDetector(FoodOnForkDetector): + """ + A perception algorithm that stores many no FoF points. It then calculates the + average distance between each test point and the nearest no FoF point. It + then trains a classifier to predict the probability of a test point being + FoF based on that distance. + """ + + def __init__( + self, + camera_matrix: npt.NDArray, + prop_no_fof_points_to_store: float = 0.5, + min_points: int = 40, + min_distance: float = 0.001, + verbose: bool = False, + ) -> None: + """ + Initializes the algorithm. + + Parameters + ---------- + camera_matrix: The camera intrinsic matrix (K). + prop_no_fof_points_to_store: The proportion of no FoF points to store. + min_points: The minimum number of points in a pointcloud to consider it + for comparison. If a pointcloud has fewer points than this, it will + return a probability of nan (prediction of UNSURE). + min_distance: The minimum distance between stored no FoF points. + verbose: Whether to print debug messages. + """ + super().__init__(verbose) + self.camera_matrix = camera_matrix + self.prop_no_fof_points_to_store = prop_no_fof_points_to_store + self.min_points = min_points + self.min_distance = min_distance + + self.no_fof_points = None + self.clf = None + + def depth_to_pointcloud(self, depth_image: npt.NDArray) -> npt.NDArray: + """ + Converts a depth image to a point cloud. + + Parameters + ---------- + depth_image: The depth image to convert to a point cloud. + + Returns + ------- + pointcloud: The point cloud representation of the depth image. + """ + # Get the pixel coordinates + pixel_coords = np.mgrid[ + int(self.crop_top_left[1]) : int(self.crop_bottom_right[1]), + int(self.crop_top_left[0]) : int(self.crop_bottom_right[0]), + ] + # Mask out values outside the depth range + mask = depth_image > 0 + depth_values = depth_image[mask] + pixel_coords = pixel_coords[:, mask] + # Convert mm to m + depth_values = np.divide(depth_values, 1000.0) + # Extract the values from the camera matrix + f_x = self.camera_matrix[0] + f_y = self.camera_matrix[4] + c_x = self.camera_matrix[2] + c_y = self.camera_matrix[5] + # Convert to 3D coordinates + pointcloud = np.zeros((depth_values.shape[0], 3)) + pointcloud[:, 0] = np.multiply( + pixel_coords[1] - c_x, np.divide(depth_values, f_x) + ) + pointcloud[:, 1] = np.multiply( + pixel_coords[0] - c_y, np.divide(depth_values, f_y) + ) + pointcloud[:, 2] = depth_values + return pointcloud + + def get_distance_from_train_points(self, pointcloud: npt.NDArray) -> npt.NDArray: + """ + Gets the average of the minimum distances from each point in the test + pointcloud to the nearest no FoF point in the training set. + + Parameters + ---------- + pointcloud: The test pointcloud. Size (n, 3). + + Returns + ------- + distance: The average of the minimum distances from each point in the test + pointcloud to the nearest no FoF point in the training set. + """ + return np.mean( + np.min(pairwise_distances(pointcloud, self.no_fof_points), axis=1) + ) + + @override + def fit(self, X: npt.NDArray, y: npt.NDArray[int]) -> None: + # Convert all images to pointclouds, removing those with too few points + pointclouds = [] + y_pointclouds = [] + for i, img in enumerate(X): + pointcloud = self.depth_to_pointcloud(img) + if len(pointcloud) >= self.min_points: + pointclouds.append(pointcloud) + y_pointclouds.append(y[i]) + pointclouds = np.array(pointclouds, dtype=object) + y_pointclouds = np.array(y_pointclouds) + print( + f"Got pointclouds, {len(pointclouds)} total, {len(pointclouds[y_pointclouds == FoodOnForkLabel.NO_FOOD.value])} no FoF, {len(pointclouds[y_pointclouds == FoodOnForkLabel.FOOD.value])} FoF" + ) + + # Split the no FoF and FoF pointclouds + no_fof_pointclouds = pointclouds[y_pointclouds == FoodOnForkLabel.NO_FOOD.value] + fof_pointclouds = pointclouds[y_pointclouds == FoodOnForkLabel.FOOD.value] + + # Randomly split the no FoF points + no_fof_pointclouds_train, no_fof_pointclouds_val = train_test_split( + no_fof_pointclouds, + train_size=self.prop_no_fof_points_to_store, + random_state=self.seed, + ) + + # Store the no FoF points + all_no_fof_points = np.concatenate(no_fof_pointclouds_train) + no_fof_points_to_store = all_no_fof_points[0:1, :] + # Add points that are >= min_distance m away from the stored points + for i in range(1, len(all_no_fof_points)): + print(f"{i}/{len(all_no_fof_points)}") + contender_point = all_no_fof_points[i] + # Get the distance between the contender point and th stored points + distance = np.min( + pairwise_distances([contender_point], no_fof_points_to_store), axis=1 + )[0] + if distance >= self.min_distance: + no_fof_points_to_store = np.vstack( + [no_fof_points_to_store, contender_point] + ) + self.no_fof_points = no_fof_points_to_store + + print("Split data, self.no_fof_points.shape", self.no_fof_points.shape) + + # Get the distances from each non-stored point and the stored points + no_fof_distances = [] + for i, pc in enumerate(no_fof_pointclouds_val): + print(f"{i}/{len(no_fof_pointclouds_val)}") + no_fof_distances.append(self.get_distance_from_train_points(pc)) + no_fof_distances = np.array(no_fof_distances) + print(f"Got no_fof_distances, {no_fof_distances}, {no_fof_distances.shape}") + fof_distances = np.array( + [self.get_distance_from_train_points(pc) for pc in fof_pointclouds] + ) + print(f"Got fof_distances {fof_distances}, {fof_distances.shape}") + + # Train the classifier + classifier_X = np.concatenate([no_fof_distances, fof_distances]) + classifier_y = np.concatenate( + [np.zeros((no_fof_distances.shape[0],)), np.ones((fof_distances.shape[0],))] + ) + print( + f"Training classifier with {classifier_X} {classifier_X.shape} {classifier_y} {classifier_y.shape}" + ) + self.clf = LogisticRegression(random_state=self.seed, penalty=None) + self.clf.fit(classifier_X.reshape(-1, 1), classifier_y) + print("Trained classifier") + print(self.clf.coef_, self.clf.intercept_) + + @override + def save(self, path: str) -> str: + if self.no_fof_points is None or self.clf is None: + raise ValueError( + "The model has not been trained yet. Call fit before saving." + ) + # If the path has an extension, remove it. + path = os.path.splitext(path)[0] + np.savez_compressed( + path, + no_fof_points=self.no_fof_points, + clf=np.array([self.clf], dtype=object), + ) + return path + ".npz" + + @override + def load(self, path: str) -> None: + ext = os.path.splitext(path)[1] + if len(ext) == 0: + path = path + ".npz" + params = np.load(path, allow_pickle=True) + self.no_fof_points = params["no_fof_points"] + self.clf = params["clf"][0] + + @override + def predict_proba(self, X: npt.NDArray) -> npt.NDArray: + probas = [] + + # show_3d_scatterplot( + # [self.no_fof_points], + # colors=[[0, 0, 1]], + # sizes=[5], + # markerstyles=["o"], + # labels=["Train"], + # title="Train Points", + # ) + # raise Exception() + + # Convert all images to pointclouds, removing those with too few points + num_images_no_points = 0 + for i, img in enumerate(X): + start_time = time.time() + pointcloud = self.depth_to_pointcloud(img) + if len(pointcloud) >= self.min_points: + distance = self.get_distance_from_train_points(pointcloud) + # print("distance", distance) + proba = self.clf.predict_proba(np.array([[distance]]))[0, 1] + # print(f"proba {proba}") + probas.append(proba) + if i % 50 == 0: + print( + f"Predicted on pointcloud {i+1}/{len(X)} in {time.time() - start_time} seconds" + ) + else: + probas.append(np.nan) + num_images_no_points += 1 + + print(f"num_images_no_points {num_images_no_points}") + return np.array(probas) + + @override + def predict( + self, + X: npt.NDArray, + lower_thresh: float, + upper_thresh: float, + proba: Optional[npt.NDArray] = None, + ) -> npt.NDArray[int]: + if proba is None: + proba = self.predict_proba(X) + return np.where( + np.isnan(proba), + FoodOnForkLabel.TOO_FEW_POINTS.value, + np.where( + proba <= lower_thresh, + FoodOnForkLabel.NO_FOOD.value, + np.where( + proba > upper_thresh, + FoodOnForkLabel.FOOD.value, + FoodOnForkLabel.UNSURE.value, + ), + ), + ) + + +if __name__ == "__main__": + FoodOnForkPointCloudTTestDetector.test_hotelling_t_test() diff --git a/ada_feeding_perception/ada_feeding_perception/food_on_fork_train_test.py b/ada_feeding_perception/ada_feeding_perception/food_on_fork_train_test.py index 5eca376c..62a8d1e5 100644 --- a/ada_feeding_perception/ada_feeding_perception/food_on_fork_train_test.py +++ b/ada_feeding_perception/ada_feeding_perception/food_on_fork_train_test.py @@ -32,32 +32,16 @@ FoodOnForkDetector, FoodOnForkLabel, ) -from ada_feeding_perception.helpers import ros_msg_to_cv2_image +from ada_feeding_perception.helpers import ( + ros_msg_to_cv2_image, + show_normalized_depth_img, +) from ada_feeding_perception.depth_post_processors import ( create_spatial_post_processor, create_temporal_post_processor, ) -def show_normalized_depth_img(img, wait=True, window_name="img"): - """ - Show the normalized depth image. Useful for debugging. - - Parameters - ---------- - img: npt.NDArray - The depth image to show. - wait: bool, optional - If True, wait for a key press before closing the window. - window_name: str, optional - The name of the window to show the image in. - """ - # Show the normalized depth image - img_normalized = ((img - img.min()) / (img.max() - img.min()) * 255).astype("uint8") - cv2.imshow(window_name, img_normalized) - cv2.waitKey(0 if wait else 1) - - def read_args() -> argparse.Namespace: """ Read the command line arguments. @@ -365,6 +349,7 @@ def load_data( # Load the data camera_info = None + num_images_no_points = 0 for rosbag_name, annotations in bagname_to_annotations.items(): if (len(rosbags_select) > 0 and rosbag_name not in rosbags_select) or ( len(rosbags_skip) > 0 and rosbag_name in rosbags_skip @@ -434,13 +419,15 @@ def load_data( print((timestamp - start_time) / 10.0**9) img = ros_msg_to_cv2_image(msg, bridge) # A box around the forktip - x0, y0 = 308, 242 - w, h = 128, 128 + x0, y0 = crop_top_left + x1, y1 = crop_bottom_right fof_color = (0, 255, 0) no_fof_color = (255, 0, 0) color = fof_color if len(y) == 0 or y[-1] == 1 else no_fof_color - img = cv2.rectangle(img, (x0, y0), (x0 + w, y0 + h), color, 2) - img = cv2.circle(img, (x0 + w // 2, y0 + h // 2), 5, color, -1) + img = cv2.rectangle(img, (x0, y0), (x1, y1), color, 2) + img = cv2.circle( + img, ((x0 + x1) // 2, (y0 + y1) // 2), 5, color, -1 + ) cv2.imshow("RGB Image", img) cv2.waitKey(1) diff --git a/ada_feeding_perception/ada_feeding_perception/helpers.py b/ada_feeding_perception/ada_feeding_perception/helpers.py index 81cb1fea..61f242f6 100644 --- a/ada_feeding_perception/ada_feeding_perception/helpers.py +++ b/ada_feeding_perception/ada_feeding_perception/helpers.py @@ -4,13 +4,14 @@ # Standard imports import os import pprint -from typing import Optional, Tuple, Union +from typing import List, Optional, Tuple, Union from urllib.parse import urljoin from urllib.request import urlretrieve # Third-party imports import cv2 from cv_bridge import CvBridge +import matplotlib.pyplot as plt import numpy as np import numpy.typing as npt import rclpy @@ -30,6 +31,118 @@ from skimage.morphology import flood_fill +def show_normalized_depth_img(img, wait=True, window_name="img"): + """ + Show the normalized depth image. Useful for debugging. + + Parameters + ---------- + img: npt.NDArray + The depth image to show. + wait: bool, optional + If True, wait for a key press before closing the window. + window_name: str, optional + The name of the window to show the image in. + """ + # Show the normalized depth image + img_normalized = ((img - img.min()) / (img.max() - img.min()) * 255).astype("uint8") + cv2.imshow(window_name, img_normalized) + cv2.waitKey(0 if wait else 1) + + +def show_3d_scatterplot( + pointclouds: List[npt.NDArray], + colors: List[npt.NDArray], + sizes: List[int], + markerstyles: List[str], + labels: List[str], + title: str, + mean_colors: Optional[List[npt.NDArray]] = None, + mean_sizes: Optional[List[int]] = None, + mean_markerstyles: Optional[List[str]] = None, +): + """ + Show a 3D scatterplot of the given point clouds. + + Parameters + ---------- + pointclouds: List[npt.NDArray] + The point clouds to show. Each point cloud should be a Nx3 array of + points. + colors: List[npt.NDArray] + The colors to use for the points. Each color should be a size 3 array of + colors RGB colos in range [0,1]. + sizes: List[int] + The sizes to use for the points. + markerstyles: List[str] + The marker styles to use for the point clouds. + labels: List[str] + The labels to use for the point clouds. + title: str + The title of the plot. + """ + # Check that the inputs are valid + assert ( + len(pointclouds) + == len(colors) + == len(sizes) + == len(markerstyles) + == len(labels) + ) + if mean_colors is not None: + assert mean_sizes is not None + assert mean_markerstyles is not None + assert len(mean_colors) == len(mean_sizes) == len(mean_markerstyles) + + # Create the plot + fig = plt.figure() + ax = fig.add_subplot(111, projection="3d") + + # Plot each point cloud + configs = [pointclouds, colors, sizes, markerstyles, labels] + if mean_colors is not None: + configs += [mean_colors, mean_sizes, mean_markerstyles] + for i, config in enumerate(zip(*configs)): + pointcloud = config[0] + color = config[1] + size = config[2] + markerstyle = config[3] + label = config[4] + ax.scatter( + pointcloud[:, 0], + pointcloud[:, 1], + pointcloud[:, 2], + color=color, + s=size, + label=label, + marker=markerstyle, + ) + if len(config) > 5: + mean_color = config[5] + mean_size = config[6] + mean_markerstyle = config[7] + mean = pointcloud.mean(axis=0) + ax.scatter( + mean[0].reshape((1, 1)), + mean[1].reshape((1, 1)), + mean[2].reshape((1, 1)), + color=mean_color, + s=mean_size, + label=label + " mean", + marker=mean_markerstyle, + ) + + # Set the title and labels + ax.set_title(title) + ax.set_xlabel("X") + ax.set_ylabel("Y") + ax.set_zlabel("Z") + ax.legend() + + # Show the plot + plt.show() + + def ros_msg_to_cv2_image( msg: Union[Image, rImage, CompressedImage, rCompressedImage], bridge: Optional[CvBridge] = None, diff --git a/ada_feeding_perception/config/food_on_fork_detection.yaml b/ada_feeding_perception/config/food_on_fork_detection.yaml index d832bb76..d21c6ee6 100644 --- a/ada_feeding_perception/config/food_on_fork_detection.yaml +++ b/ada_feeding_perception/config/food_on_fork_detection.yaml @@ -2,10 +2,10 @@ food_on_fork_detection: ros__parameters: # The FoodOnFork class to use - model_class: "ada_feeding_perception.food_on_fork_detectors.FoodOnForkPointCloudTTestDetector" + model_class: "ada_feeding_perception.food_on_fork_detectors.FoodOnForkDistanceToNoFOFDetector" # The path to load the model from. Ignored if the empty string. # Should be relative to the `model_dir` parameter, specified in the launchfile. - model_path: "pointcloud_t_test_detector.npz" + model_path: "distance_no_fof_detector_with_filters.npz" # Keywords to pass to the FoodOnFork class's constructor model_kws: - camera_matrix @@ -16,13 +16,16 @@ food_on_fork_detection: # The rate at which to detect and publish the confidence that there is food on the fork rate_hz: 10.0 # The top-left and bottom-right corners to crop the depth image to - crop_top_left: [308, 242] - crop_bottom_right: [436, 370] + crop_top_left: [344, 272] + crop_bottom_right: [408, 336] # The min and max depth to consider for the food on the fork depth_min_mm: 310 - depth_max_mm: 370 + depth_max_mm: 340 # The size of the temporal window for the "temporal" post-processor. temporal_window_size: 5 # The size of the square kernel for the "spatial" post-processor. - spatial_num_pixels: 10 \ No newline at end of file + spatial_num_pixels: 10 + + # Whether to visualize the output of the detector + viz: True \ No newline at end of file diff --git a/ada_feeding_perception/model/distance_no_fof_detector_with_filters.npz b/ada_feeding_perception/model/distance_no_fof_detector_with_filters.npz new file mode 100644 index 0000000000000000000000000000000000000000..99b0ced3923cc7ff0585e7a19faac5339e41d9a3 GIT binary patch literal 12255 zcmZ{K3p~@`|9>S(LL!o(5-R0>o7=i+rI0SQsdmNU8P@k?UL9fwad>R^3eYwB*5R>FBq!s7XaJ6>(IZ2{Mx(zR{R?>GD7a! zE;6=`)S0(P2ObUT!rk`msp5k^s zowm{+i&qsyOjLSO7glGM*FjVM>xC?JER(bNj$F&xM$osMjVgUS`^wDK5MVc^Z{H@#gD4>JPh(_40<7wh^z*zruLD^RQTKXK$AVzS>Q>-*)1L<@~mRkTs5 zP}p-98Vcs8W{|AAUtz@gy5gNX1-}%la%v|%KB#6?^p5CSD1<$NFa9HX%siP@11Dbl zK&(&szaqnttl8^_o^w~LD7O0%XG5!MFd~%J9Q%?2GfI{6_+C$;`9lv+ArGLIS^*=8 zH79(pzigjx*fnsZ<$QEpuxmg>x=|1xgM%#(;kafxqRe2 zkwc@}0~$q7NK=Hdf)Qid?D zY!s3HbB=c&67&a5sz&1j6;p|3+Jsxav(>i#iP1!E_pfo*I61l=i=V{Yr^Z?LpY}D; z6F5v9BHoqVtd3mFc4+*sHfZdsrm~mQ=l+#+vvF2lN5aa6$W)!~wE!WUOlTn|T99B@ zb2-r%e0eY8V{J#EcXvC$M|Fa_!f4Xx@98wn^5pQ%p;SR>7Cyy&@>K*%V`XNWz=4MwF)1 zMw)z)z#?RwfhJwHYSparZ$oIpdlOLhSPkaGW^^d4x*#&)LHp!+#6G(xo`+1}oQ-vR z;kTfvNT0qU?$t&g=bx~s4b)tv`1tEgnPXpmC06I@sma}I7N1Cd?6nh`KOLr!LWDg) zk)PMNmz~Bv^PY(&n&o=i;T_0FmH!3A0}MTM-fxMzQP8_11UhMXqzT z3HM>$3r6H$vxZHS80PX(1(mQDB)dB|Oy2<*8E7=S8@}A#nb_sEPYs!zVHCjl5}uAw zLWrNnp1BgxIU+6!UV5~*r~CWHuX``&5HeNYOUnBXaBJ^GjU9o8L@QDzbFH6Z=G26& zY3Ueejq07ODPc54c5jLP&LCOB<}DH9xNPbS?@)pfQhOem+%c|;`s|iD$AgZdPk(DP zB(I|72R=~!CQYqQ?K?a6ktLg(+h>l$MS7svZ2(3Rt4UCC+__T!fI?X-+?FcUZdxyd zRFsod4|`XoG;3P);(bY?v=FK^QT-T?D4;JBnz&!O{(8XFOH;y&4`Pd^O9zkUD3D8X z5Vq3Fy89~Y6LY5U3Cz3Rp)tmE{)*ow%ey=Zl_ z0A8izTVl;@;B1W>iX0EjR3n8Irx1ZPGkRZ^^3PMkI5Gx^{4}|fVPi54+;L-j)#}ce z?)DQrizt;^&&N!QhUqXX608U?cjRoABq_`)1&OV>>k3J|&@%1wWRrE}mo{R%n4$I_ zvcwHb!`?xN9R8zLftbyuU$hvcZ&iT_w{SYYbH{N^-|T3AU3<@2lS@j>pVmDNOAUIn zOdYou7K|SyN8o>c*`TRl3l#Y!8clu)YmyiBSImEK2>uP6n1^89SPdsmr{C6Zv{*^G znqigJEVVOE|URl-KtGNHC0RaioU&*YZ)fG~>e z;hc3=1UHP5=nOSAfd$_pyrA*I9eKaF*^X5VT5!@Nt zmAogW@`I5+h)v9UHAcm1!B}|XT79B{hbc){rL+`I-`nmb)}$M%g1t8!(@%X<9Fo!i0ci>S`QCHt}ZuVW~O@J4I~kk+nd zT_W{$=%;+eorcU3JAAbpX6(3OCbXbGS1dNH9m zV?zlE8)x71ED?W8eN8uFRdMa$#?X7%*8`N0{9>ul?kE0-;8eYy1Dl7HLn&)dFMLSY z-I39It;CrzxCVdavv@2cM*Q2yu^CC8}yz&-NZhjRro zoQGWwGF=gZX9IC*%LPtmwl#$-5gP+Ny5F*bG}WNNZ>EI@0FSc*#HH)Ix@9^@i6^3w z@{DwSBi*~SBKwKkaPHv#sd7(7;mn8M?~O*HGC_V4j=?Un15b>>%o~1X%;|c1#74)s z3=f{suUxrMZv^UqRg@)Nr0tF@Qr$qmgS+9^f2~g@MrWx3SGoOm*!8i0K1Ch?3C$EJoeXV##G@G1VhYpPOfl1N?#*INpGQ2y|-weK<0SgFflux^Vb$ZDGzAa%IZC$AEABD(H;f}^X0 zm6G9VGX2NTG2ZIE9-k=c*H6AxvBC<*{dJyQ4n~bsN5c=gqYEFN4PV7+mr+>ZmI150 zowsx6Up$0~AM-uLX`K|T`qiUMUGv_lwol_6DZ1hJtH(ZsW2@ev;y0Ni@yDaBYwFv% zU(t{y(w}A>hxO075DP@r0ZGn>i7b6kQ*gXC&|srIauY6B^w{iNPNEA3@;x29Ro zLZCV`4j!d*851p^HktYNDw%^dknmUG^6}W$C}=~0B!{w@S(j75v%K(fPOrA2e8hgy+>DDqGwNrZX_aS zf(93jiv3_ya~0d{;YblHLj@7ZS_8^4yp53V-HA;`PNfaM6B~oTh@%AkDwp^9U`?=T zG|RHVwJ_R~8kIG=H}Az@!2?%6O8`cm!vx67rVY*; z(W|(F_2@&+6b=xgOR5&b+lY@>^6;fqV>VwDngJoA z!*Vtw4^XxHpo4-bIqLraYK@=^6nwUO7Ckd)K78O&w!03JiwA@}PffGfK3kq+?)(f$ z*@Leu`hzGlpVVwDE7roXwD}Q<>DoTJ;Y;eRO1&)fP)t4r82o@Ft6_4sJ4z*_d`c#7 z$Vt~u&2X6T!k6drj&_@ph0jK4Bf0JMxJ*>lo=icJhW+6x(2`Gb;XL;|iSSprkZ;A{ z+POQG@SbAbduoOouEW#MsHBldZJ$divmpFbn%sLPGA zRCoC_cJd}o1iWmr2W4UQnaVPf@ePU2%Vk{O4tEY(FxQB(J@#?zc;$l875Pp}<1O7= zb8Ld~-4w$!2G;`E)#3gfw&D^1qod@_-o}*6Lhh>zpG+FY_BO1a@JG-sUJR`fnEiE> zw$Qii%13&2^~6jVK0Ox21vtbk2nS&b+jGph>EZ^LEN zH9?pYo*P{_*OS&+!CMZu%I%FBvo+4kzN-stDdETvpZhhz)&O?yJ-2ic+q|+hw2+u) zfYCv^wn}KGIy?6c#a|BYSs}Xsc^_w%l3uph%o^f(Pm-N`$-bZ4pozTk zV1&K?{Q&0K9kVP@eU9TV+C6P#$y?Zk5k~Hrv5O})n&1W0sG6%@C68u6x|`ZoDB~|& zOtcnjW$VX@XpIu-Hzr>!^QUQ{ffxaV3>4pk*8=HSpD{fXZgcl@8(PyJnjufur`tGs zjeBbdCBVNz8*}_aU1Hmeyj`6$>HC@LhLC5}XyCd8>V|}j7U+q=wFY%g9 zn!=SxvZNHR6e6=wGQ8p@PxmM68ST1TrfcLu?tKysr;W7!0OYDKJ>*vQ<>3bRABrlM z_Yr^~LHiE_aAXz~JMd`*AuVz!+@|AqA5q0)TcklSN|Qu;p@ncZQTj3_3ew^k&f{QD z186cB)L@-jhe_hPWbN+R(#AYsu1??E zUi`80N*wsdW&2b{Tltm>)sUinp9Gm-@hvWqBdg6SJHI#+k&LHH0zv{vv?H2G&~y6t zU;ge(SLTntr=teK9oRpJT5$FjD@Y`V*$~+I*%EwN&jNo0!cbfK{lN(PXzB7|hk{)b zNN5!fL!mz~J6dqu}I7~)c# zi)5jt9LeatxR3{^rGK0Zb}m_rpSK73I#JCn8t-OIZx7DOIFPP!-Fy)2NUK=hYdS3B zcQ~%T{V`ocX=G853IT?|C;PY^(1wV2eu{%@Sx-DGcB*s{%A5xBz7clNq{oyGrlM-b z{MEE{>hKwmrEau)q!-G_5IWe%--6VmAoqp5{1$q5ep8O^YfQr&jXdF?!6MZCsnTc{ zKE!&j@8MxVpFGxR~hbSXG=-~I%9IGzC=A&-vE%ZbF8`jU1UZ#ra(`44H7k_Ee%W|VSNa~Vq zTgqGz%iT32nU2v_OcuB&0ymGOueMGG_I2)DNq=E>g=xSQAQfjm0l9UscqxP z8hY_Nr`EWGEizScvEeKvmmOCt$I(nzHS=MX1&zZpf`V%z3-*ETx`e(TSa(<2j20(+ zTt9pK@_Lb%(d+wqgyYo_L!nhBR91X_5A{|`M2St*NyJMO4$CWA201Gh4IbcPt}ezX zosAV11BpX7LIdPQcjWPXghoI}`%}m8dfyt&tAom^IqL0zkn5z$l9t-wnrSsSHvfh; z5|Ihy(D8i?t*Xug^zW)eSjXXr)e-SE%t=V*A59WPEO}Q_sQ==)o5$F!HZ>MhPx(b_ zl$ezv0h;>w=_wq&C>}J&^Jiz`Lx7 z=`Wn~D0#G5A21oMuhx~9Y131%>7C|%V#>kB?vnhQB@0@W+N5coc!w<-T^}2AaPA^L ziK+?4Gy%4sc1hH9YV34qXeuz9>jh+F^Z zJw%wl_H3GuX~>c^p5JWor`nMLkE!Q|@kF78+QNjB3J*|W&w#{@HePSR=K0Nr_{H z?~`ez%W;krTK`7=Lk(FegV~G6^B57w92*Am9#V6LYOP%()0fQhjdhTqtR=mUwnh23 z;+;nOXL-E%h|cOouGt%zGwYvlPs;&seRJXsgG&W`iqF@F+B9$>t$JZc-YK3O_8Hs_ zlYhx=T9Tmz!*^`*+{K(fQAM^}QgR@#fqatOW>#4^bt$nL-J1$ic+rgq80kPa`d%4@ zWtX6{dO+tI6s!tWLlm0H%hVP#6Z~4l7Gaiw_gX37Y~fvVdY#uIy3v@|^!n^Bop>Xu zt$_!o((Fs6n0T{ut9Itt6Le!+%Y(vtiI+glR2HyM?+ou2@A*{;9{$nz39qSBi20NW zD_(|lpatavZ|BCHeTl)Hz*5Z%0SiY8CocHAicP-QlpTq0F@|g<*LJ)bad*nA92B0i zy0bOwC)6-)svtgL)&{(=aD=3$GSB5+&v5sB5Wi0vEC4 zHfU5Pvs*R6^^E{TGLUi(pH$VFbpy^huX1~?2%lsZq$rAN;sO9j;QIGeLG)Vy`AVD# z3P|!I(U0lMOG9n9Mx4&uj+}`~xkw}EoUO|YKgr5{e;9g)bW{+>?&JdSJpRX9Mc}BZ zN{X(CZcxShIHZNFAQFor>TdXJgB4}5;1==Wr{6t24@JViKeu^W_x6kWuh^{OG^w}I1~Jie?)yhnVLKe$mn zRE?+}0J}*OhdIr0$w5B@ZtqX|4~eJ579 zh``VEc!?p*pc`vzoEL%Xn5#!sp&J)V{WW!4+kfjo))kFoEC2jDe=~sT1!xT^t|8yM z+Xvs%fC6%K@H1JiD9(G}h7qZE$*K$3`@l^u#Ox)v6|gPGml4TBrkkMoys_8>LzBAc zdt+dOQ(zZq%B`MG+|l#v+N8G56n8~&(kSi)aBJ-WD$?YCvpEmMOiM@BqmY#Zl=`QV zfXVwvF!zz|d3}t_*wG}AHd357l&m;0rT2z?NfY~KGhqI7gAG&t4H89hHesL}gFr$g z_mf=pok84b&QV+r9PC*oF2j<6-y)Ppg!nX^y~_NYLa17muxmN#v@k_$%KH`?HaY#| zHSL=YQX_*EO^FjI=6n(w75eF&dcA*3VkX*MQD8z-NQP{!<)$b=T37--j6}r1?8ZiV z0FgWRzQ1G@-$(8S>`da%UoBPyO(SiX_j>bq-&}v(>({NYR@_;}_x140`NXc94IDM| zmjJC4Z7{y@8s=XAagTI!H|H5cH?TTLYrX=kLuv!3@alal8I9)c862<82%SqB)l2mS zM@9%qf#bb?jE^hMxi)8ejAXnbK$WKz*hCWfkJYzd(V?GQYfXHSbC#A4>7n^WRFznQ{enO9(}3`7Cm|#{0|;Nn&$xSuDH=luAvgb2 zDbM@a;9g+-Nxfbvm+f4|vd)szMj=Uj5O+%c7t9a;EAL|WLYc}bIo9z@%!PMuD6=!9 z|B$v9DN5FVvI5=iKZv`Zq^e!wi--zZiVAPcN@O1XdgERF?GkfL_tfs+s?VZ?{?2eE z4R_RzYl=JK=vt`ArdK988>9m^O#p7UrQ~E~0Jq0dl^_qZ1Sp=%iWeIA=rWu7pX|$M zPsAR$Hh$)vs~BNFbi^e|bSh%s0Z zZ_Wyk{?tyc;6!m!m*gB>}8RYz_#nWx*sRuabK3*=%};|V(8o%fL+dR50j zam0X0QFa8Bw;$Dn0WYNEv!U9!wK4IyZNa5hLou9rFJsheepc(H4CxYbNgkXHUB*N`SS%0KG>Yn>L}8=6J(+ekSQvPKuKHcBtJ{ ztfPRNxl=PBPy*U)j_0d`U_Qfcr5Ww#2}7Aysh5)Pv?;c&4{g2y)lS~=iLf&@oBb!oe<>?eT}E}5uhR>pDv5cBH6)LS6cSNl zHFunm&2b^=z+p&cPqvN$)TNqPlNSyz3^ftY!N!q&@jaZ(OG4GR7Oj$V-G}OhF)_)I zLLb6G%>#rzQ0B?Q0||0EnX)k&(ZFpnzU(s{F?SnRa(*c4`T`9u-|PQ7GFe@}cZ zT?{XB==D2qi#kq<$_dj;g5u%+dN509;6mScw7RBrTr&n#pE$cREp>w}= z+P#7x(TeT_;=y_c)>u4fJ}QroWOKE`TU~r80rD5z!7cIw#6i*|KJ&?d{+48q@OB_G z@+J2Sr#&VFF+Bf|Jv!PCZv+Z-5OE8o*dz=Z<@~3ka$26Cik0%0VZd}Pa zGh+M(4RwiyrvujmN%`*U5y&V@a7)%bLzew|XM}rg8TTx+9U}tBTFTCct{KjVdnp=kIHDx|{=Aw> zbI`vucW1gDb3AL7?TFY?Tot95?}r!}qJ?lX3=uN~*A%W{;{Q)cCk8Tz;4h`{-Hf8o z*xSvZn6<-LbUq;v0vz^PRXmrhbzLXWr+RucFQ!Bw(_mF27Mro8VPi{RT+J9vV6D{d zw4=Hdjy6YL1pE#Z#CYKtGHdOKKn2jOC`#>3Pmsa^ggk$fFDg?-5th}E5ch9b53GKVwp(dfo2fC57`ZfT)_9`X`moS z$pM@f+(^;_U%ae-a%x!?m`@DhAHNu+y<5e%W}BQLTyiK=(w z&d%OPuuL!UP0g@F(83YCRu(P%IqM~m@&lI^f=R>Nn_qBrMZuoIaG`2G}AU{aW3gff-( zV-9eB%9zxvm2w&P0LA$BbTs9Mv{v72WV^%U>93bj9b`e&BdwCRRW#*t&9s}8uE`5UXy<}S78||5_g){;3{@m)g=4!qcdLozP^;N{ds!_dKa~(gJY%= zcSNiF^bDr+Idyo6DotD%#c3jauf-)vEj^f(RSg#Zw>P{a zIe79T%Lg;RLrHbVhLc9g&w*Qf2MhY+38j2eJ)IJEYh(-Zw&Lt+eXaThe}nH*ij=Ku zLj`=mLe=U+7iRD?ga=ro;0RLhN@@_(iuLk-};?_cp!mAGCgW)`qm71}HZuzO&__7gOqY&oEiz}6-JQ39)B61Dje z=x6uwN&-;_x0Xs|;>&oaaKZ}=R}}muaM%*1Q|70QgRR^*o$h@Zq&54mW0O0?5~UXK z?@Hh=2CXR6e1b;0M;@3V@2&Q>+whL z6?s;Gp;kwE>wy+Kf=0txVDKptEhA_WVCE|UIkFuA#6)A0ft&&-10>=D5IznFy@+^- zGI4D9lE_XkftW~v05&Vqf1FCw%R}N&c}X+n;=BiZEfsW= zoZ2AmuWiRRDpQmhXymaPT&&-o{D($(W25(m!>R9vc~jcxP*R zpXpmF{!yO+_;;ev46LJ(eI=s4BV3uF`e zq9k_7KBToI0&-_5Z$TTB><^H2(N$=f^egD`Ml^y%uLT`+A{P9|Iq#3BB}@84*53UX z-MZh??Nd>1ifQFSxF`B?n=(_77|!tcT@DdFcXEKj@$)W&g|0PH7lR$a=(Y9Fa`XSx$u&j3}43S6!mK|EcCuF?pT+=7cs2g>l(ViYVE$hX3eVq>r}vDAyS z(AqNU8p&{JqIG~mEhC6fC1*|MqNavQcQs<`LKucgM^77eCj&{6Q+6Js{k}d(7*nJ{ zD$;`wX<7)`P2a^$#UR9q<<5?^^PIzY2`sBnPpc~{f0efj6borYP56d>U(?)@ncX=# zP4+-xJEJt=;I~9yegecOwFB5d8s_~d`3>>u@{LviL5UctN;B0a(d4yojJDB{m(&FQ zMN5i1NNB6ml_2mp(V5cN!-8{&~h}xhanNz6>kIJxx->M%8GB*)S17Q{pp2 ziwO_e$XF5HsbK#t#7S!j%={&S7=yiW&}p+UWGMAiF6e z%l^+@n$3hZ(sa-nf0nH>zQ^*GFT2VMW4%y2f0*0uQ^b04);Mmr-VOL`+Y<5MD2yKy zBTPqGz2kOe9aHC|j*cWmmZyMHm8?i1vXMskz{r#w?A5}wnA!oN(2k2Z4J`%RSj)83 zKM4O4w2W(`pTJCbx(o$6iu-KVM3N>uJ)im%O*1nWhYqL;nYXmQqNZx|Z6ziBmx&Qv z6^6MhYDa-Zb(?ZWQB{AUj}fdrP^>rDyja#phA@uP8r64q#DUe&)nx80&X*nQN(u4| znFm;7Ql~<Ta>|*mQ1pu9Si9l{h)@>w(%%y<3%`-bqyr2YzH1 zUIt$eIbN|lLppf=;Lxp+?7E6RV&bvB&$!iFQl8$&`n$SBM?If^)VW=Gw)EbDo+WfG z`RKa46mSFBh3lpM%sbJj+uwBjFyd~a>0!$0*J`_o&kH7fEYID}epz-LrF-;fgkass z15Gc+{?%h~0c~=c9^)BbHYkQKO)ZU;NhV^h)JuV3lqGah|I7O8!dvI1s-%F+QEO*} z0D=;#gUWhhY=e~(yScj$LCdP`1;vj3m{hg>b4VxF_S&sAAV61HC5S$I)(rsNgM1xW z=lJZLSh8?T)6?YBm-3ukHJ{|Q)W>IKU+8U;Xey78Jl?+hy4%qtg@6oPz};F&fE9lK z>tpdnap8h@zFz?Xd@Qo}o5soSlfCm3DR@Oo+|AH$Tp+08re;Y(m87~v`XT*(U%5Rm z-eG1t!>m~+CkCX`um4=Rk1WK>d%=zcT~BwHeqBXOk101M-Zh-dc<6m=Osg_pv+-i+ z*Q9Hot_BpJ4>OZEcRwI|=%$QgbmOU;D$&X3QVvIRvA2_B?vnFI4-5c`4cB8PQ{GG9 zf3=sW%#}+!y_<{OK32>ocHQ2dNSoK7ViB1Feb1mMcpuijDRFBpt$ppSV3k8?-Fb2B z4$Ez}DepHpg&EUqQUd=! zxBCB@&41HpyZ@&DkCXlX-Tc3=k-ts;D?HmB#CO5}&x*NqLvY{U>^=NnFrVJj_{;qd D#=K>! literal 0 HcmV?d00001 diff --git a/ada_feeding_perception/model/pointcloud_t_test_detector.npz b/ada_feeding_perception/model/pointcloud_t_test_detector.npz index b7a79c2aecdb0c4f085c2a2953bcad32aaed9375..f5f87247ab8093db60c7317dd2bc7cd85405def7 100644 GIT binary patch literal 181044 zcmY&fWmH>Tu*E6vQruliaW7DyxVx7k#odFH;#!KkySoQ>r?>=n4-lM}@6UVdowf2K zxp&q*bN0xdxf4|dcm#YH7?=;x4>gPkvR6_874#b&3=B35K8%B-iKU~ZiM@rHgDZ!F zlQ%5%*Z;2lxBk2Dzm=s25np(J=9B-HXQxNaEPp@7PWSOr^Bd1M?Uj%8(%MB9n(7ft zf-;!H3Zphu9|`_sYDC&4Y00eYx<0?5m;k-Svf~ab6Kl$FN>>k>8iF4NU@2x&Ro~|w+c^h+R7T1KI({w?{1$RMgkqR=jYTCv^6vn zx~X2@U$)~QQCWYvJS|i%L%`@_Y3l-p%fKu+w{^Rg*sGIVbXX>m?QJ>CF#6FxH%OJ z4gG3W@6mgY64ngvBp4(N|eyo`qp-jOkC=K6VNL`Xxpm>A`j6KXl@Jl-4?#z{! zTx{Q{x=}(eeb;Ci7LP+sUJMvunY6wV%qxtiJmsw1Rib=~a&JEKN#;@rTV-N8e;9>9 zM7c{KVr8cCF~2zc`Ev2xtz@V4uo0z^Fidz2=+|yY_BO*U?=~7!c^?R*MCK9NM_`V3 zeq4WaLn1e1OT^Hv%MHk7@;I*?lGo1Jo(J zEU@^51)6$j6KJ0;b(g!dH4(>g^X@T2SWw9@x(}y<1k|{bwX*tz<}rAdwGps;h88CR z)F?oYe>^M6K`W~ao^L(uaF(b12BD60)XHt$rouaUp=o8WsHY-l_KyYEG#E(t&T9f$ zrjla;BC{$8OxUDi+)cjGn9o(&ci+AP{j8AE4LI;-?jGxJCC;9c8-HbBU6aR_QsDqi z;il@8_8PZ5V=kvpD|-b@Y#QrIsKwaRzgu%WOr01E`;l;g-hcCA{Iq3Kt;kH)=l>Q4 z@8Cnjc@2<_Aew$-!*;qeZHV2aBhS_cD`)jQyJf$%MAO5)on^)uUZ-F>3b?kMm;+^m zY4q|!0+G>#%GCr+Ncl@hL~90wmb`}2u<$#PEkOr#umJMt zj7_i`ac#NK4binz^4reFr=3nufi_XB-M!mAGK;Op*7jck@#u&iZ^m{d9`h1&rC(Br zPW?EH>P+yS@2DpH^OPeIHoVX0rR86QxR_Q{*su7!{j5!V$}>2~et6Z2JlxP2vLmO4}Z$-KHWsu{?_!~BvF`hJ3JaMZo$*iAOg}PbO zJxM5-Nwnq=Y{v`p>v=LfHvwx;Ay2$Td-Jwyu~SzB#m##Bdu4iwk}|({$I9ts;uUoN zy%u4Fnmo!Ku&KXuEAD2?AJ5Ws36Vm;M^4Sl{NRfXE&dDIw~UYgjJj>Z^{#fa?k7g_ z7mhcKj%dI-_=U)z*B#Ewux42dpE@t@PW+f$faq9;enxLEu7^~ExrY-ZOns+ zy0{L&B{J{^j#p*|hP<4c{Wj%##z*5oC;k)S*F<<%nJba2ohnV<%7BCt)g0Pv1<(=b z8ONK!$tJD=esR*zPh1D21c%V|!y|cDBzwAXa!i(tq;=oH6^+*P{pXW07L{4X(qKLD zof$ZtLv^Yr`?l9ez!4SpE|}Yh^XjcH?dN4X64IHMXVJwi zFPw3;^GP^94fU6O@TBSl>x-;>)tm-PWec~#e1S}``CGf>3WuV#!Gl-)FTZE*MEfkx z#qF6upHliE^MDrzFy`L7o%TYJbLOyWFvd{l!&IWNkRcCgL%8);>RxJa;cEBSAcs$`rwmb;AEBmWf>pKl28fGS4g8(=5^w(dJ>b=3_!0kEeakWhh zr%D>IGIK9{YspEj5BkXDC%x%)UuWD6duPq9;QnAV5HQWlZXoR!u=A!_#IQsC`XOaf zd4M_~^}vQ<>Jp(N6_sf5(AOe07UpCSWyp*kXTTu9Do<(<04HhvI?wqjn_+*tKn3*a zi>`(G74yxu0l3f-z7qV!Yc+%CtR`xCo6+?cVWKSE@u!%4Um7UMc-6fW&7HCjdCGhP z-?%LyoboZoUM8T9v;Nm+xq>eLvCX-cQ6^-oxgHdDm1$(^yY#>V>&`gVc+WFO4LSOL zp`F=LGnD-NjKg@w8fV%6fqW5(fkohZri4i%=GQhWn0=MWAE5&p-&zyX9Cn8S3mUb8 zs+Mb#m-$8$A#SOciTZ33hI+<}#?(Px94KHR;yCx(!@Th%Ghp>b0;%M z5h@!U?Zq$-s#5QG(hup8f1QNs)oL!#;K!twe(=eu<(_NA+^&cT z3G}sh@TS(VE*y?g`lBXt-XJSM=7T(q*Z-kUqw(+-JM6ZR*{JHc^!WksIa;f^rt_>Hv2l=RS0>_cm)=IUPYm!#0o&-wp{xHI$|ADNp#pTRtQk%Ww zw`ejfdRt#w-81Yxrej=w=P)-e(YWgtHV19A&y5+@irJoJTt;Bc=JB+g4%mvAbWv-! zz`N_UB|SXCfg>G*&nf^faSa| z-0XD%H}%uw>SaOy_RuArW1nS&TVF5_7S#&H`hovhK_M6+gWj^5vHN}XJ@OHC4;);! zt6~iPb9FZkTKP7h(xQ`06Tmk0oI6>DHxf2)+fn^@Bxe@upV+07OwRjphp{&eO1&~t zv=pxZr;D#TUo^IU?y1J8fhc?ABS|Nlir0=5jMd^v?+x*Qpsc47=4Q&X&&rS4 z9GE6|X$ducIj6IPl{+|Z=DQx^j7cHXZ)!KVG`>e){L0e~2K*iqK3hyDsct7(#kJI; zVK^9Z?l7vBi2RUm@ZVWK_iR+t|MI5SA!lNax|=ywy!jr~x@wWck8u>Bc+xKHXeJWp z8ok7uZ!FTheG@MIZeCi2Gacr>_V$xelO0?R@t9ST3s=z!j%6n4r z-s5AI`^fYkc@Hit=eQ5{>v!MvI1vUb$P1h~Y>*Oy?Q1W6-TdiJr~(}9Z&%x3A!wV` zu+qx6kN3jD;D>8~m}u0mLmiY)QPXWSq0h4lzGG`7nY7J>W^4RMQUCCa?Y%#K`(+Uu zxoHyJU=AK3ytCNsRv=B45TVNvp`VHK`cx)lOC0gM8kwUciaRpxcysAqYMO1yXyuaMpSIT|rdLxM7 z)5nEQN6Y>Zogw>3^XVBN;(9A7VdS;1-9>JDes!1bJXaB}QV&?zlV(*-c2Qi^k~8p5 zT$7`LunjdjiN&+Juk*#^PDC`sJ4(9p_WM zv^byJnYIRS#6Z9%<2xnWdiG_lvFURX_;5vv0!R z%OJ8R`|J$~S;yR*6|Rbk+RlJ7&JF%p2(9U-6)tm5A{5a>!5yA>EA89L?$qBtYVLk! zP8b&&Ar@1U0oVR_b=kIU;bBAnrn@SfvDA+oIMgLY!a~Ju?#Bv$Nng)>KjI_V!|cjn zzcQ8l667?G^-toCuOObqaecQCojpU1(*^fVvpNi0HLHGO`WOxcIo%FDdskSBb3f|# z50MHatPB_5-yJ$rg!f3?9S@DQ*5JNy#x8c>+IJ)mYR>R0dvk9(NlhaPS1lPyCppMh-~ z@sXDxq1xr^2Uu7TQVsb^M>fJqTjiN^^!q-zP+RTA;ZfKsOHky}gRiS8@PQf4i;Zru8*tez6|s5nSXtyDok!=v$5u{h{-{#xsV7G8+^f@lX`xL!LQ=V;tr6 z{Qbpc8xI+gj7H~&LhjTQ8{1F7@bmn$$I&R=PUpJ32wQ}|`dv^|uFwGieW|_Aa#W`b3OX!C-)WE?1RzY3Ad`pF#nuYa-Q<-kB}4J zuE*oPn`n}1x@J>NmBgK9yIH=OuU%IzClYp6gi!asR`;b5>3cm?eK?5l(n{ zK?4IiXTcIw2fhwjl5_YcDc`<4d^?jB`axi9Z8_}eM(z{xqYl%2y?B(rcIv?Smp*zW z{Q0@yoRk2(7rx&_fWruUve8&3ky4teH|XcQ^zEU|kfYbe48MAY&_VKH3-zVmKjzzo zg7t;C>|7O(RtLXM;!{@vGpR*Y23T8yHv!w$KdOM?Pf~EsVwQuu-Msj(D(4;a9Jh6m zZ4T7zx?up%1~C0JwyAfn2r~&_H{qy!(IPv~0Y$k=(&V*Uz}^zudm^11@GST5G=?Ab z6wFrIL)+K2hzw|QnCSf;0*6$2G6|WJ?*4p$s#`Y^CajHFufM>Z`}SujO7a#3&FbPJ zLn?<-{-%3lF#MB<@)tJUK9JN znY&ZJnCGh;8~URinAC13WMMO|hL zLwvu3zLtsasNYvlZnGoFU(t%b2h_ms|L#4vg{1ZHJ8QZL-++t524hMRt*@*``)Y6T z@zTZj_(i{NTngT*b-&|JH4U|exc>+^R*uX}LMa@G4f+JD zCSPh=2;J#M`Sa;;cPo$8#K*qoB#)-VGc`y2PSjM+V;vzS$UD?UbfP@g#AeoW&p=Qr zb4VGrLGl~FQv^$j#zfuo5wFYiWtqmtH;jO3{YQWHKfHBsFXT?(=D?5=R z@cK2cKH=snC(dmJ0rT$NZx898q@rV5TNu)LqDRd^o=oLp0f7+vq$welVVo=1a5b}t zR*YFD_Qw8pEit#H)*%JhsUTKm!dCv-2lb1Xt=GaCSM3np016_U4NbqWt(ysOU+0CL z(DOJs0Mq@>yT%@Lbk+G(dcc!y!gAf(fqMuroVrM+pVCS4bvwE-4tUL<?Tx&f5 zc=W>n@Fj<~-o%J=n;O=toYJ3PGKcJ{i)(`T*}D7bpe<}u^P&0k@;6Vcov^0HA?$0g zBkxil)lEQ63-A5poZ(STR>hYWGjzW;d4-brz_qWt;I^1fmbt36`EdV&vIbLWitL)K zZ!44Fpuh~FVV>2$a@gu-yo%-Ddjc1LI%c@|rd;)C9+G6)a$Y*Qo$JGI+*&oCrbe20 zm7P%$?3yTZdsCX*S^ zDv{mmM7xV*mnUlrXTTG#We8KeJ@&dK`!G>j-0w}br5NL;a|&mTGV_REcj0w@H+~q2 z^K!bq?#%H{vGYcaQ>M*hpCB(M^QZ1>A09}}Vu@%0m2vCaFyRXNEvd+`^l-{^{XuJe z<}*1QU36blGg?B=x*on}^qZ@yfPnw1iF znhLt)2L`#=cs$t(A%~3b`$Z}TUk-#ZNdbFYF%80QO2sIta({KtWZwReJ})|iyWR$K ztC?C*zzX$LJ6}*eWwwAy#%CBw1v}a|`~4c$^+Psy{3Y%xfvqo|rVF(}vjTfD)p2Vn z9Ky6Ud^rTEQaP5693@&YFRI3=>^JxTWlKA=z)w5dAf7Z$Ky)C&$Nn-VqJj4pvsbm- zI%P8l|NdnYG}1QT-8VWr4$`-=;7$yE_56>zD%S*;tZnpir4MoY;p~eN0gUwL+>0?% z$GHbvB)IDhS-;4#(@b5q0a?(MBtXSYrhR=1Bmx+8jYnqH@(0T(fjCP zr0I)H8?9*UQH^>vf9yq{&yC0Apuz5Afk6avf>WF@m3z7m$)PhK->H}KR=Sws5EpCf z?Ry0t;4doMXYrslWf}&3+la(Gx~=Uy0__DMy5a!1U&~j{gbo zHx;ASxfNVd=Zf+d@C*$LFaci&WaRNnI5b^W8y9rl8xE2`~m3eDWIFJICmI`} zpMOCofTW+L7$NI(W#4fzRvKM(todPHDD?>7EuqDF(~6@ruFr<|Jh)Pj($xqkBd$Gu z=|}V9v2Fw{Y;O%Bq+tbtmawQUy}5u$+ubjP`aR!ac11{ZwwM3@0^>sZigi+d=a;$- zeV&TS>WAmweb#*Kr&^Q?Q~4yw8+l2oTAOy(MDvC9kj8=u|FEuSP?+E_MA)^d0_!Q~ ztRPqt)rO9&K~8ix^l2YHVEtDu5MY7%v>2WP+9CLhetau!P*Lio8UmnK4T)SaZeP4Y`UU-x-PUGEXf6F8_%oOC zp%LS+c4vR)V@g^#XO#eU^%q9+!-}DZg?S=p>t283b3qAcXxoj-aKaL8?@_A^_WSH7 zkY9uQ+MheWV`Q*yYsV*~YuI~9v6^rGis(+KJAQO;{twZd(*w}c{y5y_Rk|b7Q@tg| z(T0HAs(UL|DQlD}pQXP2E{phRGQq3A!1GPPVMQH~j$&4=G3=#Axl5VDH~&-m-2{8< zPvCWjr^w4=USOacQIo!{0xr_qO=FVTD?Pdt+0^cHLRC{|r#~IfhxSkU&K$by1s7BK zj?SE2H&g`fV6XZ!cIoKDvyl>al{(-OXyB0}_p+Wyxzs22FpP8|q(V)_(NR4uMT&en zzst!dXud6Vup}**DVP@pF~%3F1&1 z!2u}RcTuSuwhcHU&QjpwfvKDG3u|!cEZz!LW$3d2HWuHrSd;6{vquNS5Ph_#yCwt1 zkr8*yzIrgu^rh@44`JLe0=g3;3X+|~=E$aV589o+9X)Fb(tTa-LDJsm_xG2&F%FkB ztOWdLqe(~W&Z|H`sXTU_;iXynmy zN;!aiNzOW2o_2LA-!o{WPYF>8HXT>b&UYn(!vWHDv{Q=MqR3AfB-rms8H2tp_+P$D z-fp*{-x7eMe)f*|s{6@#cGWr9+|#-`;vDKJ<9^IQWHwE4HWmR!Vb&vp3t4x)IA6WdFzP|2 z@V^MXhz0cPuEMRzaH#O#QWe|Jv7^Ae+xI?B^iPUJc-Xe765?d!&MuGdCbz2!t1pm0 zAj>7UZV@F(-*m4hy?-IY?#%Z=;qUHio1j?7g8qB1ae47*6KS?rYvPlQp^&)O$|F*U zoo%UC&>MHQW->-EVDa=RA!32;>Cm`(68I+|y=6$G`Rm4ym+ta_)yUr!VF?cNpQhen zRsY|R1GQ%4fQ~#246!W?4A%b*IhZ?o{O^pzf0zDS|K0ZA%3OXFP6WO8T;nvP;^=EO zVoT!^Q14{^#z$dJvMyr#Ggq9D_*G6_?)M0861zf#t3mx`{pGXzsF-<~-=V9~rRzJa zNs0*txU;&=ko$1`&|PFLU}WZj32UEazc@On37n?z`2_bfiB-$ET|&H|@AlljLJ66Q zVe1czSKyLoj?ksuBw%CZAn`Bn5^1950-qd{bAScET&w&`fPX5Dv@%=^M?-I8jh5T} z53>9Yudu2msX`2lljs8~aEyV{4dY z>P(tZ(SXuV3rznMn?jYhV!I$AYIXk1crxU8;&z2;7(2}yBl#sl)OGo{jW)+tg-bGA zsB{h~FuU+r2{d{pqp?|s9dRTKsUL<)?556`a$p3jkDn;3QwsV`mRGSa=}}K*J>W6&Gy%E-%P@)BOlh=7j?ZwPp)XR9s$uq$6I`T1*!Hm!i`2M1&MUE zS$F(34=RAwSbUwa_<4J8TC2S{(}l`M`BSu&+$U6`PKtL{_B1!Ug))Q9Ec9=3xgSnz z@Ti=IW9<%opA034^{3vP^(RzVBDn;VV4{i(typx7bD9ubmZ zbQ-=NHI4DcR@8N};6vSW`JyRW>&o=@i?}7HL?&~bvFm5ShUO%$5V|>~eqr_$ozpNT zn_)@qTN5@L0@q;8q=2be%Fnl^-Llg4bFV?!agjOP8g?UGvDqy}*R!xhB1Je)J2T#M zVRb~wT9J(%iAzfgrev|Lt$mG<%8ui;ubysjcCIT!pgUeoV&JQUvkYcd4|&J;lmaa~ zYP^#(rTqsR^{uZ7@nMQ8TtYuwJd!MBxO=n>OTcceNvL>^`mS$}b13U|CVa+drs>?< zC%$K^=dN~CCV08`zgiJ~CzEX~cWuNqUT7k_i-lwE|4Qq%lO+riZjRUp2 zGn<6p*6$LgZ6{!2>i3X+Zs!Qx5Un*1#*qrC0NT|0bRHvIEWbQuXAJ#KtKArz-fa;_ z^iX3FYbc0}uP~>!dXf|Fxt|oo2Z$!2+M*%-RZ{p*pi9Lq3S&^$No3JF#+#M^1Cdv3gM0CIw86GArfEyF~Kpa6e~J{oXPjX z)_jXPQRvQ7$!;2y>pqOgSD}D%GoZd5yXWqkvz>*|7()2Z_a(3Aug_Y&lEU~O^RIDy ztYvtnYsa%=?lGlKYCq)m7(Io8ggxxfMlf=m84~XwJ7j&R5q&CzI>>yasDi}t{I0oU zU^-d{oag3z({lN8Ay-FKV`V~v2AqCw7bq)a zPTScRhJpW@JDVd7BKm__pcfUf-uih73G?G?)c*onk+q<+HwV;fQE1qM)=iv z0kk2?!=zrK)leG_1+U8+c(XyS#g^*FJm_YMf=ui|+{Rdq@bPSy=Euv5*QuT{elWe$PW51i-O+9P%CV)`<;+OP=qs9qKES5=5#2T=>SK)(hBC>LY*B3(l;rn zQ9b0orzPKpY^c!P8=L9Bwbb=yWKF&+TLPsoNOqIYA>w~6d75k^tme00zertY#OXpU zYE7JZ3@Av2ZlO(jH7KXCl{4)^aM^+S=V=fQZM@I&i%)mo%rD=IQfcM|4)q^UEp#&L z2*kSM5JTX9Mnpsv_o|0%FJfHc&EPI71|9nG9j{`9XcqX8xVf}Bl|FL)h5BkyOYb5` zebMQI#o69epKRXg6<4r?fZ3lYu8>;?`Aw^WI0uE5Bc+CLecrON-Y(W-Yi5q z6TY&34Q`TGJwDv8=!|a(Zf>o*rm;p;DeQFRv>h|@KeYe$6B~7W{k`1-7NtJZ!;F8B z5!PXSCJ-gf(E+26GQJkL)%bREk;g)a6=T7 zZ?`xa1J{1YJ)6~DhqHG41jdh|z|y8T;gXl7I@=J98k8z4iLxb9x)3GiPpyHo!r7WZ zh7Xh~=}T@fXG>G?p%Yvz>$S!QWbWC}6lOm!p=rEeAt5+?7h_YxRJ*np-#;|wIFh*N zGkGD;-II+cbh{lUhT(w)6n8R?lZby6mrY7)(i5!R>fg>$h?-W>fW=O| zv6WzNK`4kecA`kvPH_!2s(^NrP8YmSPFfgCcP`uJ<>!D0s!O-1pEGvVU*V-?Xn3n2(dD4*674=gj_f z`DbI?ut9?-Ig(D47JkU~&KHV2!XR`i<`VyWETtGsW4>Om;Y=kA@EJ&l&i@2$8Pq&`T`b;QC)aOg3g&+7(Jn?bt^6v*;ezY5wvV)77?-ygpuZ z=(Y|=8IU=d>rBnd9o9J9F};e;KkBqGq8UBk`PJpk@XvX7?T|J@JF`>uCG!0^>#h&L zSfd&r*6|Lh57`khk*9t_n0s&fc5Ik-GM>T?bHddge=+so)^&qBXRN+zt+>!b5fQ#| z0=EPApMN zzzu?VSi>uq5Bk`PdBbx@c6+9}8Y?u86xemu#}!)1g~71!VAb)G3#B^Z|FR?PZY}zJ zPlwiDl^A0fvZ+WyAG`3-zhHZ^qA+Q(A4aqSjF1&g(`#)wOykqzy zep#%!4Gp+O1WiV(gp07XHB2jUChc;;yDGrm1LXhESh*>2Cb3{U8kWpquU!7JUl0;w zto6CR$f!e?B2}tgirezVk%9aI$Bzyh5GTDAYxIXrT%MOOlszV75L6`4lS+HQ zkEM-&v?rAu?vL~PhNHXqpMD)dV-$TEpHXe$!K+I+-;_66816%BlkoS{O$0euhgBy8Gb#s#PE-$3X| z`S3HaREojzba=OXhF^hMWQ))@%KFVgKH;clm?5RVQtoXTFD$;qliAz_2!dLO=;74* z@G=Yf&+=W{p3X_GCp)yjkRx& z?F3f2_aoy68-ih2ZwTMX}s={?M%PrnNafW{$9ZbLV>3sUx`M zm8LYZIKye}^w?h2LP7Ya+l?#hy@H*bMNNIfNT=aHLpOZrZ27 zVG_=`b!gBwzZ`aJ-S7fzkpBnvg)om4h@BZdc%dqmt!_7{goFF-=Jc=t9?8TN2`K~C z!+k~{oREs92ERNQ=hZIYrn9)JB-0YtC# zt!u`1qmZRoE5u9~BDRr$5582wSg-UR~j*&pm>?nAHqKJmBDU|-XdPn$}ornbzb2M+ZP@RL~d=D)% z?267QUKMB%x4U^-Hj$t3t$D!qibD;kD4o7#{~VW4YBQD`QWf?#Q=~S}e45>1p`2}v zd#~O{lNOKgY-{?eqPVAmBrm%=pZBQz4n+Q%=@2;S>7KL>YSQ$2$bP~Ar?^2Qty@)~ z=O3ar2tz@t3637w7Qr0+6y=DNBVThAQ8ov4R`pv5r_ygsfLq3DO!jA}9x5*t?cm{W zA1(lxy}sI(x=~b3&g54;MB;d0in$)jQQzDPqUuy~pW|Ne85nJw0|j?>71sV^lJ|HtC89*xH^Pkn;-*6#R#G&>ptc(M_(p`JHiu`YEcmMve zGwi-TKX5FJamZxSo9Mbc<6LB$AT`BpH9s9-ijFNr=`|s#P*}WH%YERM$X5F3eYET9 z3D|Fw2|UlEd3uYY#(49mZ50a|gDP&!-?3mLM~QbcC2v*TJpylAy)q_}z$z2TUNc-p zz6R^Dhkz}ISJ<0)++d;524=okR!`pMt_P*f0Ha*y`rcSS2;S5_cu5Pa(mxG1&woOK zPDOIucQI&Tbw?^$u9e`!uGhI68>g8pNCh6!SV3eIHFAT^RUzWrBzs=A-*~>1qnXME zyik*l6!sFK)`ggWW}$#jE*Q(n3V+@{Pgz=esNN1Nx`Z(@U_*HYUp*L?q)X{{%UC@g zVz?c-ALq|j88biu|MOj3=h@%`N37g!Y|Tz}f21J|8B#ugLw2LZDM8MJmA623*{yZ) z=j<5b^?#Hwsp`z$ldbKvHm4x5#T>P92#X53j-vA!PlddU;3Me?1+C zuBy_d`Uu3L0PFDS6qg**q6SYu%|2}h9Q&>PvUAv%A@g56JmIH@fokJ{=ZO+W*`;j?RKt=R{;>{)GlcB$E z%jO?p%1zhU>rUc~SP_$Dcgm_)nWvkdj$l|5A)XdDm36O_=g!9(^WmS+*~%QE(705c zr<~1_FQ5%G$O9VdY~j#>Ie3E{#$Z>vM5{>*12b?Afm#$PNcdjdOvh_93-Qs2B3K>` zvz1=+CN3>LI{LAHJ)Mwx4(*a2!OrVj@beFcM@Y;S)R`y+>SyJrq_CgTf&bj;m$yt0 z#zW)JbK;k_rjgc`1PdpT-rD$^=eHNa>lQkIPB{ke?q`+R3A0HT>(99jvpI22aBL7E z@?`fTZh<$ts^;c&zxl5^hOf0UD&*2LZ!=8XZw#Lp{o+Bqko4pm+LPwP8z!xq78+qpjp{t+8V>WWk4 zhyAl9?ITn>q~!vJ;jVt+pI1Y#+W`TT+|WpZ@hT*nRo$@lsDYFt!Gvg2F3`R|PDq7# ztqYn5uE8{eYqhm>;5~W;6gSz<7S1Qs2d**A^gDiy|EwDNZy3Y)(W?d4 z&X>Zc&ykP7UvzZ#SwtQxkgeHLG*E3S;cBouVE<8r3a*=+JXRbl654_i#eDtpv>1#P zQ8j+-bZC1QlGFAK<7tN@U8e)z+2`bwa+Iy7g1XLeJDucSfPY>(-c{@1NZPabM{&LM z>URfFpG@V6^uPAel8=qBv~8_vzhcPRlh1{a=4A{J!iXm=RI-`hYcp3+y>&Y%#!|?E zgCZgS0_B8c4R4383utCtAfr=)4Cbp_V-@EG;Na1+?9kGH4m(VTdy|l(IT3-7qXrvc z?kDIIW??}<^JF%GE#i)Di3B)c2z~>NMMeDmP>BiT)C2Bp2UP~#YR61U}GT19dEGtnt@rO5ZAf!ZwM-&d_`nuzK14} zLe-HO)Fl#sWapyW*+9G>Ui|oJeHHe;qXs!LmaN$2uqrO01LMECVf(_eDkLsV)ydWB z_%k_0>Ag0!n}!PF$qRcyhq(!3kN=fIy}^;-pqCn7|J zOjoCNK*ta_6#WV(2cxlckHFWSo658Ix47HELaC0ts({du{A@v9LoG)@nB5 zW|9!47%K%VW-0%)Sea;Wts`^#+lS{AtWELz+XTJzNN7j$WAp7HTR0*&gVd7)t=-kH zL-|FYHoHVOKxD6H;cvIcA5Bc6!AN)hR_or@V^Ga6a#p>i4Yfar9gL5$A53jW(deWy z6zLSi6{R7qX0*fHr&U(fpmWY_?d>o0ZP9pEKi8O3ZcruzKcyoM6J>J8vt+|T|B{8a zgC?H$9QFvjG)j>b8tK&gu7ypGsjpe#QEiUXYHnq05vt&UA|Ww42u}!2q8JPqX~{f! zEe<#f6DtmL0roUFwF);NHYsx#M>KMo3tA-Vp5qe<2Xvf4-UqaqcHh>??G*OG}J zNXP2zdAr`z)=mKt*>~Wz|7ciw)9&lW`d#O|t6PC7BC_F9*!BLJ>&z^4)P^rNx-mTf zkuf(6N!ZoT5N|FOiuhsbBGJ%Eh^fVU(niGtV-I1#HaB~tb>mxteE3z0-y9LG2goTs z6L!B~-?vM7@-Mls^X?Tr$hGrRua!+%!Dqy5-#;j5%?mV>we?k(^c}DsC%iGw<`J5u zHpstpivHu0DFK>%AIZ%n8E0ohd3}p}l9`RMVvr|G@BC8c?_N0O#Kbl*D#<&qnh=O9 zyX0u0?ZP*jCx=riyrI=D>t=mXlL7#ljx4B$c` z6bW%ZUdXO4JKof&yW(bSe$PRn_H*|J!I3(d>+SRxyav0o@EXX%6nO^dKRPJj-|WSYY~|{iSt2+%pR%cUZvfKNvvbU|W04Fs z(_8UkxTgmNnRiF!SY8=+*F$|s_expBEuqy<5M-6di+d-r-&_!y$@qTVOo^bfS+{$7 z_n}>gSXKhxR`-Q-X1VSdX*$lqaxFt^j#-+yQekru?EOannMdT)l$PbIr0T1C+j#@8 zM$hu%I%-j8nJ?1k$9h3@6p9UO{j!W_hWei`%C-*4&FQ|56ZnL zvnMC1olO40ac?)L@3;2`QpW_tUNrh-hszp6Stu6G=D;eFdGo&ZLJQW@V-Z!_Im5@k z7#sZCrYRYRR(R7C9px!+{n;(^`_qeAcy#C^DF37cC%Yb&jvMUoKq@nlb|AP7LlN05rIh@RO*dO~cDV*eH34){5L2@(iG)88!_WIa`LoxDq?g)Y_ioGfIj zjwI1~l)bavG2K=3Y{@TQsV-iTJnhy>rdx8bEc>J-DnthRmreE7)y#Wi@e^NIbczE^ zIDWz^f6Pnx5~fcB8mAQcuYm$o7a~X33fX@1=bZ#%9RxW9wa9r$bB(1N_I@_mkXePb z@NzfMpqBo6Q(VpuUaF-PS(AZ~tf4j-C9kh`L$>>PdD>N|g_TnE!*Mq_*qC_& zK+gkp?H1Rm*NX#1fmC0!(Ha}nbyM=kJr4_lNX&2HZ1=}7%dSHn@)QUdESD4__m<+& z0?Suzs#*+{((_dS#pt{t4Wav54qhQrU)5}Q;osk9-)~_#f}U4b^2SGvonCnT88Xn< zEPYmQObOq6yN;J2jF)*m#}hjrP)olk$|48bjba8GtuLh+VOZDhf&)=&5TH-!@bqY_ zDnUi7b|*}zIZH_H~*)H zogJa%!#sk7oEc&X2Q1FlQQ~kceA|onZ}1!{ct;^m&tI(5snLTvx4e%+v^)iBe{r0c z&__x^s?x%r+s~ii9?!&nXsv0=udYg*f1Pv{iarOwv^ohxU$d-%FGm~yB=voIT{c^y zoIdC+Q*2o#ui_2Yw<0AIS(SeJJ?b)QHEgY_6gE6_@So-xmgHVte32cP23Z^G5cRD; z)j6*mPy0vD>W>BKve4uj8=lEuE#fBNt|A4g7Wf~=-aHX3Fq+l_B|aeqQ;qucM-SOv5j8VJ(Zhu z9dk#sV4`x zBV@$w-;;BKja~pyOVG|Mex4+CFxLYwO9#KY z#r$mMWuK7!EV|F0uWrsu-K64Vtj5hQJ@mslJI)jIq1I%F!ngjPK82@iNAsk;edoUR z;~LOY1pz`b@Lz}ZWF(|ZzbAWc;ft_`m1`{L7{lK?qT`PjzNq}PXCXV}q)+Nf?n%l3 zTx5MpMBowr&7ARMf97|*=PQ{X0X6?foe5BU#YfFH`#9Dlk|!c;6m6;Q1lWV%h z=8v73HeKpqTK!p*(GPj;ucKeMRTUzo2BT=+axt3+#)V6lP8n;7T8O5_uPHq{)|5P} z(b3IC&6uSAvzGQDTKlH~sxO$HnZ#tBvzYa34=Rk%wXf0StrvO!*=FY$Q&bR1W z^|blA>_3ZnVNQ1bxGyIPs~;ivH4!oOPS~#T;vWZANLs1ck%?p;C1lC-+uMdPm5+Z1L`i&ky6Vh1MUJZXD|Y_Z zDi54-!H@~IgK-P@dkbFRc?>1fwbP!5qzaf*b)M_+A7|GE#McnXF(TjZ3Jvr>P!lVO zIrBlD{`no5-YfXAvG2Tm#pN-Jtw^3*xs~70!R)*?$MQxSHKO7eeN?8Q`DXTkTc%IV zbVICSlB(iEGA7|%o`X1^?c%d;A1U*H?Y!Iorfi(gXPCUzP2ZZ|M^U@VG&s&yzj)#D z&xIpy$eLe^R)q$xMMv#pug+;+&h;NT#vVp}pO#U)bmeG*!aH|uzxV?oFlOUnbm?8w zDusWfHwirB{05auLF&}6Svd%-s&cKlD0&Y$ zl4;+{9g^8n2}85^S&uo=@pC5E7ya*1vKPdf08P1(YKG5> zpru@g_ezTUlKGMK)Is@TC^ByhXw? z0~f|47kt_uB7Nzu&y?>A?hk!r1EiTi+qv}PrkYLb^N(^!6E_hfcrW{)%M&$jaC{sbSQ4-85~*?Py>N-u zb|-nM(Y^2mQ)&ArMj^b9@?#}6=fX+fe;m^N&kO@Sg+4q}hfQ$Nw=!(mwn|`>Z z^5cR;9QUQn;1X=2ecxZPh-vCa*XlE#wjJz3;jXpqw?`Ka()yRAn$M~2H7ISjOeY%u z^VviBWjQ&nerR=B1*xGK26n4?<|N3Dq``)$TXyF=u3Gyp-A6A8H`$v*c1MCwS~vE8 zeA0r7+$|8wOjTIV=9vO3rpOBSCyQ$tI#QilPw140w`rB0|HQ8pB=;V!`}BjSsqlFz z2B8qk)P6s^ek-y|bj_M&brrY?qoPaheTr}Lz87r0Xni?6H#9B^9sSliaMdr_=iP~qW4%4~j7w1j=4;h%Fe*B&NlbN$^?`}1}Nt&29rHM1WcZSrq`gA);@A_Po{=!@rjJ(X~YIM7#Xy31g=<)!eUPiHPH}m zPZcu(Wo+kh@*G_K-C-gAQSj}DnIp8dw(lbnmMb?AvUiZ%<#bc)n00C%wU0KbKGMj!G510G6LDXqX~;Ll=6Vnl z7;L^-k^2-ScqH&fkg*2nPDHjME+&$;len3r*#mk}!7;U!6V5(ZR1>vTEY2!YB6V>;KMBi5*Citsa-|*YVPvw0_e!n6uI|(QN&(Y;4 z!>Ad#l3+z5KK8oWxSIrN_18GKer(cL$?;2`3%bZ->0-RUbMrwdZ=5$L&=Io_c5NEigrCrt+MKU3zaePJ7)l_o*ts zK5bI4n{U5hRjK8`>3io9OqJi7{n^SMC&#>~7@}a%h8%I>?H{Z2!7iB(`p#B|ACdY)Dicm{wg4ytuvQCXdz*m zbBC9f5^myL`w!8Em;@t_gynEqljD86_|ii`8(L<{1J)D&gjc}$raj3I^AfC}kM7{r zRazWYeJ+BIv;#k-C^sfqb35Z@MgSgd%o0E|Yk*Iqg^4AZfFjI&;h<6*) zbJg%F99Z4ud(JCOxGk7C?fa(S;+21_w)R#O(eWp5e60IhP4*8`4K=K| zbYycW$Baeoc1~RT6{oUyIezQvV;8`FaK)Iu!WmaR8J%Lw4_vB_dZq(A>t6D6tBv1= zML10kO+AakN4*_ByTy#XT}6+QeWOKQ?FCsUu#8`ON624@NfLg#v@`Pb{+H7;^`T!s z^`m*JdjiIg#we3WR|P)Vtx0y7P;uZ&`pdi3bLj!fCY#5&y)%58PnKD~e_mxbc1uQ+ zv++-hPmuR_WK>*g4ozs)O3Vtk4iobp}H0<56&ds|KI2q`*cAG;<&CC?!B9kOy*#zBb zJt)3|z3qL!j9o;RtSV;+jmsWMF}9Y8*Low7BZQqb!+$HeUnexDu6kJ}62<-VbopR*#>z#!B*;cKvynqda!JWW z*bO-0%i*#F1y9!wE>6on?1S^ip6muri04FxR%!A`Dqog?_;|~xYQ^%2(Zo|o&AGhn zNsGn(mkSSd=w4L|TKIGDciXy*XtqtP3cP`(ngo(!eA4wWdbxcdU3)vU)IinaO5}${gjCIWGZu!Ui*q8IY?cD|rlbns2-Sg@hkru&rtiK}C?D?Iv^Vd@< zeq~!?R_>-=^rcu9d~0r->a+c!VD%9qkBssE%EuUmlT@0>`LqkOUhFbLa#fXs_U510 zHPHbFio74rjm($P4OkWh&AwC74mY%b>gAPML&?a}YN_(x8}v&QTV|E>Df=aHvaoYU zF)U+U$>37;H*@djsC%lR5A0R^cW#|(7n!;;Q>bAYCFV}kkE5~YU&g##TXMG-v8{zf zQ1IvYre~XIu65qh_eDKKMWAB>)jgr6FK5XG9k0vbYd?$G@ljI=`IV}b@$nY%U7J@A z5AAbVj+&9sCBugtE(Rn6*ygqA>o=gJ?X*{C9Ok|y#(Vu? zbKdh2^f9~L zhAO##a|F)_q>nN(> za-70gy6@E_^ALw-PGoDbJNC7Xu6M!>NBv%Z^3XIiKbz1zWm zt1Rc!pwqNSLywpuyF}xl4npr$KR(^!|JlxA@m|ER%LV=Tz?2nhBUbtlQz0DTMj;KJ za2B-zd6wID5beIEG*uY9TIPZ2TrM#VUTs8#f}{%aXH9 zUoDy^gl61V2b?fz$Df#d2jM8^)lqMAop(#+%}IPhC?9kyCzb`rNx01{FT!;s$`70@ zf>A@YYL9P@kDeOaF+@WTXxUgN*pkvY!t6G?SSINFT%ulPtcsSQ%meSDpvUszf!IVd z9WQn%(%>-3LIdikKNi;;yNSN;xHM7SSzLGW_iEag#K)f6tE!b%`rdqh=VN+B!H9D} zWi<*mqIKWR=72I@N?#gpsK6p6^v~#J(onzeFs6+QCzW6(ca7r}2(iK2Y zUH^>TGf6;Q8`}j<-}7tt@EZPOAg}P!R5Q%?l3axUxOKrDWb8`yg;gB&$YG#T=(+e{ zUgyXr(|0-7DeG$bL6u{VkBDX_&c{G?dHW=Wval+IU)|hS6>s7pEEjfe`$2$(*;Y5c zv;{m_2G6Tj656DSA@*yjRGw%VR#A-J-Qm6EI-2aZwUofM4ebZ6uu;>=pz2N2<}wwe z(rPoOLv;3^9ZWDf-y&hNKigJ+(s3Z+VsN(Y{YXEPU1`(z>(u z7}s!f&!5Tyg{+l$&%}FE?<)!q#^DK(!>+ZFRFc zUoY;ve_H$uU_VcFR^nhZ?dgNL=emQf0iu^=M^q+)PUT;$P>V_53LW|x1hTSW%|(u? z%4(n4VH^BqHv>geI_N0wu-851Y(58SgGVOcJO8LzJcJe$!oP~l-%;nOP$_A+rLuta z2127zz;Am9RPg#$%Eo|9tiq!?aQ9Ceeu0#8T>KAn+O&XyyL&4R!JR^)^mFMah*s=* zO^k%#@bIJmce!zm2k@n`Q&YBmNpa zUySn=DO3=TJL+l7Gm;tNoIAPs<*r}UpJ|8rLiC$MH(H*h@Rvgo31=*grL@Qei)Min z(?;AGw-9~nCnp@gTEwU~lEwKv_nAI#coRj0{ru^_wRu;!iw$0;%CVX3HtgH}Bd7Fc zWV1qN8h?ixN_TrmMqE}W38s)^ce_RR1B|&FqDl9anBAkq0t|pxS?}Ztg?DO#ypdr(+{aC{&YKV;|50hfJ};z-hTE!54Yv^*e0ANHcr5vTx#_fV>y456A32lWC4TdklCW z*1%Z((N7y`^qU#kX8ZdUK?nAw{r9Biy>{wsf#nlq5)Vi)LZ;)R-$uk^T0&L34cgFR z)9|#TPII<;;OrSEhnLNS+nS7Xn!TmEb60C~0Cp9RR4Wwqed7qVnwaMh=L;J-E9Ng-f7bBS zllz}3^_&}>STX$$iQzdyOf6#r!uHxy@cXKuSGmz6>N&ClTodih(AWW6chM8(II#e` zOoM%8)+9FGU}dY;pftEniCvasbOkr=2Ra2?VaWXlWP;W>RTeL!$pD zd)8MADbb~#vxkzkx&c*|ni1EG?$YLU_P|@IgN!+o`E?yy9pdk#*nhq}IN)ojDC2Iy z_*U{N`qRd;f+TyU9Q;EPr0WFtd9%UFK8(_G1bVo{+&=coVC592?yt^CLkHu@f+5H| zo`KIR#urzv0d#3z*?9jCFzq|~W>xRsI^pyZOwp5|uP4qNRY+4jx_WTjcovQg_+=67 zN*nVsYQ`vUj+<-RUDH*sp1ZQPIAWfF`z|er**W$!URZ8n@q&`(y`G#FU6Otb&rIVz z2_+FHfMucs>rbx|9KXvbPq=2S2+c|RD9HLbYqU&46dMdnGgM5-H**qsxdXjbp>psH zpuVA{ZfJE8drY_fY@4ck^_v3;@{`n#-8-^>rYAnC$;}E>SCK`Z)S3;?4K2F*Ke)jj zKfvI-kcv~>j;R^@PI|Z0-c6|PF_;9UU2GJqZbs&_Av&0udMa3(tMW*-#egZhn&9|^ z*cDF<+uC%Fe4!ZHi@1ei>Gf1^?~F&aAvv&R>;w9 z5-+!xcuYa|uBRh)tV6+E^CY$kvt?kek*k7fMuS8_LncS-!X zquZK(04_kVy+#N764CKss4GfZBCWEhGrKkQkr0hdOm2Mzi&Ay^uUHLtOdoblgv&~4 z-&`HI{YPHkto$W+VG*z-Zw;|}6%^q8_v=qK?EG!gOc_!-|9gxsW}7m=VpW9oPEPw{3)@7RG*9 z?)%~-Hpb06T^AuMf9o{rTRPL(sckJ|-u>_<%^!UOeONi2C&>>sTuHjHtL!g@q7Etz zQJ`(M*oGtle9tHEuWjrZL9VFHstC%PJbGh;+2|a5&f^1|PBvFe4)Qr4?_$Eo>R+g>3LvMCn2Y-Fl^FTr z?i~RpB~M*^8r-$>?0oP|+{q%sS>8`&UT3afeEcRb$Tk`3O3wDzf2L0-=BlKB!;PGC zWmmYzoo&7x1`MEW zAfYBjQ_1zs7c~0YJ5|v2a7s0PqK|a)<>rQ_7fLsvaP&m%3HJ$$l9E0A`)3CMCEEB~ z^03BW^y@7HM(Q72?)XhbikahIJ=jMX%h#rwNGbXAIYN!E1jT3Dw$FTFoTEQ@t?LHkf#dnp7w;uDMOGs$<6XON^zgVi%*crOB^}!wf9xAj!*gt8QV z8eHZ4Gsfy=^y5y~E3?mriaKXk<9z*tHJw_+KI#JYwz&a`Yy0&2nA{q2nEoY}-#Ad+ zq3`OY+m&voFqo=xX?e9rl3E1As9mWKcWBXPfLM+1f&D&cp!nu^#aHw7jZ4**I(5rk zJxcYi^x~V%9%Aj@kPFXit7Cakv5)@9dIPMqp?kcdvxi*mxbxw;c{N42zKD2~I znJqEOrDjxMcNX$bpZxW{pt9NzxPoVy~Xv-9Aq%}e#^kPqyCifGGkk~e(*;4j?+VlRl93k-BXO! z>XoJ`gr5ythyHYEO`S52auUYkzWYrxHj_ji&v^f1&;yx zMuVSm@IhHJ=5sD@O{JhZE@3Q>%&UL@mT7h&KkW8f$fSNG*K0wBF8tpi6YdjNR6EnF zecdomT7QK6C41*x`dW7Ia11gut+6^~w_Rdj7y{J3UM`2H=W4O1gQB)c@`o#po65`$ zTuTMHH-}z!58K&BWf^xgl;!vz*yxN++UE%<{W}c4z?)SF6o$cjc2T<&A&_^9&z_V2K2AbYrv)OYR@L*{2rYCY!dK6q2)J^oU-Di z&xMoP|A>|eX7|d-domsksl*5nzHPLk+p>TY?0i+E2Wi>I!c?B*OM)FmZHZ6brzqUJ zYa}y#*3D_6kn}b_Kix`H<;hA&;qrF?qGm}+ZD^2WFOn69KknnqUWqzB|BCx+kRXMd3RXxWc9N>W)&_pAzF#XbzSGVOS;dQN1u#5 zGfVa!=V$io_3$+`3aj4MAOCD?Srmw^?YXZNHcI}7iCdj4`1;U4Wpl4 zxIEa&)YTlwC7^LtxB&YB4Gf`{b}km=oMiFwjl$^LIGCu0-x=v8{~et&-c0myH^kE?@XhBBvlMW#O&b`IMHfFmWS5MqV1 z*|MS{3Dy3Zd<(kB0Ly+PO*Ah-n0^+k(it0nL=TR)hN!zgU3a@`*hse86a%t;vcUbF zjK3~CDq1%unwd!lpYwR{-dC2q9hziRF4b6NXmhEBdV62CgLtB|wmy!{*h&)DU7KyW zL%W+Mem;_Y5ce@K`-I5(u8#$v@o#4L%!1TNx;G3WN1eWCRkr-b^@7A{?a2JPXy{=0 zeMKBIDrb1R)yFW19LK1N}G@cc_(KcyU>#Q}SL-_Hhm0G+s?7>+*=^^BT#I>HtRU_Lz9fmlNQI|&w+HI5; zE9~b72D>E_F=5%~!y!7IGaL6s`TLD}XWn#t0`B6DpMxSa?a!ND{mA?{1>s=1a{}kQ zm3KnFVkK&yb2t_okI;Lc0m}rbDH@8;0axAl3~LQWT~>BtL=heZV$vc^2e&`gAg!04 zrsi6V|B$i^Q`2*rQ{b0i;ctmYOX*TT;x<+Vy^bEAc-n@?W(Txnxp07InaA{i_ZN+YijN*zFW9j@+x~` z(6r_5W3NoZll<}ir^J0uTb>7I6tq_&-20zIFT|d?s1e|I?$+a2?3Ly7+mkhu16RO? zS~1K$Mm~?Y>76kC-;7%sfDoDO^(Q{IyGVawkY&jgd7y{17r&9A_BV51Zd#0kycw6&)h?%NsOW2Elb9zb zD-O9C1g>}*6##i`Y~S;dK2~Y_tM3QX3ibqFLWJsHSvnk6!+uF6WV3TAY3tJ`+EiMHG;-s=drK|1PNHK6KVUSWOw3)!a}Wl~a$2mprf=DsV7sffm@jc%UGjlRKMXSo0j{S6tO_-L(gf-(x6& z?e1?5keL1hjM2zw9S>}FX3YxMxa{LFaSyZ0DimPhKs)8Sidn7}VnDil^syR4~FvdaXgTx1J`Hn5zMa|&HMp#D+-Qd!`{Fg`Y}5iaEw zoq%o~q8X-HT)BhL(hwAR@pV-0az0Qr#vN&TlH+%@iG>Q+e-eH0hV4i1nmb=kYDAss zR5jHf8cYcMcK%-Ut-z_7dgs#s2Q|tJN6R^sc9w3pj?^ena~_dgzH?<8yj(M+XV%Q~ z3~lT^{qig&%=GW}3gbQix5~6G8Fj!H+<-5_oo|Q(u>EB~5da{W_Jg-gtTYhhRKHeBoUs6wdQrSMl>{R-OhTPa8mRKo{_Dd*kOBc~1>olfZ(lyzE2%N+6?GVCjzPZTvd zcYS2^Zet_BUm$ta<-^W|h^cFNpG#5(oXs0pKU(2=)oYI*qN&=26h=1g$ZMU*s{4XR zve9g7)5^Nu;d(HJClP9YhB_a8T<3+mifG>~Q&zu7+Z{{v=Hs^#?=9$Dx+H~;ISb^Z zfz3glO;hJZ&f?{KRt zrXN0KBVpSzARh6%Io3-O{Wj7gpypX?!fN4{tsK<((1XBZO+8esUI58rP#q&mH zbEdhdDD%=QHLq9ipNzgSHg7C!3=8F~4tSy_7k1qsN;gl=NO`Zwy<%y6V&4Kwy}B%9|@qCL9Q053OeJ)ry&zFp*_rFD80e=4GWt z3ZM17R@TrId=a^mL+eAQ@*AebQ%aCyq=!5JH<`mH(JSIV-$V}n)ZQ50q2xdKs&YQ` z{YJ1*>1fDIVbmSs(aRGSO}DQajfQ?P2A0guq}{k-p2u?}C?V8ZNqA1PDBj||pVsBE zurDXOM0v(TC2MEj?6@6E(YC2+c?^(5tFw_~Pf5mQ3o7L`GD0{aJ*n*YJg?yS8W0Rl z%y>T3WgO;xmRTyWD}2f8w^mT@Mj_X;>uT}Rb1@Kj2=t+&nV@mjYySA_#= zeq9t2m3wrH5ApUg5Y@usikp83qjUe?=Tb4U=R9J#I5?gj<>27|KhLH5KmU1)y@UN? zAH;rTryAZ%c_`e4igs3Wb+?{0DjS&3Fc&bBkG@|&^y9qp4<$&xwCq4_RD;{#H@jF7 zy`FO~PwG7o){C7KK3-p~#vl9V_xqs_a$>Ut$+o(UDY{0dHV%r*A)+X@=3r;P;;u7( zzh;o_FF}9hDJ?0HFDeJt$%4EI+~9bL(*k5}=E{2L+q+ySQURB?R0PJ?af_I< z!=#)_6T{OPclGC%BEap9>Bj`lJ0u)+^0zotS3TgIdtp|m`l#Gb#lzDHP;p=RCcbII zwwXQdkLYJ+99lK#^OOq?&vI+7&C}d?(RqZi(24H49~*whY~Mk-)4iDM0wGo5$5+xK zl7CF_?RTf~i_F2fX$O5;s>|#L{<@ySg?Bq1Ul+S6xPQBjaDSt8j(_3nxu6L7CClvi zaH8Xtz-)^BEA5bPi9z9{l_MVoYoHqY@Qu!&NKwY42e^`bWS(Szy~BrTo;8+D`?Z}X z7s@a#CX%adsL#j>gG!D7@6WL(l353~Em+U4p8U{Nbxgy=C($`^G4U~m@*_@(2-mn6 z#yHT&&#KrD9dtd1lCm%BKjLYDd6w`zJ36#Xk+DMSPVU$2Gd#I-i>~`xbzBwnxfB08 z*+o*d#Qd zVWW2-p(m`uDDMImI^CAi94|5jf{zJT@dXG_tYqv#&eR~H!#9c>Jt>iQ#MM!tWZwg` zM)6nfI`dUWQ<0IoZ$k`t8gSPk+Tl%1na0ceR-k}9`Trjwpvi+B{KUfPy zTP!E>=z!`m8BQyTdE&e-9>l>Cn&a9jL%J>NfaC1~EOqUiA*tJFhO7>rLp@!GuC88A z(?eJU|;-dtBD!gZW-c3ai5Mg3>8y^tjZ^kw$UkB1E1ZP--xK)R;P1zm2^?86y<%pS>9 zDUA7sA&_i&qf}$>11i{-A;lbmR3abezSDJocO^$i_uIe^qtJwxENZzBtWPv&2vSD5 zTR}eD(h~Gz{YUf4o34yv?CBjPqM`upO|TK}4XU4@N_O~vKVQ!4;?=>jM+Z2>3b*RPl#jBd zQY*5%9elC)@;#q_q)*h9@atkHHbZIc=el81( zVWzw+-qdMs;Qmr0Uj?x0ya4lELjj)pNYEF5dUibZu;CZK>#Jcfw{VOVe$DVLQ1 zqfQO5rdYce)}k&Qt4r@<%@bHe45QP5i9zk|gK{|ky@CJc&t5BN7(YS?ZX=j)A}dT8 z9bJE1P0bj8x-PM@9pqv1;9fd;;~^2Q#6oJ4JQC3TVMX+!X&Tzm#5hqjK{yiY}m zm@*ceCzK2ZK;7cXEFDbRpF8~yJqR6AYyv5y1vZKdrlNIB)~^KQL9vUTM6@YmXfZ77 zeo!181+>Cz2zMDf&Ynby{}(9rnvQW#O6Kp}eQZ|~ZorOCN167FW{wBt1G_e*O$-&)20l#5Rf(QbgkABW zjU4_p?ML@)BN4P=P>;2pQlSscFZN1_3;usIZ@|`sp}M99S(;IpgyEh)KL;F)atTrt zNB|$|l=-?GqQrb}MoEXYIO(-ymfZnNf^5BlWz8p)sVC_Ihe&>%wv&OCMj#bN&itwu zeVMEIy`&76Yo`tCNvZo!^7wCz#xYlVdse$K2Ep*uV|u`NDsy11amGv!Tml?6a{|I@ z#rkbA2&uG9N(!+`>j7%T&F%#ap+Mf$`tQE%|JoKz-oUv5k9Ek}S2atZFQJ0+pnb!w zxLh;F=VAlqx(o0B^&2?OVkxVEYe6M))T)W^Xt!pMz^xbipR@Mwn63BJPpcAPIm@(K zO;T)*2o+5otqKW+(~Wr7&^HiZD9K2rGDq_Neu@7$LJny{Ge@n;F8Mlqi6q2LV-A2g z;7JDkpaF5v;i+WpN4$s(Db-g!bA1xhDBLs8h=doqFlJR{?`kPvDdneicl&gG0h>BE z51cAVc7xFamtXbcO_g{cU|NlB@dJCFrE> z$G+Oxzb~Y!5T~V)*$DDneYY*mQvu77D$`yLJ|8IY96mo&I0#Ja_Gx=M2~@ z=r7wtXmS34zl;SEX=~I01Z8s@yF(pj1OaVN-c%5dFQEdNjM-Me!(!<;Oz8g)AN{XO zhf6^+hs@bQqsk%-@274M(Q9eivufbbHMF+9HjK_=O)Us=?3Qefs50MN?p?1MtqRKu zWA2UsZ;Ixj=s&Cw>&lVubU)G+NnDOD8Ze@zPJgi*#7(dV&ED)Y9hyBwO`g*G=6Y~|jV^VI$80%_MuSTq^Y<1jz;bmbx{MXG0`1Gb|nswEHCCR z;A+5z!`JDC&x5#`Xv>fbAYtOqfH>%#WdNp>V;andr+f7$E5c@Ho4Ey5BeD63FQYh4H2 ztZM@1yXFfG*fh`mkg7yfwicNTm!~}zYtm=ha;YL#%L`^0P`0kDH0%xb_yocA@p4XHG6m#kucLv+gOHF3X+T@om;o<*YyE5#0C+J z0Mmlo=>3r9BP4LbCrlHF^aU{IA2CXUIbdO$7uZH}ElBdbUBiGwsSs(M(Wpgk6aga4 ze9wz$qkxXojB0Kokegao%fklCK70>jAzMr;iJ zq}K0cce@)itT%b<6TRYJfVH&I#1L|dwX<|#-ZL#o&RnPhK=q%9@cnm*FqG%aq>dT* z0gw-TsonNkzm@H1>^9#zZCFmn#`$?j0)FeeK1-S*UZ;9Y%{D6ZBe-)hyN$cYrC}bJ z>B$()7&DKVwrQgebOxBvFc70@f`WgA_<0Bdc)kyxHG*Vmpk6Gtjr6o|0Wgk4P;5`R z_JL-uR|VAi=a~+JT3OmdomND6V82anLI5xOEOpGV{a7w~Hv_Zhr$ggJQ_sGbA0apN-b0Ng3p#)76UCd@sDf@zqOiY8o zh}(@&GSb=m3miTG6mfvR@_^TTxa8$vLoCCvURus@{qL}8Ce=R%w|tZBT6NC`Es@xm zqg|P!J2ci{0HxV5z7;29bS+V9t4l!xqgA1rRE8g^EJuKv)`kY=wuD0ewSIV+#^Nk7 zu`&tO7EuYE7`{YkFLNNP`~l<8FVCSupxJcASTN4j_68vc(~Nw!uK{ZzK`Q8!INTvH zj4qe z7HPeUbnznVgw4n|#_|>mDn4xIR2#jJf0L4J)B63sfR1*o$bOKJ~f|-+6p}=>Cu(R2Gy2eA9 z?Pi=}cEb^1AAs$XUL&*z#jEf>2Q8yhfTPSB7ZCyS2Qm^8Nz&3=3S&4K0k|L99A9pi zrOhf^TB~U5C%@{ayX`QnLZ4~^=LYqp+cdz*wVOAye@Uew0^9^$`&k=S&{3#{ksv_* zWO}m~*htZciR~g9p6Vl7t~)W!`?FZsHBT>38aqgQYwb&q0QaNFLVD@uB4WZ$t^K2; z_;t)m3;4BeI0woDAcTJ4sP$REK3-rSKzGF5Jktf$B-l)(X4kvK4FFYGFPpP0y9NG7 ztN?Z-Y(XY-_f5<^a&;#s!FC#8y1?Yb;xhb2!i1g!xrFKwQXoGI!qydM0FAhdunl^} zG!D};(2ZkSYp?}LUzU~&6ioI5A<~xoV5M36Kf7vQ#Am^%?){Ck^=2?+SVb7#c}5+t ztIpObGn5VaVkq8+JVi#YIkw`MgTX#KxFEbdK)}!s_#DXOt<8lc*2kH8c;FW(qlu9U zsf-SgWG4lZX_z`V`9B*gV(S6W?!pssl_Qb+q{ST@@)(=p(gr~I+W^BgtJ3h5kcuO~ zF{4Bqz?Dw>4Uijs8*~6n8hJFuZXl8e_=DDg6hLS%r4D6UITj5-z6NLj$XxMtZA!NF z^wi#lf3wQHi4XwRnZ4I`Kz?+US3q|=XAI=B$Ye>u>wweHXhxaj8e-ZbN-p53J(Unz zFcowIOsFAaK&_PK)==m=AabZq)|gQuxCOYfc|Y(YvmGrQxM%_+1j!&0-K&|trv5*w zO5j24Q-QoU;4u}@dFP2hAYThRO5~$KsF#6tG#Br z0K9CfBC%zqy9b5jJ))@l7DCVgY_a206vgIRAmhOxf>4{c0P8gDHnI(|OPB!|^{NZX z6@+)DKFn^fYIM&<{mZ$e^7S~%BmwAtqqGeOK)dihrFnh$7cb3&tQyYQ+6r2+9=hab%4U48+FX?91lJn4=Yd#SPncMYABHC|i)UY`%gylyc!b^~;=4f~`?*ff zMn%@p*Cl{oxtTduz?M2sPobu?OOyAe8_Q`n<3V3c7wTqqbCgrm25i`*y9Dp^I3*AB zUPLr7a+WQNx9SK8bjt(a9h8j@1>VaDV0h?LcFX#d)&L-Su6{*q&+HomH&p}5?wSrK zV02KAphf`OLXmyMdbUy`{|ea<-`lAS@?dG-g--Q{cyKYZv{nf3r)K^7$Cjy7BE>7K zYbqQ>2!*$31o7hS2#*wt6aWFV1aC6{oO#W8N)1l-LDC^&xFVe~@e(0Y4I$H}<+=xR zCc)O%i7w#uzo9|B7Y%xxxq+_9S*Z0AW|Zf-4z>RI5%A& zrviAGltatP3gSh=hzKAu0j`||1CaO`N(E@2S2)o5(sPK+2|fXgk%lpGWe*Ao6sr} zE`Br|Mq$$VKLFB}3u{qwAPk{WoDk!$We(SAiNudLZ+WAiy;TohMret#5 zM9`sx0Q_ZX9Y|Pr26*)=W_=U5_$FhBO?hK~Ac%y2d!C$4vz9Rek}nCreju3YGwX0L zayf{ABvS!mt--gXX~v|YT!}i28-U~P1rhv;O^2&Mm{x$xO;EE@#2wsH7Ii8Ua0Vd3 zTE_&Vtf3x~uKk1wh#9dgIar>WMkMF;Uvux)g#nAP7=iz@AvrkOo5OO+#n9p5?jja) z;*KS1t7dHi7;DAF&qQd`QiujmTQMH4ENwPjJ?_t0j-Sw@5i;r9L>r|6b;7Jck3)~O zCaEl8I8DnJYP1>5!HlhOM{2|k#5 zc-DSHS2t+N;TmjGZykWVyWWGdW9%~8UiCyRK?8uuM4NgzAUvqo$YAoA4*QT67Zk!; zaxG2LnGJjT06wlJF_`XvT-2@1MgeD&7Kfy1^pyPvC}@^E3@FB}cOf!E70}UaMfVHd z-JtnU=5+E`d@B(LQzqF~ashb)HLEJQEFjP3@D7~n{o8bjK&p(2zekZ`F6P}wy% zr9vAr0svC=&o}Ne{kxD9z!&c(=jy^*<~KC}KLhiu|6=U-x6+W8iZ-=?hBP}d%DN4U zT}7E~pwR(ZM5O1q_J0Ob8GuhW?=sk8h(zyF$?Lzm9PPH$p9?FGI7D@2@a*QN+z90wqaW9LDHD(6noia>s5;ug;?rSrG^*J3 z3#<&W@lBm#V1eB4)v9bQ*uYxA4-?NF#mq5uFKUL==o!(~tXC$Ni$P+VB^5XBig zK*)qESTl$ETY>bBPnR|uQX$EH9}B7gKBM-L4GjPa0_{P)3<|T4a9w;{4QZ3h5480x zP>`9|sa|533i)8*GiEs`i;jnY)bcA5aA+yE**KV(q2nc<(! zL^vGbfhf#9%vJ_AIJZ-{eiUYBb5#n62B6qP2(_X82GDu93gI`q_I!pNT8#JrGf6kL zE}3kdtR!z_bKqp|F!{XoL7gM(|rCtZB|P$EEFI0E!Me zLNf+^k4Y-^`*1yTAjTjW=u?Zz zf73K(UE5J$Gv*=wy+;GBm}{asQ7eHZ<<_l93`FVMI#ph z+8N(o3*aGuS&LR}m>{27I#ru8HVXl6|3t2T9|8&pEW4N#JGJF>( z5GFy%z*_Q6#sm?r)>pwUuMt7Bxc`T;caLl8zW>L&kDuv2?W*f~!D*3hwzW=?S`}0b zY1dU-sWSCbQ6j{aDn%|4B18yD>N;y%FVq{T5Yp8mbqJ{fi6JCMTNO2swA>=(a#To8 zAta|HB!`oe%kT9L-M-!Sn4ib*FLL9S_j$kGuh;Vy)WfH8)I7m42OxYYxLtJqI1G({ z6zxi;oJob~jGNz}t`v}PE5*AZWu#XO{jqx_rP0` zi5DA+3PaNege0^>eZ(JNne!-3&#mf`U<+I}zD8B;0b5VD|D*tuL&0U*04iOF<%O(4 zsz_Y)Yxz;sVXRnv!4ro&Zpq6Y1X#b{q`omyVr{9wmAQ#OjLiZ{qW}GQk`vPvAE&8t zKoN8p`G;WWvAJsMF$Lc4k*W6;{%xR7P(5{ZDvs5(eK3YF=4X?<+f-7j3)+|=YP6w> zA`G}yp@h-oUM0SSm#3+N_hzC+;Nn*nM;=qk^CEBf4<=r#v9V_#^xz_gwnd1+7;-iD?}fj<-c4Pb8spmUdLR8UXde zwIw*TKF24T6I?j}N?<$(x>`OqRNb#o)glbw*(9fw*_fa*{296nlUCSpun55kBPKW| zyXL@~+9I%WBKR#FhypqMYBfoi#9VWsLgC`b4#S2#BUVV6&5@HZnE#tt4pp0>mjcw& zrx!I;)_y=6R^)`T47nVtWj&POEqyMJWhm)!^h<=+zC{(#=VYaq8mOkBBr;SIwu_wn z&)0Vwv}FD;;Kwo%zRK81d&)_xJOz&8Qd%QFIFt4~x;F^{yxP$M_X9W$bYi9vI34|X zrlUXZMxT;ft;s46hLix|F6gqhw2M7y!O!bjI_1DV%ni4A{*RyalM{GIB-5tgq2*pq zjlSAnjK5STwq*7;wY#oVuy%%ozKtO~6=uA#0ST3Q6TcmufW->T)BTr#Hn=q>4vX~| z*{`JJ7+$obb|psARmG}o*4#uE}z%c4HOOvKxgB=rYv zFdb656Y8`m$NI@Zarm7ibhgS0vz%xsp#yM0!)x+?FRh&cPn`5{R&Kz=W|qnHb>z(5 zv^MXjXRe5buI4Vavy`=)@1xhiaUwdGdRT|Z2IJZsbb{s`ktOB_8H4GSl>2_z5xGky zr$Fuk!R>_D6lcG-gq|CBYe0B?z*pN8UL5jZ(fap7X4mUw326;z&0G#u= z`2aLrNpH3^L5X_NZrl~x9OXgNdePscwbP3J3o9*#v*U>*?9GNIC|LJBh!*{G!{e~^ zm4Ut-bc~ahX6<*2pk4rO+}MXsb3wPM!|VI18g6d$`%Vgh8uISER9$6x2ZlZiy0=+of@{LCQ@Rk!qTz!lT|MW zE)8Xf8xdu6A|qvnV|0U?BfJ?@qq9!W8{TnC6W9h-#sg&9^uD_FgBSC*Uw~f}!$rf^ zCy%8Xc#Da*um@li4}Et%UDK%k+9kMERAHbR6+!LyCQW(o%iNLWYU4p|#|BT_>0Kq6 z#k*}z>f$J2z$_QBT_I}&+!?#sqEd{(`=x^e%ENk~IRU&{4 zO8;_UsAhU$I$Qaw8j-JhK<1msG(;~bD&Sdz?A#v#Wu9H z0dL5&5T*aXU#^f9=LL?W_0wvHY=}#{zeG`jA%Kvh7-$qW9QXwtE2LE7E(7ZD@=ThZ zZ)lH6;o@tCLV3_AG&#*2A$s%hVqVd)5PBbtRyEK2tNBoDnvah+!KGnP6yg5dh0$Mj z@7*GBC8NV6Yb={I8%wte;9}auQOO0DtQs~?Y-$vquY4}-9;ACVyBwN@(H)Z8eh2@e z^9;v-3aYt z>0ch-+rW=wlbv$?53j2ZrQUq>Cl&nPZtndHP;-TeKa4~rZDt8ar$g!XNG0UTIw?zU zEtyW|gsquQOI_~i!Qz)gHKQJVQFEXHb3DgCq@n&dQRwQCCmmsVo^*3AwcqCIFI$x< zl15-#v`;Jnb;8Kp*pfn;$YaI{!m5_{=MPBo(d1+z2jJO(!6Btn-hH*$5X@{x=n{TO z?K9rOEQKk;FA=)*B@9^eB@GA6=*eJ>rey}2s~S}#&D4HwQoXH@1s9yHDY)%2bRkcOogHv;|DYol<(b+YS1L?}XddsVUB`^y zA0l<>iEs%4Bq($N3v?l1Dr?AN2F@Sf>&;cK>0onSDix3hY+tDCZx#S1p-1hQ(OsBo zz_j%Q34HSQ6U)%Z$CQ5?dSZzE2tuH?iM>_-wqSpM;F)8->COKA|=wpfXC$>%T!;Hy#)?^KdCkf4O6gKk)C@bW{`{ggFXcARg=^JP>% z`eUGLcWQ{F7@~uVFH??R1l;|cOyXfV?^n~^KOgn=2?wr6ie^YdMgE&0hs>Tq=;76I z=`Pr)_q(y84F4hY7x+4pqrX6Cg~YMS_znDRPQbNLLF_gtsSKnWkYzbpxZ$L`62^qF zA4Vk48UqXX#ydG-Y5Lh7AWn?(f6c%ApxSraXn3o;z9AZQAP zd7wLz){96@&pv-|`+Tw*uwWpzZ6b1G)I~QoKfju21vU!v&-5Plq|G33iR`3OADa$1 z(;_S3lR{|kL)bdvTZ)u5@QC;&rjp6>I8ulw0>bC+wLD z0K~HGDbc)X#)@UGr`)W=vHUNlmUgesx%*KdEB~_^-KC$4T>)PwIS}6p*UjD#pM2Yt zV36M@ckaKHH5%+aeHh2Et80g61`DPX1th~tDZUrGo+`4l4xS=EUW zalfi19G&&^r1aKBdFh1uqf=}_f#6&I0wWXj3;-Up{Y@A)0FKC06D@}QEBE0^>Xw5q z&^d_&O9b`hi{w79g@Tg!Y!X?ow)U;pSFx4u418rAw37FaH&zh>GFA#NG{01-uyQoj z*azk_0`Z`^3k~)O=R}^3lQ_|?db>9XI-&0I1-vsHHHcMEyFunhC~M(c<|X9tP#Y~{ zIr{g;745bMYMfMaIdrseHXTvz7}WSqBcvAKF~IQ0#`3gvtcBcqz+z3yd7|f`nf3BC zYjmVVXoz%(Sz9L-3HDqM)EaJW^#Gt>32oHatXr7t6=~+R-UrW)HGLo)8Bwm%6#2=1 z)?V);G4(a9;%QEdxlB9z&k_b(dc5^4A>UDcv55PQE?POoO}$%QjUQuWgvxHnPa>kq zXa3H^xwNK3W@nCV^J}(5pWs&lu4f8c-IDc-D!IY??GsCFi=3G&KvgOD5t;2L2e`{5 z1FsIh132J-a^{c9jGGthOyf~d~zO#qW3lF3zc9Z`a7f@0g`d$ot>{M&BFE4YjxFG z8lKFghGq&TkM2b>3XM5DL!OFISoi{~h3aQ<^NiL=12W3uP`WT_hBfy9<5H);CopN0 z+ZIu7P*1Xf^hOo*#jUOp8c?fEhc1_fw&Hc$LG&41GjsUmpl@z$|5}_YyD$2CYw_=2 zpQ&*EdcxVmD_yA?H>KzPxRRk_-{t6LHs#2B58nJN81Diq0|UKaVY~CQIN^ApVf3iS z_)^^L{>MB<_YGVU-l>mXBH{Y>MngVxJeg^i6N`$FI46H=AKl%+EXDlS;ovEjEs0}S zpaya4W|Bmtv73R$kZTq2P+RyOX>Ql^eqeBB*1Ff!33{6J_D3UFgZX=(VF3Ebga)jZa9?> z5Ffhryps*9NIeas#TL5Zybg)4Dz2)9Y+RK%^9?bQp$b2QiPNuv)ua{S0n zDU8Ao&5fc!K-EJpC|ZgJc-{ST8qMh?L|m<0a5RK!)WQ4blntkw2wtqo1Ud(@=C3Vd zbCyX+)Jys-)R%OY1^_t0U3raUvyQ(%@KkEYkM@XvU$49Kd*eUrr!6!r3~kk1D=U)zX3Y=}*d5R`Qc&YJy0WR`AMka>VN z!eHgocTca7p*p#h7WW6#A?o+@Ey6gM?zfit zgnd>-)48jxebZrnn7LtKDYkY}w)5{RH~C0S7sz~TWA}QQIr0;MhohUDfMySM#0f$T zo@2aTiKjqeP0m$i+7Sr!8IetoJGApx#iV zW8r_KBNWzqm}Y`ja$Mecg%s^C^XHldG?iVPRA@k7xD5J2=turv(PXbq0*Q`S*Iv88 z#iTR9fWh7)kSH&BdC#pRNdzGUZEq=%Tb`XGn&+4j0U5;$ne(~iWnxmCF+UGSER=Or zDMV%SqjAC@gHMBmMvgXIb zwb;Y?^%}jzbSVz{G5}H6%y+hN>!z4oK{&ROZsZw*Y5$OF1RI$aw-F$4w3N3Q-HEJtvT*dW#jxUF7t z0~C}+W^`!E+p@*pfbouma#~=n?)qTm^^a<#%ty58(PrU>dCR}<^(arc>+zre=QVoh zp`+IBmCdAlh~yLlRX`|PjYEgyKFC2X6T`!V4pPCYu*)VB!q$q5o=gV{8_hsXXy z%KeX`582q^IRQXlrEO7Xr?|O^;Yzl^NxaE@3CY~PCi(Gv2guLom%$+6$dw(>DcWrf z$cneZ07g>W5oH9x8%?R%VO5@ov=2^xIPm@W$@L8F=XV5!Ao7Ras|GD)Q9XqPgkl z5vjFkTLWV0l$%_oNSt?#=ma(L{^B@-yjy`4gJv02>q|828|x<31KIu{lGAsS-tph_ zBhvZ0;mTwlIX9x3kHrnQ`qN5U9It?Qt}|a#G!2R8`cpQQYNFw9Qtb$h@szyJ%T$sD z&_uJ>t2irfiLh}b<11Ow5QneUfB+n5Ry&B~{9^dS&WPjcqUv>^vO7=F0V zN#;*tXpZewj)P;UW^-L1(L`9fMAT^Z8#8U(vNK)vP%}Y5r}kAKAv2xMY>q<0VJw^L zcqhn;bU7_?-d`;X7pms0g>8SCV>dTyB9w*=C^;4y0A*P3btFPht~8TXKG3DWv}b^k z9}yz9zEQkN4eEn!Nf=;lj=xvzNJSu^e~N%;sv`AvGrn8p9pjc1Fb?eT9gfFof$T_?&hL(i?SbPPSFjIP#Y**B&3dd zgr$F~n|ZHa4QhSs%PN45<{sMfnV30hf3ub(T<7usj0}vWX9ky(X^(u%Y54i*&FC$c zaK$@=McZ{+>+QF&iRHom!66=TNHaxb$n1=+->1DcHtQLTxPRdl{CF-uea8&b@l%0< zS?}>g?RlSRDN8rfn+plk0Qio|MPyqqNF)qmk4QsWx+4!c+WNpBAQL&%=qpz^sP6fu z6$wi44h{~-I71mSi?-vd%2n_|d%`&jBtlOcKwkS~JZ9DUkk;ZEKq8V9v9VO&Kl0q_ zkg`+6(>)b9?NRzP$rg|g0DGR$Aa9z&Gf|7YNC3cCE9Ss91*Shi6DxvOK!tOOsXa#- z)Pq9XD@Rn6L0e!QxqpG?L_{R$MGkz00rV09$InOIEv=`*)lGKU>@B_vLZ871LOe(f zpaJrXm4Wy<2GlY23JPc-jL~+C`hq&k|`H#XpEKt)@ z1o}82rnh*2sQ$n3fYQ_fQA+PqS70uA*70zwUs}E$f4{u{%1IBk1IVJJ^lU0IW11kQREGRHzL`2T9BDJ*uERpeC!-(+E^wq^A38U=9VS-JD=v**a~OZO|Ka1i=^77qH!o`oXp&Ys<_ zAQg3B)Vk&t8zfDK+b0!4Ynu$XdSj?!!Mp$c&&Bbl_ulWKu2dOgQ||=zssUfg$R`YW zux9kTS>GGx%#$RUmMQQokt)*`W74oG7j-D00u@a%C_~6Am_T9+6etXNCSU4J(xPDl ziEu+ykA$hg8dZ@;4C1K$T+rr5I2pfI(}I>QWs~6~TF>NEi!OEKzL{p?Nj|zt&J*&Y z$L2~vNCE%C)l;QEa=F6*62R`bo2s|M&fYKMkxA=AZmlSy%?t{u+Q>@HCK~{Z!=TR` zc@DT)G-+ymzd>?)o(0rBk|_->OyN8g+JpVnB$tPj{-yzST+uPmEdlz*=Q=VYaxTyj z#vxtF23e{dq>>T#)^Bzzi(NUEg>)szXG^`gKpen+^csmS>mIrHSf~oN7lEq{5%{eo z!2;To@NCe7$g{j+e1rcqJe_4)7U%tHlEwu&rN+1QqZ4>5Ee-|RN3C(N$N+QK9hgZc zKRPb>3;-Z+AR*ahmdBQW#Q&!&_Aj@uEW5@HE>i2=w6#}(M~T$b*euAt?s|CzH;+nM zKgD*TAyG0VWMMo!nc>Ey@~5kh_8SfO%Za?vAa%57h%K2$vltjvTtc|)TD}0y_Wk2H zpNG10oFCEngNq0j&1iN+==eD0ZW#tZ=o4a56$Ogo`2j$tL>+W5z{HdL577cA1g=;X zT)r>fPzoh2fm-l+&I5U~Dh{^Fy;MDJI*7Tg`+G#ldqi-(=JuGnN9SOeD%ykxbmPn1K2 zpq7GT3|T&5urJ&i4_2cKK+7!+y8012oB@L8?!DtK3uwlm&##NVLU1~OIu{5mMl}2m zJoMvUoJeP3hPU_+mg(Gm0Y5j6)EcHy&+5RkSrek)OZ_{_Q}ydZ3zmL+J4Q1lIdt>U zGHDuI8lLl9dO7!;4NOLw6_op||0G}lEpgBvfU8{KOs<2kW{;eAOB6l=Rk{#wF(f>u z*(VH*gGn=^Cr)$-k2m>j@%Bxacd_Ep9%vc8KydhK7gd1Jm8BPVhhDYA8z%=FU$?gB zwT`KUIv)m!?}Q4FvMBs>PtwXNS4mp@B~|#Hwnmoq4RkYDZ5Y~o0^Ynix5`3E}spZ@7V9vITGpguIDK2CQ$AeuCHTq zhUC0~2*Sridvc1twYKo2E3eLEv@laE@~AX6A}0kd117}!tVka3m|Avdw5d!C-ZEo3 z^Y(3N%M>^gY@RySHmLnm;J0kNtqrlV#l4&uXH1>smsJmB)*pK4Tb0kPj+G37=;dtu zZc{P$r3_wJQ!(){O(s&t4pgdvB^q=lxa7T8#18m>qGIZ`MQp+%NeSBLip;ry1i}rc z(jq^JwH0tj{s`m3$pn|KPV6~4l1Krq7MHXczO(1GwyA|sTqDfTL3qK_hv@cgrnLaFO&B1TC zg*5OUD>$y~85QVxyeZCR4(k~*wQlA`>q~Jva-}Q3ITf@9tIvb%FY@BsCSM=C^f+F^ zy>zk|KWkIM4nxX~CNSkeao+xBi6`_4&8ecY6JV80K%Kt~U93XGL_`8kgoH$~TIz}a z+%i7&Egj#R64b8Qg~+63lIE$Ss=;Mn9Qxk2%%@bTkpnBmKG zt^y!nEspVj;+JWigPBR zQ(vO1&q8=+-%m&PKj^oZPi*Kana55loa2E!)EWVk4v;Wrf^_L6&tiI0$Jz`T)P8bYk~l? zxYfRfP5_nGxY}qB<7==m%K;PqT*$m*ONr_R@Jq#vu0w~S?s`~j}T zmg|h$&a@&4nNT~R6{4mFH02^~WxY)fYNLBuTiXmgEsRg7tvTRvVKGg@nBPi3Xw>^n zgzUR$VJ2-Zhk@13!o^gs713@Z-Aa$upIZ%%$AirXPyt2Rg$Ai0CyFphC=k<@t`LfK zb`5ZSpC_3{TSS87d4x`~glLA2qZM>V`ujU9pp$wr{2N_4@vf;j&U?vquR2gg!K#9x zO6>xz6yVe*SH=2>8y~t@lf5D7cSGdxZvp!II0Yu6li^W@bo_k6s(~@^jWT~cnJh(G z5|41@^6+#3u$XPj68@#j_{rTXgV(o~x}r)vYWu8u0#;CD$R^7B-+zuOotF``&fU6X z&44E3&ZQfsV8-~Q0Viqo6s>tfpCOs5AAs(8IWH7ECvxtJ3|PRo3#n`nwct$xnd2Q0jlkY=BI)h+ zH*?04aO5S14JiWMHKKLHRuRmDS5LXmAuqw77i%@l^5`L|BhuA4Oz@7vqNd_SyrN&v zml)v1lN;00^#(Ykb3~{a$%Xe6eMRGVK6DO9@Zw5l!BQ4M@zw#<1~zA#){Gpc9~%~Q z-w-w&hh6h)S(+cfGy@NZwkP6E=9!AhRYLY`lbS7=;Y_DC$82y5L06;+Td@)@T$Jay z_>Gdr5BQ{vQE2%h5QCKz8|K*Xidmdk9a zPxx_c1lU^B$wOLS<0aVHSz;cY>EJKbzj#7V(lGgjb#cNLiW z2es%(_f`2~4kHX3b|k!q$ZFG@guhk_XaCtY2zNp;HbV(cBySKO5{Z*R#0fVb&|zzY zg`fis=wJ)X96rW~j9Q3*u(jVrSQfxzlsXnN-X~eyUBf03;A5@|N8aFCbgS`Xn;1?Q z;gZ8OEBA4e4368i7;vmPZy=yb**SI_IYXVfIz`ENfIR~cY;Gc_wSeo_!U86h6Z&e2 z^lWoBn;VP4Q!Ks#+52#riO=OO^7xH#EhtnR#@7O*#9BV5*xIdy@7NkoD{uVGb%7D>%S1Xisf>gV5 z6SmqmK=Vwb(IS}_E*nYxe%pi0c>na{9{S8~vPF^Fbzn6eU+PoIzq>-Mb$uUw=a?ai zH%%2Myztz6LSJ6!h3G9!c7$DpMi3-w*sNlYy=x%^{M43r59b|nlE_dVHZdh0dq!C%nE=q-s6U8bkt40(L)zAc=0 zhCF)@WVWzq?#jkUUEYr$*cD2PN)|&2h&k8S0u_0t=WV~Y+~EWuVA6q(VDx`D&^I}D zA!!Ae9*~RxKx+0@J(^a^W07V3*D}E-LofUgu%m0%>ASxvgFh|X?}wiYW5Lc{=_!*Q zbUEbGAPw6YFkUI(L*@0S!@d8zGG`v>g0uY^aEuJzUU!0d9r}>5iITs`YEj*IN+vsJ zOG_Ur-Rd^5{|5hqhtPLj4b)X9gv-1ABYC63tzjYj=6;CHaW;X#&QqAi<;_U;Mf^ev znq%}U;fS8p3rBp1C_JZuH55t**kA!{pWUH=q0ZZ4dVzZEx8c{J_-0ta1OllnPtR?v zk;D_5AE+08sBwtdqqY&cIhWn*QnGK!On*$poMX592L)dRI=PE66qn^3)mfP*J&++V zVw@unQghT(gsufcyd9trJ}I=)N6ug;5)jUsBh#EfR&*C=>FJ7fl+7{Dz{3uQjK*fB zK*wxh8-^Q$rMOsYBW@d$`arp{2Qo%(z}F)9+4C?|XMp#Ft%WKDoh}4VCg?%bSu)38 z_rR?|_p;P}u(N%>VQK?Fw?;5=T!MX<~G3x+@W(cI_K za(SAMXijRRJ)nZ62GmbGdxRj?Ivuh1?c;KNU5MbUIkFtKyouq0C@~C_mt$Scq^@9( zPD{WUy?W!C@9%~}<_Zz2ClgKb1kzB=?i^&n<&>B2xFPa~K}25aszF>Rbe?88FX$L~ zcJ2iZ*|I5XCLhMD2nR@qC7!^x~UXYXpX-I)Z$-M;iV)0eHPa5i=TOQvfB?F zIqzn_mM&7>S@dc>*R#}>^MfjV4>}>r)}=DDcY3hd&&!E{!*)RUz7o+i>g-agS8Zcy8Pn}O<)4FD> z7B}(QxCgIu}gFz?b$pj~n>xePp<;SrTRxvyz zw&t1SO|@7BBZ7Oo{wEJHq;(@&(eV8t>I)D$qJC3E!=3maUV0N8LkhJIWTe2k$4iF$ z`g`M&Dq@1m#Encw?EQ0L z{rkPUpWKg&F^o6Rq3EOp=(f8YTU8xa@fd4of$G!M_J{ z$fk*t$NJ)65d50lw0N+Nt%ufWKVEm90&gA!gH^+J+6Qkc{=Ck%ato@^O`Y_;@}_aP zWRTgT;-Kj&WKE?-Uw~^L^m+~DTWHDYiYophb{ZluuaK3)LEIHJ7=amuY@5F86~qM? z)Y+=C$8GBY!T{e6tzj)phohlQT474qKt7K^L!t(%14?AN@7bBg)gCU4`_5gLg-(Vu zVtL*8$l zpO>2dSBp;N!A^B~klTD6CJF(?neAuEDs&0oK|{X|6NWa=Xjl)l=PDX-R6YResq^+W zKPP`c%n(}WXKEs0hkx2~2{@#4bzcp&y%XBD(~Y~#iBx>csO~&I@p_9n_506GCKiV_ zkL1{8l(Spj8z(xkR4@!yuZL6h;T;iAkgsF_q{w7~t5V7^=-a4ts`&#a+Qudkv%oF` zk(j+_GVQC_lw^E$G@xX8@L33=`oaN-6a2IjL4~NX+>>ur4pC0{H@NoMS$E){l$!k;>Sn$*&?HYkF`8gYXZldnDni^PoHlgx zwiFZzMbuzDuYl$Jdi#hjLORlw_>&|VY&^jYHr5qCAmr@_Quk!k?x+h7aryt#e~h(j z8d83JD`Tw>6#};@2x^woWXVF4;bO(7OxKN^_XEcK&lK)$*b17at^{ddUSOmXNY@~+ zy*^e%#BB}*ZU}e?vsJZt{Gk${Jb*>fmO$pf6Jqa4&*lUmwMXum>EuUnI_TL3&Sx%8 z=R>K6-PqSvqDF&L?Mc!-wG>92tMJL{?&*R4%DenWaIe!-Z!1?%;o>Dw;DE|)JY$rD zIRnPcK~3Ew;M7&^pnNA$Ta=o%HxATgkq$}UEa1Ufoa5$MG;I{5e<8oFUOj2Fs%8mE zP&a?V_xu*0;61(06wN0Hk^g2oGUD}U6qnTYIZS)J@02nH(!ESHaC zuKrbAKu18RR`8?zOMw}qtA&qPTgThT7XZS67OksA7@hTqR?A<-JzqJKcB=*8c9i@Kz7093?>S4(dG>pNQiPARcwN5^t90 zS=w*oRwX3q{2hxYTA|;|=9!hHAAQO;z5?hzvVW(v+B38u5$}|7iXaW`zzQ_10PEsE z4Q@IJv1mYb2Vl|!L~0>S-jb6JRwg*|l#tS~3YeE{o|^D~1P){ei{io7sMBU=IDQ8S z7&SmCPFk5Kfd;6N?FtyTpARlXe?D45z5KD}?pPnGJ9}Sfb$dUsP&@IP%E9aH=Tu{Sa2ml$q z^wSi@=*r4tG9gvsq}KK2jMm803n)?E!Y~aW-hj~+Fp&qxoC4S_gS5f2Pc)cRC?;J& zH~zDthh+#bI=F;LQFfr2KiF?*Xswh-oYP|5+B)f+{s+go$D%E(1+Ed}QAy5wAmX>B zqu4Z9O|TFEEF6=HFOz$Jl^NE+3&0?K^;F=7ruG1zhZzQt0}9th;oB%Co-)_!g}FAd!TM1 zyQaJdfSEM|-_R32@BpF91(+7w9KBj%weD4p|LV6AL!U4b$rjQu+t7tk#(`KGxQs0B zy$U>Y2m^>0+w)afgMRTlQVDH6=@xEVM%^EI;KClF>xO0L$o-pOI&t@(ZLn1S-R%s? zR||&XY)3A7Yr6H(i4wXgB)kV`drNnH`xgg&J|F^+hX?8e>pplN8K2DbMbk1L_}Cu}mn-}L_)-ITM? z$L_4MogC}KKvH&SSphPCjN!nq5XqkV5tcobM(b#s=W3DfD=x>=b`%52HG8n&O$5jHYm#@rh=CJR4Gb> z`9>>{><<9g4C$rfUov)}r<@k13;7fZf>l)NZF~fo)FI*kS#z><2<6-UCJyXBav9Lo zI<2}Exvk{$$k%kd{z=9=>kTtfLkT~ufj|ig-cj!ti;(P`^?`sAqh~}e?>UHk6Yp{j zAc+nU3UxIKA>-{WA%l=AYlf+aXUh3vv`sil|J3`!N&}BUiinWgw2!eDoT+aPJ`Ixi>+fBWNsvMS z7j>6@f$(+4E@+qs|CX~+3C4I35ok;DsJ0%2#O91?v{NJ?Q#nixxP*`@@-S9&oe}{T z!9$wy-M&C=UQP}QVH$;s5m83k2a+P^|GAc8s|()kjsqi*wc<%!KdoU%5j*h*4)+2~gI|Azp)4$t)K_!A9)N$0@i^2x&8b^td`bD6$ExfTA~^$f*{NvZ}K2sbvvzs9$zc1-MJ1jj)Q`i7BSTN6 z8bApNRMvhj4woV1sNCz;BUt}yxrEe?LwjEpV;w zeD5*w^XQ8$@G!E;?4v^tqt5X!>Rt?0Nf*wj)By+qC7hz}EV3qE? zmG^AttmhT49e#FM^VE&8)*xw%Px^)Q=F7jFGw0@|58IiE6%FrPOqaC~B%tR_nDNE#;3V?S>{$O&%RnKQJN zA?ia7WS3+v{I6v~qQD&!b=Q&jy=wXqE?mmh9?G|yd~~AULjcpryK3<$M^(M#Pj~LW z-2Q0PaY^QXj>k($GPsy?)xslBjV}0pL*l7r5`(Pl+Vq`zuD;R*8Fa$Hrl4;@&l18l z!3Su)iL_QCh3F`){5e@N`+HMqd4)DXqJ5<3!^gl=4cTV%1G$W=;Rt*kMOqB_S_Z@o z=sS~ac~s3JS55eGR(?OM$7LQw#fXO2vdjr!9BBhK85O%buAmhexe)=1`Wvl<*#-@e zSdr&J%nk%73Ai9O{#vdniUbZA6izENE^r^zD-g~-5A(RdnGF^c0X_ov>)PP?XIF>( z=Sosy1Qs^ppCV7I#`pJV79gUAll6um=zHl zD-|Yg$QnCOrXgh;IHV`?QIbKoHBng%=^>e>G8DZ7k89*o5Xkp?I31rp_Ad+fPj{`i zjkdCj;5@8Z(r#AAtq7ksbnlCen79^uluhmZD-H9r%AxJg1f$*uT5xuOEf2b!r!yU_ zx`^PFTOS7@ixs1fd19JGiy;rxIHH>aL9;pFH8?15$vai2_6^?5tGZ@bcEndUQ zy=d?5nlvYm+fb0ii}u0$s!TNU)bK^`ZEHkRYr{1sC=xvI1d9;~NP#xc9=Y%S<}UI% zymZ1h+MQ_EQg%jv1}LK^#J)Uc@cJF_=aEX6seM3$kLR1os4OOMIpi`)z~JPmW`m0c zk7IhPAk5|JsWqX&&Kj%^k&cj8u?Sizu*0B!%a(IjbSj``r8=pu057=upBC(&?!5o{ zuGv3~C^h^0rnmY<@>J_9GhQn?`=qZ_)PS#&y8;x;MKoxm)wh?$6nJcdQ9LtU4c5@h;_IDd*h2OV

jEoMn8hF( zNCfjAtVkx1q#*D)MX&@0WL4&YOE7$A35W}E0Q-6hx<&fw;w`HY=v`v4o)Lz(0z=O) zMyanYN@tdVhqCZ|3TBj!4I(U&1JQEmP%$ZV=11%QnH%UKh2{_KN#%Z{^@?4uLA`EHu;z%+>R>t6Zjk!VWT1VB zw4UoA8KNBl;ddyU4}SF+3TEmiA%;{zw;30Ih)teW7L(;*Bf9KvWEN+Eg#9GXlT;W= zn{m;Hr+Pb?jrN;hxF{3^5QApxWYS!Nuy(gV&cc3@hDF_ET_!{JPGER$go=cC+X>dL zQ06oy<$9-#_YB1^2#DGC<#lWn1B%?G8vJJG8yRl3_V!g=BT_KcUG zmn>pdIgC#8#l)|&BE(WURudb3`VsiPCd4(JmgHOk01b}VWgO7ve)#C#WZz9#l4PUH z10bYh$Y>>QaR=0FnZH&(wq>tjN0OKu>~gfklZHC+*fRGcq-ThiXQ_m7Ea#37Tm)>M z$(Y}%32%Z2PE@!|8laR8d$c0w@8DxvAh#ImoohhJ+zFqDde`+96F@^**|w5?YuCr< zjYVTPr2k}J%s7wQexkZPT>$;$e`i7@gD*M}2DpwDoNQc-jT1;w*)@QG$D_Yh=J1e1 zzwn${kE*nkL4;FpQ;ZVNEdG<;gtVK4xmEd2zLq&_F@QQz z4)ge9bHhrz#*=A^9MJ^xkxg9a`VE?~ z;j?j`7KGct$qMRh0sK?u#ff|MZ-Lqv?2N{X&mTD>Ii7C@37|Fgg*=Pl7-qf#E=G;M z#Hcy3A}E4)`t7Z)1{lt>e@mXPhL9EluP5FfVLX-FLbsix~@4RnYYIm z4H)Ahk)GNBDqEgx`uoevX&L`yyvvBvh+aHbain~HdI5yt16TQk z`0OnbEGYRn8sYrbULD_Y1(#=o zIUFK-0jWoYs-t(GydT2`@)4dnYK7!hzVIQlC4T~rF-dP4Zf|1O^Vwr~1 zlq3yegbK<>RR?8ZZgMFoh+%E3u{z|t3AR2hSE8sB7TT(jM=m`rx7?8b)l=CR$0) z?@O#d2U>q4+80mGv}wY0i6i$ZpPw!}U&x|+WQ;M9Yk;>Vf2P(sVi6^Bvi(?m62&T)B$ zB=62a-29r58PJvhX>BQX#tMi)&Xn49o*J-o1};28d0`=&cxJ<=IHWIK|7bu_63efC zblk5Homnc3)RPc6hTxnv{g&0|4KtzxB3u^k!{ zeC904jQ@d`<$ED|Vj~2S`vT?b2y67{U>J}&Lz6fIlfx#aOZw z+MrduQu1_H19@5ay-(xWjPx@Qkm8sg2zpEu%5H*8CrX=>j=n0je3n@<#i|8KJJQnO zRsra^y@R7*jY_!7Bw(2~9y zmxKqpzpDDSWwfE_A63igKK` zkJzLIzOt-=UE%GMhqk$+un#OT`={zbY*8fU`k1+@6)X1+8H)at2pe?FTNM9keDNLDXO8toLlhG8*szs;k0f+jXbufwh2DEE_k^R{5uXLlBujMj)W8`Z2@{W zQrfUxL~Rk+m!a3}-nbIzB2-f^q~`w?f2}#tl7o&<`{1#R6!>=Nk-oYh$iLdx4yu++ zML<>WEf{?bPUUi4sqLu&)I`DXsqaF8RHdP`IK~Js6K`3Y*uTn^hD8kpW#Y>X!`J0L`o1cBBTPblwRq<+ciC;<(Mz zZ01@x4PY$?ip}geQJvW9P0OL6O?4L4Bv=T?mB|LkxSVV?oWwMI$*Ap4`DAyb^rO)n zitlAw2awGAo;d8oJjm6B$aCY(ShbS*=s0`>s9V!#Yq*!xERT zW6TO+J{h`$hB=tR1*2$2Zzy8gAx#V<^;rN{?C0ipYRTW(l(|S>1I6*#d<5qpwQq1N ziw7nUc2@8w1Blf?CHv_3yXAfFv-oY%?{WGrbM9!(klpy~bCR~{ zw@(+U4P$Ojlw1ehl#urd+jk*LkMl3OB`$qT&LhE+ZeizflmCeNfK^>uLn2$FX>9!x z7X$IZ@TUV*4YAmhU(x;0i+SS8(mQJOZe6G`g1B#{M_7cfR0gFHm?Oc{C+K)|Vqid^ zt$dG;MG;l-DLGsbVC2cw0YxWY7xATrt%3{D6JS$qhB~Yf+;z;xTk?O*!F06sTn|PP z&Mi+z9EMtrr)^f$orr)g>nde&;V5zt;QEsD2Q)~*XzPSe zd}@!xE~6o`au6H_H@>+9PKA3eh;QggTmib4$Y((`fOi10))9yuhP-RG<7-MKGvf$C zhx(g6tsO;Hc}Oi0$^hIAxnM!j842ox=;!Xedj;g#A;Yq}!KaY``cfSv^JQckOn&Q| zI}I~_vfKXk=JpN%!NwG>5Cp#Dxp4~1(gFRl6i z2>aTArp`3&cHGtNcGS1i-P+b7v$c-XSCKkaDaMfLm$s#9tuw`nkhWA2Bcu``LP%2E zojP5sj8#Del5ShI4nm4ZB824FT15qtR)hfgI93P|LUM$V974X{>p3_xyE|{)Uyv9f zwoG|dLhG?7 z?G1EdUf>HDuoU&7RuO5~Rg0Bgl)2n&4}50P_M?^rR`Q@f56f(2)7IEIU{>YAJ~o!u zSYC0NM0hT}_99?h@L7UOwbR++`-9L{;iX$*B@JY4UecV*kYT1#E}WZDuS1_7T&gJQ z&F4mcq7^7!PjQAUqJTikslp}EYh?L7?CbtIcIrJWZ_N5%FDE>!x7tn~cje2mSzd94 zcb$8Kv@$7+=FWODHthlt!91Mxat855O8;nQtE2dVQCU4hW`nJNvLXfntL_J+R;knL z7(!$8LD}t%unWo$vHfkmUo(`*$G%(6Og;~A=FKO{cMtW<$Gtoo;79sy#T*mG} zR3d42*i`Sp72&qeFqr>naWotP$g}C~K=`4$6!w2!#=kwjq5Q`8&*QL{F6Q~;z);L= z)k44TbhlN~W%7@Zz`9tcfg)~)j!N^iEg4p0+-HV4!&2n}$ymg<(eX%tPH6nXrF*xu zJXWbeJdQYKFH6pk`jwVVAolnJwh(wtq<@#4Dm@Zc$=cz!;wdoc2P6gG>x%GlgKzO%eX)tQpR#!B!s2dYS1T;O|&l>Oc$}v%&stwH|uC;z=Qe< z|EA4T(|Yu_=tfyDhpH4t(ObeDy~e6$x=E>ZHCZx=h8;{li<1gWWxJjY;VgV)wK5h4 zV%3LJE#pASN`=`QAz-Dsk=^I(V)s*0CTxC$#6+Yaya_T)UF;KV#1O`ioe~g0OZDcI zs1ds(y64X4y=>=`;j30tgZV{lA64$LCBMj?R=k}BQUd3kCs!Vt{WbI^PhIW!W+eMM zLp@jXVb;t>7$HUy+A8HqqMxS1?BX>{-|Dw!o-)egsC!cL`4o9u{@s_q&bI4Y|J8m&W-tL@=E=l2gjzDeh?v_@iW8B;L zQm~ZYuQkJQOk9Zqw3JUKB)LW;?Hv+GL2tmMfk)Sn3BypRt7cAs+hZ#x$AM=bs#WVK zi86^GU4_Puh;OO%lj&n!-})tjx@9*!JbE#VpG35?oq0H}8<{<_+iaUSBb34(gly{s z#t(YXn2ss3^w_vC_fvR#lQGTahJ9o(u}+4lkT{b|{|j&Hj3NWP`*uDP=33yh1br|6Nwz;~s4^-}eE zQ=C8`zr!V29!^KpW;syW?9dw7sQG>A~P?L9XG6vtcZi( zpIQAMs}e(kPHdBMtMU2;fTKbf{R#D3gQ*xtEaLXhZ5+2kR5|JU_vqlUkWWh%XlskJ zo>&1wS&D|9Tc}l3ClLjyA8PF+u`F4wLbBY5>E9MJ=l2(1PW=83rq^juP%u=Ha_ryq zS+oTE=gJP+@FCd@A|$Q!Pc=bq`9-knx;TmDv_9Eh&?Sp3$>B+7zkN zASYNB;;&|i@QjIknpv~=8iTc5<TpNkgN zYwpsE{?DKL+jcsY@S++v24KyRzskcc<1HrI)R?Dg$^E6;Lw~gQhxg~@AUHc7BrEUq zHdRdH+|}}`a`U3%sA?}F?fe1V*Q6%%X+w+G4~9@5Wp;(G?RdcFTK<*)7xQE4)?)QO zPF5~%MJgr7OGIB1eR|WW4`r^HyoV{hh1cPo}*xoPCdbo&ZY@MjvOQ<7R*10hDkZOv~{?=h~Jp%Ey>LEMKQ7p5n<1 z%m{!syq1bDvmx|2nvQvBD7MM?adA=$Mf7lVVom+n*M#}Yltp@1SMqu!3{1lZ*~{X_ z$<07V{>E+zL#iqK;*J-+_~EN5^k0dKN0s%DnX!M1upIy*D}E`KLW(IL%=aYYPM?Na zvMQ?O|8G>`7ydP?&+c`fvC~(;3x6mu+!$W6^S!p^*6d%huGNZB&8#f9(R56CVrsOC z@8=0Ge#$S5<_~zf06CD!$G}36{WYkO6H|kqyJF3i%n@h=EX59;z-tq%iCjvq*6V8C*^!P_xjbnM2?LD`r~HXLW>i{R3NXG<#HmuL)ki&T$Sd zj~HT&h9Lex$60I$V6DwWO=fX4D)XL=I2J%|otj~j_ze9;W*ed6Tb>l#FrCA+%N6Il zb{xMcrS@!IY_XnEVVHcLd48$>_(8pkX@qYYEDnMkjKa?!P7gG$W^G-Oh?Gh5H<@0FG;0=re#l%bHB*1i zZ33trs6M3ih@g&15-un|t02?5ip>-Ty%+(EZ%K(QG?87CQuasksJ1APQ z%+$JiI{*XG^)#kWd>&bGSuPzktN>p{hteFb%b){m;Pz?xbwaZaJ1^$KxxV7LrI}=( z&a>NzA2mA9W*4ZbAiq&}Oa?Uv(hJQVyP80PcdXzy<=IoH0yrH46!f_!o>9~gkLt5# zA*ea9DG!6TrD!{OQ6dXONa|V%K?G}v6a1!YQL-Cvu$|RpREAY!E)E8moF{%OemZF9 z?P{j$Wy%#;?JiqQ6~Z6gjbwCkvRN$bZ7Mw+OU_29-jSqBGs4Nz9JiqWGAWsS+syIdV48pJv-)YkYp){<&7phx zZiQ3&@zrnn^^WJ{Gm{Ia!FhG|*H4sozt1mdi|a=O@T23>?18P*wre)h_iMh>F zqxr7=b<+%+zwZB}aZheWWdE^P>w8gI((Uf0>iXTTD%KX2xxH1Cp$to zD*eW3tVvB5XfRC=apxrREy|m??-npky5cu|aEz=yyHkkKJox0WF>vSM!+Pu0T#wPQ z`jfC9<42(B3XdUl%^`#28LDLLrRz~&J5EMy)D$FKRPTv^)P(RSk^P0MbZ?%gdPnM0&54FMe1>zZByy?n@bIo(>M+quIWKE9cq7?9_&3WlVn%oT|kV<$m& z*Qq6eYet!8Nj@E}P=WHBB%0=?T(v>-^zP6()*GocAR2PsI|}5Ld5Od^%equ7U+LAy zax)BORszX?81^$Y=0B2z$u7bR{DnF}WFC;7nvL(G?LJgwP&L9ldrH9!YSR?C`VW3I zHf<{UosT~GpOwykeSEtNevpP?<`ATf-B34HM|&JZoSHZI^HcpmU&X#Bn1t)p|>deDt&cLbZgKYye1DF9aVCKnln%AuZ;Q5 zL^P4>XgUSuw)T!^Q#gc;C-DdtKkY8M&-%E*ceR?~sH=VeKIth1QQ` zjei&=+?t*3(cn$Qird@?{oM9Ccr4=UY$6*i^*f&h-;``>dPhxh=ASah*NkUU(-{C=Q{^dEnV80hgSrIfX{&LBbB|kV9tyeMNn{b2 zyGvL29vkjjfG!Z(HH3xAgq^vf)S2!V+v%Y!vj)q|$m9}7f=}e`6$4YlWi{DwkW;vC z78%IdRB{OpAeG^+PG2}0jPSaD)3D6c=RKc3%j~ndfWqj^oC}#sXOhXtc6YN6!LYC+ zez`=E??Gq>HY~PT;^ zS&^$u*O^jLt?t^OZHKA&60mKmEEDIH(*pY>t;EAfNIQyPd~r;HsmVs{1_#GiENheT zVD!@*%(U)KjM(uGvT3DmCn;^~`n;YS<6NQ13pmW*%6*i~QbB>fy9d3~-FT??>`E7w zYrfHW(_b0P9{fxtP)rN99q2N-hkCNF#20ytwFJbgcj>-V&sR3rgv#=_jAGFCDL5#J zsqQUijp9dSF=d4HtJJFm^i{` z$!+25M1s`lm`VM|Rq>n|4bPk?~44SZT1+B^I45+|6Dox4GrtwW`x~X5`cq z6N}BF4*NBN*nr_t9G^o58P$wcmogjQw8FD~;*TBA=Gcw4Rh;#ND}n8u1nAyAl~H}r z4eXG@=j5x_>W9D{X@IrMU_|7-+4_Ro|=LBYLnzrI$w*2gu?+dePpyezr`M{%`T|xF==ynn+jL%SjHG z`?H4P*faiA%|TkKKKY@MfLhqm!rIUZVh9Id3^woo(<$@paGv`wPMPuej4>`8B((a$ z&x45>ax$!_6i6W%B(fNt*iWWVwm-{*oPmE45HXz{{`6!roR$A^u8xSqPMqB)G){(0 zRfb^m!g>B5lg9wI6`8K}HVG5oP^2RL4G;To4?8r(%B*7fE7MAUZm7UthRLGSE~ODD zl4r930~O1ZITpiVS?m!^mRp;+@%@nATVo5EF}L%5Y@*3$4nt*=_Q~a-o0Cf4?;U_0j*iP;_6o?!Fp@)%ulqceRi$ z_5dHfUszpP5%vv~>gB3!3~@i*=$Ss=4gc|jg8ZnfQZlTL?}2%arlhJc&>c(|MB1*$ z!I0&%;aZDHXl|@b zfE5ZBr_*xF+FW{=Hp?k5*TL=XQdOA)KafkP}-qD~7e7@#}WusOg|AgL9^+ zKhM()TrrZ<>OejzvYj+p-fJ(KVqSaMV*3&}uL9_X?aNXPa8W>|BzEZ1)U&xXn3bb} z;KE?Kn^?p?x|RJx5&PF>OpX+(OS12xqy~FTNw0~hbULT1AXGvHM=`PW+z2uyPfBeb zcX43cN(Y8VMs)&)6bq}P-C)1;dDIq33$0`@hfpq%Hi!L{?ygAGj1?iTl4QcUOMW~{ z^@i6Rs~k0G8az$PWt9`hEuda&CUI&n!Kr1`fP;DiM}IIEwc8Ft=Oq5JDYb?jLee+E zZD8MClgA$Y;ZjSzf;6wfO%UgItrWTIeV9Gqlg5SGTos0;t;)tpXFQGZ!z zZO{>qv4rPyEZEv>Hp{G74!Mljqd!^HH%y7ax+TBnTSh;il|ShN{`_Qk;~)m3T~tF&>h=e!K4Fm)pE$ZOPH+)%!&7iU$| zBgJMg=P{AR$}!vvANo;sQ8?^3hqnXbCrn#SBzuk|RAMoKsV48#-5Z|_8Q6E>vbNC5 zLR_upI+jig*cQXs-CQNm{i8m9b0u5wm)doLEMzGcs-`gf)N` zf?6e`I1z?pA5iUOge(KjtV`nu)s?$2WE^zI*dTvz0H%&l4J4=Lx>B}8H@-u-V@3U6 zd+jYl=Z`f_9vxjZp+2)iKrJnReO6fUOs+LO&uoDH;76S^$796+`Q&ZUJPrG`l4!wr z9WWW5g`F;SqL4_4={Kb9HC5Q?{9^m6Rw#NGt==@4_vs#pV~UD2IQ^8jhsjww5&%_*QI-B8m{V4VW(` zQ5^YNNEk4%A!TGbR6$%G8ZlW85>ZercWWpdoqa1Jqw5N97lQPHLJ-wsIK(U&NR;C* zpp;AsR4ad=H$;J(Ac}Og>*!r$X^Vvy7AbVjGv@EVv23OuDWlbXNMqffB`Lq0I#J(} z^O@=?`^0|B`Q-A=KK{xm7N=fA2@l3h)3=B0jjs+~0>jfV>*VeOogwOHPrqf=>4?Aq z`E5d?5i%0DRrCo^6BB_{Jh6i1%Ja^f8bm(%68`Y9m?^t8VYrf2j|pq)mb=jP#_W)Rw_u=!{zk11P(${Ld$mv-0= zTnbhC^^*;GV&drT#i(|mOa#2kKtfegdNWK%12Tt%a^|_ zAeq8p8B6>lK!h^NL7?*0k&sd%tLEnAfpFuTt~S=8G&4ubNvDl`%bIi+9HyKV#YwcN z>Z|(k6lI(~LR#P5;*Ou}2_T2D-Ve`EjW+cRbDRk6@(dY4?W z!5DL07Gy{L`-7mXA5fai=Os};TuRdgiv&-c#8_csM~^rVMrAOj-C{C=kGjVRj%Ksr zC{3&TpN;E}Sh5?7582633+`q*v)OQDC+XpxW4fMIq zOFKY>l5sxH(Px~w8ORl_#^>`R8@krCai)xHTpsv~VFwLs&k~2(Z;mJv+zsi!CIM$# zTIr^9ap9)Z*`ogpC*y|cIg?Ia^RYQG6>$le&V5OnTNS~FhU70?RcEe^XWL^PXM~L( z<1XUbuTfX+$-T0H*xCNtlLv{E{`!11-ElF)r(9Usz-jBRpR7b=Rb8oUfJSUXw4{4~H5IJMK} zWKGKLpE;g)`~K7PBT#zR)Bxk}Pcz2-{k`$GXWo|un;uKl-A9_Q!;%)}v#4thPZ^R> zj)=~SSR0P#dz6Mo1%`5XfZ;n;#cKM=;EzlLMU$3u#{}){yha<_sWF-YuA|7`^jB+i zNGkGJD(1#~Cr}1KL?JV@oG?H+3wmjX107eVrD*uv$++uCN_1BuVPoh!Y?VIT0I)LMxaa@D^m=h-GLNwNio9!&PlFHtwC|rj6M&VL?vI)}cH1b02m|&8SHR zLVUF*%i2svY7>t-t5_V!X~L5RALe3_Arbnzc#NjPk9zjOn3$WsyI~db4uF36YvL-T z6e4I?PAXG!rATvLn!px52$h)ve>o~apqIk?OYyK$$tnoRJ9oC%SNPh-MjcVnxmHV4 z9b?%<^MW&-tf4bw(TrtmRL+fg;I#N~mh~LkXAf8LnzGID(paR<>CngKz&btT=(eL zn^Q7Ro8M26oFcXPhJ$59eKs77J!(=iGgQ(V%fjGA_o(^Bt6WH2uDLi6=FeIX(`MW0 zZzW`WXx2MKsxUymxmeh*_XaLrRyuaAm6{Sr+4-i$(JHs`r~*&8d0IT?bbb1+3&)5d zL&4w*0{5tK~Kn8-X1EeX|=kRIEgy-Mw)}C@u*s^sOcnzsHhVuKy!*j z)I5-pmWcguGj(r^L*3cEj7}i+=k-b@uss_H9Z=`I;weh!pvb--?L1T&rklPjiCd3^jc<;$sG!J`Rn9>P zo67wnw!MZw4AKeY@PwvKDBeZYA7&AEn5*ebnVo?0U;@I`ZV`TUPm%-g4{q$ku(v@Z zZ!&X~jn#|?PV^)VmW8$l6Rv$y-#_(l=g;4Lmnq)g>1%F8NeXZS#OQ-y&BLvw-<-Vw z9tW+l%UyceoGWO#y9} z3{(h*Ymf#ULSg(e_zoZ1MfhjH=mfv0hJW>7j2&s0r2FlVS%;9DpPa zskz|o!IebGUO;ycsX3Nw?Ou@io{nsex`QG&KX&CS0w zybf`RFX{;9TD@K1oUW$o453Gm_I6GhI4oxQ#8=o1p?1V~a{4&n<;Ui(go)kVIGQ(1 zH#Lg#_WF|O_Ddc%Lm1dFz5Ch;y^D23_}g6j&V?g4+UNY|?nVo}%18E7Rf4WS6_R89 z9B@iUX(%I&a@*9?)huMaB$6GvFs(mta21)`?hqUFE={hD1uT8jS4kBdC%IaUzh}dp zq!D=l;>unDE`I6Km5s*GyVJ$G4+H$V6xNpg%Z%)^3NDacKK#@^JYUGNa}t7k*~y(150N1-SmB z8ZslBImDJ$FMW-9V&ya=d_jmo0V&u8m;*%XdbrD`j7U%=w3Y>T;Y)Ruw2b&kj+RRlL03LF zg%itN+esqU^7Jxm_!aAHN2`A9anu?iJL&T%t4sXh1$nKn5)d}I@+JId*e z;$-r@J!pXI2SHgbdS1=6L|`bAT~OEtl&RQPo3yI-}Nkk z;1-Mx2;ig>O8>Ppjk^Euw#C0bal@o4|K42DJ;WL^Wm7UE-&%5*^F&QDM;dF2N>g0^#^-Zn)lGRu9zYX){qwqyA-*$ta2A&H99 z4Fe|3Q8;BncbzA5=p6x|{SI(vMIrg`X?>}hQnD#sQCX2&v7dm&yFyHL)E)wh9pEBI z2Z1(xgrH#v@d2$_^8*F@2VB{&x%v&00lXUXQfej2C%i7+vQZ~S9O+Y+j75MB2nB@H z1|1u90^wK~`Ixx4K>2e*#G7L7o&rV@>v{N2;Omyw8+L<`9O9C)ofdgnn4bM?hOb=A-%hf8WpVh643Eo7TDs)q+fT6i)1lP4ELUyQP7rN|%ML6(-*osu>UgLI5)IQSUy|4Hx| z_6;U@-%m>PgiGQ%eAy{yAtAd{s}tXbZg$cu04^+~CM*>t*epE2$(3>!5tksqtTmt| zboA}B2|~;zlK~;V?&P$zzQNdUz>Y30cN3rXWVaFfBwE?Fmd#_NQqLajLBoJ@Xg=~A z%1EJ#JgF1W#h0U@f0F@i^YnW6L$MeUYA@tnrxDpx;N->J}y{j>wp`wRM| zZ}%mBVLrFJSu_u_y`{42Qzu5j&q}k);$Tx?ev(_w0;I^)xS*)zR$Q zpML9s(Ndf)^wJ;$TAR7pG`08*%F2hm8jq2cPLg5@9K8aL6k|TKGn4*zN*w6SYUQpCNbyF^2YyxzWO+!#ZW zcfseuYjF;sWht>t{P7?LG?}4Ka2`0NHGERObq7qTkr%Ft?TSSCN}}iBxsEGfjo1T{ zKS>zxNivD5UT772o&b;J1buR-wrK5qwoOg15PJ;e;H-d5BhwY)IJ8a_oc*R9Y}Pg#ZZM#+?16aumB(ST2kZ{_-5&z+7Ss zLl2NF2Ci((iT06yG1hqXY{@dOiqd_EN!~9sJ6rWJ@ppx&LbjO2i=V%X;l@4poVSiQ zZJ$*zXsoHk)Y(5=$LkgZonaQ^{8QP&CFWxSy8$V$fud4+H$T)Qnax)|2~CYrG;yY- zRTw>84)-@vk7SjJzFK0F!EtP(vl3ji@r`BQSv?gD;qx7E`QG60(uDxYc0b&z0u+^x$GZzJsIiHV<9Sl+-e<*V3FQ=7JuZ*ru zHFE(d?pF9S{WF!TkM`XFFi}-s@)Wl8va^K6EHfSO_P|=~Tk(pJf%i;y?3*HTeIV5e zJuRM)1G0^;=8Ohh2Y5P{!d9T3r_7~MIX{sp3aIvBe@_#wbVp?q$sgB6qV2CQZzV+{ zB@8S`8nL}NAtN_Hur$s6&PQQBxhbE-^c_>#Kihw6nBot$w5wuow{M&PGf?;8dh-v@@|3n2+reqnWvl;9DY`#1((7)B**bE!1FnF9-x7+?{v6EoF9wiz z0Q2$svl!QmG;E*brb9B~D_1VcoTiK<#b))r*h)n-L~N%S>DI=!KSN|bm&FLF*Z7(T zQ-q2T!3uD_nz4UICoajopF2@^S_u7-gqPciDFmMOkaG(SMc2o~m;fCFX@-leNWH?| zc;~ULtPW#GZX^mFow~wKmMH9O>SF7$E9U)REI}X^hCKMORpg&s9BU`x`KBDPA>)3?vQQI@b1wL-SlP+BRl>(on?d2R)D zF2s~(!0JujA3kmmJsk@0{W47%y$c@*Sv}T3GX}oUBgh)SDc>}G%;RVgeP$$q$Q*is zOOF@_0ws1hnoI5P=VHu3X3<}RoC@LwY;6n#*dUi~M`mv`Mgj!Vs6qRK=e{ud!G+|m zA%OPj==uGOBc6=nP`G5xhx`Bz5>}EJf`J@_?tX$GrfYSaJM}W0vu!O5nX(=>lI#gL zO`I(JeRFuXB?EN%4JbB4zYp-GB5$9$npRAQS0Hx})kz#zE8s(iTP837`#rM484L!o zE-(ddIl=0VRy;|;_61T=69HZA^42+jE$;sAn_qrFm6IqjgJhs+`PS@G>u#hMhvhw4 zOW#VJEuGd~mNf8-QEK0tUud8Dv@*qIWU?7P^|4dyw=3hAb zwl&bd5r_&PzCbv6|_AX+~mly@}ih+1b- zt4NTIh9o)_BODIJsP+`=mN&{2=B}baunPO$?itrAmcg4(C2i{vk>RO)Hnf$bsrBtI z%7e)Kf=W&ljFfR7(?!q352hOf#?oLZq1?A7tPnJ9h3y={`w#mpi`pq-*rqYCx%SMgd^u;nZaC;h2@9BW!1osek@Nv zN9=@UE=_`?Tnb7K=rUCT%k!1thK7)@OXfxEiJ%Osv&GRwRQ3$7-U#KTe$Y6^NoMSb64W2mjM^3@cxR5E0!<9WNwPRI>Pykgk zHeJ9mx1Z_RC6>Q|&s9Fu+nnfeAaFaU$KFNwRB+m}SD<(BRw!G0dojf$zJE|vUG_Gm zH$4;Bfq)Q969r_z`W4BU(~gk(rhYv9z3pkSKcAVA?+!Q(A>tv2`^9X#w(83;VsQz3 z8EP+!?b-zeii?S5j>(iw#ts6*2_(Qm9EZU%L8?CK7pRuEz?DtbcI<900p}bmS{d_j z`Yn{&AMusV#357knLt)Kb@WPp#f`iY+a16AznsClz`WlT;ymjpjNn>mgp zuv;w;8Gzma8)>z|ofthAfW@c5M*wU9bG<%$$3?uuW$mekFCjYng?iMaZvavF<&sN< z3`0LFbJ_2Fl7Obx5GMMFg9ERCU2K}1v|@K9Zr~%gdZdX3btK^`i^lttggK9CjA6-N z)(v|x!(&9fGQMFJHizLc+V!rJ$h~zk9jCK?A!U8IiC73 zKM)dErC+Z%9}$?k3@@fghGz^Z9ZQ^vPQJHtRhuwWzrVgf_)hDJRIXV|Eh^<9byjb> zl3hc*7~rdy7%M*+CJriaW#c&pwesS{zWB%wTYq`g8(F8YrnJvShUKp_cE%!ymJ&NJ zS96Zo18wn+#ur2R@vzrJ6gbVn?urF@ob#Sy(;`F7UhYI%)Tq|o(VSLNT~K&7E)BIb zGy&$=ly@c4oU1N;;7Mg}M~dZQ9l^CDXRp_Gl7eK26Vj0?GGFW`swE<{VB9xr_3TVn z9IHz4B32{x^`Y9%D+Vbn4&vA@Pa~^AtMTRi1A;C1odf`B{?S3II~8lqHbX-UQQZf@ ztX9Q9m{X^2%!h%NxeWXl(y*m#Jy`=xMq{ZqVuTGtTl)b)d2xuYU*3?ea zr1j?a)MNQYJ~oS=sHWwAP&GfG`&!=E2bY(@E0CTtkg@s87x;I~j5^}Nhu^KseLtRY zOdmV3Py2DSdzm^}>3(NGxxE-H&{R3@#&C~qIVoCk1}(U?J6Bg-iCXf3H?U?@bBUv#dJX z-5kKodN2+Csr}KQ;Ao(|MomsHbyT0_sE^D!`5{RQoQ$nVKz5z=TC3cr+&UokpFxx@ z$PNu#PQg%r`Gy$3MZ;Xw1vBA@bpptU6^R`Xq-8){i#>u9roKLt)0rCGj^&f-s67Eg z4Tp--#cO@>+>waP=>SXiSB1IP3LJXRd`RY#SN3b$K$QQ@|I(?YPc)rQ>je>i(q`)G z&1%&0u$gKARoH93+9T1kcT5qd1#JDLN9j+4(R5~>|1`*J<1j^8=Szn}Vyx1$7Z%^f zvUxlD!|GUtyB=tgu}j+*b-ivJk2^hw5Y*vnsa)7tF+Y~o%BNq5!t97s^~20rv_flZ zT@6p~Q4t)w&9elttQLdgJ2;Y&hAg^kNxvYkN4F>+Qhcm5=$#Tc1%D|o8*+VanSE+M zBQ$fB|0{#JRk-?#GTy^6OGsUCGMQYS7mXzxnV9$Y0Au4)X2jjYvFX~%{>@&;t*yCN z`ubyU-^QHrG0CAqkK`z02q}K|N-oj#H@wKUm=K&(x?0+LNq)%A?!g#lINaiAJp;W8 zfs0Iy-f9aucX^hX$ihvgpmXLtEN7s7xb7>TcqY2B>aE`ir(lMsw82*6F5=M}o{My} zy+RZlf7>zrR@FTD^{`eDIx@ZcV9W4lRfY5)_gQ|+7l-HF!m68n`&aXopUk+dc5IS$ z8*;A1SMN@|_`A@e!m;pNDKlm*V>e8ZIzH4bG71*Gf$mD*Ks=(|y|P9%DJZM(Spo2K zjMoy3o_JOlwN2k;MLh}dZLwL_)zHrDnti*hfsw@TSpIcxiB5Zifp*4U<^B~?6J8b| zFTD*3ld`_}twySFr$G^HcG1rI;3KudQQgq(Qc^XVE;(6UM-k(XanIbOuIw}h& z9k9mWvr^(o3&vKU5yjAm$8a)kn8-V!e9D|yXiK8xeJd=;4}riX79awbV+unmLvP`A zlUKQ{hD3tKtXP2|1aX%htr+N<5zqkIg68*>=iI6*|MZvr@c;L9oW5NUJZAr(6bIFM zA{TVp+`lRe&wydg_A1MDNsC#T_m(y+o6=|-;cY#x;>DUIDWd30B6hRC4Xnh?`_=TZ zl)`A@(NuVg4vP9eb;0i5GCq1%MA53?xCl~i=Q)wueRCJ^#!Gd(Cr$|`9xcrX6^#lC zZLwR=phJVnfeuvd;5lEJ!TI^XS`Fg;{C(QW(EcLBKFm*H4rI9l)~A-+)KX#qMvN?o ziJ>yDJ-VZ2kylL_M8ctWATL6XtE?u&6_|njKBRs%JEJ0XF=VYa~gm&5EtCCStxXPL|WOWixP5>?f49HuAa z-fN^)u67XyhcM?#q=-&2j1jKt5J%EyGbA+Rl&x1~@Nrvtnu+~NQr}OPF)aj@F8eVe zNXm+`M?vgBLH7?|Yy`;+BkMn?W?WlzU97wxV=Jklfv>+yj?d>6xl?3m)}O)Qt#c!> zYaRzv>E(FMy`rH$L<6>`4Ykk7y|3q3(#?kol>-}sy2n(*EKIy}PfraW%^H4I@SFbp zi}Z!Sm-CdBVONzel0W;_AcH6pLP2ru^YtAz#xGWy+f@RL_)tGGas$dlxZ}d|oP1Rt zA$DOfAb9Fh)2>X;Wu0knXLhnYurJS>KW#SrqXwpSjuf*;j^n<8Jj%AFm~#~^x6Y$; zAkJIzkiF?%C5?01p+61>^O{-WDMkb9;4UZ3y2n#4Ol_8f(s)tM8^7LApej7bwOXBT zm~yQQ$FlN^t4~<9d7%&ogI+F6V)R4gOrj9AnqdToluvl>EYSd)D{BWOD zASi_1x=RDG()Q3m8R_>Bv)kk%!A@r5j!gGkF%`}>lITqnGM*=wQIQ_6Ct!lYVd$Gt zngEf`)ourI5G$WN%f3u^)I0A&5P#qC^J;qDk_0t;-Xf|qr$4JkaT18zMIaEfg6(uK zNp-xWr=OG!>ZT?iBQm<0}+WUfLL#V=4Qpq;)b*U?hoAms9=xIAp}Y$y38CZ3}! z<#DIRa}3;Bq|T6J7Xrqj9gwY^#o83YPHB636@-K&$z^Y7fWZ`&myEiJc&F3exwu~@ zQ-Ea3VKOCMO(lG>*{xt6_w;v@T4UzLTqNNVHtZbHr7jq*lniXIk{k)FxC-T^9^VH>jnI zAw8N0G=axp+`c1>-1b$*d()>4YC7LUu2#qT>|LVzyXJG=bB`rREZd^gdaBC8WRWvyZ~W(bGW>#337FYL+Qc7wi1T!OEDd`0klwEfs^&Cn^~c(MCL=yZ@; z=-&%<;HOlU!arN+Zq9{BbhdCXSqWR;lEW>vk;#5O#ITcc}mfur1B0P)R> zV1XZSKR<9$p%ibGd+QA9uVl__3D)WW1@85b-?INvNBu#qj^#U(m{LFZ0?? z!n8*FNew}p-|c3tlHj#{p_hUk+xb#vxMJr81zo3}7t6Y6&`iN$QSXcl2+GBu+xC&E z@0Kf7#}VnSIRG)qZzDqs4$mGRppxefD7Lyv^9F`j-BqgbsIVN@$K~O>)VZQ!EdpYo%Pv%Ys9?Mr;$Rd1?)KMy)jXaH>CbZvMb zB7AWBc~?DT@7L0oE@S z@(kt!l(rD7PNZ4yC{lj`0=T@F+-=V=&BT=f270hI^>Nmw>l_5JAYP!y4S-OKPq&bglv%-1*%0-fqC5JA)#Xwe&UNU?F8))iQML%y zr8{F@7+X~I_%z#!KEI3PDV%sDcS`81hI{5T+?(qCYWmpb($4n@GCA7wO2y@oM|YXF z*zYO*;r*q#*As}cHt$BPUMfz{pMB-ij}{2`e*VI`FTa}d;_Ek?WBOOWSbysuezxQG z?cbK=?h30l4MksVt9h!rzwJ1`&@P$X-I#G}!}JYZ#<|RHTDL#jED%o%twwKt+fAN0 zZ8!?MxPsRvLSF@Ci`JlHz{!K{Uk<+|Rc#gBG$yxwKo=4;lGbT=K9G#y$fXpBYrRbc zviqYGvv2#uH7T`VD)?4RO5^RkiK$JfJSNK&)_z8*u!rS5*GS(r|pU6+bZRft^iw44sS*BLgXyK?3ax_(=AwYFL6uwGaym=b?RPs0`}cN$=T&r{<6 zT;T!-u3-;+OFvJ6u`N}TaXN0(l9)Ww+~9@*f{?dCFa>#$j`%{VM&`24sI5?DoUeuT z)pC?C2kClkAU`q#W=~y{HhaG2>mQ>_uo|T`dqm9n&@zHgbd1f$Pm&0wkf{_nu2PYD zyd>n%JAvJHn89FzRmIJvpDJaTmgc8>m)xy%x#zPn`3H8Uva!s}4s23V?)EvSb{pHQ zRj5y{*RRYJQ1#jSdcJune^f}_s~p;#7@nBEVwuhIDj!C3m&s`HV5}*wgx~*?uKf!a zV|WHOCxMz8Z1#LW#{|*XFAEsrHt{L{EBsAKq0i60Cv-G}Wrzw=S44T<_B;-U%$e3O zwvCbs*1CTFZBe#nlA$HOBZGoEV3`A==Jn&@E&~$G`j27YZ71*|>6O;_%dPf zLIQNad)o>l_AmM1TRjQ?ODSAPYAfj`1l&ClK`x#@d5b2u+0t}wOSHUvo=`*^IE})6gbd zlX_1RX6}b5DVq`@PKRT8j+6X_AiGu9kB={-B{A}05FRB#KF77RM13FDvS&gjoCy?z zcTN$|_xN<%m)tcd_WeH^>8`zvLHp|_fR)5FKb&=SPNEX^UEvf}c-^C0U7sLB{QL4E z+2WLY=i-P;fe%HjtE$Kz-uJ_K-4kZINABLGcU8X$vzve%%c>)R>2=8Rresu|*EG8w zocwY%L7`927`1YF#X$4XGun10W;74)9jz@Au_+s)T?1en!oM2H43O9obRnWA2{3@0 zVM9thEY(P_TN4eSG~7ct97DjK^FDXNaUUPPHyZjD(LlIn$Z#nThCX@WirB6$?dk-WOe?4K-b zd8;XPJKAUN-*=69?XIQ`Q62&&7p7=yLR|xq-V1&}&ZUO_;&XGXwT*rs=?_Re9_}J_ zuG=vh#K+i$+ko5zQI5|EzqKSrmqC^vEvF`;`uR$jTJ3+p8n#mEd4m66EB@E#-haK> z;LEIc(c&-6mTz{%XGT7^G|+ct3<5hSah@F3YztH;xRJ!&Zz)8jm+rp<;mOI#iuT*l%8K=C;sNmiDT!~6YZLuyYT;SPYi5$KjoPC zA4C6n7#Xl#wso^_nd47R5eC3J?#agy3!CQN=(a|;OZTf9Xxe{FQYne+CU)0ZR4L>< z56fxZ_ z$r7bIJmIe6K657-{r191b`FTf#Ilx#&YrM~%#x}vxYQ7vgEk10YCv3QmR)*DL`Ge|O62XiiB?|2cC9FWVS(%kqI9Nd@Y z+9TRLqnHN=>Vhfyo!E!T`)p4zY|>A|&#ETMLaVW;X74--7ronyxU*i~ZJg_Od}I(W zzDFcJU+QrP1xmQeK!gr28E%V#mrNKIHB4u6I2_cSTr<-9(*iec-DL+AJV!%PZB70a zYFclR_*8Z&{VZQP9Okq)^)21Y6YH{pRZq&KzHlL|JE-j>9SS^`xcU*H|Al}E6ah|d*a*2ar#syWAn!f5X)EVT1 z8utN$`wztIvBKe1ME`x# z{*k;XH(sF3X*b$l^t$1YSiH=edeVekUkPOx6OkVUDu}zsKt-p97sKu1ngz3{=EfRJ z-s6Q)4+&)=M-DW8nb+?#-DuY+SkVa}P`9G+o6f`{zB6H$zf~n}hw3Yh zVvcH$X1A$ZQ(<_g^L~gAeqk9Bv|Nvl>)#tHPuW9qwi;}8J~|<2TnbaW>nppDd|tVJRaxR{-;UE47qa=t7@7yYDe} zI6c^zn39$p3+Uh3Le=*RAN{`BTX5F*)8e*!?#VtT4TWnfL2L4>kxMqGCq0;z7wbjj zr+^9Q_^>CLK+25x3h`ko4G#1Qn91I~IUL#!Zjt|H!CPjdhy4B$17E=|t(V4}e-Z|J zUCU7lOl%+@_g5N63;n(sJ)ZZx7B&(%yVhkEspnD!q;)KZe}dkM)?8uRVQIEs{$dsu zh_lS@;f@@32-y_elBxE#{AGoJdt@n1E%*2kF@v?EKBEs{TO~B2hD0G330k_n;SPy; z+o@dAA3j;r>mvQ(ZeenE(@3WK1!#R%4-y}HIV{y-8q)P0$)K>hZrQOCqI!YklNoau zTxv0y)2sDoCGm;M6b%fQN&=58l+izorn8Q85_NxB*c-{q{YE29n?LerCvwndP@z!i z{Wtvl@n?dmS3sfumdJajI=1JPg%cCSd0n`%d!L=iF8E-{Si|jS{Ce~6TK^^ar>&Uo zd4G-k{)|YI>x>6(B*7I+TpA^D3Up>Beb9$bA3-DfvZm%ewF-aHM85e?6b?GsSw>1$E=Fd&TriNXL*#a+o*H+?Tfvu0As$f+LR)KsTz}G$ScJ?4KUNXj6YXp-g zmN7b9Ma2xOS6=%d9Ay2BT}+r@ez}b6<0tzNVjPPL0ynju6eY)=*dNU2!VUquTnmsu zvsL6GO+;X^7HDhWuG6HQ%*`dL&`?l9vPlMEu+;q?@zW%ud*1tf zX!@A#SK5g`n3uYvq0gg|`AQTo!y{Tvnm=5}QnNg2j0xpEfVzAC9mLj69@`GqJj*#e zg8bc<;Tr6Wd(9wJCMy@Y9-Dnz7%Qh5WbsR56Z!(H@la7{sdKN|W%NWZVsBJ2#vDg4 zIQNlWUq9<`4gQkyIGQd8F(1Zfdk0|o>s5iqPz+fjs=XvAm*PmNXKW9>Im#sqJ_hU= z4j8R14G($U8K~(@x+1}P)b}_CCML0~OUS$?c@Vv4A|o98^@{7&BoZuxB;NUjKtR*C=@Q(P{T3b06 zv>WIpLA!~Gd|c)AE|92?nN`aD5q8pzgbz28he0L(6EwQ=S#HhHKV;t?NTWgx|BDRZ zo_k*Sg*?}V zwd$lHGAAjfuo_T+s}d+SW$hHXo>fn&q3AfN!?o=*gA^`TJBg$%O??s%)<=8E9j{3# z1vAp~9QMBJQU^XEeAHoW(W%lu21TTV#S(ijjz^V&wadK zxWP97`%}r-X$OsP>X1sNykGE-S17t!y*O4Zcyv)_G~$&*@ItDVL3;-@-&oNVRQo1d zI9S7?SD2-C*SV{#VW>HZz+OxUZ3JD z3Htj&7jw>+>2_jM_I>#)B?KgP_mSztOXlErNF!5=A6#XHw{8pc$awI8|%bO}{1?F}6PCFHf_T;dd`qsJmYOA2SG`jVf%b#rhs#WEJ)&L9bq-he`{IPE@+7lH z9XnXW7`iTS6u91NvLY8rNM22?TIog_!@=qSofq``mr+X(Nz9%4AhGp?=c0Zy=EyGs zMqH;Z?HTTBXU~?pom95iL(ER{qQV)o2fjdy;y>f9vMlcbQ@^jyKCbmvg2|r^nL$N) zF{bSY>CwzZ5lL<7)?hlQpRlX=1E`k0*H*z(!N4@^aZ>sAh8{`iL?M(IL6UGcfV zjGZaeNm4=wx*CCXq4vg{kMQ)frf6sUKf=B|uBkI$za8i5oom(G>781Oz;tZubQBqD zl_Caax;ZUXrtPn8ENM%XS_mmbh!B$0@wQH{3S+BKMUqY}qE$!{NeCf1b`zB)En9>v zM}-g}Bu9zlnEm&>htAwtKI8pMazKnZ=Y8Mr_xV0cPYn1UJ3T6Bbt4b zhZng3k0#^Iu`dJw3PL@eehgi3#Pj&lVY1?eM0RmkE)OG@287TJtvx;SQWBDz2j*f? zu9eURxDnX1FG<|Bso>!}@KJg*;~Z|)Irfr}8xt+%TRd$E8N}f>CAH9ugJWVv9!PJO zBA%b%NFO#D+%|qvB)Nis_<4i9H2~RC7sQD}*x}9l8H))70o%_+>SZs76&AwUd~Q?W zbJjMhBj;?M4TSMm#NL&Z-=1@Ggug!I_O$6kf3mE~aWmU4QnIy2P#opFW#>QBB@<&m zI`CEJ;2oCVUCp;o(Q8-aD^=U9GX4Ro>}Hj!!*?uRsTw%C-MwId)&!W^iN>g3E>5rV$DS#;=G*3zc({+bTc&%SZtey!^g@zp-yfUtx&gFsV>bZP3MK$zP==OD+*O zkeWRFf{xAgUT`vE`Tr|sOc=Lq9>;gEk4ekDoRL{_d)@eGNIiQhRSEG3cj_bK)fs|c ziGqPB^f7JAoIVyt0&o+YD!CNJXqRD#s!HC2(t+ONcjbKHB5}c#>_w@=P>d<_k7doT zO41iYfoa}B1lhknF19BVf&j}pyw;qHv`zxsvHzgfhFuC++f@wmh=U=5#;t3Me633T)X1QEXD+)3y-GKJ3+>IUQ=u?~>D! z<)<(dGkU&ubx}EJY;I~V`84#;;@PjO&DD9cKp!|RkWHok!xH+Nmn#~sEZdg#qx`KE zL+>J?hq<`>PGa z-mxkrVwhDlSJmE7bR<_-5-q-0f40zOcwo**LU+{?my+xqH!s%fO)8`qe2}(%SWgji zb#G6gl+&iZFq`&;JRGsWSL7U;S?b0J{;CNc>LkQzyIt2Ng?0!ZtzMi(@1p#3OY^Vl z+I%&D1Ydg*`(OXpQ{wMDI@>^q{dcl4RVFv+{*7;&>dpig2>Z?X66uVvX0}7cRGUhl zPr{pdEbgc#>G=S@YJ^y+^n*&e)u#xQWi;)Y*Wd!B6j-94wWTWepBiQJC{E3kLqAEp zih5OTc>3NYs5C&pNEVk=b8wX&_zoO+R-FS*sn9W1q7HO{3=hE#E zP_YvVRdj}Awm}}yd4^j0-kp3Gjzw+ zqYvGoyv7YZ=lo;i4j0S5&ZGk_tjt%OqCKr}0*7ft!>~=`e^%v8{ZqYA73%g(_*A+g zSCJ*Kfx2Gw>`=h_^GGPt{c-fBOsVruH0Hl~Z0@@29R;Itg+4m!FEYN`9Zl`_BMAcb zkefXbJ>)UQjS+36=BU3J7-O2K-StUm1%yFMpeL>Gq*sCNsvX}fB7dMW>k?j!UJ*$) zZ~Pk0f(`A)z7Kg>;re)urR$@J%IvM2aH`1CPE4l5;}GB&Jr04^c(JSZOJ1aO`#kO5 zqiF9@;NNT)=nL=jk&>l-k-U@$fK%ET&D5oJoHOpiir`o?S~LP74lGGHzyK-~t(mMd zk(sNgthIh){x7h;?G8kqkx)qdLZ?77wJP~NBfpii&-LwGQqxQ_29fRzAmMyj%Txx} zsY!igU^-f5z7FuhXZIRBm7Qk#6qNq!IBGQ`OqoZ}kMD0SpQNHlK900p`S^UEe3^(0 zQLS_&d-w&dNrkVQKQt4}qup#i|7|z@f{<(+vH8ULh5V#mD-arj+h-VJ`WBoYdGIav zi%?9_A6}{qHZ#~Oj;3J4R^7=-K5z??+?s9>z5jPY*e}VT|p#i+YE2t%?EF6 zC4j=LlJ|q2iPvJ~>VXN!7E_~CcLzpGI^(WOD-ksKmXEM^*~>e+?Qcs3p;yruQn>*LMuNG&1Qiwfpt)tqD4QJXlQOPVnO95LJj1*A-7c9-M_)`Xz6zvjthZ6#2b{8ZV93@m~hhSISXFCOv;HEj}>MkNN- z$aj`iP$zZ;sR?ywFAUP+%|s?LC7_@|G>BuDPWnv`CbrqY@?M0I4e+?CWUep*)~E7 z6lKI=-iolu4@|!c3!uJ`rM#)>c3ixZYrLP_B1Fsm-WUz% zB?q*}a65)5ID*=z7FA?9L_eI^EvG9YfchQ~eqw&uz~!~9?NW{gj%2uV$? zxMaOY$hwBN(SB#8F8(l*!4usQx9|RP*i4or&(}bPK+&SKq!XmXzW@gJ$B=`J{lXqE zFk>i*#nsLWAin`nK0zC^DZ9-~809@HCFzj$Fq(<q0Fub*Z;t98@WlqEV6Q~B`hAbUl@Kmng;9jN5Ln7Y&5xHaDG1=& zn!?W{-e$9mjB^c^TJ+bFH+MSPPC4-45Q(ks>-Y79Yc3lSTo!6392b=7XSg&gZ-dk| zz`$?XX)cMEt^=l$si&09AD!^!){GdA<6$3F^CVHrJpiZc9ylQU#QLq*IeyQvrO|zc zXyW8Z?uMd6Y_*`hC(*Q9JA@kVuWwx0Y zc1zdG95O}FUeE5-F^TOpo&`j)e(bcuaY)?lcF_87LtqkH}>Qk-%l(1QBOU0FBD2TJhp9z&xL4~e}mAQaG z;So;;nHJ&@)_@xSKT>F0Xaa000t`}Orz}8eOT)Ga;>-%9(0Yd6)**mNr?SID;6zd) zO=x^?^L54HjKaXP0HT`HnnuI_Ai9*47?hUc1Z43gV32QMsZ4fsfba5TZ@S_91?DhnY9(zmJ8@!I7Fr; zOU4j~_*l?8mUvB`f>Fla>L_`XerUbkWG zCF+ZbHq=H`XdworPf+O4FA5F9h+qWQ{A<+Kz@SHn2kmyo*rX)1;uD$6$Cam^9C^+i zwz+f8!-Bhu_x{Y{gY#0w;Jdt%wnr`_{9^SNIs3IUCpw~!?Y4b3qKu0a`&w?XChIfm zH=BUmR4jhXH#|ZM)9Vhu&EI<*9tAw*SHW~qs; z{jA$&D~rcZ_0`Fp`T^2Eug7@$zA0_aWWJ$Jnh`HA30Tjt3MT>+(h?~+1vcS_9S5vU zCFI(LV`AqT*PE`_e6QAgTL*sA`0GAZMuMCf@)#vdzN(1s%@<$_XdX3$MaF7wZ(ra*a89_$K&y9T;3U47l*8sLMca}X8818Q+ zk4BQ5qcX$_p_U{=U7(I62z;JK(E&%%D^2gwhh{lDfM~#Fa zx9I77qm7sig*%-#$$tm6(E$SR4(9wW!PP6^0;n&0zU_?cgi4ENZLK&X2~WQ9yZ|QF z%2-`Ow<(o6zW!SON5~{!C=>jx*Pi$_fBTLkxs0EG>W8&?334e;(>ZdWZMn^2R-SY-ioVL8HsxNaSp=moK&H|qX%e7unmGr>@O2G@yZ4-LdfYD5-+`9hfKMV474r0Xw z?uf{Se)1cKLaTOVI=6!OL9$89%>&3Z*w=$W;*6Z0PeWE#MRkun2xNT>w;2OfeeBy8gT&$MA;SI(i zi#q9V@6kVg{qqkQO%U;1SX$;xxWFq<9ZizWQcsLjd`v62Y~g8s2bcWrD95Ukc!PA9 z2N?fV@z}Y=L&vq%Z>cPu3HbQw()ELsETKt`9g3QBY<=l9gbZ37vUT(o^ zBixO^L~{pFh#2Tk@kQx0T{79W6#h*p0pU7MEc#>f^;IOs=27L%s*$&)9I`(Y zza`9`PnF>F&t8|AjGtoWB@v^gUvGN?<1ywazB*s+w?PF^}>?re9v$6Q5cGKDyZ6n{Lr$0yhDF|{hNnHaX)98@Bidj@oN{On_)JH{%fS7 z=Qq4;!Mw!hX2```%Qf#=KdKC_u&0TY*{i-V=2*|!yaZlaTwoyLmTaGj+9RVq`GQZ@ z8fnS$)jKCjgiQjmp`J8Fo95FUQc&o=BC$?fCKA&I?1d;e+WNlk2MgJdo0*YBk?3IJ zXX^KsG*oe-8L8R98BLrWFjR2Fj@!*m>FO)^IABBA9wJ3$@fDSMmprfrlzk|d;O&Ri zRzY54m2uwFWc5i+y8d;3At$aj=?0!}Agf?1Q)IZK%q1(99;* z`zOQ(LqMOPkJB;cn1-WrYm?etQy0C|*Z+Lm+W{LmDhtj}i0kXk4p8i1g#mg91}(QC z$EcSQW|s@-&gJlCgb@RjAA7py+jfJG*a5&WFJQ3BDynGpl+8~(Zl(k_U{VNgaL|g? z-$KECr}^?-H%bk(dcK%3e5OF$rArAhoqFQH{YI8UFS<~$XMmp}Nbzi*)L_!g?`Y%X zza72_o<~>%86>mm1u)9x4y>QC z!(9BOv;7b|K}vfl4$q{xhfLfl#skNSu$0Q$nj8A};!!9LLo|VSU`y#TOq;*_IQu;R zL##!twRL902_GHBU49@Hvoqo!e|xaNWMrP#6RBavLS`lz7B6L|JT$Fzx4?%L*5dB1 zY!G9jRBs62fmkjVm<&723>H?@=CX<}LSZkZ1ApV9J}kt->bXT$p+uC9k@F(l-hEH5 z`i_2Y_17o1%tDnLxu?m&KQ#G_@n5-0lO=XSApSGVwC2>#xxIPy$DprCZq0=n&i$I> zaUuI9VlNbBVauvEp!1DJWe1O>sPO#@E6SWRgXp$koZ3_`fkAqt^pp}X$w9ML`B1okY+94S*wjv|~zQ{}v7{9?|*1jg~!&nZ?G z{C~lFpNQ058;}g`!9V%ZUz@LbLJfaiMT`RB`E3P9Uvq&0qxO&jCu9>xCJ0&_|l#Uf#$gU zSDIYm7#JpI<4rFWWrO?)sG6)}jp=C!R>@R-hp^}q92672DvmlBga{EM4p`If`MzckROkv?j&Ovv5J;peV=E9k16IQIansN z!oS~mb|f9!OG^vN@^#(rGOJa4qkV+PuIhhWWpLAPk{apb8Ximv%WyBUA7)l4zRtG@^I+x@P zn(6t?MsNf$>HOAlN!Vt>K-9O?TOY`d8rLZQtQT{Rx69#841&jxWtByNQUsj{2O*__ z_q?g8kncv*EK~|~+mRvrU$THjKmQ>rA>hTQ9xgHLVng`ASl|q{u$lDkiVrErwGkseMwUjzAlQLbHZ)PN_^_{`Bw3t1 z?d*+ATM8IWiysgfFAuer>t-lZ^O@gr6}+ZKR87~)$!_(+SV!hJmz1A=sOB$Q_^ipj#NQG8ywsuh0=UIFY0%q_Bp2Z{-U4ESV?>DXCQ_mxg$^vcm@m z2-&ZxAPaX)gP{^tuH7r`RLbVQjp3bd=4s!tyl0JfOlrRCuHV>|=5QZVvTi%{OpeEm zeP4DWWhN44F~Ph))q4Ti8Ee;3CqV!G%@T1ixV=Xh(N3ABu8qn|o^KjO_KyP$gK=jZ zMxea(Rsm&M>g$yTiiW{N+nC%7u<5VUQ3Ix5PCC@8;|yeE`Kvj z*4>Ul42ghqoIyMx6lDbGa91e*C*=>Lk%Lx^kzDe5t8HVLg6_t|An>tuWtwi&8NS$K z_)O2BGbiH$vs=5Yp=Bq(l5PQW)Y`=!1yOG3=>~$-AE4Em9iTb3NQ-ml5mmsF998CL zL1zC(I0_=L4mL~#YpP3fo7V+grkqRM+8Z8J)kF?VE9n1&YP6V)a=ARe-BxPqj$C-j zd{#&p!D;<)#QOGPWb)cYr591?k5cx0P{sT!HmO~U9Q+4wU!|Ss6TxbJrz4Y_#eHPt zJAZ?|w%-#^-xl{V z>Kj{O+7r*T?vJY5y;k8;RqAB2+@4ahWe@up#Q5&4AZaYdCEZo50hQZxu9!4 zoXoCstXPdUVo)ei9q#EOj(ZO$w@ZZ`&vqy=+E*K4)QtXgz~&@kP-tyE`OHI4g$Mfa zh~MbIC`;A%b+gB`!O#(P!;DGGz_-Mh`o;XgR>L%8@+jpJjJ=KkD_p#)Gf1Y#bPBqM z@YGu0QBbgh!qKvywJmGV&yZ)_YH-z<$TYAq?ZE{m5EyW&G0 z&1ziH3v8Z2ECTk=xdA;CIO~8dO2&vbS7nIgk6jz`1&VDbVpl};yGZEDUO+5Mlf5;b z4a8o^HRr~LSd3@kL)Tq|Z1oBke1N_-szq7juZQGMW4|2_*y@ujBVT!0)3BLG7r*0* zyJ4_0LtJ{PMjo?RE_DtP*%e>H3{94h$pxb@`SGXINW=(lJkwfYt>%aB6bE|6Z`hNe z%kQu&YIm1xFnYEPNz+JP3h{($sp9){mq!CrQ4i31s(6My4^BkR ze180SF_Y6NpLnX~>kg1H39H1>lAUFi#23{PSv4|Ch}6sSxMsqNZ3*Zetv41G+Jo?} zAA;y&_rLq%HjZO-A)3wFJEp!E0RZMv=mB^=p&=hB+fa~^fGE8{3%r|xOX)R*J>Imo* zYi{5u9!ksql!UkNmICsM*Gy#5JJSMx{1dwNX?+dEw%gbpkZ-X2D(eG7?hrohbrc*) zV!6;8TSTZcw~Cd;XE<#zkE*Q#edNP?2OzQ`9>|i3DpTu)qBD>x!|(EbM*g;pFw^tM zR#9m&XJNBn>a?}X)LNB(SH6+7LZ``H(1#oZ1P_TbzwJy z3|ymB@mR4ywyRg-9Qvz0s+zB*>( zcU6hqUiMP;(crxvGd!(`Pgm@pVM87QZJm7L2#0`)smt1qfl7-I(9u;Bh0p`iwHXS4 zLJ?1Q0e?srPrg;vpsiA&;d+lQFt+WeT?SYx$CC^aFm6^m&toHv(QPrP4}`329$Liyu)zzL@0^?;5gkMSECTOoL$#GI{qdc>G6yZLk0Ni*vbtS%(rkaketi z`W`G~wB;$DC;rwcG7e5M^_GrIxpPgOBE)oJ7`-fgbh@L1tL}37vSH07a#7;G?u&zc zB)>_z@+itczn2bH!dxakBJT1&A{wJl@q-HknJA_kJ#s^+zX0ImVk#F?f~lUE7YM2n zUIQSd|I6%-P}Vx|n3W2FNUJ?1;X;!cNLM;kOVbP9r9f7BC$_ ziF*aw81PYz2O0)rNpgvO*zKzfO%~5?N3BcpOiYksqe_xu7z18%yZHh}C+P*atD1kLYjoyLgui&$;0_y$ZQ2Z^Qn z)vDuQw7$m|z<%p?X_Uh*ipA8Wg9vDkb9=1nUVwS3*M|fBIF+B=y;453%WqXZ0#4Dto=1Q4>d;dgDCgjo+20*V`r=Jk zAOB!(=ln!*=4?gOF^EGUcu)9b`1Eht#pV5X`BFCyJym{)ZY|B^tU@-0iEx*#$uZKR zMl@;$Nh>0|%)(NKx;s^JeYy9FARR$#c(*a>=sl-}M|j`mxB>wZ+zx(_B#~)xHtk;q zD;(fL#F7LkN4J5E7QsoxXGLvu&S>yt1~`u`wq9iY=3*qbxOb=tek9nJLYdf?aIy+r zgMXm%!}E~L*5NI|Y4kx_iK(=F&h4POxo8%S#i8?JNQx0(QEjW7L!7r@3L+Jz&O@>F zLv-6OM$$B=>oY&&65Lz@&p^(ir^1RF&)JU%^)bE!yBZ?CmqTo{eKDk*UhdrGlG@nA z2H zw`Dq|KUyW|((|UOv%X#>Y@N+pJ41xQaI}0>^u!ktaWa3F>ze}T%3|tvm43CuDG9J9 zAxtLyUWw5CmX8Q=jLMQhJuv=IdC3uDsmb-)n^VbO%?uWF$kah|bij2eoV)=M3DU6! zrSv7+S(2iTBzD$7P)EMhWa~j88OvHkrg3~Do^ocHrZk+Ah|YlAjHhuo&*0#AbbWYIp>5vVJdacyqxxEW!b&eREvP`0 zeqs?q5-e~gbqNe24ETV%pm)WuJP-gdg%v7D!QApIUq z>F>Dq&h0y$&empOiij}fLbVz;gc(T@{oNpupPYeP$#f#Z0hDHwb9-E?Dd}QSL7ZK{ zV(3S#MSJl^`ONEq96Tvr*rw0F7dEE)_6v+TXhX$0XD98IjIF@WF(1o6n}v9<13@$B z`Ao!mi|3!aW29X|~9P>qFg+Mtg<% zw`8zgdv=5`99&(Yh*U!?Aw53mi8t6Tfr^w*bJJ`S#%hLzM7jhYO=Su;NV^B$G6VyH zfaTfsk;yZ(CLVx~-Lt0H8tJrrDD}OHZt;1O%ftIdaHU0{)V0h36B@)EAZp70iDF@6 zR+ZeY`gT9+No=o+C`M6?_APK^*dVE&g@JaFMI7(4q^u8(uISge3C}<}*L+^ed8OGC ztm&DjrC7_yVNuGwiIL4Nn#XU=q0N{Q(a224XpUn|wPFv|<-Cw!sUk6GFsh(-d_O5{ zs*m#Wq^Lfxva%|PWc%V~0&m6m)KPA2^4r{Qny-D*7kgM8HOkAx5Fv4!5Ptb=CNpK~ zIWENrBVZI+M4BB0;sTMBfLqB%xHZjs$s<$^?852)3%R>eH8OdMFEJ#18{B(&aQ;+q z#o?8ABvpD$PQC`VdFEx&$r6b5|G9#F(g*eu|rWe8k68{IN?Mn4HQR4k}5zc zAk!$y(4~3gpeGlMg)aYYWag#4Yyd7Yo6FN#(aPW3u#CITgOGanCgr=9uL6w~kP?cOwR$n-`gv*i<@sYdKVKgn>JAz9x^f_i z5{+!IdXU&Vw@;Yzbp9ZZ!ZQ5N;T6B{=8tC+BTDjpXElo<7S2Gmh(!EOiuz#LsV5uo zG+)GDfUKwi)VL>^YDen_O}h+Fx=YiGnc*F;(K32;T?D&JJms>E|Kj}IGMVXe;Y+YK zk=94&Vd39A$z;S2_Rw6--pJIDbFQvU%*zhj=G@NB;g5Jst1pm7y*j;=}c!fTO*aMODK<*YC)gZe=IL1Gfj8~2{P!c!W>#Dm;$1IBRIhx3*yEkkNxL4ofiEU6JlW4hor=o4us~K4lh2 zMls;#t^h$Qp6y#kCJ*MWLIPvQvSaF__3t6>$yA|pXfin2sI)cYSEf&fwzO~xxFxk} z5cYmOI^0#tS=3ziRG|WRz;ks#f{o+H*^>+8&o^*W^(VH|&t8hyc5`n^0`V(HGP}rob`+@ zTR#Jqqk`8N`ElN0_KqvhzZiC9okgoA9DGpFN}0zj$Fx|Vk? zWmP?_;&B4GW$lBzR6+@x_vI<#FJT-Wi8Uuv;km8Tv-9Uu%xX<7QsX7X#$IynA?tzb z^*l@s;c}0A8p%KU-s+c>;d+9%JR>dFrV^nk4pl=*zKiVCFU3Yce1T75R;AUmVKJtD zC2M+I!VX(W!*2V=qWhIzfHp)iVh@g0HgCls{>w@JX1PAbY|u=Ja3l&TSDrN~EooEa zG?~1+^w#%ldf%dzBzky;@6F1P=Ycu5S-J{c z)k2?Xjx#apy1Asnbndb{1PV<8l*xDm)gib;ZKd@C#6KCqHwcfyaYsJTq|4s_d_?Zz zI779$qrOu_2JeME8}Y~Z!}6(2Q7U=x-`>l%XThoMzT3@WD;#_}@G!$Bx&0DtD?%m} zvDXS7m*hHm#O6kNiZjiS)#taS6J%$J@NiWF#=1b-+a+C_%_YEC*I)aHzNyZDXb8jz zr(pnmA4dYsVPv>oo&?R>(=}3uVZLgAeA;T*6IvwnvL6BL*a*7Q9(V7~Bdx6*Akk&`v^3r5$x7!OSLam(=lh@^xYIQ@35Hbj z#sGBz6EnqZLjL22-8Q#)RbpaacrY* z4o(;5o2z*gO!rAVsW-Z>^`)E#UdjDL3RvAiB=>_a9KNHyR~B6y$qe1U-#@dBXbOxm zx*0^Kr-_U^y7`wDN&;rAL|MAKB^m}(N9Yfew#m{*i{_WT9~8ML^W$iiK7wvQss@b6 z=^9rS^ab(eSEd6&RG?666>5bVtK$;&dA&83)1l(kMKtu7DE2#uZH@aJvPP5e>Gls; z%{cMUKteSs%Z**`H44xIki*TiMQ0TMbTNhY9y34$8!cg71aL6{+rrHTUxg@9ai^NK z1vE)9dU1(VM+hrOV;{ErNhkAHM}&;eNSqPE|9+gk^rVwJ(2l7KD7}k)?t-u@lM@ZS zkFX^700V7(Rh0s~=9~vS%XC6~;6Kim{mR`2tFnVOVx}-2g=$fQ2-=VR>XJC|zL1a^ z2Y=o(=wS)7@w~bqHi4?$wRWC%J?yPbN_hb21oi$@P7P$KcPNW8%(9=9QF}?a$_e4F zQ+zfi*aD2Ko07;wF815yujDex8)h}1RRdcX zCWPLa*Y5GHEoM}PPBB`y>iaA8UzGr5VqVHc5GAWXpO`8W#06wd=bIb-8hG~dn8$(UlHy0Fb{ z15@a^utD$HnRLU@<-zlhX^j-eo(Ykp=GD`#O>Mch-f4wvSkJ<0luHcdVKyA$<+kGO zU;sjxc^~t{Uh3vF3f~Y^8HGGgBCJV2n9kyC-8*bM4TD}qt}6$ z29Bll0r@X{7kcF>D7W~xGvI!Jx*j80*WfWn{8nTH zD6>1FHM@V%Wf)0@o1Ev=5D2=V*aqD@iJI!x=IexVxwRe^V#XEIKxS=aiM6ESXv9t| zmXnAQ^#E0bdVX={S&Cj0J;6?R1jMRbG~vOZ8Ank}x*O(6R&o@jN*a1>Or*$9-JKqb^1bxI3*t}LzcW)Po6_++?gTjB^{(lsMK|?tT6c8| zai`d_+UVO09(-%-;)un!Xc;B!7XhZ|c5Kh7u%4q2b&5uW)-wmd{t^;1*P>47izUje zTfwmb=@FvUxFn>QsF$dlhbMj6Zkq%CvyKjm7N-d-gJaVsFKNhcJ|3*q2il1M1j3EP z2QLVb%89mXOjP!(d_D4RfTP$U)`no!xX~s{)BUj#kxcmt3{he7;&QRWbx#30ImCA5 zW)jhc7m={D(e)M3H}hR>4%`q7BX}Yw;l7wE8W{^fY_o;~?dfhvHMpB&Yb!{Rz_o{n z(Ukdv#)BzcHi@ZQZv2zEiSIe&b(>U>vprVZL^mh3XRe>OVPsmo_H$Uy|{J7{Jugfbz=Lqnh{UDxFJ z*VFL3?)qe9`=r>G7jT^1>=7pXsh5{GWmX7mE(U^;%X9uDADxL<@$LSW0B!%4P4v=K zNXNjQ+>iflfyYF~V9*2`EJJm&VNt)B8HQ)FEwb`Ue*kH*5}4xkT!YyT%yod`dV``o zD!wq4k-ymY8ySvw(0?#pX-ip#IZ6-2PS!f!H=TT2D_+N)y{E`@-hId*cGaX5AJ>vt8 z<8c^PbVY{ZrIjnifh1NLaZvaCrJMbyKYy*^(_0T=gOp)QHB}@402<#t6hF z2}*l%G9Rr1Do?PaJPE@EUJYU7kl%nP8>f}@Pq56;_oaS=jj)HX9VSni`H+ENH&ziw}ggi zj7!j#4t6+^4>QfiX+KZmnt)K7E=;L$94iGLD;boh1iE!Vyg@A|Kl$H;A2AAVfv9Gjmxf)V8vjZa(eQ=(~w)r;xbrJvKVx006ed|bJIz67CKW?#U zA$c2X?;OyOKN~%3a>AND^@y(!YRXlulP(P{fvpCj{;IP~t?%iBvh%@zde;8_LideO zr7h(m?6NcLmYW`v+})V;mK=7w{7WI0B1FB3>1e;dNFPbF7v|8hL&ivbA=#X6i&R@d z28OX(SYS{c+6zv*JWh;(SHD9WiR9#xGy@Nr;>xW99YtSoV?mEVOYI{n$Z%Ud>)XZ< zyQnpj!X(%}*d4cr)fS~D%#kCp;q8VATQX3x*hAG1$xEA)d-Ac6#hr97IWJ{8fy#Q` za32=E%R}09?wZuk=B=B+*jHw$tDfTORJX}o>U}f@`$dZT09}ao9Bsvv_a*xb(3*ehQo3Q3S~eo#o3wS*pj$7H089@{${V78PTxCAhBluv6U6@5OGwVn$% z^RM7RkI~Bg?C7P)1zsU{5~t+nD}pJu)ALtG%wG*w`)+>aOC1Xk>Pz5iWs+nGi=(^) z!687}nJ$6EyUMFa^XZz7P<<)?oQ?2xzsHG?vilLT|LcrrM{}jTE%|?cFaPG%ZE9=7 z&qnlHyw{;OX&0P3!h2%|vg+&%nMf734$R%LZ>G0osg{LLNXq9ZWqGJvX?9<(Pi?+{ zfp)&@IsETap|M%JvCnQbK&-p&9v5Ll6>1c)pP z$qiXh3WMk($OVY~;B|xWG9WPzhaD-|uKtep2FXz8*g34vh3D2#h{1Tz&yEq;~SG5)( zGT^lXHGhr#7nKIf%Fv~^(h(c#!vh9+mTN9X&hQn80?-)EI zrn=ffNiZBpL)#r~7ViYMMzA2`Sp!*;C+o-2bWP^p87=Le+gLphm2$a3a#1HQe`P@ldXi0V0Z^u_HP?`DTHoNmz7m95*_`-@!WpYy&H{ z38at`!Ivx8ybQ~gy}3;b>qApTlKV2touEY5HAMs%@p3m7AE!e85scC_QC?<_CS=HU zXg(8=UN00HE0+?z{{9@Q7@8>Y3>2+RMty!u`U<{;l^!r&OT;Z}599{CwPr9Sh>hr2 zxg=-}=mhy41JZmpJY;s*nghQyGZj#t^gk}709V5mjEKcjEVhReHUbYA^u$J8hYxT( zmiF7;;HfQ&JH(`3iBv97SEOzmlCSU5yc>G$VodXH#l-gyeqrA_YxNs56qW-IUVlES zao6|3jly$aEXCZC%}DIJUw*HSWQ7>!=1`?!*P-HbP%iW|gPRLh5@T@GY|DV)1ml+5 zBbu(%jSwb&Q)jrDKX!GDD+diCQpgFmK@TT%-w*)NHX!kf%*|&Dx07y6Nrj;7 z7m2U9z!KoBHX!-xOWikDHfF;jN^UrkqE{qy5pd10|AZb!E`?q9G_Hvi#}S$AtWgr! zL>k8%`3lZ6)HSnsY)kag$RPwASV0Ut6Jj~5;U|Ssa^8>YY{0qcUF5Vs%-IN+D7^Qs zlnbX>07wci@R;GOrzBedLd)U8|8Q3AI*)BGoQ^(Ack97a--wK6`c9rXciq+C47dU= zW!FjC^Webg?cU9+FKm4@#g}7@u%ms#vPV8{XkS$oKr@-hyG`U_*Gg>i7g=QWPw>%+YV{o{0o^?_89PlO^7O zTb>V_zp?I+a*#|H$%QwU70>YP=Z1*M?FD8+=S6Ky|G?dy47dq4#@m?RA8HX%D3`&0 zWnEulPXz+Kb6ER8o>o;$qGJ`_-z* zJ<)lh-wl{{l3*SxbR!8&}>Cj}qQ>vG?+vgZF(DVa%FH#ze4Urr}jW z?GBU%R!hS@&l)3kH3iYO)OgDzkRuy}^h(KeWvb*!1)h>ZBkleTH0(Z)SNjg8)L;T* z{{&;|`*UHeUSU~7O1|?@>+KbJGbp+;ut+3&;)dD9juigTy|#wDOfBy-JOm&Dc@8Hz(ec1_A78^=G}fnBwIqH^y?kven5VW$hE@%So3+098> zuXm|5vk*jGJLjzAkB1_A%%#3ZClM)S*g2w_`V$@}%m9Me=RganHWyaT{e^?C8u)G7 zgt$5AWS9C5;bRJ7PJHJ_=i}{xH96D15JFKms0;8FNPmo77;v-`aGUm+HeOle5H5x> z-kIBm@PpEbv|3vRl0Dt&ONH$BB<#<|hC(oxLgoOukDkqMOPIjk!7mFudds_*^Ztp3 zjOY`93VjKThJXuwtSzU5KYo=McCQt%vhtbWgK3TLVO`%m*(!-ml1pJN3zsraGi!s7 zIbX8O><$^`O;sEFY$XIy1tB8p2e}gZj?+O`R{*9Tri$&1PD5hl&5pBfI6b7mj1%f4 zewx3K^{yom@Be*9B1q4(c?riFUY>&Tt*i#T?i zF6V@xO{1n&h-WL{>quzBg46KJ^okD#_u`f^JbuHj()n1mr`ll4{uDN#L-0~S0|>H6 zsgn8ms8MzRE-vLQDFNMv@PgBW{mdQK+Q;9r=1?VVJR1n!kX{Qp3%v^lNZ4fe%r;a| zL4M4nBZ0xV;+n{s(8UD2{1};47P}&nCGaGVgMCG}9ZVdZ*@{;@tecPcJ4v_idlE&2 z4@FE>da(xn&!Ltb{cETqKD;~p1?@rY60RdoH|(H!gpy0D9_@&)10_?arRS@V%we#Q zu4LSoEB)pIe~TI>(DQI-JK|d9kHg(A)KVscgN3Q$6p$ni@xw4{h=3L^obs}{T#aN9 zz&V&qJtSrjKN8)8#-rTOA_m}|+aGW&p}}Dbv9C(ah8<&(C}JGqhDH}e5sOPcI#k^P zp7BlZcgV2Fxg^ws#crmFX=;*NmJTm5scRBE>%7yc0kK>mP0=#UG=-a#L zZXU7Lx$a9nY?6*#_vH=_yOqK`SffIM2G^t|P^q;aHQPdAEJo~i6$^3+0VgluO~)}x zO%T*DG2bA+NIU{Pl42G!IIyCI4FRxAIh4x3##h6Ztp0+r))C4DOg)GPq*Zm8r8c5? z#ef#G30b+fTM88*sc^MiWM1MpOg#uQxP3X*jBm6zV*o8ZO??iHr{-?zt+K$hVvHha`ao_&LR)z$7YPDQ!{5XYLDmY_)+P zUN>u8sq?dE45@{&;z(PLJ^76=_{w=cQ3o?%Y1ZFbvRz>!zA)24rCbS`DA|h zc7RbMzCdU%KTIF-8zU26!37%*D&%fWl^BjR$$gGD>_$c>-%k94w+j*Zj5dD+gTk>- zgdV7$s+7mt7^nl`Sc}Z|ic^fP-3a|#!ry5nd|$zs!Ah3I5av~+pUBy) zix(fm+VOKu3aE_(E^`R9k}*()WK zmw=M1ck!3h6FP8=XeVY-`jC6w!g!MWMp}bxE!;u9;eqpdLJr0V%GI_ObKpT!=?OB+ z<%wOK#0x559n6MTz~#i;ZcI^Q;1yzr8`udSOzgnWcD0%wZy$V0wGvEih}n-?-x!_v zm&@o~(-Y>ow~jZ@j83HDB%MEGTL)UJ9z3?I^t{CdOeWMKIS%u%-}ypyvd9Up!%zpJ zk!%?$p});uJbuq2zlYoB1LNHk!}%bx(Fu|Hp3xH0sZ;)L4G^&Zh&2zunf8}H<8`zd z?S>*7n56gzK0%#2`w zDp>`Cm7f%SnjA_(Ry@qb>LfN^%|sHR$9&%=%tska=w_G(<$+K}YT~cPtEHf6*pt!p?`HdZ~nbCke zIsk)^MpzkSK68oIg%pHLfjI6bH6X`cgFP+Zb3F6(VGSRBRvGRwKmt(f7%NB{@6kJD zxSP*hK659)yf&-K}xF_71vxVUaH|s_0iFy*vw@ zjWglbiqKH>ZBM?AMrGa_lud;^qDj6uqR|Udo|ZAApu}jfOVnU~c96A7O11gnpjzVm z)K0H{3ljX*K$KGNo7S`NTeoEyUWSZ_G3#mAvZ6V|9Yi8e7Ykh`R+b&{?|gAUiYP*8 zDIhq);wRs)_dMzAkc?KwH0VNxMwbnyQ22-hR+GP_IP5=OlIxMu#E?MNuG8!V-jio@ zlnx>$<67^Qo$=xi!Tdf>-$rdiV3>-i8w0SHhVCSm*3tsNWDm-|9GHhtdr9#bh6;C=hHGq$>FCV-+C(~BaZ%O=EwKfTZ4czMNEq=Apc zm5nyB3Ln!&x#gzY^#+8RKn^5yFPSS#X;@XZy^GYE3h$o5BM%wDsbSCdCbMmooYwT%{k zv5hZ(l?2Xfp@9oKGFC>0-redj^mSCq15>3-Pq}?rJtWgJjW$S~B3Stuq3>|M)wS^T zh;`tpK+~t|hhH+63XAT0NN(8W9l*#940Pj=6pzDCm6`@U3%>2c$=QfhD!vluOShg_ zv2Tm#kU?WlqwfDdj6A>dBj4B`r+QtPAVwb$oIm1M>ThMTF#QLR#t*yATif>(P&?qQ=R( zz1|9#djf=hrJHX3olg@7WvK`GtWQn7&Zp9gI zTWUU3{Uqm`<|eE&02J-P=DF9lQYY=S?9sQq)n&4&Q(5N9%+MW@2=99Bxuyx3qf;$4 z3>J2Oj8S4*_;z$(q4A4Q=A|_qVc(JZL%dSBN?@ovLS=4eWl3n91=bQJPd@gkBl6*C zYaKu!NkcmZyCfK}tYLu6XA_cphr0u1(IY4czp0R(z+b2CPhi+OncZ_x3_FP{Ro6yI z;X(WfK#rN}3WP|xi9c`qJgCoLV!-3e;Me{hNNTI|s~ui){(>AI6d=4BVg}eG|d+rd$?KaiMv&lZADaHMC4S78vw!k``67 zM2l2KH>G)+SHH{+0|+H?xKa|AGe+W%3v<2fK0A|4j49^zXX5=a)#saIwnU#?adfza zQFJJ{-nqFpP&kV?PX?}aOWnYbXm(Ex>mqQj#4u?ib99Ve9UH0fsZK@Y^1J>!dV~M^ z*mWHh=NxsmMO(yj$HbL_*@uHo_Q>P?VbAw@QQw^$o~tHY?Uq@XYB`T=kLdEe|JS_f zf9sx+kRDu$2Gj2^#priq;yLGXQ+w`}kMpf1in?9d1JtkPpW3yh#|x@W{?bTu)B|0z zshKfiSn}pv?P1nlOd+EcsNRG_#=&z{_T2W`lNuGu6|2}KDScA0dXI@GANs8@9{YxT zsZ+WZ8l*9F9Tdi-sXzO7A{1!k3BLDx**pE%#7upXt2jTI>UGNU(+t1z;)G zI+F51+63xyP~*y#l5G^ubtm^=m6HuMv@m)hYpGEFF-Uqr%cuJKX%CjOD$Qi>?O-LA zf6ChY{&3DKoJ7{Y_i5sZw!br5J@36!T8aNwL zjFvY=!rLCpL|EW+VWx8GQrw#2#*i#RY+f}%_%{DhK_OCzvtH)PLWr}7N>MWdl%7;< z5;6aL1OIa6Kff-xJ6sU88HAi%!eG3;#!j(=lg5^a?UF$-a^88)%Yrhp*=vl`!mWMi z45=N@lXjjMSdd{>VTT)@ zHMrff@?wZ_&~Gl%jAz-}Xhh69{y$-F9?;a8?vLB+jNVz)+v!ZTwa83uYkL)_bwPxX zPG?%DrPj92h#Dcaj8Ypy3J4KGk~-bTg{cdu2ytrBwhD+y0)*t)v5Lx)x*aL`@9D`ckb_g>-__yOY&hUotg_8^sY{&3WgR3p z7S>{%z}(@>#KkpEnl)}T*gEr7D$;vz#{Gl|w~AY(o4wo8Q^%a1(mM_&e^8SUYHJ&C zg`9}(Sk7L(T|mb?irmI;(v>EO%+~7suF;d6I?-t$AC$92l~cK4W&6~NoU4>D*{)EE=(&VOibK;ou(RCN0JRiZ z4q1E=%op=$PKixIBRLA6K2kw-w|YHL#1nRw&{Zk5Jf|zTe>T{SDiEDu%4z5||%Q}~Y zR7&$@BiDy(8H!OOab&q-K#=X*v4|SZfBT-f)|s4UsDKV9copfifGbeXIjXvr*Hz!j z9I8+b2OVMW&;2RAIx_6p*&De?AgL=L@qlej{5faak?vR?+2?5t&nlc~tV~c%hF_p3 zdVwlr_fd5CIB@$}3$)myGBIarYm-{WbC<+YCz7yW!GD))-{a{$u~~Rgl#otT9T#lqMMD^K1YK_EyeaW2hqhh$@N8KbPO3 zOlQ*+h+6^%SxrKcKfoQ`eKB-&BeDL0l3IzS@KlV&%(_^7Yy zRlU~N2w*B`__Bn2z@^u$r?EK)v|ynqsCrQ$ZW#s>x>NzE&rXVKjOxj4wW?||ODLt3Qvh;?ZTDnl)8S#=@XmeI9JZN@nyXH* zKVo4*<7Ahz$UZ4@3&Nw9+_i;1KLjJdA(cm@tu0y)s+E}>z*Q&E)`4VI7>&D=92DRG zV+qF`!*i>N&Yk7ACFA%Ogmn@+P)L7*t>=4OaujY5{~~uEfL!DXSwyKKosJwG=Md9N zz(Z}Yf$xI>XOg45u>T~YTRIx;V6WQS^Ta=q3a1Y3d;wv{HbhIL`H z>K@F8k7KMqN~P@iS9RY)qZw2_c_Q)0Rg_*c@RVJ0g(}FI0$K+8t~S$pVpTwh z52&$=<^ZhpNNt!FLu=w42#|$BaQyDe-O4^Zlkw6vpVxvhH@dUxhI~!91uJY-pD#`S zo<$Wpa5$4uasFyTdnxMNJYX2(gMSZ_9>CnGbsk=3qU#mB3Eg~owq1}N&K)@#gGH;T zAvIWG4OiK;fpl}n&>jX{FkH!?nTZsVBwW(8->}{vH&@N z?jpp^Z;2_)%Mo|xCQGXQqYY!gocfTP@JU5$LcX2RRRo^i$uERU*sPw`=Q zCvPLMvsY2T=rBw1WbWLhRw9C0Wsuk->z70bf~*^D*ug40FPne^_b@#oIWv1m9RHm} zXKIS9{RVixm3zz2B2%_t@TN zrvksK&9rQdbAFBBrL3m*!8wspczTT9iP{sfvD^)y5-Sos;*|@(y%;5kRBv7D&YuI) zP*-VvG4@G}JtcR?o=pa>5XKR7wB=QvXkBttWv_n(){7Tq@VbZ3c^*oDy{474LR{b4 zt28CJ4%&-8wmhqJ2vigO6`p;1_R9ey{1=lqhT*!-04xTdw&BF28M$C65r|zB#J4C+Di#NIQ!WXHzu_ z;aT+z#$NESyPYr$C+JU1^CQjgC9l8;L|IggbPz0$ymqbYkj_1fjn1JBrW>nwUuJ76 z)fUx?+O8CGVVcJLQ{Sdn9-Yx3)!Ubz7(1+rG;&6z|A9|Uq~-vcfnub%#_}Ocn&18s z&HL`m-=WcODFpKx`gM{FWMOQn|&QMHg{9aFTpLlr5w$t7$g5_K(FAdf$y|Z)=7tnuO!r8c& zN2>PMQrjx%JHCSigSEG4iJN*h-J;^i#z(Mro5R8k5m-CRVBxXb;}y}m?=t=@9x_); z;6@9bC-IW0A~e0G4G#CPoNqpm9vpS&7<0(}pb;dY`k@k71J)GTKkTT8c~W?1!$h&IQM@zeQiOoV2NC1}qCBWyWy2F{U+m>3ckwIekoAl&tV= znKHJqm-0ZZdg^Dc^vc!dCcr@G$ZN-okci@0Qy9 z+_OQ^3k;ajBndCK03`X}8??m@Qh7>TY6ta|(_+r1zYbH&t`-J*3tSSx@yJu=4%*hF z^L>U~HH)5@_Fpk+;T(eKCc1|V0vCo{BBpeQXH^`5?-k4?k3H~~7pO5)S}o@w(G9s3 z;>n!pn}TsueFbiq*C*!vS(mb)bJx8RmuersX{&#Jti!Que*u-Z(UMG;=Y>K?gt&m= zu&ETz^v7seuvb^Mo)>C^DvUDLf3qblk*Onlt@WBYk@Lf$7C+!Tf}J~KqVRPP80_7k zQJ6GTkZ0I_jCOH1o~;5A=PEINWWd7M_18C?jxqEq36f&v4p6*IgV1rAG6 zAYYQ~4VIRx&pQ|JpK>ApDI-9^cI6{L`9>=Tmgd6HPL3&^#oquk=@x`*HYn(uZ-R7q zgyu$fBG3EO?hqzkM`*#Z4UF;XnS2lZ@C|Fz3hvd+8F_8JeND9l!Z?RB0bFVLz}IEk zjbnb?ICe`D&A#Idu}t*hmSxS28^hrpEDQ?Z>7%uYaKmjGa~(93AjI2Fqp4Cz;z{5` zT-__7S1fqp!o9qRZzz981=1F`xeC7u%ORC8c5!p#Y{Oo%5CyW&hZw!B{nLkMq^UFu zB3e#4G&C?%)V?X) zS3%_6sM}2DQ)t(vVm-_tf2peafO8XNK!b-X0GP~ouveeo9>mm!c$*?Y&1}7VmS6}0 zDCUQ1WqMun>J`Ler${|I=M@#&<-Riq6cJ*T*L_{tR6d6F48F6)aFyg%0OKG4T&vcZ z?s)vUu&tWAoJm~2H(3q+%WBHzV&c|fMr*;3Uxuos22pafh)DL67qV87rUcvZ!cg`a zQ6f`4jt&labfgm*<=uC(d#e#}Vmg}-!0Z%Oa@z4o0@f+5){VBOD zZ6Dt!7$tTArjzbU=24dZ72dlTZ;*_A!e3xRm@I5p85OT@WO6ve)!$XW7h<|LCC&54 zM4q^s5HyOqXF6g2@J;nr(PWExtsevoW7>wc+IzTmPMGlMCseU&AsygmTc$Rn-dIm> zEiv;mxIs@>K^Il_sy!Pk-}X81`BRzGA}ymMfPl^RTdw@H$ol19t& zNP08Im=|DfRghvh( z`f~;AgcR9z$<8B$`hg*;Fk+k?L0-9fF&r zjz71w)$HqWpSn>7j?V!x959dxH*7mw%!(KFc+@mBmSw{@8yCTOT*a(yeQXVJ^d@vILCvX(*ZUOJ#LMQOT#lT zR+_39uHNBMMssSiJ5@c-_-x2rz|Y)NZLq`SD-A!i$6e;@#Jz<9v%EqgGL!5*SUJr# zFBqk$Ma~Ms8q?obS%dfq8u#|1S6#n(J-ljSwfX^!<}yw6F9i2!{U%Ik(aPFFS7nzP z?I!6zi2T_*T9??Pc4xN9+M+U;#G@6$PFvwC35w&@+%N8m(*Xf1to|KkRESlEDm({> zgj1J`oV$*w1%%y2t0Id)|H^MSFC||rPs=vg7#puQnKz>RlBDJ-`n9~#K!U5!v`FC%Pw)lY|f-F(7RpqlI1Eos1lEHfbU8%u+bin+y|B65XPcl4(A;CC7 zNP5O#d(H^JxK)|H7RI;$T(~I;%kz-_BHr#t#O0)dAd08P)?t*5goWvjz2NZy(-jj? zB)aqx>O0TAA?3jJA=%^E5Ge0c?A%Q9OMaBm^5x;p@0f1!T9V?zT1r7BY`lGtAN?%n zUbii=*x8>~6Z>l9vrV0hs;mj)rc2|XeKxOE4!#$)$&+Rv*kCtbbC#EbQM9_^Vm@?CTJt%eUg16`zy-Ndwr z#*0A1I3)qzDb4T)=<6!#VR?HN0U1y{eMFmG!8{R4!iQfcQz z9d2jPm?VPw1BjJv=^{#OHJkL3s?8`rw%akxGL`)D>vuQ!4E&({4q?Dxr{D(r65{|_ zq7GSrEQNwkK@x#x+R*j8FLz5&r&fp(2@wLr?Ht?9>tFdL<+kou$bcrvr>DDNPyZe^ z?@=|u+GltgBT}o7CJ@09nLR0enoh^W8-S&(lsPHg|xg6u^b=UqISC0vY3cP!n`Jei1g3Hxx@6tQFgZlEgNX`Rk za9#S<21mc6QBKBqe?8$zdh}wqE_DymEn5wFUdbQ--8=tF%d^ z)#qW_f6RLVm+2bo*rf-x4w3O5bKnoScV>9nb|pG8F}3^4d_OEeuWx>*jr9o4mNTTX zHkr10F)7=9r#QX4UiWIa7!Uj1=IoA^2<+3qT+)O&rUtS;w}MsifVVGG$=1%rAMvSU_@Y0RDGf9%T|*`S`k{~7y<@q~S-B%p z<>zFVE~Y-m&+*aG4$xr~`Yd_YXVwd)3a%b^k|Mlna;b?Fe67I|VgPf6={Q+&^rILy zKxz+#N(MgE?mI~s=D$jkeA;#s{b=jQN}tz6R2BCkHcj|$sWE2ctW|G%iZ|6_lzN9O z&3;PA65Ly&;nsLs`Mf4|3k5{M5b z3}0nd{3ha5&+^DPU!8|`#ydqvRgS!Vh#ElsEZnL0<>lXM911I1$MdH`+x@J@vdgUx?dx9|p8ZPmT%#rgLm0E{pws#1I< z)~`R@_AWo-$^69(W{=vk&-s9(Y4zzYD9H>K4SD&B=%mn$_Z<&Ypl|IPT3MHtzwDV z-U{*+j0%a*mSK%C1-x9s3w>da8`V|k(?`1B1;Obr3r@KKUQz!x`F{RrJixm`r4!)Y z&oph?_i9u_c~>L047+Ytswj+5_1wuranrKiEhYQtW-@$023YfA+W;cmJz4zA+fF)X zC4k42?@2CGaD;QOH21mvjRmU6uwwg^Q9guJ##AmdiDjqZAk8Pez=}5WPNdXQSoA6t zTC~S~jQ;Vz?2iBYVcpg4cV}lmd-SG1BmUcqvzmUa@U5OQHoUX@Ik7FYaTM-Xx##-N zXrFjY-98DxttF{)kup2dTU2jXk3L&*#$ntfAeO2osj2s*A8gTv_ts5+&28=^o+2w$ zbbsHnJwa~j+j^#IYE3z&X-Ya}dr+ycb2Zwjj}F#WKE{U}9~TSHtBIHKWgvGG4|e zWUCZKjjl<-fg^HeQqVi|3)w*ymg-lS#{BGF6*-^bHZMVnDK;hdFt~&Q>^PwFRYQwC zaM3TB`CTb+ADoyi3gCn_2i4Sld?o&)j9IMdO3dbzIcC?_T3Nc|yFPyjf~l<@Ah(Yt zheN308sy(`x=u;t74#;(IJ(JJ-m-`}s3RxF2(5?9y3`fFbD6-Ec1-LE>@25=F(I@@$D4E=8D3F3J>Y910`44E6gpr=F8S5COTUh^ z+%v=df87cB>Nw0bNBtLj$&C=z#0v>;v_;9L87da3abjMpJXf0V`b5EtvlqYfLU?Zc zJC=G-pBQPAP6)<}e|+fUr4=sE;&`_kumNfOT{9V zj|?`1H_d(uxSkyf+YF|wYJVHOtp-zIz~>q%wU-jarwUH25$rITIqyqFyEzAdnb#|4sU zqUkt7HwB_Ru&DQrGhn!!3l$9?ksQY>aT=-{!B;4a9xjo$4K&R3-~RUNy+qH6R_P6L zY+CnPo|GTPum926qWOwDsx>Ctb0NY+WJ=X)1K;Eh+%70o+&EN#&uvX{_oVE2%>6;~ zj=V)0L0PHO=ci*s2K?4IFxOp0Dg8NNclX$7W4C3iJM>eL>YjOW|Mj(QgW<+8dV^=4 zM)+08uuOKk6j9O23j>Ru&I=cv3w6rdC*9niH~r|=)|Un4%>0LEfVo>lIAa_7(w@!4mMUF zh*ehv^7$Se+%!~=q6oFxdH#>Dg7-i`Cj3Y;{X4!-(e7X`k5@=u4DRP#a*JTHp_!8Z zA3_X0+ozH#zUeGaCdJHvln=1F7e$Sd${YlL9hrrYNBw-Qz6rf`;Khg(1=F!=eVO7Z z-fvJj+NWQ^-R))@YuQf$iX9P4t)ZL&gBD#3DO5@?orGuqqdW&HBis#d;BC0o9-anA z?rN}()rBJ#Vnl@tYF&S(MaQ2J9o!5-@LR*}bZ$F-pkqy9#Mtw7K5OFQJ0*N*ppqK~ z8vSB%vB(ZLl^0uzbaV>jvQsI<*%LH&oHjq>(>6+F1q*&bsT*~b+Yf&7yDsKteN2%b3R2J7i1Quz%&*wI#2 zaDrs8&aFOR*V(R^E|Nl6tONy-7zcj6?{c5AkP)m32Wko-`zA$9smq~fb1>m)uNJHW z`MV4LYm5OKB3&T!z61Lk_mRR8EMQzOrdg!u0cCL{UaLS>3jt|!WFyzUvH*qU*2bA# zh|DGY;@32{`EZNRlG)<|1txJdWmH3fhI!QaXCNl8)hfF&q=O_57x}10hHM3bFoLGm z1N<;Q*Ndt`DPs9d%ANwN#IR2PUiW2XQyBrl;LQOjt(73c^HP|ho!Wl0^;yQ!B2%s+ zdpv8!9?xHB8A~z_oVQ#YQo3M*q3H2luiZpHt0shheu*w#87{qdq``zek2?Dm{T@^A z*BN2|(qBi4%(UP4*HigSPCJrNF;a8ZP+sTleF~I(V=&*j>FsBo8KYJ<&^!o#2Uf`{ zL3UkeoCg=-7p|2IK@0fS=*)d}@6lzUFU5zSR)jl7F{@RTFNw(7keu~ausQ1}EI&s5 z>NVPx)bBHVL17$}Q=i=~?0qHliyew^LgJlGy&7`17z>4&VdccseuMB#>o&$%vbKyt z*Zs-4_J4cK%*gK-R%T50i{>Mm$O-O=TBNNXEa`eTCZ~VW=zccw{CwmBccg7MJ*##t z5%maOydYc|4!S*Xoe~azH55x)DRcSazFBv0suwjd&tKGJE6NsAsFkE^?5UlO=}$!p zBsFpSC0M!F%2GteEq+F1;|_8=m{rqIk;G<)5v2ha#vUS2&^woubzc76`$0=(UBfnh zYT*)fR!Ly33KxLp;K@YEG%l7rKDoMv)KxP?;XXUMcE*@tZQd8v?<;r41lI)#K$+xP zZLT2!8>Sdb^R*;?!yecvck*pq@YJaMI6Tf0BQdNtBlKlXgXxStW$`;ER21YV;H+7j z{O8WTW%xGG+ih%QT@7fOxD_`A4C1xsn;E!&ms8PYV@2c88!SgGtzn!u1GlpaTMA|i zA4~)|_u|YGY+e3|@KKnlO=}C^ls=;9mA|vR#4j-ivd9@njhZZHF{%j7B8Qh!ihh!G zXS%lVMQKm+9R5Gp&3_}CAYHD`RC!EYMdy`*=fa`AZjq3{Z)hf?uExF)UN=!0l|`l6 zZ*kdcWVWDm!JmKFF?Yg*%^Q0KE0pEg{!pj!zUbP2hGL!;cWvjY8KPn^$NDy$U8$lLlYF=8iAPCJj;WRaHCx1duy-KG zFUU)oMwE>sm_zI(KJp{in=Q;-q&(o_AZ5YSa&#K13!lrto6-9^4ZKM`l(LwHz^uO8 zFhnLD85TYC5n|nYeV3Jn5{w8JhF;pn`a8JGt`NBb*=rO&7mU652e zbM}F9)@%cB=75M)o15&l-jf@sn?6M>Y)-<>SoSS&B6Kq|XZVq>GhQ_87W;kXlgy<5 zRSW+A|3S%8isrMfl#5OF8}A~K1FhM~)=rIS=7teNbtRui3;uq~sa&)nlJ5c{`ayro z$d_V&k{511qRXb;5y>?oUe6s)aGUdFdX@+jq9Yf2mcl)Lpaf$I2q&dxRcBBqU}=QZ zItwp9uTb2zUe(A3w-D5GAB`xnA^Vp8+&Ep%DCyTem-u|VP!b$<9xR=mRxgD03mUvn zMW-TJV8jv=EE3jH4ChtVc>9gIgy)~F*f#VwK}YL`YI%n2z;%PeWs~jPpZrH+w2Sd{ zEr~jDJ!F&jhwYfi9Gq`0Ak(I6sht)=mTB#;O5^rLoyrrTu>+L}e}SRjlrB)ut@q+! z_i^5;V?#D$ZRa(4+gsMgI1<$n=?sOnn%A%c4fQjWdFhkh&rwl=|MTo)A3XiHd$&*9>#^h6ZU&!))M83l};t_o} z&P3xabhCxJh-)BQY^h(?Nneawpyrswg2|zAmf$`Ll8|s=GMB_L%BBm^F=)P(_d&4% zK7XnCKw>(`+%cwrq&WxFI6bFT^!<*f_`@i;0TLa++|b0D4nRIZZL~$!fUNKcOhlqS zCjwXy&E~VTx+A;Xw42t-Da7GM(nT$C?EQ1pu=oU5bIAT=j8(@GJlt8q0m3F+*>_}M z7P@mZ%Xu{e;iYMH7{oq(&X`B0!f(8Mw>_`=6Bi_IthXF(>4e9p_;4CbTCSCuR$7`% zN~zK=Lb+(2R}F?@nr@T!OCPc0Zi)6bdN~==-r`ozCpDLXE3=jqsgr z^tM1y`$?(nPkEg$~ zotB^Nf6ZOn0vt;fb5DM!DNp>5d)prra7bY!;{Mr7#2dv&fnD=4uw zS{@_`C{%%RMPdtarc#L_7~Mj4B zU6w6zLpHS-y`;vRhs(vXWj~HLt+jgVLVMUj___!GzL&cCX~3E}cf(&R?={VT z^{>Vv@#}qCHB}$%_b@PePEqn+ z(4?zKhS=h1%V**h74?s->2Y%IQ*3^9HJ_de_ekOM?!bJtBF0c=cqjD<2 zp4uO2bfzJc%C?|aYeR}uAZbYH0V)YTqQO&%|8On1iV1E7x#GlAmw=i|J)shqIqNfC z$jMw z$SAeJO_S^LWEcHiaf+A`Z79osPqUp!)b+S%b1>mTAn$_N>htvb2Wq439hGX)H&4L( zv#a)>r(EVIx}eqG__O5HaP&W7)T}?e{(<6iL5t0M&`&34{RPuHOVZAhL0hITC_9Po zyjLh0dDnGU=(d8JWi6G8VUVHOVsG&F%zcO~=0^RI080+Wp>{%Q^S~A@`_RFCK^^B2 zPmc#DPFRl1oLBu5D(u+UK?R!ktO#i{11ASzFB%s|#i>VQ=??=tOk=!wh_Jo0{W=U# zWNpj`qC6S(72cYP;RwHa$P?5C1E$cb1fl^fiwxGn29y16b;!%IMwWCM_De=zh1N9$+cdP!T=WPs8QsFVGj)5S~fvD2LD*^JV7w z^WwHm1nY@j-b>NQcZrK@+FreFkNV1PAu>#Sc`a#L#|Sa>>-Xq(1}~kgwas&^fdQbx z$g2TYj4)#8zIJoRkI_F|zwWz~^|KR-dDl97-;GhU1bzMUXYz^e3F1wY<5x{o?|-H> z?RT!_FRR?k-acg5QjvaqQozHrqi@?w>VA?g;%c0Smc8{|BV%n|(wpkv;psQ?$kg7& zosOBeurPnAs;-t}bdRr9Y*9R1j@I7kWDxqmPYnIZ*@x^H+Vg~X0d~*}F(NZCNPgz; zw%DKsBTdSl2aRo(7H5AX9t3~sUPJEyr2A7Byyrgg7NdE3OM;l}|*Fdvh zm@4lO5hffdN}Gzbw!Ab_B= zvHQfnB~$iX=~_h%EPTUs5IL`boKVw1mZk)!!&`?Aex;R1BS6aqHK*58;<80v45z@x zv`@5{uBDX5uVVVmaW8~}HA)GiM6dSszRE7Hc)Hnj=-?GzwETfM`;tJ-`;lH=s$_##1h(wSR95N zAF@e}LO7XQnR&ag-@uH_E`n{J*`$K2UMQghxZ6wN(ikdmFE6cU*IklR@V`r5K`y7c zOt5NV<>;pm-;#kGnVjwV@fP=PD!-|NTQc)I2;6N`wqS~b&wh#DqxW^|!;{7aN(-fq zzYA21O>dB z^oihJ{ZejCf#M*x#`1NHhDhIE46Gr}72y->vzz+u;P$;TP)EmtyH!>+F3aq~g^c3^ z+Hiw3P3;y#YIze3omegWCL=D|V8XnDi1GhqSy<~mfs#JG;@n~RfWgN+UvU;3E#XQP zG(4!QtqS6G4-Gom)Mmc`D?Igwi}Zne(dhQ|>Ncn^Jy`3QRWBSavHdnycGc?H1HX}= zx*Rgx)0IopCu)!1UuKdOxnIcouJmxc{8Z3Jf&vl;wEn32t)F_?>go9(-ap_sqsBPK z^tYO17P%}RE!7nr%2MognFt>Re+@M&>6lw%Je%p3tIM||nNFTEO{BsB;;tzys=_V< z2Rq!8I;O>rB>|7+7;D-1iX1>mOqeksMXvVCM8geIy*7phnnDTRbXQSS+XV7BjWDUi6J&Vps85 za%lrs5Y3P3``un(uGg;G|^y@PPL#sRf$>s8XISr+m&B0Z*ih zxL>CsYpaL)-7pK%0|!ARuGq%3uxLOqB9ngeI=}*DIa{557s2FreMTh`{>*H9Rwkol zz4NR%2o&v1ubL*8JmaxQ7*2=nm2^gT|33?-|NG!{-Z$cKXF0sjHqg(3Ef;~X=B&Lg z(34~&{Ri0F zIB>Ct!kMH91jsjDmfVJk4=(3;lE8mZkf#-aAq!rAIY|-FM~o-&+CWo*%F>Bo7s;@W zv6eNDb7}xSLpn>s6O2e_O8g>5uTxwAX81{tRn;rb27Do1+mpf|NUlCI+&NQM?2K#_7Xe=@)IRtOk!EV zz=XKwVDlm{BriyCUTcQR3%K`_{$*tH@sv!@#IfEO7IICPREGHd2e?G!4+J+e21S$2 z^j3`^(ouSEBZLY2zJ`aE1sYjt?Z7^T`leYRPEg!U-%-0VFNndCb0p8vglb84ZjGDv zZihnZLi7UlQxZ_-9uW=0`7C!?r>q0cX99ET0C|;Ymc$20);P~^$(5nw^c03yUvBe~ zLiG_(*(jyO>u2BiS?`f>a>^4H%TZR1Q2b@2YGCOn%8g)-|0`7 zr5i=MD9{37T=iW38P`mg^9j||3aWq@Cq$RU_D0Kj)wQsul7cCMci?+P^tnn3E-qj1 zE7`_k*!z=nkK`%87*{}hTZrrd3TRs)DzBTpxryxko};{F<88<^O8j+EvNnOBA_~z!sFYbDBT>(_$gM zO-^V~@)Xxg2`SKn5Fh5dbmWdo`d&s&6DGju153oK1V0>{j4iMg6;ynYcV}DVvBse?xVd>Nwy{b4mpB%qI!@#B3m9ZyX_Ql zCFt@Dzk++A_nFoX84~Ln{Zy=hT>p)x$c7OC$gJMhHx2vzYBBg|@9-+QHjO^P9nof` zW?$bzaKTEo+OzqV<0Mr)6TG|P{tRFL+0IDYE1()+JD| zFmQ}>R)33fTen^KcqR`uY;p(p7U3oRN2>~8(+|t$oEK}466su&$6j-lU%&IJ>Ur;G zwykLB!9FGKjHaR5v}4mz+X-VW4dv%~8Y^#x>e5K!KPB2#rnJA~%Gc9~NyaF-Vels) zMTxLk*%aqSlZb7Dv_VVD}W4 zT*hO4B=XvR@*FJ`Zq!I3hB$PdL~Kgi=fZZ0Uz&UtB(=t)9$Dg5Xx3AVabtf(^&y&I zFTcKuDiOB(vLF3|jxdV-Qnt`-!4eFC)KsJ0OuL9QTgmHwQR!6oTgYW0@z#9)l`1xy zR}0`ZRaFY)t^7~o1Ok^xj0Vx0-XsZr}vc z28Pr7;WBhRPpy{FhCPG`^~s7v9YFSCXyo9&;HFx}vigyXc7~~3Z>_Us_A!dq4k2%X zm*-|oC*ffZbj3z|Zp@R4;-QF$V=SUX7#YkHY5Ul>g+HuCMR3k~b@|Q6%?ksuu60rE z+N}oj+S5Dx-$nk_q|x4iMc^$zNr@cCbD17#wTLfmHDJUj6%eI*Y#pxFMHhHvsEWmhyswp1Zw2Ls5@Z!!o|K_Opj?tPag#d;j?5V{9k7g zrq)1`IVB)_uHp-5LRzpKK1+^1ska-(E1WJpLTA@wB5_n)7_s#6<;}n)y*E9O1=}sv z#6)>%?4yIUtXzbk6~s(yW!Zi*hP(sAJe~xhRU%=M=NJ3&l#&e4Erl{dx-jYFVjv2b zy3?wTw?~#?9;vk3x_?i2GH70Me49^r3292B4tcWt0`2Hc`48-b{L`m@r4+fRBP(!l zzHHRM9Yn-TRQo|1(#LRtPwFA2^*-t^$F0%5fYnb|mIvp94SJ4{Mu|HJ$ipCr-d@_c zp*L5#i1<#_KT&c3F*$8->c7A|4JFLnd|2@MUFER7qI^Kn!8v6T->Se%3)^KtqL3(& z-DJ0%CuSdiFpoO%&lF z;PS7y;9h>`Y`z{|nM&G|#9{O+4`65eSE?w6Av{$So=@kB&u8~ygM$xf+xawMgsZaW zMq!PPw4tN@%lwhQDkCVo_X{H91kwJyTqAw>MOg1 z!_-z`hsFMy=jcPQhR9iZV@-^Y6r56h1halqFJhR|~L z%v}mLmiaoMZWn!v$lDt{pw=NU9l=vjl?@r;N{l*)A{NW&D`Xx6_&cAZHV-+Wm^x#^ zY#DRMKQ<2~iwG0x*{9gZG;!#N`Ba4d?fyj(<3t#ehyv6{NJEpPMA&&Mk2Xz*8!(LLX|}XQeRhOO?aArj!#_{Nx2u{ z>0T@SU;gjVNbLr+El(ybemY|^0(bNFa|>?SPudPBxIaN?kl%)>)V6f{x=Wby{sE5Q1i*q0(D%&O3LNG=^u!HHe85- zdBn>Qz&;$9v;Kg;Qdv3)RkpqUZ)#UiHz}M&1nmt^1Ov6@iy}82uN!apsd**nc`5it zio@soGiDPfIi{_sY3eNWK%O-qMvD8Qpnn12?+8`)XZdw0ik?^C1@F)Ab?K`5KfpVB z+D_VPQ<}(}$UjdQM~#BZGLHNM>;Oenxzp5EB#iU(_I`m!gfSX9#G#lHhE8R%2~DRy z@}`1T&2C!596gKgY_JC!i~FoA_NVCYJo44n5@H`#<^azf)(QAbi8!f*J8@i|b;t_7 zl(|Gdw8Df9%$wov1qB|qWhYu{4}vrCQ)+FI0+qC?wOAN-6eW^zc&2aN`$5|%p-}5H zx0J0LaWsw3jmlwu8~xK%&gKij@4ej*@J+jP@i@X8?-N{6J3^xzKPopJ}L?$EU7LBIn6$SdhjL4j(rm*RTeW$~vE$4<~`O^4%tZ91rg^SA!J0+@c6J<}>aT@$G= zm8y+DzEgnY?wHnB)`d}!1NrJqMm9n+YyLoY@8kQegd#a())%Q(V0=#eipRj1KtUZ}n)qB;xzk3>n81kIsLiq-6-NIC zJoe;slY*g8cQt$7uh7x6M-S<=ode8i)~RZ>OcV~A()xosD=cpwE+i9QXv8oJnSFCg z&(ha2XZ$XF$@DI4;RB*Ov40GA95^=SCB812%cY`wSUFzmXb2aV(W=VB@2&FPi0ZkF zNOf|oWEGl~JzJ)nTEM{n47F`*adn7UBKq#1jOI7!B#>(ZNZp>7zO4Trl>&7kt3PN-=9T*bn`e0eFcE2lQIStfTMwx|?`vk>#8Y zNkRx6GI-X_F?Z57R;wa$C4qv@yo%q$sN9>KUymOP$7BQx5oAi`=x+{H7NC%-HArn> zMuOrV)-{yz0P!pxrO@+~SFuEXOp#HK|x(>FaAdb|^^Ih!erkc(1(0Q;& zHEG&rW;%?IMc9MGu>AJPXX)M}7D*y^wl2G(^`h9cmd_(9ODs~Q_*Ns9GV=42Y~_Dv z9w#+f-4jNu)?Y)M!IQIk)N8AIS7Qq%dq+W8QdH7qmxpr2i1*H?bK~N3l1Ore zWtYBiX`{5!F8Tsx+yHzqK|4Zk+L%Eru+1T7C|dR*0?!RY*9TYdp+lsr{ay>i7S^rf zy;5O>Q$2k?<;^9{l7CE-rTHl_eSG8Pr}9IvR>X6S&}kA!jMnYZ&!jp?(r~PlCbbqd zW*hYb%ox}BD6spH;d@yA9%*Kg=$Kcc5tcPauq0JaW;c~Bc4Z7v8?u~zIx?+S4*kufUOS>}|oGBKUlwl+1sXRCx9FIOU|GBGSLXvinf?4&>FY3U{+z z#8c@@pJ6PW+wuR}A<1)h)T35s=`UMLs~lsN=brn|_uqf)N4sw1of~m+)ZbRt{EfNw zw60`BTT*Ve*q1EX{vXdg^>umoj7NLCDQz>NAY;n*2M0A(@2z!7 zXOFWe!gGr!Rzna}_P}oShrxKsKZM6%f9C0^j5uCT_FB@+0T|auCphm49acLR*D0Uz&vK) z=yly861su-8=Q~sVFg%cRrWTFd%&O0qK@tq*+;sO4dCoxSHoz=Z7i(W_MdG`NtTG2 zpLjxQu=8W@`9o=J-*6}lUo6*}6fmb>A=_oW2;6sUr|?raT7h=gx?mLQFb+ec#Ek@v zi1zD#-d({t-yBr88>LM|wE}P}+c3i)ohRdln_8-BL0AEm%zOBi`ERyqEJ*f-EbFUN zn}jLh+=<@gH~%cQ%3BmmKi)@mok=Dxxg)TWA($Q;b)3rJH22>=NuP4pz8SX4++Z>k zNks+s6bx*7Cq^zt>}`3um?Q8MpPr;<8$V@`aSG=@U$u zn#}vGmHhfcCJ$zo*{3Z)mm*%FW@MmS8NM2)stgW?lA-|9&CWgz)_7(c-Pf{W1)8O+ zI#-7Ljo#)s4Il?|G zcbls;wwp|f3a!Sg%Z>-D{=^1tO3Whxb4Uk_W8}d)1w<1B$rw!>ejL7UnTF+y|GBDjX14RjiE#dRzM1ugeU+2L+5$UWqn{!A7Bd_^ zx^@w0?d`P9pd(0=Gt?dOZ1H<6c7j>5`vy8FfJ&l?vS;E`05Po#uZynQdG#kRtZ~CF zG@Mg!M=cotL+fqA4FW`b>3sJX?aONT@!0vO)w#>0;DxnJ8vRmN{q5?gF?&h^e)ekE;ilFG*3CWJJMYKolbz(iHXzwc-8{$rgnq1URjBq zhXjEcOj_Eng+uMNRC>vZTEdCcNF9bQz%`nDr+_wjJ)$zBaJn87Z6AM9{gk3RL^RxR zG?YDWMTMe&#IFIr4xNKfl@ro6OoE{JVDSMOgi%&C{cr2nrVkTKHUt(0qOQK6%F zXVeypOAl8dB!QmOZI~EtPP{eLktdmkusa!}FfVOVO~yF`XmC@&>#TsP3d2d-9qX)s zCl4%LbX>aQ8q|Awd#QRha$I3A(yLhf-4#Nowz@@H(-qSN<9q0l4lmvD(FVKT+q*h) z@YryiQ_XHZ8Gg!AV$QI{>x#)4dsE*nP(nHc$pK@%xt?p_!#E4SoQ5U}@qeHzf&Cxf z2?rK{7qqf=d{El&cJ*SI1@9n%A7;#Jpo^BTQ00G^`R{CDCRARt0x^#A)NoIbAFAB;>{s0hz>*)$`6)w7w+ z*IoDYVJ0`?s|WH~wsA|+%85f`w-fJlpPyxzC<^T3O_LABqr|%SP>G|Jje-MF&jJK6 zP^#@h1t|S1`bd7rr_|=wE<5-9MKE^|-9$+fN>HabC+DcKg*GR%pgx<`Xx*R4aTk8H3~-4L8H5+h8C^X;fC0z#B}bn05$ zIi{Cq@@r4kc=wZ5zU_`Am-kMdvHJ-I71J9p!+eSeb~L4ZYnGDUWW$1%aOYuG zzlIFd{Dr+RE6#}i)D5iw;rF+0P-7xr5dkf#Qa-3)q(QHH6`&ek)GC5H9PB*VF4D7Af!Iy}*pd4RgTT}zO&Y69pbJ1b@ zTEU*BYa)A`tq%YC+v_lwF4Sk0ZJehRINwm?o(AZd%B>@{o4z>0R9qrsWM+C>b)hKg z`A+f8$A}7?j^SpG3zt+f@C>eO8Ju}5A7qXOlR+8N(S7rIe>l@(uT@GH-@6ifdKkCm zmYGb9$lV$Q2|Vv+?*MqIYG<|mVGFHn4?+(^FO91ks*F*`l9&Mmv*;c(TARHBQFyh2 zP0+U256Vb1>#i-8K{3eP-ooRb93GCiSCqz>r=K}{k!k{&1~-c@sYKz!rX5Hc`OJV= zGQ>Jsa)jDfjUW5jOdx6QoDz|%^$GX%MQRsjx=6#JGBJ)Nl~zzd&W6~u+{jga#<$a- zm&)5AkNlN`eH6dTU-ZXRkQeDTs*z*kJ%oK89?8TdBRRGk!$S~?F%cw~wWidTg6ltH zx9QGr@`!=@xxrmNf?F$gvYn{G;Jr5|Qi9U!>5U6RU5R&c3g!R6{q1*WE5PH3oXI_h ze}(>Lty@vcW7QvM9_J~jeej{}x3GxuNSe!js-+n{+f**VfkLd5)hiqC_){*FL|qNM zdUVF6>_gTP+zpo|+14dRkT)l}*QB9VV*K%_zVG4O!KrJT4#&S?g3tmvkV|jMi(tehv!tuAN&TaHcIJfAtEo0(xWF<2i4UK*cEUaAzMEVWHY5UB1<=r6LxxL z%)Ale>^W{ryh)-Va5n8KJQ(y=)XEU;amFXX`teog zwejK#8B46J5X5ZrCr9`|5n~4gi$o~XLnvWo51){qs94(ipDE#0h`lkLB6$#kA3nGz zOh^}fV~}j?*+%E*9j}b;&~ip|r=nk-O8Mt$`Ff(fz%CE%v*0P zjC9RBpV=qVw{}JvGh|jhSQ*&75Jmx;yB1RY!J=siPhxt7v|u6@t=Ln+;}UiVF?x_s zV`hW?QlLJz&0$~heZ+@k8#@Hq93d989&dmx5V?wPL#q-Cw#rX}eZ47y-(R5hg&LAb zb1m~lvFlBcFmVaNy_KY8DanNcIRe`!9D|NY`_0XbDwX59Qblr;K%>tB*Zy@-y2NXB zG6rhT2e5a&?QlT~!~1Y$KO_L@h#bv(A9PvL2C=n|n5jYy6sND?(~UX00i&jIVN@76 z$8_FcD*GW3)Sv0ZRj5jia_{Sa{W#$PLbsPvF&bHp-)VKX%VQ-Gq|oHlC}2>>@mI9_ zESDi{0(BC6H;~{3SxvS2h>e0$Q-@1$(!wl|xQ-=^6XDuoC{6(y-1+!7m|y>6YA~7g zIrh7M5XMFm!&ttFOs_V^&_~uJ3lHQ(l(KGYj`I_5m|h7#85P{y@u$AP&V6*={H4&; zQsJ;3X1%%L%QZ^Zn?u4(F4Q~)B%%x#WsY}A=xqc+sI(-N)ZHf|q`UiLz!FI&sla{z zQ2MVAnq=!K>;aIVJ`{U5bPDcCR&KRtcKpwJZT zhKdr8m~^ffk;9M@VRhY-Fb5!#0q;Ooh<80a6ek6LkQmxrUuko9lK0%DYMmlUnas_C zsf3g8sopr4=FGcEt6ZTfi&D%^B_}VZ3m_5Y(8v@ zwH1mKLWLVra+R-qHi$erGdlj;PchBx<{X35(-Bjj?=YgqUrzNkE5sNN%IFq;Pel%o z-Rkab%vM>9io2A<>;(7>mhxgnQ}%vc^B*|EZo9oY&o^ov=NL|>Z6V_}m^%R7vKUTz z(s|AOop|O7$>J%2?U3^gQd?7%XIWjB>C7S++QIv46rk|!TdoRwI1P&%`B`SN%Z$*; zaiMZN=&hwJ`ah6lFc=S@KHLu9^0(V6I9n;(a1TB=DPrGESf?1+((jemEPI5dy5fq` z5a7WinGOigbvI1+UxC}uw)E8ZE13Jmr53fJBCu%b_Z8CVbv4a}PDoi(sT=uG@tD|? zZx*^L#5uPuap$f#(K#OCWaK?_#>KV!YYlSOB1O1$(pA|#ZY=yt_ZN%8ot1&K+TUoB zR1+bZn|Wfmr02KeaZi{VoZWP&qM-mt6W6vk@r7{Z=l9QCG8?1h6GL2m4(@=Ggn4Ub z+gXy!Vjl4@vNliG7Bk2s4Q%>1L2*GQ@AThxy=jR*vKmf!#7MA|E~T390Nh81xmrUHMrrtnU0O+zbcb%@A$u~@a%S0+2$ zf5Dr$rCpOK!Oa#~e<5uJp+7SSuMN8Rs=wa%I#i zJe-9rMv^E5u>+`do=4=sCn#$sn0Ly`&6jL82qy=!XS)28Zccwn?V1;bLb&E2eHmef z8DzNJ72tcMvg~olsqBe3F(1;mqBn*MfwO~?p}G%5y1caC!>@WaCWGKzLTY(z8+ezf z-u3u)&z1FOlH};jaZ}A}s0Y{d+W*JcyT>(krfb9PxOd%qrrNi=^VN0~nW^L0ZbfRT zQp6TVZb;v)VU8pY4NN?s%3l81EXw}d(-umUyS9~ zg+`@6z6Q5F0&CsX)JVzTKIPH3IpZ;){(3$*6a$-sf>KzYCuwQ7o-{s!=fN02{$$_4 zuq7u`XVJxGGn8m!LoMcN-*&|yv69xZu$t0b1W9gfU^biE6}IGj9UU*CrP0@tAjTQc zZX(W}gnLyX95Y%Dl8^}{8SGH`qO^#qlaq_^=$uIko9iLh+l-xe5XbRA}VW{l^Pv zj5z_K@k~2{K#L=Gz|6rfcB@F6Gt=A?F6U@jIMj0$CeENjerqU0{@Rz1D82d9vcNJ} zl13;1w_HvfcaAT!A10T~;S~3mRH-THh){`5NwVvxm&}@MHANDd_(Mp_ZAU&h3iu8i z2E2Cacge{J&;(8n$2dE|VvU<|zDqd(16nrs@LiCvgO8RR6Sz}7>hb$v}O(An0%J>>S5QwT_Ui!u9?Fr*z{q|C=J#s7JwsuJ}+bUak3S<%P zxNj`T3SM7!HhVDon*Fxc*^>NBfsBz_>WyFt$lPsPmMr@&Hqn?uj-Jzu5v1UPz(KjY z4HSPMVJ^c}-m*s7gov_JoT@%1$pAJU|0Dp(6|&(*irlE>>s$}$^R@PwY-jy7I>%N4TPClNInr7clPYoZ_7KgLok1^O}75>JtLk0_2C=T6_Sq z_%e!$*4h$5Kn97Nw@!*9ZIGIalv$jz5t?j@APw;3^$HoBT2T#%qJiL|U~X+52wfzJ z?=+%lNcN$zOpWs7;yEZclS^h&eLmg6r(U!;o|4^Vj=#+Z&l1(=%(jy--_*u!!J;@< zEyzL|2F%D^4#|1TUn%X+Fb6Z)Z;f-yn1K*bz$)LPx0?(Pgvw_z)SrOB++4`?6KcwLH4S=XQxaiR!FNI>xK6b+ ztSucaKAo;JLx2;4Bpn*zs`Jq8a8FBN)?@`P;gGIP2CRBe<2jPSd)8>{+2*6~LltrW z55XLTvoN$N&PRSc1$w~g7sZZ95N~go- z6G3T!)4L*8A~_d_8BWtdsO2UY64X3}JoJ5nw<2qtqWvVg%hQ%H1lZ{qp3IuATg2sw zX8?K%=IIB9m1V)kUWD(|)QGC>L(8F(U7@b=k6$tqY^os0CZB4#;?&juh2;a#u+Fkq)G0xFH-M-%TZ$XxI zzJq%M?&^2qo(57}{1#lfH>w%{9ewp}!SLsLTSmq{BaZ>xt z$;SPng2?)wUYl!S#_-zz7ndGqsjlbk1g=@$=$yMWYECT}iIm=I(iGUdxlT_zRJFks z$Uo#METE=W1UGI6Q8r9@5CAz>kQkgrFx%iM z=?)HaY5vrVLW4ud#@G#7aV?1Q2Tkyk$4&X5PT-itL>pSlFAteW1{g#osDJS&V&vd| zWyO04@h9;Gwm`jQ47J`h!_%`RANk)U*tv|TGqLo5b-*>PlFj|X3#=Ma0zp6f+fT) zy%6lU3pjDlS>?x{8t663`G%$=ziezSS0FY!)~P80DGcXQK6rPPYNs zj6bf4{ih|oEh<#Tlj5mmun~6}v0Lre4-`CSD{eQ_EGt|cS?`6T;Ks_H=fwTtOyvWz zMVx=uw<%3x?zi;o$TC7sxqu%SToLJoo~|qS5tb8m?8^kyf=F5d@bf>^`mpw|&T!i+O7CJ&qP5+Q6Cieg5 zzmNnb3NmrL5OtMG*|PBiCk^ zrH2;1a7nz}3=!dR+O{EC_K;}B#1|0Zkr9M@(UjjH0=IjS%#)6KA>1fpa?rOS{upzp z&5jq~?O(SAXObx+Ks@F4v}aGtj`_4{Ywcb!0FY`CYm8%Zsek{ctNRZRKbq7IN=R;! zCpfN0*3fqlkid(gHW`Qj&7nAeyRKy@yf6uzv7D*F@V9)Tt>n_&CCbIwtrBGzj@q&* zM%0jKm^-q5vgP#{d*fhH&Eho?L!7u(LZWkgW#H4o6MEwB69MpQABF!=Gl_2hWLF@7 z*}SM--Y%fepRVzwV2ST-=(F)WDa;6lmQ^~)!rs#9h@QJ2u6zoxEU2h4i01*L%@9o)h>WOYUM(#R zhpL-Bq^0Rt)!!_ElwF-z*cQ^q$=ukAV~T4^9Y|EQGG|r#65PxzYhC8Zm9gm-$)$X7 z+ckdAJQ-`VUP}tiO$c}?v2s=zQOT`+KCsxoVmkL3mad)z;8?RbE8@IwuB=y4-$mlb z20nY}7#M6&N!`U5_pJMUeK2>HlKJQtqabRzHw>p z>3e0~tuwYZLKA z%d98v1wTipUbi@apm;b(E=uQCV1WBwj#=$~le8qTkIW@N>EE9Kc^X^HiJQa{s4zTJ zv34C~D7Bx^f&oi3i_a;ojk>TYsCO-NMGqyxzx?TN(Iqzlo%s`O z##{lWk*VA%EXmt#8H(Q8x+?hsPWcdS9nm5InfAd)G!w3r_(O;nmyS#eG4-nn`vZ{W zN`YV_J2q|B6u#Xb)TuE~Q4p5TD9e;@qsSMr}f zf0hiTJ+9MQXRdZox62?Ezh(i=F+j`hp}<(vFkR~W*cA`Y-4gZw=rLDg``8qRKI18k zG;Cy#6?GvUkW^@^d>KXU9nnLc-0uQ3sn7g&J^7#u2bQK6*c8UzU}6x~4kY?m{Xh`r zH6B>h1d4~0_F|ECs`9cos~1M)?V;Wm!dU((t#3;hp3j)*iOVE>#>_?-EW?8uERofv zpw3UJ{pyKSFnp#xhI8@-m-#I{?_a|uVX^b$LlMEih>K%&zU`gpAw547Ec(D*L!k2E z6JX90x0uAKkoCEwG z;QY&FQ(xmj6GE2T9{lI)^uyz`b8Zwww4JBr>z}gSH<6WlZ}R48)%Lv^U$`oD)AB5# zGkZ@d*tPrtEgC*u@J31}tprN)3!=v@;3z>^w&yu^kvPSEP9=!SX<66I%gHWIGqkK* zqZUz&hp2KwJ!SdaiZzk(i~5qEMMi_E8B7aO5y)u^4pd?C7ZT!$PbeW$LNW#{t?Nov z|2y8N`gh#}0V#2Xe1z)(hkmPhl+|<+81iDkqM>$pZQ;tjh|SF8cCSyQ@_otPnH6-G zw4v&K%x>=tbW9ivoODU@W!Bc0L}Z{8I*K$YLZQzvZL!#3q=$7O;x3lCiwlQBJ)pi5 zqXMA+pgY1r^oT;YzAlqd2^)@Ju%!a$@#4oV@`8~!l1o5i9G1a;6jLLU-rq#}YM|3r zkn8`7pN@XGhaA3Qu~IV2)C{8DD>47E8>X1`G3|e zQsYCbYi&~<7qDFnms;sIjXuBMwfy&KM1ebm!;r)jl7*IkF5EOg)>*-~&K|z0`GEjQ zbSz9_N(4}y`FEXaSoIPHvUO)1*K@(FZs-%CV#3*aYvfI{iKN0W4BScl9H^9AusRoK zp4N!lX3k9_?(+6H`4mT$;oupO5t9ob5(+Pgu~nnRC9Ee7Ew@*wMIj4|*04`=eLv?26&npA~){ z_iT#fLy}LZ9dpZnX5A)`wZY6X@Qj)mjHtJBUZ(o9mT57rgg4e28(dT%=WLCLXAY~Q zr>B+7)TpkxIW(iFg@-ISq!2!Fn}kmUW2MGigKLQnzS5Q}ui{-ekl1xabHV;+-J)76 zq+M8FtP@EtXh#51;RigD4L$~7p(l^G<>!w)_FIJ;Yb`9risR+A{(LozwONl!qu0ff z?=Cgv)&lMD=fiOOSshaWj1c53Mh+J*!u^$Hw31&+G8IVCtTSdy&MHrN%XQ>@iPR$l z&FZ<1EDE0%=E(#!Z_#zi%CQX6oyodV5?gc}l4q%exWha>w?5yuW&uLTX)3Vgbmo7-5MW%Mi}PF{s@G;Rg z_a(H|QAe2~!}8HXnv&63YPU9<8lK!|uTBh;;OWWiOPNQK3L>0JZu%fZAbME@F8dmx zMQ)Dtz7Qmz36v-{pj|L+Q09H4fUd%jlP0MQRVAakEs%eL`WDNmQOBNE0pu-6BGE8J zrwJ-@)l?3Qeko@Iau1qg>syiH^jUZ@d6>5x05K!>2PJNq)ztI5t0DbK9-WwMke?*& zufW@9U2G-CXVJ+(6^BwB6i74>f8z9Lcl$pId)CQuzio1%?EUgnd!=zc+k%O@;_Ij1 zAa-vD*|Agv1O`ntbR)p~KQF0U$_`xUkl3^uf+53>7}C^b}nvYmAwDZE$a5L!HH z%a!Mo%f{{-3uc#m)74t=mwnOG(?RB5Wm#`{WX6Q6vgKc$`4)=% zV#zNHXM6jkO0&c1XDZTh7*}P`m<2r%+MG&j3mT46recH&f=nbsv=yE%f0*{gz~^61 z1XnG-8eKhHI0y(}@@HZ`4a^`?#-DgZzexyZ{;_S;UrXbvh`CcfbqV#8glMsQv<}--mNaa2H|j(Y`6!M8a!-_ ztS1H&ZVYC_s~e6+&qxaT1o1Fw0_9Rtdm?7Ne7dtqnl-8WTNm6!N>uJQaa&-L>l1`6 zgh~?WWbM?yg~ijAe5ZAKgWt(B95Ty>TiX)umWbxG4T|*`7ch35D|}PvHE0l@m$Tl_#=)vlFD$gpk!<;t?Pg7fw2jRdVM_E*YHHd8Y%Gd;f`vsfcWx&9yO?#uE>H({=V zC1I*I#Y_RhNI%=f+r#RPwbXL!7I2n7<0{DEqj~O{F9R;t zwRwaca-h1S$~sBfhXYbaZpIXtPo3_Zf~=knj}q6D$AAx)lQZLr1(uCNbaXw+nGy%A zA_hJW3NjcyNJVWgA~!bgoaKMAfZ6)q;Zh574Ha}Q^I?15*?lNMJ#8E^8)o#5r(~E+ zr(Jvcwk?o;a$kjk9jrP^Hfr%@AI|yDd=8!&&J@0 zx|ZmTldl&bY1D)mcyfiALW{A4cW>$5fI(L|f-&GMLEL}iB?jvx@zzBQCCn%Y<5NZp ztQX))_U9!SrIAJn6@<-Ox46d+F37)!MrSj1Sw+!hxLWUr`7oY%T*E1M}fMEV>J_K%9(>Ux-#GSQ8`x2+X2lF`+_}5_OFk zCKvnpxBzg)5w|$?bPq9cQp1M&>A3>@S2IC$$^Wngc3K-csi`9}BS9l^N@7kaFPHdi zxVV}4EaI}hm1)$$?g(j5k^7 z$0FIk@!0&k5!A32RYS~tm_KA$vjhK@%H}KM?lkxxL(Qn44Yq|kmAfjbINs+|%6nVX z0woI0iiY@|`J8?{TG*=tng1(T!P;DD;jSEfv|RfNL`-lPR7{~2E>Tn*mAJTc8j^3o z9*GxP2ae0ju~6cL>8+d9Pz6L_TW?2?h30XfAzTWsLcB1ob=c{B42?&F{ImTn)3BNE zZ_vlG9h3-{#B;dBC*3{W|B}yTVO?rbT6VD zaB6iEq&duv*bkQTXJuZr>uNipS|krMP|Lv;I*u(}s3TH>O`Rqu-av+}%oz5+ScyIU zH@aaJ^UG+m#voU$rdu>am0;PNdnK45INvX);H{c&j+L?z&`O{8;J-_W*gN-zk5?-> z!Kx-2t~ZLDj?j-6B%#FHT8tpHIkHz|>z|7xZ-qoj7g{y@@%de~ll3|7OLObDN5&8p zx)Cf-VS4VrCcPSw%{5OJ_k(pmP`(QPe-{OUcQuO~?CxQhGk*G$^Lm)iNeB z8ynAXd159WKl#0<(`Uc%wU}Pc@Vlk%oh%9fD>y>6EYggg2=(VOHk{v?$&mLW9fCsg-W(lT}h2|5!)GthX$h@)NHS4-EuxsqTm2ZMO+v?l? z#kJ8tgvd^aub8qSkSAkg8=%&Zo-Nk{L#3eE?LsNGwqkU)MSz}_@Ln0<#YlJY_yF>| z$Y-Hd%f7_m@$-C@>xHjZY!2Mz8uC~7I&0mhf|__CG6h7S?+=H7a(zZm9PxgpGfK%K ztKrw0B{ns3l_@{|+VG>xZ?{d5%s|7?xoI z3;G$fJB0VCSa&KN?vQWn7AWCA@#iJF8SDcW&7_aGc%;ovc+u@Em}F)$D0_$`OT8jo z-6|0iF9E?zu}rIhm9cZ2s1to&wP$>3$|kGA5GUE~U{@|IA+1|4>(T8x%|S=$XdgLi zDv3>qD#GEdb&Ee5GwH^yFw0G$pw{k~yRhx4PYL{;pOI{mq-+cX4 zC_VqWM)`34l|}k%?(l_6^vj!xm@;P(;rYTkV1q9%t-xOq4L=h^q-$LVekk+}sr&K~6oH@Z z`hAe6^u4h=PD!G1ucy<=5|6@CEpkSJacMGtn`s)X>T_0RG2gY$zOHUvM(2`~yg8An zuf@k+DV=I#(k*m9Cin=r^;KOEz+w|bV97vRAPD9oM>J`?nE;Acfeem-IGPT!h%RJ! zx~;%lVGVSWWixS70z(jTOb&e8RN}<-zi`5oTQHK1mHnNReo9wh#5RIbA66bf5q~WV z%8TKF^mKR(?gTTn8c+ZX%vKg6Wz4~W#TeMVfF`dJ2*zeI_B6#fy)f3}ANk6{(-E+_56&aVIyY>wgGtzIb;dCh{ofoXjhjl|3QXfgY*j2VN z%m})AWG@AMDl>nKX&Qk^V^%k?j+jqysV=Fv>ri|#D zEV{iSf^?k8K?n)vzFX~$7XKec$yj&}J2o|5Y>xx48p%Pgl95Fr4@(XWRKiURtM~76 zwixLcx?a9n6Po}}VsJH|YhNi#MV43g9ka(kG=Y`@`J}PlN znMgj8dSep(Q<<{&G(!U9J|4*)R3^TIFRtukWy80Ux7IkwD?g=dFz-e9Tg^U}I5lTj zyX410f?Sqe+^qqdQXW+!x3jz)(O-ks?-<DMhzdFyM#JH<{?kd%^5;ehcAbYvY)PAv3i8rdU3`(cUg5S zRu4LuBS}b^H?7o$RikVFoKE@k1P1m&ttK(7C*eXdpKYh?eIF0Tk{c~tW}Pt>uELEL zIW@f7s5G^@zVD2Qqgd?u6){~($IQ7>yKWI?)?wz41WvMLyozfB@x7tDt86eNn6&`J zD88I0joRP4F&IrnFt5X@?ID&@xE);pFGwf08i@g<%0?%)nr=n?h673`qlTS||C$nN zPJE%l7B6!dn`N<2kQ)8!xl-(0^4Sa=aCvP+J*hML5sY4djx28~8T60^B! z#mihkFD!E8#e7ANh+WAq-Bu-F0z zt}Q2QnS9FVAUVf;T4wvyKqoDlSEB>ZkJRs5E`Z8KraMxzF25JDY5qA=1ux#RH+rOF zqTg6Ye}}5&h!(u}1~sr|wwr7M6RtD@Det@!lUXJ~&x@NZd*yl|?rwIDXgOZqEt2k@ zi5!p_$3R<^SB6!xI0*phM=ySo8VFDI0SXEbyml%U(o~4*X3WO0A@1mc=+V50iqu6L z`w*rHBneKFKGqH^>18*E$Ac-e|3F2ScKkS^b8SLfv0HF?^iaOunBL+Pi}cVP z2xy<+k^`2x*<84G6KyKN#;s#9ch3cjErpa{1xm|W(3#$)Z8we^jE50??6EOT$7up* zI-k}}6otdZ%nkX0Fw4A0WG{^8v9D&H*+3hs!=u6c8Er{_s@zXU9)151RNQ@cL9V)_ z^u4rr%;OW-?rVeX&Z$n3Ll<#^zlOP~(s3bH1i8&qX4D zbRx{Y=A0mXZ?a?}X+Zna~ghNIaM0G^>ej^EbOV}cDHZ~6k~Gw)S9U5C z@c2H(<+^G>viZ`UXLrZk1`D<0*j>g~-f7|~v5VBhv7=a#oIP!_7vA> z-Y}hG&NsGuKU5jvA$ra7#YS_!;{;N9DpZ^aIx4)qaGbUbvjI1NDI5n{_ zFZU1_NuI%Ox?`kCj3h1s6C~FGl*%k9EnnUh@I!KpDksOzFF-;o8X@Jn?7e=Iyu5In z{bcbJgRmYX2~U)3ux(#Z7C{-~WiHBYUJ^M~PebR>Wz9j?`^n5(YJiZ=j34et&%k zf1gA-LmwJV{P9h2n_ISio6>%M4cK9ohX*7|hLFR~R?FWD)yHl1r&_ELLzO{p{5)!G zcSf>^-6Gs7P-DRCG@~)4Lwq^O95F2A&#HlvKXlc4O_Es)mC2Z7qf7HJMP|xllZdL+ zO5Yhzq^=N1qQxYO&Eez+=?dsZA`Y%T78_ZieHlDarkI|&!@QCLv~cI>TRaieW>C+k z>UM!Q`cM1dxQT#<=5~Z4#3J$N1g`FQgORtXZRzna>BOgpAS2|k8aX28K)^>h;Dma8 zeJwX-=yUp$24Xy`o+;zGAj3;ibKSzM$eJ4gvi-TR{fR}?0{<<%>E1^dC9`@%xkBQ_ zWP}JOY}z{(Av{4e&K=;HWf>0WDd^UBqP@SHBsT+d5^YEUe!yg@SJze;(6pD*9}hDC zx8HifcrW;l_h+A)aX_}}&MMPv7#_Rl=DMP2^z=1J`AU5>dV4g{c-$Uc{NChB%@dJm z*B>2oqO$f42|41rD7)Y)y!)cLLGcwAt)3KU^5N5GDH8cJfVxDZi&@zD5$ishx9*Fu zKREco;V%IWeq+HXGp@Y!z>hEK|K%&&j#D+bK4md5f|0yqleLy*vWO-%cvT|P#+$<%&C&Mpt>Q+KoFvcco>@c` zQWaU+qfOgok%{52qg-RA{sYUKR~X+3&>6%vbZL6Q^T4Zl2fe}Jx36D;ecq+I%u`5z zFAg;Gd+NNnKkbt90yqA`5H4n+kx#vW~wqozOIpjJC%{zxq40g}m45*r6-+U?F^S5j8%KN#neXM$J5rKEE`q(Y->o2zW zg~ip2G5dU}VqBj=46)C**NCL(WLP%(`ZH#>0cLU<7uf>(=nVyG%|zIf0@RAVkOwZ( zjTU2c=U3NEx~O1uj>1zhwUtNnhl_ZJ@kb7tCHlwVU}_R;-TdZe_ptyEVHgME;6iTH zu)zTR1Xdm-<2#nJlOL0^u|tiO<;cY(Z$vch>fK_H-Y=k{kWQ}DEU1atUf|k?5Co`e z!jg|1rkUrkfw$b-fC6Sz9lXt10`{gs7#-VGa)+t1CaT%&z0J`9d%~b3pMs10CAi3E zYrDO2`;4s!iVsT4de-Y(IJwu8J30%H%86>A5$~pShz6GuH*QqBK7C9S+x5Y3_!3h{SRPySDZy4 z-D9qv?(ty{z(&r-NHZRy{?aMYHua|^r_6OOuR0vv*x6@LqV73&XdnVY1^&nJAh!B9I*x9Doi!r~Ai5Vo(G&37{^-?r z9+pf;Z1<+lHIwCwqq)>wR_6JKW$cP;PB;+UiJglWFwyDoFe{T}sA~7b!R{(B-0+xtlzSh}!kzI-qQVKPUE`oUVZ4CN`* z%S~a`Wyap#rL?mJ9%qU}3HdQd6Aru*HGR$y6Zuvd<%b`9(z=tdF2JQriF)OyLPK(P z4c|{7Ln12@(#lTmdL+m}H4WNCY>o|vSfu4cSKUmYYi+2GOzU(~ig$Vuijna`ip{!D z$K$P4G71V{~oRxSC zgu!^arA+L83Fqq)sdt?kq;F-}+Js6{+;*W5@>i;99XmHCD$8R9n>qQwT31ogSB$7T*{*3$2$V;yMQP!e$@h2c_6JVG21eoTBivn_L$Mun>jTzEs$ zMQIARyfW0%!a*o1Q-!qL3Y0S}h?$cs{Cl|DG3fLlD-9-L9(vkG48(z1Dk{5MWd`C@ zOnL_JMuJI23t26JH&bBP&r4yx#`s#w=wJrFzRc!Ct53YV0z+mpO&G@VXdz-T@Iub} zckQQ|H;YaDWg9|RF9+*mII=AIn3Stac9r;quPSnH@Ers>LXiOY)ne1(lO9QzV`-%I?<)cpR#v8++ zru*fLjwAQT%QwDGdBo7c7PyCZ0LGq4G-bG$wuX`Cc_@4&7z`<$Z&`9ASe$* zZ!ft3`QI6xA7GRFBHzJqy;!GcgXSGg-bc z?5XF_ijwuDDM5baMI9M#{~1rCz}^PKExKUEgHgwpW|D7C1$!#1X{^qU-uGNCwNeC_!6 zcN42U?VWv7AG6i(R-HVSOsrd>z{!U~MXYN&VfdbaTB_tMh3tpSl1o@cwg7hdsJ&W> zbO^pYZNIFxq}z;QUJ#bBwg^rB z0KWVJg9s2Q=gDgum{d|7T{;@S(}*I|vM4FeQlWeNhKprX2a78_d1r!RruR zqX&$d%?h&<`j!%`6h9&Itr|xPnyzhcfG#%EJr3xSWIRL0R)*Er|EzwxpR*uxyn4OD zfAq&!&{@AH@tbRsZ$Fj%?IaO|;$kgSXGbro<0t_frTT;H>@QdOY9b8-1(f8n+Sfgo zfLNnb6(Cx6>~xlNQbd4=emGivX?Vyp2d@4EJ-{EF!yWQ0bLgBc;D#YmfxIfnbRg6-#6p3B`|6n;x@mrcICU{Kx$?)a+&$I+btIXD3)esw4)5ttC1=}_ zXVD^J3w4@w*d!kw&mcY-!gMjxf81&|yf|=wFb;d+EcMAqSrw(sinLiyMQ@Dlf4L6%l70_crIE^#SL=poUSA0y-p=MS3zt(LFq%@;P#9?*e$;b6fI% zihZpqR~^MCzqTLs^1U*9ALX|{8W&c@j}1R`&>ltqqX1Wbls&~{HOcj zHD&zJYRc2Mx$k45{%P3(>#<*aZ<&kG#ILBQX2Bt67$OkSMRoFvinJTQpV52;0RjU{ zZyrjh(QhH_Y%Pe3H)oq+FaTd<@CKGzZk?>6tM)51TcWRZ=0cHk9(Im~xO8uB{Y;c% zL=JT04CdQJmDjujk(zMzkGh7cDtQ|u`0WzO9=s^Qay7hvgzj!XB1Vxcfg4}uRC&yM zd0OjA@Z%u7#SM>Su(OPH=!#dnTm96mrXB0MCl3;3cUZBu$c6s;IE@)b@WuWZB$2j) z4}!40#dYoxUSKDR8#y@p5?kb%3ER1xaK-xg=+3&*9-_W~$gj_ltB;-7WF@3Hd8o;g_zJc)qsS#@IsNq6U%iJE((B+`=(_?kJ>Y^4mF8wbZes zi#^iRWTeXs`v%60)~gAYeN;8?{(2@@KQb^J-Mj)3v*(To ziQ+mwHPX|u1gFki#B!0gx*{v`q>6ab2j8?QDnp=sS>T+3%$iI@WMEYeoN;B1K1RSB zM7rzvax`FT7t*O434PZt$9*hds(A{1=Z0aa=+ibjS9OvWoYakV?S1rRunEjz6CxTvDIk?mzExP0^i?2OP2~&-FM7il zO%k;e(p{38$oWqh7%Q!`xCo3xgnwDay&>%SF+M_~ClamxoL_qWc9lTyrIATyYw@iR zD3bKm@fW)860R6YuE;R`E4?DE{sSh_65u|cQYI|%i8jU$0f);X9fUD*7=9fgiLrS) zF$pGP3ANckM=Fm{sDNZqyGn*hfrI-#2)mOZOHRj~{Gq(V^ITNeDmr?Ulso*6n>4QD zXGoqh;Vhlg_4Pl`ifF#z9Gy*k=}^}IEB>K_xHDeDp@XYlSI3o-!}jAg3EaJKrXG0s z4jvaw8UuvN_khiLv=1#v_i@E zS2hjb zWiq?sj8ga_Y(P@~q9vF?urg=!EQ(%DeT=6DD-%;YxSit@_;dXvNW+(e8Exci85RdD2JI zjg?PxucY?+|MlkgBk4`c-nbOgvfVUx>lb|Rv&^?bTKJ3aU#cCh`es|a@>tv!7+hO& zamcwxOZ4RJ$_{F%>5-DjkbAApqT5xi93&O^GGngIRp`@IcbR9+Qz{ra#pV-NE{lmp z8fSmdBXdE^f)1AJL2?qII!vVk-!1^T3|a!|+~R3Yot#7kaE_^{fGdWUpgbJXI;8H0 z+rUJaG?nE}BSh!pYB}p@1ceL{09=-B8x@(^CifYyK|)_sYJ~7YqnjpKn;g&X1C9Mt zOPV7C88yU-qjnHy`LvxV^WgjgW(7|bWAq?O zfH4h*8IkRS>CR@sFz3pI4>#f0%DfMw;`1Ipbd;K3Q~2K9Vn^?}r>**t*~~J!df<0! z^}4TfP<+2@X-Yc`vFg3!wpW4a9ww`jDkVqG0pD@*p&5g6fQyM}YmRu*&LJY@l_r;1 zo=He&O&+Po1^9TMvj#8Reud5C`Y(8{n{vgHXYs@IE+WREM0qy!U})|U#u9Hwx{RJ= zuGr3LLCrri!=C6+W{hSMU->FSKu_ke6G@7)-WHO10XPC1msO={lc>=L_7@*Sb}zoR zqG3`iYj^;RiW0jHqGb2;;o+tOIuGdqg~Mmw%raEKGAj!s2sk`Jt@c4$lF|d!96~pS z%hl`C77&h}z1kLKGn1$VGB1x@rGZ@rB+GRSISHEC-VqIYz8gN%!t6E_f7}>1gOh7f zy@Jw^6zYGJ6s1y`vY=hi`T8W%FzCT?-Qw3G+`gcv97%*Yq*Zd{GJ}X(&?h#*ADPhU zmMH6YfWMxuJ`o=+M{)1&Y|KLX$}Dw#wK%M`?u{mXsQCZ>v9|b!N5fBAy|=Q;SXt%F zjZP}76EuO(a@29rS8SHVrUJF3e>Ukd(gj?rJjSpi+o=ywZX8!4He#4BA0ujuq-EFR zM&`Lh4GtGc!FfsQh2jgX#F=}<&T=(~KrB3Y@cXrm&!u*Rv}O9eZ_mD2S0csO#9DPy z(x&4_r<;Zdo7O*|5R4hD%a|*KRFeL(1ea*CP=Anvi99c&Yms_$aYaO=)$`6<6Y1^_ z7ygiohn7$H(U1;9&~nnB15A;>h&`Y;;3YacBx~5Qg}u>{Kh4%!61!A6vWPr;i{Yo^ z!-ZzKX(nitBnJnqYs(P?X<jofCWmgY?M|1?I1NFKyPQh8>iu{uY!yA8Ls5( z_x$?Oz%0%D5B8ne{M~Ox!m-C^AN=k7r~c2bozutHeK`>I6(9dJwY2uhhk6s#7pn(4 zPs>b~U8)?;SSu=k6cPlYCc;OVBa5~jlUIh>zz-Z1-V`D(Hxw==@>OdQzZjQL^L;u8 zk&N3Y%hTDw?iDlPr51%fny_7N3!nUsIRE5(B3rR`TxZ*OmsS8cYo|#u6e= zg_2pem_-D#N5-_^2f1lu)j{goHdwO0x9Vds{FU$Ror(O>D@PL8rq>h~X8-tv_SrdA zsn?M;Wb?%&fY?Cix~go?B}=D-{8ff9MzhIqfiX1>RoZy^7f*P2N|Jp2*0`&3JW3`)!kk4u`!u$C8(|_DP$_3SWr9&Ed$5l&66)b_8Oaa~7>l+<^gN6@9y^vl*6R5H!Cm0I+BS2FFZ)Wtw!B86M5WnP>(F1wUa#9-n zgp$T^6Y3*VNKXJcS>)*dhO3ehe)!$?`8Nj^YbWIvXkgO`%RTuf3X0 zuh7YTPfJIzywv=tAlI@V{1jNQIk>NbvU1GFfK?_k_zOIa6XfdTfjL0zW2YWKXYI31 z4bGpjL7GNpV|{om#}ZpilwIwd0x)ks)qY87dDGEK2z z>c3bIKLse}rvPd3VV*{z0!@>2XQKpS=0pVdLV8cXfm~p)aOHszv8OzV9rqBZ+{-Wg z8%)`*h649pCT+zpE@>3p|3GlQ=lsnxf02v)hO87J8JZabGt2D|?UQK$Se3~#yN5Xl z(<@j)^HI!6K>XW6L&u88)HW0%^yL^lBW?4r*Vvt*dI$G@&>Fq6k2s*A5HBB<3e(Ck ztC=ZGXT1Zs_r|$l-DKZEJ31$6znpjbe7oyB>8stMxj>9dS6z<@r6#Q^qaF7*uypDMf@w-~zZ{jz* zHywtw=qb?grYK%zZl{qZB$Y=;G_{y+-r;uzW;69u?|4myjv@0H8&}N18d4Kyw~>vm zZ3IY`3hzD~A}uQZyhFxKt0t_%Wv~Qf<)AfeBv60puC>K?v7}j%CIhMKE7y^dsQg+) z8jHqA7N@j_-Ba!(DIEo2Db_~h?`xy2U`M-|?m9;1VpnRC%Oh*N?+0^}u8?;~BTReZ zP0)da7F{&2PjWcG1u}Zf?Q>LQojef=9flO3%(Ytjm8|ZqY@^8F5t)>X4aBp>4TaQK3rD-8^;WxWr`n^$9WS5mva@IMrF|L~yeDeF%HANTxZ>)^~qeY*PB{TY@& znQIG%J{QYp!XaVC>rF2@{u~&p{B~Pn@qzm)%5?JUUkB?mzOj0*AG&ZPIjkl&VV}Sz zOzU0&tDtoT*NEDnh_u%;s$B;}o?kk+f|7R}Ay2&zy215H(NgD3%z#b7tkLVE$jcag z3-}pM)mx6yUu}lLST3>Xe!a&O{Sz!Uz|lM^jj8e%%yg4nrT7^^**ItYV#LTJWyV*nHD(ys8+JT!JfB%J zi*KUr3CCqlAbxy9B^pz>wD6jQU-5#`;tsXn>4 zX+);_jD*-1!_cH>YEm%nl#jT0XN1X8CY2_CDL=Bsq8+GaD}u4JZw{tY(LQb4-BWe% z*|yc|zNt*}McMDFOVsk}nMH>$r76avVf7x`?G5$kJ(}8=?V?<-Bt)0~ZrafKL3MnT zy@3{MIk-gmm(-J)mOx3cyjQ1Q5FIduwT02GB;QhQGbymundLSzOYHn>WM~L2SHX?q z>mi-MCrTiuBbn^_2QVoEej(?wXOXWiw8840;2#6JF%zlJQ!O>L4tFOQCY7khQNs)9 zop=eSQZD+c5=lv+@d9(C9XS6itD{1537k9hap=?fifh~htp?Xo_QFbzhv~Z~{0niP z!^1e<(L(k|eAZVEQpnF0D%da+f~3fCTH+w_YzQVtooGOM57EiCF zZ!-nYuwVtqIV6AF)~KEbU&F(Z#f@NQ^Sf;?=T6aJh&3Vj~Hv9KYmN(Sm@WcPG*#7ZB$HMU&Cs&4sY^_N> zO7rmAXS)pbFdRobX%?3!4T>PHH#&I#1QO zf9d%xZ+t^b{{XxZPo6o&KA~?0x*m^vW`nWHa1tU(kKP#{Tgome1^|iPHr(jgIe0nq zQ@WyB76{h~4&dfd*g=`9cxXu2gSxXrz(Kw832KMigT=bVP``d)F%0DoVEzCdU$<4( z$A0|kjRA`qLFSflm|70%jtv9x-bP5zfSTwWNmsaFH2$}dH5Yq6+rKrxFYeKK@GULt zhz!%_4Hc`;AV2Aeq0fh$YU~Azo|xx~ZhA>lX+MfIY2G%ZeS@Lsp>|N2cmmhXt$pe6 zsbBVmr7aSPSeL{gyZ*-w9uM`s^0PCtriObo8y(MS7eAYlcUHB0c;=~iofrse9A^`yqmP{YM)xnl_3X*0 zY5BSLySvLQpC#;mrr?+)eG)-1`WALF-*~?F1&hZZLwvhg8!%;cgzDa92Cf1AMivzN zYN9GvaK3kkMI$3dt0>nB`X;wR%ER-WrPnp49jc7mizUbt-L4y|(oc(W=aA(wkPNtN zfikYpuoL_BiCs=VE+ombSf<xCS4lwSJIFL6C)rYnrXw9LWHLl|u_PejGyVjPJYG zE?<=cTvVnCd=b&*Mau-*Jrd-Y?WZ}f=Pd+z#M&;Fz^Fj-CAEafL~;tL(@2iauZ8s& z+~x6B3uB8^Htj618MRxW3EJR@R2rs74=KZ!*5B1V>g{ks=Qy`YAcOY_;hd^7ez4RTbj?4dLJbBamAo8L zk;oPl@~}$5P>Xn+n>FaaL0Koy!s;RiJ{oum*!+5bf-X?xz}>+GV1!}A8_xdi45P9cEdD}INO!EKld}(V(C!{l zw3M)=v#?7)9d^#}I8V@j2K0#J6vKXA7AwgFV_q2GpT#dUCD~emqK!la%w^3o?scCg z`q`^XzG{-Galqf7ooDmbGbDCI$C@k(&x|eb2pgKcibPVBR~-~lWv1a%C5;xjXU02R zK;|~U+oQ~`WE^s;G;l3jkvknf`sa!!m&7*yIsM~3`aSoYUuq7NZ8rJYe&{@$k_;^jIIuQ6PkU;rIy&g5r;*X<}zOSf%{(ciH+Mq|C5eMtnh=sx=jM^z_cK5 zfDN&c&YlWm3({dBwJ?`VY#xH2wLKR+FG5Eg0|#hsgX1|Fcv{F?f<&e`9d|XN48fjz z+)BjDv{&xM9|R8+DOm|m9tR1JWq(_H)?&JqH3_C2W!j{2KgNHp%<34=B(goG4e-~A zn@I&*bqy0_+nbQIS@8_kNGrr}ogsfdyC#vpLc}JU{s59;+9?OF@sY6pASg?i*uYP5 z-0yW-mlNmgj58AU3+BdU*bjJ%jePO6+EOs`t1$1o=vxasXX;tsAtTA7A&wh+Yc_z9 zwgY?Q<)dC4uR}~gud_+rDVF5eorl+ET`^9IJ&v$+e9jN_;rD3GN*NjP0>y)N&fUirZj6{**6hg zt<6~Z?X%+HXAG9vV)Pq1>y^qfpnvUee|YR6-`C>!1A$no}VBd#-)3`fM5hx#DO zaZPV95o6 zr7_%5BHf>tmH7mi61?$>+~z<{3;SYBa;D=g@#8H4`Az}s<{5(7)C(K*U}Z{zdL^g~$d*+((?p{Z~t*^O!N#CDR|_(31> zUcU9nC2-g(AFK|6*!yUf?XFkup6mBV7ZEN)$sAsDu95MY^WH{Gv=0b2Dr5+Lz%UNT zZgT=)kG~7K;;H$!js>Y%uZC|F_YoJcOEC%2xU|JCEu-Rc&|OL`*49H{TX!F`ndFnj zD1cn15$AFgsy~R#_b=|Z8OQ{b_@3lLz_tdTk9;II5^aj2(pJfxezzi?QxK%H^=&1^ zCqN9C2C@nsqe&wPOTJhQkZWFp&W!N!;JJbJg#gTgNs!>mP@;t9z!Yp?2%lA~Z@r;t z1N#{i7Yv&SEA!l2Mt+hy7EC3O2NH*~pds2W7Se{V4o+evFU)CiwqSf*W-H{PL?>kG zs6%l}kj=gf^zo8K(!YebIn*=!=d89&;h0&uwhfbpVx_XcEWnI?(ueCvoNx*8<;FDx zfI1_VPm6E!%Wax~lF=}LfOC0j`Ou4(NtxWikRe&Tn$k^!jA-b-v09u^Bb$CnL-PLU zi_8B&g(W1oCDv;;gQt&%D9 zS$!925hUpXFs-@Jf$zB4d%fwjNQx9^+(xNzKnp^+QEql9y*C`?}tG+ zPgfX|@iSRomq%XMn{mc6g%O-V)GQ<_?)D*2{fHa@sRtHQGdN4cnH;)S?4|#b{qo5` zaEiF_130i^)>38u|1IqMqn7mri3_Fw_9eURNf+; zFqM>a!jcJNjBWby-mI%aR})fX>xW2&fPye!Y_lv$`Eg8y0sC=G7z@UBWP=^YetnjlGNt(%XDAkZGB4PYBtWro;KN-VXsJP(MFK9evx^lksCrp zMbx~|P6NVI%B*4+-EkEG((AIkE{6$Or0vyni}`^kf4*nfU7?BDV`I;EF;bmpMib_D zot8a?>Ok|U^g^v7!^cK~Br67F7UIOV5InOjV9)XN_~5(K+`NxOdQW757j=XK&Q+i9 zTVq1ZWaM|Fb?8!LbV!cKt!#a&X@;i&=L%R0hw8U9Vkkr`9uCv_s>O<`eH-Q(!!WhK zTN+k%gz1>FSVBmsznRK}`I;zPE(wRia-#3m5{zPCyf?`XBoQpnApTBA<_lOKu|yzC z7_6}H*W@f>x}e`C)Cz1Ya8vT9GrIQ6H%3 zinqrTz7Db@UTPZ_+E+4u;ONCs3ly3?OVcW6fvfqHG`N(zUNKvABRhP5r|%|gglb)(#6qaPfNuvsgtJm zC13)Gyw_iI=|Ks$O2i90r6Uoyf?9XD(7_*Eb^4+fX?cvbcx-vgvsi0wf7AUP<8v*m~mC$}^A+A?jlY$UV> zmJX)aGty;~wnPIg^0~=ikbZ_57X@Zas4a=~`zUv%{VT*+M6k6ww8W_bUVhRTtj#d@ zVl%N0Vy^E_V5Ne=Ks6jEIL>Em%g=afl_+fci|Rm>N0*7fD@s$oS2k;SVS;TSxjgse z>lg1xj^1rpObvU#KkZ`{NW%oomhI=2&vbjnhhx@ud~BpEcm)>I_pZX@*a;+^ke?#d z-gjgfg3$TZFDBEM6b`>5#dp=gs=%vv@dly3F@cTnK@vP2$mQsg4%TTw3yw}6{;?^( z$Gcigq0P--w{X@H-+!y$<T=tJw$j-I zb<~>vO}&lP*}KLuH6LFsP9*E?1Qt$Zcc{qjdDW6lhtjJ)9|Io-T|slTYyrBD5vXWM zxwOvUG)AN>(UYPp?2ZHe3-OHbpy-N)O^4t~$|?N_Z_JvdNz=+QZY}7w(V_gJ{{wPa zk7Vws|F_8|`{PHI(rV-2_y`4#*bUDa*--eXe&Xl-S^jlh z_6sMZ^HmcW)SIo5jZ+hyaADk1*tL6}^u*m0Pqpy&3b&jFzd0@M&>?Q>RNXi9;V}61 zg;hZ2Da2msawwx0Hz=>)qZsT%Z`Vf%2zIa+TMgDx+Yqy|jTY^6DdunW*Lku_Ys>Iqhuf5D#?CubDzCd$B7I9pl&4M-u24j>A)~ zQXm61NQzxs)BA@*omZQ>S!A=4`lfnp4)N50OYZ z5@pE`X)T1+34`~hbJblfuo@&5?|Q$qDB)@<=%Ags{+gaD_=a5gSXCUzkchag@HF8o zDv9DqpHnF$Ojlz4&jbyClh>9H6;u4-6W6}-EWxD$o~fki{g3FrmW5tY+77Y(HC!G( z2|hCd3x*yg3qZ?DFxwQtY!ivDcWP3?rLK2>?Re^8DniKUPW)qBPkqR3pS{hIP#t7A z?NQZxU21qMaTN2Hc;USCc2E}&a>|z06^Sr6Xowg~NB65@c-GGbtGBEP>mzDTdplEn zPZP7WWbOrdCyW`?2`$Cn5>{GEMyDL&YSzS!&1?r13`0d^)$t~A69P~DBA{yiM+$kKy8TM7cCz@br&BXOH4#Y!BJBFRP}a&#GQA}a zh&zVERXsM;!&poTXM*u^Qd>rpyJcezUYOtMgVi(#W$tZLcczF~O^c|}?%W~O8^r!2 zgxmrt(~0%x>WH_Ge#Fan=Nb0p_jg zZ*@bN@cW{`1g}BYwzK;~p=3wg9OrZFi6<1ze)_#EzG9}Sp4C#b1vC8(ZaBODTHoI- z5lrK(k+)uL1c4fPU`1lZ{ru;x!W8srzvkMnvbOCcakRda*)YvV_-d#3+pLRFL7sb{ zs&Mv?;R>|R%j4Zd8_DkAXb}9Y?$%~VZ{kG(81Zggw?duq6=76nty9zej`QqkWwH8t z^>JDwRT3CUgoLZ*)!A9Zxm^@C<4M>BJNb!*twCM~?A?vT571NJIPSv{Plu#}^pzwJ zp=$OO#Hxe=9Z!|m?juBNVrCk4c)w5s0XPbt1G4@VhE*s0-3zcoK9S(5biY0g`YPCE z=5&Z6POAg2V3Wr~_;d*3nO) zdTcLB4$S!1W%Pf2{a+N_nm3&Mj;RLPzSUGc6~_y1upC|fs3I7A85}j+Hk4H7Ih*2q zk9h6na$BwGe&pMD^t#Y1cyd)3`Zg>U1%+XS^T}NXx%Q|_-#qYuQ~$)lFThf3k@@_X zu`E>0^dUJRB=T-(Sm$D@G3Px(iRfJ+(R}fzL;<6AbVg=|e?Y7mnP(uVc@O&flSfxx z@vCMSJ;ZF2L-$unns%yC(?X^@n;>Hb8w9Kq2YHWW|)oMO6ryB^Y?WL+${fS&tl(vMUAk zCS_yU>~SOY8gNK!vL5*oDWC;m?o-&B*Np{%Lq{w65IsUZqEsh^Y+zj6Z&U2JK1ypQ zwp7mz1uFRCeOue_K&k%3MP+G@=BT2qwbb{|#Yz3+v`dWCl3RAls%JzCHyTCMhnT7C zl6pSAr^lh7&(1pUfEisiz#XE(6iwBFiE(#6#~$3g=)5Ap&_iMC7fh6!B=gyY-e|BA zB?Z30C4&Y|#3A;39LFGQR+t*eU@Xv3c#=@3iTeiZYi%ok**IvdrQ?aiU|e;m3^TYFMJj(*o+mJ(W87cMV_^0DwBf4#uw zHM0*v!@O6q*3_&_yWet5XW5U+KdH6wVC^o1u^3+FJKqjbSRq)lG^&YV$TrW|XVBH2 zDpM1@@pAXGAou%PBo8-$?NAL9g8y|}{jV>sOEMSqcmd&%h$7>6gfkegAUq6oOX*K4 z{KV5r4IXqGXiAu*g@Y4Tc7S~$32};RcVW6y5hEP{Q|2|dur~`lAHqdrLhXdD7V=bd zL*5J#QZjV2${7iP2gU{*K17sYGN6jBb*PG21rD#gMV`_Gab< z>}X?z><2R>AaBUPG!)i4nv3(ui9-GuE(2MZSU8djt>*+e8n1xY03?17IPC}=N!)i|(ql7q3b(rqPKm$Ttk=RVqef|)8%s(7qqJ_N; zG3Fy~;X^OOm6|AOE;okxp`M&p9W15T14V@DbU1f>hiPS-e%TdGHsrd$*5h&*@x$}v z8J~^(-`i@m)DEya^puhdjn4IZEq>_DPaRosCtnx1?1$cKFxr+Gm$^#iQU+-UobuVF%p+JR8&itz>fmJx39#G;T`|s6{jgY}or-_^DQiy4lL<*5%IlWC>fFSERMA$rMZ+!5ng!iE#kA%r z7Futwt}Y>xg2+%YV;#emnP5YQ3aH$wHedkwvg?oG7zRG>kB7vjBO+3YknD z6XE_Js~Rfe8lF2vZrudRXMNuKGS+IDl5GtxoGr_By^Js@O8)Gb_Ca zLX~}B25+|!eE+S8A@2Dbr4QXd#9i5WnY$O%;hz_(?Oxa3{7cj2$hy0DPE0?x z7IyE6Rs8wx%e@}y8RR)SrZ7JIy2s~c3@rWetlz+F^!VwSlFLS_W&ekYF%%+gN`>Ab z)ASFD2WDg~usPtzAjq*dpOazZA`Qr9Es~?2NGLnV>J~jdP@RI{&0mK-ihYwF#d34g zIbX`eGSoJG*kNw+-S!PLhT`4m$!`~&o()otHzb^09c{c@ssHUo_ z@@&;`I{gb@ZZr|25d48npNVCx7TDVd)I4_wTv_e5m}sp!eih~^FhkT9=K;3pS~)>l z)iI&2JO#WFcJLrVHHJuwLS~L0M96s#x?i8PJNCxXEC;TF#PdHcCc6gfBMiow6#HPG zS2+7h9hTG%~b`zrNjU$Z{w8GkRpHqQRh z*jQLh*Sk}hmjDmJ#@@6S^WvbEO`C>N!f}v&Gs@7xw=5NA|7Je8=If(yW=O<6b~G<9SLgjhd&B^^>_5 zwggCz!Y3063&&V8ab3H<5o45a9uTpVCvN_IJhm8 zKtvxIMo!xG8wUqv;l!{Va1{~09Ue|ZmqXZVXs?51&De;kcsXkRPW`BknG27&s38^= za2lPX&Yz8%_OyWUrgpc5y+%uT7+M{ZV*~=U>ghl}kMYf@(%uzX%Q~eF@-f&>S6Y@< z!x}n5uBQ$u6!3h(tZ~2cPAbmOJ)a4chPE1?vZe|K2Hu69h+DZ4Wa9WNVr!-k96sVX z-@kMtr6lC{#c6o+&@V2!_@UYF*o+S-?Qpitl~IGW3klc-PwiO@>`hkXZ!hu4$kzj` z$p}jpa%kA+ahPERa`@IGs2edH3Y%0x#k{EMxLyq4>UprU7gcFPa(Fj6E%1VBdL3gd z*Z`m>K&j$CDXEw=t?m^AEBiAl6CA4CPkgGJ-DEh;G(e2lTzE)-F5Lq5CM0)m3uap% z6lMT!AtDLEkj_Msp>V`zx%vTa$7o>&#>|Na?%r;9S`%KzyRO#r)==R0lkst7Hk%a{ z_DVKCm4~ceQuWti|CIq`A~En485;HSUIn3kxq5lU9?bk>V(Je1Oc$ki{dvJ@*Y?H28R)6Dt%ouC9b7p<^b#aMRVl`6XMTEjK(N&jQ*xv$E4clyeKz% zBzBxu&>s{`?`{<*gm&@8ky;_QWd8rv*H1|g-->;*bzlJa*^xT`;`lRL^uccF2b@s0 zSSh&NE8?-lJqrO+)2u>J7t7iV^u(f5AzuODfXx&V&euBu*&Xd4L_}lvGenExV|y<@ z5*r#cUZ|4g37ifC*~yB_b`e2d!pb;>6BRaPo2zYH-r#76;=Q9HBdJ*q2deGc!zoZ{hg(|oI zJsI^vE5bjCQ{?SAmG?||P6b=S_X5%jR_u5;Yo8#hOIovK>~X6?&`mkh6d?nJps~N)68l@oGi{Za@tFR z%H{j$q>x#gMD?}T#a>Sw@)1N}-&}ERSicDyu06bIb*dCj=*zC>Dxv_XU!Tk~kBk5L z)$_b)g>$!U*{8(g+H*Hy4bQ&0*sa$4VCGpP^nC|=#H<#RoNui)EQ1ktLb4B1rLd)E zjP;;ap`Lv@SfXI!`IJIjBm94rv|TWDZ7>i?=%_%|rz0^~8N5 zZHC<V0AC7mWqThe20)Hi>L^5O)Kx><(~_@m)jB5+)i>#m>!>#zEU*`Gf} zyC3w#_ZX?oneyUmvFE$0F`^1;$cU-~+~r)OLFyejtJbqS;)#)Dp$uLKS8b0fV2g8K z6_jQJwHIjx-IH^Dj!kGSD5Z}jWd*buTn*rX&zl6KNh_*2bNAQS-3b|9+-vn}G91Ro}ht-^ju zaF--g#ujXlX#+7#6B4~pL=kIN6gP!F51c!evLGymcSlH`z^uYnN^~`#&}B$^qEaDF#2wp~lr(~U4K{mG6;onz_bg6ZgJE5f;JWqNHe<5I)>@-K8r zXz=zpi#^%sh>Q_Op`O;4DtnCaS;TKTgZPw;vTxl`duP&RHNe-M!;d+OjLfoYbkFYoj@z z7~|4nHqnR1tOeJe6>bJttuS)xcc{wsvp&De=ge;7j0ihze30_G_ZRE6V&aPrzJ%R` zy<`unyXNe_xeOiHPCyVI(wbVv-MpfXLf%c_U$?=r@X*4zf`TLtiQS2`;!p8}K%e-jMqx18H?ym%rEdodrIjflxGh^gqwnN+$_ zMv^_gNRs-RyH??IzZMm8O8dT=P+{^=l;Q4HpAE7bmWJvTSPXf-o=|DHIz`n%oXqP> z-LFUSoDLQ7IY-(?c&oIOv1zkFHphr6AR{yoW2_n-LMNl!l4;J18Q(eX{~SeaZe2Z$ zT|0wj~Cw) zoPnv3bvv0jlnDl{gyoB@Ah(?U_Fk_58yB~uCQo6~7IyB5R#YK}7WV>HwG^Pn2tLC% zU$+^XZci1F4(SV13B3_+%bF^sUJNlHA$>;kw{>dENhff%NhS^F5Pf6YD*;&3lI=FY z;)9$ZP{sJB9LiB*0M0orY%jhcOi7!Fs5Ml1GB$urk_^w?F1$wHe65C;*Xybf-GaO( zkzm-{gvZo*kO!=#)#McXU?A4UB6C3KtJhdjw~R9u!vs!|0iMG4>%%^#TLzq_b8G>8 zL|{hi<3MFIl~clEu*j{b&2@nJX6k(I&&Va-`m^_0c%`)MuM^Sfg#GP_yTla+1A!yQ zCk|5QGS*SY74}ElIctLx;NC8*AA^6mPUGW}BGYSvO`jXtmUN`Yk$zdfC8iXbCQtSy z`dDB>%4GA4`Xfr9sXdxCeSqk8z0D_Lr9tqD&|Iq$^N3V0U&$NHHUxUUfj%R@KA;Qa zPdBmV&`X)2j4vR|U}f%I{Rv@S@2%XPTnvt|+>Jqo<_>fObW^eWiA_sm#?L6>tNhc+7WCa(UV5B$aALJ+c9n9PHWLU(>k_N{SvwpQr_!JKWS zWTLFkxh=*F39^=0lWIX@g}crs{TA-pAph6JBz2oWTlO5yT){a%cP6aA>8ug9mBYb> zCwahG7(pfmaU*In)43^KYuX9_Qh;7H+xV9uJBpM0lP*SykxNV#`i6lH*J^CQMfp?5 zA^S^6KD8$w{)7q7&kqHuKeo%)Qg?!&n+qB})rEt`DM=t$XKZ|LyuT){Th;m*%OR{Ko+;e??IHZOS9`+isDZP%gC#XDPV)(?D^ZQ#hz#cxhI08CTLJSL2&@_)f zc4zE$5OB69tPY0mKE?@+B-~`8ettK-{meVdopS2z?m*I9@z?_hgjjZ^gtLCCr){+8 zlgf2&kSCtuJD-`JD_Z%^c~#tta-J?b^i06!s4_nrC!|u;dn_lc(1aXCP;IAFW#w5n zTlE?146gO0w{B!4j7S!}0W`SZsA9f7UAg~|Li03#$QC9&CdBZU$B@>SZrU8Mxf=Vk z$SPol&e`x)P>R#wOFM-?_wX5^E%J+rGCkTi}Iy}bR8$9WP{rHIH?4?l*tcUj!vhSQ?C!OPDgl`cv4)gVs$nFqs%FFQALYUIsgWG%4Wd5+2W- z6jA7HC%M-kzyQ{iZ)%wj(Z`( zbkc0_6eQO7jgAaJsGFJE(q`nhFoDD!Lkq0#nf_yvx(V+&hiVKpX zbtf&;!Cle!mWGXMImkA;sB=a{)4&h6Vcwy_|Arg&g9Kz@F5y&uG|FEvwz84(VyLPwT3eVo}&5qqW^1klue% zO&sR-!k`YOY$>=2-#V;@G4kkq#=>HGy>Xbbh~T0VzQUzV>HG-^tP+~@o_et@9n_!GP+6V}Zes`GLoOeo-7;V*mBc?Sm0-+kd_5o4Y}(5p^!_(W8A>SsurcM#DRKa}v&L_=ovk2RawbI=^ zV`3Z$X&s5Pq7~b0&GmP|UIM_vxt;RnF!EVh3CDx`TM(E?d z%M#6DyN!zG8CV*44$_9nZ9wu8*m@Kfh`f6@Rrgl>&2gEC46fxvUrPhqOY!&pDApn+ z3-2kW*-%ddFjC%)bA8qaNFFKmxlTk&0Ph`DmOJ7~nKuZda>Pq9aZ%rR#N?RuG z_QQ%sxN!%%Gq6|DMIb2KHwbfih%u$?;)ieAFgBhy8t2Sqofdw)0-T^en6s2eyoF^9 zCSD2Y62RVn(H>hU-q)cRw1msRv;e3GD-7 z*6VyZVT}bGhep-CCWY-a+(yD>d;dH6?9@v^Pd_FPR)P$MvxsO*fefeDcS$RaoD=HzNQE<#DS1ByZr5M$YxLWx z^gFwd=ce2yd9T=7&?x3-`NhgXEO$_7`|F_%2G#=S)<@DAPK#1{(q9GxP$WBd2-{_j zO8cR_ZulpW!Qpq_=*F}`MVqJnT_Oo9i4(Ws!gNO)EEmY)^FwH+JYlV>GO5;c<-Xd67)FzfXk-F*u+RFo$ztW=P?- zDkR=bm*|Dw#OXWeKbOr0@`C2=&ZOXHpRVJ)J#JLC*G#RH_t*9;JCn9-dn_Y= zd-&#-!p`&j-nZ)_ehe@bXxEzL5!uu8i5?AGq0HCYbXO!<9lr~;mvS#gPRRQEYW74f zP{{4Zyw_ZCMe8gTg2VS)xvazn-X)ydq!wSk4+n`Gm#`m%rr_>32xJHUHP!MHkQ}mnTDcSwF%dD#z3&Gs;rM5Et9NaE_ zMvE`y7MbgGRx9lJ^z$eDjSi$#HR?%VABZoV^2Y~Qr_QGP6>c&|CA*8&VwqXZH4bX) zqTugj>eh@uK9Cf9T^bLr-DZ#pId`N9_5qRMJH zKMGI&oit%Ol-VREQD}~c^n(c$ETyllyyhROYkI%yS-C-Xtp!y)?jG-IcEdcNGQ_0y zM z-FAQ%?w2}?!ltg5IEuw?1ByvP>{bt?>Z09sVk!zIad6EJHMmZq|E`W&YgwZDe5$ct zO8h4-m(aBX)ecolhc2&;-?uwy39^>BgVp075-g6p(B~#4`XC{rH}odg`_cCDFqDq` z`MTlvpX-aUCXFw5_1b>?%qtsNIwYpMf!yFVdn2oQ*D>7yVC%mFWdfdTG@^}4p5xMxa>bl&0PRPqU z&5WJl7Z-InkfG=NMC*-|PSrJoo3NY46qS??L~3+nEiaE^N--P*5(ZL5QxAEBC)IhY zkSh+(Y$c0fAoAp6W5yAwhZ`zIM4MbP?3^ef`Yw?UZiw}4x}Z_-$JX(1p{0^NcNpyv zZV#C#TwGu%#j_PLgzQ3)usx(b($seVPr(>*8Qm$o(KP#J0LdM}1fp~ZTO-q%6=ngLs*5;-FWEQT}e4a6tU0_H#ZF;@$xQyfxnC$|83P?i&Rsc7jhk|mKN zb5d%!siz3E%*pKGq3rF(q=wkLoC$q+ypAv~w+(wTQYu5Ia3it%$6rPna^S2D06n^< zQ16+jID8BHi11)>P=ZI@*U-=t8fJwXWlQebme$aI@@U1Ng=ti0F`@8iU@P%U3LH1r zB*nDPP6O?d`p|eT9AQ)9EcFo^tT`SHYae&&_=>43GR|AR_1Gp0S>hi9aS@r-05E(d zK~ZryfaGuDud$}|`a-zB9dWgN`19<9DN|mRY;7!!8Yl0x7P=hH4ZJUc~#H8;%R3e)G+gnPS~gT_tBx`;Xd<=IS8m^5b8*Y7|u8w`}ZDF|mKBqK&+z{ZCoEg7Q3Sw^@%AvZg> zTJg|pE*qf_?f}b%gyqP*t+(dB8uVCX$0Q*sd8N=;tS|VT*GTdMW3ta~HHT~@S-S#> zVxgRGC>m7{eomN34*?ChE_+CiZmX6}B{VFhB5=RYPb~73vb*n`Jv625y2_fnWCxc% zLa2FU@aY&?Vk^||-VlP7W$<;&t=?oXfa2e=6_o0a$C~$s?P`zO-kPG`Qg~c{Bt9qD zasUzaW9bA^SS-fqg`-*upOcuFp>EmGXOP}sim}+16V{H)i*%qN(IaY0zfH(Y^7N25 zg2>@s4Mpajx6I9wsHF-4#>-^Jd8@Kf0*w|no^t?f(bmcfFzhFH&*ya_ei&-FMl81> z%FFBu=0ci;M2l8F+z2LiMinU&aT?)AtGjwph8qnmu-_ENyg7}jFnWf_wDZBk)H)-E zbGV!Z=3p*r)f`J$z;}ua(#W7(miN7z2XQPZ@EX!psU!Z%Y$-1WB~E3w8-oOreqs5T z?MNGpGRpPA$ab z%~)?CMRt{LG8$^q#Y(GOD*gvMZ*+NXo4JoT7Y(~H#VHOM6>b~(B_RXL4|vGq|wb_brlgf#iey4bpy$;)q0R_9VeBqZGJ*l@>h67x3pt6C@@4 zyahrd5B5EXfbR{CLZWcn(&~@+7DzM$uyq07()cc&{tDD4GV=6lBO&N%GJ2}lWf?t< z`@8l`D(%2!50tODUQDg+Yor$i2qC=k1c?4Oo?TViEh2;4xVv;Yp=gcYgm82pzm3!FFtcB z=aRZ|!*~gG<5J|QyLjCViC2`S*Wicxa?rn~X8DEx6kPm*cZD31t*VBOljYZ1=4ogH|Fx8o?I(E8^o!{ccD4SE5H|LRl_axo#RBy30qk=xT zQsC2ceS1t1V2C&BR8!5qRItYpKnp^s@OcyyLfZ<*CLbLU?stta@tK+2PS=W*_Kjgj zZ^Yi4=;?TOotAycD^*)MXL!i$jmYGO&_NTim#K5l@|O2aMJ)IL^=&>?`-ijdaPLh~ zTCq;rBO4}Cs{22V=V14#_(}I+3w2P(^dCu$NRRR4kB=zklA6NR+X=g}cS7;1`H;na z<1cEnBMd}yV)AB$vjp4|Jh>5%)XEl^Jkr!Vx{dRM0jJ>yjZgQ&7g@0LDnAV zd1^#FBH->X3R&l>2P|T|pL~(?XmO4+&8oNV$j}(jJ|7U;<@SXy%kA(@K;dD6)e>|b zt@vS>RfOx0n3Og@XZiqo6vYPNR2IL!VtN_avv&|N+l|b|3fiTAY{DaHz1PQN1HF9s z{YF{FXhUJ8yxqQEr$}9LAt;^h6&bI?#aQWI)HLx%^}Gp>^d7IRgWKwn{>rOvwkzZT z_FDDTTTSridH65c#5kJwG)$RXE{XS%w|!=TVB_G7)YQ!*ddzCaCZ6_&X8$vH3cl1j9`cHtA5XDenfsrZb*`CoT3Cw?Y8P25mci>n`e?e$@O-{ z?%=$$A&j zf7H!{E?7jVQo)=+2E6f*vg{smq>XQXJT;h<=v>bM8MmOYHRxKMe>ohT7U{M@w??-7 zGXou0!x8Z+keJfK`D)Gl^~oe%Le$Lj7$(EwHO)&lz^w|Ub`GXZv#q~};OkLC6j36rm!CdfHw&*`Kan*nY&~kWgq|N9X$Q@Gkra_( zzn!z)3*(z52WoQ8Fq=Y4z+qY@4IY18KCbzvbMP+@&(~p`kQ68~sFOmJOFVcDRHi%+ z;V-qc2?6n8j0hrrh<}Of>sg+s#myrNAd`rIs89*Xb{0ys9-png4ZX3oKuI6sqz2P; zeiF!u*Dc5x^RpbEsXLH28sB58Hz#s%@q$)uGLZ`4s{0YvlHNwFQ;A9CBVx1dvXIsk zHij}GnJ%I0G4>|$ECWT(3~bKCqECZhM`-J-Oomtze2gFg5D5v$)>2-UO_F!8>NJMl zfy+D!RDT(wIZ=agj0n^ttIme`*}lyKRAnE$=E-0!A7f=1;-mg&@uZH-UDY7qH!USm zuD?vn>x?38NA&XoT1WV&`A1nIk4h_$%7*P}UupfT1MpW%Dan>Q(k*>Ul71lHo z3W!*hdORSue=Q^U@kj|fif>^vQ=0Ct2C>c*r{1Az>3v?!l&`@n=3XkR1n3S`i;rrNt8V3xuE90yL)(+n2LDYEakXx++15OPBK z8|#2G47{1dGkJqU7aPk81>%jgyn6ghD4sxaI$7q>98f$zn7EaLp$G7qrz6W8Ze^q= z#O_<3r1vQ$R8TU+ybruvSL(*!4Yfpxg~K_an1{FTWvNcsO@$xEQX^wZnSc(DF{igcrNsuX$KS#*G&&mX+OnLT~Ez!F$)lZhp zS|6yfEe}f3OJ)bcGd@ONfz(^bzNh#6X61Uh&VFh3**z^tApVbC|JJm0HyRIlrpym9oSPL?F4IL`lRqy$)Eg`tvN_d;!Y>*KZd^~1HoJ8SVg6&So)HtA&b~lT^;o0;Jj?VhjoO{`ij%>pn1d1 zab3Psl2~G?%Y1x5Jz_Edh62f^frKjp<<(H^{h#mkoD^5?9mAP^17#wW<%kR@5!W*|dKdFzj2%UovZnV$n9= zje*dicGgPUNlRdBy($fxQzpc8S7ZZ9XKk-*!p>}jbW=n|S^l#q<_PK@kJ&!yT;=?Q z2C(zKrZ9_#!uYpxeRNSR0TI($g+t^n?}Xwbyq*v`SZSz#b6hK-*^64)AL!b;og@8C zUhcwf@)8KbUAlLXzyrFKU1L5n@!j}u9t&wMjzbL4$rO!d44x)zEr_xcGnvN&WO*>V z0_&fF=l&mMU{!MlmN(`=3&St+kB`-Gvm*;t#l9mGzZ<{*u~6F7!t|kyMBOMXa$H`0 zPWr)z`s_;54anEmyFFozI#}K-IJiv)+`@>lUGN8V_amS7S0H(y>GOwy;Tube6yS1v zV0g&e^^h{U{h7o&P5b}N$=)JDwS_63nBt~StFfHu72pP@?PNl5P?vhoHnM_a)1LrS1nueUZ64uGww`lERH)bVQrU=gsx z;BVy9MPOHg_LTwJS0kP8<;L(2`Hme2op#*j^3sV?2(CaLQ0gsv@jfnFO={nBefx-p zwN*UQjj-#~}<2>#cPA0LBTZak=-5rtoN@=GJe&+{3o!L>+3)J_`>e zV!tVhxJFPK_&jRagBYU8wRE&NuQKu~*`8cpK`|f^M7J4@ifV`$5j(lx24rBqANwSh zJXBc*rf!|MIQLq=Oi z%18c+*DvErMvcESp&v(<(p zha8QUXOn;wVmNPydl^A}9F`DYD%QOH!t@t5uL`xWJ`ym`H= zwsw5^1XHUxzw!SasoNp1{(S0q1^>l7H|Pcv*1#}WHh|igWOcT%boq0tndQ+!$`aV% zwS%#`cHWPjIw?08^mSOC<|Z1)OS=LOwGN?~rSc06DDNm5>jqn-|O zjQgVWzY$jctBH?TM=~TV5|=tdzYn$v%1%oQ#OkZ<`IV(*um3|7fXXeFrA$Z1E%dR2?b&XI3G;`jz!+p=N z*^3i{W8G5SK8$t2-8O%Nz51M_s%M2h=RQnVu0C1kDz!YT27L6_99=v1;^E&qUcZMP zT604ImVxYawt%Du?_K^}l$4G)ya3(Sb5Vlc<>pmAU)_qo>6I~mn$@kJo_%Q9XpOkB z@K0FIGOo_HHAbFBA$Q_n-MdQXLYkUd>e?t34r@+tOHiI3ETCsWNGQc}j{c|02Nv;@50 z$<#Q-sp7NlC_Amwy739_mG$LN7a~3SEvATDO_i|S?B7Nw6oS73;*U?Z>-U}qaswcS z@LnrFWk7_sDA*T`C=1^*6({0=QeU?3q53OQ*S_+O?=#2!TNb?i^Jc2J+g5bwje)Ja zMz(P)zhYXvZv~H@>m8}Es)Tm!6Drve|EUqT_|=XCad6k*sM^9AX%p=zl@6fy)PIz3 z_V){AQh%KUnI?wXyr8he2GT3Xkm37(ZYg@7;`?LzxG^fIERyxdbH5MT|KP3eO^i*R z)_p7xAbL?6PYyrs*G`NFZY=fLtw=f1(Z!twjdd9$cxFQWW*$FEG*DPrs7?8@iQbR)5DnD4MG-Wx* zdKM2meP&6kxoN{Z->Lh@&c-@8v1!3;*1T8e{g@`~H5|vymiw)aNG}p>(Z24r=W2^a7^!oCO+E2aAeLNo8Nfo%8<2V;H*NRQZ)XPmNlA_VQ)_N;*QWpYhViQ%Ug^Ua1i$uX$ItR&zc9^$@qX*Bc*hU^x38;>51J z$8v6H2JZMVYm{PUKq?NNjlY>8->1fXeGmCqDefcgsEC0ay$BuBIp1L4iWtoQzaP{M z$=Cp}9ETWv-j^b(#2ClQ zXZKrKro@)_D^Qlc6m=XkK0}<4{$&5oT;q-OWI=AamciiIyzv`wGj1XYAeM%U5fU9bsIHn(?3>wl z*2PimV%U4Miz@)G=6RH2>~&8^XK4nPa=s9ay~R;{aAfCSOh0X8|Nh^?r-Bznh3j&v zcqyz7IMeBM^?!e8cd92|D10GU=jO-K|X?pZhcrd6rllXXM?`C9!gtI0J`vmVok)|*e1Hts#*R&P8w+H?8$QuA`m>VQkgE7}SxK}aSE{>} z4yf~q45hk1xNyU%saP2K>YK_Xr0n?29H-Ad75OzPk-os$b;-kzwUG;@LuH>6gi-QD zes4j=(4!-`Xef@tNt|!Syv+`q;Hw~#iTcbn(#(z-a=O3{O#DQ<5M!Y9j?N2m{IE># zh1Tr**v0Z-l5wZuNtgB;l%K0g3XSvnx8tf+bH9!>pqX7k95OmBbU z_qp{W%rCUd(m&{c&P&=m+y)9O9&&$dFsUcGqnJo8{^tB3VyG7C@CU++~e{ zkHXXA^1jo?B^SAbNPj9Ftm-ex@ z3)}?* z6$Q)7ZGV_rJ7OvS#_mxY-5qt(sK3rK>yJgWm4uqMF@*jv?>;8g72ZVAl5S%?pUP$W z+)HMQx={0s{0%J3%k||L5c*_|I~vQEIni8HGsTHyz&IgSCCwh}#tMw3KRRtY7H|xG z19IbvVjz-uw*H!A@;O1X&FKK>C67{H#dJ}xQ)$zg@BysUrgbQsX(mv#JSn`g#|ayx znbae}(`&BS4AI$^1YBq*+%S^(gpyo9!vw{WLkI}#W3FO!_ewo0;?kLub66nA`d0LL$s8i zpFSQjCDO`$HSw-r{C4VZak9ucd~C{!X}L!}e-vLmF=fhs{rwb9nX)@vRb>kKTZLQs z8Cy1GiWX(QEBV(~KlZ1;ev|z2lqnAircC)~kbC!CR=nr!SEmVc{_TqcrPl=?04{&) z-YHZ5*+6FZT{67g?HB+1pPTXI@4v5j{TEYq@77MitN;Gr?z>*V6!rE?-Dw53qs!z;L!;_hw*iaQi2UaUxQhu{<_#Y%B^m*ByJySuvt4IVVS^v`?i z&06MN~A znmVR?wmG9PZd|UU)PHfpiZ*XFxj%=N+_6Km&uz%!IfKBVY#D!U za_%sWsms~h_CW@w znj`B2g)nXkQE7_LO$pcVP%~eeSY;rXm-TM!PdEJ(3=8bcSZFtBi@t5=>dt%#F)M*4 zxIqd{$o16)+g;!Sl$GM;RD9goG83;&V*Dz0CRfP_r*7Ltw?l^VfscyV>7q4;?vZUNL;BRKE0)8KCTTql{iB^&Vbcfedoe!#h zcO1_q!+zG-=x8#PNEQVs8S3a>4(9Ip#I3mzs?=FGaTiBQho-WjQ+i%l>)({YTGcq~ z7ZeV*{0P`>glJ!%OB}@QFKRzu$&oyGEHPWAb0+Jfyw2CzZodd9Rfl6rhw+p5R4yCZ z65C;v`1R8?6vrio=acwwj_vnE=owzB`w{F+>}aG-vxNM#VI}1!9*j@!apOgJAT50DG9K#%g17@mTmj9Vv}krc zcuDbj*otS|gj409AH%hntl|l*Rz2(z8x`4;eQ)~X56c@m4sYJ`bU^89S}qpmad`Jh z)9#fg(7}W)mUP-7VD+bOFNIad(R~+nUqYE!P^RcIz|=usm-#&BY0aY$C3$#fzIZSX zYA=u(EmjcNQ_W+qD2j_}@jLk_*TEpxmNF$&Soz8vFOg$g^K|0KB)`)e)|mHz#u270 zF#n6s)@jJ2=M_+`5y6Qq-;DAb+kdNH@oOA3<2hVlu)eiD}yB!9oXz3LQMTk=! z?@rd`{AvmH(v|u%7NymJ9j*L4oLrZpWMGng##6czXB&O-d-_}0W&G~zhXWUdyF-h& z&b@jM@`p8BTWqnj;x8--_XH{xD92{`Kz_}d>-t$AZ$dt>7xx4xQ(A}i?aOPgMnTx- z#yuy0Gr^6F-}GosGcL#%ZE_VzePiTM+Wcg4_vnSfJ3$;oSNtMw$EpYp*jxM`+*obv`61ND-CA`rP zpE_ViHO_uY@sg&1(ND0N5F?8xDcP;8UnNSvo2qz4<}2Y?lGllGv!#TwaU+nRq~!lo zI4URBs_61Fn94K`^zw94Ir%<2Y+vNNpg>Y;4abh1*&nweHCYnW;!mccmx?sSVndAeJ3 z93D}Ci z8IP_9WOv?QN`@(JG-Lara%9kO6Qt!%I*`PHINABvId>LmzzJTnI zM?V++E=ezK_;e;~6_%DotH6z&+;{`Vi18oIUtaMx9narCC{b;+#hY#-Tg$j1I zno?pf%lfmnxllQWrh>YhgB}SVw%s7~E#e&(hmsdNC?OvgD!WmeVB;!Mi!SwX8r|Zc zdhn-<8hd+kMZ+Q7ST|Jiq8GLG`Wvc z=j;)$TUPyUq1HGTua%km5WWz**zyo)0{@{gpTn#&j53`Orqce{#p_bz-V|+<<*VKFR zgfoIYO?mIKl_E`3S#x5%>k^a;pGX$=&%=GMiXrqAJkC+-swa}1En~)(8Tqrrb?c;a zNRj*tBvlkYb|+n4(M9w?fcIwh`3s$~pd{lHmCer^mci`Q0T+j2vHUx}n;PC;hX%Or z!uJ#j1NWI-Jb8&JCVm^)0R15+CV}BOQ?#S}H~6(J{)CaL9k+iUqwmGNmHc-}cbi$n z#guTp_!qT&naDR{71SJ#I$`LSsub|o;0x}64Qqn^*~H^@JHE{TmJtgp0k>~6mieQZ zV4?ae%Vr?%Lkg@-w$vk#nxNzI&s{dTZS*|1(a$Rv1(mMik_nZ25h7z`M@N2xUljxG z=%Kwprt!dWyUXPOLN9f)DUGC_`}<`6?1L^M45jropVo9~S+l*7pH5khWG>36S80{4 z$rj=+5L6u8o2~Y+u2FgYl*ua0XL0x4iVPN=20*usj-a;C>~0wMZylHN&tGR;jZ@h7%fSR8k{<(GtivnlXu(b3PYKJUHgsvULnN8SgYuwexYDhc_ z{B%<2QhWhX?ccD}9j1@u;th4w4O>ZrfN7+s&I16{FRGy9Ai2JLI(i9CBH2vCqT5&D zOlD83a_34yN86Ob22BN}zN;20II)H?)dA0$op}X>_B3D)^1mir3(V-wztfD+R9{Vu zIh&GIZYHa`n(2t4j-#B0SM>Q13kO`C>)2mg0vZQ$u^=Nyb7+!RpV*(GG$6jgZFLq?mg`4`c=OfnbR;rE0J(gr~x#q+h{7VRIE5JwN zoEj4o>N+Ych@a36ccJnf@=v0&_sGm$4S6dn2?-ghB7*)@2UUefNF3y6c?z7DS0az! zP>ntng^6zXG_Z=|yu8u5RQ0W*J1Uyklg)RyH0^iYd*S@@mcYFN`RW0TA3p7JJu>y& zonTAHzxUn3hcYWeh1!ZoOG!EhW$gDWfciunDM82^h}CRu+6h6E=XNnqZa_{r&TT}t zaE{~S1VhE2&<^hcdx>fcQJiC5A7OO(d1UnHcKq5DvFX!lw?95@o=-@U4P z67cAdQM_)Y4bWR8(&@OZ0a*W){IL}BQc7-JfX6Hr$%oPjyo(w)1+W{5LqvCYt~sG$ zx>ZznD|egc=qiwuo`MYdfX#rdStSo$lj>5Nfeii*43aO7Fs(~oFMQhexld=j(rLyt z(4)#Gx6?Aq1U%nwSKxzw))OL=Csf)PdFP=vt(gs^jy<#WJ*)M})NSsDUFrOkk($ar z&{p=?iE9Ci6LfXo_=OmvFf-#m>=;(HF1q`8^t~>|3jR}Wj_zu~IM~6U!;3pj7{v?MFH=AK-rfED;$rk8f95&yZ|Kxm zj@Yw)Y=y=Pp%EBwVhW}$l&(S^_j1x@wZ(Og63yOBu@XkC$m7a!k)0vaXOBulFzDK@ z-n%0KCboScUE7C~i0?wM52H(5Tb_od@+YHj0D$~8uHyX+3DYj=HDOAN7L`!rcF!~G z)Zfhk4^!KG+MPmx8c$6dTIsp_g>bNp>ySL8|98mXhT95^79N6)IzZ}n@op;FG0W2` z$rSihyJov2MMzMY?&?h8rXYS2_2SVR(0Zg(LU9RF(|=ovwP9>SvHuan_(X$|H9EBF zH@RJkS3|ILkY+?}{wDP2+CgRJ6b$0BS1P^e8RdYfc8TOa@8%#O(1F*VsYQ7d3{}LF zPj|#>8xotGyc3R-p*BM^4Nft6IvB^t`y}vyc^1i-4?PP{hTDW2^HJRA&A+A+{F+Fd z5+Yu7qktuEX1vI&u;9=QSlBxyu1f9B%K>VnwU?-kP3?-ZkAqepng8IxRU2Y?RbHzu z-+PX0NrRIBf_3h1D886B2LzxgBz$ zx^gFAyEvrey_90uFbw!0b~b=XJc0`uis-qba5PuDNPqK4`|idK7^5kKEuoVwSip$s zHz;cSeEw#eBjvD6Jj{1L5hxBs5xaI^KjK3V$ft*=>*0w0$07Qb9r+n=lK0_~@}USa z=>~Eqe%voo*N<*)Y$^+od3}^Ia`9v5D#W;Se3FNb-Ca*EOKqS-CugNE9q+lVsix5c zLsZ+Kz#mF_l)CNH+wer4zQ6P`<)Jx}^L5XWDzthboukEQDZ=+J587eB+et3v#On^~ z?D2+nDT9#BW4i~Sqx;t1fWqKf5~meM!8vCPw@b&q87|Wky-02fU*qk^T)tAzF=t>@ zsyX06X>{XZ_zPh61zwLQUABe278!}ebQcjutPYIs5oi(Ab`gvq)i`G4Sot;nSN2R$zkKI&9!s&bbmgN>$lvy$1 zEpn)Ww(#P6GEY#ZZgA|f@Poxh!K)KX+$pgz$b#KmSE{Ef*O!K8%^u;=$nihNmJ1hE z(wLz(CT1kd_LjBRROd7;>YjUur1&jyVu~rIJG3z4iz!BBd|Y^pyj~+~dvqF4tZ68& z)s1_VceXPc9CPuk?{j-~K#4u~bR@CKHc_aaZb?G`F+YyVD|HzRxJ;e@$+BpG7wsMy z&;$FP-uU{lfU{nCo1uBxsdSO{!58oDPT4!l`$;0~b}44n)o+5jG)ZK8Lmd=m6wH1) z`D#w3P&tk4c4OaMYcxnre4zU7EhNm`bhm-_uJeVRLlE@e&FXxLvlNE+yrTQb7j#^c zAH`(iD5|WDEVhX+KeG;sl-7c%l%fZ3QlcM39luAicLNAQ_XVA=o826;y5;n)1?q&B zTnKJwV5bsTYg?^pnrbVtkNq^y`Qws<3~P_jL(EZ{K5dV_vJ|<#$bH?`((VNnH=pyj zK4$Zj3r_zvu~oxq$?3ZC)Uc`u*2&Q*Z@m(qJ_Rt0ex15Rajm}m6gQtFeD3pNz5ni9 zWALd$mhUXFDY0FL&}(pRffFW`r9YhXcIp?+L$O%{`o3!1&=L}LZ*~AbX#W zl;*hcXDF`N(Y#5txATNlTWrTXZf%Y<^4|PpD3MsGZ3kc-nN&IJ&=C1zc#toRzgmAl zcM;e?rR1L-@o(B4qn{ebd>-7y7Jimf=;^D9tMDMAb?zb7Z1Q93LU#9<8CC~MX4=0? zY9q_+|2X#s1IoO6NY2{b9Q@E*cwR`*LsK z&zxK(GG|TPz8yE~Fvdspj^vV6%@+tlYV$WCD#3f&Sdf3dA@F5t)i$Rn87llx9K>Y1 zxlkc_abwho?U(h&-Svi=y_pOhk{M)z1HbV;liuvA{Cu>>rLiew?r@SNyZORA@vuq| z76V8wlj+n|YXMj46T5q*AG)p4rR0`4Ex2!N&TO}#`uV6Hz?U(m-6;zS^t5>ph|3(zdRJ--EJ>U%&TU+ZfjT(}O;^-}e&k5%iUyLqV(s50%0 z?X9+{yB7|JGAC}9ceaC#PVx5~dFty`N5O#i`-k`@B;t_35z@?5+Z2wgzn%s-IZ!Gp z_;U@_LF^so$VyJn@p#oc0J;%D`N>uNC-864vfc0B;6)rU!xTy5MRXx@xFnY65U0Jm zKjY3+X)mi%#TI2tovLk>O z_87zqbE~Hz7lySh9+f}1pA3T4fEGe-fe$$2gx^d6i8KiYHpR!7PK3O%AVe1#7NQlQ+Y5m>gK~>;5V|Tj*L@sSm_r~4Q ztc5mU+a#8Z+8AW05OMs3KF0^Qvo4kF3Ovmrs}{JvHz9;SKcXOu=Y#J0RZe=uy>^E$ z^v=n))bx`S^T8M*#bF2E0%HFopz4}^g${)eVI1Uwv2{S zXl_Wh9cs>%G_&3Gk8@CNsOlKjWjCJr_nKZhS0|?9sLGAQg#LP;Es5<0Fw)7H;W?S* z9W|^H06vf46#ooq7hP_ff^Jh@uYC~_l_l!Rzu(L~ zAA2Pz@sP~oJ)Ta@g{SZqL*Ybk*mg#?Gao;a2q+;LP_=5Cq!T=TV&~6%914KV+l;eQ zy}TrZmIV-W4b(?HCN)AFz5aHY5zTsg_f;KXjxO~e{}84}#uIbY6_R1BW*pgn{jzC3 ziiJuqS4$=O8#66{_SF?^#c9Ov{5bo-aY6C?2Yiv$SqO4&_jr|khQhGY@;Vmv<3w$1 zWR!93;+J;yzPVF%w9vB_vMKWwdD8LR){thqG=4wz8;}#)bM563MJVn@g>tnZzj$nt z?m(8~{^W1}kiYp5=uWQw6jMpa@R)ss&?HOxjSyDoxv^d*N~5<|@)WSoe?=qPoed`N zECsiUIZDHl+GsqGh^XP;nqCM78AWy;2ht~Iy@hythbzs(sc}zneqpsBi9usrVhCPs z@c0!Nc?mksj1f`1P~^aqM?Li*6Bsl^iKQttV~QewXU?mT>#~vuYJe1}GnY!QAHEUa zIane&ZP&1`!i)*hZ4EkjQ;03p2PRe=f%*c|hF4GQHvWVS!!Hm11WkMar`vx7;H_^w zmyoF>N8@?>ueLOwUG}~#T0FoO zA3j`Qm(?wvcTE?@9Z_Yq zFWu`jnAe<1vj~fNw0ln5GDi`RB?eY(PdVAy?(|{bDQ7QsC{1p~WDP0N>tn-iZ`UV2Vl+HZDV_w9+uaRbAh?Oe&%+bH= zqT5r$@k~aZ(5Z!8b@X^<@;gj6lI~7Y(A4CjY(_SWLiJbPV+&E13JbqB5s;hY6ru3* zO;-nS5KLonY#ALLi?fEYYacpS*>;DQ(85ry#P%lP(aTDW zfw2QgpWPVD!M|)U-{=SW33WcrFuy-91UOm)FwXDCzVoi*KgJFDj!?vT0ohg%{YM5A z*0Ig_t6f<-An2iqU4`r64Z(k4;RD7M)pso#=M_Juq&A(T)%IZF;K;zyXK6@dFxvR@VKg4q9EmOybccZSI8wh*{RM!m?_3_FI!Wnn%jpnaTr4nc+Yv z9_v?aHFc{xGEeAzo`dQdyMnf$=M0FKuonQEdt#FKb+4IG*>#1CJEG+Y5$|l50OBTA zkOB|HP2(Gsnt8>X66I-}@;vpKd5~Is4!>u`5#zP}Cz6m6@>IyrTM|k69b$SM!bs?Q z*N}!f9yb}iY7@iIe9<{nr)5NVe)=xJ5mpfWV$4hZX@|0Ba;}XkA1jyV@dac5N6!oX z>Us9Tt2UwLxmBYWVOENis@d>|<3joock_<$4SOaZ4urid=qQW>b*YhHC*g&Qr2J?& z@#li1tHrvBZX2xFB_6?h{`|^{)D8>!mw=*j{Vj z9B~AlGm4G+m8zU!@zfM^JnUcIpq`1nZ*vP#7fb)$vEVUAxiiVFV+-m-r#!8Qp5c=X z=mE-Bmj2!OdwdzWv^HqvVHarshwS{`Y}0vHdDH}u`A2EcDtIGoH$^h+GL9LX~DTw#ruLfjMSS&b0@edp;>oZPWTRRF}YJU zHyO>B+#hq@zWpa>r$1P;cZ(hZ-2KMB8o>yRG#M-eTuw~-E0 zNO~%}_YLe0wI456zaF*1UvDcvX>Kq_iWRaR52I_}VWMZx8;MjGdxkwGwS*8oCbym? zNI&s8OoU}zROMO2V)##P^n%034F_6Xjwtssk*L%}jw8rlJ4B23iyYCw>mro=I`DfA zTz?i31;(lXjb(8|IM#j}yxYGGl&kR!7`|~T`CRb?Yob#3b+z3o5s@Z+=h@zEwrQo0 z&%esiW9ZcZ*I;{!l3E@mbUi_hhx^sre4?nJN+zxzUUIvpku%%r!sd4IycFm(WQlj& zFw7d6Wa=uy0|p+z)+}RGHqEu=VooGRGv&8vo?Iw8bLBeW9=rDv>i_Q?{43J@skST< z5~n2+65juvgPS{g{O>XNzgz#tzsLTKj3t=F9Q390!aQS(oZLoUsYjVqmbywwv4`;^ zPJTjOK|v|61+Btw#ahjGL&g!umeBUU?V8Li8S%fM_p1)j;~R9})|-*F{MGG@1$VJ* z%tb)w;2kH`9_C(H#_3QbL&hGj?yya!X0icD^K91pKxv%+ASTPRQS2TZ3#}IdT+l*y zh)(S@R4-Y9c|{!#g_uxKcT1vxECuoZ}?dh6d z+)C63!Snp~ESa4Y0QvCe1c#xYv;P5SJ3rtyEw)X03bRqLP2rQbH@RpeNN@_$ehD`BQFrXe7SL>dY9YXp7203)(9EU%ce};*Wyg z2nUJW?#5(6vM*V^^c8P<6;*J*mb-i#=~~N@zv!Y)gp(;0w31>5*omlx8_s%vZ=sd6 zlMvUO`QNqF>@C)a*5-7ZptF0cOG1^;Zow6hKQObXBYuTdE+ioNWJvhq@CT;>-1fa0 z?$1_T@3}N;)?x!t`T~-Ej0EdXtyPg-SFyAgNFRi(R6vm@JuM>B<~08;JUyf`bV9Y} z+w=%$hk_*gA|2p|jabyDa#?-{YYYYI%!|g4DK8=viV)k=L!CpKIL z7&j%T29?3g1b(nhNNYn&UrG69ziK@0_;}IgMp_THv77P9l-!KT{E`4>z5js4e%dtO z2oXf>@Tab-H7>+m`%3-XZS5@32?sPtcK}i_Pw_e2t6l#^O5_=oX0K}A9a7toslAWy z^}W#yx)W~+p|JI>XsJZ`7A}~&qI)&}@Ar${S4^M01!hzJ~DkT@{QC?d8FgMi!ZG(Id3-^<|`LQ3?@<(GX5ZI;jU z0>=H<&ZG)dt|cmX#slbNtWu2`I>m@$`tj0~n4~rS6O-M<66COjtX3xo$b|T~2@H0a z2!Io>X`%_Puk?BEq|U0Y}h(kR_Ch#x7iGSCd-_e?fSQV?eC^H z^3{?L#wIsW_P6DF-_i$(G|C=5ScUTCP0HGdeOA!^1(? zXk@~*|E<a*GJj2R0b4;V^4~NFlW@+mdpdtPOoms2A_9ZUaXdB5gW0sfe z;3jkQ`p2TXh}v(1+>b;YHqkkg3PzLhnph`50a7PWB8^>Pd8Dp01zP7+)hO2Llj=_q zk8=R%$UI}>lSr+W<}MdeN()!f(}7IxBEbcpe|nw#z#?|$Z&;x;aK5^Q-JB2+*oc;i z%S3~|Z-3IQP2@z07{zHiGPm~g{+>RH1si|)>tCT)2RXqb_03}H5jWh@0$a)ka5Ax+k3G44;UvJW~+?b}*BEZ%FdUdRlH1SnE zsNn<+#AiR>o93ORm(({j0vlsnNRMgUP_WqyGD~sezxY z&9%u!*z8^om;Gv4IuW$}-&0AJR0;xgJBDAXGtqvi*|pli6n`NKe7>W1zP~bWGI!J6 z(QJd<>kISBJ3j3w{!)@#wx%UTVaq|fn)W!fSYTm`nD7{)GGaRFi=a$UA+`=9!#5;- zuWnTU`?uq?AC^-oG{c3O3p~?6WE%nU;Ya=4DxOIHFyuIh>0x}%ta@|l2pwIsDW_&- zZxnP(Ue6;w{ix!Map>t!>6@v*3vv0u2wfFIWG#OP1=#n|lK)F}?#aeGZj4}6o3Ch$ z?zx5W)MhclCJMj<0db#0K?z^(=8xi^LKHV+C`^zk%Lg&KU??JN?sxQ^saP!Vy+gkI z9n?Jf);)l{)mq}pUd}KcIu+{EuyX;TTt|%BJnwvh-du}Z8bay2UVUGhkO(g;{s4ta zNMz#<(b&W7=PL{2ae<#>*f#FtWDv+UqbuGrtAcI3xspO|H;gJ4XDr5I_V zPy7%^;xp7*3&JVpds-E4il~i~0%vc@n^wC!E7pjI$_Ok&aetE(`U{NbAFJ3S`eqVlKRI-JkguP>&Fca`T1eO z{}xesR1`gdP38~Iep8b2jBySc4RSXY8g%yo^b~lAck3*gSOKC|aH@*0ZFC&YP@Bv} z%Aalgc!5;)qoRhhn#w`zdJ$N_7yHk;bmMSg-X*N+jcX;P38;p zkW$VlJ$3hiE;xlaMkklLm4Q;7g!R+m&UwWwwkZJZ$HwetQLt_zcTKR-(0`tGk#wDQ z-kz9V1Q>(1^|Hkf^PlG{qzW)94(av0Y~oJCUYPizSOM9>WLA7LeYvmv0bnIHVG1#%7ZbTLo_mJWfk9= zwXf8|RaD42znerx1B%o_G_#_thJScvAAn>0{EkbBB}fPhyg$pq(AAK7D+ydI(v` zXAkt7Z-dG~q)2`Jv<^QVs37RoLsFjtRHpl%PsH?se@pPE3C8CE@hT$Bm~;uK`aah5 z#$RMIUhxBzgNh$>VVs#Ki^K1!qI%ul2j0#uNlD7!-o-U^H_3ti<6{=Kn@%aATcfwR zHM7UXfeTkZL9}`JWV~%wrQ(6F*uCH~HSlqj$pfCgr$ZltM4E z^TZ-M{;?$ppI!Wu-e9nV8i{?9x z@is9j2Isv8uc7FSS31_E*jV;l)9wdAgmFxFIrlUymLt|JAx9d}S`{0?i{Mue`?!rd z3?Z&{N>}gA8V1ydQ*2Kn=2FS``edy8KCMWN^D_=B!s}NzIA3V1J-HCN!m7_f%1VHc zcm39D44{JfL^OF5ep^F4Br)m#Rp^1_n-U`-yJB{JHwF5Jp~=+0Opozns)s3ay}wO% zC2*wJ3!EgLi+1rfg6xvvy-&<|HBC?@gXd0l)m1=}Y7dsc{6`uG#8eUZ1i|JE1~$LZ z8J%_#B7ck~VHP;uOtZVylYMhc@~!jB-k}4`AI6 zkxa|y&$?FRz3b=oy0j7K)bUJbeScKY9UD$>`$+)7`YYg1Dzd6ssEMdX+xuqpftcBY ziuoemgC5H?A96cV-NFWeRsv5}pVWsuGUd*m5GgWu3q_U+CZ0ThHaGQN_huCPll~mc zL3FB;Pxs8{h`QJe=x(Jf&@^59wFczJ`_~54JB&N05-B%D_}OHG)&=kQMDX8Uu@L>& zoEA2u+D~($)8&an*=iLOx+#1FX7xuf*)s23S5Kc?iH5__8h=0PI?9=?_>ZeU0}5|d zhd!eoW?y}0$ikf3y8ZctB(g60OXN1}{&UL%0e@R#z@=x@JE*wWouzA;EOoHMVWU*O z2@?M==zLn+=a7KB9~3lRk5p%iRu3DnkZNd#fiY)F9P zo~|T)8dA|8EhPt&4hZt&=UvENvL6Y)nU<>!4io$a`;&e6-1x2D_OQ!)c*R8?0GV$% z;V71LO+x;Ugb1OAZ^0|>&%rT_30#YlFUG0JY~y0W=n237T!HaUDrP+b+l_KsJY`4; z&T!$Do4!}`6}i}@p_20O8);1JAh#o*dvFOpe~R8qK9hD$aY)-s&b zu{yNYjhKVb=x*0)S&e_Sc@Xd3r0TV2_L+@Er2+~-1$Sj`xR3fotJ^QX;o#7Th;7Km z;@3YRV(#voZdgvdIy-p=Dl#Rcy`g_jmCy7;Ls)Y{^maZ`V$@(46 z8eo#RU6c1?gJeYU(g#TwaN$7Cs{uYi56u72GcoO{d!5g$+9NX4>)s60VtotDLtzvwzV{3$ zvR}omhGpqOrml*maJa0>#Pbk11t^LZjZpt4iJDw%7jDa5ZDQH+Lt<1Wm!Tw~H-4`` z$c6r_U-$4lr~BONL?1E3ZF8j^m52gYN%bg~X}}Qq*Q=en%Nf7sUz72|#2;XxZp;2@ z&hre+t93lr=|4FCwKJP_P<3Tf3SSZKJVjj$)=gr98_0yB zukit?yj2m9KE8N+vX+j;`gNz*pTa){nTEtS{}`r|^Q)!~-FC?c36SX+`E{CtG>Vn{ z(R(sc^3St`62sbYz+)V0fS*xaZi>LmPfD@-gQ+Xh1YgV1l?0H0nGzal?@Gqbsfc)p zC+OglAXT9t*!;daD7IGwa*l4HC{rmMWlVMq+^wfHlw3) zKLvneuLGzh^nRJPohyN_ptFCBya9P#jOMW3J-z&zDA35LoGB+wE@Y;mN0S>kPuS0->c|^CL*kw!8MoGWprjerKD?DPY(OYvDm9 zG`!3O$CpW~mLDWVTHhj_Y(__LHiu(Q061$=#Q(v_$=h#|YiAT9gm;=bRXPSi zS%Qux0^SYnw;BSS;({E9$DU%$*DVrR=rI@K69E(}JujFAV5{yjf#a}ShVh_+40HC< zLrciiOqRe6+G)YW1Xb&`Vg#CjgM<8X*#H6-ZtabZNIjELTUCEty}vMg(^1<0xrr9d znIa7ITr*6E_}fE(zh)#Z)pf-@iH$izTdaWbSC}>W!>A);3=MO{Fy3+KoQQZgV;dQ} zLl(h{9@CVzST+Fym5NzdQSxtg#rI^}GxhKk+eSSxf+1!;d4=;WWc-*j0`$Ao^@&+Q2L zN11(uS2Khz%6E$ep76aweBu)8CjBj0)Zz4I{X)M6tZ&Ks+F$TuHMjKV*pRRG|Jj(b zzcthGQZDz;RXi|fON1s%4}S=8Y6j9ye;f%H)>l|z8OS=@&hLuyEBDM`%Ryjnc#F~c ztLM~n`RZi~jbXt*!}p$=Ax6G^HYoqv+xRLWFG&0mq1OEIC9;a_b zBufIUL^PgakQ*Gxc~_@(L*~E4wCRKM(7!EU{~VO#)yhQ`fPPdrMKqXX@I97iHd^c# zmlti&k;^CA1;qPCM(@hTMP&J;n+vGq4Fu9E^LzGEbz z9lTc6nY4a-Xyz}|fdu}1*D+YN_EHUX3ty<}e~XRy!e%JucgNOH)0@GGFn{=wT3`PWtnG@8jJ_kSr`{dW}fj=fCI%QknNb0^51j=NS<3ckOq zT}r4Efh;jhS1qgq-LVU#>7X5amTm1go+oe13BFNjVawKi54-MZ{_xy4s@h~S70vA_MG&}oe?X-J}>VPt=dW?u{KGcPvz#GQEB6p(yt)+|~&P)82 z7yfE1Gk@zKoDfjpb~+09N6Fy6X$lvH-Vdf*+6lf9C=TH(EagcI`Qu|ueUGub@r`&2 zm>@`jGy@yqn(cdp6j`Z0njJk9fKvLc^yw)PjO1f{2z}ifU7YUzelfF+h(kM>ei$epA;Days8Pnsn z$lzuF3JIXP2TUd*4Ar6!c>u`?ZZd7`k(2ZpCb-%ErS>YxaGU#_Nh=nK=80pqcEM$d zfHgejBf})kZ_+!*QXJ+YOil~Sx)SgccDXz>!leFmVI&XJo?-j$^3qAu$Y9l2lgVPQMV{vcLuvm-0MU_0Nb)7P#1+sTQ{Prr__nVq>BAI_sMl=r4N#9J|J z>hy5vt}o!F}i`uySjL{R>&jqK)mga5Pvt`7TN31&BRy;Ql!A(Fp0d`Nv03cM|A{zI5MfRnA_y&zjw z>y|lf`mbW>ZRJf~=LuhE7lBI;FpV9IpQmMZ4>Z1w|Fs1`_SirlaJFJ7#4K)pj!>b{ z+Y?gxHt*qm?OM)hz4U#B8Jl3eQfRE^Q+fJnMO=>Au&u;ES^VGOi4pV42a9j)$OeuZ zj#g;SNEO*s4Q=cgLg@qzOu%89%I_<}H)6@S#}ZT$e#fGSBmpc(+YBz!qRpL+@K)BQ zqA+xJ#B>^<{_=NsUKd`NC>V*Eqdc^l%u&lcygD#BM4*&a3^bvwGo1%##u2tLQ{3sN z6>9Ec+#r9q=9(D9vxd~_p7`XJM~M?A3qiBn{%2AFLXD@RY)!ixBOkwucRGLA@)H$3 z_(WgrpRm5T2#Kf$wJ`!RJzUW$_`%-!2f|c{=mrOanWX%_eC2WSKH$!EuD*y^jNo53 zpxtQ``f_6a_7E#h1Sq1S98@+{CbrJ+YB50QNaAu^_dZb7m-$Br)lOjdfsWi*avKtq zDuClch)6;I%%$0}lAD5l)=#jJ@t+gMHbZ@x=@W(ndwiH7Xyfj>?BKAfmr)Jr-0QIc zFK5Rmy?puO*^!I%*+}SAP%tCHX@C;?;#pD2ggRRk8p$~yi_%dQK3^lyIyG$++c67% zRBX|g)^(B#MH(#>pG&vPM}Xmmi++i@_`uH{aO0~6e@sK43D)c3u6Mj_loxl<2amw# zP4m#+ed#YHZuK4WM;{R)SHv#hs`-(+t)2Vj_<%zbzXW{_U_YObk8kvNg!R!L=~1$a zzrC`Nx8z2wr!W!(+==mf92zW%rN*L^8b+ydb^WkkG!d3JYl`DYNQ2-e7oWPq~$Mf@+H(uJzOjen6aDSd+zrKy{F^Mm?ycUefEK`KP7 z!W~6C`rnCaC>oQoKC1HFlQNt39#oLHNOsQ>qaoKiguq8@r@bJ%H@iwh{vdo5a395F zi6{<_uickDA2XE~+sbS=gSTm&NP=X@@Rz5?zY|QADft!LL?b&S5MK2pms6bKO%x*n zrRE($l)Sd%mrW<*TUzJ3In#$sr`KbfaJcH%!IqbKeeWe$qD}_l-6vlal~=A;k1-6sK5N@5kD&Nto_#RUjaKXlNDkq2i|n~ znZ3WI_+@MCKNSqjuGj8pCwam1ZxZbuZ@(u>L}Zja%drNr?tlGc0V*@~d7bz#T@}5J zKGzDIce5>8Vn~3ym7;bMIPbc@zeV30N40K>M??J)TrC1ZWh~d-ipK!}yXagmw~yE3 zWAT|_dz8a8-agyp4M0AWxqk3nBI`OFZZgopW7sZahlBM{r(RUZhHeM{W&=H({xgfmZ19VzEMBE!slY z+5HgB@aN!o^cTZ_hXS4e!)E91zoj;1~gX$s|pcMear zNtktO*D+R2|4hRPd+arBWul9Tv6kNqL6B#VHwFIwfCT6ZNd5v zb1PqRYoNu8JHdh!rx4uTrMMHkxVy_u-hKDoxp(IMnMo#-|IB9p-97Ss=j`5m&wZ`? z-KV4`=Aw09YN$tH*TFu;O{RnAGh7))?Ogu;uxkS@BT8L|vSSbf6%@UGtN!GKE}|Lp z@Jr(zH%vObp2!+w9B%^MX9_SXO7W54M1&aONq6Yl;%SNtg_g#383Y~B z(*H&_#SH#z;WSi3*JP)I!QiFpyzs4v`lPg($&7B6kHy=by%yR|yBu0x;fq3a&sJHp z^bM3if!e|JM4XjYo0H$3CJKgF7zcxym{{E2C|HC;;}y=w($Iv#S0wWaAv|SmBP>*i z2&g30{iyKRybItXXs7n<$U0}eAfNaUp~&6aiX*V1pu=6flDpA>)T}*}%q5nMaG>*T zcjw;@_!AhI_qJp@btu9e$atwtntvY#-j=3+olxC}Qd(=tg!p^f&*bqS+?P^oGIRgN zc?S^63$ePbAKU23mx3i}F@^&n9ji^C+zfG3*_%I}_fc+1O82<%NaJdqlY<6_WVzMn z{pZ~VI*fz1ehAiGLa>34<1a0acqxA4(S*MC5B!`Ghb90qE%;C{G;JL-UcU*r9EqZm zs3kBA?~ay$RA$i4-wxtEMgnEN>EkwiXCnB~>C_$GtI+(o-WJuuds~pTXY`pOfnMNr zR|t(58Y*)>TrAOpwyk%V>56&~S=^?>ygg}1b1L$1i4C^_Y1YfAZw zXI%olXOvan#2(fCaOju3V{o6YLa$aSRDvO7klBWGU+2XERd$6DjW-_PSE~ zaK}f|oUPWB=7Q3b=x%$`#i4FbmG>tPZUdw$?yW|9*s@(g`>2Q6m<}R!PF>J%rF7x( zxei^G(HGgBEQ5p{cwM~)LeY*{@ZlDw#**XIrh9?s3m}!p$rbVKaYtscE_oeaQqJU2 zi)sk!xGmzQ;I7g3m{txZv6e+xvyJ^7UsGBvVnGDdgBRWp$8 zW!qG6wt0^i%Y`aXdk~=mhTSvkLm>+`?N{4sD{hr{HW{h07KLBq@W8J|GY(Pa_6FUl z9uD(5hq|247d*Z3kLDtcEj8!anRdVo6?$1V> zG&GRUc^j`F)8@fa5ui z9caD>u62SpKRW|{Yo91pXs+dG2?o9m6Lu!U0n;6!H{} z$DwT2RPHr6YoTR%jTJ{wZ%t&P z#v2v}wb|E*ydeHN-H!9Lmue~3O`Sr?D7wJ97Uq{l5+qz+#rispNVNe4gWJ^noLVuC z0;k3ZB1?Dby07%jvM)oU&O_QKFj8F`Elz5ZpD5H`YKHCkD(*<9$gRpr8EFA><%X?= z;Nz$s|2a|W8FdWSA7d90RtblCnEAX{O8i;QV>aZPE1a=7u^+t3K))S_GKz zVyWoOwtA<7ZPUa!iZE90-kfhzafzr|(W`L&!6syG{jI?E3rn)*@(Y{KZwBC_=lkt( zR?R?$^l3uJfQ4E5rz&!e&weG=ScnJ@sAiY=$6?nuU9K@%IKeHOn3T>DEkcd6@S>O`aX6gbEy^Xwj1-LPQVRQ?EIj)wF%ha zxr$MWPzCe#x7Opzb9Jh{Hm9S!o>qnll6=>~20pbpb_Yd;=fv0W1s>BnTy$BK_eEY1yonVTEFoMy0D8yv(e)QmFSzN9w8^jBjh=u?!w|EY9jx3nx9?G*OW(d_DA@i1s1i+%{pck%<;EH z`kL(X#sxP+nQzzi8>Izy?VDPn{6LC90pISEZ<@y8ZCsN9VPJ=NOofmG&54lD9eBM7 zldO!G^msHqK?@?avv&=Ia=FAZQXUm2~q`146i2~3;$R$a*PCs+~10vskjA^?-6Anqm zpQu#9{2LeGQa@{qld%>Bo<#gI`RfV_OjGVqrcI;Oi%+VCUFJy(fq zqE$yS$^RfaI=OCS^pk+wYPq_2cehlG-K|xo8;n=$uD^dv!=yXZ8+SVUi})^q*P9k3*!PXTAOLmI zNtugnLnH!yXwp}37L`MLwfu{Rj|wLGlb*V+Wf%kuaf|E`vVQM{bQL^LQXGs?$O_~s zrNu`~DEoWKD_$M8H4L#o&Df4VrmcrK<|{1=r6qkObxT95v-G9Aw>4d~w&E{+FA!N; z-kLgH9x#43F!SU>!e$@x8u>Cc=qT-H0yQ0)>}FCN)k~680pBECVMx%dxgQ(6g$&7u zEnM^RZ2$V4yHY>B^2W{!MH>s^g_D3XwQOD4h1O@I%Tie~Jui>TL05AyT(4mWTi@Ot znRUq|#>}5a|9iIsQC}xcaZ{r+`mhR_kn*~VN$|YILZ)-pWsO0zfD7EOK)oc|Mgo0M zd~EehaFzXtE06e8RfD{?TqkEJlrTzCfsbAO904o##(Sd z7`!6ecGE5n1`G@})NOZJ@1ieQ_Er+Mk6a2TT0iNY;KRGEt7@TKuv$n;2mu*PkoFl1yIVTGr4Dd<9P~YTJclEozls1Y+w-T#>$KX z@aFsby`P}c?z8t3qQCfYHPBp^^~}q!>JXe_lLO?Ln`YT_&ZToI3un_`3TS4n_%Z}J za>dW`Sgcgq-q*`*%T$BtHHi7X8_G$&7Nua?9p(Gw4pYk(%YL6QOXR4@tYG&D|6;xW zJjE>&PCHZWOaOQ%vMj?ExiUT>^x&UxUl{)!lSk=MSn-t()?X*k@9K4RB8G=C3VNYQ zoN__PwmB6{HfVmicY9?Kk(dxp3u%?@uY4D)vXyJmiw1z6A1)_Ag5no){znob%h9qzix2FndK;_$&rnGEiBE< z?nnvnHV_&yhWmGul+#bXbVlMWJrlDZ-};Hz*abmndVE}ZZe6Xmt{En-Oq-l~r7V@} zoZPkLg%E2SHu%K&mxenc=Yg}TWECa(qHsO@>a=j6iAH~kA>@K6jiB~zbIX11us0vZ z@_vNCmGVQ-EZLSZtIPS;jCz<~J2ZGeSBm;W^?R=Tt2G-;%bsgF;M=~jEcMcX#f|@y z537Ha20K@ncNjERnwY%QJE>{=HYpM(k~8W$EUY~nV^{8gg-4t%iuy!fT%Cqcvx)w# zYT1o+*dud9py6cHze$3=SjdkgjOljSZLEi)nV;mO;!Dp1;9+tyOV0fo(@fvPsSf6Nd{lLnocbdwz zQ>^4+Gu1>|+4KP28D@K==zdFa074(gMd&m_fF`1tDZ6Gr8TAbHEvXyn4?f(n(6kIp z7bH}l2VrL`6?krQd>TI7azfD5zs^&FZ&i&?4)a74fjzx>L*)~qY%pIg&>JjJ`M3YsZ*5W5(>)IE~rV~eV~h1G@tPSgr+ zGtzs6+RWHbZf2G-6K|^4zLQhJ_2BBH668+z2ebbox&AXq+X96~K3V}Nb)t28|7aja z0#6CMj(M35z0Ri!_7@=kGy3idXqQ#%mEJ8a((Gl?|#!Myos@=uzKNXP;+_o(Qf;PJDoO}4)I zudx~?EvrvW9?29Kb6lIULce^1zRsHSfzy27XSk_MZl8GZPgRu3J{k1EX^kU&P*GF( zwb$E&2-)F(Cs!RAPi^`P)~`1s^6!n76n`+2?^b}J5Gq29_w7Ca7}?4WN4RTCcOutro6p&^89$ti zd17%2P;HH$JB790zUC z&Fk?DS}6LV@kr2$c?k)oXk%WWLrQc+S6fy}_ZzOEIU-7^q{7QrbJ$KfMHR5*L+8vt zQRoJQ5ovOZ$SUyvMcb#bPJIJeJtK^X`&vM-ZP zD`K_vbBS!e&}J5otsX{};E@8p!(pHh*P6r0l|g?wV1i$$?DmhQlDqVK)A(`M>}6M& z*ts-bL&&u|>#hR}`_#G;GJ@R=7regLpeHv2^SF@It7btG&aDAC*u%m~0YkWkl0!r7a@86=7NJX9Ht!D zsW)ro;#+aRL^Zg?UP&uK7?)W2i?7K+VCSFG(U#-t`!Vd8VwdqdQRSH zGJ@p01VreXU-3ASYRvt`%lq))jTFo4Sr>}h8jKouReTUy zOl$T&QQt_buySJwi^n!VIns=wQvJkx{Ekv14~Mm#5MjbQ7yF0&{N_$HHh)Ci4(chN zGjIICYU;LCAVi(GDs#^c@@+3U!LGd7`7VJ1SMeQZWkJZ)?P;i}A!=YBW%cqk8i_Wl zmb7c_hcYcdy8-{jdeb*FoSd8D8ggq=_;bZsC}6-K3|tFIkq8>+;T5Ta&TRxsqj+(= z_p~4fQte*%oSA&LYM>Eh5TLv zL@{<%eodtWV{17dX?rq$BV59VK39&-Nt>O=B5o&%7bGt!zJRR6ow-tlKD8|Q<^QUd zG`1A`5Q3GM_zJ)%g$38pfOPF5y4??0MYMmTO9h27D87<|HQfl`d6&e^dY1^tL$3Ah zEZo3YB)U^dvQj5UCC~g<_qWAyt;F($C3kM2UV$j~c1yEwW7K|h65sVpmF*zSHGF<5 z&x^t`*{<@-Q$*ys97Z(5QYp2SclZ3?$&s_%aM0xZ(T@v>ddurqUdlu}{APt@e?u|^ zb(`~R7abFP9SQhWB=JE; zKXp=i|C}*CtY~=8x_r^JXM0KUgFh;06H;Rl-mt|Ejj@}cc`Nq;TS(ccr|Y{ipc~#q zlAB+n6k8P9xog^GFb>^VqLc4qIDn|IbG_E}s{?KOQ7Z#gh9?+n7NF(jwMPmE9-0If z50tEt2xg{jcFHHSL_AMFpvf^Z#By0}=#d_y%#nkxnGGhTgOt+BC|VCh;o-XC7nmBG zO9*C0xc0a|JN>FeP|}}kYx@g5p)SxObEwNkap9qRz*$F9Plh&CB=ta4%Oyoufww1F zd0|ZyUuP4Bt+t4_#HgWEEt%#t0hFVtes)+-V&$?pHlF>Qygvp1XnFD ztHFvJNT_d)Q2k`z?wt|{=$usjx=3yqVgxW{caqXi5!fMkhT3PYw^j>`*lC?Mxpt)# z7}@rDVIk~oS+i!1-ig;&alQ@eSMHYaNPkJ1-*2%^2_PVGWE{dV_LiWsaUMGy_kpXjC{+t<|Pi)=|3k9Ew6Y7rV)?DH$Bc z2TEj;g~O4Mv&pOJOeHmNliWgea3{Jk<6Z z-i(nF-Zg)9^t!L-#p)AgNSpW77~Cy{1yJjjd}YgC=Sv~RA;&u4;#;k+&3~OTu>gfM zEMk=x%ww$k?o1jUkKI3-!&AR2pSKGK2XS?m8$_%0;>?b_(bQjB+G&9!IZ?x?R+d#| zy#{VmAI+Lu(rjmVlso~5U^n*y1}{ft^Dr?qpYg%Oicov7v>(?Cj0oe_^3thBIhg#) zbU#Q+6m}4uw&{jgOW$&#jLekZJ8gnEz736iWc@MSFM0QRRM9F=TDLcUo>UgD@Bc(x-JWg@(Hs@Kfpz9`Md z;wO*>t~zx)9@5uleYmHvi})$ajqyDMTF&wGCVwUMWuqz4-pNphJ#7fwrQxXp^wQg8 z(&0r)=5qKGXw~w&N#=3NAMqz&-KtrZe`q@XMtJ<_ zFL1SLG@s>!OuXpr3i+16g~7V{y-fwZGFFHDK9;!@TzxR7FMAH+XVQXDH!G$i6d^IJ zx*;bHCnQri5tPD%0l^9nrzB?)?HXKh$|r(JA0J&cKBg;#__2&YurG}fG!bLJJ*WnZ zwwXl!vUgB*RX*SN@*aYp>zO?_QJhN@11aIIocb*qNtf8`If$@GdjthNe{i%<)Z`5= zXi_khpR%lEti)dJDGGt_-`A&A+bqh2&v_sh>Mpuu9U;LBL164P7X>%q*FM%3v9Hh0 zcwTE)J5;S7ef~bv1qJ2jgjfHmn_S%g;I9lE>~{91Lonus9t0IiBBZT}yMoDry|Co% zxG)hZW}V8hEPdUCI>7UGWl&Rf64$pi-^dU~u|@<0>sP8{b5^4rQ{-r=KkbVpFPKD1 zon#R1uffZ*@3n|l9+a=GeIDnzLj4Hq5V}Hi!~mw><<{I{8RxmPUv?_Ps#NyxK&Vuf z^ICfQX|<1KBKd|8>+v0$B9uRqRZuAg{&sP%3cUc?M`u)gJDs*ca$E7!)oQ3E@tAihScW^3dHq_hX4$!>hrQt7$P z{1`#fP7B1{>Iqe@ivEhQ${u$#tgn1@`0K!!dZw<>qPZxib3U`ZP<-xxg4CfcV2j8C zt~CJNh>1dO?p4uIdm$`*G9M zAKpeO?A|}A6_LPRWOIN0glfs~vE~e)@jt;{6Z4(#y}t`j82X*-O0}>dig$yE`Jf3* zU$e7kCpxp;un5nddry~ELZgV59mcr!QRnJxl7pH4=87eEn2L@!d%lGeET&6utQzD! zHmV(StY$uj212Dm)<^x>LrmB3y4Izemc!+2lC#7!VxIRK47#%A|M5oQoqjQaSU81_ zU^E>L$`;dGH`r4qFeR#CQEEh0=`-kM5CmD&;O4;-_gT|osudMnSJc8J6(tzI2PTB| zWECDX?+62gXRi-If}_vodHQoKSz{gO&a@xlB^m3%*T3tgv2n9b+UBK*UcCz49&}w0 z@3>a8yCRBy9QfJeeLlLQqmD)AQXYAk?EBdh+igz3OEm`*Z}RdQJxNY3G#$$2YwIb9 z^2}kkQccOj=_n5MbeHCo%MPHd%#<%WAzuBxavAuko^EU%WXV@&o7R89r0KUeQS8(| z6w6$pH03C^ny-zn$w}|RI{JO3tN^3tWach^X6o0MbS_@dFDXMVzWQ{Jy|=aR9K_aj z;uGSrsfZjq!VcEI?HJzn&vI}mI`G~ov#z+hz0u*81blM)NobkwF7r<&?}g10sB*oG zEW8VDvT{w(2>HPcmkROTTZb#e`c8`Y3r#DBvd-1|<~uK_pYmGsJ$upR$gdJ_MYUy(Tl$%t$R0h% z%S*WeUMxzRDdm6v3VlZRxXx>4@J`Dm+i{<5U|19ExmAuI*FT}G5ZMD=Z9WIc{gz#< z#jb$=sr&x!F+7yTb>FXj)_8b$kjOjR5<>J2sK9%jqdu76(2@}_b8%pU8I z_%!X!?nhv_8>V2npWxls_QfY*esy*OvSk>=C>p1=>1gYc6s1#boE-al6T?XEa$n;_iD3vYoN{q! z>WAK1M+G+qos>IMz_XR735=VonYL96DSqOZ0aFAN;2YNsS*Oej!MlC)0FW6Cz~N=e z(QlAiq+ienOsfoCe{#z%=r;Q+kw{|77Zm-9K|+T5-lfIlsE}Xl%i4?%{fLB0D{KfR zIPE|&$^+z97Ek(WI`ieFoy6)$6-Ev|D(5NNw|Ud1k4a(}qptl0{Y#+HSKjfWU;B-N4pE zWDtYF+%{$!=3Q04Sd3M}=S;}&Ve!+XyOB#wuleu8QJ5i>+g+6>7SAQyue#}f0%f)$ zt5N(%^-tsqHpbShPK6P9V;!bK1ey8OFU!rrCDD3Q;Sh^i*^Paw_<4fi;_J#w1_5=m zyuNR)6uYbVdahCM$tTDB**%DXH=S}4O8su#Xr)`=X6?be`*Ysndy`(q7b7qe%JJV1 zKqkW9&hbw0aj*e@a(aSF{g~|e1!(@vI5r9HXK&F2NGGpn=s3BR3<`%nY;nyLo9rK0 z)iH8o2jL1qzAWyR`Ggo{$kotZN4-0jD~pQ=W>{CRG@SM=(%a;VsszI`#*eYtEZ_gW zCFGy$&sG>7i|U%88V3BGCCr&`L4JEm8QVW)gNn=l_G|l3#>_oom{!D{Ew&97)A>sm z2a5+vYCxM!?tSr?>E5>Q#xh6eO7Y^Ow{$?Tu4v6*z`U(3l_XOX(a?qI6ABh3#foyX z*S7*(Dt63>2o_RN{$FHqM-Q?&toPHiyAI)l&Um-;yJV~$N2t%tjNIpN%?INlU1Fk$ ze8%{nyV8VQEVX?@MM5fng@lCj-@DTM_t7kf9}pMfCd8GIG$c2rLfGdwGkQASWniVf z0A7HOtI%^%TW%VfQ&?M}FvvVU`vUH{z^}~rD(QM(H6&KNkQoVRHE%q{y>c!R9 z9(HS?l~wm7_$eBmi_XXC-XjfdC8f5^-u(FK93!4kTK+}Kb1Q#?!&3$T#f2A!NrACG zEiPWKSB~FBq&{lbxb~w1a8}tx!$4C*g$Oq&fF$7gQ7*$Rqphtumv;!&k-tCXm*a?p zU3)8O1Hm=ZhGw@wAn+v!T@N$5UCblgb!85U3u19(X-7H;3_sC*b?gN3Jz!=Hs4uz! zNsUM>2LnI&40%F2A9t=hC(8++*w2vXwr`%zX`Fbj*tB9dfPR^vM5z8};J>;1HHHhy zZl#YSlJyk#pAQCSHD`Fh_k%w(D`**&PV)DooiQ3xcyEjGHkkV_`_EksHj>l#QO`u{ z30g=_VB!uO*!TeCVj*{v%;1)jf&n=)ChkkJpCv}0Y-G>+)P=|>{l4@#8s+R|x@u}& zzcw=-?JM(D^P5g_9t|jN3*Ftuzd+q1DfD94Y%adXamXyneCbPhq41*RNWzsra3yf- zN6`?kORu;YZ=V(Y5AROh;xs4s)QX#J_=|5BxP)Z6yzoTHwfTg{){Hr^h-lG1+`O4%t{GdVC(zO3w=Qi#nKv+7wAKw#eqGq$w0Dyzck+uk&T}R_#`A4R88eUa9kl`u*%J zFTANm!J$T^YxNPYO&MpV(dG|Iyaji;C=Ahw4ly@!!wqV9sdal*g|XsW1__xi>v`>H z;>p8JOz=*E(v6P9ots}2`y~P{Q;wvZWgqi>ERQUyETdZ64NTAexGO(q zxr;wSf|^mOBLA&ihu*1p+D!-`7yNaPcu0B&d>?f;!gZ;2e6u+_H7@X^M7D3-dz_NO zxM#n#&Av{U>NR=)+sC8d>)LPi8k0DCHa%5LSjJ~l``E_6=)+-hMB7%l^|Jdg>U7K2 z2|0(mUH2N{KX-h)X^M#lGvR5^5>M)!s1@M3EU5Ikr2Z~S1+=U0(|)VxY>)vwt~Y5V z@kLdZLq;J){r{bq^q Date: Fri, 8 Mar 2024 15:54:20 -0800 Subject: [PATCH 13/18] Formatting, cleaning up code --- .pylintrc | 2 + ada_feeding_msgs/msg/FoodOnForkDetection.msg | 10 +- .../food_on_fork_detection.py | 201 +++-- .../food_on_fork_detectors.py | 787 ++++++------------ .../food_on_fork_train_test.py | 111 ++- .../ada_feeding_perception/helpers.py | 93 ++- .../config/food_on_fork_detection.yaml | 5 +- .../model/pointcloud_t_test_detector.npz | Bin 181044 -> 0 bytes 8 files changed, 511 insertions(+), 698 deletions(-) delete mode 100644 ada_feeding_perception/model/pointcloud_t_test_detector.npz diff --git a/.pylintrc b/.pylintrc index 4f111ac1..94e84468 100644 --- a/.pylintrc +++ b/.pylintrc @@ -207,9 +207,11 @@ good-names=a, ps, x, x0, + x1, X, y, y0, + y1, z, u, v, diff --git a/ada_feeding_msgs/msg/FoodOnForkDetection.msg b/ada_feeding_msgs/msg/FoodOnForkDetection.msg index 221f3ac7..d752c038 100644 --- a/ada_feeding_msgs/msg/FoodOnForkDetection.msg +++ b/ada_feeding_msgs/msg/FoodOnForkDetection.msg @@ -3,9 +3,15 @@ # The header for the image the detection corresponds to std_msgs/Header header +# The status of the food-on-fork detector. +int32 status +int32 SUCCESS=1 +int32 ERROR_TOO_FEW_POINTS=-1 +int32 UNKNOWN_ERROR=-99 + # A probability in [0,1] that indicates the likelihood that there is food on the -# fork in the image. Negative values indicate error. +# fork in the image. Only relevant if status == FoodOnForkDetection.SUCCESS float64 probability -# If an error was encountered, this field will contain the error message. +# Contains more details of the result, including any error messages that were encountered string message diff --git a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py index d7ec1960..58ddb01b 100644 --- a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py +++ b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py @@ -33,7 +33,6 @@ class to use and kwargs for the class's constructor; (b) exposes a ROS2 service cv2_image_to_ros_msg, get_img_msg_type, ros_msg_to_cv2_image, - show_3d_scatterplot, ) from .depth_post_processors import ( create_spatial_post_processor, @@ -212,6 +211,9 @@ def read_params( viz_lower_thresh: The lower threshold for declaring FoF in the viz. rgb_image_buffer: The number of RGB images to store at a time for visualization. """ + # pylint: disable=too-many-locals + # There are many parameters to load. + # Read the model_class model_class = self.declare_parameter( "model_class", @@ -408,7 +410,9 @@ def read_params( descriptor=ParameterDescriptor( name="rgb_image_buffer", type=ParameterType.PARAMETER_INTEGER, - description="The number of RGB images to store at a time for visualization. Default: 30", + description=( + "The number of RGB images to store at a time for visualization. Default: 30" + ), read_only=True, ), ) @@ -494,6 +498,94 @@ def camera_callback(self, msg: Image) -> None: with self.img_buffer_lock: self.img_buffer.append(msg) + def visualize_result(self, result: FoodOnForkDetection) -> None: + """ + Annotates the nearest RGB image message with the result and publishes it. + + Parameters + ---------- + result: The result of the food on fork detection. + """ + # Get the RGB image with timestamp closest to the depth image + with self.img_buffer_lock: + img_msg = None + # At the end of this for loop, img_message will be the most + # recent image that is older than the depth image, or the + # oldest image if there are no images older than the depth + # image. + for i, img_msg in enumerate(self.img_buffer): + img_msg_stamp = ( + img_msg.header.stamp.sec + img_msg.header.stamp.nanosec * 1e-9 + ) + result_stamp = ( + result.header.stamp.sec + result.header.stamp.nanosec * 1e-9 + ) + if img_msg_stamp > result_stamp: + if i > 0: + img_msg = self.img_buffer[i - 1] + break + # If img_msg is None, that means we haven't received an RGB image yet + if img_msg is None: + return + + # Convert the RGB image to a cv2 image + img_cv2 = ros_msg_to_cv2_image(img_msg, self.cv_bridge) + + # Get the message to write on the image + proba = result.probability + status = result.status + if proba > self.viz_upper_thresh: + pred = "Food on Fork" + color = (0, 255, 0) + elif ( + proba <= self.viz_lower_thresh + or status == FoodOnForkDetection.ERROR_TOO_FEW_POINTS + ): + pred = "No Food on Fork" + color = (0, 0, 255) + elif status == FoodOnForkDetection.SUCCESS: + pred = "Uncertain (Ask User)" + color = (255, 0, 0) + else: + pred = "Unknown Error" + color = (255, 255, 255) + msg = f"{pred}: {proba:.2f}" + + # Write the message on the top-left corner of the image + cv2.putText( + img_cv2, + msg, + (10, 30), + cv2.FONT_HERSHEY_SIMPLEX, + 1, + color, + 2, + cv2.LINE_AA, + ) + + # Add a rectangular border around the image in the specified color + cv2.rectangle( + img_cv2, + (0, 0), + (img_cv2.shape[1], img_cv2.shape[0]), + color, + 10, + ) + + # Also add a rectangle around the crop box + cv2.rectangle( + img_cv2, + self.crop_top_left, + self.crop_bottom_right, + color, + 2, + ) + + # Publish the image + self.rgb_pub.publish( + cv2_image_to_ros_msg(img_cv2, compress=False, bridge=self.cv_bridge) + ) + def run(self) -> None: """ Runs the FoodOnForkDetection. @@ -520,7 +612,8 @@ def run(self) -> None: continue food_on_fork_detection_msg.header = depth_img_msg.header - # Convert the depth image to a cv2 image + # Convert the depth image to a cv2 image, crop it, and remove depth + # values outside the range of interest depth_img_cv2 = ros_msg_to_cv2_image(depth_img_msg, self.cv_bridge) depth_img_cv2 = depth_img_cv2[ self.crop_top_left[1] : self.crop_bottom_right[1], @@ -536,103 +629,33 @@ def run(self) -> None: # Get the probability that there is food on the fork try: - proba = self.model.predict_proba(X)[0] + proba, status = self.model.predict_proba(X) + proba = proba[0] + status = status[0] food_on_fork_detection_msg.probability = proba - if np.isnan(proba): - food_on_fork_detection_msg.message = "Could not assess food on fork" + food_on_fork_detection_msg.status = status + if status == FoodOnForkDetection.SUCCESS: + food_on_fork_detection_msg.message = ( + "Successfully assessed food on fork" + ) + elif status == FoodOnForkDetection.ERROR_TOO_FEW_POINTS: + food_on_fork_detection_msg.message = ( + "Too few detected points. This typically means there is " + "no food on the fork." + ) # pylint: disable=broad-except # This is necessary because we don't know what exceptions the model # might raise. except Exception as err: err_str = f"Error predicting food on fork: {err}" self.get_logger().error(err_str) - food_on_fork_detection_msg.probability = -1.0 + food_on_fork_detection_msg.probability = np.nan + food_on_fork_detection_msg.status = FoodOnForkDetection.UNKNOWN_ERROR food_on_fork_detection_msg.message = err_str # Visualize the results if self.viz: - # show_3d_scatterplot( - # [self.model.depth_to_pointcloud(depth_img_cv2)], - # colors=[[0, 0, 1]], - # sizes=[5], - # markerstyles=["o"], - # labels=["Test"], - # title="Test Points", - # ) - - # Get the RGB image with timestamp closest to the depth image - with self.img_buffer_lock: - img_msg = None - # At the end of this for loop, img_message will be the most - # recent image that is older than the depth image, or the - # oldest image if there are no images older than the depth - # image. - for i, img_msg in enumerate(self.img_buffer): - img_msg_stamp = ( - img_msg.header.stamp.sec - + img_msg.header.stamp.nanosec * 1e-9 - ) - depth_img_stamp = ( - depth_img_msg.header.stamp.sec - + depth_img_msg.header.stamp.nanosec * 1e-9 - ) - if img_msg_stamp > depth_img_stamp: - if i > 0: - img_msg = self.img_buffer[i - 1] - break - # If img_msg is None, that means we haven't received an RGB image yet - if img_msg is not None: - # Convert the RGB image to a cv2 image - img_cv2 = ros_msg_to_cv2_image(img_msg, self.cv_bridge) - - # Get the message to write on the image - if proba > self.viz_upper_thresh: - pred = "Food on Fork" - color = (0, 255, 0) - elif proba <= self.viz_lower_thresh or np.isnan(proba): - pred = "No Food on Fork" - color = (0, 0, 255) - else: - pred = "Uncertain (Ask User)" - color = (255, 0, 0) - msg = f"{pred}: {proba:.2f}" - - # Write the message on the top-left corner of the image - cv2.putText( - img_cv2, - msg, - (10, 30), - cv2.FONT_HERSHEY_SIMPLEX, - 1, - color, - 2, - cv2.LINE_AA, - ) - - # Add a rectangular border around the image in the specified color - cv2.rectangle( - img_cv2, - (0, 0), - (img_cv2.shape[1], img_cv2.shape[0]), - color, - 10, - ) - - # Also add a rectangle around the crop box - cv2.rectangle( - img_cv2, - self.crop_top_left, - self.crop_bottom_right, - color, - 2, - ) - - # Publish the image - self.rgb_pub.publish( - cv2_image_to_ros_msg( - img_cv2, compress=False, bridge=self.cv_bridge - ) - ) + self.visualize_result(food_on_fork_detection_msg) # Publish the FoodOnForkDetection message self.pub.publish(food_on_fork_detection_msg) diff --git a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py index 01279d2c..44744e45 100644 --- a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py +++ b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py @@ -7,13 +7,12 @@ from enum import Enum import os import time -from typing import Optional, Tuple +from typing import Callable, Optional, Tuple # Third-party imports import numpy as np import numpy.typing as npt from overrides import override -import scipy from sensor_msgs.msg import CameraInfo from sklearn.linear_model import LogisticRegression from sklearn.metrics.pairwise import pairwise_distances @@ -21,7 +20,9 @@ from tf2_ros.buffer import Buffer # Local imports +from ada_feeding_msgs.msg import FoodOnForkDetection from ada_feeding_perception.helpers import ( + depth_img_to_pointcloud, show_3d_scatterplot, show_normalized_depth_img, ) @@ -35,7 +36,6 @@ class FoodOnForkLabel(Enum): NO_FOOD = 0 FOOD = 1 UNSURE = 2 - TOO_FEW_POINTS = 3 class FoodOnForkDetector(ABC): @@ -213,7 +213,9 @@ def load(self, path: str) -> None: """ @abstractmethod - def predict_proba(self, X: npt.NDArray) -> npt.NDArray: + def predict_proba( + self, X: npt.NDArray + ) -> Tuple[npt.NDArray[float], npt.NDArray[int]]: """ Predicts the probability that there is food on the fork for a set of depth images. @@ -225,6 +227,8 @@ def predict_proba(self, X: npt.NDArray) -> npt.NDArray: Returns ------- y: The predicted probabilities that there is food on the fork. + statuses: The status of each prediction. Must be one of the const values + declared in the FoodOnForkDetection message. """ def predict( @@ -233,7 +237,8 @@ def predict( lower_thresh: float, upper_thresh: float, proba: Optional[npt.NDArray] = None, - ) -> npt.NDArray[int]: + statuses: Optional[npt.NDArray[int]] = None, + ) -> Tuple[npt.NDArray[int], npt.NDArray[int]]: """ Predicts whether there is food on the fork for a set of depth images. @@ -242,25 +247,52 @@ def predict( X: The depth images to predict on. lower_thresh: The lower threshold for food on the fork. upper_thresh: The upper threshold for food on the fork. - proba: The predicted probabilities that there is food on the fork. If - None, this function will call predict_proba to get the probabilities. + proba: The predicted probabilities that there is food on the fork. If either + proba or statuses is None, this function will call predict_proba to get + the proba and statuses. + statuses: The status of each prediction. Must be one of the const values + declared in the FoodOnForkDetection message. If either proba or statuses + is None, this function will call predict_proba to get the proba and + statuses. Returns ------- - y: The predicted labels for whether there is food on the fork. + y: The predicted labels for whether there is food on the fork. Must be one + of the values enumerated in FoodOnForkLabel. + statuses: The status of each prediction. Must be one of the const values + declared in the FoodOnForkDetection message. """ - if proba is None: - proba = self.predict_proba(X) - return np.where( - proba < lower_thresh, - FoodOnForkLabel.NO_FOOD.value, + # pylint: disable=too-many-arguments + # These many are fine. + if proba is None or statuses is None: + proba, statuses = self.predict_proba(X) + return ( np.where( - proba > upper_thresh, - FoodOnForkLabel.FOOD.value, - FoodOnForkLabel.UNSURE.value, + proba < lower_thresh, + FoodOnForkLabel.NO_FOOD.value, + np.where( + proba > upper_thresh, + FoodOnForkLabel.FOOD.value, + FoodOnForkLabel.UNSURE.value, + ), ), + statuses, ) + def visualize_img(self, img: npt.NDArray) -> None: + """ + Visualizes a depth image. This function is used for debugging, so it helps + to not only visualize the img, but also subclass-specific information that + can help explain why the img would result in a particular prediction. + + It is acceptable for this function to block until the user closes a window. + + Parameters + ---------- + img: The depth image to visualize. + """ + show_normalized_depth_img(img, wait=True, window_name="img") + class FoodOnForkDummyDetector(FoodOnForkDetector): """ @@ -292,405 +324,21 @@ def load(self, path: str) -> None: pass @override - def predict_proba(self, X: npt.NDArray) -> npt.NDArray: - return np.full(X.shape[0], self.proba) - - -class FoodOnForkPointCloudTTestDetector(FoodOnForkDetector): - """ - A food-on-fork detection algorithm that determines the probability that a - test image and the most similar no-FoF image from the training set are from - the same underlying distribution. The algorithm reasons about images as 3D - point clouds and uses a t-test to compare the distributions of the two - images. - """ - - # pylint: disable=too-many-instance-attributes - # Necessary for this class. - - def __init__( - self, - camera_matrix: npt.NDArray, - min_points: int = 40, - verbose: bool = False, - ) -> None: - """ - Initializes the food-on-fork detection algorithm. - - Parameters - ---------- - camera_matrix: The camera intrinsic matrix (K). - min_points: The minimum number of points in a pointcloud to consider it - for comparison. If a pointcloud has fewer points than this, it will - return a probability of nan (prediction of UNSURE). - verbose: Whether to print debug messages. - """ - # pylint: disable=too-many-arguments - # Necessary for this class. - super().__init__(verbose) - self.camera_matrix = camera_matrix - self.min_points = min_points - - self.no_fof_means = None - self.no_fof_covs = None - self.no_fof_ns = None - - def depth_to_pointcloud(self, depth_image: npt.NDArray) -> npt.NDArray: - """ - Converts a depth image to a point cloud. - - Parameters - ---------- - depth_image: The depth image to convert to a point cloud. - - Returns - ------- - pointcloud: The point cloud representation of the depth image. - """ - # Get the pixel coordinates - pixel_coords = np.mgrid[ - int(self.crop_top_left[1]) : int(self.crop_bottom_right[1]), - int(self.crop_top_left[0]) : int(self.crop_bottom_right[0]), - ] - # Mask out values outside the depth range - mask = depth_image > 0 - depth_values = depth_image[mask] - pixel_coords = pixel_coords[:, mask] - # Convert mm to m - depth_values = np.divide(depth_values, 1000.0) - # Extract the values from the camera matrix - f_x = self.camera_matrix[0] - f_y = self.camera_matrix[4] - c_x = self.camera_matrix[2] - c_y = self.camera_matrix[5] - # Convert to 3D coordinates - pointcloud = np.zeros((depth_values.shape[0], 3)) - pointcloud[:, 0] = np.multiply( - pixel_coords[1] - c_x, np.divide(depth_values, f_x) - ) - pointcloud[:, 1] = np.multiply( - pixel_coords[0] - c_y, np.divide(depth_values, f_y) - ) - pointcloud[:, 2] = depth_values - return pointcloud - - def fit(self, X: npt.NDArray, y: npt.NDArray[int]) -> None: - """ - Converts all the no-FoF images to pointclouds. Gets the mean, covariance, - and num points within each pointcloud and stores them. - - Parameters - ---------- - X: The depth images to train on. - y: The labels for the depth images. - """ - # Get the most up-to-date camera info - if self.camera_info is not None: - self.camera_matrix = np.array(self.camera_info.k) - no_fof_imgs = [] - no_fof_pointclouds = [] - for i, img in enumerate(X): - if y[i] != FoodOnForkLabel.NO_FOOD.value: - continue - pointcloud = self.depth_to_pointcloud(img) - if len(pointcloud) >= self.min_points: - no_fof_imgs.append(img) - no_fof_pointclouds.append(pointcloud) - self.no_fof_means = np.array([np.mean(pc, axis=0) for pc in no_fof_pointclouds]) - self.no_fof_covs = np.array( - [np.cov(pc, rowvar=False, bias=False) for pc in no_fof_pointclouds] - ) - self.no_fof_ns = np.array([pc.shape[0] for pc in no_fof_pointclouds]) - self.no_fof_X = np.array(no_fof_imgs) - - @override - def save(self, path: str) -> str: - if ( - self.no_fof_means is None - or self.no_fof_covs is None - or self.no_fof_ns is None - ): - raise ValueError( - "The model has not been trained yet. Call fit before saving." - ) - # If the path has an extension, remove it. - path = os.path.splitext(path)[0] - np.savez_compressed( - path, - no_fof_means=self.no_fof_means, - no_fof_covs=self.no_fof_covs, - no_fof_ns=self.no_fof_ns, - no_fof_X=self.no_fof_X, - ) - return path + ".npz" - - @override - def load(self, path: str) -> None: - ext = os.path.splitext(path)[1] - if len(ext) == 0: - path = path + ".npz" - params = np.load(path) - self.no_fof_means = params["no_fof_means"] - self.no_fof_covs = params["no_fof_covs"] - self.no_fof_ns = params["no_fof_ns"] - self.no_fof_X = params["no_fof_X"] - - @staticmethod - def hotellings_t_test( - samp1_means: npt.NDArray, - samp1_covs: npt.NDArray, - samp1_ns: npt.NDArray, - samp2_mean: npt.NDArray, - samp2_cov: npt.NDArray, - samp2_n: int, - ) -> npt.NDArray: - """ - Performs a Hotelling's T^2 test to compare the distributions of pairwise - samples where the underlying populations are assumed to be multivariate - Gaussian distributions with unequal covariances. Based on: - https://www.ncss.com/wp-content/themes/ncss/pdf/Procedures/NCSS/Hotellings_Two-Sample_T2.pdf - - Samp2 is expected to be a simple sample. Samp1 can be a list of m samples. - This function computes the p-value pairwise between samp2 and each sample - in samp1. - - Parameters - ---------- - samp1_means: The means of the m samples to compare samp2 with. Shape (m, k) - samp1_covs: The covariances of the m samples to compare samp2 with. Shape (m, k, k) - samp1_ns: The number of points in each of the m samples to compare samp2 with. Shape (m,) - samp2_mean: The mean of the sample to pairwise compare with each sample in samp1. Shape (k,) - samp2_cov: The covariance of the sample to pairwise compare with each sample in samp1. Shape (k, k) - samp2_n: The number of points in the sample to pairwise compare with each sample in samp1. - - Returns - ------- - ps: The p-values of the pairwise tests between samp1 and every sample in samp2. - """ - # pylint: disable=too-many-arguments, too-many-locals - # Necessary for this function. - - # Get sizes - m, k = samp1_means.shape - - # Calculate the S Matrix, of size (m,k,k) - samp1_covs_div_ns = samp1_covs / np.repeat( - samp1_ns, [k**2] * m, axis=0 - ).reshape((m, k, k)) - samp2_cov_div_n = samp2_cov / samp2_n - S = samp1_covs_div_ns + samp2_cov_div_n - - # Calculate the T^2 statistic, of size (m,) - means_diff = samp1_means - samp2_mean # (m,k) - S_inv = np.linalg.inv(S) # (m,k,k) - t_sq = np.einsum( - "ij,ij->i", means_diff, np.einsum("ijk,ik->ij", S_inv, means_diff) - ) # (m,) - - # Define custom ot product and trace functions for this matrix shape - def dot_mkk_mkk(a: npt.NDArray, b: npt.NDArray): - return np.einsum("ijk,ikl->ijl", a, b) - - def trace_mkk(a: npt.NDArray): - return np.einsum("ijj->i", a) - - # Calculate the degrees of freedom, of size (m,) - df1 = np.repeat(k, m) - df2 = np.divide( - trace_mkk(dot_mkk_mkk(S, S)) + trace_mkk(S) ** 2.0, - ( - ( - trace_mkk(dot_mkk_mkk(samp1_covs_div_ns, samp1_covs_div_ns)) - + trace_mkk(samp1_covs_div_ns) ** 2.0 - ) - / (samp1_ns - 1) - ) - + ( - ( - np.trace(np.dot(samp2_cov_div_n, samp2_cov_div_n)) - + np.trace(samp2_cov_div_n) ** 2.0 - ) - / (samp2_n - 1) - ), + def predict_proba( + self, X: npt.NDArray + ) -> Tuple[npt.NDArray[float], npt.NDArray[int]]: + return ( + np.full(X.shape[0], self.proba), + np.full(X.shape[0], FoodOnForkDetection.SUCCESS), ) - # Calculate the corresponding F value - f_vals = np.multiply(np.divide(df2 - df1 + 1, df1 * df2), t_sq) - - # Calculate the p values - ps = 1 - scipy.stats.f.cdf(f_vals, df1, df2 - df1 + 1) - - return ps - - @staticmethod - def test_hotelling_t_test() -> None: - """ - Tests the Hotelling's T^2 test function. - """ - # pylint: disable=too-many-locals - # Necessary for this function. - print("Testing Hotelling's T^2 test function...") - - # Verify that two samples with the same mean and covariance have a p-value - # of 1.0 - m = 100 - k = 2 - n = 100 - samp1_means = np.zeros((m, k)) - cov_magnitude = 1.0 - samp1_covs = np.repeat(np.eye(k).reshape((1, k, k)), m, axis=0) * cov_magnitude - samp1_ns = np.ones(m) * n - samp2_mean = samp1_means[0] - samp2_cov = samp1_covs[0] - samp2_n = samp1_ns[0] - ps = FoodOnForkPointCloudTTestDetector.hotellings_t_test( - samp1_means, samp1_covs, samp1_ns, samp2_mean, samp2_cov, samp2_n - ) - assert np.allclose(ps, 1.0) - - # Verify that two samples with small/large differences in mean relative to the - # covariance have a p-value close to 1.0/0.0 - for div, target_p in [(100, 1.0), (1, 0.0)]: - diff = cov_magnitude / (div) - samp2_mean = np.array([samp1_means[0, 0] - diff, samp1_means[0, 1] + diff]) - ps = FoodOnForkPointCloudTTestDetector.hotellings_t_test( - samp1_means, samp1_covs, samp1_ns, samp2_mean, samp2_cov, samp2_n - ) - assert np.allclose(ps, target_p, atol=0.01) - - # Test with realistic values from pointclouds - samp1_means = np.array( - [ - [0.03519467, 0.05854858, 0.32684903], - ] - ) - samp1_covs = np.array( - [ - [ - [3.10068497e-05, -3.51810972e-06, 7.46688582e-06], - [-3.51810972e-06, 4.12632792e-05, -4.49831451e-05], - [7.46688582e-06, -4.49831451e-05, 5.09933589e-05], - ], - ] - ) - samp1_ns = np.array([1795]) - samp2_mean = np.array([0.03419327, 0.05895837, 0.32637653]) - samp2_cov = np.array( - [ - [7.00616784e-06, 4.17580593e-06, -4.68206042e-06], - [4.17580593e-06, 2.97615922e-05, -3.61209300e-05], - [-4.68206042e-06, -3.61209300e-05, 4.50266659e-05], - ] - ) - samp2_n = 1960 - ps = FoodOnForkPointCloudTTestDetector.hotellings_t_test( - samp1_means, samp1_covs, samp1_ns, samp2_mean, samp2_cov, samp2_n - ) - # Get the mean difference and the determinant of the cov matrix - mean_diff = np.linalg.norm(samp1_means[0] - samp2_mean) - cov_magnitude = np.linalg.norm(samp1_covs[0]) - print(ps) - print(mean_diff, cov_magnitude) - - print("Hotelling's T^2 test function passed!") - - @override - def predict_proba(self, X: npt.NDArray) -> npt.NDArray: - if ( - self.no_fof_means is None - or self.no_fof_covs is None - or self.no_fof_ns is None - ): - raise ValueError( - "The model has not been trained yet. Call fit before predicting." - ) - pointclouds = [self.depth_to_pointcloud(img) for img in X] - probas = [] - n = len(pointclouds) - for i, pointcloud in enumerate(pointclouds): - if self.verbose: - print(f"Predicting on pointcloud {i+1}/{n}") - m = pointcloud.shape[0] - if m < self.min_points: - # probas.append(np.nan) - probas.append(0.0) - continue - # Calculate the T^2 statistic and p-value - pointcloud_mean = np.mean(pointcloud, axis=0) - pointcloud_cov = np.cov(pointcloud, rowvar=False, bias=False) - pointcloud_n = pointcloud.shape[0] - ps = FoodOnForkPointCloudTTestDetector.hotellings_t_test( - self.no_fof_means, - self.no_fof_covs, - self.no_fof_ns, - pointcloud_mean, - pointcloud_cov, - pointcloud_n, - ) - closest_train_img_i = np.argmax(ps) - print(f"pointcloud_mean {pointcloud_mean}") - print(f"pointcloud_cov {pointcloud_cov}") - print(f"pointcloud_n {pointcloud_n}") - print(f"closest_train_img_mean {self.no_fof_means[closest_train_img_i]}") - print(f"closest_train_img_cov {self.no_fof_covs[closest_train_img_i]}") - print(f"closest_train_img_n {self.no_fof_ns[closest_train_img_i]}") - p = ps[closest_train_img_i] - print(f"p {p}") - show_normalized_depth_img(X[i], wait=False, window_name="test_img") - show_normalized_depth_img( - self.no_fof_X[closest_train_img_i], wait=False, window_name="train_img" - ) - - # Sample from the mean and cov of each image to see how well the - # distributional assumptions match. - sampled_pointcloud = np.random.multivariate_normal( - pointcloud_mean, pointcloud_cov, pointcloud_n - ) - closest_train_img_sampled_pointcloud = np.random.multivariate_normal( - self.no_fof_means[closest_train_img_i], - self.no_fof_covs[closest_train_img_i], - self.no_fof_ns[closest_train_img_i], - ) - print("ASDF") - print(pointcloud.tolist()) - print("GHJK") - print(self.depth_to_pointcloud(self.no_fof_X[closest_train_img_i]).tolist()) - show_3d_scatterplot( - [ - # pointcloud, - sampled_pointcloud, - # self.depth_to_pointcloud(self.no_fof_X[closest_train_img_i]), - closest_train_img_sampled_pointcloud, - ], - colors=[ - # [1, 0, 0], - [0, 1, 0], - # [0, 0, 1], - [0, 0, 0], - ], - sizes=[5, 5], # ,5,5], - markerstyles=["o", "x"], # , "o", "x"], - labels=["Test", "Train"], # , "Test Sampled", "Train Sampled"], - title="Test vs Train", - mean_colors=[[0, 0, 1], [0, 0, 0]], # , [0, 0, 1], [0, 0, 0]], - mean_sizes=[20, 20], # , 20, 20], - mean_markerstyles=["^", "^"], # , "^", "^"], - ) - - # p is the probability that the null hypothesis is true, i.e. the - # probability that the pointcloud is from the same distribution as - # the no-FoF pointclouds. Hence, we take 1 - p. - probas.append(1.0 - p) - - return np.array(probas) - class FoodOnForkDistanceToNoFOFDetector(FoodOnForkDetector): """ - A perception algorithm that stores many no FoF points. It then calculates the - average distance between each test point and the nearest no FoF point. It - then trains a classifier to predict the probability of a test point being - FoF based on that distance. + A perception algorithm that stores a representative subset of "no FoF" points. + It then calculates the average distance between each test point and the nearest + no FoF point, and uses a classifier to predict the probability of a + test point being FoF based on that distance. """ def __init__( @@ -707,149 +355,181 @@ def __init__( Parameters ---------- camera_matrix: The camera intrinsic matrix (K). - prop_no_fof_points_to_store: The proportion of no FoF points to store. + prop_no_fof_points_to_store: The proportion of no FoF pointclouds in + the train set to set aside for storing no FoF points. Note that not + all points in these pointclouds are stored; only those that are >= + min_distance m away from the currently stored points. min_points: The minimum number of points in a pointcloud to consider it for comparison. If a pointcloud has fewer points than this, it will return a probability of nan (prediction of UNSURE). - min_distance: The minimum distance between stored no FoF points. + min_distance: The minimum distance (m) between stored no FoF points. verbose: Whether to print debug messages. """ + # pylint: disable=too-many-arguments + # These many are fine. + super().__init__(verbose) self.camera_matrix = camera_matrix self.prop_no_fof_points_to_store = prop_no_fof_points_to_store self.min_points = min_points self.min_distance = min_distance + # The attributes that are stored/loaded by the model self.no_fof_points = None self.clf = None - def depth_to_pointcloud(self, depth_image: npt.NDArray) -> npt.NDArray: + @staticmethod + def distance_between_pointclouds( + pointcloud1: npt.NDArray, + pointcloud2: npt.NDArray, + aggregator: Callable[npt.NDArray, float] = np.mean, + ) -> npt.NDArray: """ - Converts a depth image to a point cloud. + For every point in pointcloud1, gets the minimum distance to points in + pointcloud2, and then aggregates those distances. Note that this is not + symmetric; the order of the pointclouds matters. Parameters ---------- - depth_image: The depth image to convert to a point cloud. + pointcloud1: The test pointcloud. Size (n, k). + pointcloud2: The training pointcloud. Size (m, k). + aggregator: The function to use to aggregate the distances. Should take + in a size (n,) np array and output a float. Default is np.mean. Returns ------- - pointcloud: The point cloud representation of the depth image. + distance: The aggregate of the minimum distances from each point in the test + pointcloud to the nearest point in the training pointcloud. """ - # Get the pixel coordinates - pixel_coords = np.mgrid[ - int(self.crop_top_left[1]) : int(self.crop_bottom_right[1]), - int(self.crop_top_left[0]) : int(self.crop_bottom_right[0]), - ] - # Mask out values outside the depth range - mask = depth_image > 0 - depth_values = depth_image[mask] - pixel_coords = pixel_coords[:, mask] - # Convert mm to m - depth_values = np.divide(depth_values, 1000.0) - # Extract the values from the camera matrix - f_x = self.camera_matrix[0] - f_y = self.camera_matrix[4] - c_x = self.camera_matrix[2] - c_y = self.camera_matrix[5] - # Convert to 3D coordinates - pointcloud = np.zeros((depth_values.shape[0], 3)) - pointcloud[:, 0] = np.multiply( - pixel_coords[1] - c_x, np.divide(depth_values, f_x) - ) - pointcloud[:, 1] = np.multiply( - pixel_coords[0] - c_y, np.divide(depth_values, f_y) - ) - pointcloud[:, 2] = depth_values - return pointcloud + return aggregator(np.min(pairwise_distances(pointcloud1, pointcloud2), axis=1)) - def get_distance_from_train_points(self, pointcloud: npt.NDArray) -> npt.NDArray: + def get_representative_points(self, pointcloud: npt.NDArray) -> npt.NDArray: """ - Gets the average of the minimum distances from each point in the test - pointcloud to the nearest no FoF point in the training set. + Returns a subset of points from the pointcloud such that every point in + pointcloud is no more than min_distance away from one of the representative + points. Parameters ---------- - pointcloud: The test pointcloud. Size (n, 3). + pointcloud: The pointcloud to get representative points from. Size (n, k). Returns ------- - distance: The average of the minimum distances from each point in the test - pointcloud to the nearest no FoF point in the training set. + representative_points: The subset of points from the pointcloud. Size (m, k). """ - return np.mean( - np.min(pairwise_distances(pointcloud, self.no_fof_points), axis=1) - ) + if self.verbose: + print("Getting a subset of representative points") + + # Include the first point + representative_points = pointcloud[0:1, :] + + # Add points that are >= min_distance m away from the stored points + for i in range(1, len(pointcloud)): + if self.verbose: + print(f"Point {i}/{len(pointcloud)}") + contender_point = pointcloud[i] + # Get the distance between the contender point and the representative points + distance = np.min( + np.linalg.norm(representative_points - contender_point, axis=1) + ) + if distance >= self.min_distance: + representative_points = np.vstack( + [representative_points, contender_point] + ) + return representative_points @override def fit(self, X: npt.NDArray, y: npt.NDArray[int]) -> None: - # Convert all images to pointclouds, removing those with too few points + # pylint: disable=too-many-locals + # This is the main logic of the algorithm, so it's okay to have a lot of + # local variables. + + # Get the most up-to-date camera matrix + if self.camera_info is not None: + self.camera_matrix = np.array(self.camera_info.k) + + # Convert all images to pointclouds, excluding those with too few points pointclouds = [] y_pointclouds = [] for i, img in enumerate(X): - pointcloud = self.depth_to_pointcloud(img) + pointcloud = depth_img_to_pointcloud( + img, + *self.crop_top_left, + f_x=self.camera_matrix[0], + f_y=self.camera_matrix[4], + c_x=self.camera_matrix[2], + c_y=self.camera_matrix[5], + ) if len(pointcloud) >= self.min_points: pointclouds.append(pointcloud) y_pointclouds.append(y[i]) + + # Convert to np arrays + # Pointclouds must be dtype object to store arrays of different lengths pointclouds = np.array(pointclouds, dtype=object) y_pointclouds = np.array(y_pointclouds) - print( - f"Got pointclouds, {len(pointclouds)} total, {len(pointclouds[y_pointclouds == FoodOnForkLabel.NO_FOOD.value])} no FoF, {len(pointclouds[y_pointclouds == FoodOnForkLabel.FOOD.value])} FoF" - ) + if self.verbose: + print( + f"Converted {X.shape[0]} depth images to {pointclouds.shape[0]} pointclouds" + ) - # Split the no FoF and FoF pointclouds + # Split the no FoF and FoF pointclouds. The "train set" consists of only + # no FoF pointclouds, and is used to find a representative subset of points + # to store. The "val set" consists of both no FoF and FoF pointclouds, and + # is used to train the classifier. no_fof_pointclouds = pointclouds[y_pointclouds == FoodOnForkLabel.NO_FOOD.value] fof_pointclouds = pointclouds[y_pointclouds == FoodOnForkLabel.FOOD.value] - - # Randomly split the no FoF points no_fof_pointclouds_train, no_fof_pointclouds_val = train_test_split( no_fof_pointclouds, train_size=self.prop_no_fof_points_to_store, random_state=self.seed, ) + val_pointclouds = np.concatenate([no_fof_pointclouds_val, fof_pointclouds]) + val_labels = np.concatenate( + [ + np.zeros((no_fof_pointclouds_val.shape[0],)), + np.ones((fof_pointclouds.shape[0],)), + ] + ) + if self.verbose: + print("Split the no FoF pointclouds into train and val") - # Store the no FoF points - all_no_fof_points = np.concatenate(no_fof_pointclouds_train) - no_fof_points_to_store = all_no_fof_points[0:1, :] - # Add points that are >= min_distance m away from the stored points - for i in range(1, len(all_no_fof_points)): - print(f"{i}/{len(all_no_fof_points)}") - contender_point = all_no_fof_points[i] - # Get the distance between the contender point and th stored points - distance = np.min( - pairwise_distances([contender_point], no_fof_points_to_store), axis=1 - )[0] - if distance >= self.min_distance: - no_fof_points_to_store = np.vstack( - [no_fof_points_to_store, contender_point] - ) - self.no_fof_points = no_fof_points_to_store - - print("Split data, self.no_fof_points.shape", self.no_fof_points.shape) - - # Get the distances from each non-stored point and the stored points - no_fof_distances = [] - for i, pc in enumerate(no_fof_pointclouds_val): - print(f"{i}/{len(no_fof_pointclouds_val)}") - no_fof_distances.append(self.get_distance_from_train_points(pc)) - no_fof_distances = np.array(no_fof_distances) - print(f"Got no_fof_distances, {no_fof_distances}, {no_fof_distances.shape}") - fof_distances = np.array( - [self.get_distance_from_train_points(pc) for pc in fof_pointclouds] + # Store a representative subset of the points + all_no_fof_pointclouds_train = np.concatenate(no_fof_pointclouds_train) + self.no_fof_points = self.get_representative_points( + all_no_fof_pointclouds_train ) - print(f"Got fof_distances {fof_distances}, {fof_distances.shape}") + if self.verbose: + print( + f"Stored a representative subset of {self.no_fof_points.shape[0]}/" + f"{all_no_fof_pointclouds_train.shape[0]} no FoF pointclouds" + ) + + # Get the distances from each point in the "val set" to the stored points + val_distances = [] + for i, pointcloud in enumerate(val_pointclouds): + if self.verbose: + print( + "Computing distance to stored points for val point " + f"{i}/{val_pointclouds.shape[0]}" + ) + val_distances.append( + FoodOnForkDistanceToNoFOFDetector.distance_between_pointclouds( + pointcloud, self.no_fof_points + ) + ) + val_distances = np.array(val_distances) # Train the classifier - classifier_X = np.concatenate([no_fof_distances, fof_distances]) - classifier_y = np.concatenate( - [np.zeros((no_fof_distances.shape[0],)), np.ones((fof_distances.shape[0],))] - ) - print( - f"Training classifier with {classifier_X} {classifier_X.shape} {classifier_y} {classifier_y.shape}" - ) + if self.verbose: + print("Training the classifier") self.clf = LogisticRegression(random_state=self.seed, penalty=None) - self.clf.fit(classifier_X.reshape(-1, 1), classifier_y) - print("Trained classifier") - print(self.clf.coef_, self.clf.intercept_) + self.clf.fit(val_distances.reshape(-1, 1), val_labels) + if self.verbose: + print( + f"Trained the classifier, with coeff {self.clf.coef_} and " + f"intercept {self.clf.intercept_}" + ) @override def save(self, path: str) -> str: @@ -876,65 +556,80 @@ def load(self, path: str) -> None: self.clf = params["clf"][0] @override - def predict_proba(self, X: npt.NDArray) -> npt.NDArray: + def predict_proba( + self, X: npt.NDArray + ) -> Tuple[npt.NDArray[float], npt.NDArray[int]]: probas = [] + statuses = [] - # show_3d_scatterplot( - # [self.no_fof_points], - # colors=[[0, 0, 1]], - # sizes=[5], - # markerstyles=["o"], - # labels=["Train"], - # title="Train Points", - # ) - # raise Exception() - - # Convert all images to pointclouds, removing those with too few points - num_images_no_points = 0 + # Get the prediction per image. + print_every_n = 50 for i, img in enumerate(X): - start_time = time.time() - pointcloud = self.depth_to_pointcloud(img) + if self.verbose and i % print_every_n == 0: + start_time = time.time() + + # Convert the image to a pointcloud + pointcloud = depth_img_to_pointcloud( + img, + *self.crop_top_left, + f_x=self.camera_matrix[0], + f_y=self.camera_matrix[4], + c_x=self.camera_matrix[2], + c_y=self.camera_matrix[5], + ) + + # If there are enough points, use the classifier to predict the probability + # of food on the fork. Else, return an error status if len(pointcloud) >= self.min_points: - distance = self.get_distance_from_train_points(pointcloud) - # print("distance", distance) + distance = ( + FoodOnForkDistanceToNoFOFDetector.distance_between_pointclouds( + pointcloud, self.no_fof_points + ) + ) proba = self.clf.predict_proba(np.array([[distance]]))[0, 1] - # print(f"proba {proba}") probas.append(proba) - if i % 50 == 0: + statuses.append(FoodOnForkDetection.SUCCESS) + if self.verbose and i % print_every_n == 0: print( - f"Predicted on pointcloud {i+1}/{len(X)} in {time.time() - start_time} seconds" + f"Predicted on pointcloud {i}/{X.shape[0]} in " + f"{time.time() - start_time} seconds" ) else: probas.append(np.nan) - num_images_no_points += 1 + statuses.append(FoodOnForkDetection.ERROR_TOO_FEW_POINTS) - print(f"num_images_no_points {num_images_no_points}") - return np.array(probas) + return np.array(probas), np.array(statuses) @override - def predict( - self, - X: npt.NDArray, - lower_thresh: float, - upper_thresh: float, - proba: Optional[npt.NDArray] = None, - ) -> npt.NDArray[int]: - if proba is None: - proba = self.predict_proba(X) - return np.where( - np.isnan(proba), - FoodOnForkLabel.TOO_FEW_POINTS.value, - np.where( - proba <= lower_thresh, - FoodOnForkLabel.NO_FOOD.value, - np.where( - proba > upper_thresh, - FoodOnForkLabel.FOOD.value, - FoodOnForkLabel.UNSURE.value, - ), - ), + def visualize_img(self, img: npt.NDArray) -> None: + # Convert the image to a pointcloud + pointclouds = [ + depth_img_to_pointcloud( + img, + *self.crop_top_left, + f_x=self.camera_matrix[0], + f_y=self.camera_matrix[4], + c_x=self.camera_matrix[2], + c_y=self.camera_matrix[5], + ) + ] + colors = [[0, 0, 1]] + sizes = [5] + markerstyles = ["o"] + labels = ["Test"] + + if self.no_fof_points is not None: + pointclouds.append(self.no_fof_points) + colors.append([1, 0, 0]) + sizes.append(5) + markerstyles.append("^") + labels.append("Train") + + show_3d_scatterplot( + pointclouds, + colors, + sizes, + markerstyles, + labels, + title="Img vs. Stored No FoF Points", ) - - -if __name__ == "__main__": - FoodOnForkPointCloudTTestDetector.test_hotelling_t_test() diff --git a/ada_feeding_perception/ada_feeding_perception/food_on_fork_train_test.py b/ada_feeding_perception/ada_feeding_perception/food_on_fork_train_test.py index 62a8d1e5..42ac52a5 100644 --- a/ada_feeding_perception/ada_feeding_perception/food_on_fork_train_test.py +++ b/ada_feeding_perception/ada_feeding_perception/food_on_fork_train_test.py @@ -1,6 +1,9 @@ """ This script takes in a variety of command line arguments and then trains and test a -FoodOnForkDetector as configured by the arguments. +FoodOnForkDetector as configured by the arguments. Note that although this is not +a ROS node, it relies on helper functions and types in ada_feeding, ada_feeding_msgs, +and ada_feeding_perception packages. The easiest way to access those is to build +your workspace and source it, before running this script. """ # Standard Imports @@ -32,10 +35,7 @@ FoodOnForkDetector, FoodOnForkLabel, ) -from ada_feeding_perception.helpers import ( - ros_msg_to_cv2_image, - show_normalized_depth_img, -) +from ada_feeding_perception.helpers import ros_msg_to_cv2_image from ada_feeding_perception.depth_post_processors import ( create_spatial_post_processor, create_temporal_post_processor, @@ -63,8 +63,7 @@ def read_args() -> argparse.Namespace: help=( "A JSON-encoded string where keys are an arbitrary model ID and " "values are the class names to use for that model. e.g., " - '{"dummy_detector": "ada_feeding_perception.food_on_fork_detectors.FoodOnForkDummyDetector", ' - '"t_test_detector": "ada_feeding_perception.food_on_fork_detectors.FoodOnForkTTestDetector"}' + '{"dummy_detector": "ada_feeding_perception.food_on_fork_detectors.FoodOnForkDummyDetector"}' ), required=True, ) @@ -85,7 +84,8 @@ def read_args() -> argparse.Namespace: type=int, help=( "The size of the temporal window to use for post-processing. If unset, " - "no temporal post-processing will be done." + "no temporal post-processing will be done. See depth_post_processors.py " + "for more details." ), ) parser.add_argument( @@ -94,7 +94,8 @@ def read_args() -> argparse.Namespace: type=int, help=( "The number of pixels to use for the spatial post-processing. If unset, " - "no spatial post-processing will be done." + "no spatial post-processing will be done. See depth_post_processors.py " + "for more details." ), ) @@ -105,14 +106,14 @@ def read_args() -> argparse.Namespace: default=(0, 0), type=int, nargs="+", - help=("The top-left corner of the crop rectangle. The format is (x, y)."), + help=("The top-left corner of the crop rectangle. The format is (u, v)."), ) parser.add_argument( "--crop-bottom-right", default=(640, 480), type=int, nargs="+", - help=("The bottom-right corner of the crop rectangle. The format is (x, y)."), + help=("The bottom-right corner of the crop rectangle. The format is (u, v)."), ) parser.add_argument( "--depth-min-mm", @@ -154,10 +155,10 @@ def read_args() -> argparse.Namespace: help=("The topic to use for camera info."), ) parser.add_argument( - "--include-motion", + "--exclude-motion", default=False, action="store_true", - help=("If set, include images when the robot arm is moving in the dataset."), + help=("If set, exclude images when the robot arm is moving in the dataset."), ) parser.add_argument( "--rosbags-select", @@ -236,14 +237,27 @@ def read_args() -> argparse.Namespace: type=int, help=( "The maximum number of evaluations to perform. If None, all evaluations " - "will be performed. Typically used when debugging a detector" + "will be performed. Typically used when debugging a detector." ), ) parser.add_argument( - "--viz", + "--viz-rosbags", default=False, action="store_true", - help="If set, visualize images during the process", + help=( + "If set, render the color images in the rosbag and the label while " + "loading the data. This is useful for find-tuning ground-truth labels." + ), + ) + parser.add_argument( + "--viz-evaluation", + default=False, + action="store_true", + help=( + "If set, visualize all images where the model was wrong. This is useful " + "for debugging, but note that it will block after every wrong prediction " + "until the visualization window is closed." + ), ) return parser.parse_args() @@ -258,9 +272,9 @@ def load_data( crop_bottom_right: Tuple[int, int], depth_min_mm: int, depth_max_mm: int, - include_motion: bool, - rosbags_select: List[str] = [], - rosbags_skip: List[str] = [], + exclude_motion: bool, + rosbags_select: Optional[List[str]] = None, + rosbags_skip: Optional[List[str]] = None, temporal_window_size: Optional[int] = None, spatial_num_pixels: Optional[int] = None, viz: bool = False, @@ -286,8 +300,8 @@ def load_data( The top-left and bottom-right corners of the crop rectangle. depth_min_mm, depth_max_mm: int The minimum and maximum depth values to consider in the depth images. - include_motion: bool - If True, include images when the robot arm is moving in the dataset. + exclude_motion: bool + If True, exclude images when the robot arm is moving in the dataset. rosbags_select: List[str], optional If set, only rosbags in this list will be included rosbags_skip: List[str], optional @@ -313,6 +327,13 @@ def load_data( """ # pylint: disable=too-many-locals, too-many-arguments, too-many-branches, too-many-statements # Okay since we want to make it a flexible method. + print("Loading data...") + + # Replace the optional arguments + if rosbags_select is None: + rosbags_select = [] + if rosbags_skip is None: + rosbags_skip = [] # Set up the post-processors bridge = CvBridge() @@ -384,7 +405,7 @@ def load_data( ): i += 1 arm_moving = annotations[i][2] - if not include_motion and arm_moving: + if exclude_motion and arm_moving: # Skip images when the robot arm is moving continue if annotations[i][1] == FoodOnForkLabel.FOOD.value: @@ -414,9 +435,9 @@ def load_data( elif connection.topic == camera_info_topic and camera_info is None: camera_info = deserialize_cdr(rawdata, connection.msgtype) # RGB Image - elif connection.topic == color_topic and viz: + elif viz and connection.topic == color_topic: msg = deserialize_cdr(rawdata, connection.msgtype) - print((timestamp - start_time) / 10.0**9) + print(f"Elapsed Time: {(timestamp - start_time) / 10.0**9}") img = ros_msg_to_cv2_image(msg, bridge) # A box around the forktip x0, y0 = crop_top_left @@ -436,6 +457,7 @@ def load_data( X = X[:j] y = y[:j] + print(f"Done loading data. {X.shape[0]} depth images loaded.") return X, y, camera_info @@ -467,6 +489,8 @@ def load_models( models: dict A dictionary where keys are the model ID and values are the model instances. """ + print("Loading models...") + # Parse the JSON strings model_classes = json.loads(model_classes) model_kwargs = json.loads(model_kwargs) @@ -485,6 +509,7 @@ def load_models( models[model_id].crop_top_left = crop_top_left models[model_id].crop_bottom_right = crop_bottom_right + print(f"Done loading models with IDs {list(model_classes.keys())}.") return models @@ -509,7 +534,7 @@ def train_models( absolute_model_dir = os.path.join(os.path.dirname(__file__), model_dir) for model_id, model in models.items(): - print(f"Training model {model_id}...", end="") + print(f"Training model {model_id}...") model.fit(X, y) save_path = model.save(os.path.join(absolute_model_dir, model_id)) print(f"Done. Saved to '{save_path}'.") @@ -574,6 +599,7 @@ def evaluate_models( ] results_txt = "" for model_id, model in models.items(): + print(f"Evaluating models {model_id}...") # First, load the model load_path = os.path.join(absolute_model_dir, model_id) print(f"Loading model {model_id} from {load_path}...", end="") @@ -599,21 +625,10 @@ def evaluate_models( if viz: # Visualize all images where the model was wrong - last_0_0 = None for i in range(y_pred_proba.shape[0]): if y[i] != y_pred[i]: - print(f"y_true: {y[i]}, y_pred: {y_pred[i]}") - show_normalized_depth_img( - X[i], wait=False, window_name="misclassified_img" - ) - if last_0_0 is not None: - show_normalized_depth_img( - X[last_0_0], - wait=False, - window_name="last_correct_no_fof_img", - ) - if y[i] == 0 and y_pred[i] == 0: - last_0_0 = i + print(f"Mispredicted: y_true: {y[i]}, y_pred: {y_pred[i]}") + model.visualize_img(X[i]) # Compute the summary statistics txt = textwrap.indent(f"Results on {label} dataset:\n", " " * 4) @@ -632,6 +647,7 @@ def evaluate_models( print(txt, end="") results_txt += "\n" + print(f"Done evaluating model {model_id}.") # Save the results results_df = pd.DataFrame(results_df, columns=results_df_columns) @@ -658,6 +674,8 @@ def main() -> None: args = read_args() # Load the dataset + print("*" * 80) + print(f"Timestamp: {time.strftime('%Y_%m_%d_%H_%M_%S')}") X, y, camera_info = load_data( args.data_dir, args.depth_topic, @@ -667,16 +685,18 @@ def main() -> None: args.crop_bottom_right, args.depth_min_mm, args.depth_max_mm, - args.include_motion, + args.exclude_motion, args.rosbags_select, args.rosbags_skip, args.temporal_window_size, args.spatial_num_pixels, - # viz=args.viz, + viz=args.viz_rosbags, ) - print("X.shape", X.shape, "y.shape", y.shape) # Do a train-test split of the dataset + print("*" * 80) + print(f"Timestamp: {time.strftime('%Y_%m_%d_%H_%M_%S')}") + print("Splitting the dataset...") if args.seed is None: seed = int(time.time()) else: @@ -684,8 +704,11 @@ def main() -> None: train_X, test_X, train_y, test_y = train_test_split( X, y, train_size=args.train_set_size, random_state=seed ) + print(f"Done. Train size: {train_X.shape[0]}, Test size: {test_X.shape[0]}") # Load the models + print("*" * 80) + print(f"Timestamp: {time.strftime('%Y_%m_%d_%H_%M_%S')}") models = load_models( args.model_classes, args.model_kwargs, @@ -698,9 +721,13 @@ def main() -> None: # Train the model if not args.no_train: + print("*" * 80) + print(f"Timestamp: {time.strftime('%Y_%m_%d_%H_%M_%S')}") train_models(models, train_X, train_y, args.model_dir) # Evaluate the model + print("*" * 80) + print(f"Timestamp: {time.strftime('%Y_%m_%d_%H_%M_%S')}") evaluate_models( models, train_X, @@ -712,7 +739,7 @@ def main() -> None: args.lower_thresh, args.upper_thresh, args.max_eval_n, - viz=args.viz, + viz=args.viz_evaluation, ) diff --git a/ada_feeding_perception/ada_feeding_perception/helpers.py b/ada_feeding_perception/ada_feeding_perception/helpers.py index 61f242f6..6e334ad2 100644 --- a/ada_feeding_perception/ada_feeding_perception/helpers.py +++ b/ada_feeding_perception/ada_feeding_perception/helpers.py @@ -81,6 +81,9 @@ def show_3d_scatterplot( title: str The title of the plot. """ + # pylint: disable=too-many-arguments, too-many-locals + # This is meant to be a flexible function to help with debugging. + # Check that the inputs are valid assert ( len(pointclouds) @@ -102,7 +105,7 @@ def show_3d_scatterplot( configs = [pointclouds, colors, sizes, markerstyles, labels] if mean_colors is not None: configs += [mean_colors, mean_sizes, mean_markerstyles] - for i, config in enumerate(zip(*configs)): + for config in zip(*configs): pointcloud = config[0] color = config[1] size = config[2] @@ -143,6 +146,67 @@ def show_3d_scatterplot( plt.show() +def depth_img_to_pointcloud( + depth_image: npt.NDArray, + u_offset: int, + v_offset: int, + f_x: float, + f_y: float, + c_x: float, + c_y: float, + unit_conversion: float = 1000.0, +) -> npt.NDArray: + """ + Converts a depth image to a point cloud. + + Parameters + ---------- + depth_image: The depth image to convert to a point cloud. + u_offset: An offset to add to the column index of every pixel in the depth + image. This is useful if the depth image was cropped. + v_offset: An offset to add to the row index of every pixel in the depth + image. This is useful if the depth image was cropped. + f_x: The focal length of the camera in the x direction, using the pinhole + camera model. + f_y: The focal length of the camera in the y direction, using the pinhole + camera model. + c_x: The x-coordinate of the principal point of the camera, using the pinhole + camera model. + c_y: The y-coordinate of the principal point of the camera, using the pinhole + camera model. + unit_conversion: The depth values are divided by this constant. Defaults to 1000, + as RealSense returns depth in mm, but we want the pointcloud in m. + + Returns + ------- + pointcloud: The point cloud representation of the depth image. + """ + # pylint: disable=too-many-arguments + # Although we could reduce it by passing in a camera matrix, I prefer to + # keep the arguments explicit. + + # Get the pixel coordinates + pixel_coords = np.mgrid[: depth_image.shape[0], : depth_image.shape[1]] + pixel_coords[0] += v_offset + pixel_coords[1] += u_offset + + # Mask out values outside the depth range + mask = depth_image > 0 + depth_values = depth_image[mask] + pixel_coords = pixel_coords[:, mask] + + # Convert units (e.g., mm to m) + depth_values = np.divide(depth_values, unit_conversion) + + # Convert to 3D coordinates + pointcloud = np.zeros((depth_values.shape[0], 3)) + pointcloud[:, 0] = np.multiply(pixel_coords[1] - c_x, np.divide(depth_values, f_x)) + pointcloud[:, 1] = np.multiply(pixel_coords[0] - c_y, np.divide(depth_values, f_y)) + pointcloud[:, 2] = depth_values + + return pointcloud + + def ros_msg_to_cv2_image( msg: Union[Image, rImage, CompressedImage, rCompressedImage], bridge: Optional[CvBridge] = None, @@ -164,21 +228,20 @@ def ros_msg_to_cv2_image( is a ROS Image message. If `bridge` is None, a new CvBridge will be created. """ - imageTypes = [Image] - compressedImageTypes = [CompressedImage] + image_types = [Image] + compressed_image_types = [CompressedImage] try: - imageTypes.append(rImage) - compressedImageTypes.append(rCompressedImage) + image_types.append(rImage) + compressed_image_types.append(rCompressedImage) except NameError as _: # This only happens if rosbags wasn't imported, which is logged above. pass - if isinstance(msg, tuple(imageTypes)): - if bridge is None: - bridge = CvBridge() + if bridge is None: + bridge = CvBridge() + if isinstance(msg, tuple(image_types)): return bridge.imgmsg_to_cv2(msg, desired_encoding="passthrough") - if isinstance(msg, tuple(compressedImageTypes)): - # TODO: This should use bridge as well - return cv2.imdecode(np.frombuffer(msg.data, np.uint8), cv2.IMREAD_UNCHANGED) + if isinstance(msg, tuple(compressed_image_types)): + return bridge.compressed_imgmsg_to_cv2(msg, desired_encoding="passthrough") raise ValueError("msg must be a ROS Image or CompressedImage") @@ -210,13 +273,7 @@ def cv2_image_to_ros_msg( if bridge is None: bridge = CvBridge() if compress: - success, compressed_image = cv2.imencode(".jpg", image) - if success: - return CompressedImage( - format="jpeg", - data=compressed_image.tostring(), - ) - raise RuntimeError("Failed to compress image") + return bridge.cv2_to_compressed_imgmsg(image, dst_format="jpeg") # If we get here, we're not compressing the image return bridge.cv2_to_imgmsg(image, encoding=encoding) diff --git a/ada_feeding_perception/config/food_on_fork_detection.yaml b/ada_feeding_perception/config/food_on_fork_detection.yaml index d21c6ee6..49275769 100644 --- a/ada_feeding_perception/config/food_on_fork_detection.yaml +++ b/ada_feeding_perception/config/food_on_fork_detection.yaml @@ -28,4 +28,7 @@ food_on_fork_detection: spatial_num_pixels: 10 # Whether to visualize the output of the detector - viz: True \ No newline at end of file + viz: True + # The upper and lower thresholds for the visualization to say there is(n't) food-on-fork + viz_lower_thresh: 0.5 + viz_upper_thresh: 0.5 \ No newline at end of file diff --git a/ada_feeding_perception/model/pointcloud_t_test_detector.npz b/ada_feeding_perception/model/pointcloud_t_test_detector.npz deleted file mode 100644 index f5f87247ab8093db60c7317dd2bc7cd85405def7..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 181044 zcmY&fWmH>Tu*E6vQruliaW7DyxVx7k#odFH;#!KkySoQ>r?>=n4-lM}@6UVdowf2K zxp&q*bN0xdxf4|dcm#YH7?=;x4>gPkvR6_874#b&3=B35K8%B-iKU~ZiM@rHgDZ!F zlQ%5%*Z;2lxBk2Dzm=s25np(J=9B-HXQxNaEPp@7PWSOr^Bd1M?Uj%8(%MB9n(7ft zf-;!H3Zphu9|`_sYDC&4Y00eYx<0?5m;k-Svf~ab6Kl$FN>>k>8iF4NU@2x&Ro~|w+c^h+R7T1KI({w?{1$RMgkqR=jYTCv^6vn zx~X2@U$)~QQCWYvJS|i%L%`@_Y3l-p%fKu+w{^Rg*sGIVbXX>m?QJ>CF#6FxH%OJ z4gG3W@6mgY64ngvBp4(N|eyo`qp-jOkC=K6VNL`Xxpm>A`j6KXl@Jl-4?#z{! zTx{Q{x=}(eeb;Ci7LP+sUJMvunY6wV%qxtiJmsw1Rib=~a&JEKN#;@rTV-N8e;9>9 zM7c{KVr8cCF~2zc`Ev2xtz@V4uo0z^Fidz2=+|yY_BO*U?=~7!c^?R*MCK9NM_`V3 zeq4WaLn1e1OT^Hv%MHk7@;I*?lGo1Jo(J zEU@^51)6$j6KJ0;b(g!dH4(>g^X@T2SWw9@x(}y<1k|{bwX*tz<}rAdwGps;h88CR z)F?oYe>^M6K`W~ao^L(uaF(b12BD60)XHt$rouaUp=o8WsHY-l_KyYEG#E(t&T9f$ zrjla;BC{$8OxUDi+)cjGn9o(&ci+AP{j8AE4LI;-?jGxJCC;9c8-HbBU6aR_QsDqi z;il@8_8PZ5V=kvpD|-b@Y#QrIsKwaRzgu%WOr01E`;l;g-hcCA{Iq3Kt;kH)=l>Q4 z@8Cnjc@2<_Aew$-!*;qeZHV2aBhS_cD`)jQyJf$%MAO5)on^)uUZ-F>3b?kMm;+^m zY4q|!0+G>#%GCr+Ncl@hL~90wmb`}2u<$#PEkOr#umJMt zj7_i`ac#NK4binz^4reFr=3nufi_XB-M!mAGK;Op*7jck@#u&iZ^m{d9`h1&rC(Br zPW?EH>P+yS@2DpH^OPeIHoVX0rR86QxR_Q{*su7!{j5!V$}>2~et6Z2JlxP2vLmO4}Z$-KHWsu{?_!~BvF`hJ3JaMZo$*iAOg}PbO zJxM5-Nwnq=Y{v`p>v=LfHvwx;Ay2$Td-Jwyu~SzB#m##Bdu4iwk}|({$I9ts;uUoN zy%u4Fnmo!Ku&KXuEAD2?AJ5Ws36Vm;M^4Sl{NRfXE&dDIw~UYgjJj>Z^{#fa?k7g_ z7mhcKj%dI-_=U)z*B#Ewux42dpE@t@PW+f$faq9;enxLEu7^~ExrY-ZOns+ zy0{L&B{J{^j#p*|hP<4c{Wj%##z*5oC;k)S*F<<%nJba2ohnV<%7BCt)g0Pv1<(=b z8ONK!$tJD=esR*zPh1D21c%V|!y|cDBzwAXa!i(tq;=oH6^+*P{pXW07L{4X(qKLD zof$ZtLv^Yr`?l9ez!4SpE|}Yh^XjcH?dN4X64IHMXVJwi zFPw3;^GP^94fU6O@TBSl>x-;>)tm-PWec~#e1S}``CGf>3WuV#!Gl-)FTZE*MEfkx z#qF6upHliE^MDrzFy`L7o%TYJbLOyWFvd{l!&IWNkRcCgL%8);>RxJa;cEBSAcs$`rwmb;AEBmWf>pKl28fGS4g8(=5^w(dJ>b=3_!0kEeakWhh zr%D>IGIK9{YspEj5BkXDC%x%)UuWD6duPq9;QnAV5HQWlZXoR!u=A!_#IQsC`XOaf zd4M_~^}vQ<>Jp(N6_sf5(AOe07UpCSWyp*kXTTu9Do<(<04HhvI?wqjn_+*tKn3*a zi>`(G74yxu0l3f-z7qV!Yc+%CtR`xCo6+?cVWKSE@u!%4Um7UMc-6fW&7HCjdCGhP z-?%LyoboZoUM8T9v;Nm+xq>eLvCX-cQ6^-oxgHdDm1$(^yY#>V>&`gVc+WFO4LSOL zp`F=LGnD-NjKg@w8fV%6fqW5(fkohZri4i%=GQhWn0=MWAE5&p-&zyX9Cn8S3mUb8 zs+Mb#m-$8$A#SOciTZ33hI+<}#?(Px94KHR;yCx(!@Th%Ghp>b0;%M z5h@!U?Zq$-s#5QG(hup8f1QNs)oL!#;K!twe(=eu<(_NA+^&cT z3G}sh@TS(VE*y?g`lBXt-XJSM=7T(q*Z-kUqw(+-JM6ZR*{JHc^!WksIa;f^rt_>Hv2l=RS0>_cm)=IUPYm!#0o&-wp{xHI$|ADNp#pTRtQk%Ww zw`ejfdRt#w-81Yxrej=w=P)-e(YWgtHV19A&y5+@irJoJTt;Bc=JB+g4%mvAbWv-! zz`N_UB|SXCfg>G*&nf^faSa| z-0XD%H}%uw>SaOy_RuArW1nS&TVF5_7S#&H`hovhK_M6+gWj^5vHN}XJ@OHC4;);! zt6~iPb9FZkTKP7h(xQ`06Tmk0oI6>DHxf2)+fn^@Bxe@upV+07OwRjphp{&eO1&~t zv=pxZr;D#TUo^IU?y1J8fhc?ABS|Nlir0=5jMd^v?+x*Qpsc47=4Q&X&&rS4 z9GE6|X$ducIj6IPl{+|Z=DQx^j7cHXZ)!KVG`>e){L0e~2K*iqK3hyDsct7(#kJI; zVK^9Z?l7vBi2RUm@ZVWK_iR+t|MI5SA!lNax|=ywy!jr~x@wWck8u>Bc+xKHXeJWp z8ok7uZ!FTheG@MIZeCi2Gacr>_V$xelO0?R@t9ST3s=z!j%6n4r z-s5AI`^fYkc@Hit=eQ5{>v!MvI1vUb$P1h~Y>*Oy?Q1W6-TdiJr~(}9Z&%x3A!wV` zu+qx6kN3jD;D>8~m}u0mLmiY)QPXWSq0h4lzGG`7nY7J>W^4RMQUCCa?Y%#K`(+Uu zxoHyJU=AK3ytCNsRv=B45TVNvp`VHK`cx)lOC0gM8kwUciaRpxcysAqYMO1yXyuaMpSIT|rdLxM7 z)5nEQN6Y>Zogw>3^XVBN;(9A7VdS;1-9>JDes!1bJXaB}QV&?zlV(*-c2Qi^k~8p5 zT$7`LunjdjiN&+Juk*#^PDC`sJ4(9p_WM zv^byJnYIRS#6Z9%<2xnWdiG_lvFURX_;5vv0!R z%OJ8R`|J$~S;yR*6|Rbk+RlJ7&JF%p2(9U-6)tm5A{5a>!5yA>EA89L?$qBtYVLk! zP8b&&Ar@1U0oVR_b=kIU;bBAnrn@SfvDA+oIMgLY!a~Ju?#Bv$Nng)>KjI_V!|cjn zzcQ8l667?G^-toCuOObqaecQCojpU1(*^fVvpNi0HLHGO`WOxcIo%FDdskSBb3f|# z50MHatPB_5-yJ$rg!f3?9S@DQ*5JNy#x8c>+IJ)mYR>R0dvk9(NlhaPS1lPyCppMh-~ z@sXDxq1xr^2Uu7TQVsb^M>fJqTjiN^^!q-zP+RTA;ZfKsOHky}gRiS8@PQf4i;Zru8*tez6|s5nSXtyDok!=v$5u{h{-{#xsV7G8+^f@lX`xL!LQ=V;tr6 z{Qbpc8xI+gj7H~&LhjTQ8{1F7@bmn$$I&R=PUpJ32wQ}|`dv^|uFwGieW|_Aa#W`b3OX!C-)WE?1RzY3Ad`pF#nuYa-Q<-kB}4J zuE*oPn`n}1x@J>NmBgK9yIH=OuU%IzClYp6gi!asR`;b5>3cm?eK?5l(n{ zK?4IiXTcIw2fhwjl5_YcDc`<4d^?jB`axi9Z8_}eM(z{xqYl%2y?B(rcIv?Smp*zW z{Q0@yoRk2(7rx&_fWruUve8&3ky4teH|XcQ^zEU|kfYbe48MAY&_VKH3-zVmKjzzo zg7t;C>|7O(RtLXM;!{@vGpR*Y23T8yHv!w$KdOM?Pf~EsVwQuu-Msj(D(4;a9Jh6m zZ4T7zx?up%1~C0JwyAfn2r~&_H{qy!(IPv~0Y$k=(&V*Uz}^zudm^11@GST5G=?Ab z6wFrIL)+K2hzw|QnCSf;0*6$2G6|WJ?*4p$s#`Y^CajHFufM>Z`}SujO7a#3&FbPJ zLn?<-{-%3lF#MB<@)tJUK9JN znY&ZJnCGh;8~URinAC13WMMO|hL zLwvu3zLtsasNYvlZnGoFU(t%b2h_ms|L#4vg{1ZHJ8QZL-++t524hMRt*@*``)Y6T z@zTZj_(i{NTngT*b-&|JH4U|exc>+^R*uX}LMa@G4f+JD zCSPh=2;J#M`Sa;;cPo$8#K*qoB#)-VGc`y2PSjM+V;vzS$UD?UbfP@g#AeoW&p=Qr zb4VGrLGl~FQv^$j#zfuo5wFYiWtqmtH;jO3{YQWHKfHBsFXT?(=D?5=R z@cK2cKH=snC(dmJ0rT$NZx898q@rV5TNu)LqDRd^o=oLp0f7+vq$welVVo=1a5b}t zR*YFD_Qw8pEit#H)*%JhsUTKm!dCv-2lb1Xt=GaCSM3np016_U4NbqWt(ysOU+0CL z(DOJs0Mq@>yT%@Lbk+G(dcc!y!gAf(fqMuroVrM+pVCS4bvwE-4tUL<?Tx&f5 zc=W>n@Fj<~-o%J=n;O=toYJ3PGKcJ{i)(`T*}D7bpe<}u^P&0k@;6Vcov^0HA?$0g zBkxil)lEQ63-A5poZ(STR>hYWGjzW;d4-brz_qWt;I^1fmbt36`EdV&vIbLWitL)K zZ!44Fpuh~FVV>2$a@gu-yo%-Ddjc1LI%c@|rd;)C9+G6)a$Y*Qo$JGI+*&oCrbe20 zm7P%$?3yTZdsCX*S^ zDv{mmM7xV*mnUlrXTTG#We8KeJ@&dK`!G>j-0w}br5NL;a|&mTGV_REcj0w@H+~q2 z^K!bq?#%H{vGYcaQ>M*hpCB(M^QZ1>A09}}Vu@%0m2vCaFyRXNEvd+`^l-{^{XuJe z<}*1QU36blGg?B=x*on}^qZ@yfPnw1iF znhLt)2L`#=cs$t(A%~3b`$Z}TUk-#ZNdbFYF%80QO2sIta({KtWZwReJ})|iyWR$K ztC?C*zzX$LJ6}*eWwwAy#%CBw1v}a|`~4c$^+Psy{3Y%xfvqo|rVF(}vjTfD)p2Vn z9Ky6Ud^rTEQaP5693@&YFRI3=>^JxTWlKA=z)w5dAf7Z$Ky)C&$Nn-VqJj4pvsbm- zI%P8l|NdnYG}1QT-8VWr4$`-=;7$yE_56>zD%S*;tZnpir4MoY;p~eN0gUwL+>0?% z$GHbvB)IDhS-;4#(@b5q0a?(MBtXSYrhR=1Bmx+8jYnqH@(0T(fjCP zr0I)H8?9*UQH^>vf9yq{&yC0Apuz5Afk6avf>WF@m3z7m$)PhK->H}KR=Sws5EpCf z?Ry0t;4doMXYrslWf}&3+la(Gx~=Uy0__DMy5a!1U&~j{gbo zHx;ASxfNVd=Zf+d@C*$LFaci&WaRNnI5b^W8y9rl8xE2`~m3eDWIFJICmI`} zpMOCofTW+L7$NI(W#4fzRvKM(todPHDD?>7EuqDF(~6@ruFr<|Jh)Pj($xqkBd$Gu z=|}V9v2Fw{Y;O%Bq+tbtmawQUy}5u$+ubjP`aR!ac11{ZwwM3@0^>sZigi+d=a;$- zeV&TS>WAmweb#*Kr&^Q?Q~4yw8+l2oTAOy(MDvC9kj8=u|FEuSP?+E_MA)^d0_!Q~ ztRPqt)rO9&K~8ix^l2YHVEtDu5MY7%v>2WP+9CLhetau!P*Lio8UmnK4T)SaZeP4Y`UU-x-PUGEXf6F8_%oOC zp%LS+c4vR)V@g^#XO#eU^%q9+!-}DZg?S=p>t283b3qAcXxoj-aKaL8?@_A^_WSH7 zkY9uQ+MheWV`Q*yYsV*~YuI~9v6^rGis(+KJAQO;{twZd(*w}c{y5y_Rk|b7Q@tg| z(T0HAs(UL|DQlD}pQXP2E{phRGQq3A!1GPPVMQH~j$&4=G3=#Axl5VDH~&-m-2{8< zPvCWjr^w4=USOacQIo!{0xr_qO=FVTD?Pdt+0^cHLRC{|r#~IfhxSkU&K$by1s7BK zj?SE2H&g`fV6XZ!cIoKDvyl>al{(-OXyB0}_p+Wyxzs22FpP8|q(V)_(NR4uMT&en zzst!dXud6Vup}**DVP@pF~%3F1&1 z!2u}RcTuSuwhcHU&QjpwfvKDG3u|!cEZz!LW$3d2HWuHrSd;6{vquNS5Ph_#yCwt1 zkr8*yzIrgu^rh@44`JLe0=g3;3X+|~=E$aV589o+9X)Fb(tTa-LDJsm_xG2&F%FkB ztOWdLqe(~W&Z|H`sXTU_;iXynmy zN;!aiNzOW2o_2LA-!o{WPYF>8HXT>b&UYn(!vWHDv{Q=MqR3AfB-rms8H2tp_+P$D z-fp*{-x7eMe)f*|s{6@#cGWr9+|#-`;vDKJ<9^IQWHwE4HWmR!Vb&vp3t4x)IA6WdFzP|2 z@V^MXhz0cPuEMRzaH#O#QWe|Jv7^Ae+xI?B^iPUJc-Xe765?d!&MuGdCbz2!t1pm0 zAj>7UZV@F(-*m4hy?-IY?#%Z=;qUHio1j?7g8qB1ae47*6KS?rYvPlQp^&)O$|F*U zoo%UC&>MHQW->-EVDa=RA!32;>Cm`(68I+|y=6$G`Rm4ym+ta_)yUr!VF?cNpQhen zRsY|R1GQ%4fQ~#246!W?4A%b*IhZ?o{O^pzf0zDS|K0ZA%3OXFP6WO8T;nvP;^=EO zVoT!^Q14{^#z$dJvMyr#Ggq9D_*G6_?)M0861zf#t3mx`{pGXzsF-<~-=V9~rRzJa zNs0*txU;&=ko$1`&|PFLU}WZj32UEazc@On37n?z`2_bfiB-$ET|&H|@AlljLJ66Q zVe1czSKyLoj?ksuBw%CZAn`Bn5^1950-qd{bAScET&w&`fPX5Dv@%=^M?-I8jh5T} z53>9Yudu2msX`2lljs8~aEyV{4dY z>P(tZ(SXuV3rznMn?jYhV!I$AYIXk1crxU8;&z2;7(2}yBl#sl)OGo{jW)+tg-bGA zsB{h~FuU+r2{d{pqp?|s9dRTKsUL<)?556`a$p3jkDn;3QwsV`mRGSa=}}K*J>W6&Gy%E-%P@)BOlh=7j?ZwPp)XR9s$uq$6I`T1*!Hm!i`2M1&MUE zS$F(34=RAwSbUwa_<4J8TC2S{(}l`M`BSu&+$U6`PKtL{_B1!Ug))Q9Ec9=3xgSnz z@Ti=IW9<%opA034^{3vP^(RzVBDn;VV4{i(typx7bD9ubmZ zbQ-=NHI4DcR@8N};6vSW`JyRW>&o=@i?}7HL?&~bvFm5ShUO%$5V|>~eqr_$ozpNT zn_)@qTN5@L0@q;8q=2be%Fnl^-Llg4bFV?!agjOP8g?UGvDqy}*R!xhB1Je)J2T#M zVRb~wT9J(%iAzfgrev|Lt$mG<%8ui;ubysjcCIT!pgUeoV&JQUvkYcd4|&J;lmaa~ zYP^#(rTqsR^{uZ7@nMQ8TtYuwJd!MBxO=n>OTcceNvL>^`mS$}b13U|CVa+drs>?< zC%$K^=dN~CCV08`zgiJ~CzEX~cWuNqUT7k_i-lwE|4Qq%lO+riZjRUp2 zGn<6p*6$LgZ6{!2>i3X+Zs!Qx5Un*1#*qrC0NT|0bRHvIEWbQuXAJ#KtKArz-fa;_ z^iX3FYbc0}uP~>!dXf|Fxt|oo2Z$!2+M*%-RZ{p*pi9Lq3S&^$No3JF#+#M^1Cdv3gM0CIw86GArfEyF~Kpa6e~J{oXPjX z)_jXPQRvQ7$!;2y>pqOgSD}D%GoZd5yXWqkvz>*|7()2Z_a(3Aug_Y&lEU~O^RIDy ztYvtnYsa%=?lGlKYCq)m7(Io8ggxxfMlf=m84~XwJ7j&R5q&CzI>>yasDi}t{I0oU zU^-d{oag3z({lN8Ay-FKV`V~v2AqCw7bq)a zPTScRhJpW@JDVd7BKm__pcfUf-uih73G?G?)c*onk+q<+HwV;fQE1qM)=iv z0kk2?!=zrK)leG_1+U8+c(XyS#g^*FJm_YMf=ui|+{Rdq@bPSy=Euv5*QuT{elWe$PW51i-O+9P%CV)`<;+OP=qs9qKES5=5#2T=>SK)(hBC>LY*B3(l;rn zQ9b0orzPKpY^c!P8=L9Bwbb=yWKF&+TLPsoNOqIYA>w~6d75k^tme00zertY#OXpU zYE7JZ3@Av2ZlO(jH7KXCl{4)^aM^+S=V=fQZM@I&i%)mo%rD=IQfcM|4)q^UEp#&L z2*kSM5JTX9Mnpsv_o|0%FJfHc&EPI71|9nG9j{`9XcqX8xVf}Bl|FL)h5BkyOYb5` zebMQI#o69epKRXg6<4r?fZ3lYu8>;?`Aw^WI0uE5Bc+CLecrON-Y(W-Yi5q z6TY&34Q`TGJwDv8=!|a(Zf>o*rm;p;DeQFRv>h|@KeYe$6B~7W{k`1-7NtJZ!;F8B z5!PXSCJ-gf(E+26GQJkL)%bREk;g)a6=T7 zZ?`xa1J{1YJ)6~DhqHG41jdh|z|y8T;gXl7I@=J98k8z4iLxb9x)3GiPpyHo!r7WZ zh7Xh~=}T@fXG>G?p%Yvz>$S!QWbWC}6lOm!p=rEeAt5+?7h_YxRJ*np-#;|wIFh*N zGkGD;-II+cbh{lUhT(w)6n8R?lZby6mrY7)(i5!R>fg>$h?-W>fW=O| zv6WzNK`4kecA`kvPH_!2s(^NrP8YmSPFfgCcP`uJ<>!D0s!O-1pEGvVU*V-?Xn3n2(dD4*674=gj_f z`DbI?ut9?-Ig(D47JkU~&KHV2!XR`i<`VyWETtGsW4>Om;Y=kA@EJ&l&i@2$8Pq&`T`b;QC)aOg3g&+7(Jn?bt^6v*;ezY5wvV)77?-ygpuZ z=(Y|=8IU=d>rBnd9o9J9F};e;KkBqGq8UBk`PJpk@XvX7?T|J@JF`>uCG!0^>#h&L zSfd&r*6|Lh57`khk*9t_n0s&fc5Ik-GM>T?bHddge=+so)^&qBXRN+zt+>!b5fQ#| z0=EPApMN zzzu?VSi>uq5Bk`PdBbx@c6+9}8Y?u86xemu#}!)1g~71!VAb)G3#B^Z|FR?PZY}zJ zPlwiDl^A0fvZ+WyAG`3-zhHZ^qA+Q(A4aqSjF1&g(`#)wOykqzy zep#%!4Gp+O1WiV(gp07XHB2jUChc;;yDGrm1LXhESh*>2Cb3{U8kWpquU!7JUl0;w zto6CR$f!e?B2}tgirezVk%9aI$Bzyh5GTDAYxIXrT%MOOlszV75L6`4lS+HQ zkEM-&v?rAu?vL~PhNHXqpMD)dV-$TEpHXe$!K+I+-;_66816%BlkoS{O$0euhgBy8Gb#s#PE-$3X| z`S3HaREojzba=OXhF^hMWQ))@%KFVgKH;clm?5RVQtoXTFD$;qliAz_2!dLO=;74* z@G=Yf&+=W{p3X_GCp)yjkRx& z?F3f2_aoy68-ih2ZwTMX}s={?M%PrnNafW{$9ZbLV>3sUx`M zm8LYZIKye}^w?h2LP7Ya+l?#hy@H*bMNNIfNT=aHLpOZrZ27 zVG_=`b!gBwzZ`aJ-S7fzkpBnvg)om4h@BZdc%dqmt!_7{goFF-=Jc=t9?8TN2`K~C z!+k~{oREs92ERNQ=hZIYrn9)JB-0YtC# zt!u`1qmZRoE5u9~BDRr$5582wSg-UR~j*&pm>?nAHqKJmBDU|-XdPn$}ornbzb2M+ZP@RL~d=D)% z?267QUKMB%x4U^-Hj$t3t$D!qibD;kD4o7#{~VW4YBQD`QWf?#Q=~S}e45>1p`2}v zd#~O{lNOKgY-{?eqPVAmBrm%=pZBQz4n+Q%=@2;S>7KL>YSQ$2$bP~Ar?^2Qty@)~ z=O3ar2tz@t3637w7Qr0+6y=DNBVThAQ8ov4R`pv5r_ygsfLq3DO!jA}9x5*t?cm{W zA1(lxy}sI(x=~b3&g54;MB;d0in$)jQQzDPqUuy~pW|Ne85nJw0|j?>71sV^lJ|HtC89*xH^Pkn;-*6#R#G&>ptc(M_(p`JHiu`YEcmMve zGwi-TKX5FJamZxSo9Mbc<6LB$AT`BpH9s9-ijFNr=`|s#P*}WH%YERM$X5F3eYET9 z3D|Fw2|UlEd3uYY#(49mZ50a|gDP&!-?3mLM~QbcC2v*TJpylAy)q_}z$z2TUNc-p zz6R^Dhkz}ISJ<0)++d;524=okR!`pMt_P*f0Ha*y`rcSS2;S5_cu5Pa(mxG1&woOK zPDOIucQI&Tbw?^$u9e`!uGhI68>g8pNCh6!SV3eIHFAT^RUzWrBzs=A-*~>1qnXME zyik*l6!sFK)`ggWW}$#jE*Q(n3V+@{Pgz=esNN1Nx`Z(@U_*HYUp*L?q)X{{%UC@g zVz?c-ALq|j88biu|MOj3=h@%`N37g!Y|Tz}f21J|8B#ugLw2LZDM8MJmA623*{yZ) z=j<5b^?#Hwsp`z$ldbKvHm4x5#T>P92#X53j-vA!PlddU;3Me?1+C zuBy_d`Uu3L0PFDS6qg**q6SYu%|2}h9Q&>PvUAv%A@g56JmIH@fokJ{=ZO+W*`;j?RKt=R{;>{)GlcB$E z%jO?p%1zhU>rUc~SP_$Dcgm_)nWvkdj$l|5A)XdDm36O_=g!9(^WmS+*~%QE(705c zr<~1_FQ5%G$O9VdY~j#>Ie3E{#$Z>vM5{>*12b?Afm#$PNcdjdOvh_93-Qs2B3K>` zvz1=+CN3>LI{LAHJ)Mwx4(*a2!OrVj@beFcM@Y;S)R`y+>SyJrq_CgTf&bj;m$yt0 z#zW)JbK;k_rjgc`1PdpT-rD$^=eHNa>lQkIPB{ke?q`+R3A0HT>(99jvpI22aBL7E z@?`fTZh<$ts^;c&zxl5^hOf0UD&*2LZ!=8XZw#Lp{o+Bqko4pm+LPwP8z!xq78+qpjp{t+8V>WWk4 zhyAl9?ITn>q~!vJ;jVt+pI1Y#+W`TT+|WpZ@hT*nRo$@lsDYFt!Gvg2F3`R|PDq7# ztqYn5uE8{eYqhm>;5~W;6gSz<7S1Qs2d**A^gDiy|EwDNZy3Y)(W?d4 z&X>Zc&ykP7UvzZ#SwtQxkgeHLG*E3S;cBouVE<8r3a*=+JXRbl654_i#eDtpv>1#P zQ8j+-bZC1QlGFAK<7tN@U8e)z+2`bwa+Iy7g1XLeJDucSfPY>(-c{@1NZPabM{&LM z>URfFpG@V6^uPAel8=qBv~8_vzhcPRlh1{a=4A{J!iXm=RI-`hYcp3+y>&Y%#!|?E zgCZgS0_B8c4R4383utCtAfr=)4Cbp_V-@EG;Na1+?9kGH4m(VTdy|l(IT3-7qXrvc z?kDIIW??}<^JF%GE#i)Di3B)c2z~>NMMeDmP>BiT)C2Bp2UP~#YR61U}GT19dEGtnt@rO5ZAf!ZwM-&d_`nuzK14} zLe-HO)Fl#sWapyW*+9G>Ui|oJeHHe;qXs!LmaN$2uqrO01LMECVf(_eDkLsV)ydWB z_%k_0>Ag0!n}!PF$qRcyhq(!3kN=fIy}^;-pqCn7|J zOjoCNK*ta_6#WV(2cxlckHFWSo658Ix47HELaC0ts({du{A@v9LoG)@nB5 zW|9!47%K%VW-0%)Sea;Wts`^#+lS{AtWELz+XTJzNN7j$WAp7HTR0*&gVd7)t=-kH zL-|FYHoHVOKxD6H;cvIcA5Bc6!AN)hR_or@V^Ga6a#p>i4Yfar9gL5$A53jW(deWy z6zLSi6{R7qX0*fHr&U(fpmWY_?d>o0ZP9pEKi8O3ZcruzKcyoM6J>J8vt+|T|B{8a zgC?H$9QFvjG)j>b8tK&gu7ypGsjpe#QEiUXYHnq05vt&UA|Ww42u}!2q8JPqX~{f! zEe<#f6DtmL0roUFwF);NHYsx#M>KMo3tA-Vp5qe<2Xvf4-UqaqcHh>??G*OG}J zNXP2zdAr`z)=mKt*>~Wz|7ciw)9&lW`d#O|t6PC7BC_F9*!BLJ>&z^4)P^rNx-mTf zkuf(6N!ZoT5N|FOiuhsbBGJ%Eh^fVU(niGtV-I1#HaB~tb>mxteE3z0-y9LG2goTs z6L!B~-?vM7@-Mls^X?Tr$hGrRua!+%!Dqy5-#;j5%?mV>we?k(^c}DsC%iGw<`J5u zHpstpivHu0DFK>%AIZ%n8E0ohd3}p}l9`RMVvr|G@BC8c?_N0O#Kbl*D#<&qnh=O9 zyX0u0?ZP*jCx=riyrI=D>t=mXlL7#ljx4B$c` z6bW%ZUdXO4JKof&yW(bSe$PRn_H*|J!I3(d>+SRxyav0o@EXX%6nO^dKRPJj-|WSYY~|{iSt2+%pR%cUZvfKNvvbU|W04Fs z(_8UkxTgmNnRiF!SY8=+*F$|s_expBEuqy<5M-6di+d-r-&_!y$@qTVOo^bfS+{$7 z_n}>gSXKhxR`-Q-X1VSdX*$lqaxFt^j#-+yQekru?EOannMdT)l$PbIr0T1C+j#@8 zM$hu%I%-j8nJ?1k$9h3@6p9UO{j!W_hWei`%C-*4&FQ|56ZnL zvnMC1olO40ac?)L@3;2`QpW_tUNrh-hszp6Stu6G=D;eFdGo&ZLJQW@V-Z!_Im5@k z7#sZCrYRYRR(R7C9px!+{n;(^`_qeAcy#C^DF37cC%Yb&jvMUoKq@nlb|AP7LlN05rIh@RO*dO~cDV*eH34){5L2@(iG)88!_WIa`LoxDq?g)Y_ioGfIj zjwI1~l)bavG2K=3Y{@TQsV-iTJnhy>rdx8bEc>J-DnthRmreE7)y#Wi@e^NIbczE^ zIDWz^f6Pnx5~fcB8mAQcuYm$o7a~X33fX@1=bZ#%9RxW9wa9r$bB(1N_I@_mkXePb z@NzfMpqBo6Q(VpuUaF-PS(AZ~tf4j-C9kh`L$>>PdD>N|g_TnE!*Mq_*qC_& zK+gkp?H1Rm*NX#1fmC0!(Ha}nbyM=kJr4_lNX&2HZ1=}7%dSHn@)QUdESD4__m<+& z0?Suzs#*+{((_dS#pt{t4Wav54qhQrU)5}Q;osk9-)~_#f}U4b^2SGvonCnT88Xn< zEPYmQObOq6yN;J2jF)*m#}hjrP)olk$|48bjba8GtuLh+VOZDhf&)=&5TH-!@bqY_ zDnUi7b|*}zIZH_H~*)H zogJa%!#sk7oEc&X2Q1FlQQ~kceA|onZ}1!{ct;^m&tI(5snLTvx4e%+v^)iBe{r0c z&__x^s?x%r+s~ii9?!&nXsv0=udYg*f1Pv{iarOwv^ohxU$d-%FGm~yB=voIT{c^y zoIdC+Q*2o#ui_2Yw<0AIS(SeJJ?b)QHEgY_6gE6_@So-xmgHVte32cP23Z^G5cRD; z)j6*mPy0vD>W>BKve4uj8=lEuE#fBNt|A4g7Wf~=-aHX3Fq+l_B|aeqQ;qucM-SOv5j8VJ(Zhu z9dk#sV4`x zBV@$w-;;BKja~pyOVG|Mex4+CFxLYwO9#KY z#r$mMWuK7!EV|F0uWrsu-K64Vtj5hQJ@mslJI)jIq1I%F!ngjPK82@iNAsk;edoUR z;~LOY1pz`b@Lz}ZWF(|ZzbAWc;ft_`m1`{L7{lK?qT`PjzNq}PXCXV}q)+Nf?n%l3 zTx5MpMBowr&7ARMf97|*=PQ{X0X6?foe5BU#YfFH`#9Dlk|!c;6m6;Q1lWV%h z=8v73HeKpqTK!p*(GPj;ucKeMRTUzo2BT=+axt3+#)V6lP8n;7T8O5_uPHq{)|5P} z(b3IC&6uSAvzGQDTKlH~sxO$HnZ#tBvzYa34=Rk%wXf0StrvO!*=FY$Q&bR1W z^|blA>_3ZnVNQ1bxGyIPs~;ivH4!oOPS~#T;vWZANLs1ck%?p;C1lC-+uMdPm5+Z1L`i&ky6Vh1MUJZXD|Y_Z zDi54-!H@~IgK-P@dkbFRc?>1fwbP!5qzaf*b)M_+A7|GE#McnXF(TjZ3Jvr>P!lVO zIrBlD{`no5-YfXAvG2Tm#pN-Jtw^3*xs~70!R)*?$MQxSHKO7eeN?8Q`DXTkTc%IV zbVICSlB(iEGA7|%o`X1^?c%d;A1U*H?Y!Iorfi(gXPCUzP2ZZ|M^U@VG&s&yzj)#D z&xIpy$eLe^R)q$xMMv#pug+;+&h;NT#vVp}pO#U)bmeG*!aH|uzxV?oFlOUnbm?8w zDusWfHwirB{05auLF&}6Svd%-s&cKlD0&Y$ zl4;+{9g^8n2}85^S&uo=@pC5E7ya*1vKPdf08P1(YKG5> zpru@g_ezTUlKGMK)Is@TC^ByhXw? z0~f|47kt_uB7Nzu&y?>A?hk!r1EiTi+qv}PrkYLb^N(^!6E_hfcrW{)%M&$jaC{sbSQ4-85~*?Py>N-u zb|-nM(Y^2mQ)&ArMj^b9@?#}6=fX+fe;m^N&kO@Sg+4q}hfQ$Nw=!(mwn|`>Z z^5cR;9QUQn;1X=2ecxZPh-vCa*XlE#wjJz3;jXpqw?`Ka()yRAn$M~2H7ISjOeY%u z^VviBWjQ&nerR=B1*xGK26n4?<|N3Dq``)$TXyF=u3Gyp-A6A8H`$v*c1MCwS~vE8 zeA0r7+$|8wOjTIV=9vO3rpOBSCyQ$tI#QilPw140w`rB0|HQ8pB=;V!`}BjSsqlFz z2B8qk)P6s^ek-y|bj_M&brrY?qoPaheTr}Lz87r0Xni?6H#9B^9sSliaMdr_=iP~qW4%4~j7w1j=4;h%Fe*B&NlbN$^?`}1}Nt&29rHM1WcZSrq`gA);@A_Po{=!@rjJ(X~YIM7#Xy31g=<)!eUPiHPH}m zPZcu(Wo+kh@*G_K-C-gAQSj}DnIp8dw(lbnmMb?AvUiZ%<#bc)n00C%wU0KbKGMj!G510G6LDXqX~;Ll=6Vnl z7;L^-k^2-ScqH&fkg*2nPDHjME+&$;len3r*#mk}!7;U!6V5(ZR1>vTEY2!YB6V>;KMBi5*Citsa-|*YVPvw0_e!n6uI|(QN&(Y;4 z!>Ad#l3+z5KK8oWxSIrN_18GKer(cL$?;2`3%bZ->0-RUbMrwdZ=5$L&=Io_c5NEigrCrt+MKU3zaePJ7)l_o*ts zK5bI4n{U5hRjK8`>3io9OqJi7{n^SMC&#>~7@}a%h8%I>?H{Z2!7iB(`p#B|ACdY)Dicm{wg4ytuvQCXdz*m zbBC9f5^myL`w!8Em;@t_gynEqljD86_|ii`8(L<{1J)D&gjc}$raj3I^AfC}kM7{r zRazWYeJ+BIv;#k-C^sfqb35Z@MgSgd%o0E|Yk*Iqg^4AZfFjI&;h<6*) zbJg%F99Z4ud(JCOxGk7C?fa(S;+21_w)R#O(eWp5e60IhP4*8`4K=K| zbYycW$Baeoc1~RT6{oUyIezQvV;8`FaK)Iu!WmaR8J%Lw4_vB_dZq(A>t6D6tBv1= zML10kO+AakN4*_ByTy#XT}6+QeWOKQ?FCsUu#8`ON624@NfLg#v@`Pb{+H7;^`T!s z^`m*JdjiIg#we3WR|P)Vtx0y7P;uZ&`pdi3bLj!fCY#5&y)%58PnKD~e_mxbc1uQ+ zv++-hPmuR_WK>*g4ozs)O3Vtk4iobp}H0<56&ds|KI2q`*cAG;<&CC?!B9kOy*#zBb zJt)3|z3qL!j9o;RtSV;+jmsWMF}9Y8*Low7BZQqb!+$HeUnexDu6kJ}62<-VbopR*#>z#!B*;cKvynqda!JWW z*bO-0%i*#F1y9!wE>6on?1S^ip6muri04FxR%!A`Dqog?_;|~xYQ^%2(Zo|o&AGhn zNsGn(mkSSd=w4L|TKIGDciXy*XtqtP3cP`(ngo(!eA4wWdbxcdU3)vU)IinaO5}${gjCIWGZu!Ui*q8IY?cD|rlbns2-Sg@hkru&rtiK}C?D?Iv^Vd@< zeq~!?R_>-=^rcu9d~0r->a+c!VD%9qkBssE%EuUmlT@0>`LqkOUhFbLa#fXs_U510 zHPHbFio74rjm($P4OkWh&AwC74mY%b>gAPML&?a}YN_(x8}v&QTV|E>Df=aHvaoYU zF)U+U$>37;H*@djsC%lR5A0R^cW#|(7n!;;Q>bAYCFV}kkE5~YU&g##TXMG-v8{zf zQ1IvYre~XIu65qh_eDKKMWAB>)jgr6FK5XG9k0vbYd?$G@ljI=`IV}b@$nY%U7J@A z5AAbVj+&9sCBugtE(Rn6*ygqA>o=gJ?X*{C9Ok|y#(Vu? zbKdh2^f9~L zhAO##a|F)_q>nN(> za-70gy6@E_^ALw-PGoDbJNC7Xu6M!>NBv%Z^3XIiKbz1zWm zt1Rc!pwqNSLywpuyF}xl4npr$KR(^!|JlxA@m|ER%LV=Tz?2nhBUbtlQz0DTMj;KJ za2B-zd6wID5beIEG*uY9TIPZ2TrM#VUTs8#f}{%aXH9 zUoDy^gl61V2b?fz$Df#d2jM8^)lqMAop(#+%}IPhC?9kyCzb`rNx01{FT!;s$`70@ zf>A@YYL9P@kDeOaF+@WTXxUgN*pkvY!t6G?SSINFT%ulPtcsSQ%meSDpvUszf!IVd z9WQn%(%>-3LIdikKNi;;yNSN;xHM7SSzLGW_iEag#K)f6tE!b%`rdqh=VN+B!H9D} zWi<*mqIKWR=72I@N?#gpsK6p6^v~#J(onzeFs6+QCzW6(ca7r}2(iK2Y zUH^>TGf6;Q8`}j<-}7tt@EZPOAg}P!R5Q%?l3axUxOKrDWb8`yg;gB&$YG#T=(+e{ zUgyXr(|0-7DeG$bL6u{VkBDX_&c{G?dHW=Wval+IU)|hS6>s7pEEjfe`$2$(*;Y5c zv;{m_2G6Tj656DSA@*yjRGw%VR#A-J-Qm6EI-2aZwUofM4ebZ6uu;>=pz2N2<}wwe z(rPoOLv;3^9ZWDf-y&hNKigJ+(s3Z+VsN(Y{YXEPU1`(z>(u z7}s!f&!5Tyg{+l$&%}FE?<)!q#^DK(!>+ZFRFc zUoY;ve_H$uU_VcFR^nhZ?dgNL=emQf0iu^=M^q+)PUT;$P>V_53LW|x1hTSW%|(u? z%4(n4VH^BqHv>geI_N0wu-851Y(58SgGVOcJO8LzJcJe$!oP~l-%;nOP$_A+rLuta z2127zz;Am9RPg#$%Eo|9tiq!?aQ9Ceeu0#8T>KAn+O&XyyL&4R!JR^)^mFMah*s=* zO^k%#@bIJmce!zm2k@n`Q&YBmNpa zUySn=DO3=TJL+l7Gm;tNoIAPs<*r}UpJ|8rLiC$MH(H*h@Rvgo31=*grL@Qei)Min z(?;AGw-9~nCnp@gTEwU~lEwKv_nAI#coRj0{ru^_wRu;!iw$0;%CVX3HtgH}Bd7Fc zWV1qN8h?ixN_TrmMqE}W38s)^ce_RR1B|&FqDl9anBAkq0t|pxS?}Ztg?DO#ypdr(+{aC{&YKV;|50hfJ};z-hTE!54Yv^*e0ANHcr5vTx#_fV>y456A32lWC4TdklCW z*1%Z((N7y`^qU#kX8ZdUK?nAw{r9Biy>{wsf#nlq5)Vi)LZ;)R-$uk^T0&L34cgFR z)9|#TPII<;;OrSEhnLNS+nS7Xn!TmEb60C~0Cp9RR4Wwqed7qVnwaMh=L;J-E9Ng-f7bBS zllz}3^_&}>STX$$iQzdyOf6#r!uHxy@cXKuSGmz6>N&ClTodih(AWW6chM8(II#e` zOoM%8)+9FGU}dY;pftEniCvasbOkr=2Ra2?VaWXlWP;W>RTeL!$pD zd)8MADbb~#vxkzkx&c*|ni1EG?$YLU_P|@IgN!+o`E?yy9pdk#*nhq}IN)ojDC2Iy z_*U{N`qRd;f+TyU9Q;EPr0WFtd9%UFK8(_G1bVo{+&=coVC592?yt^CLkHu@f+5H| zo`KIR#urzv0d#3z*?9jCFzq|~W>xRsI^pyZOwp5|uP4qNRY+4jx_WTjcovQg_+=67 zN*nVsYQ`vUj+<-RUDH*sp1ZQPIAWfF`z|er**W$!URZ8n@q&`(y`G#FU6Otb&rIVz z2_+FHfMucs>rbx|9KXvbPq=2S2+c|RD9HLbYqU&46dMdnGgM5-H**qsxdXjbp>psH zpuVA{ZfJE8drY_fY@4ck^_v3;@{`n#-8-^>rYAnC$;}E>SCK`Z)S3;?4K2F*Ke)jj zKfvI-kcv~>j;R^@PI|Z0-c6|PF_;9UU2GJqZbs&_Av&0udMa3(tMW*-#egZhn&9|^ z*cDF<+uC%Fe4!ZHi@1ei>Gf1^?~F&aAvv&R>;w9 z5-+!xcuYa|uBRh)tV6+E^CY$kvt?kek*k7fMuS8_LncS-!X zquZK(04_kVy+#N764CKss4GfZBCWEhGrKkQkr0hdOm2Mzi&Ay^uUHLtOdoblgv&~4 z-&`HI{YPHkto$W+VG*z-Zw;|}6%^q8_v=qK?EG!gOc_!-|9gxsW}7m=VpW9oPEPw{3)@7RG*9 z?)%~-Hpb06T^AuMf9o{rTRPL(sckJ|-u>_<%^!UOeONi2C&>>sTuHjHtL!g@q7Etz zQJ`(M*oGtle9tHEuWjrZL9VFHstC%PJbGh;+2|a5&f^1|PBvFe4)Qr4?_$Eo>R+g>3LvMCn2Y-Fl^FTr z?i~RpB~M*^8r-$>?0oP|+{q%sS>8`&UT3afeEcRb$Tk`3O3wDzf2L0-=BlKB!;PGC zWmmYzoo&7x1`MEW zAfYBjQ_1zs7c~0YJ5|v2a7s0PqK|a)<>rQ_7fLsvaP&m%3HJ$$l9E0A`)3CMCEEB~ z^03BW^y@7HM(Q72?)XhbikahIJ=jMX%h#rwNGbXAIYN!E1jT3Dw$FTFoTEQ@t?LHkf#dnp7w;uDMOGs$<6XON^zgVi%*crOB^}!wf9xAj!*gt8QV z8eHZ4Gsfy=^y5y~E3?mriaKXk<9z*tHJw_+KI#JYwz&a`Yy0&2nA{q2nEoY}-#Ad+ zq3`OY+m&voFqo=xX?e9rl3E1As9mWKcWBXPfLM+1f&D&cp!nu^#aHw7jZ4**I(5rk zJxcYi^x~V%9%Aj@kPFXit7Cakv5)@9dIPMqp?kcdvxi*mxbxw;c{N42zKD2~I znJqEOrDjxMcNX$bpZxW{pt9NzxPoVy~Xv-9Aq%}e#^kPqyCifGGkk~e(*;4j?+VlRl93k-BXO! z>XoJ`gr5ythyHYEO`S52auUYkzWYrxHj_ji&v^f1&;yx zMuVSm@IhHJ=5sD@O{JhZE@3Q>%&UL@mT7h&KkW8f$fSNG*K0wBF8tpi6YdjNR6EnF zecdomT7QK6C41*x`dW7Ia11gut+6^~w_Rdj7y{J3UM`2H=W4O1gQB)c@`o#po65`$ zTuTMHH-}z!58K&BWf^xgl;!vz*yxN++UE%<{W}c4z?)SF6o$cjc2T<&A&_^9&z_V2K2AbYrv)OYR@L*{2rYCY!dK6q2)J^oU-Di z&xMoP|A>|eX7|d-domsksl*5nzHPLk+p>TY?0i+E2Wi>I!c?B*OM)FmZHZ6brzqUJ zYa}y#*3D_6kn}b_Kix`H<;hA&;qrF?qGm}+ZD^2WFOn69KknnqUWqzB|BCx+kRXMd3RXxWc9N>W)&_pAzF#XbzSGVOS;dQN1u#5 zGfVa!=V$io_3$+`3aj4MAOCD?Srmw^?YXZNHcI}7iCdj4`1;U4Wpl4 zxIEa&)YTlwC7^LtxB&YB4Gf`{b}km=oMiFwjl$^LIGCu0-x=v8{~et&-c0myH^kE?@XhBBvlMW#O&b`IMHfFmWS5MqV1 z*|MS{3Dy3Zd<(kB0Ly+PO*Ah-n0^+k(it0nL=TR)hN!zgU3a@`*hse86a%t;vcUbF zjK3~CDq1%unwd!lpYwR{-dC2q9hziRF4b6NXmhEBdV62CgLtB|wmy!{*h&)DU7KyW zL%W+Mem;_Y5ce@K`-I5(u8#$v@o#4L%!1TNx;G3WN1eWCRkr-b^@7A{?a2JPXy{=0 zeMKBIDrb1R)yFW19LK1N}G@cc_(KcyU>#Q}SL-_Hhm0G+s?7>+*=^^BT#I>HtRU_Lz9fmlNQI|&w+HI5; zE9~b72D>E_F=5%~!y!7IGaL6s`TLD}XWn#t0`B6DpMxSa?a!ND{mA?{1>s=1a{}kQ zm3KnFVkK&yb2t_okI;Lc0m}rbDH@8;0axAl3~LQWT~>BtL=heZV$vc^2e&`gAg!04 zrsi6V|B$i^Q`2*rQ{b0i;ctmYOX*TT;x<+Vy^bEAc-n@?W(Txnxp07InaA{i_ZN+YijN*zFW9j@+x~` z(6r_5W3NoZll<}ir^J0uTb>7I6tq_&-20zIFT|d?s1e|I?$+a2?3Ly7+mkhu16RO? zS~1K$Mm~?Y>76kC-;7%sfDoDO^(Q{IyGVawkY&jgd7y{17r&9A_BV51Zd#0kycw6&)h?%NsOW2Elb9zb zD-O9C1g>}*6##i`Y~S;dK2~Y_tM3QX3ibqFLWJsHSvnk6!+uF6WV3TAY3tJ`+EiMHG;-s=drK|1PNHK6KVUSWOw3)!a}Wl~a$2mprf=DsV7sffm@jc%UGjlRKMXSo0j{S6tO_-L(gf-(x6& z?e1?5keL1hjM2zw9S>}FX3YxMxa{LFaSyZ0DimPhKs)8Sidn7}VnDil^syR4~FvdaXgTx1J`Hn5zMa|&HMp#D+-Qd!`{Fg`Y}5iaEw zoq%o~q8X-HT)BhL(hwAR@pV-0az0Qr#vN&TlH+%@iG>Q+e-eH0hV4i1nmb=kYDAss zR5jHf8cYcMcK%-Ut-z_7dgs#s2Q|tJN6R^sc9w3pj?^ena~_dgzH?<8yj(M+XV%Q~ z3~lT^{qig&%=GW}3gbQix5~6G8Fj!H+<-5_oo|Q(u>EB~5da{W_Jg-gtTYhhRKHeBoUs6wdQrSMl>{R-OhTPa8mRKo{_Dd*kOBc~1>olfZ(lyzE2%N+6?GVCjzPZTvd zcYS2^Zet_BUm$ta<-^W|h^cFNpG#5(oXs0pKU(2=)oYI*qN&=26h=1g$ZMU*s{4XR zve9g7)5^Nu;d(HJClP9YhB_a8T<3+mifG>~Q&zu7+Z{{v=Hs^#?=9$Dx+H~;ISb^Z zfz3glO;hJZ&f?{KRt zrXN0KBVpSzARh6%Io3-O{Wj7gpypX?!fN4{tsK<((1XBZO+8esUI58rP#q&mH zbEdhdDD%=QHLq9ipNzgSHg7C!3=8F~4tSy_7k1qsN;gl=NO`Zwy<%y6V&4Kwy}B%9|@qCL9Q053OeJ)ry&zFp*_rFD80e=4GWt z3ZM17R@TrId=a^mL+eAQ@*AebQ%aCyq=!5JH<`mH(JSIV-$V}n)ZQ50q2xdKs&YQ` z{YJ1*>1fDIVbmSs(aRGSO}DQajfQ?P2A0guq}{k-p2u?}C?V8ZNqA1PDBj||pVsBE zurDXOM0v(TC2MEj?6@6E(YC2+c?^(5tFw_~Pf5mQ3o7L`GD0{aJ*n*YJg?yS8W0Rl z%y>T3WgO;xmRTyWD}2f8w^mT@Mj_X;>uT}Rb1@Kj2=t+&nV@mjYySA_#= zeq9t2m3wrH5ApUg5Y@usikp83qjUe?=Tb4U=R9J#I5?gj<>27|KhLH5KmU1)y@UN? zAH;rTryAZ%c_`e4igs3Wb+?{0DjS&3Fc&bBkG@|&^y9qp4<$&xwCq4_RD;{#H@jF7 zy`FO~PwG7o){C7KK3-p~#vl9V_xqs_a$>Ut$+o(UDY{0dHV%r*A)+X@=3r;P;;u7( zzh;o_FF}9hDJ?0HFDeJt$%4EI+~9bL(*k5}=E{2L+q+ySQURB?R0PJ?af_I< z!=#)_6T{OPclGC%BEap9>Bj`lJ0u)+^0zotS3TgIdtp|m`l#Gb#lzDHP;p=RCcbII zwwXQdkLYJ+99lK#^OOq?&vI+7&C}d?(RqZi(24H49~*whY~Mk-)4iDM0wGo5$5+xK zl7CF_?RTf~i_F2fX$O5;s>|#L{<@ySg?Bq1Ul+S6xPQBjaDSt8j(_3nxu6L7CClvi zaH8Xtz-)^BEA5bPi9z9{l_MVoYoHqY@Qu!&NKwY42e^`bWS(Szy~BrTo;8+D`?Z}X z7s@a#CX%adsL#j>gG!D7@6WL(l353~Em+U4p8U{Nbxgy=C($`^G4U~m@*_@(2-mn6 z#yHT&&#KrD9dtd1lCm%BKjLYDd6w`zJ36#Xk+DMSPVU$2Gd#I-i>~`xbzBwnxfB08 z*+o*d#Qd zVWW2-p(m`uDDMImI^CAi94|5jf{zJT@dXG_tYqv#&eR~H!#9c>Jt>iQ#MM!tWZwg` zM)6nfI`dUWQ<0IoZ$k`t8gSPk+Tl%1na0ceR-k}9`Trjwpvi+B{KUfPy zTP!E>=z!`m8BQyTdE&e-9>l>Cn&a9jL%J>NfaC1~EOqUiA*tJFhO7>rLp@!GuC88A z(?eJU|;-dtBD!gZW-c3ai5Mg3>8y^tjZ^kw$UkB1E1ZP--xK)R;P1zm2^?86y<%pS>9 zDUA7sA&_i&qf}$>11i{-A;lbmR3abezSDJocO^$i_uIe^qtJwxENZzBtWPv&2vSD5 zTR}eD(h~Gz{YUf4o34yv?CBjPqM`upO|TK}4XU4@N_O~vKVQ!4;?=>jM+Z2>3b*RPl#jBd zQY*5%9elC)@;#q_q)*h9@atkHHbZIc=el81( zVWzw+-qdMs;Qmr0Uj?x0ya4lELjj)pNYEF5dUibZu;CZK>#Jcfw{VOVe$DVLQ1 zqfQO5rdYce)}k&Qt4r@<%@bHe45QP5i9zk|gK{|ky@CJc&t5BN7(YS?ZX=j)A}dT8 z9bJE1P0bj8x-PM@9pqv1;9fd;;~^2Q#6oJ4JQC3TVMX+!X&Tzm#5hqjK{yiY}m zm@*ceCzK2ZK;7cXEFDbRpF8~yJqR6AYyv5y1vZKdrlNIB)~^KQL9vUTM6@YmXfZ77 zeo!181+>Cz2zMDf&Ynby{}(9rnvQW#O6Kp}eQZ|~ZorOCN167FW{wBt1G_e*O$-&)20l#5Rf(QbgkABW zjU4_p?ML@)BN4P=P>;2pQlSscFZN1_3;usIZ@|`sp}M99S(;IpgyEh)KL;F)atTrt zNB|$|l=-?GqQrb}MoEXYIO(-ymfZnNf^5BlWz8p)sVC_Ihe&>%wv&OCMj#bN&itwu zeVMEIy`&76Yo`tCNvZo!^7wCz#xYlVdse$K2Ep*uV|u`NDsy11amGv!Tml?6a{|I@ z#rkbA2&uG9N(!+`>j7%T&F%#ap+Mf$`tQE%|JoKz-oUv5k9Ek}S2atZFQJ0+pnb!w zxLh;F=VAlqx(o0B^&2?OVkxVEYe6M))T)W^Xt!pMz^xbipR@Mwn63BJPpcAPIm@(K zO;T)*2o+5otqKW+(~Wr7&^HiZD9K2rGDq_Neu@7$LJny{Ge@n;F8Mlqi6q2LV-A2g z;7JDkpaF5v;i+WpN4$s(Db-g!bA1xhDBLs8h=doqFlJR{?`kPvDdneicl&gG0h>BE z51cAVc7xFamtXbcO_g{cU|NlB@dJCFrE> z$G+Oxzb~Y!5T~V)*$DDneYY*mQvu77D$`yLJ|8IY96mo&I0#Ja_Gx=M2~@ z=r7wtXmS34zl;SEX=~I01Z8s@yF(pj1OaVN-c%5dFQEdNjM-Me!(!<;Oz8g)AN{XO zhf6^+hs@bQqsk%-@274M(Q9eivufbbHMF+9HjK_=O)Us=?3Qefs50MN?p?1MtqRKu zWA2UsZ;Ixj=s&Cw>&lVubU)G+NnDOD8Ze@zPJgi*#7(dV&ED)Y9hyBwO`g*G=6Y~|jV^VI$80%_MuSTq^Y<1jz;bmbx{MXG0`1Gb|nswEHCCR z;A+5z!`JDC&x5#`Xv>fbAYtOqfH>%#WdNp>V;andr+f7$E5c@Ho4Ey5BeD63FQYh4H2 ztZM@1yXFfG*fh`mkg7yfwicNTm!~}zYtm=ha;YL#%L`^0P`0kDH0%xb_yocA@p4XHG6m#kucLv+gOHF3X+T@om;o<*YyE5#0C+J z0Mmlo=>3r9BP4LbCrlHF^aU{IA2CXUIbdO$7uZH}ElBdbUBiGwsSs(M(Wpgk6aga4 ze9wz$qkxXojB0Kokegao%fklCK70>jAzMr;iJ zq}K0cce@)itT%b<6TRYJfVH&I#1L|dwX<|#-ZL#o&RnPhK=q%9@cnm*FqG%aq>dT* z0gw-TsonNkzm@H1>^9#zZCFmn#`$?j0)FeeK1-S*UZ;9Y%{D6ZBe-)hyN$cYrC}bJ z>B$()7&DKVwrQgebOxBvFc70@f`WgA_<0Bdc)kyxHG*Vmpk6Gtjr6o|0Wgk4P;5`R z_JL-uR|VAi=a~+JT3OmdomND6V82anLI5xOEOpGV{a7w~Hv_Zhr$ggJQ_sGbA0apN-b0Ng3p#)76UCd@sDf@zqOiY8o zh}(@&GSb=m3miTG6mfvR@_^TTxa8$vLoCCvURus@{qL}8Ce=R%w|tZBT6NC`Es@xm zqg|P!J2ci{0HxV5z7;29bS+V9t4l!xqgA1rRE8g^EJuKv)`kY=wuD0ewSIV+#^Nk7 zu`&tO7EuYE7`{YkFLNNP`~l<8FVCSupxJcASTN4j_68vc(~Nw!uK{ZzK`Q8!INTvH zj4qe z7HPeUbnznVgw4n|#_|>mDn4xIR2#jJf0L4J)B63sfR1*o$bOKJ~f|-+6p}=>Cu(R2Gy2eA9 z?Pi=}cEb^1AAs$XUL&*z#jEf>2Q8yhfTPSB7ZCyS2Qm^8Nz&3=3S&4K0k|L99A9pi zrOhf^TB~U5C%@{ayX`QnLZ4~^=LYqp+cdz*wVOAye@Uew0^9^$`&k=S&{3#{ksv_* zWO}m~*htZciR~g9p6Vl7t~)W!`?FZsHBT>38aqgQYwb&q0QaNFLVD@uB4WZ$t^K2; z_;t)m3;4BeI0woDAcTJ4sP$REK3-rSKzGF5Jktf$B-l)(X4kvK4FFYGFPpP0y9NG7 ztN?Z-Y(XY-_f5<^a&;#s!FC#8y1?Yb;xhb2!i1g!xrFKwQXoGI!qydM0FAhdunl^} zG!D};(2ZkSYp?}LUzU~&6ioI5A<~xoV5M36Kf7vQ#Am^%?){Ck^=2?+SVb7#c}5+t ztIpObGn5VaVkq8+JVi#YIkw`MgTX#KxFEbdK)}!s_#DXOt<8lc*2kH8c;FW(qlu9U zsf-SgWG4lZX_z`V`9B*gV(S6W?!pssl_Qb+q{ST@@)(=p(gr~I+W^BgtJ3h5kcuO~ zF{4Bqz?Dw>4Uijs8*~6n8hJFuZXl8e_=DDg6hLS%r4D6UITj5-z6NLj$XxMtZA!NF z^wi#lf3wQHi4XwRnZ4I`Kz?+US3q|=XAI=B$Ye>u>wweHXhxaj8e-ZbN-p53J(Unz zFcowIOsFAaK&_PK)==m=AabZq)|gQuxCOYfc|Y(YvmGrQxM%_+1j!&0-K&|trv5*w zO5j24Q-QoU;4u}@dFP2hAYThRO5~$KsF#6tG#Br z0K9CfBC%zqy9b5jJ))@l7DCVgY_a206vgIRAmhOxf>4{c0P8gDHnI(|OPB!|^{NZX z6@+)DKFn^fYIM&<{mZ$e^7S~%BmwAtqqGeOK)dihrFnh$7cb3&tQyYQ+6r2+9=hab%4U48+FX?91lJn4=Yd#SPncMYABHC|i)UY`%gylyc!b^~;=4f~`?*ff zMn%@p*Cl{oxtTduz?M2sPobu?OOyAe8_Q`n<3V3c7wTqqbCgrm25i`*y9Dp^I3*AB zUPLr7a+WQNx9SK8bjt(a9h8j@1>VaDV0h?LcFX#d)&L-Su6{*q&+HomH&p}5?wSrK zV02KAphf`OLXmyMdbUy`{|ea<-`lAS@?dG-g--Q{cyKYZv{nf3r)K^7$Cjy7BE>7K zYbqQ>2!*$31o7hS2#*wt6aWFV1aC6{oO#W8N)1l-LDC^&xFVe~@e(0Y4I$H}<+=xR zCc)O%i7w#uzo9|B7Y%xxxq+_9S*Z0AW|Zf-4z>RI5%A& zrviAGltatP3gSh=hzKAu0j`||1CaO`N(E@2S2)o5(sPK+2|fXgk%lpGWe*Ao6sr} zE`Br|Mq$$VKLFB}3u{qwAPk{WoDk!$We(SAiNudLZ+WAiy;TohMret#5 zM9`sx0Q_ZX9Y|Pr26*)=W_=U5_$FhBO?hK~Ac%y2d!C$4vz9Rek}nCreju3YGwX0L zayf{ABvS!mt--gXX~v|YT!}i28-U~P1rhv;O^2&Mm{x$xO;EE@#2wsH7Ii8Ua0Vd3 zTE_&Vtf3x~uKk1wh#9dgIar>WMkMF;Uvux)g#nAP7=iz@AvrkOo5OO+#n9p5?jja) z;*KS1t7dHi7;DAF&qQd`QiujmTQMH4ENwPjJ?_t0j-Sw@5i;r9L>r|6b;7Jck3)~O zCaEl8I8DnJYP1>5!HlhOM{2|k#5 zc-DSHS2t+N;TmjGZykWVyWWGdW9%~8UiCyRK?8uuM4NgzAUvqo$YAoA4*QT67Zk!; zaxG2LnGJjT06wlJF_`XvT-2@1MgeD&7Kfy1^pyPvC}@^E3@FB}cOf!E70}UaMfVHd z-JtnU=5+E`d@B(LQzqF~ashb)HLEJQEFjP3@D7~n{o8bjK&p(2zekZ`F6P}wy% zr9vAr0svC=&o}Ne{kxD9z!&c(=jy^*<~KC}KLhiu|6=U-x6+W8iZ-=?hBP}d%DN4U zT}7E~pwR(ZM5O1q_J0Ob8GuhW?=sk8h(zyF$?Lzm9PPH$p9?FGI7D@2@a*QN+z90wqaW9LDHD(6noia>s5;ug;?rSrG^*J3 z3#<&W@lBm#V1eB4)v9bQ*uYxA4-?NF#mq5uFKUL==o!(~tXC$Ni$P+VB^5XBig zK*)qESTl$ETY>bBPnR|uQX$EH9}B7gKBM-L4GjPa0_{P)3<|T4a9w;{4QZ3h5480x zP>`9|sa|533i)8*GiEs`i;jnY)bcA5aA+yE**KV(q2nc<(! zL^vGbfhf#9%vJ_AIJZ-{eiUYBb5#n62B6qP2(_X82GDu93gI`q_I!pNT8#JrGf6kL zE}3kdtR!z_bKqp|F!{XoL7gM(|rCtZB|P$EEFI0E!Me zLNf+^k4Y-^`*1yTAjTjW=u?Zz zf73K(UE5J$Gv*=wy+;GBm}{asQ7eHZ<<_l93`FVMI#ph z+8N(o3*aGuS&LR}m>{27I#ru8HVXl6|3t2T9|8&pEW4N#JGJF>( z5GFy%z*_Q6#sm?r)>pwUuMt7Bxc`T;caLl8zW>L&kDuv2?W*f~!D*3hwzW=?S`}0b zY1dU-sWSCbQ6j{aDn%|4B18yD>N;y%FVq{T5Yp8mbqJ{fi6JCMTNO2swA>=(a#To8 zAta|HB!`oe%kT9L-M-!Sn4ib*FLL9S_j$kGuh;Vy)WfH8)I7m42OxYYxLtJqI1G({ z6zxi;oJob~jGNz}t`v}PE5*AZWu#XO{jqx_rP0` zi5DA+3PaNege0^>eZ(JNne!-3&#mf`U<+I}zD8B;0b5VD|D*tuL&0U*04iOF<%O(4 zsz_Y)Yxz;sVXRnv!4ro&Zpq6Y1X#b{q`omyVr{9wmAQ#OjLiZ{qW}GQk`vPvAE&8t zKoN8p`G;WWvAJsMF$Lc4k*W6;{%xR7P(5{ZDvs5(eK3YF=4X?<+f-7j3)+|=YP6w> zA`G}yp@h-oUM0SSm#3+N_hzC+;Nn*nM;=qk^CEBf4<=r#v9V_#^xz_gwnd1+7;-iD?}fj<-c4Pb8spmUdLR8UXde zwIw*TKF24T6I?j}N?<$(x>`OqRNb#o)glbw*(9fw*_fa*{296nlUCSpun55kBPKW| zyXL@~+9I%WBKR#FhypqMYBfoi#9VWsLgC`b4#S2#BUVV6&5@HZnE#tt4pp0>mjcw& zrx!I;)_y=6R^)`T47nVtWj&POEqyMJWhm)!^h<=+zC{(#=VYaq8mOkBBr;SIwu_wn z&)0Vwv}FD;;Kwo%zRK81d&)_xJOz&8Qd%QFIFt4~x;F^{yxP$M_X9W$bYi9vI34|X zrlUXZMxT;ft;s46hLix|F6gqhw2M7y!O!bjI_1DV%ni4A{*RyalM{GIB-5tgq2*pq zjlSAnjK5STwq*7;wY#oVuy%%ozKtO~6=uA#0ST3Q6TcmufW->T)BTr#Hn=q>4vX~| z*{`JJ7+$obb|psARmG}o*4#uE}z%c4HOOvKxgB=rYv zFdb656Y8`m$NI@Zarm7ibhgS0vz%xsp#yM0!)x+?FRh&cPn`5{R&Kz=W|qnHb>z(5 zv^MXjXRe5buI4Vavy`=)@1xhiaUwdGdRT|Z2IJZsbb{s`ktOB_8H4GSl>2_z5xGky zr$Fuk!R>_D6lcG-gq|CBYe0B?z*pN8UL5jZ(fap7X4mUw326;z&0G#u= z`2aLrNpH3^L5X_NZrl~x9OXgNdePscwbP3J3o9*#v*U>*?9GNIC|LJBh!*{G!{e~^ zm4Ut-bc~ahX6<*2pk4rO+}MXsb3wPM!|VI18g6d$`%Vgh8uISER9$6x2ZlZiy0=+of@{LCQ@Rk!qTz!lT|MW zE)8Xf8xdu6A|qvnV|0U?BfJ?@qq9!W8{TnC6W9h-#sg&9^uD_FgBSC*Uw~f}!$rf^ zCy%8Xc#Da*um@li4}Et%UDK%k+9kMERAHbR6+!LyCQW(o%iNLWYU4p|#|BT_>0Kq6 z#k*}z>f$J2z$_QBT_I}&+!?#sqEd{(`=x^e%ENk~IRU&{4 zO8;_UsAhU$I$Qaw8j-JhK<1msG(;~bD&Sdz?A#v#Wu9H z0dL5&5T*aXU#^f9=LL?W_0wvHY=}#{zeG`jA%Kvh7-$qW9QXwtE2LE7E(7ZD@=ThZ zZ)lH6;o@tCLV3_AG&#*2A$s%hVqVd)5PBbtRyEK2tNBoDnvah+!KGnP6yg5dh0$Mj z@7*GBC8NV6Yb={I8%wte;9}auQOO0DtQs~?Y-$vquY4}-9;ACVyBwN@(H)Z8eh2@e z^9;v-3aYt z>0ch-+rW=wlbv$?53j2ZrQUq>Cl&nPZtndHP;-TeKa4~rZDt8ar$g!XNG0UTIw?zU zEtyW|gsquQOI_~i!Qz)gHKQJVQFEXHb3DgCq@n&dQRwQCCmmsVo^*3AwcqCIFI$x< zl15-#v`;Jnb;8Kp*pfn;$YaI{!m5_{=MPBo(d1+z2jJO(!6Btn-hH*$5X@{x=n{TO z?K9rOEQKk;FA=)*B@9^eB@GA6=*eJ>rey}2s~S}#&D4HwQoXH@1s9yHDY)%2bRkcOogHv;|DYol<(b+YS1L?}XddsVUB`^y zA0l<>iEs%4Bq($N3v?l1Dr?AN2F@Sf>&;cK>0onSDix3hY+tDCZx#S1p-1hQ(OsBo zz_j%Q34HSQ6U)%Z$CQ5?dSZzE2tuH?iM>_-wqSpM;F)8->COKA|=wpfXC$>%T!;Hy#)?^KdCkf4O6gKk)C@bW{`{ggFXcARg=^JP>% z`eUGLcWQ{F7@~uVFH??R1l;|cOyXfV?^n~^KOgn=2?wr6ie^YdMgE&0hs>Tq=;76I z=`Pr)_q(y84F4hY7x+4pqrX6Cg~YMS_znDRPQbNLLF_gtsSKnWkYzbpxZ$L`62^qF zA4Vk48UqXX#ydG-Y5Lh7AWn?(f6c%ApxSraXn3o;z9AZQAP zd7wLz){96@&pv-|`+Tw*uwWpzZ6b1G)I~QoKfju21vU!v&-5Plq|G33iR`3OADa$1 z(;_S3lR{|kL)bdvTZ)u5@QC;&rjp6>I8ulw0>bC+wLD z0K~HGDbc)X#)@UGr`)W=vHUNlmUgesx%*KdEB~_^-KC$4T>)PwIS}6p*UjD#pM2Yt zV36M@ckaKHH5%+aeHh2Et80g61`DPX1th~tDZUrGo+`4l4xS=EUW zalfi19G&&^r1aKBdFh1uqf=}_f#6&I0wWXj3;-Up{Y@A)0FKC06D@}QEBE0^>Xw5q z&^d_&O9b`hi{w79g@Tg!Y!X?ow)U;pSFx4u418rAw37FaH&zh>GFA#NG{01-uyQoj z*azk_0`Z`^3k~)O=R}^3lQ_|?db>9XI-&0I1-vsHHHcMEyFunhC~M(c<|X9tP#Y~{ zIr{g;745bMYMfMaIdrseHXTvz7}WSqBcvAKF~IQ0#`3gvtcBcqz+z3yd7|f`nf3BC zYjmVVXoz%(Sz9L-3HDqM)EaJW^#Gt>32oHatXr7t6=~+R-UrW)HGLo)8Bwm%6#2=1 z)?V);G4(a9;%QEdxlB9z&k_b(dc5^4A>UDcv55PQE?POoO}$%QjUQuWgvxHnPa>kq zXa3H^xwNK3W@nCV^J}(5pWs&lu4f8c-IDc-D!IY??GsCFi=3G&KvgOD5t;2L2e`{5 z1FsIh132J-a^{c9jGGthOyf~d~zO#qW3lF3zc9Z`a7f@0g`d$ot>{M&BFE4YjxFG z8lKFghGq&TkM2b>3XM5DL!OFISoi{~h3aQ<^NiL=12W3uP`WT_hBfy9<5H);CopN0 z+ZIu7P*1Xf^hOo*#jUOp8c?fEhc1_fw&Hc$LG&41GjsUmpl@z$|5}_YyD$2CYw_=2 zpQ&*EdcxVmD_yA?H>KzPxRRk_-{t6LHs#2B58nJN81Diq0|UKaVY~CQIN^ApVf3iS z_)^^L{>MB<_YGVU-l>mXBH{Y>MngVxJeg^i6N`$FI46H=AKl%+EXDlS;ovEjEs0}S zpaya4W|Bmtv73R$kZTq2P+RyOX>Ql^eqeBB*1Ff!33{6J_D3UFgZX=(VF3Ebga)jZa9?> z5Ffhryps*9NIeas#TL5Zybg)4Dz2)9Y+RK%^9?bQp$b2QiPNuv)ua{S0n zDU8Ao&5fc!K-EJpC|ZgJc-{ST8qMh?L|m<0a5RK!)WQ4blntkw2wtqo1Ud(@=C3Vd zbCyX+)Jys-)R%OY1^_t0U3raUvyQ(%@KkEYkM@XvU$49Kd*eUrr!6!r3~kk1D=U)zX3Y=}*d5R`Qc&YJy0WR`AMka>VN z!eHgocTca7p*p#h7WW6#A?o+@Ey6gM?zfit zgnd>-)48jxebZrnn7LtKDYkY}w)5{RH~C0S7sz~TWA}QQIr0;MhohUDfMySM#0f$T zo@2aTiKjqeP0m$i+7Sr!8IetoJGApx#iV zW8r_KBNWzqm}Y`ja$Mecg%s^C^XHldG?iVPRA@k7xD5J2=turv(PXbq0*Q`S*Iv88 z#iTR9fWh7)kSH&BdC#pRNdzGUZEq=%Tb`XGn&+4j0U5;$ne(~iWnxmCF+UGSER=Or zDMV%SqjAC@gHMBmMvgXIb zwb;Y?^%}jzbSVz{G5}H6%y+hN>!z4oK{&ROZsZw*Y5$OF1RI$aw-F$4w3N3Q-HEJtvT*dW#jxUF7t z0~C}+W^`!E+p@*pfbouma#~=n?)qTm^^a<#%ty58(PrU>dCR}<^(arc>+zre=QVoh zp`+IBmCdAlh~yLlRX`|PjYEgyKFC2X6T`!V4pPCYu*)VB!q$q5o=gV{8_hsXXy z%KeX`582q^IRQXlrEO7Xr?|O^;Yzl^NxaE@3CY~PCi(Gv2guLom%$+6$dw(>DcWrf z$cneZ07g>W5oH9x8%?R%VO5@ov=2^xIPm@W$@L8F=XV5!Ao7Ras|GD)Q9XqPgkl z5vjFkTLWV0l$%_oNSt?#=ma(L{^B@-yjy`4gJv02>q|828|x<31KIu{lGAsS-tph_ zBhvZ0;mTwlIX9x3kHrnQ`qN5U9It?Qt}|a#G!2R8`cpQQYNFw9Qtb$h@szyJ%T$sD z&_uJ>t2irfiLh}b<11Ow5QneUfB+n5Ry&B~{9^dS&WPjcqUv>^vO7=F0V zN#;*tXpZewj)P;UW^-L1(L`9fMAT^Z8#8U(vNK)vP%}Y5r}kAKAv2xMY>q<0VJw^L zcqhn;bU7_?-d`;X7pms0g>8SCV>dTyB9w*=C^;4y0A*P3btFPht~8TXKG3DWv}b^k z9}yz9zEQkN4eEn!Nf=;lj=xvzNJSu^e~N%;sv`AvGrn8p9pjc1Fb?eT9gfFof$T_?&hL(i?SbPPSFjIP#Y**B&3dd zgr$F~n|ZHa4QhSs%PN45<{sMfnV30hf3ub(T<7usj0}vWX9ky(X^(u%Y54i*&FC$c zaK$@=McZ{+>+QF&iRHom!66=TNHaxb$n1=+->1DcHtQLTxPRdl{CF-uea8&b@l%0< zS?}>g?RlSRDN8rfn+plk0Qio|MPyqqNF)qmk4QsWx+4!c+WNpBAQL&%=qpz^sP6fu z6$wi44h{~-I71mSi?-vd%2n_|d%`&jBtlOcKwkS~JZ9DUkk;ZEKq8V9v9VO&Kl0q_ zkg`+6(>)b9?NRzP$rg|g0DGR$Aa9z&Gf|7YNC3cCE9Ss91*Shi6DxvOK!tOOsXa#- z)Pq9XD@Rn6L0e!QxqpG?L_{R$MGkz00rV09$InOIEv=`*)lGKU>@B_vLZ871LOe(f zpaJrXm4Wy<2GlY23JPc-jL~+C`hq&k|`H#XpEKt)@ z1o}82rnh*2sQ$n3fYQ_fQA+PqS70uA*70zwUs}E$f4{u{%1IBk1IVJJ^lU0IW11kQREGRHzL`2T9BDJ*uERpeC!-(+E^wq^A38U=9VS-JD=v**a~OZO|Ka1i=^77qH!o`oXp&Ys<_ zAQg3B)Vk&t8zfDK+b0!4Ynu$XdSj?!!Mp$c&&Bbl_ulWKu2dOgQ||=zssUfg$R`YW zux9kTS>GGx%#$RUmMQQokt)*`W74oG7j-D00u@a%C_~6Am_T9+6etXNCSU4J(xPDl ziEu+ykA$hg8dZ@;4C1K$T+rr5I2pfI(}I>QWs~6~TF>NEi!OEKzL{p?Nj|zt&J*&Y z$L2~vNCE%C)l;QEa=F6*62R`bo2s|M&fYKMkxA=AZmlSy%?t{u+Q>@HCK~{Z!=TR` zc@DT)G-+ymzd>?)o(0rBk|_->OyN8g+JpVnB$tPj{-yzST+uPmEdlz*=Q=VYaxTyj z#vxtF23e{dq>>T#)^Bzzi(NUEg>)szXG^`gKpen+^csmS>mIrHSf~oN7lEq{5%{eo z!2;To@NCe7$g{j+e1rcqJe_4)7U%tHlEwu&rN+1QqZ4>5Ee-|RN3C(N$N+QK9hgZc zKRPb>3;-Z+AR*ahmdBQW#Q&!&_Aj@uEW5@HE>i2=w6#}(M~T$b*euAt?s|CzH;+nM zKgD*TAyG0VWMMo!nc>Ey@~5kh_8SfO%Za?vAa%57h%K2$vltjvTtc|)TD}0y_Wk2H zpNG10oFCEngNq0j&1iN+==eD0ZW#tZ=o4a56$Ogo`2j$tL>+W5z{HdL577cA1g=;X zT)r>fPzoh2fm-l+&I5U~Dh{^Fy;MDJI*7Tg`+G#ldqi-(=JuGnN9SOeD%ykxbmPn1K2 zpq7GT3|T&5urJ&i4_2cKK+7!+y8012oB@L8?!DtK3uwlm&##NVLU1~OIu{5mMl}2m zJoMvUoJeP3hPU_+mg(Gm0Y5j6)EcHy&+5RkSrek)OZ_{_Q}ydZ3zmL+J4Q1lIdt>U zGHDuI8lLl9dO7!;4NOLw6_op||0G}lEpgBvfU8{KOs<2kW{;eAOB6l=Rk{#wF(f>u z*(VH*gGn=^Cr)$-k2m>j@%Bxacd_Ep9%vc8KydhK7gd1Jm8BPVhhDYA8z%=FU$?gB zwT`KUIv)m!?}Q4FvMBs>PtwXNS4mp@B~|#Hwnmoq4RkYDZ5Y~o0^Ynix5`3E}spZ@7V9vITGpguIDK2CQ$AeuCHTq zhUC0~2*Sridvc1twYKo2E3eLEv@laE@~AX6A}0kd117}!tVka3m|Avdw5d!C-ZEo3 z^Y(3N%M>^gY@RySHmLnm;J0kNtqrlV#l4&uXH1>smsJmB)*pK4Tb0kPj+G37=;dtu zZc{P$r3_wJQ!(){O(s&t4pgdvB^q=lxa7T8#18m>qGIZ`MQp+%NeSBLip;ry1i}rc z(jq^JwH0tj{s`m3$pn|KPV6~4l1Krq7MHXczO(1GwyA|sTqDfTL3qK_hv@cgrnLaFO&B1TC zg*5OUD>$y~85QVxyeZCR4(k~*wQlA`>q~Jva-}Q3ITf@9tIvb%FY@BsCSM=C^f+F^ zy>zk|KWkIM4nxX~CNSkeao+xBi6`_4&8ecY6JV80K%Kt~U93XGL_`8kgoH$~TIz}a z+%i7&Egj#R64b8Qg~+63lIE$Ss=;Mn9Qxk2%%@bTkpnBmKG zt^y!nEspVj;+JWigPBR zQ(vO1&q8=+-%m&PKj^oZPi*Kana55loa2E!)EWVk4v;Wrf^_L6&tiI0$Jz`T)P8bYk~l? zxYfRfP5_nGxY}qB<7==m%K;PqT*$m*ONr_R@Jq#vu0w~S?s`~j}T zmg|h$&a@&4nNT~R6{4mFH02^~WxY)fYNLBuTiXmgEsRg7tvTRvVKGg@nBPi3Xw>^n zgzUR$VJ2-Zhk@13!o^gs713@Z-Aa$upIZ%%$AirXPyt2Rg$Ai0CyFphC=k<@t`LfK zb`5ZSpC_3{TSS87d4x`~glLA2qZM>V`ujU9pp$wr{2N_4@vf;j&U?vquR2gg!K#9x zO6>xz6yVe*SH=2>8y~t@lf5D7cSGdxZvp!II0Yu6li^W@bo_k6s(~@^jWT~cnJh(G z5|41@^6+#3u$XPj68@#j_{rTXgV(o~x}r)vYWu8u0#;CD$R^7B-+zuOotF``&fU6X z&44E3&ZQfsV8-~Q0Viqo6s>tfpCOs5AAs(8IWH7ECvxtJ3|PRo3#n`nwct$xnd2Q0jlkY=BI)h+ zH*?04aO5S14JiWMHKKLHRuRmDS5LXmAuqw77i%@l^5`L|BhuA4Oz@7vqNd_SyrN&v zml)v1lN;00^#(Ykb3~{a$%Xe6eMRGVK6DO9@Zw5l!BQ4M@zw#<1~zA#){Gpc9~%~Q z-w-w&hh6h)S(+cfGy@NZwkP6E=9!AhRYLY`lbS7=;Y_DC$82y5L06;+Td@)@T$Jay z_>Gdr5BQ{vQE2%h5QCKz8|K*Xidmdk9a zPxx_c1lU^B$wOLS<0aVHSz;cY>EJKbzj#7V(lGgjb#cNLiW z2es%(_f`2~4kHX3b|k!q$ZFG@guhk_XaCtY2zNp;HbV(cBySKO5{Z*R#0fVb&|zzY zg`fis=wJ)X96rW~j9Q3*u(jVrSQfxzlsXnN-X~eyUBf03;A5@|N8aFCbgS`Xn;1?Q z;gZ8OEBA4e4368i7;vmPZy=yb**SI_IYXVfIz`ENfIR~cY;Gc_wSeo_!U86h6Z&e2 z^lWoBn;VP4Q!Ks#+52#riO=OO^7xH#EhtnR#@7O*#9BV5*xIdy@7NkoD{uVGb%7D>%S1Xisf>gV5 z6SmqmK=Vwb(IS}_E*nYxe%pi0c>na{9{S8~vPF^Fbzn6eU+PoIzq>-Mb$uUw=a?ai zH%%2Myztz6LSJ6!h3G9!c7$DpMi3-w*sNlYy=x%^{M43r59b|nlE_dVHZdh0dq!C%nE=q-s6U8bkt40(L)zAc=0 zhCF)@WVWzq?#jkUUEYr$*cD2PN)|&2h&k8S0u_0t=WV~Y+~EWuVA6q(VDx`D&^I}D zA!!Ae9*~RxKx+0@J(^a^W07V3*D}E-LofUgu%m0%>ASxvgFh|X?}wiYW5Lc{=_!*Q zbUEbGAPw6YFkUI(L*@0S!@d8zGG`v>g0uY^aEuJzUU!0d9r}>5iITs`YEj*IN+vsJ zOG_Ur-Rd^5{|5hqhtPLj4b)X9gv-1ABYC63tzjYj=6;CHaW;X#&QqAi<;_U;Mf^ev znq%}U;fS8p3rBp1C_JZuH55t**kA!{pWUH=q0ZZ4dVzZEx8c{J_-0ta1OllnPtR?v zk;D_5AE+08sBwtdqqY&cIhWn*QnGK!On*$poMX592L)dRI=PE66qn^3)mfP*J&++V zVw@unQghT(gsufcyd9trJ}I=)N6ug;5)jUsBh#EfR&*C=>FJ7fl+7{Dz{3uQjK*fB zK*wxh8-^Q$rMOsYBW@d$`arp{2Qo%(z}F)9+4C?|XMp#Ft%WKDoh}4VCg?%bSu)38 z_rR?|_p;P}u(N%>VQK?Fw?;5=T!MX<~G3x+@W(cI_K za(SAMXijRRJ)nZ62GmbGdxRj?Ivuh1?c;KNU5MbUIkFtKyouq0C@~C_mt$Scq^@9( zPD{WUy?W!C@9%~}<_Zz2ClgKb1kzB=?i^&n<&>B2xFPa~K}25aszF>Rbe?88FX$L~ zcJ2iZ*|I5XCLhMD2nR@qC7!^x~UXYXpX-I)Z$-M;iV)0eHPa5i=TOQvfB?F zIqzn_mM&7>S@dc>*R#}>^MfjV4>}>r)}=DDcY3hd&&!E{!*)RUz7o+i>g-agS8Zcy8Pn}O<)4FD> z7B}(QxCgIu}gFz?b$pj~n>xePp<;SrTRxvyz zw&t1SO|@7BBZ7Oo{wEJHq;(@&(eV8t>I)D$qJC3E!=3maUV0N8LkhJIWTe2k$4iF$ z`g`M&Dq@1m#Encw?EQ0L z{rkPUpWKg&F^o6Rq3EOp=(f8YTU8xa@fd4of$G!M_J{ z$fk*t$NJ)65d50lw0N+Nt%ufWKVEm90&gA!gH^+J+6Qkc{=Ck%ato@^O`Y_;@}_aP zWRTgT;-Kj&WKE?-Uw~^L^m+~DTWHDYiYophb{ZluuaK3)LEIHJ7=amuY@5F86~qM? z)Y+=C$8GBY!T{e6tzj)phohlQT474qKt7K^L!t(%14?AN@7bBg)gCU4`_5gLg-(Vu zVtL*8$l zpO>2dSBp;N!A^B~klTD6CJF(?neAuEDs&0oK|{X|6NWa=Xjl)l=PDX-R6YResq^+W zKPP`c%n(}WXKEs0hkx2~2{@#4bzcp&y%XBD(~Y~#iBx>csO~&I@p_9n_506GCKiV_ zkL1{8l(Spj8z(xkR4@!yuZL6h;T;iAkgsF_q{w7~t5V7^=-a4ts`&#a+Qudkv%oF` zk(j+_GVQC_lw^E$G@xX8@L33=`oaN-6a2IjL4~NX+>>ur4pC0{H@NoMS$E){l$!k;>Sn$*&?HYkF`8gYXZldnDni^PoHlgx zwiFZzMbuzDuYl$Jdi#hjLORlw_>&|VY&^jYHr5qCAmr@_Quk!k?x+h7aryt#e~h(j z8d83JD`Tw>6#};@2x^woWXVF4;bO(7OxKN^_XEcK&lK)$*b17at^{ddUSOmXNY@~+ zy*^e%#BB}*ZU}e?vsJZt{Gk${Jb*>fmO$pf6Jqa4&*lUmwMXum>EuUnI_TL3&Sx%8 z=R>K6-PqSvqDF&L?Mc!-wG>92tMJL{?&*R4%DenWaIe!-Z!1?%;o>Dw;DE|)JY$rD zIRnPcK~3Ew;M7&^pnNA$Ta=o%HxATgkq$}UEa1Ufoa5$MG;I{5e<8oFUOj2Fs%8mE zP&a?V_xu*0;61(06wN0Hk^g2oGUD}U6qnTYIZS)J@02nH(!ESHaC zuKrbAKu18RR`8?zOMw}qtA&qPTgThT7XZS67OksA7@hTqR?A<-JzqJKcB=*8c9i@Kz7093?>S4(dG>pNQiPARcwN5^t90 zS=w*oRwX3q{2hxYTA|;|=9!hHAAQO;z5?hzvVW(v+B38u5$}|7iXaW`zzQ_10PEsE z4Q@IJv1mYb2Vl|!L~0>S-jb6JRwg*|l#tS~3YeE{o|^D~1P){ei{io7sMBU=IDQ8S z7&SmCPFk5Kfd;6N?FtyTpARlXe?D45z5KD}?pPnGJ9}Sfb$dUsP&@IP%E9aH=Tu{Sa2ml$q z^wSi@=*r4tG9gvsq}KK2jMm803n)?E!Y~aW-hj~+Fp&qxoC4S_gS5f2Pc)cRC?;J& zH~zDthh+#bI=F;LQFfr2KiF?*Xswh-oYP|5+B)f+{s+go$D%E(1+Ed}QAy5wAmX>B zqu4Z9O|TFEEF6=HFOz$Jl^NE+3&0?K^;F=7ruG1zhZzQt0}9th;oB%Co-)_!g}FAd!TM1 zyQaJdfSEM|-_R32@BpF91(+7w9KBj%weD4p|LV6AL!U4b$rjQu+t7tk#(`KGxQs0B zy$U>Y2m^>0+w)afgMRTlQVDH6=@xEVM%^EI;KClF>xO0L$o-pOI&t@(ZLn1S-R%s? zR||&XY)3A7Yr6H(i4wXgB)kV`drNnH`xgg&J|F^+hX?8e>pplN8K2DbMbk1L_}Cu}mn-}L_)-ITM? z$L_4MogC}KKvH&SSphPCjN!nq5XqkV5tcobM(b#s=W3DfD=x>=b`%52HG8n&O$5jHYm#@rh=CJR4Gb> z`9>>{><<9g4C$rfUov)}r<@k13;7fZf>l)NZF~fo)FI*kS#z><2<6-UCJyXBav9Lo zI<2}Exvk{$$k%kd{z=9=>kTtfLkT~ufj|ig-cj!ti;(P`^?`sAqh~}e?>UHk6Yp{j zAc+nU3UxIKA>-{WA%l=AYlf+aXUh3vv`sil|J3`!N&}BUiinWgw2!eDoT+aPJ`Ixi>+fBWNsvMS z7j>6@f$(+4E@+qs|CX~+3C4I35ok;DsJ0%2#O91?v{NJ?Q#nixxP*`@@-S9&oe}{T z!9$wy-M&C=UQP}QVH$;s5m83k2a+P^|GAc8s|()kjsqi*wc<%!KdoU%5j*h*4)+2~gI|Azp)4$t)K_!A9)N$0@i^2x&8b^td`bD6$ExfTA~^$f*{NvZ}K2sbvvzs9$zc1-MJ1jj)Q`i7BSTN6 z8bApNRMvhj4woV1sNCz;BUt}yxrEe?LwjEpV;w zeD5*w^XQ8$@G!E;?4v^tqt5X!>Rt?0Nf*wj)By+qC7hz}EV3qE? zmG^AttmhT49e#FM^VE&8)*xw%Px^)Q=F7jFGw0@|58IiE6%FrPOqaC~B%tR_nDNE#;3V?S>{$O&%RnKQJN zA?ia7WS3+v{I6v~qQD&!b=Q&jy=wXqE?mmh9?G|yd~~AULjcpryK3<$M^(M#Pj~LW z-2Q0PaY^QXj>k($GPsy?)xslBjV}0pL*l7r5`(Pl+Vq`zuD;R*8Fa$Hrl4;@&l18l z!3Su)iL_QCh3F`){5e@N`+HMqd4)DXqJ5<3!^gl=4cTV%1G$W=;Rt*kMOqB_S_Z@o z=sS~ac~s3JS55eGR(?OM$7LQw#fXO2vdjr!9BBhK85O%buAmhexe)=1`Wvl<*#-@e zSdr&J%nk%73Ai9O{#vdniUbZA6izENE^r^zD-g~-5A(RdnGF^c0X_ov>)PP?XIF>( z=Sosy1Qs^ppCV7I#`pJV79gUAll6um=zHl zD-|Yg$QnCOrXgh;IHV`?QIbKoHBng%=^>e>G8DZ7k89*o5Xkp?I31rp_Ad+fPj{`i zjkdCj;5@8Z(r#AAtq7ksbnlCen79^uluhmZD-H9r%AxJg1f$*uT5xuOEf2b!r!yU_ zx`^PFTOS7@ixs1fd19JGiy;rxIHH>aL9;pFH8?15$vai2_6^?5tGZ@bcEndUQ zy=d?5nlvYm+fb0ii}u0$s!TNU)bK^`ZEHkRYr{1sC=xvI1d9;~NP#xc9=Y%S<}UI% zymZ1h+MQ_EQg%jv1}LK^#J)Uc@cJF_=aEX6seM3$kLR1os4OOMIpi`)z~JPmW`m0c zk7IhPAk5|JsWqX&&Kj%^k&cj8u?Sizu*0B!%a(IjbSj``r8=pu057=upBC(&?!5o{ zuGv3~C^h^0rnmY<@>J_9GhQn?`=qZ_)PS#&y8;x;MKoxm)wh?$6nJcdQ9LtU4c5@h;_IDd*h2OV

jEoMn8hF( zNCfjAtVkx1q#*D)MX&@0WL4&YOE7$A35W}E0Q-6hx<&fw;w`HY=v`v4o)Lz(0z=O) zMyanYN@tdVhqCZ|3TBj!4I(U&1JQEmP%$ZV=11%QnH%UKh2{_KN#%Z{^@?4uLA`EHu;z%+>R>t6Zjk!VWT1VB zw4UoA8KNBl;ddyU4}SF+3TEmiA%;{zw;30Ih)teW7L(;*Bf9KvWEN+Eg#9GXlT;W= zn{m;Hr+Pb?jrN;hxF{3^5QApxWYS!Nuy(gV&cc3@hDF_ET_!{JPGER$go=cC+X>dL zQ06oy<$9-#_YB1^2#DGC<#lWn1B%?G8vJJG8yRl3_V!g=BT_KcUG zmn>pdIgC#8#l)|&BE(WURudb3`VsiPCd4(JmgHOk01b}VWgO7ve)#C#WZz9#l4PUH z10bYh$Y>>QaR=0FnZH&(wq>tjN0OKu>~gfklZHC+*fRGcq-ThiXQ_m7Ea#37Tm)>M z$(Y}%32%Z2PE@!|8laR8d$c0w@8DxvAh#ImoohhJ+zFqDde`+96F@^**|w5?YuCr< zjYVTPr2k}J%s7wQexkZPT>$;$e`i7@gD*M}2DpwDoNQc-jT1;w*)@QG$D_Yh=J1e1 zzwn${kE*nkL4;FpQ;ZVNEdG<;gtVK4xmEd2zLq&_F@QQz z4)ge9bHhrz#*=A^9MJ^xkxg9a`VE?~ z;j?j`7KGct$qMRh0sK?u#ff|MZ-Lqv?2N{X&mTD>Ii7C@37|Fgg*=Pl7-qf#E=G;M z#Hcy3A}E4)`t7Z)1{lt>e@mXPhL9EluP5FfVLX-FLbsix~@4RnYYIm z4H)Ahk)GNBDqEgx`uoevX&L`yyvvBvh+aHbain~HdI5yt16TQk z`0OnbEGYRn8sYrbULD_Y1(#=o zIUFK-0jWoYs-t(GydT2`@)4dnYK7!hzVIQlC4T~rF-dP4Zf|1O^Vwr~1 zlq3yegbK<>RR?8ZZgMFoh+%E3u{z|t3AR2hSE8sB7TT(jM=m`rx7?8b)l=CR$0) z?@O#d2U>q4+80mGv}wY0i6i$ZpPw!}U&x|+WQ;M9Yk;>Vf2P(sVi6^Bvi(?m62&T)B$ zB=62a-29r58PJvhX>BQX#tMi)&Xn49o*J-o1};28d0`=&cxJ<=IHWIK|7bu_63efC zblk5Homnc3)RPc6hTxnv{g&0|4KtzxB3u^k!{ zeC904jQ@d`<$ED|Vj~2S`vT?b2y67{U>J}&Lz6fIlfx#aOZw z+MrduQu1_H19@5ay-(xWjPx@Qkm8sg2zpEu%5H*8CrX=>j=n0je3n@<#i|8KJJQnO zRsra^y@R7*jY_!7Bw(2~9y zmxKqpzpDDSWwfE_A63igKK` zkJzLIzOt-=UE%GMhqk$+un#OT`={zbY*8fU`k1+@6)X1+8H)at2pe?FTNM9keDNLDXO8toLlhG8*szs;k0f+jXbufwh2DEE_k^R{5uXLlBujMj)W8`Z2@{W zQrfUxL~Rk+m!a3}-nbIzB2-f^q~`w?f2}#tl7o&<`{1#R6!>=Nk-oYh$iLdx4yu++ zML<>WEf{?bPUUi4sqLu&)I`DXsqaF8RHdP`IK~Js6K`3Y*uTn^hD8kpW#Y>X!`J0L`o1cBBTPblwRq<+ciC;<(Mz zZ01@x4PY$?ip}geQJvW9P0OL6O?4L4Bv=T?mB|LkxSVV?oWwMI$*Ap4`DAyb^rO)n zitlAw2awGAo;d8oJjm6B$aCY(ShbS*=s0`>s9V!#Yq*!xERT zW6TO+J{h`$hB=tR1*2$2Zzy8gAx#V<^;rN{?C0ipYRTW(l(|S>1I6*#d<5qpwQq1N ziw7nUc2@8w1Blf?CHv_3yXAfFv-oY%?{WGrbM9!(klpy~bCR~{ zw@(+U4P$Ojlw1ehl#urd+jk*LkMl3OB`$qT&LhE+ZeizflmCeNfK^>uLn2$FX>9!x z7X$IZ@TUV*4YAmhU(x;0i+SS8(mQJOZe6G`g1B#{M_7cfR0gFHm?Oc{C+K)|Vqid^ zt$dG;MG;l-DLGsbVC2cw0YxWY7xATrt%3{D6JS$qhB~Yf+;z;xTk?O*!F06sTn|PP z&Mi+z9EMtrr)^f$orr)g>nde&;V5zt;QEsD2Q)~*XzPSe zd}@!xE~6o`au6H_H@>+9PKA3eh;QggTmib4$Y((`fOi10))9yuhP-RG<7-MKGvf$C zhx(g6tsO;Hc}Oi0$^hIAxnM!j842ox=;!Xedj;g#A;Yq}!KaY``cfSv^JQckOn&Q| zI}I~_vfKXk=JpN%!NwG>5Cp#Dxp4~1(gFRl6i z2>aTArp`3&cHGtNcGS1i-P+b7v$c-XSCKkaDaMfLm$s#9tuw`nkhWA2Bcu``LP%2E zojP5sj8#Del5ShI4nm4ZB824FT15qtR)hfgI93P|LUM$V974X{>p3_xyE|{)Uyv9f zwoG|dLhG?7 z?G1EdUf>HDuoU&7RuO5~Rg0Bgl)2n&4}50P_M?^rR`Q@f56f(2)7IEIU{>YAJ~o!u zSYC0NM0hT}_99?h@L7UOwbR++`-9L{;iX$*B@JY4UecV*kYT1#E}WZDuS1_7T&gJQ z&F4mcq7^7!PjQAUqJTikslp}EYh?L7?CbtIcIrJWZ_N5%FDE>!x7tn~cje2mSzd94 zcb$8Kv@$7+=FWODHthlt!91Mxat855O8;nQtE2dVQCU4hW`nJNvLXfntL_J+R;knL z7(!$8LD}t%unWo$vHfkmUo(`*$G%(6Og;~A=FKO{cMtW<$Gtoo;79sy#T*mG} zR3d42*i`Sp72&qeFqr>naWotP$g}C~K=`4$6!w2!#=kwjq5Q`8&*QL{F6Q~;z);L= z)k44TbhlN~W%7@Zz`9tcfg)~)j!N^iEg4p0+-HV4!&2n}$ymg<(eX%tPH6nXrF*xu zJXWbeJdQYKFH6pk`jwVVAolnJwh(wtq<@#4Dm@Zc$=cz!;wdoc2P6gG>x%GlgKzO%eX)tQpR#!B!s2dYS1T;O|&l>Oc$}v%&stwH|uC;z=Qe< z|EA4T(|Yu_=tfyDhpH4t(ObeDy~e6$x=E>ZHCZx=h8;{li<1gWWxJjY;VgV)wK5h4 zV%3LJE#pASN`=`QAz-Dsk=^I(V)s*0CTxC$#6+Yaya_T)UF;KV#1O`ioe~g0OZDcI zs1ds(y64X4y=>=`;j30tgZV{lA64$LCBMj?R=k}BQUd3kCs!Vt{WbI^PhIW!W+eMM zLp@jXVb;t>7$HUy+A8HqqMxS1?BX>{-|Dw!o-)egsC!cL`4o9u{@s_q&bI4Y|J8m&W-tL@=E=l2gjzDeh?v_@iW8B;L zQm~ZYuQkJQOk9Zqw3JUKB)LW;?Hv+GL2tmMfk)Sn3BypRt7cAs+hZ#x$AM=bs#WVK zi86^GU4_Puh;OO%lj&n!-})tjx@9*!JbE#VpG35?oq0H}8<{<_+iaUSBb34(gly{s z#t(YXn2ss3^w_vC_fvR#lQGTahJ9o(u}+4lkT{b|{|j&Hj3NWP`*uDP=33yh1br|6Nwz;~s4^-}eE zQ=C8`zr!V29!^KpW;syW?9dw7sQG>A~P?L9XG6vtcZi( zpIQAMs}e(kPHdBMtMU2;fTKbf{R#D3gQ*xtEaLXhZ5+2kR5|JU_vqlUkWWh%XlskJ zo>&1wS&D|9Tc}l3ClLjyA8PF+u`F4wLbBY5>E9MJ=l2(1PW=83rq^juP%u=Ha_ryq zS+oTE=gJP+@FCd@A|$Q!Pc=bq`9-knx;TmDv_9Eh&?Sp3$>B+7zkN zASYNB;;&|i@QjIknpv~=8iTc5<TpNkgN zYwpsE{?DKL+jcsY@S++v24KyRzskcc<1HrI)R?Dg$^E6;Lw~gQhxg~@AUHc7BrEUq zHdRdH+|}}`a`U3%sA?}F?fe1V*Q6%%X+w+G4~9@5Wp;(G?RdcFTK<*)7xQE4)?)QO zPF5~%MJgr7OGIB1eR|WW4`r^HyoV{hh1cPo}*xoPCdbo&ZY@MjvOQ<7R*10hDkZOv~{?=h~Jp%Ey>LEMKQ7p5n<1 z%m{!syq1bDvmx|2nvQvBD7MM?adA=$Mf7lVVom+n*M#}Yltp@1SMqu!3{1lZ*~{X_ z$<07V{>E+zL#iqK;*J-+_~EN5^k0dKN0s%DnX!M1upIy*D}E`KLW(IL%=aYYPM?Na zvMQ?O|8G>`7ydP?&+c`fvC~(;3x6mu+!$W6^S!p^*6d%huGNZB&8#f9(R56CVrsOC z@8=0Ge#$S5<_~zf06CD!$G}36{WYkO6H|kqyJF3i%n@h=EX59;z-tq%iCjvq*6V8C*^!P_xjbnM2?LD`r~HXLW>i{R3NXG<#HmuL)ki&T$Sd zj~HT&h9Lex$60I$V6DwWO=fX4D)XL=I2J%|otj~j_ze9;W*ed6Tb>l#FrCA+%N6Il zb{xMcrS@!IY_XnEVVHcLd48$>_(8pkX@qYYEDnMkjKa?!P7gG$W^G-Oh?Gh5H<@0FG;0=re#l%bHB*1i zZ33trs6M3ih@g&15-un|t02?5ip>-Ty%+(EZ%K(QG?87CQuasksJ1APQ z%+$JiI{*XG^)#kWd>&bGSuPzktN>p{hteFb%b){m;Pz?xbwaZaJ1^$KxxV7LrI}=( z&a>NzA2mA9W*4ZbAiq&}Oa?Uv(hJQVyP80PcdXzy<=IoH0yrH46!f_!o>9~gkLt5# zA*ea9DG!6TrD!{OQ6dXONa|V%K?G}v6a1!YQL-Cvu$|RpREAY!E)E8moF{%OemZF9 z?P{j$Wy%#;?JiqQ6~Z6gjbwCkvRN$bZ7Mw+OU_29-jSqBGs4Nz9JiqWGAWsS+syIdV48pJv-)YkYp){<&7phx zZiQ3&@zrnn^^WJ{Gm{Ia!FhG|*H4sozt1mdi|a=O@T23>?18P*wre)h_iMh>F zqxr7=b<+%+zwZB}aZheWWdE^P>w8gI((Uf0>iXTTD%KX2xxH1Cp$to zD*eW3tVvB5XfRC=apxrREy|m??-npky5cu|aEz=yyHkkKJox0WF>vSM!+Pu0T#wPQ z`jfC9<42(B3XdUl%^`#28LDLLrRz~&J5EMy)D$FKRPTv^)P(RSk^P0MbZ?%gdPnM0&54FMe1>zZByy?n@bIo(>M+quIWKE9cq7?9_&3WlVn%oT|kV<$m& z*Qq6eYet!8Nj@E}P=WHBB%0=?T(v>-^zP6()*GocAR2PsI|}5Ld5Od^%equ7U+LAy zax)BORszX?81^$Y=0B2z$u7bR{DnF}WFC;7nvL(G?LJgwP&L9ldrH9!YSR?C`VW3I zHf<{UosT~GpOwykeSEtNevpP?<`ATf-B34HM|&JZoSHZI^HcpmU&X#Bn1t)p|>deDt&cLbZgKYye1DF9aVCKnln%AuZ;Q5 zL^P4>XgUSuw)T!^Q#gc;C-DdtKkY8M&-%E*ceR?~sH=VeKIth1QQ` zjei&=+?t*3(cn$Qird@?{oM9Ccr4=UY$6*i^*f&h-;``>dPhxh=ASah*NkUU(-{C=Q{^dEnV80hgSrIfX{&LBbB|kV9tyeMNn{b2 zyGvL29vkjjfG!Z(HH3xAgq^vf)S2!V+v%Y!vj)q|$m9}7f=}e`6$4YlWi{DwkW;vC z78%IdRB{OpAeG^+PG2}0jPSaD)3D6c=RKc3%j~ndfWqj^oC}#sXOhXtc6YN6!LYC+ zez`=E??Gq>HY~PT;^ zS&^$u*O^jLt?t^OZHKA&60mKmEEDIH(*pY>t;EAfNIQyPd~r;HsmVs{1_#GiENheT zVD!@*%(U)KjM(uGvT3DmCn;^~`n;YS<6NQ13pmW*%6*i~QbB>fy9d3~-FT??>`E7w zYrfHW(_b0P9{fxtP)rN99q2N-hkCNF#20ytwFJbgcj>-V&sR3rgv#=_jAGFCDL5#J zsqQUijp9dSF=d4HtJJFm^i{` z$!+25M1s`lm`VM|Rq>n|4bPk?~44SZT1+B^I45+|6Dox4GrtwW`x~X5`cq z6N}BF4*NBN*nr_t9G^o58P$wcmogjQw8FD~;*TBA=Gcw4Rh;#ND}n8u1nAyAl~H}r z4eXG@=j5x_>W9D{X@IrMU_|7-+4_Ro|=LBYLnzrI$w*2gu?+dePpyezr`M{%`T|xF==ynn+jL%SjHG z`?H4P*faiA%|TkKKKY@MfLhqm!rIUZVh9Id3^woo(<$@paGv`wPMPuej4>`8B((a$ z&x45>ax$!_6i6W%B(fNt*iWWVwm-{*oPmE45HXz{{`6!roR$A^u8xSqPMqB)G){(0 zRfb^m!g>B5lg9wI6`8K}HVG5oP^2RL4G;To4?8r(%B*7fE7MAUZm7UthRLGSE~ODD zl4r930~O1ZITpiVS?m!^mRp;+@%@nATVo5EF}L%5Y@*3$4nt*=_Q~a-o0Cf4?;U_0j*iP;_6o?!Fp@)%ulqceRi$ z_5dHfUszpP5%vv~>gB3!3~@i*=$Ss=4gc|jg8ZnfQZlTL?}2%arlhJc&>c(|MB1*$ z!I0&%;aZDHXl|@b zfE5ZBr_*xF+FW{=Hp?k5*TL=XQdOA)KafkP}-qD~7e7@#}WusOg|AgL9^+ zKhM()TrrZ<>OejzvYj+p-fJ(KVqSaMV*3&}uL9_X?aNXPa8W>|BzEZ1)U&xXn3bb} z;KE?Kn^?p?x|RJx5&PF>OpX+(OS12xqy~FTNw0~hbULT1AXGvHM=`PW+z2uyPfBeb zcX43cN(Y8VMs)&)6bq}P-C)1;dDIq33$0`@hfpq%Hi!L{?ygAGj1?iTl4QcUOMW~{ z^@i6Rs~k0G8az$PWt9`hEuda&CUI&n!Kr1`fP;DiM}IIEwc8Ft=Oq5JDYb?jLee+E zZD8MClgA$Y;ZjSzf;6wfO%UgItrWTIeV9Gqlg5SGTos0;t;)tpXFQGZ!z zZO{>qv4rPyEZEv>Hp{G74!Mljqd!^HH%y7ax+TBnTSh;il|ShN{`_Qk;~)m3T~tF&>h=e!K4Fm)pE$ZOPH+)%!&7iU$| zBgJMg=P{AR$}!vvANo;sQ8?^3hqnXbCrn#SBzuk|RAMoKsV48#-5Z|_8Q6E>vbNC5 zLR_upI+jig*cQXs-CQNm{i8m9b0u5wm)doLEMzGcs-`gf)N` zf?6e`I1z?pA5iUOge(KjtV`nu)s?$2WE^zI*dTvz0H%&l4J4=Lx>B}8H@-u-V@3U6 zd+jYl=Z`f_9vxjZp+2)iKrJnReO6fUOs+LO&uoDH;76S^$796+`Q&ZUJPrG`l4!wr z9WWW5g`F;SqL4_4={Kb9HC5Q?{9^m6Rw#NGt==@4_vs#pV~UD2IQ^8jhsjww5&%_*QI-B8m{V4VW(` zQ5^YNNEk4%A!TGbR6$%G8ZlW85>ZercWWpdoqa1Jqw5N97lQPHLJ-wsIK(U&NR;C* zpp;AsR4ad=H$;J(Ac}Og>*!r$X^Vvy7AbVjGv@EVv23OuDWlbXNMqffB`Lq0I#J(} z^O@=?`^0|B`Q-A=KK{xm7N=fA2@l3h)3=B0jjs+~0>jfV>*VeOogwOHPrqf=>4?Aq z`E5d?5i%0DRrCo^6BB_{Jh6i1%Ja^f8bm(%68`Y9m?^t8VYrf2j|pq)mb=jP#_W)Rw_u=!{zk11P(${Ld$mv-0= zTnbhC^^*;GV&drT#i(|mOa#2kKtfegdNWK%12Tt%a^|_ zAeq8p8B6>lK!h^NL7?*0k&sd%tLEnAfpFuTt~S=8G&4ubNvDl`%bIi+9HyKV#YwcN z>Z|(k6lI(~LR#P5;*Ou}2_T2D-Ve`EjW+cRbDRk6@(dY4?W z!5DL07Gy{L`-7mXA5fai=Os};TuRdgiv&-c#8_csM~^rVMrAOj-C{C=kGjVRj%Ksr zC{3&TpN;E}Sh5?7582633+`q*v)OQDC+XpxW4fMIq zOFKY>l5sxH(Px~w8ORl_#^>`R8@krCai)xHTpsv~VFwLs&k~2(Z;mJv+zsi!CIM$# zTIr^9ap9)Z*`ogpC*y|cIg?Ia^RYQG6>$le&V5OnTNS~FhU70?RcEe^XWL^PXM~L( z<1XUbuTfX+$-T0H*xCNtlLv{E{`!11-ElF)r(9Usz-jBRpR7b=Rb8oUfJSUXw4{4~H5IJMK} zWKGKLpE;g)`~K7PBT#zR)Bxk}Pcz2-{k`$GXWo|un;uKl-A9_Q!;%)}v#4thPZ^R> zj)=~SSR0P#dz6Mo1%`5XfZ;n;#cKM=;EzlLMU$3u#{}){yha<_sWF-YuA|7`^jB+i zNGkGJD(1#~Cr}1KL?JV@oG?H+3wmjX107eVrD*uv$++uCN_1BuVPoh!Y?VIT0I)LMxaa@D^m=h-GLNwNio9!&PlFHtwC|rj6M&VL?vI)}cH1b02m|&8SHR zLVUF*%i2svY7>t-t5_V!X~L5RALe3_Arbnzc#NjPk9zjOn3$WsyI~db4uF36YvL-T z6e4I?PAXG!rATvLn!px52$h)ve>o~apqIk?OYyK$$tnoRJ9oC%SNPh-MjcVnxmHV4 z9b?%<^MW&-tf4bw(TrtmRL+fg;I#N~mh~LkXAf8LnzGID(paR<>CngKz&btT=(eL zn^Q7Ro8M26oFcXPhJ$59eKs77J!(=iGgQ(V%fjGA_o(^Bt6WH2uDLi6=FeIX(`MW0 zZzW`WXx2MKsxUymxmeh*_XaLrRyuaAm6{Sr+4-i$(JHs`r~*&8d0IT?bbb1+3&)5d zL&4w*0{5tK~Kn8-X1EeX|=kRIEgy-Mw)}C@u*s^sOcnzsHhVuKy!*j z)I5-pmWcguGj(r^L*3cEj7}i+=k-b@uss_H9Z=`I;weh!pvb--?L1T&rklPjiCd3^jc<;$sG!J`Rn9>P zo67wnw!MZw4AKeY@PwvKDBeZYA7&AEn5*ebnVo?0U;@I`ZV`TUPm%-g4{q$ku(v@Z zZ!&X~jn#|?PV^)VmW8$l6Rv$y-#_(l=g;4Lmnq)g>1%F8NeXZS#OQ-y&BLvw-<-Vw z9tW+l%UyceoGWO#y9} z3{(h*Ymf#ULSg(e_zoZ1MfhjH=mfv0hJW>7j2&s0r2FlVS%;9DpPa zskz|o!IebGUO;ycsX3Nw?Ou@io{nsex`QG&KX&CS0w zybf`RFX{;9TD@K1oUW$o453Gm_I6GhI4oxQ#8=o1p?1V~a{4&n<;Ui(go)kVIGQ(1 zH#Lg#_WF|O_Ddc%Lm1dFz5Ch;y^D23_}g6j&V?g4+UNY|?nVo}%18E7Rf4WS6_R89 z9B@iUX(%I&a@*9?)huMaB$6GvFs(mta21)`?hqUFE={hD1uT8jS4kBdC%IaUzh}dp zq!D=l;>unDE`I6Km5s*GyVJ$G4+H$V6xNpg%Z%)^3NDacKK#@^JYUGNa}t7k*~y(150N1-SmB z8ZslBImDJ$FMW-9V&ya=d_jmo0V&u8m;*%XdbrD`j7U%=w3Y>T;Y)Ruw2b&kj+RRlL03LF zg%itN+esqU^7Jxm_!aAHN2`A9anu?iJL&T%t4sXh1$nKn5)d}I@+JId*e z;$-r@J!pXI2SHgbdS1=6L|`bAT~OEtl&RQPo3yI-}Nkk z;1-Mx2;ig>O8>Ppjk^Euw#C0bal@o4|K42DJ;WL^Wm7UE-&%5*^F&QDM;dF2N>g0^#^-Zn)lGRu9zYX){qwqyA-*$ta2A&H99 z4Fe|3Q8;BncbzA5=p6x|{SI(vMIrg`X?>}hQnD#sQCX2&v7dm&yFyHL)E)wh9pEBI z2Z1(xgrH#v@d2$_^8*F@2VB{&x%v&00lXUXQfej2C%i7+vQZ~S9O+Y+j75MB2nB@H z1|1u90^wK~`Ixx4K>2e*#G7L7o&rV@>v{N2;Omyw8+L<`9O9C)ofdgnn4bM?hOb=A-%hf8WpVh643Eo7TDs)q+fT6i)1lP4ELUyQP7rN|%ML6(-*osu>UgLI5)IQSUy|4Hx| z_6;U@-%m>PgiGQ%eAy{yAtAd{s}tXbZg$cu04^+~CM*>t*epE2$(3>!5tksqtTmt| zboA}B2|~;zlK~;V?&P$zzQNdUz>Y30cN3rXWVaFfBwE?Fmd#_NQqLajLBoJ@Xg=~A z%1EJ#JgF1W#h0U@f0F@i^YnW6L$MeUYA@tnrxDpx;N->J}y{j>wp`wRM| zZ}%mBVLrFJSu_u_y`{42Qzu5j&q}k);$Tx?ev(_w0;I^)xS*)zR$Q zpML9s(Ndf)^wJ;$TAR7pG`08*%F2hm8jq2cPLg5@9K8aL6k|TKGn4*zN*w6SYUQpCNbyF^2YyxzWO+!#ZW zcfseuYjF;sWht>t{P7?LG?}4Ka2`0NHGERObq7qTkr%Ft?TSSCN}}iBxsEGfjo1T{ zKS>zxNivD5UT772o&b;J1buR-wrK5qwoOg15PJ;e;H-d5BhwY)IJ8a_oc*R9Y}Pg#ZZM#+?16aumB(ST2kZ{_-5&z+7Ss zLl2NF2Ci((iT06yG1hqXY{@dOiqd_EN!~9sJ6rWJ@ppx&LbjO2i=V%X;l@4poVSiQ zZJ$*zXsoHk)Y(5=$LkgZonaQ^{8QP&CFWxSy8$V$fud4+H$T)Qnax)|2~CYrG;yY- zRTw>84)-@vk7SjJzFK0F!EtP(vl3ji@r`BQSv?gD;qx7E`QG60(uDxYc0b&z0u+^x$GZzJsIiHV<9Sl+-e<*V3FQ=7JuZ*ru zHFE(d?pF9S{WF!TkM`XFFi}-s@)Wl8va^K6EHfSO_P|=~Tk(pJf%i;y?3*HTeIV5e zJuRM)1G0^;=8Ohh2Y5P{!d9T3r_7~MIX{sp3aIvBe@_#wbVp?q$sgB6qV2CQZzV+{ zB@8S`8nL}NAtN_Hur$s6&PQQBxhbE-^c_>#Kihw6nBot$w5wuow{M&PGf?;8dh-v@@|3n2+reqnWvl;9DY`#1((7)B**bE!1FnF9-x7+?{v6EoF9wiz z0Q2$svl!QmG;E*brb9B~D_1VcoTiK<#b))r*h)n-L~N%S>DI=!KSN|bm&FLF*Z7(T zQ-q2T!3uD_nz4UICoajopF2@^S_u7-gqPciDFmMOkaG(SMc2o~m;fCFX@-leNWH?| zc;~ULtPW#GZX^mFow~wKmMH9O>SF7$E9U)REI}X^hCKMORpg&s9BU`x`KBDPA>)3?vQQI@b1wL-SlP+BRl>(on?d2R)D zF2s~(!0JujA3kmmJsk@0{W47%y$c@*Sv}T3GX}oUBgh)SDc>}G%;RVgeP$$q$Q*is zOOF@_0ws1hnoI5P=VHu3X3<}RoC@LwY;6n#*dUi~M`mv`Mgj!Vs6qRK=e{ud!G+|m zA%OPj==uGOBc6=nP`G5xhx`Bz5>}EJf`J@_?tX$GrfYSaJM}W0vu!O5nX(=>lI#gL zO`I(JeRFuXB?EN%4JbB4zYp-GB5$9$npRAQS0Hx})kz#zE8s(iTP837`#rM484L!o zE-(ddIl=0VRy;|;_61T=69HZA^42+jE$;sAn_qrFm6IqjgJhs+`PS@G>u#hMhvhw4 zOW#VJEuGd~mNf8-QEK0tUud8Dv@*qIWU?7P^|4dyw=3hAb zwl&bd5r_&PzCbv6|_AX+~mly@}ih+1b- zt4NTIh9o)_BODIJsP+`=mN&{2=B}baunPO$?itrAmcg4(C2i{vk>RO)Hnf$bsrBtI z%7e)Kf=W&ljFfR7(?!q352hOf#?oLZq1?A7tPnJ9h3y={`w#mpi`pq-*rqYCx%SMgd^u;nZaC;h2@9BW!1osek@Nv zN9=@UE=_`?Tnb7K=rUCT%k!1thK7)@OXfxEiJ%Osv&GRwRQ3$7-U#KTe$Y6^NoMSb64W2mjM^3@cxR5E0!<9WNwPRI>Pykgk zHeJ9mx1Z_RC6>Q|&s9Fu+nnfeAaFaU$KFNwRB+m}SD<(BRw!G0dojf$zJE|vUG_Gm zH$4;Bfq)Q969r_z`W4BU(~gk(rhYv9z3pkSKcAVA?+!Q(A>tv2`^9X#w(83;VsQz3 z8EP+!?b-zeii?S5j>(iw#ts6*2_(Qm9EZU%L8?CK7pRuEz?DtbcI<900p}bmS{d_j z`Yn{&AMusV#357knLt)Kb@WPp#f`iY+a16AznsClz`WlT;ymjpjNn>mgp zuv;w;8Gzma8)>z|ofthAfW@c5M*wU9bG<%$$3?uuW$mekFCjYng?iMaZvavF<&sN< z3`0LFbJ_2Fl7Obx5GMMFg9ERCU2K}1v|@K9Zr~%gdZdX3btK^`i^lttggK9CjA6-N z)(v|x!(&9fGQMFJHizLc+V!rJ$h~zk9jCK?A!U8IiC73 zKM)dErC+Z%9}$?k3@@fghGz^Z9ZQ^vPQJHtRhuwWzrVgf_)hDJRIXV|Eh^<9byjb> zl3hc*7~rdy7%M*+CJriaW#c&pwesS{zWB%wTYq`g8(F8YrnJvShUKp_cE%!ymJ&NJ zS96Zo18wn+#ur2R@vzrJ6gbVn?urF@ob#Sy(;`F7UhYI%)Tq|o(VSLNT~K&7E)BIb zGy&$=ly@c4oU1N;;7Mg}M~dZQ9l^CDXRp_Gl7eK26Vj0?GGFW`swE<{VB9xr_3TVn z9IHz4B32{x^`Y9%D+Vbn4&vA@Pa~^AtMTRi1A;C1odf`B{?S3II~8lqHbX-UQQZf@ ztX9Q9m{X^2%!h%NxeWXl(y*m#Jy`=xMq{ZqVuTGtTl)b)d2xuYU*3?ea zr1j?a)MNQYJ~oS=sHWwAP&GfG`&!=E2bY(@E0CTtkg@s87x;I~j5^}Nhu^KseLtRY zOdmV3Py2DSdzm^}>3(NGxxE-H&{R3@#&C~qIVoCk1}(U?J6Bg-iCXf3H?U?@bBUv#dJX z-5kKodN2+Csr}KQ;Ao(|MomsHbyT0_sE^D!`5{RQoQ$nVKz5z=TC3cr+&UokpFxx@ z$PNu#PQg%r`Gy$3MZ;Xw1vBA@bpptU6^R`Xq-8){i#>u9roKLt)0rCGj^&f-s67Eg z4Tp--#cO@>+>waP=>SXiSB1IP3LJXRd`RY#SN3b$K$QQ@|I(?YPc)rQ>je>i(q`)G z&1%&0u$gKARoH93+9T1kcT5qd1#JDLN9j+4(R5~>|1`*J<1j^8=Szn}Vyx1$7Z%^f zvUxlD!|GUtyB=tgu}j+*b-ivJk2^hw5Y*vnsa)7tF+Y~o%BNq5!t97s^~20rv_flZ zT@6p~Q4t)w&9elttQLdgJ2;Y&hAg^kNxvYkN4F>+Qhcm5=$#Tc1%D|o8*+VanSE+M zBQ$fB|0{#JRk-?#GTy^6OGsUCGMQYS7mXzxnV9$Y0Au4)X2jjYvFX~%{>@&;t*yCN z`ubyU-^QHrG0CAqkK`z02q}K|N-oj#H@wKUm=K&(x?0+LNq)%A?!g#lINaiAJp;W8 zfs0Iy-f9aucX^hX$ihvgpmXLtEN7s7xb7>TcqY2B>aE`ir(lMsw82*6F5=M}o{My} zy+RZlf7>zrR@FTD^{`eDIx@ZcV9W4lRfY5)_gQ|+7l-HF!m68n`&aXopUk+dc5IS$ z8*;A1SMN@|_`A@e!m;pNDKlm*V>e8ZIzH4bG71*Gf$mD*Ks=(|y|P9%DJZM(Spo2K zjMoy3o_JOlwN2k;MLh}dZLwL_)zHrDnti*hfsw@TSpIcxiB5Zifp*4U<^B~?6J8b| zFTD*3ld`_}twySFr$G^HcG1rI;3KudQQgq(Qc^XVE;(6UM-k(XanIbOuIw}h& z9k9mWvr^(o3&vKU5yjAm$8a)kn8-V!e9D|yXiK8xeJd=;4}riX79awbV+unmLvP`A zlUKQ{hD3tKtXP2|1aX%htr+N<5zqkIg68*>=iI6*|MZvr@c;L9oW5NUJZAr(6bIFM zA{TVp+`lRe&wydg_A1MDNsC#T_m(y+o6=|-;cY#x;>DUIDWd30B6hRC4Xnh?`_=TZ zl)`A@(NuVg4vP9eb;0i5GCq1%MA53?xCl~i=Q)wueRCJ^#!Gd(Cr$|`9xcrX6^#lC zZLwR=phJVnfeuvd;5lEJ!TI^XS`Fg;{C(QW(EcLBKFm*H4rI9l)~A-+)KX#qMvN?o ziJ>yDJ-VZ2kylL_M8ctWATL6XtE?u&6_|njKBRs%JEJ0XF=VYa~gm&5EtCCStxXPL|WOWixP5>?f49HuAa z-fN^)u67XyhcM?#q=-&2j1jKt5J%EyGbA+Rl&x1~@Nrvtnu+~NQr}OPF)aj@F8eVe zNXm+`M?vgBLH7?|Yy`;+BkMn?W?WlzU97wxV=Jklfv>+yj?d>6xl?3m)}O)Qt#c!> zYaRzv>E(FMy`rH$L<6>`4Ykk7y|3q3(#?kol>-}sy2n(*EKIy}PfraW%^H4I@SFbp zi}Z!Sm-CdBVONzel0W;_AcH6pLP2ru^YtAz#xGWy+f@RL_)tGGas$dlxZ}d|oP1Rt zA$DOfAb9Fh)2>X;Wu0knXLhnYurJS>KW#SrqXwpSjuf*;j^n<8Jj%AFm~#~^x6Y$; zAkJIzkiF?%C5?01p+61>^O{-WDMkb9;4UZ3y2n#4Ol_8f(s)tM8^7LApej7bwOXBT zm~yQQ$FlN^t4~<9d7%&ogI+F6V)R4gOrj9AnqdToluvl>EYSd)D{BWOD zASi_1x=RDG()Q3m8R_>Bv)kk%!A@r5j!gGkF%`}>lITqnGM*=wQIQ_6Ct!lYVd$Gt zngEf`)ourI5G$WN%f3u^)I0A&5P#qC^J;qDk_0t;-Xf|qr$4JkaT18zMIaEfg6(uK zNp-xWr=OG!>ZT?iBQm<0}+WUfLL#V=4Qpq;)b*U?hoAms9=xIAp}Y$y38CZ3}! z<#DIRa}3;Bq|T6J7Xrqj9gwY^#o83YPHB636@-K&$z^Y7fWZ`&myEiJc&F3exwu~@ zQ-Ea3VKOCMO(lG>*{xt6_w;v@T4UzLTqNNVHtZbHr7jq*lniXIk{k)FxC-T^9^VH>jnI zAw8N0G=axp+`c1>-1b$*d()>4YC7LUu2#qT>|LVzyXJG=bB`rREZd^gdaBC8WRWvyZ~W(bGW>#337FYL+Qc7wi1T!OEDd`0klwEfs^&Cn^~c(MCL=yZ@; z=-&%<;HOlU!arN+Zq9{BbhdCXSqWR;lEW>vk;#5O#ITcc}mfur1B0P)R> zV1XZSKR<9$p%ibGd+QA9uVl__3D)WW1@85b-?INvNBu#qj^#U(m{LFZ0?? z!n8*FNew}p-|c3tlHj#{p_hUk+xb#vxMJr81zo3}7t6Y6&`iN$QSXcl2+GBu+xC&E z@0Kf7#}VnSIRG)qZzDqs4$mGRppxefD7Lyv^9F`j-BqgbsIVN@$K~O>)VZQ!EdpYo%Pv%Ys9?Mr;$Rd1?)KMy)jXaH>CbZvMb zB7AWBc~?DT@7L0oE@S z@(kt!l(rD7PNZ4yC{lj`0=T@F+-=V=&BT=f270hI^>Nmw>l_5JAYP!y4S-OKPq&bglv%-1*%0-fqC5JA)#Xwe&UNU?F8))iQML%y zr8{F@7+X~I_%z#!KEI3PDV%sDcS`81hI{5T+?(qCYWmpb($4n@GCA7wO2y@oM|YXF z*zYO*;r*q#*As}cHt$BPUMfz{pMB-ij}{2`e*VI`FTa}d;_Ek?WBOOWSbysuezxQG z?cbK=?h30l4MksVt9h!rzwJ1`&@P$X-I#G}!}JYZ#<|RHTDL#jED%o%twwKt+fAN0 zZ8!?MxPsRvLSF@Ci`JlHz{!K{Uk<+|Rc#gBG$yxwKo=4;lGbT=K9G#y$fXpBYrRbc zviqYGvv2#uH7T`VD)?4RO5^RkiK$JfJSNK&)_z8*u!rS5*GS(r|pU6+bZRft^iw44sS*BLgXyK?3ax_(=AwYFL6uwGaym=b?RPs0`}cN$=T&r{<6 zT;T!-u3-;+OFvJ6u`N}TaXN0(l9)Ww+~9@*f{?dCFa>#$j`%{VM&`24sI5?DoUeuT z)pC?C2kClkAU`q#W=~y{HhaG2>mQ>_uo|T`dqm9n&@zHgbd1f$Pm&0wkf{_nu2PYD zyd>n%JAvJHn89FzRmIJvpDJaTmgc8>m)xy%x#zPn`3H8Uva!s}4s23V?)EvSb{pHQ zRj5y{*RRYJQ1#jSdcJune^f}_s~p;#7@nBEVwuhIDj!C3m&s`HV5}*wgx~*?uKf!a zV|WHOCxMz8Z1#LW#{|*XFAEsrHt{L{EBsAKq0i60Cv-G}Wrzw=S44T<_B;-U%$e3O zwvCbs*1CTFZBe#nlA$HOBZGoEV3`A==Jn&@E&~$G`j27YZ71*|>6O;_%dPf zLIQNad)o>l_AmM1TRjQ?ODSAPYAfj`1l&ClK`x#@d5b2u+0t}wOSHUvo=`*^IE})6gbd zlX_1RX6}b5DVq`@PKRT8j+6X_AiGu9kB={-B{A}05FRB#KF77RM13FDvS&gjoCy?z zcTN$|_xN<%m)tcd_WeH^>8`zvLHp|_fR)5FKb&=SPNEX^UEvf}c-^C0U7sLB{QL4E z+2WLY=i-P;fe%HjtE$Kz-uJ_K-4kZINABLGcU8X$vzve%%c>)R>2=8Rresu|*EG8w zocwY%L7`927`1YF#X$4XGun10W;74)9jz@Au_+s)T?1en!oM2H43O9obRnWA2{3@0 zVM9thEY(P_TN4eSG~7ct97DjK^FDXNaUUPPHyZjD(LlIn$Z#nThCX@WirB6$?dk-WOe?4K-b zd8;XPJKAUN-*=69?XIQ`Q62&&7p7=yLR|xq-V1&}&ZUO_;&XGXwT*rs=?_Re9_}J_ zuG=vh#K+i$+ko5zQI5|EzqKSrmqC^vEvF`;`uR$jTJ3+p8n#mEd4m66EB@E#-haK> z;LEIc(c&-6mTz{%XGT7^G|+ct3<5hSah@F3YztH;xRJ!&Zz)8jm+rp<;mOI#iuT*l%8K=C;sNmiDT!~6YZLuyYT;SPYi5$KjoPC zA4C6n7#Xl#wso^_nd47R5eC3J?#agy3!CQN=(a|;OZTf9Xxe{FQYne+CU)0ZR4L>< z56fxZ_ z$r7bIJmIe6K657-{r191b`FTf#Ilx#&YrM~%#x}vxYQ7vgEk10YCv3QmR)*DL`Ge|O62XiiB?|2cC9FWVS(%kqI9Nd@Y z+9TRLqnHN=>Vhfyo!E!T`)p4zY|>A|&#ETMLaVW;X74--7ronyxU*i~ZJg_Od}I(W zzDFcJU+QrP1xmQeK!gr28E%V#mrNKIHB4u6I2_cSTr<-9(*iec-DL+AJV!%PZB70a zYFclR_*8Z&{VZQP9Okq)^)21Y6YH{pRZq&KzHlL|JE-j>9SS^`xcU*H|Al}E6ah|d*a*2ar#syWAn!f5X)EVT1 z8utN$`wztIvBKe1ME`x# z{*k;XH(sF3X*b$l^t$1YSiH=edeVekUkPOx6OkVUDu}zsKt-p97sKu1ngz3{=EfRJ z-s6Q)4+&)=M-DW8nb+?#-DuY+SkVa}P`9G+o6f`{zB6H$zf~n}hw3Yh zVvcH$X1A$ZQ(<_g^L~gAeqk9Bv|Nvl>)#tHPuW9qwi;}8J~|<2TnbaW>nppDd|tVJRaxR{-;UE47qa=t7@7yYDe} zI6c^zn39$p3+Uh3Le=*RAN{`BTX5F*)8e*!?#VtT4TWnfL2L4>kxMqGCq0;z7wbjj zr+^9Q_^>CLK+25x3h`ko4G#1Qn91I~IUL#!Zjt|H!CPjdhy4B$17E=|t(V4}e-Z|J zUCU7lOl%+@_g5N63;n(sJ)ZZx7B&(%yVhkEspnD!q;)KZe}dkM)?8uRVQIEs{$dsu zh_lS@;f@@32-y_elBxE#{AGoJdt@n1E%*2kF@v?EKBEs{TO~B2hD0G330k_n;SPy; z+o@dAA3j;r>mvQ(ZeenE(@3WK1!#R%4-y}HIV{y-8q)P0$)K>hZrQOCqI!YklNoau zTxv0y)2sDoCGm;M6b%fQN&=58l+izorn8Q85_NxB*c-{q{YE29n?LerCvwndP@z!i z{Wtvl@n?dmS3sfumdJajI=1JPg%cCSd0n`%d!L=iF8E-{Si|jS{Ce~6TK^^ar>&Uo zd4G-k{)|YI>x>6(B*7I+TpA^D3Up>Beb9$bA3-DfvZm%ewF-aHM85e?6b?GsSw>1$E=Fd&TriNXL*#a+o*H+?Tfvu0As$f+LR)KsTz}G$ScJ?4KUNXj6YXp-g zmN7b9Ma2xOS6=%d9Ay2BT}+r@ez}b6<0tzNVjPPL0ynju6eY)=*dNU2!VUquTnmsu zvsL6GO+;X^7HDhWuG6HQ%*`dL&`?l9vPlMEu+;q?@zW%ud*1tf zX!@A#SK5g`n3uYvq0gg|`AQTo!y{Tvnm=5}QnNg2j0xpEfVzAC9mLj69@`GqJj*#e zg8bc<;Tr6Wd(9wJCMy@Y9-Dnz7%Qh5WbsR56Z!(H@la7{sdKN|W%NWZVsBJ2#vDg4 zIQNlWUq9<`4gQkyIGQd8F(1Zfdk0|o>s5iqPz+fjs=XvAm*PmNXKW9>Im#sqJ_hU= z4j8R14G($U8K~(@x+1}P)b}_CCML0~OUS$?c@Vv4A|o98^@{7&BoZuxB;NUjKtR*C=@Q(P{T3b06 zv>WIpLA!~Gd|c)AE|92?nN`aD5q8pzgbz28he0L(6EwQ=S#HhHKV;t?NTWgx|BDRZ zo_k*Sg*?}V zwd$lHGAAjfuo_T+s}d+SW$hHXo>fn&q3AfN!?o=*gA^`TJBg$%O??s%)<=8E9j{3# z1vAp~9QMBJQU^XEeAHoW(W%lu21TTV#S(ijjz^V&wadK zxWP97`%}r-X$OsP>X1sNykGE-S17t!y*O4Zcyv)_G~$&*@ItDVL3;-@-&oNVRQo1d zI9S7?SD2-C*SV{#VW>HZz+OxUZ3JD z3Htj&7jw>+>2_jM_I>#)B?KgP_mSztOXlErNF!5=A6#XHw{8pc$awI8|%bO}{1?F}6PCFHf_T;dd`qsJmYOA2SG`jVf%b#rhs#WEJ)&L9bq-he`{IPE@+7lH z9XnXW7`iTS6u91NvLY8rNM22?TIog_!@=qSofq``mr+X(Nz9%4AhGp?=c0Zy=EyGs zMqH;Z?HTTBXU~?pom95iL(ER{qQV)o2fjdy;y>f9vMlcbQ@^jyKCbmvg2|r^nL$N) zF{bSY>CwzZ5lL<7)?hlQpRlX=1E`k0*H*z(!N4@^aZ>sAh8{`iL?M(IL6UGcfV zjGZaeNm4=wx*CCXq4vg{kMQ)frf6sUKf=B|uBkI$za8i5oom(G>781Oz;tZubQBqD zl_Caax;ZUXrtPn8ENM%XS_mmbh!B$0@wQH{3S+BKMUqY}qE$!{NeCf1b`zB)En9>v zM}-g}Bu9zlnEm&>htAwtKI8pMazKnZ=Y8Mr_xV0cPYn1UJ3T6Bbt4b zhZng3k0#^Iu`dJw3PL@eehgi3#Pj&lVY1?eM0RmkE)OG@287TJtvx;SQWBDz2j*f? zu9eURxDnX1FG<|Bso>!}@KJg*;~Z|)Irfr}8xt+%TRd$E8N}f>CAH9ugJWVv9!PJO zBA%b%NFO#D+%|qvB)Nis_<4i9H2~RC7sQD}*x}9l8H))70o%_+>SZs76&AwUd~Q?W zbJjMhBj;?M4TSMm#NL&Z-=1@Ggug!I_O$6kf3mE~aWmU4QnIy2P#opFW#>QBB@<&m zI`CEJ;2oCVUCp;o(Q8-aD^=U9GX4Ro>}Hj!!*?uRsTw%C-MwId)&!W^iN>g3E>5rV$DS#;=G*3zc({+bTc&%SZtey!^g@zp-yfUtx&gFsV>bZP3MK$zP==OD+*O zkeWRFf{xAgUT`vE`Tr|sOc=Lq9>;gEk4ekDoRL{_d)@eGNIiQhRSEG3cj_bK)fs|c ziGqPB^f7JAoIVyt0&o+YD!CNJXqRD#s!HC2(t+ONcjbKHB5}c#>_w@=P>d<_k7doT zO41iYfoa}B1lhknF19BVf&j}pyw;qHv`zxsvHzgfhFuC++f@wmh=U=5#;t3Me633T)X1QEXD+)3y-GKJ3+>IUQ=u?~>D! z<)<(dGkU&ubx}EJY;I~V`84#;;@PjO&DD9cKp!|RkWHok!xH+Nmn#~sEZdg#qx`KE zL+>J?hq<`>PGa z-mxkrVwhDlSJmE7bR<_-5-q-0f40zOcwo**LU+{?my+xqH!s%fO)8`qe2}(%SWgji zb#G6gl+&iZFq`&;JRGsWSL7U;S?b0J{;CNc>LkQzyIt2Ng?0!ZtzMi(@1p#3OY^Vl z+I%&D1Ydg*`(OXpQ{wMDI@>^q{dcl4RVFv+{*7;&>dpig2>Z?X66uVvX0}7cRGUhl zPr{pdEbgc#>G=S@YJ^y+^n*&e)u#xQWi;)Y*Wd!B6j-94wWTWepBiQJC{E3kLqAEp zih5OTc>3NYs5C&pNEVk=b8wX&_zoO+R-FS*sn9W1q7HO{3=hE#E zP_YvVRdj}Awm}}yd4^j0-kp3Gjzw+ zqYvGoyv7YZ=lo;i4j0S5&ZGk_tjt%OqCKr}0*7ft!>~=`e^%v8{ZqYA73%g(_*A+g zSCJ*Kfx2Gw>`=h_^GGPt{c-fBOsVruH0Hl~Z0@@29R;Itg+4m!FEYN`9Zl`_BMAcb zkefXbJ>)UQjS+36=BU3J7-O2K-StUm1%yFMpeL>Gq*sCNsvX}fB7dMW>k?j!UJ*$) zZ~Pk0f(`A)z7Kg>;re)urR$@J%IvM2aH`1CPE4l5;}GB&Jr04^c(JSZOJ1aO`#kO5 zqiF9@;NNT)=nL=jk&>l-k-U@$fK%ET&D5oJoHOpiir`o?S~LP74lGGHzyK-~t(mMd zk(sNgthIh){x7h;?G8kqkx)qdLZ?77wJP~NBfpii&-LwGQqxQ_29fRzAmMyj%Txx} zsY!igU^-f5z7FuhXZIRBm7Qk#6qNq!IBGQ`OqoZ}kMD0SpQNHlK900p`S^UEe3^(0 zQLS_&d-w&dNrkVQKQt4}qup#i|7|z@f{<(+vH8ULh5V#mD-arj+h-VJ`WBoYdGIav zi%?9_A6}{qHZ#~Oj;3J4R^7=-K5z??+?s9>z5jPY*e}VT|p#i+YE2t%?EF6 zC4j=LlJ|q2iPvJ~>VXN!7E_~CcLzpGI^(WOD-ksKmXEM^*~>e+?Qcs3p;yruQn>*LMuNG&1Qiwfpt)tqD4QJXlQOPVnO95LJj1*A-7c9-M_)`Xz6zvjthZ6#2b{8ZV93@m~hhSISXFCOv;HEj}>MkNN- z$aj`iP$zZ;sR?ywFAUP+%|s?LC7_@|G>BuDPWnv`CbrqY@?M0I4e+?CWUep*)~E7 z6lKI=-iolu4@|!c3!uJ`rM#)>c3ixZYrLP_B1Fsm-WUz% zB?q*}a65)5ID*=z7FA?9L_eI^EvG9YfchQ~eqw&uz~!~9?NW{gj%2uV$? zxMaOY$hwBN(SB#8F8(l*!4usQx9|RP*i4or&(}bPK+&SKq!XmXzW@gJ$B=`J{lXqE zFk>i*#nsLWAin`nK0zC^DZ9-~809@HCFzj$Fq(<q0Fub*Z;t98@WlqEV6Q~B`hAbUl@Kmng;9jN5Ln7Y&5xHaDG1=& zn!?W{-e$9mjB^c^TJ+bFH+MSPPC4-45Q(ks>-Y79Yc3lSTo!6392b=7XSg&gZ-dk| zz`$?XX)cMEt^=l$si&09AD!^!){GdA<6$3F^CVHrJpiZc9ylQU#QLq*IeyQvrO|zc zXyW8Z?uMd6Y_*`hC(*Q9JA@kVuWwx0Y zc1zdG95O}FUeE5-F^TOpo&`j)e(bcuaY)?lcF_87LtqkH}>Qk-%l(1QBOU0FBD2TJhp9z&xL4~e}mAQaG z;So;;nHJ&@)_@xSKT>F0Xaa000t`}Orz}8eOT)Ga;>-%9(0Yd6)**mNr?SID;6zd) zO=x^?^L54HjKaXP0HT`HnnuI_Ai9*47?hUc1Z43gV32QMsZ4fsfba5TZ@S_91?DhnY9(zmJ8@!I7Fr; zOU4j~_*l?8mUvB`f>Fla>L_`XerUbkWG zCF+ZbHq=H`XdworPf+O4FA5F9h+qWQ{A<+Kz@SHn2kmyo*rX)1;uD$6$Cam^9C^+i zwz+f8!-Bhu_x{Y{gY#0w;Jdt%wnr`_{9^SNIs3IUCpw~!?Y4b3qKu0a`&w?XChIfm zH=BUmR4jhXH#|ZM)9Vhu&EI<*9tAw*SHW~qs; z{jA$&D~rcZ_0`Fp`T^2Eug7@$zA0_aWWJ$Jnh`HA30Tjt3MT>+(h?~+1vcS_9S5vU zCFI(LV`AqT*PE`_e6QAgTL*sA`0GAZMuMCf@)#vdzN(1s%@<$_XdX3$MaF7wZ(ra*a89_$K&y9T;3U47l*8sLMca}X8818Q+ zk4BQ5qcX$_p_U{=U7(I62z;JK(E&%%D^2gwhh{lDfM~#Fa zx9I77qm7sig*%-#$$tm6(E$SR4(9wW!PP6^0;n&0zU_?cgi4ENZLK&X2~WQ9yZ|QF z%2-`Ow<(o6zW!SON5~{!C=>jx*Pi$_fBTLkxs0EG>W8&?334e;(>ZdWZMn^2R-SY-ioVL8HsxNaSp=moK&H|qX%e7unmGr>@O2G@yZ4-LdfYD5-+`9hfKMV474r0Xw z?uf{Se)1cKLaTOVI=6!OL9$89%>&3Z*w=$W;*6Z0PeWE#MRkun2xNT>w;2OfeeBy8gT&$MA;SI(i zi#q9V@6kVg{qqkQO%U;1SX$;xxWFq<9ZizWQcsLjd`v62Y~g8s2bcWrD95Ukc!PA9 z2N?fV@z}Y=L&vq%Z>cPu3HbQw()ELsETKt`9g3QBY<=l9gbZ37vUT(o^ zBixO^L~{pFh#2Tk@kQx0T{79W6#h*p0pU7MEc#>f^;IOs=27L%s*$&)9I`(Y zza`9`PnF>F&t8|AjGtoWB@v^gUvGN?<1ywazB*s+w?PF^}>?re9v$6Q5cGKDyZ6n{Lr$0yhDF|{hNnHaX)98@Bidj@oN{On_)JH{%fS7 z=Qq4;!Mw!hX2```%Qf#=KdKC_u&0TY*{i-V=2*|!yaZlaTwoyLmTaGj+9RVq`GQZ@ z8fnS$)jKCjgiQjmp`J8Fo95FUQc&o=BC$?fCKA&I?1d;e+WNlk2MgJdo0*YBk?3IJ zXX^KsG*oe-8L8R98BLrWFjR2Fj@!*m>FO)^IABBA9wJ3$@fDSMmprfrlzk|d;O&Ri zRzY54m2uwFWc5i+y8d;3At$aj=?0!}Agf?1Q)IZK%q1(99;* z`zOQ(LqMOPkJB;cn1-WrYm?etQy0C|*Z+Lm+W{LmDhtj}i0kXk4p8i1g#mg91}(QC z$EcSQW|s@-&gJlCgb@RjAA7py+jfJG*a5&WFJQ3BDynGpl+8~(Zl(k_U{VNgaL|g? z-$KECr}^?-H%bk(dcK%3e5OF$rArAhoqFQH{YI8UFS<~$XMmp}Nbzi*)L_!g?`Y%X zza72_o<~>%86>mm1u)9x4y>QC z!(9BOv;7b|K}vfl4$q{xhfLfl#skNSu$0Q$nj8A};!!9LLo|VSU`y#TOq;*_IQu;R zL##!twRL902_GHBU49@Hvoqo!e|xaNWMrP#6RBavLS`lz7B6L|JT$Fzx4?%L*5dB1 zY!G9jRBs62fmkjVm<&723>H?@=CX<}LSZkZ1ApV9J}kt->bXT$p+uC9k@F(l-hEH5 z`i_2Y_17o1%tDnLxu?m&KQ#G_@n5-0lO=XSApSGVwC2>#xxIPy$DprCZq0=n&i$I> zaUuI9VlNbBVauvEp!1DJWe1O>sPO#@E6SWRgXp$koZ3_`fkAqt^pp}X$w9ML`B1okY+94S*wjv|~zQ{}v7{9?|*1jg~!&nZ?G z{C~lFpNQ058;}g`!9V%ZUz@LbLJfaiMT`RB`E3P9Uvq&0qxO&jCu9>xCJ0&_|l#Uf#$gU zSDIYm7#JpI<4rFWWrO?)sG6)}jp=C!R>@R-hp^}q92672DvmlBga{EM4p`If`MzckROkv?j&Ovv5J;peV=E9k16IQIansN z!oS~mb|f9!OG^vN@^#(rGOJa4qkV+PuIhhWWpLAPk{apb8Ximv%WyBUA7)l4zRtG@^I+x@P zn(6t?MsNf$>HOAlN!Vt>K-9O?TOY`d8rLZQtQT{Rx69#841&jxWtByNQUsj{2O*__ z_q?g8kncv*EK~|~+mRvrU$THjKmQ>rA>hTQ9xgHLVng`ASl|q{u$lDkiVrErwGkseMwUjzAlQLbHZ)PN_^_{`Bw3t1 z?d*+ATM8IWiysgfFAuer>t-lZ^O@gr6}+ZKR87~)$!_(+SV!hJmz1A=sOB$Q_^ipj#NQG8ywsuh0=UIFY0%q_Bp2Z{-U4ESV?>DXCQ_mxg$^vcm@m z2-&ZxAPaX)gP{^tuH7r`RLbVQjp3bd=4s!tyl0JfOlrRCuHV>|=5QZVvTi%{OpeEm zeP4DWWhN44F~Ph))q4Ti8Ee;3CqV!G%@T1ixV=Xh(N3ABu8qn|o^KjO_KyP$gK=jZ zMxea(Rsm&M>g$yTiiW{N+nC%7u<5VUQ3Ix5PCC@8;|yeE`Kvj z*4>Ul42ghqoIyMx6lDbGa91e*C*=>Lk%Lx^kzDe5t8HVLg6_t|An>tuWtwi&8NS$K z_)O2BGbiH$vs=5Yp=Bq(l5PQW)Y`=!1yOG3=>~$-AE4Em9iTb3NQ-ml5mmsF998CL zL1zC(I0_=L4mL~#YpP3fo7V+grkqRM+8Z8J)kF?VE9n1&YP6V)a=ARe-BxPqj$C-j zd{#&p!D;<)#QOGPWb)cYr591?k5cx0P{sT!HmO~U9Q+4wU!|Ss6TxbJrz4Y_#eHPt zJAZ?|w%-#^-xl{V z>Kj{O+7r*T?vJY5y;k8;RqAB2+@4ahWe@up#Q5&4AZaYdCEZo50hQZxu9!4 zoXoCstXPdUVo)ei9q#EOj(ZO$w@ZZ`&vqy=+E*K4)QtXgz~&@kP-tyE`OHI4g$Mfa zh~MbIC`;A%b+gB`!O#(P!;DGGz_-Mh`o;XgR>L%8@+jpJjJ=KkD_p#)Gf1Y#bPBqM z@YGu0QBbgh!qKvywJmGV&yZ)_YH-z<$TYAq?ZE{m5EyW&G0 z&1ziH3v8Z2ECTk=xdA;CIO~8dO2&vbS7nIgk6jz`1&VDbVpl};yGZEDUO+5Mlf5;b z4a8o^HRr~LSd3@kL)Tq|Z1oBke1N_-szq7juZQGMW4|2_*y@ujBVT!0)3BLG7r*0* zyJ4_0LtJ{PMjo?RE_DtP*%e>H3{94h$pxb@`SGXINW=(lJkwfYt>%aB6bE|6Z`hNe z%kQu&YIm1xFnYEPNz+JP3h{($sp9){mq!CrQ4i31s(6My4^BkR ze180SF_Y6NpLnX~>kg1H39H1>lAUFi#23{PSv4|Ch}6sSxMsqNZ3*Zetv41G+Jo?} zAA;y&_rLq%HjZO-A)3wFJEp!E0RZMv=mB^=p&=hB+fa~^fGE8{3%r|xOX)R*J>Imo* zYi{5u9!ksql!UkNmICsM*Gy#5JJSMx{1dwNX?+dEw%gbpkZ-X2D(eG7?hrohbrc*) zV!6;8TSTZcw~Cd;XE<#zkE*Q#edNP?2OzQ`9>|i3DpTu)qBD>x!|(EbM*g;pFw^tM zR#9m&XJNBn>a?}X)LNB(SH6+7LZ``H(1#oZ1P_TbzwJy z3|ymB@mR4ywyRg-9Qvz0s+zB*>( zcU6hqUiMP;(crxvGd!(`Pgm@pVM87QZJm7L2#0`)smt1qfl7-I(9u;Bh0p`iwHXS4 zLJ?1Q0e?srPrg;vpsiA&;d+lQFt+WeT?SYx$CC^aFm6^m&toHv(QPrP4}`329$Liyu)zzL@0^?;5gkMSECTOoL$#GI{qdc>G6yZLk0Ni*vbtS%(rkaketi z`W`G~wB;$DC;rwcG7e5M^_GrIxpPgOBE)oJ7`-fgbh@L1tL}37vSH07a#7;G?u&zc zB)>_z@+itczn2bH!dxakBJT1&A{wJl@q-HknJA_kJ#s^+zX0ImVk#F?f~lUE7YM2n zUIQSd|I6%-P}Vx|n3W2FNUJ?1;X;!cNLM;kOVbP9r9f7BC$_ ziF*aw81PYz2O0)rNpgvO*zKzfO%~5?N3BcpOiYksqe_xu7z18%yZHh}C+P*atD1kLYjoyLgui&$;0_y$ZQ2Z^Qn z)vDuQw7$m|z<%p?X_Uh*ipA8Wg9vDkb9=1nUVwS3*M|fBIF+B=y;453%WqXZ0#4Dto=1Q4>d;dgDCgjo+20*V`r=Jk zAOB!(=ln!*=4?gOF^EGUcu)9b`1Eht#pV5X`BFCyJym{)ZY|B^tU@-0iEx*#$uZKR zMl@;$Nh>0|%)(NKx;s^JeYy9FARR$#c(*a>=sl-}M|j`mxB>wZ+zx(_B#~)xHtk;q zD;(fL#F7LkN4J5E7QsoxXGLvu&S>yt1~`u`wq9iY=3*qbxOb=tek9nJLYdf?aIy+r zgMXm%!}E~L*5NI|Y4kx_iK(=F&h4POxo8%S#i8?JNQx0(QEjW7L!7r@3L+Jz&O@>F zLv-6OM$$B=>oY&&65Lz@&p^(ir^1RF&)JU%^)bE!yBZ?CmqTo{eKDk*UhdrGlG@nA z2H zw`Dq|KUyW|((|UOv%X#>Y@N+pJ41xQaI}0>^u!ktaWa3F>ze}T%3|tvm43CuDG9J9 zAxtLyUWw5CmX8Q=jLMQhJuv=IdC3uDsmb-)n^VbO%?uWF$kah|bij2eoV)=M3DU6! zrSv7+S(2iTBzD$7P)EMhWa~j88OvHkrg3~Do^ocHrZk+Ah|YlAjHhuo&*0#AbbWYIp>5vVJdacyqxxEW!b&eREvP`0 zeqs?q5-e~gbqNe24ETV%pm)WuJP-gdg%v7D!QApIUq z>F>Dq&h0y$&empOiij}fLbVz;gc(T@{oNpupPYeP$#f#Z0hDHwb9-E?Dd}QSL7ZK{ zV(3S#MSJl^`ONEq96Tvr*rw0F7dEE)_6v+TXhX$0XD98IjIF@WF(1o6n}v9<13@$B z`Ao!mi|3!aW29X|~9P>qFg+Mtg<% zw`8zgdv=5`99&(Yh*U!?Aw53mi8t6Tfr^w*bJJ`S#%hLzM7jhYO=Su;NV^B$G6VyH zfaTfsk;yZ(CLVx~-Lt0H8tJrrDD}OHZt;1O%ftIdaHU0{)V0h36B@)EAZp70iDF@6 zR+ZeY`gT9+No=o+C`M6?_APK^*dVE&g@JaFMI7(4q^u8(uISge3C}<}*L+^ed8OGC ztm&DjrC7_yVNuGwiIL4Nn#XU=q0N{Q(a224XpUn|wPFv|<-Cw!sUk6GFsh(-d_O5{ zs*m#Wq^Lfxva%|PWc%V~0&m6m)KPA2^4r{Qny-D*7kgM8HOkAx5Fv4!5Ptb=CNpK~ zIWENrBVZI+M4BB0;sTMBfLqB%xHZjs$s<$^?852)3%R>eH8OdMFEJ#18{B(&aQ;+q z#o?8ABvpD$PQC`VdFEx&$r6b5|G9#F(g*eu|rWe8k68{IN?Mn4HQR4k}5zc zAk!$y(4~3gpeGlMg)aYYWag#4Yyd7Yo6FN#(aPW3u#CITgOGanCgr=9uL6w~kP?cOwR$n-`gv*i<@sYdKVKgn>JAz9x^f_i z5{+!IdXU&Vw@;Yzbp9ZZ!ZQ5N;T6B{=8tC+BTDjpXElo<7S2Gmh(!EOiuz#LsV5uo zG+)GDfUKwi)VL>^YDen_O}h+Fx=YiGnc*F;(K32;T?D&JJms>E|Kj}IGMVXe;Y+YK zk=94&Vd39A$z;S2_Rw6--pJIDbFQvU%*zhj=G@NB;g5Jst1pm7y*j;=}c!fTO*aMODK<*YC)gZe=IL1Gfj8~2{P!c!W>#Dm;$1IBRIhx3*yEkkNxL4ofiEU6JlW4hor=o4us~K4lh2 zMls;#t^h$Qp6y#kCJ*MWLIPvQvSaF__3t6>$yA|pXfin2sI)cYSEf&fwzO~xxFxk} z5cYmOI^0#tS=3ziRG|WRz;ks#f{o+H*^>+8&o^*W^(VH|&t8hyc5`n^0`V(HGP}rob`+@ zTR#Jqqk`8N`ElN0_KqvhzZiC9okgoA9DGpFN}0zj$Fx|Vk? zWmP?_;&B4GW$lBzR6+@x_vI<#FJT-Wi8Uuv;km8Tv-9Uu%xX<7QsX7X#$IynA?tzb z^*l@s;c}0A8p%KU-s+c>;d+9%JR>dFrV^nk4pl=*zKiVCFU3Yce1T75R;AUmVKJtD zC2M+I!VX(W!*2V=qWhIzfHp)iVh@g0HgCls{>w@JX1PAbY|u=Ja3l&TSDrN~EooEa zG?~1+^w#%ldf%dzBzky;@6F1P=Ycu5S-J{c z)k2?Xjx#apy1Asnbndb{1PV<8l*xDm)gib;ZKd@C#6KCqHwcfyaYsJTq|4s_d_?Zz zI779$qrOu_2JeME8}Y~Z!}6(2Q7U=x-`>l%XThoMzT3@WD;#_}@G!$Bx&0DtD?%m} zvDXS7m*hHm#O6kNiZjiS)#taS6J%$J@NiWF#=1b-+a+C_%_YEC*I)aHzNyZDXb8jz zr(pnmA4dYsVPv>oo&?R>(=}3uVZLgAeA;T*6IvwnvL6BL*a*7Q9(V7~Bdx6*Akk&`v^3r5$x7!OSLam(=lh@^xYIQ@35Hbj z#sGBz6EnqZLjL22-8Q#)RbpaacrY* z4o(;5o2z*gO!rAVsW-Z>^`)E#UdjDL3RvAiB=>_a9KNHyR~B6y$qe1U-#@dBXbOxm zx*0^Kr-_U^y7`wDN&;rAL|MAKB^m}(N9Yfew#m{*i{_WT9~8ML^W$iiK7wvQss@b6 z=^9rS^ab(eSEd6&RG?666>5bVtK$;&dA&83)1l(kMKtu7DE2#uZH@aJvPP5e>Gls; z%{cMUKteSs%Z**`H44xIki*TiMQ0TMbTNhY9y34$8!cg71aL6{+rrHTUxg@9ai^NK z1vE)9dU1(VM+hrOV;{ErNhkAHM}&;eNSqPE|9+gk^rVwJ(2l7KD7}k)?t-u@lM@ZS zkFX^700V7(Rh0s~=9~vS%XC6~;6Kim{mR`2tFnVOVx}-2g=$fQ2-=VR>XJC|zL1a^ z2Y=o(=wS)7@w~bqHi4?$wRWC%J?yPbN_hb21oi$@P7P$KcPNW8%(9=9QF}?a$_e4F zQ+zfi*aD2Ko07;wF815yujDex8)h}1RRdcX zCWPLa*Y5GHEoM}PPBB`y>iaA8UzGr5VqVHc5GAWXpO`8W#06wd=bIb-8hG~dn8$(UlHy0Fb{ z15@a^utD$HnRLU@<-zlhX^j-eo(Ykp=GD`#O>Mch-f4wvSkJ<0luHcdVKyA$<+kGO zU;sjxc^~t{Uh3vF3f~Y^8HGGgBCJV2n9kyC-8*bM4TD}qt}6$ z29Bll0r@X{7kcF>D7W~xGvI!Jx*j80*WfWn{8nTH zD6>1FHM@V%Wf)0@o1Ev=5D2=V*aqD@iJI!x=IexVxwRe^V#XEIKxS=aiM6ESXv9t| zmXnAQ^#E0bdVX={S&Cj0J;6?R1jMRbG~vOZ8Ank}x*O(6R&o@jN*a1>Or*$9-JKqb^1bxI3*t}LzcW)Po6_++?gTjB^{(lsMK|?tT6c8| zai`d_+UVO09(-%-;)un!Xc;B!7XhZ|c5Kh7u%4q2b&5uW)-wmd{t^;1*P>47izUje zTfwmb=@FvUxFn>QsF$dlhbMj6Zkq%CvyKjm7N-d-gJaVsFKNhcJ|3*q2il1M1j3EP z2QLVb%89mXOjP!(d_D4RfTP$U)`no!xX~s{)BUj#kxcmt3{he7;&QRWbx#30ImCA5 zW)jhc7m={D(e)M3H}hR>4%`q7BX}Yw;l7wE8W{^fY_o;~?dfhvHMpB&Yb!{Rz_o{n z(Ukdv#)BzcHi@ZQZv2zEiSIe&b(>U>vprVZL^mh3XRe>OVPsmo_H$Uy|{J7{Jugfbz=Lqnh{UDxFJ z*VFL3?)qe9`=r>G7jT^1>=7pXsh5{GWmX7mE(U^;%X9uDADxL<@$LSW0B!%4P4v=K zNXNjQ+>iflfyYF~V9*2`EJJm&VNt)B8HQ)FEwb`Ue*kH*5}4xkT!YyT%yod`dV``o zD!wq4k-ymY8ySvw(0?#pX-ip#IZ6-2PS!f!H=TT2D_+N)y{E`@-hId*cGaX5AJ>vt8 z<8c^PbVY{ZrIjnifh1NLaZvaCrJMbyKYy*^(_0T=gOp)QHB}@402<#t6hF z2}*l%G9Rr1Do?PaJPE@EUJYU7kl%nP8>f}@Pq56;_oaS=jj)HX9VSni`H+ENH&ziw}ggi zj7!j#4t6+^4>QfiX+KZmnt)K7E=;L$94iGLD;boh1iE!Vyg@A|Kl$H;A2AAVfv9Gjmxf)V8vjZa(eQ=(~w)r;xbrJvKVx006ed|bJIz67CKW?#U zA$c2X?;OyOKN~%3a>AND^@y(!YRXlulP(P{fvpCj{;IP~t?%iBvh%@zde;8_LideO zr7h(m?6NcLmYW`v+})V;mK=7w{7WI0B1FB3>1e;dNFPbF7v|8hL&ivbA=#X6i&R@d z28OX(SYS{c+6zv*JWh;(SHD9WiR9#xGy@Nr;>xW99YtSoV?mEVOYI{n$Z%Ud>)XZ< zyQnpj!X(%}*d4cr)fS~D%#kCp;q8VATQX3x*hAG1$xEA)d-Ac6#hr97IWJ{8fy#Q` za32=E%R}09?wZuk=B=B+*jHw$tDfTORJX}o>U}f@`$dZT09}ao9Bsvv_a*xb(3*ehQo3Q3S~eo#o3wS*pj$7H089@{${V78PTxCAhBluv6U6@5OGwVn$% z^RM7RkI~Bg?C7P)1zsU{5~t+nD}pJu)ALtG%wG*w`)+>aOC1Xk>Pz5iWs+nGi=(^) z!687}nJ$6EyUMFa^XZz7P<<)?oQ?2xzsHG?vilLT|LcrrM{}jTE%|?cFaPG%ZE9=7 z&qnlHyw{;OX&0P3!h2%|vg+&%nMf734$R%LZ>G0osg{LLNXq9ZWqGJvX?9<(Pi?+{ zfp)&@IsETap|M%JvCnQbK&-p&9v5Ll6>1c)pP z$qiXh3WMk($OVY~;B|xWG9WPzhaD-|uKtep2FXz8*g34vh3D2#h{1Tz&yEq;~SG5)( zGT^lXHGhr#7nKIf%Fv~^(h(c#!vh9+mTN9X&hQn80?-)EI zrn=ffNiZBpL)#r~7ViYMMzA2`Sp!*;C+o-2bWP^p87=Le+gLphm2$a3a#1HQe`P@ldXi0V0Z^u_HP?`DTHoNmz7m95*_`-@!WpYy&H{ z38at`!Ivx8ybQ~gy}3;b>qApTlKV2touEY5HAMs%@p3m7AE!e85scC_QC?<_CS=HU zXg(8=UN00HE0+?z{{9@Q7@8>Y3>2+RMty!u`U<{;l^!r&OT;Z}599{CwPr9Sh>hr2 zxg=-}=mhy41JZmpJY;s*nghQyGZj#t^gk}709V5mjEKcjEVhReHUbYA^u$J8hYxT( zmiF7;;HfQ&JH(`3iBv97SEOzmlCSU5yc>G$VodXH#l-gyeqrA_YxNs56qW-IUVlES zao6|3jly$aEXCZC%}DIJUw*HSWQ7>!=1`?!*P-HbP%iW|gPRLh5@T@GY|DV)1ml+5 zBbu(%jSwb&Q)jrDKX!GDD+diCQpgFmK@TT%-w*)NHX!kf%*|&Dx07y6Nrj;7 z7m2U9z!KoBHX!-xOWikDHfF;jN^UrkqE{qy5pd10|AZb!E`?q9G_Hvi#}S$AtWgr! zL>k8%`3lZ6)HSnsY)kag$RPwASV0Ut6Jj~5;U|Ssa^8>YY{0qcUF5Vs%-IN+D7^Qs zlnbX>07wci@R;GOrzBedLd)U8|8Q3AI*)BGoQ^(Ack97a--wK6`c9rXciq+C47dU= zW!FjC^Webg?cU9+FKm4@#g}7@u%ms#vPV8{XkS$oKr@-hyG`U_*Gg>i7g=QWPw>%+YV{o{0o^?_89PlO^7O zTb>V_zp?I+a*#|H$%QwU70>YP=Z1*M?FD8+=S6Ky|G?dy47dq4#@m?RA8HX%D3`&0 zWnEulPXz+Kb6ER8o>o;$qGJ`_-z* zJ<)lh-wl{{l3*SxbR!8&}>Cj}qQ>vG?+vgZF(DVa%FH#ze4Urr}jW z?GBU%R!hS@&l)3kH3iYO)OgDzkRuy}^h(KeWvb*!1)h>ZBkleTH0(Z)SNjg8)L;T* z{{&;|`*UHeUSU~7O1|?@>+KbJGbp+;ut+3&;)dD9juigTy|#wDOfBy-JOm&Dc@8Hz(ec1_A78^=G}fnBwIqH^y?kven5VW$hE@%So3+098> zuXm|5vk*jGJLjzAkB1_A%%#3ZClM)S*g2w_`V$@}%m9Me=RganHWyaT{e^?C8u)G7 zgt$5AWS9C5;bRJ7PJHJ_=i}{xH96D15JFKms0;8FNPmo77;v-`aGUm+HeOle5H5x> z-kIBm@PpEbv|3vRl0Dt&ONH$BB<#<|hC(oxLgoOukDkqMOPIjk!7mFudds_*^Ztp3 zjOY`93VjKThJXuwtSzU5KYo=McCQt%vhtbWgK3TLVO`%m*(!-ml1pJN3zsraGi!s7 zIbX8O><$^`O;sEFY$XIy1tB8p2e}gZj?+O`R{*9Tri$&1PD5hl&5pBfI6b7mj1%f4 zewx3K^{yom@Be*9B1q4(c?riFUY>&Tt*i#T?i zF6V@xO{1n&h-WL{>quzBg46KJ^okD#_u`f^JbuHj()n1mr`ll4{uDN#L-0~S0|>H6 zsgn8ms8MzRE-vLQDFNMv@PgBW{mdQK+Q;9r=1?VVJR1n!kX{Qp3%v^lNZ4fe%r;a| zL4M4nBZ0xV;+n{s(8UD2{1};47P}&nCGaGVgMCG}9ZVdZ*@{;@tecPcJ4v_idlE&2 z4@FE>da(xn&!Ltb{cETqKD;~p1?@rY60RdoH|(H!gpy0D9_@&)10_?arRS@V%we#Q zu4LSoEB)pIe~TI>(DQI-JK|d9kHg(A)KVscgN3Q$6p$ni@xw4{h=3L^obs}{T#aN9 zz&V&qJtSrjKN8)8#-rTOA_m}|+aGW&p}}Dbv9C(ah8<&(C}JGqhDH}e5sOPcI#k^P zp7BlZcgV2Fxg^ws#crmFX=;*NmJTm5scRBE>%7yc0kK>mP0=#UG=-a#L zZXU7Lx$a9nY?6*#_vH=_yOqK`SffIM2G^t|P^q;aHQPdAEJo~i6$^3+0VgluO~)}x zO%T*DG2bA+NIU{Pl42G!IIyCI4FRxAIh4x3##h6Ztp0+r))C4DOg)GPq*Zm8r8c5? z#ef#G30b+fTM88*sc^MiWM1MpOg#uQxP3X*jBm6zV*o8ZO??iHr{-?zt+K$hVvHha`ao_&LR)z$7YPDQ!{5XYLDmY_)+P zUN>u8sq?dE45@{&;z(PLJ^76=_{w=cQ3o?%Y1ZFbvRz>!zA)24rCbS`DA|h zc7RbMzCdU%KTIF-8zU26!37%*D&%fWl^BjR$$gGD>_$c>-%k94w+j*Zj5dD+gTk>- zgdV7$s+7mt7^nl`Sc}Z|ic^fP-3a|#!ry5nd|$zs!Ah3I5av~+pUBy) zix(fm+VOKu3aE_(E^`R9k}*()WK zmw=M1ck!3h6FP8=XeVY-`jC6w!g!MWMp}bxE!;u9;eqpdLJr0V%GI_ObKpT!=?OB+ z<%wOK#0x559n6MTz~#i;ZcI^Q;1yzr8`udSOzgnWcD0%wZy$V0wGvEih}n-?-x!_v zm&@o~(-Y>ow~jZ@j83HDB%MEGTL)UJ9z3?I^t{CdOeWMKIS%u%-}ypyvd9Up!%zpJ zk!%?$p});uJbuq2zlYoB1LNHk!}%bx(Fu|Hp3xH0sZ;)L4G^&Zh&2zunf8}H<8`zd z?S>*7n56gzK0%#2`w zDp>`Cm7f%SnjA_(Ry@qb>LfN^%|sHR$9&%=%tska=w_G(<$+K}YT~cPtEHf6*pt!p?`HdZ~nbCke zIsk)^MpzkSK68oIg%pHLfjI6bH6X`cgFP+Zb3F6(VGSRBRvGRwKmt(f7%NB{@6kJD zxSP*hK659)yf&-K}xF_71vxVUaH|s_0iFy*vw@ zjWglbiqKH>ZBM?AMrGa_lud;^qDj6uqR|Udo|ZAApu}jfOVnU~c96A7O11gnpjzVm z)K0H{3ljX*K$KGNo7S`NTeoEyUWSZ_G3#mAvZ6V|9Yi8e7Ykh`R+b&{?|gAUiYP*8 zDIhq);wRs)_dMzAkc?KwH0VNxMwbnyQ22-hR+GP_IP5=OlIxMu#E?MNuG8!V-jio@ zlnx>$<67^Qo$=xi!Tdf>-$rdiV3>-i8w0SHhVCSm*3tsNWDm-|9GHhtdr9#bh6;C=hHGq$>FCV-+C(~BaZ%O=EwKfTZ4czMNEq=Apc zm5nyB3Ln!&x#gzY^#+8RKn^5yFPSS#X;@XZy^GYE3h$o5BM%wDsbSCdCbMmooYwT%{k zv5hZ(l?2Xfp@9oKGFC>0-redj^mSCq15>3-Pq}?rJtWgJjW$S~B3Stuq3>|M)wS^T zh;`tpK+~t|hhH+63XAT0NN(8W9l*#940Pj=6pzDCm6`@U3%>2c$=QfhD!vluOShg_ zv2Tm#kU?WlqwfDdj6A>dBj4B`r+QtPAVwb$oIm1M>ThMTF#QLR#t*yATif>(P&?qQ=R( zz1|9#djf=hrJHX3olg@7WvK`GtWQn7&Zp9gI zTWUU3{Uqm`<|eE&02J-P=DF9lQYY=S?9sQq)n&4&Q(5N9%+MW@2=99Bxuyx3qf;$4 z3>J2Oj8S4*_;z$(q4A4Q=A|_qVc(JZL%dSBN?@ovLS=4eWl3n91=bQJPd@gkBl6*C zYaKu!NkcmZyCfK}tYLu6XA_cphr0u1(IY4czp0R(z+b2CPhi+OncZ_x3_FP{Ro6yI z;X(WfK#rN}3WP|xi9c`qJgCoLV!-3e;Me{hNNTI|s~ui){(>AI6d=4BVg}eG|d+rd$?KaiMv&lZADaHMC4S78vw!k``67 zM2l2KH>G)+SHH{+0|+H?xKa|AGe+W%3v<2fK0A|4j49^zXX5=a)#saIwnU#?adfza zQFJJ{-nqFpP&kV?PX?}aOWnYbXm(Ex>mqQj#4u?ib99Ve9UH0fsZK@Y^1J>!dV~M^ z*mWHh=NxsmMO(yj$HbL_*@uHo_Q>P?VbAw@QQw^$o~tHY?Uq@XYB`T=kLdEe|JS_f zf9sx+kRDu$2Gj2^#priq;yLGXQ+w`}kMpf1in?9d1JtkPpW3yh#|x@W{?bTu)B|0z zshKfiSn}pv?P1nlOd+EcsNRG_#=&z{_T2W`lNuGu6|2}KDScA0dXI@GANs8@9{YxT zsZ+WZ8l*9F9Tdi-sXzO7A{1!k3BLDx**pE%#7upXt2jTI>UGNU(+t1z;)G zI+F51+63xyP~*y#l5G^ubtm^=m6HuMv@m)hYpGEFF-Uqr%cuJKX%CjOD$Qi>?O-LA zf6ChY{&3DKoJ7{Y_i5sZw!br5J@36!T8aNwL zjFvY=!rLCpL|EW+VWx8GQrw#2#*i#RY+f}%_%{DhK_OCzvtH)PLWr}7N>MWdl%7;< z5;6aL1OIa6Kff-xJ6sU88HAi%!eG3;#!j(=lg5^a?UF$-a^88)%Yrhp*=vl`!mWMi z45=N@lXjjMSdd{>VTT)@ zHMrff@?wZ_&~Gl%jAz-}Xhh69{y$-F9?;a8?vLB+jNVz)+v!ZTwa83uYkL)_bwPxX zPG?%DrPj92h#Dcaj8Ypy3J4KGk~-bTg{cdu2ytrBwhD+y0)*t)v5Lx)x*aL`@9D`ckb_g>-__yOY&hUotg_8^sY{&3WgR3p z7S>{%z}(@>#KkpEnl)}T*gEr7D$;vz#{Gl|w~AY(o4wo8Q^%a1(mM_&e^8SUYHJ&C zg`9}(Sk7L(T|mb?irmI;(v>EO%+~7suF;d6I?-t$AC$92l~cK4W&6~NoU4>D*{)EE=(&VOibK;ou(RCN0JRiZ z4q1E=%op=$PKixIBRLA6K2kw-w|YHL#1nRw&{Zk5Jf|zTe>T{SDiEDu%4z5||%Q}~Y zR7&$@BiDy(8H!OOab&q-K#=X*v4|SZfBT-f)|s4UsDKV9copfifGbeXIjXvr*Hz!j z9I8+b2OVMW&;2RAIx_6p*&De?AgL=L@qlej{5faak?vR?+2?5t&nlc~tV~c%hF_p3 zdVwlr_fd5CIB@$}3$)myGBIarYm-{WbC<+YCz7yW!GD))-{a{$u~~Rgl#otT9T#lqMMD^K1YK_EyeaW2hqhh$@N8KbPO3 zOlQ*+h+6^%SxrKcKfoQ`eKB-&BeDL0l3IzS@KlV&%(_^7Yy zRlU~N2w*B`__Bn2z@^u$r?EK)v|ynqsCrQ$ZW#s>x>NzE&rXVKjOxj4wW?||ODLt3Qvh;?ZTDnl)8S#=@XmeI9JZN@nyXH* zKVo4*<7Ahz$UZ4@3&Nw9+_i;1KLjJdA(cm@tu0y)s+E}>z*Q&E)`4VI7>&D=92DRG zV+qF`!*i>N&Yk7ACFA%Ogmn@+P)L7*t>=4OaujY5{~~uEfL!DXSwyKKosJwG=Md9N zz(Z}Yf$xI>XOg45u>T~YTRIx;V6WQS^Ta=q3a1Y3d;wv{HbhIL`H z>K@F8k7KMqN~P@iS9RY)qZw2_c_Q)0Rg_*c@RVJ0g(}FI0$K+8t~S$pVpTwh z52&$=<^ZhpNNt!FLu=w42#|$BaQyDe-O4^Zlkw6vpVxvhH@dUxhI~!91uJY-pD#`S zo<$Wpa5$4uasFyTdnxMNJYX2(gMSZ_9>CnGbsk=3qU#mB3Eg~owq1}N&K)@#gGH;T zAvIWG4OiK;fpl}n&>jX{FkH!?nTZsVBwW(8->}{vH&@N z?jpp^Z;2_)%Mo|xCQGXQqYY!gocfTP@JU5$LcX2RRRo^i$uERU*sPw`=Q zCvPLMvsY2T=rBw1WbWLhRw9C0Wsuk->z70bf~*^D*ug40FPne^_b@#oIWv1m9RHm} zXKIS9{RVixm3zz2B2%_t@TN zrvksK&9rQdbAFBBrL3m*!8wspczTT9iP{sfvD^)y5-Sos;*|@(y%;5kRBv7D&YuI) zP*-VvG4@G}JtcR?o=pa>5XKR7wB=QvXkBttWv_n(){7Tq@VbZ3c^*oDy{474LR{b4 zt28CJ4%&-8wmhqJ2vigO6`p;1_R9ey{1=lqhT*!-04xTdw&BF28M$C65r|zB#J4C+Di#NIQ!WXHzu_ z;aT+z#$NESyPYr$C+JU1^CQjgC9l8;L|IggbPz0$ymqbYkj_1fjn1JBrW>nwUuJ76 z)fUx?+O8CGVVcJLQ{Sdn9-Yx3)!Ubz7(1+rG;&6z|A9|Uq~-vcfnub%#_}Ocn&18s z&HL`m-=WcODFpKx`gM{FWMOQn|&QMHg{9aFTpLlr5w$t7$g5_K(FAdf$y|Z)=7tnuO!r8c& zN2>PMQrjx%JHCSigSEG4iJN*h-J;^i#z(Mro5R8k5m-CRVBxXb;}y}m?=t=@9x_); z;6@9bC-IW0A~e0G4G#CPoNqpm9vpS&7<0(}pb;dY`k@k71J)GTKkTT8c~W?1!$h&IQM@zeQiOoV2NC1}qCBWyWy2F{U+m>3ckwIekoAl&tV= znKHJqm-0ZZdg^Dc^vc!dCcr@G$ZN-okci@0Qy9 z+_OQ^3k;ajBndCK03`X}8??m@Qh7>TY6ta|(_+r1zYbH&t`-J*3tSSx@yJu=4%*hF z^L>U~HH)5@_Fpk+;T(eKCc1|V0vCo{BBpeQXH^`5?-k4?k3H~~7pO5)S}o@w(G9s3 z;>n!pn}TsueFbiq*C*!vS(mb)bJx8RmuersX{&#Jti!Que*u-Z(UMG;=Y>K?gt&m= zu&ETz^v7seuvb^Mo)>C^DvUDLf3qblk*Onlt@WBYk@Lf$7C+!Tf}J~KqVRPP80_7k zQJ6GTkZ0I_jCOH1o~;5A=PEINWWd7M_18C?jxqEq36f&v4p6*IgV1rAG6 zAYYQ~4VIRx&pQ|JpK>ApDI-9^cI6{L`9>=Tmgd6HPL3&^#oquk=@x`*HYn(uZ-R7q zgyu$fBG3EO?hqzkM`*#Z4UF;XnS2lZ@C|Fz3hvd+8F_8JeND9l!Z?RB0bFVLz}IEk zjbnb?ICe`D&A#Idu}t*hmSxS28^hrpEDQ?Z>7%uYaKmjGa~(93AjI2Fqp4Cz;z{5` zT-__7S1fqp!o9qRZzz981=1F`xeC7u%ORC8c5!p#Y{Oo%5CyW&hZw!B{nLkMq^UFu zB3e#4G&C?%)V?X) zS3%_6sM}2DQ)t(vVm-_tf2peafO8XNK!b-X0GP~ouveeo9>mm!c$*?Y&1}7VmS6}0 zDCUQ1WqMun>J`Ler${|I=M@#&<-Riq6cJ*T*L_{tR6d6F48F6)aFyg%0OKG4T&vcZ z?s)vUu&tWAoJm~2H(3q+%WBHzV&c|fMr*;3Uxuos22pafh)DL67qV87rUcvZ!cg`a zQ6f`4jt&labfgm*<=uC(d#e#}Vmg}-!0Z%Oa@z4o0@f+5){VBOD zZ6Dt!7$tTArjzbU=24dZ72dlTZ;*_A!e3xRm@I5p85OT@WO6ve)!$XW7h<|LCC&54 zM4q^s5HyOqXF6g2@J;nr(PWExtsevoW7>wc+IzTmPMGlMCseU&AsygmTc$Rn-dIm> zEiv;mxIs@>K^Il_sy!Pk-}X81`BRzGA}ymMfPl^RTdw@H$ol19t& zNP08Im=|DfRghvh( z`f~;AgcR9z$<8B$`hg*;Fk+k?L0-9fF&r zjz71w)$HqWpSn>7j?V!x959dxH*7mw%!(KFc+@mBmSw{@8yCTOT*a(yeQXVJ^d@vILCvX(*ZUOJ#LMQOT#lT zR+_39uHNBMMssSiJ5@c-_-x2rz|Y)NZLq`SD-A!i$6e;@#Jz<9v%EqgGL!5*SUJr# zFBqk$Ma~Ms8q?obS%dfq8u#|1S6#n(J-ljSwfX^!<}yw6F9i2!{U%Ik(aPFFS7nzP z?I!6zi2T_*T9??Pc4xN9+M+U;#G@6$PFvwC35w&@+%N8m(*Xf1to|KkRESlEDm({> zgj1J`oV$*w1%%y2t0Id)|H^MSFC||rPs=vg7#puQnKz>RlBDJ-`n9~#K!U5!v`FC%Pw)lY|f-F(7RpqlI1Eos1lEHfbU8%u+bin+y|B65XPcl4(A;CC7 zNP5O#d(H^JxK)|H7RI;$T(~I;%kz-_BHr#t#O0)dAd08P)?t*5goWvjz2NZy(-jj? zB)aqx>O0TAA?3jJA=%^E5Ge0c?A%Q9OMaBm^5x;p@0f1!T9V?zT1r7BY`lGtAN?%n zUbii=*x8>~6Z>l9vrV0hs;mj)rc2|XeKxOE4!#$)$&+Rv*kCtbbC#EbQM9_^Vm@?CTJt%eUg16`zy-Ndwr z#*0A1I3)qzDb4T)=<6!#VR?HN0U1y{eMFmG!8{R4!iQfcQz z9d2jPm?VPw1BjJv=^{#OHJkL3s?8`rw%akxGL`)D>vuQ!4E&({4q?Dxr{D(r65{|_ zq7GSrEQNwkK@x#x+R*j8FLz5&r&fp(2@wLr?Ht?9>tFdL<+kou$bcrvr>DDNPyZe^ z?@=|u+GltgBT}o7CJ@09nLR0enoh^W8-S&(lsPHg|xg6u^b=UqISC0vY3cP!n`Jei1g3Hxx@6tQFgZlEgNX`Rk za9#S<21mc6QBKBqe?8$zdh}wqE_DymEn5wFUdbQ--8=tF%d^ z)#qW_f6RLVm+2bo*rf-x4w3O5bKnoScV>9nb|pG8F}3^4d_OEeuWx>*jr9o4mNTTX zHkr10F)7=9r#QX4UiWIa7!Uj1=IoA^2<+3qT+)O&rUtS;w}MsifVVGG$=1%rAMvSU_@Y0RDGf9%T|*`S`k{~7y<@q~S-B%p z<>zFVE~Y-m&+*aG4$xr~`Yd_YXVwd)3a%b^k|Mlna;b?Fe67I|VgPf6={Q+&^rILy zKxz+#N(MgE?mI~s=D$jkeA;#s{b=jQN}tz6R2BCkHcj|$sWE2ctW|G%iZ|6_lzN9O z&3;PA65Ly&;nsLs`Mf4|3k5{M5b z3}0nd{3ha5&+^DPU!8|`#ydqvRgS!Vh#ElsEZnL0<>lXM911I1$MdH`+x@J@vdgUx?dx9|p8ZPmT%#rgLm0E{pws#1I< z)~`R@_AWo-$^69(W{=vk&-s9(Y4zzYD9H>K4SD&B=%mn$_Z<&Ypl|IPT3MHtzwDV z-U{*+j0%a*mSK%C1-x9s3w>da8`V|k(?`1B1;Obr3r@KKUQz!x`F{RrJixm`r4!)Y z&oph?_i9u_c~>L047+Ytswj+5_1wuranrKiEhYQtW-@$023YfA+W;cmJz4zA+fF)X zC4k42?@2CGaD;QOH21mvjRmU6uwwg^Q9guJ##AmdiDjqZAk8Pez=}5WPNdXQSoA6t zTC~S~jQ;Vz?2iBYVcpg4cV}lmd-SG1BmUcqvzmUa@U5OQHoUX@Ik7FYaTM-Xx##-N zXrFjY-98DxttF{)kup2dTU2jXk3L&*#$ntfAeO2osj2s*A8gTv_ts5+&28=^o+2w$ zbbsHnJwa~j+j^#IYE3z&X-Ya}dr+ycb2Zwjj}F#WKE{U}9~TSHtBIHKWgvGG4|e zWUCZKjjl<-fg^HeQqVi|3)w*ymg-lS#{BGF6*-^bHZMVnDK;hdFt~&Q>^PwFRYQwC zaM3TB`CTb+ADoyi3gCn_2i4Sld?o&)j9IMdO3dbzIcC?_T3Nc|yFPyjf~l<@Ah(Yt zheN308sy(`x=u;t74#;(IJ(JJ-m-`}s3RxF2(5?9y3`fFbD6-Ec1-LE>@25=F(I@@$D4E=8D3F3J>Y910`44E6gpr=F8S5COTUh^ z+%v=df87cB>Nw0bNBtLj$&C=z#0v>;v_;9L87da3abjMpJXf0V`b5EtvlqYfLU?Zc zJC=G-pBQPAP6)<}e|+fUr4=sE;&`_kumNfOT{9V zj|?`1H_d(uxSkyf+YF|wYJVHOtp-zIz~>q%wU-jarwUH25$rITIqyqFyEzAdnb#|4sU zqUkt7HwB_Ru&DQrGhn!!3l$9?ksQY>aT=-{!B;4a9xjo$4K&R3-~RUNy+qH6R_P6L zY+CnPo|GTPum926qWOwDsx>Ctb0NY+WJ=X)1K;Eh+%70o+&EN#&uvX{_oVE2%>6;~ zj=V)0L0PHO=ci*s2K?4IFxOp0Dg8NNclX$7W4C3iJM>eL>YjOW|Mj(QgW<+8dV^=4 zM)+08uuOKk6j9O23j>Ru&I=cv3w6rdC*9niH~r|=)|Un4%>0LEfVo>lIAa_7(w@!4mMUF zh*ehv^7$Se+%!~=q6oFxdH#>Dg7-i`Cj3Y;{X4!-(e7X`k5@=u4DRP#a*JTHp_!8Z zA3_X0+ozH#zUeGaCdJHvln=1F7e$Sd${YlL9hrrYNBw-Qz6rf`;Khg(1=F!=eVO7Z z-fvJj+NWQ^-R))@YuQf$iX9P4t)ZL&gBD#3DO5@?orGuqqdW&HBis#d;BC0o9-anA z?rN}()rBJ#Vnl@tYF&S(MaQ2J9o!5-@LR*}bZ$F-pkqy9#Mtw7K5OFQJ0*N*ppqK~ z8vSB%vB(ZLl^0uzbaV>jvQsI<*%LH&oHjq>(>6+F1q*&bsT*~b+Yf&7yDsKteN2%b3R2J7i1Quz%&*wI#2 zaDrs8&aFOR*V(R^E|Nl6tONy-7zcj6?{c5AkP)m32Wko-`zA$9smq~fb1>m)uNJHW z`MV4LYm5OKB3&T!z61Lk_mRR8EMQzOrdg!u0cCL{UaLS>3jt|!WFyzUvH*qU*2bA# zh|DGY;@32{`EZNRlG)<|1txJdWmH3fhI!QaXCNl8)hfF&q=O_57x}10hHM3bFoLGm z1N<;Q*Ndt`DPs9d%ANwN#IR2PUiW2XQyBrl;LQOjt(73c^HP|ho!Wl0^;yQ!B2%s+ zdpv8!9?xHB8A~z_oVQ#YQo3M*q3H2luiZpHt0shheu*w#87{qdq``zek2?Dm{T@^A z*BN2|(qBi4%(UP4*HigSPCJrNF;a8ZP+sTleF~I(V=&*j>FsBo8KYJ<&^!o#2Uf`{ zL3UkeoCg=-7p|2IK@0fS=*)d}@6lzUFU5zSR)jl7F{@RTFNw(7keu~ausQ1}EI&s5 z>NVPx)bBHVL17$}Q=i=~?0qHliyew^LgJlGy&7`17z>4&VdccseuMB#>o&$%vbKyt z*Zs-4_J4cK%*gK-R%T50i{>Mm$O-O=TBNNXEa`eTCZ~VW=zccw{CwmBccg7MJ*##t z5%maOydYc|4!S*Xoe~azH55x)DRcSazFBv0suwjd&tKGJE6NsAsFkE^?5UlO=}$!p zBsFpSC0M!F%2GteEq+F1;|_8=m{rqIk;G<)5v2ha#vUS2&^woubzc76`$0=(UBfnh zYT*)fR!Ly33KxLp;K@YEG%l7rKDoMv)KxP?;XXUMcE*@tZQd8v?<;r41lI)#K$+xP zZLT2!8>Sdb^R*;?!yecvck*pq@YJaMI6Tf0BQdNtBlKlXgXxStW$`;ER21YV;H+7j z{O8WTW%xGG+ih%QT@7fOxD_`A4C1xsn;E!&ms8PYV@2c88!SgGtzn!u1GlpaTMA|i zA4~)|_u|YGY+e3|@KKnlO=}C^ls=;9mA|vR#4j-ivd9@njhZZHF{%j7B8Qh!ihh!G zXS%lVMQKm+9R5Gp&3_}CAYHD`RC!EYMdy`*=fa`AZjq3{Z)hf?uExF)UN=!0l|`l6 zZ*kdcWVWDm!JmKFF?Yg*%^Q0KE0pEg{!pj!zUbP2hGL!;cWvjY8KPn^$NDy$U8$lLlYF=8iAPCJj;WRaHCx1duy-KG zFUU)oMwE>sm_zI(KJp{in=Q;-q&(o_AZ5YSa&#K13!lrto6-9^4ZKM`l(LwHz^uO8 zFhnLD85TYC5n|nYeV3Jn5{w8JhF;pn`a8JGt`NBb*=rO&7mU652e zbM}F9)@%cB=75M)o15&l-jf@sn?6M>Y)-<>SoSS&B6Kq|XZVq>GhQ_87W;kXlgy<5 zRSW+A|3S%8isrMfl#5OF8}A~K1FhM~)=rIS=7teNbtRui3;uq~sa&)nlJ5c{`ayro z$d_V&k{511qRXb;5y>?oUe6s)aGUdFdX@+jq9Yf2mcl)Lpaf$I2q&dxRcBBqU}=QZ zItwp9uTb2zUe(A3w-D5GAB`xnA^Vp8+&Ep%DCyTem-u|VP!b$<9xR=mRxgD03mUvn zMW-TJV8jv=EE3jH4ChtVc>9gIgy)~F*f#VwK}YL`YI%n2z;%PeWs~jPpZrH+w2Sd{ zEr~jDJ!F&jhwYfi9Gq`0Ak(I6sht)=mTB#;O5^rLoyrrTu>+L}e}SRjlrB)ut@q+! z_i^5;V?#D$ZRa(4+gsMgI1<$n=?sOnn%A%c4fQjWdFhkh&rwl=|MTo)A3XiHd$&*9>#^h6ZU&!))M83l};t_o} z&P3xabhCxJh-)BQY^h(?Nneawpyrswg2|zAmf$`Ll8|s=GMB_L%BBm^F=)P(_d&4% zK7XnCKw>(`+%cwrq&WxFI6bFT^!<*f_`@i;0TLa++|b0D4nRIZZL~$!fUNKcOhlqS zCjwXy&E~VTx+A;Xw42t-Da7GM(nT$C?EQ1pu=oU5bIAT=j8(@GJlt8q0m3F+*>_}M z7P@mZ%Xu{e;iYMH7{oq(&X`B0!f(8Mw>_`=6Bi_IthXF(>4e9p_;4CbTCSCuR$7`% zN~zK=Lb+(2R}F?@nr@T!OCPc0Zi)6bdN~==-r`ozCpDLXE3=jqsgr z^tM1y`$?(nPkEg$~ zotB^Nf6ZOn0vt;fb5DM!DNp>5d)prra7bY!;{Mr7#2dv&fnD=4uw zS{@_`C{%%RMPdtarc#L_7~Mj4B zU6w6zLpHS-y`;vRhs(vXWj~HLt+jgVLVMUj___!GzL&cCX~3E}cf(&R?={VT z^{>Vv@#}qCHB}$%_b@PePEqn+ z(4?zKhS=h1%V**h74?s->2Y%IQ*3^9HJ_de_ekOM?!bJtBF0c=cqjD<2 zp4uO2bfzJc%C?|aYeR}uAZbYH0V)YTqQO&%|8On1iV1E7x#GlAmw=i|J)shqIqNfC z$jMw z$SAeJO_S^LWEcHiaf+A`Z79osPqUp!)b+S%b1>mTAn$_N>htvb2Wq439hGX)H&4L( zv#a)>r(EVIx}eqG__O5HaP&W7)T}?e{(<6iL5t0M&`&34{RPuHOVZAhL0hITC_9Po zyjLh0dDnGU=(d8JWi6G8VUVHOVsG&F%zcO~=0^RI080+Wp>{%Q^S~A@`_RFCK^^B2 zPmc#DPFRl1oLBu5D(u+UK?R!ktO#i{11ASzFB%s|#i>VQ=??=tOk=!wh_Jo0{W=U# zWNpj`qC6S(72cYP;RwHa$P?5C1E$cb1fl^fiwxGn29y16b;!%IMwWCM_De=zh1N9$+cdP!T=WPs8QsFVGj)5S~fvD2LD*^JV7w z^WwHm1nY@j-b>NQcZrK@+FreFkNV1PAu>#Sc`a#L#|Sa>>-Xq(1}~kgwas&^fdQbx z$g2TYj4)#8zIJoRkI_F|zwWz~^|KR-dDl97-;GhU1bzMUXYz^e3F1wY<5x{o?|-H> z?RT!_FRR?k-acg5QjvaqQozHrqi@?w>VA?g;%c0Smc8{|BV%n|(wpkv;psQ?$kg7& zosOBeurPnAs;-t}bdRr9Y*9R1j@I7kWDxqmPYnIZ*@x^H+Vg~X0d~*}F(NZCNPgz; zw%DKsBTdSl2aRo(7H5AX9t3~sUPJEyr2A7Byyrgg7NdE3OM;l}|*Fdvh zm@4lO5hffdN}Gzbw!Ab_B= zvHQfnB~$iX=~_h%EPTUs5IL`boKVw1mZk)!!&`?Aex;R1BS6aqHK*58;<80v45z@x zv`@5{uBDX5uVVVmaW8~}HA)GiM6dSszRE7Hc)Hnj=-?GzwETfM`;tJ-`;lH=s$_##1h(wSR95N zAF@e}LO7XQnR&ag-@uH_E`n{J*`$K2UMQghxZ6wN(ikdmFE6cU*IklR@V`r5K`y7c zOt5NV<>;pm-;#kGnVjwV@fP=PD!-|NTQc)I2;6N`wqS~b&wh#DqxW^|!;{7aN(-fq zzYA21O>dB z^oihJ{ZejCf#M*x#`1NHhDhIE46Gr}72y->vzz+u;P$;TP)EmtyH!>+F3aq~g^c3^ z+Hiw3P3;y#YIze3omegWCL=D|V8XnDi1GhqSy<~mfs#JG;@n~RfWgN+UvU;3E#XQP zG(4!QtqS6G4-Gom)Mmc`D?Igwi}Zne(dhQ|>Ncn^Jy`3QRWBSavHdnycGc?H1HX}= zx*Rgx)0IopCu)!1UuKdOxnIcouJmxc{8Z3Jf&vl;wEn32t)F_?>go9(-ap_sqsBPK z^tYO17P%}RE!7nr%2MognFt>Re+@M&>6lw%Je%p3tIM||nNFTEO{BsB;;tzys=_V< z2Rq!8I;O>rB>|7+7;D-1iX1>mOqeksMXvVCM8geIy*7phnnDTRbXQSS+XV7BjWDUi6J&Vps85 za%lrs5Y3P3``un(uGg;G|^y@PPL#sRf$>s8XISr+m&B0Z*ih zxL>CsYpaL)-7pK%0|!ARuGq%3uxLOqB9ngeI=}*DIa{557s2FreMTh`{>*H9Rwkol zz4NR%2o&v1ubL*8JmaxQ7*2=nm2^gT|33?-|NG!{-Z$cKXF0sjHqg(3Ef;~X=B&Lg z(34~&{Ri0F zIB>Ct!kMH91jsjDmfVJk4=(3;lE8mZkf#-aAq!rAIY|-FM~o-&+CWo*%F>Bo7s;@W zv6eNDb7}xSLpn>s6O2e_O8g>5uTxwAX81{tRn;rb27Do1+mpf|NUlCI+&NQM?2K#_7Xe=@)IRtOk!EV zz=XKwVDlm{BriyCUTcQR3%K`_{$*tH@sv!@#IfEO7IICPREGHd2e?G!4+J+e21S$2 z^j3`^(ouSEBZLY2zJ`aE1sYjt?Z7^T`leYRPEg!U-%-0VFNndCb0p8vglb84ZjGDv zZihnZLi7UlQxZ_-9uW=0`7C!?r>q0cX99ET0C|;Ymc$20);P~^$(5nw^c03yUvBe~ zLiG_(*(jyO>u2BiS?`f>a>^4H%TZR1Q2b@2YGCOn%8g)-|0`7 zr5i=MD9{37T=iW38P`mg^9j||3aWq@Cq$RU_D0Kj)wQsul7cCMci?+P^tnn3E-qj1 zE7`_k*!z=nkK`%87*{}hTZrrd3TRs)DzBTpxryxko};{F<88<^O8j+EvNnOBA_~z!sFYbDBT>(_$gM zO-^V~@)Xxg2`SKn5Fh5dbmWdo`d&s&6DGju153oK1V0>{j4iMg6;ynYcV}DVvBse?xVd>Nwy{b4mpB%qI!@#B3m9ZyX_Ql zCFt@Dzk++A_nFoX84~Ln{Zy=hT>p)x$c7OC$gJMhHx2vzYBBg|@9-+QHjO^P9nof` zW?$bzaKTEo+OzqV<0Mr)6TG|P{tRFL+0IDYE1()+JD| zFmQ}>R)33fTen^KcqR`uY;p(p7U3oRN2>~8(+|t$oEK}466su&$6j-lU%&IJ>Ur;G zwykLB!9FGKjHaR5v}4mz+X-VW4dv%~8Y^#x>e5K!KPB2#rnJA~%Gc9~NyaF-Vels) zMTxLk*%aqSlZb7Dv_VVD}W4 zT*hO4B=XvR@*FJ`Zq!I3hB$PdL~Kgi=fZZ0Uz&UtB(=t)9$Dg5Xx3AVabtf(^&y&I zFTcKuDiOB(vLF3|jxdV-Qnt`-!4eFC)KsJ0OuL9QTgmHwQR!6oTgYW0@z#9)l`1xy zR}0`ZRaFY)t^7~o1Ok^xj0Vx0-XsZr}vc z28Pr7;WBhRPpy{FhCPG`^~s7v9YFSCXyo9&;HFx}vigyXc7~~3Z>_Us_A!dq4k2%X zm*-|oC*ffZbj3z|Zp@R4;-QF$V=SUX7#YkHY5Ul>g+HuCMR3k~b@|Q6%?ksuu60rE z+N}oj+S5Dx-$nk_q|x4iMc^$zNr@cCbD17#wTLfmHDJUj6%eI*Y#pxFMHhHvsEWmhyswp1Zw2Ls5@Z!!o|K_Opj?tPag#d;j?5V{9k7g zrq)1`IVB)_uHp-5LRzpKK1+^1ska-(E1WJpLTA@wB5_n)7_s#6<;}n)y*E9O1=}sv z#6)>%?4yIUtXzbk6~s(yW!Zi*hP(sAJe~xhRU%=M=NJ3&l#&e4Erl{dx-jYFVjv2b zy3?wTw?~#?9;vk3x_?i2GH70Me49^r3292B4tcWt0`2Hc`48-b{L`m@r4+fRBP(!l zzHHRM9Yn-TRQo|1(#LRtPwFA2^*-t^$F0%5fYnb|mIvp94SJ4{Mu|HJ$ipCr-d@_c zp*L5#i1<#_KT&c3F*$8->c7A|4JFLnd|2@MUFER7qI^Kn!8v6T->Se%3)^KtqL3(& z-DJ0%CuSdiFpoO%&lF z;PS7y;9h>`Y`z{|nM&G|#9{O+4`65eSE?w6Av{$So=@kB&u8~ygM$xf+xawMgsZaW zMq!PPw4tN@%lwhQDkCVo_X{H91kwJyTqAw>MOg1 z!_-z`hsFMy=jcPQhR9iZV@-^Y6r56h1halqFJhR|~L z%v}mLmiaoMZWn!v$lDt{pw=NU9l=vjl?@r;N{l*)A{NW&D`Xx6_&cAZHV-+Wm^x#^ zY#DRMKQ<2~iwG0x*{9gZG;!#N`Ba4d?fyj(<3t#ehyv6{NJEpPMA&&Mk2Xz*8!(LLX|}XQeRhOO?aArj!#_{Nx2u{ z>0T@SU;gjVNbLr+El(ybemY|^0(bNFa|>?SPudPBxIaN?kl%)>)V6f{x=Wby{sE5Q1i*q0(D%&O3LNG=^u!HHe85- zdBn>Qz&;$9v;Kg;Qdv3)RkpqUZ)#UiHz}M&1nmt^1Ov6@iy}82uN!apsd**nc`5it zio@soGiDPfIi{_sY3eNWK%O-qMvD8Qpnn12?+8`)XZdw0ik?^C1@F)Ab?K`5KfpVB z+D_VPQ<}(}$UjdQM~#BZGLHNM>;Oenxzp5EB#iU(_I`m!gfSX9#G#lHhE8R%2~DRy z@}`1T&2C!596gKgY_JC!i~FoA_NVCYJo44n5@H`#<^azf)(QAbi8!f*J8@i|b;t_7 zl(|Gdw8Df9%$wov1qB|qWhYu{4}vrCQ)+FI0+qC?wOAN-6eW^zc&2aN`$5|%p-}5H zx0J0LaWsw3jmlwu8~xK%&gKij@4ej*@J+jP@i@X8?-N{6J3^xzKPopJ}L?$EU7LBIn6$SdhjL4j(rm*RTeW$~vE$4<~`O^4%tZ91rg^SA!J0+@c6J<}>aT@$G= zm8y+DzEgnY?wHnB)`d}!1NrJqMm9n+YyLoY@8kQegd#a())%Q(V0=#eipRj1KtUZ}n)qB;xzk3>n81kIsLiq-6-NIC zJoe;slY*g8cQt$7uh7x6M-S<=ode8i)~RZ>OcV~A()xosD=cpwE+i9QXv8oJnSFCg z&(ha2XZ$XF$@DI4;RB*Ov40GA95^=SCB812%cY`wSUFzmXb2aV(W=VB@2&FPi0ZkF zNOf|oWEGl~JzJ)nTEM{n47F`*adn7UBKq#1jOI7!B#>(ZNZp>7zO4Trl>&7kt3PN-=9T*bn`e0eFcE2lQIStfTMwx|?`vk>#8Y zNkRx6GI-X_F?Z57R;wa$C4qv@yo%q$sN9>KUymOP$7BQx5oAi`=x+{H7NC%-HArn> zMuOrV)-{yz0P!pxrO@+~SFuEXOp#HK|x(>FaAdb|^^Ih!erkc(1(0Q;& zHEG&rW;%?IMc9MGu>AJPXX)M}7D*y^wl2G(^`h9cmd_(9ODs~Q_*Ns9GV=42Y~_Dv z9w#+f-4jNu)?Y)M!IQIk)N8AIS7Qq%dq+W8QdH7qmxpr2i1*H?bK~N3l1Ore zWtYBiX`{5!F8Tsx+yHzqK|4Zk+L%Eru+1T7C|dR*0?!RY*9TYdp+lsr{ay>i7S^rf zy;5O>Q$2k?<;^9{l7CE-rTHl_eSG8Pr}9IvR>X6S&}kA!jMnYZ&!jp?(r~PlCbbqd zW*hYb%ox}BD6spH;d@yA9%*Kg=$Kcc5tcPauq0JaW;c~Bc4Z7v8?u~zIx?+S4*kufUOS>}|oGBKUlwl+1sXRCx9FIOU|GBGSLXvinf?4&>FY3U{+z z#8c@@pJ6PW+wuR}A<1)h)T35s=`UMLs~lsN=brn|_uqf)N4sw1of~m+)ZbRt{EfNw zw60`BTT*Ve*q1EX{vXdg^>umoj7NLCDQz>NAY;n*2M0A(@2z!7 zXOFWe!gGr!Rzna}_P}oShrxKsKZM6%f9C0^j5uCT_FB@+0T|auCphm49acLR*D0Uz&vK) z=yly861su-8=Q~sVFg%cRrWTFd%&O0qK@tq*+;sO4dCoxSHoz=Z7i(W_MdG`NtTG2 zpLjxQu=8W@`9o=J-*6}lUo6*}6fmb>A=_oW2;6sUr|?raT7h=gx?mLQFb+ec#Ek@v zi1zD#-d({t-yBr88>LM|wE}P}+c3i)ohRdln_8-BL0AEm%zOBi`ERyqEJ*f-EbFUN zn}jLh+=<@gH~%cQ%3BmmKi)@mok=Dxxg)TWA($Q;b)3rJH22>=NuP4pz8SX4++Z>k zNks+s6bx*7Cq^zt>}`3um?Q8MpPr;<8$V@`aSG=@U$u zn#}vGmHhfcCJ$zo*{3Z)mm*%FW@MmS8NM2)stgW?lA-|9&CWgz)_7(c-Pf{W1)8O+ zI#-7Ljo#)s4Il?|G zcbls;wwp|f3a!Sg%Z>-D{=^1tO3Whxb4Uk_W8}d)1w<1B$rw!>ejL7UnTF+y|GBDjX14RjiE#dRzM1ugeU+2L+5$UWqn{!A7Bd_^ zx^@w0?d`P9pd(0=Gt?dOZ1H<6c7j>5`vy8FfJ&l?vS;E`05Po#uZynQdG#kRtZ~CF zG@Mg!M=cotL+fqA4FW`b>3sJX?aONT@!0vO)w#>0;DxnJ8vRmN{q5?gF?&h^e)ekE;ilFG*3CWJJMYKolbz(iHXzwc-8{$rgnq1URjBq zhXjEcOj_Eng+uMNRC>vZTEdCcNF9bQz%`nDr+_wjJ)$zBaJn87Z6AM9{gk3RL^RxR zG?YDWMTMe&#IFIr4xNKfl@ro6OoE{JVDSMOgi%&C{cr2nrVkTKHUt(0qOQK6%F zXVeypOAl8dB!QmOZI~EtPP{eLktdmkusa!}FfVOVO~yF`XmC@&>#TsP3d2d-9qX)s zCl4%LbX>aQ8q|Awd#QRha$I3A(yLhf-4#Nowz@@H(-qSN<9q0l4lmvD(FVKT+q*h) z@YryiQ_XHZ8Gg!AV$QI{>x#)4dsE*nP(nHc$pK@%xt?p_!#E4SoQ5U}@qeHzf&Cxf z2?rK{7qqf=d{El&cJ*SI1@9n%A7;#Jpo^BTQ00G^`R{CDCRARt0x^#A)NoIbAFAB;>{s0hz>*)$`6)w7w+ z*IoDYVJ0`?s|WH~wsA|+%85f`w-fJlpPyxzC<^T3O_LABqr|%SP>G|Jje-MF&jJK6 zP^#@h1t|S1`bd7rr_|=wE<5-9MKE^|-9$+fN>HabC+DcKg*GR%pgx<`Xx*R4aTk8H3~-4L8H5+h8C^X;fC0z#B}bn05$ zIi{Cq@@r4kc=wZ5zU_`Am-kMdvHJ-I71J9p!+eSeb~L4ZYnGDUWW$1%aOYuG zzlIFd{Dr+RE6#}i)D5iw;rF+0P-7xr5dkf#Qa-3)q(QHH6`&ek)GC5H9PB*VF4D7Af!Iy}*pd4RgTT}zO&Y69pbJ1b@ zTEU*BYa)A`tq%YC+v_lwF4Sk0ZJehRINwm?o(AZd%B>@{o4z>0R9qrsWM+C>b)hKg z`A+f8$A}7?j^SpG3zt+f@C>eO8Ju}5A7qXOlR+8N(S7rIe>l@(uT@GH-@6ifdKkCm zmYGb9$lV$Q2|Vv+?*MqIYG<|mVGFHn4?+(^FO91ks*F*`l9&Mmv*;c(TARHBQFyh2 zP0+U256Vb1>#i-8K{3eP-ooRb93GCiSCqz>r=K}{k!k{&1~-c@sYKz!rX5Hc`OJV= zGQ>Jsa)jDfjUW5jOdx6QoDz|%^$GX%MQRsjx=6#JGBJ)Nl~zzd&W6~u+{jga#<$a- zm&)5AkNlN`eH6dTU-ZXRkQeDTs*z*kJ%oK89?8TdBRRGk!$S~?F%cw~wWidTg6ltH zx9QGr@`!=@xxrmNf?F$gvYn{G;Jr5|Qi9U!>5U6RU5R&c3g!R6{q1*WE5PH3oXI_h ze}(>Lty@vcW7QvM9_J~jeej{}x3GxuNSe!js-+n{+f**VfkLd5)hiqC_){*FL|qNM zdUVF6>_gTP+zpo|+14dRkT)l}*QB9VV*K%_zVG4O!KrJT4#&S?g3tmvkV|jMi(tehv!tuAN&TaHcIJfAtEo0(xWF<2i4UK*cEUaAzMEVWHY5UB1<=r6LxxL z%)Ale>^W{ryh)-Va5n8KJQ(y=)XEU;amFXX`teog zwejK#8B46J5X5ZrCr9`|5n~4gi$o~XLnvWo51){qs94(ipDE#0h`lkLB6$#kA3nGz zOh^}fV~}j?*+%E*9j}b;&~ip|r=nk-O8Mt$`Ff(fz%CE%v*0P zjC9RBpV=qVw{}JvGh|jhSQ*&75Jmx;yB1RY!J=siPhxt7v|u6@t=Ln+;}UiVF?x_s zV`hW?QlLJz&0$~heZ+@k8#@Hq93d989&dmx5V?wPL#q-Cw#rX}eZ47y-(R5hg&LAb zb1m~lvFlBcFmVaNy_KY8DanNcIRe`!9D|NY`_0XbDwX59Qblr;K%>tB*Zy@-y2NXB zG6rhT2e5a&?QlT~!~1Y$KO_L@h#bv(A9PvL2C=n|n5jYy6sND?(~UX00i&jIVN@76 z$8_FcD*GW3)Sv0ZRj5jia_{Sa{W#$PLbsPvF&bHp-)VKX%VQ-Gq|oHlC}2>>@mI9_ zESDi{0(BC6H;~{3SxvS2h>e0$Q-@1$(!wl|xQ-=^6XDuoC{6(y-1+!7m|y>6YA~7g zIrh7M5XMFm!&ttFOs_V^&_~uJ3lHQ(l(KGYj`I_5m|h7#85P{y@u$AP&V6*={H4&; zQsJ;3X1%%L%QZ^Zn?u4(F4Q~)B%%x#WsY}A=xqc+sI(-N)ZHf|q`UiLz!FI&sla{z zQ2MVAnq=!K>;aIVJ`{U5bPDcCR&KRtcKpwJZT zhKdr8m~^ffk;9M@VRhY-Fb5!#0q;Ooh<80a6ek6LkQmxrUuko9lK0%DYMmlUnas_C zsf3g8sopr4=FGcEt6ZTfi&D%^B_}VZ3m_5Y(8v@ zwH1mKLWLVra+R-qHi$erGdlj;PchBx<{X35(-Bjj?=YgqUrzNkE5sNN%IFq;Pel%o z-Rkab%vM>9io2A<>;(7>mhxgnQ}%vc^B*|EZo9oY&o^ov=NL|>Z6V_}m^%R7vKUTz z(s|AOop|O7$>J%2?U3^gQd?7%XIWjB>C7S++QIv46rk|!TdoRwI1P&%`B`SN%Z$*; zaiMZN=&hwJ`ah6lFc=S@KHLu9^0(V6I9n;(a1TB=DPrGESf?1+((jemEPI5dy5fq` z5a7WinGOigbvI1+UxC}uw)E8ZE13Jmr53fJBCu%b_Z8CVbv4a}PDoi(sT=uG@tD|? zZx*^L#5uPuap$f#(K#OCWaK?_#>KV!YYlSOB1O1$(pA|#ZY=yt_ZN%8ot1&K+TUoB zR1+bZn|Wfmr02KeaZi{VoZWP&qM-mt6W6vk@r7{Z=l9QCG8?1h6GL2m4(@=Ggn4Ub z+gXy!Vjl4@vNliG7Bk2s4Q%>1L2*GQ@AThxy=jR*vKmf!#7MA|E~T390Nh81xmrUHMrrtnU0O+zbcb%@A$u~@a%S0+2$ zf5Dr$rCpOK!Oa#~e<5uJp+7SSuMN8Rs=wa%I#i zJe-9rMv^E5u>+`do=4=sCn#$sn0Ly`&6jL82qy=!XS)28Zccwn?V1;bLb&E2eHmef z8DzNJ72tcMvg~olsqBe3F(1;mqBn*MfwO~?p}G%5y1caC!>@WaCWGKzLTY(z8+ezf z-u3u)&z1FOlH};jaZ}A}s0Y{d+W*JcyT>(krfb9PxOd%qrrNi=^VN0~nW^L0ZbfRT zQp6TVZb;v)VU8pY4NN?s%3l81EXw}d(-umUyS9~ zg+`@6z6Q5F0&CsX)JVzTKIPH3IpZ;){(3$*6a$-sf>KzYCuwQ7o-{s!=fN02{$$_4 zuq7u`XVJxGGn8m!LoMcN-*&|yv69xZu$t0b1W9gfU^biE6}IGj9UU*CrP0@tAjTQc zZX(W}gnLyX95Y%Dl8^}{8SGH`qO^#qlaq_^=$uIko9iLh+l-xe5XbRA}VW{l^Pv zj5z_K@k~2{K#L=Gz|6rfcB@F6Gt=A?F6U@jIMj0$CeENjerqU0{@Rz1D82d9vcNJ} zl13;1w_HvfcaAT!A10T~;S~3mRH-THh){`5NwVvxm&}@MHANDd_(Mp_ZAU&h3iu8i z2E2Cacge{J&;(8n$2dE|VvU<|zDqd(16nrs@LiCvgO8RR6Sz}7>hb$v}O(An0%J>>S5QwT_Ui!u9?Fr*z{q|C=J#s7JwsuJ}+bUak3S<%P zxNj`T3SM7!HhVDon*Fxc*^>NBfsBz_>WyFt$lPsPmMr@&Hqn?uj-Jzu5v1UPz(KjY z4HSPMVJ^c}-m*s7gov_JoT@%1$pAJU|0Dp(6|&(*irlE>>s$}$^R@PwY-jy7I>%N4TPClNInr7clPYoZ_7KgLok1^O}75>JtLk0_2C=T6_Sq z_%e!$*4h$5Kn97Nw@!*9ZIGIalv$jz5t?j@APw;3^$HoBT2T#%qJiL|U~X+52wfzJ z?=+%lNcN$zOpWs7;yEZclS^h&eLmg6r(U!;o|4^Vj=#+Z&l1(=%(jy--_*u!!J;@< zEyzL|2F%D^4#|1TUn%X+Fb6Z)Z;f-yn1K*bz$)LPx0?(Pgvw_z)SrOB++4`?6KcwLH4S=XQxaiR!FNI>xK6b+ ztSucaKAo;JLx2;4Bpn*zs`Jq8a8FBN)?@`P;gGIP2CRBe<2jPSd)8>{+2*6~LltrW z55XLTvoN$N&PRSc1$w~g7sZZ95N~go- z6G3T!)4L*8A~_d_8BWtdsO2UY64X3}JoJ5nw<2qtqWvVg%hQ%H1lZ{qp3IuATg2sw zX8?K%=IIB9m1V)kUWD(|)QGC>L(8F(U7@b=k6$tqY^os0CZB4#;?&juh2;a#u+Fkq)G0xFH-M-%TZ$XxI zzJq%M?&^2qo(57}{1#lfH>w%{9ewp}!SLsLTSmq{BaZ>xt z$;SPng2?)wUYl!S#_-zz7ndGqsjlbk1g=@$=$yMWYECT}iIm=I(iGUdxlT_zRJFks z$Uo#METE=W1UGI6Q8r9@5CAz>kQkgrFx%iM z=?)HaY5vrVLW4ud#@G#7aV?1Q2Tkyk$4&X5PT-itL>pSlFAteW1{g#osDJS&V&vd| zWyO04@h9;Gwm`jQ47J`h!_%`RANk)U*tv|TGqLo5b-*>PlFj|X3#=Ma0zp6f+fT) zy%6lU3pjDlS>?x{8t663`G%$=ziezSS0FY!)~P80DGcXQK6rPPYNs zj6bf4{ih|oEh<#Tlj5mmun~6}v0Lre4-`CSD{eQ_EGt|cS?`6T;Ks_H=fwTtOyvWz zMVx=uw<%3x?zi;o$TC7sxqu%SToLJoo~|qS5tb8m?8^kyf=F5d@bf>^`mpw|&T!i+O7CJ&qP5+Q6Cieg5 zzmNnb3NmrL5OtMG*|PBiCk^ zrH2;1a7nz}3=!dR+O{EC_K;}B#1|0Zkr9M@(UjjH0=IjS%#)6KA>1fpa?rOS{upzp z&5jq~?O(SAXObx+Ks@F4v}aGtj`_4{Ywcb!0FY`CYm8%Zsek{ctNRZRKbq7IN=R;! zCpfN0*3fqlkid(gHW`Qj&7nAeyRKy@yf6uzv7D*F@V9)Tt>n_&CCbIwtrBGzj@q&* zM%0jKm^-q5vgP#{d*fhH&Eho?L!7u(LZWkgW#H4o6MEwB69MpQABF!=Gl_2hWLF@7 z*}SM--Y%fepRVzwV2ST-=(F)WDa;6lmQ^~)!rs#9h@QJ2u6zoxEU2h4i01*L%@9o)h>WOYUM(#R zhpL-Bq^0Rt)!!_ElwF-z*cQ^q$=ukAV~T4^9Y|EQGG|r#65PxzYhC8Zm9gm-$)$X7 z+ckdAJQ-`VUP}tiO$c}?v2s=zQOT`+KCsxoVmkL3mad)z;8?RbE8@IwuB=y4-$mlb z20nY}7#M6&N!`U5_pJMUeK2>HlKJQtqabRzHw>p z>3e0~tuwYZLKA z%d98v1wTipUbi@apm;b(E=uQCV1WBwj#=$~le8qTkIW@N>EE9Kc^X^HiJQa{s4zTJ zv34C~D7Bx^f&oi3i_a;ojk>TYsCO-NMGqyxzx?TN(Iqzlo%s`O z##{lWk*VA%EXmt#8H(Q8x+?hsPWcdS9nm5InfAd)G!w3r_(O;nmyS#eG4-nn`vZ{W zN`YV_J2q|B6u#Xb)TuE~Q4p5TD9e;@qsSMr}f zf0hiTJ+9MQXRdZox62?Ezh(i=F+j`hp}<(vFkR~W*cA`Y-4gZw=rLDg``8qRKI18k zG;Cy#6?GvUkW^@^d>KXU9nnLc-0uQ3sn7g&J^7#u2bQK6*c8UzU}6x~4kY?m{Xh`r zH6B>h1d4~0_F|ECs`9cos~1M)?V;Wm!dU((t#3;hp3j)*iOVE>#>_?-EW?8uERofv zpw3UJ{pyKSFnp#xhI8@-m-#I{?_a|uVX^b$LlMEih>K%&zU`gpAw547Ec(D*L!k2E z6JX90x0uAKkoCEwG z;QY&FQ(xmj6GE2T9{lI)^uyz`b8Zwww4JBr>z}gSH<6WlZ}R48)%Lv^U$`oD)AB5# zGkZ@d*tPrtEgC*u@J31}tprN)3!=v@;3z>^w&yu^kvPSEP9=!SX<66I%gHWIGqkK* zqZUz&hp2KwJ!SdaiZzk(i~5qEMMi_E8B7aO5y)u^4pd?C7ZT!$PbeW$LNW#{t?Nov z|2y8N`gh#}0V#2Xe1z)(hkmPhl+|<+81iDkqM>$pZQ;tjh|SF8cCSyQ@_otPnH6-G zw4v&K%x>=tbW9ivoODU@W!Bc0L}Z{8I*K$YLZQzvZL!#3q=$7O;x3lCiwlQBJ)pi5 zqXMA+pgY1r^oT;YzAlqd2^)@Ju%!a$@#4oV@`8~!l1o5i9G1a;6jLLU-rq#}YM|3r zkn8`7pN@XGhaA3Qu~IV2)C{8DD>47E8>X1`G3|e zQsYCbYi&~<7qDFnms;sIjXuBMwfy&KM1ebm!;r)jl7*IkF5EOg)>*-~&K|z0`GEjQ zbSz9_N(4}y`FEXaSoIPHvUO)1*K@(FZs-%CV#3*aYvfI{iKN0W4BScl9H^9AusRoK zp4N!lX3k9_?(+6H`4mT$;oupO5t9ob5(+Pgu~nnRC9Ee7Ew@*wMIj4|*04`=eLv?26&npA~){ z_iT#fLy}LZ9dpZnX5A)`wZY6X@Qj)mjHtJBUZ(o9mT57rgg4e28(dT%=WLCLXAY~Q zr>B+7)TpkxIW(iFg@-ISq!2!Fn}kmUW2MGigKLQnzS5Q}ui{-ekl1xabHV;+-J)76 zq+M8FtP@EtXh#51;RigD4L$~7p(l^G<>!w)_FIJ;Yb`9risR+A{(LozwONl!qu0ff z?=Cgv)&lMD=fiOOSshaWj1c53Mh+J*!u^$Hw31&+G8IVCtTSdy&MHrN%XQ>@iPR$l z&FZ<1EDE0%=E(#!Z_#zi%CQX6oyodV5?gc}l4q%exWha>w?5yuW&uLTX)3Vgbmo7-5MW%Mi}PF{s@G;Rg z_a(H|QAe2~!}8HXnv&63YPU9<8lK!|uTBh;;OWWiOPNQK3L>0JZu%fZAbME@F8dmx zMQ)Dtz7Qmz36v-{pj|L+Q09H4fUd%jlP0MQRVAakEs%eL`WDNmQOBNE0pu-6BGE8J zrwJ-@)l?3Qeko@Iau1qg>syiH^jUZ@d6>5x05K!>2PJNq)ztI5t0DbK9-WwMke?*& zufW@9U2G-CXVJ+(6^BwB6i74>f8z9Lcl$pId)CQuzio1%?EUgnd!=zc+k%O@;_Ij1 zAa-vD*|Agv1O`ntbR)p~KQF0U$_`xUkl3^uf+53>7}C^b}nvYmAwDZE$a5L!HH z%a!Mo%f{{-3uc#m)74t=mwnOG(?RB5Wm#`{WX6Q6vgKc$`4)=% zV#zNHXM6jkO0&c1XDZTh7*}P`m<2r%+MG&j3mT46recH&f=nbsv=yE%f0*{gz~^61 z1XnG-8eKhHI0y(}@@HZ`4a^`?#-DgZzexyZ{;_S;UrXbvh`CcfbqV#8glMsQv<}--mNaa2H|j(Y`6!M8a!-_ ztS1H&ZVYC_s~e6+&qxaT1o1Fw0_9Rtdm?7Ne7dtqnl-8WTNm6!N>uJQaa&-L>l1`6 zgh~?WWbM?yg~ijAe5ZAKgWt(B95Ty>TiX)umWbxG4T|*`7ch35D|}PvHE0l@m$Tl_#=)vlFD$gpk!<;t?Pg7fw2jRdVM_E*YHHd8Y%Gd;f`vsfcWx&9yO?#uE>H({=V zC1I*I#Y_RhNI%=f+r#RPwbXL!7I2n7<0{DEqj~O{F9R;t zwRwaca-h1S$~sBfhXYbaZpIXtPo3_Zf~=knj}q6D$AAx)lQZLr1(uCNbaXw+nGy%A zA_hJW3NjcyNJVWgA~!bgoaKMAfZ6)q;Zh574Ha}Q^I?15*?lNMJ#8E^8)o#5r(~E+ zr(Jvcwk?o;a$kjk9jrP^Hfr%@AI|yDd=8!&&J@0 zx|ZmTldl&bY1D)mcyfiALW{A4cW>$5fI(L|f-&GMLEL}iB?jvx@zzBQCCn%Y<5NZp ztQX))_U9!SrIAJn6@<-Ox46d+F37)!MrSj1Sw+!hxLWUr`7oY%T*E1M}fMEV>J_K%9(>Ux-#GSQ8`x2+X2lF`+_}5_OFk zCKvnpxBzg)5w|$?bPq9cQp1M&>A3>@S2IC$$^Wngc3K-csi`9}BS9l^N@7kaFPHdi zxVV}4EaI}hm1)$$?g(j5k^7 z$0FIk@!0&k5!A32RYS~tm_KA$vjhK@%H}KM?lkxxL(Qn44Yq|kmAfjbINs+|%6nVX z0woI0iiY@|`J8?{TG*=tng1(T!P;DD;jSEfv|RfNL`-lPR7{~2E>Tn*mAJTc8j^3o z9*GxP2ae0ju~6cL>8+d9Pz6L_TW?2?h30XfAzTWsLcB1ob=c{B42?&F{ImTn)3BNE zZ_vlG9h3-{#B;dBC*3{W|B}yTVO?rbT6VD zaB6iEq&duv*bkQTXJuZr>uNipS|krMP|Lv;I*u(}s3TH>O`Rqu-av+}%oz5+ScyIU zH@aaJ^UG+m#voU$rdu>am0;PNdnK45INvX);H{c&j+L?z&`O{8;J-_W*gN-zk5?-> z!Kx-2t~ZLDj?j-6B%#FHT8tpHIkHz|>z|7xZ-qoj7g{y@@%de~ll3|7OLObDN5&8p zx)Cf-VS4VrCcPSw%{5OJ_k(pmP`(QPe-{OUcQuO~?CxQhGk*G$^Lm)iNeB z8ynAXd159WKl#0<(`Uc%wU}Pc@Vlk%oh%9fD>y>6EYggg2=(VOHk{v?$&mLW9fCsg-W(lT}h2|5!)GthX$h@)NHS4-EuxsqTm2ZMO+v?l? z#kJ8tgvd^aub8qSkSAkg8=%&Zo-Nk{L#3eE?LsNGwqkU)MSz}_@Ln0<#YlJY_yF>| z$Y-Hd%f7_m@$-C@>xHjZY!2Mz8uC~7I&0mhf|__CG6h7S?+=H7a(zZm9PxgpGfK%K ztKrw0B{ns3l_@{|+VG>xZ?{d5%s|7?xoI z3;G$fJB0VCSa&KN?vQWn7AWCA@#iJF8SDcW&7_aGc%;ovc+u@Em}F)$D0_$`OT8jo z-6|0iF9E?zu}rIhm9cZ2s1to&wP$>3$|kGA5GUE~U{@|IA+1|4>(T8x%|S=$XdgLi zDv3>qD#GEdb&Ee5GwH^yFw0G$pw{k~yRhx4PYL{;pOI{mq-+cX4 zC_VqWM)`34l|}k%?(l_6^vj!xm@;P(;rYTkV1q9%t-xOq4L=h^q-$LVekk+}sr&K~6oH@Z z`hAe6^u4h=PD!G1ucy<=5|6@CEpkSJacMGtn`s)X>T_0RG2gY$zOHUvM(2`~yg8An zuf@k+DV=I#(k*m9Cin=r^;KOEz+w|bV97vRAPD9oM>J`?nE;Acfeem-IGPT!h%RJ! zx~;%lVGVSWWixS70z(jTOb&e8RN}<-zi`5oTQHK1mHnNReo9wh#5RIbA66bf5q~WV z%8TKF^mKR(?gTTn8c+ZX%vKg6Wz4~W#TeMVfF`dJ2*zeI_B6#fy)f3}ANk6{(-E+_56&aVIyY>wgGtzIb;dCh{ofoXjhjl|3QXfgY*j2VN z%m})AWG@AMDl>nKX&Qk^V^%k?j+jqysV=Fv>ri|#D zEV{iSf^?k8K?n)vzFX~$7XKec$yj&}J2o|5Y>xx48p%Pgl95Fr4@(XWRKiURtM~76 zwixLcx?a9n6Po}}VsJH|YhNi#MV43g9ka(kG=Y`@`J}PlN znMgj8dSep(Q<<{&G(!U9J|4*)R3^TIFRtukWy80Ux7IkwD?g=dFz-e9Tg^U}I5lTj zyX410f?Sqe+^qqdQXW+!x3jz)(O-ks?-<DMhzdFyM#JH<{?kd%^5;ehcAbYvY)PAv3i8rdU3`(cUg5S zRu4LuBS}b^H?7o$RikVFoKE@k1P1m&ttK(7C*eXdpKYh?eIF0Tk{c~tW}Pt>uELEL zIW@f7s5G^@zVD2Qqgd?u6){~($IQ7>yKWI?)?wz41WvMLyozfB@x7tDt86eNn6&`J zD88I0joRP4F&IrnFt5X@?ID&@xE);pFGwf08i@g<%0?%)nr=n?h673`qlTS||C$nN zPJE%l7B6!dn`N<2kQ)8!xl-(0^4Sa=aCvP+J*hML5sY4djx28~8T60^B! z#mihkFD!E8#e7ANh+WAq-Bu-F0z zt}Q2QnS9FVAUVf;T4wvyKqoDlSEB>ZkJRs5E`Z8KraMxzF25JDY5qA=1ux#RH+rOF zqTg6Ye}}5&h!(u}1~sr|wwr7M6RtD@Det@!lUXJ~&x@NZd*yl|?rwIDXgOZqEt2k@ zi5!p_$3R<^SB6!xI0*phM=ySo8VFDI0SXEbyml%U(o~4*X3WO0A@1mc=+V50iqu6L z`w*rHBneKFKGqH^>18*E$Ac-e|3F2ScKkS^b8SLfv0HF?^iaOunBL+Pi}cVP z2xy<+k^`2x*<84G6KyKN#;s#9ch3cjErpa{1xm|W(3#$)Z8we^jE50??6EOT$7up* zI-k}}6otdZ%nkX0Fw4A0WG{^8v9D&H*+3hs!=u6c8Er{_s@zXU9)151RNQ@cL9V)_ z^u4rr%;OW-?rVeX&Z$n3Ll<#^zlOP~(s3bH1i8&qX4D zbRx{Y=A0mXZ?a?}X+Zna~ghNIaM0G^>ej^EbOV}cDHZ~6k~Gw)S9U5C z@c2H(<+^G>viZ`UXLrZk1`D<0*j>g~-f7|~v5VBhv7=a#oIP!_7vA> z-Y}hG&NsGuKU5jvA$ra7#YS_!;{;N9DpZ^aIx4)qaGbUbvjI1NDI5n{_ zFZU1_NuI%Ox?`kCj3h1s6C~FGl*%k9EnnUh@I!KpDksOzFF-;o8X@Jn?7e=Iyu5In z{bcbJgRmYX2~U)3ux(#Z7C{-~WiHBYUJ^M~PebR>Wz9j?`^n5(YJiZ=j34et&%k zf1gA-LmwJV{P9h2n_ISio6>%M4cK9ohX*7|hLFR~R?FWD)yHl1r&_ELLzO{p{5)!G zcSf>^-6Gs7P-DRCG@~)4Lwq^O95F2A&#HlvKXlc4O_Es)mC2Z7qf7HJMP|xllZdL+ zO5Yhzq^=N1qQxYO&Eez+=?dsZA`Y%T78_ZieHlDarkI|&!@QCLv~cI>TRaieW>C+k z>UM!Q`cM1dxQT#<=5~Z4#3J$N1g`FQgORtXZRzna>BOgpAS2|k8aX28K)^>h;Dma8 zeJwX-=yUp$24Xy`o+;zGAj3;ibKSzM$eJ4gvi-TR{fR}?0{<<%>E1^dC9`@%xkBQ_ zWP}JOY}z{(Av{4e&K=;HWf>0WDd^UBqP@SHBsT+d5^YEUe!yg@SJze;(6pD*9}hDC zx8HifcrW;l_h+A)aX_}}&MMPv7#_Rl=DMP2^z=1J`AU5>dV4g{c-$Uc{NChB%@dJm z*B>2oqO$f42|41rD7)Y)y!)cLLGcwAt)3KU^5N5GDH8cJfVxDZi&@zD5$ishx9*Fu zKREco;V%IWeq+HXGp@Y!z>hEK|K%&&j#D+bK4md5f|0yqleLy*vWO-%cvT|P#+$<%&C&Mpt>Q+KoFvcco>@c` zQWaU+qfOgok%{52qg-RA{sYUKR~X+3&>6%vbZL6Q^T4Zl2fe}Jx36D;ecq+I%u`5z zFAg;Gd+NNnKkbt90yqA`5H4n+kx#vW~wqozOIpjJC%{zxq40g}m45*r6-+U?F^S5j8%KN#neXM$J5rKEE`q(Y->o2zW zg~ip2G5dU}VqBj=46)C**NCL(WLP%(`ZH#>0cLU<7uf>(=nVyG%|zIf0@RAVkOwZ( zjTU2c=U3NEx~O1uj>1zhwUtNnhl_ZJ@kb7tCHlwVU}_R;-TdZe_ptyEVHgME;6iTH zu)zTR1Xdm-<2#nJlOL0^u|tiO<;cY(Z$vch>fK_H-Y=k{kWQ}DEU1atUf|k?5Co`e z!jg|1rkUrkfw$b-fC6Sz9lXt10`{gs7#-VGa)+t1CaT%&z0J`9d%~b3pMs10CAi3E zYrDO2`;4s!iVsT4de-Y(IJwu8J30%H%86>A5$~pShz6GuH*QqBK7C9S+x5Y3_!3h{SRPySDZy4 z-D9qv?(ty{z(&r-NHZRy{?aMYHua|^r_6OOuR0vv*x6@LqV73&XdnVY1^&nJAh!B9I*x9Doi!r~Ai5Vo(G&37{^-?r z9+pf;Z1<+lHIwCwqq)>wR_6JKW$cP;PB;+UiJglWFwyDoFe{T}sA~7b!R{(B-0+xtlzSh}!kzI-qQVKPUE`oUVZ4CN`* z%S~a`Wyap#rL?mJ9%qU}3HdQd6Aru*HGR$y6Zuvd<%b`9(z=tdF2JQriF)OyLPK(P z4c|{7Ln12@(#lTmdL+m}H4WNCY>o|vSfu4cSKUmYYi+2GOzU(~ig$Vuijna`ip{!D z$K$P4G71V{~oRxSC zgu!^arA+L83Fqq)sdt?kq;F-}+Js6{+;*W5@>i;99XmHCD$8R9n>qQwT31ogSB$7T*{*3$2$V;yMQP!e$@h2c_6JVG21eoTBivn_L$Mun>jTzEs$ zMQIARyfW0%!a*o1Q-!qL3Y0S}h?$cs{Cl|DG3fLlD-9-L9(vkG48(z1Dk{5MWd`C@ zOnL_JMuJI23t26JH&bBP&r4yx#`s#w=wJrFzRc!Ct53YV0z+mpO&G@VXdz-T@Iub} zckQQ|H;YaDWg9|RF9+*mII=AIn3Stac9r;quPSnH@Ers>LXiOY)ne1(lO9QzV`-%I?<)cpR#v8++ zru*fLjwAQT%QwDGdBo7c7PyCZ0LGq4G-bG$wuX`Cc_@4&7z`<$Z&`9ASe$* zZ!ft3`QI6xA7GRFBHzJqy;!GcgXSGg-bc z?5XF_ijwuDDM5baMI9M#{~1rCz}^PKExKUEgHgwpW|D7C1$!#1X{^qU-uGNCwNeC_!6 zcN42U?VWv7AG6i(R-HVSOsrd>z{!U~MXYN&VfdbaTB_tMh3tpSl1o@cwg7hdsJ&W> zbO^pYZNIFxq}z;QUJ#bBwg^rB z0KWVJg9s2Q=gDgum{d|7T{;@S(}*I|vM4FeQlWeNhKprX2a78_d1r!RruR zqX&$d%?h&<`j!%`6h9&Itr|xPnyzhcfG#%EJr3xSWIRL0R)*Er|EzwxpR*uxyn4OD zfAq&!&{@AH@tbRsZ$Fj%?IaO|;$kgSXGbro<0t_frTT;H>@QdOY9b8-1(f8n+Sfgo zfLNnb6(Cx6>~xlNQbd4=emGivX?Vyp2d@4EJ-{EF!yWQ0bLgBc;D#YmfxIfnbRg6-#6p3B`|6n;x@mrcICU{Kx$?)a+&$I+btIXD3)esw4)5ttC1=}_ zXVD^J3w4@w*d!kw&mcY-!gMjxf81&|yf|=wFb;d+EcMAqSrw(sinLiyMQ@Dlf4L6%l70_crIE^#SL=poUSA0y-p=MS3zt(LFq%@;P#9?*e$;b6fI% zihZpqR~^MCzqTLs^1U*9ALX|{8W&c@j}1R`&>ltqqX1Wbls&~{HOcj zHD&zJYRc2Mx$k45{%P3(>#<*aZ<&kG#ILBQX2Bt67$OkSMRoFvinJTQpV52;0RjU{ zZyrjh(QhH_Y%Pe3H)oq+FaTd<@CKGzZk?>6tM)51TcWRZ=0cHk9(Im~xO8uB{Y;c% zL=JT04CdQJmDjujk(zMzkGh7cDtQ|u`0WzO9=s^Qay7hvgzj!XB1Vxcfg4}uRC&yM zd0OjA@Z%u7#SM>Su(OPH=!#dnTm96mrXB0MCl3;3cUZBu$c6s;IE@)b@WuWZB$2j) z4}!40#dYoxUSKDR8#y@p5?kb%3ER1xaK-xg=+3&*9-_W~$gj_ltB;-7WF@3Hd8o;g_zJc)qsS#@IsNq6U%iJE((B+`=(_?kJ>Y^4mF8wbZes zi#^iRWTeXs`v%60)~gAYeN;8?{(2@@KQb^J-Mj)3v*(To ziQ+mwHPX|u1gFki#B!0gx*{v`q>6ab2j8?QDnp=sS>T+3%$iI@WMEYeoN;B1K1RSB zM7rzvax`FT7t*O434PZt$9*hds(A{1=Z0aa=+ibjS9OvWoYakV?S1rRunEjz6CxTvDIk?mzExP0^i?2OP2~&-FM7il zO%k;e(p{38$oWqh7%Q!`xCo3xgnwDay&>%SF+M_~ClamxoL_qWc9lTyrIATyYw@iR zD3bKm@fW)860R6YuE;R`E4?DE{sSh_65u|cQYI|%i8jU$0f);X9fUD*7=9fgiLrS) zF$pGP3ANckM=Fm{sDNZqyGn*hfrI-#2)mOZOHRj~{Gq(V^ITNeDmr?Ulso*6n>4QD zXGoqh;Vhlg_4Pl`ifF#z9Gy*k=}^}IEB>K_xHDeDp@XYlSI3o-!}jAg3EaJKrXG0s z4jvaw8UuvN_khiLv=1#v_i@E zS2hjb zWiq?sj8ga_Y(P@~q9vF?urg=!EQ(%DeT=6DD-%;YxSit@_;dXvNW+(e8Exci85RdD2JI zjg?PxucY?+|MlkgBk4`c-nbOgvfVUx>lb|Rv&^?bTKJ3aU#cCh`es|a@>tv!7+hO& zamcwxOZ4RJ$_{F%>5-DjkbAApqT5xi93&O^GGngIRp`@IcbR9+Qz{ra#pV-NE{lmp z8fSmdBXdE^f)1AJL2?qII!vVk-!1^T3|a!|+~R3Yot#7kaE_^{fGdWUpgbJXI;8H0 z+rUJaG?nE}BSh!pYB}p@1ceL{09=-B8x@(^CifYyK|)_sYJ~7YqnjpKn;g&X1C9Mt zOPV7C88yU-qjnHy`LvxV^WgjgW(7|bWAq?O zfH4h*8IkRS>CR@sFz3pI4>#f0%DfMw;`1Ipbd;K3Q~2K9Vn^?}r>**t*~~J!df<0! z^}4TfP<+2@X-Yc`vFg3!wpW4a9ww`jDkVqG0pD@*p&5g6fQyM}YmRu*&LJY@l_r;1 zo=He&O&+Po1^9TMvj#8Reud5C`Y(8{n{vgHXYs@IE+WREM0qy!U})|U#u9Hwx{RJ= zuGr3LLCrri!=C6+W{hSMU->FSKu_ke6G@7)-WHO10XPC1msO={lc>=L_7@*Sb}zoR zqG3`iYj^;RiW0jHqGb2;;o+tOIuGdqg~Mmw%raEKGAj!s2sk`Jt@c4$lF|d!96~pS z%hl`C77&h}z1kLKGn1$VGB1x@rGZ@rB+GRSISHEC-VqIYz8gN%!t6E_f7}>1gOh7f zy@Jw^6zYGJ6s1y`vY=hi`T8W%FzCT?-Qw3G+`gcv97%*Yq*Zd{GJ}X(&?h#*ADPhU zmMH6YfWMxuJ`o=+M{)1&Y|KLX$}Dw#wK%M`?u{mXsQCZ>v9|b!N5fBAy|=Q;SXt%F zjZP}76EuO(a@29rS8SHVrUJF3e>Ukd(gj?rJjSpi+o=ywZX8!4He#4BA0ujuq-EFR zM&`Lh4GtGc!FfsQh2jgX#F=}<&T=(~KrB3Y@cXrm&!u*Rv}O9eZ_mD2S0csO#9DPy z(x&4_r<;Zdo7O*|5R4hD%a|*KRFeL(1ea*CP=Anvi99c&Yms_$aYaO=)$`6<6Y1^_ z7ygiohn7$H(U1;9&~nnB15A;>h&`Y;;3YacBx~5Qg}u>{Kh4%!61!A6vWPr;i{Yo^ z!-ZzKX(nitBnJnqYs(P?X<jofCWmgY?M|1?I1NFKyPQh8>iu{uY!yA8Ls5( z_x$?Oz%0%D5B8ne{M~Ox!m-C^AN=k7r~c2bozutHeK`>I6(9dJwY2uhhk6s#7pn(4 zPs>b~U8)?;SSu=k6cPlYCc;OVBa5~jlUIh>zz-Z1-V`D(Hxw==@>OdQzZjQL^L;u8 zk&N3Y%hTDw?iDlPr51%fny_7N3!nUsIRE5(B3rR`TxZ*OmsS8cYo|#u6e= zg_2pem_-D#N5-_^2f1lu)j{goHdwO0x9Vds{FU$Ror(O>D@PL8rq>h~X8-tv_SrdA zsn?M;Wb?%&fY?Cix~go?B}=D-{8ff9MzhIqfiX1>RoZy^7f*P2N|Jp2*0`&3JW3`)!kk4u`!u$C8(|_DP$_3SWr9&Ed$5l&66)b_8Oaa~7>l+<^gN6@9y^vl*6R5H!Cm0I+BS2FFZ)Wtw!B86M5WnP>(F1wUa#9-n zgp$T^6Y3*VNKXJcS>)*dhO3ehe)!$?`8Nj^YbWIvXkgO`%RTuf3X0 zuh7YTPfJIzywv=tAlI@V{1jNQIk>NbvU1GFfK?_k_zOIa6XfdTfjL0zW2YWKXYI31 z4bGpjL7GNpV|{om#}ZpilwIwd0x)ks)qY87dDGEK2z z>c3bIKLse}rvPd3VV*{z0!@>2XQKpS=0pVdLV8cXfm~p)aOHszv8OzV9rqBZ+{-Wg z8%)`*h649pCT+zpE@>3p|3GlQ=lsnxf02v)hO87J8JZabGt2D|?UQK$Se3~#yN5Xl z(<@j)^HI!6K>XW6L&u88)HW0%^yL^lBW?4r*Vvt*dI$G@&>Fq6k2s*A5HBB<3e(Ck ztC=ZGXT1Zs_r|$l-DKZEJ31$6znpjbe7oyB>8stMxj>9dS6z<@r6#Q^qaF7*uypDMf@w-~zZ{jz* zHywtw=qb?grYK%zZl{qZB$Y=;G_{y+-r;uzW;69u?|4myjv@0H8&}N18d4Kyw~>vm zZ3IY`3hzD~A}uQZyhFxKt0t_%Wv~Qf<)AfeBv60puC>K?v7}j%CIhMKE7y^dsQg+) z8jHqA7N@j_-Ba!(DIEo2Db_~h?`xy2U`M-|?m9;1VpnRC%Oh*N?+0^}u8?;~BTReZ zP0)da7F{&2PjWcG1u}Zf?Q>LQojef=9flO3%(Ytjm8|ZqY@^8F5t)>X4aBp>4TaQK3rD-8^;WxWr`n^$9WS5mva@IMrF|L~yeDeF%HANTxZ>)^~qeY*PB{TY@& znQIG%J{QYp!XaVC>rF2@{u~&p{B~Pn@qzm)%5?JUUkB?mzOj0*AG&ZPIjkl&VV}Sz zOzU0&tDtoT*NEDnh_u%;s$B;}o?kk+f|7R}Ay2&zy215H(NgD3%z#b7tkLVE$jcag z3-}pM)mx6yUu}lLST3>Xe!a&O{Sz!Uz|lM^jj8e%%yg4nrT7^^**ItYV#LTJWyV*nHD(ys8+JT!JfB%J zi*KUr3CCqlAbxy9B^pz>wD6jQU-5#`;tsXn>4 zX+);_jD*-1!_cH>YEm%nl#jT0XN1X8CY2_CDL=Bsq8+GaD}u4JZw{tY(LQb4-BWe% z*|yc|zNt*}McMDFOVsk}nMH>$r76avVf7x`?G5$kJ(}8=?V?<-Bt)0~ZrafKL3MnT zy@3{MIk-gmm(-J)mOx3cyjQ1Q5FIduwT02GB;QhQGbymundLSzOYHn>WM~L2SHX?q z>mi-MCrTiuBbn^_2QVoEej(?wXOXWiw8840;2#6JF%zlJQ!O>L4tFOQCY7khQNs)9 zop=eSQZD+c5=lv+@d9(C9XS6itD{1537k9hap=?fifh~htp?Xo_QFbzhv~Z~{0niP z!^1e<(L(k|eAZVEQpnF0D%da+f~3fCTH+w_YzQVtooGOM57EiCF zZ!-nYuwVtqIV6AF)~KEbU&F(Z#f@NQ^Sf;?=T6aJh&3Vj~Hv9KYmN(Sm@WcPG*#7ZB$HMU&Cs&4sY^_N> zO7rmAXS)pbFdRobX%?3!4T>PHH#&I#1QO zf9d%xZ+t^b{{XxZPo6o&KA~?0x*m^vW`nWHa1tU(kKP#{Tgome1^|iPHr(jgIe0nq zQ@WyB76{h~4&dfd*g=`9cxXu2gSxXrz(Kw832KMigT=bVP``d)F%0DoVEzCdU$<4( z$A0|kjRA`qLFSflm|70%jtv9x-bP5zfSTwWNmsaFH2$}dH5Yq6+rKrxFYeKK@GULt zhz!%_4Hc`;AV2Aeq0fh$YU~Azo|xx~ZhA>lX+MfIY2G%ZeS@Lsp>|N2cmmhXt$pe6 zsbBVmr7aSPSeL{gyZ*-w9uM`s^0PCtriObo8y(MS7eAYlcUHB0c;=~iofrse9A^`yqmP{YM)xnl_3X*0 zY5BSLySvLQpC#;mrr?+)eG)-1`WALF-*~?F1&hZZLwvhg8!%;cgzDa92Cf1AMivzN zYN9GvaK3kkMI$3dt0>nB`X;wR%ER-WrPnp49jc7mizUbt-L4y|(oc(W=aA(wkPNtN zfikYpuoL_BiCs=VE+ombSf<xCS4lwSJIFL6C)rYnrXw9LWHLl|u_PejGyVjPJYG zE?<=cTvVnCd=b&*Mau-*Jrd-Y?WZ}f=Pd+z#M&;Fz^Fj-CAEafL~;tL(@2iauZ8s& z+~x6B3uB8^Htj618MRxW3EJR@R2rs74=KZ!*5B1V>g{ks=Qy`YAcOY_;hd^7ez4RTbj?4dLJbBamAo8L zk;oPl@~}$5P>Xn+n>FaaL0Koy!s;RiJ{oum*!+5bf-X?xz}>+GV1!}A8_xdi45P9cEdD}INO!EKld}(V(C!{l zw3M)=v#?7)9d^#}I8V@j2K0#J6vKXA7AwgFV_q2GpT#dUCD~emqK!la%w^3o?scCg z`q`^XzG{-Galqf7ooDmbGbDCI$C@k(&x|eb2pgKcibPVBR~-~lWv1a%C5;xjXU02R zK;|~U+oQ~`WE^s;G;l3jkvknf`sa!!m&7*yIsM~3`aSoYUuq7NZ8rJYe&{@$k_;^jIIuQ6PkU;rIy&g5r;*X<}zOSf%{(ciH+Mq|C5eMtnh=sx=jM^z_cK5 zfDN&c&YlWm3({dBwJ?`VY#xH2wLKR+FG5Eg0|#hsgX1|Fcv{F?f<&e`9d|XN48fjz z+)BjDv{&xM9|R8+DOm|m9tR1JWq(_H)?&JqH3_C2W!j{2KgNHp%<34=B(goG4e-~A zn@I&*bqy0_+nbQIS@8_kNGrr}ogsfdyC#vpLc}JU{s59;+9?OF@sY6pASg?i*uYP5 z-0yW-mlNmgj58AU3+BdU*bjJ%jePO6+EOs`t1$1o=vxasXX;tsAtTA7A&wh+Yc_z9 zwgY?Q<)dC4uR}~gud_+rDVF5eorl+ET`^9IJ&v$+e9jN_;rD3GN*NjP0>y)N&fUirZj6{**6hg zt<6~Z?X%+HXAG9vV)Pq1>y^qfpnvUee|YR6-`C>!1A$no}VBd#-)3`fM5hx#DO zaZPV95o6 zr7_%5BHf>tmH7mi61?$>+~z<{3;SYBa;D=g@#8H4`Az}s<{5(7)C(K*U}Z{zdL^g~$d*+((?p{Z~t*^O!N#CDR|_(31> zUcU9nC2-g(AFK|6*!yUf?XFkup6mBV7ZEN)$sAsDu95MY^WH{Gv=0b2Dr5+Lz%UNT zZgT=)kG~7K;;H$!js>Y%uZC|F_YoJcOEC%2xU|JCEu-Rc&|OL`*49H{TX!F`ndFnj zD1cn15$AFgsy~R#_b=|Z8OQ{b_@3lLz_tdTk9;II5^aj2(pJfxezzi?QxK%H^=&1^ zCqN9C2C@nsqe&wPOTJhQkZWFp&W!N!;JJbJg#gTgNs!>mP@;t9z!Yp?2%lA~Z@r;t z1N#{i7Yv&SEA!l2Mt+hy7EC3O2NH*~pds2W7Se{V4o+evFU)CiwqSf*W-H{PL?>kG zs6%l}kj=gf^zo8K(!YebIn*=!=d89&;h0&uwhfbpVx_XcEWnI?(ueCvoNx*8<;FDx zfI1_VPm6E!%Wax~lF=}LfOC0j`Ou4(NtxWikRe&Tn$k^!jA-b-v09u^Bb$CnL-PLU zi_8B&g(W1oCDv;;gQt&%D9 zS$!925hUpXFs-@Jf$zB4d%fwjNQx9^+(xNzKnp^+QEql9y*C`?}tG+ zPgfX|@iSRomq%XMn{mc6g%O-V)GQ<_?)D*2{fHa@sRtHQGdN4cnH;)S?4|#b{qo5` zaEiF_130i^)>38u|1IqMqn7mri3_Fw_9eURNf+; zFqM>a!jcJNjBWby-mI%aR})fX>xW2&fPye!Y_lv$`Eg8y0sC=G7z@UBWP=^YetnjlGNt(%XDAkZGB4PYBtWro;KN-VXsJP(MFK9evx^lksCrp zMbx~|P6NVI%B*4+-EkEG((AIkE{6$Or0vyni}`^kf4*nfU7?BDV`I;EF;bmpMib_D zot8a?>Ok|U^g^v7!^cK~Br67F7UIOV5InOjV9)XN_~5(K+`NxOdQW757j=XK&Q+i9 zTVq1ZWaM|Fb?8!LbV!cKt!#a&X@;i&=L%R0hw8U9Vkkr`9uCv_s>O<`eH-Q(!!WhK zTN+k%gz1>FSVBmsznRK}`I;zPE(wRia-#3m5{zPCyf?`XBoQpnApTBA<_lOKu|yzC z7_6}H*W@f>x}e`C)Cz1Ya8vT9GrIQ6H%3 zinqrTz7Db@UTPZ_+E+4u;ONCs3ly3?OVcW6fvfqHG`N(zUNKvABRhP5r|%|gglb)(#6qaPfNuvsgtJm zC13)Gyw_iI=|Ks$O2i90r6Uoyf?9XD(7_*Eb^4+fX?cvbcx-vgvsi0wf7AUP<8v*m~mC$}^A+A?jlY$UV> zmJX)aGty;~wnPIg^0~=ikbZ_57X@Zas4a=~`zUv%{VT*+M6k6ww8W_bUVhRTtj#d@ zVl%N0Vy^E_V5Ne=Ks6jEIL>Em%g=afl_+fci|Rm>N0*7fD@s$oS2k;SVS;TSxjgse z>lg1xj^1rpObvU#KkZ`{NW%oomhI=2&vbjnhhx@ud~BpEcm)>I_pZX@*a;+^ke?#d z-gjgfg3$TZFDBEM6b`>5#dp=gs=%vv@dly3F@cTnK@vP2$mQsg4%TTw3yw}6{;?^( z$Gcigq0P--w{X@H-+!y$<T=tJw$j-I zb<~>vO}&lP*}KLuH6LFsP9*E?1Qt$Zcc{qjdDW6lhtjJ)9|Io-T|slTYyrBD5vXWM zxwOvUG)AN>(UYPp?2ZHe3-OHbpy-N)O^4t~$|?N_Z_JvdNz=+QZY}7w(V_gJ{{wPa zk7Vws|F_8|`{PHI(rV-2_y`4#*bUDa*--eXe&Xl-S^jlh z_6sMZ^HmcW)SIo5jZ+hyaADk1*tL6}^u*m0Pqpy&3b&jFzd0@M&>?Q>RNXi9;V}61 zg;hZ2Da2msawwx0Hz=>)qZsT%Z`Vf%2zIa+TMgDx+Yqy|jTY^6DdunW*Lku_Ys>Iqhuf5D#?CubDzCd$B7I9pl&4M-u24j>A)~ zQXm61NQzxs)BA@*omZQ>S!A=4`lfnp4)N50OYZ z5@pE`X)T1+34`~hbJblfuo@&5?|Q$qDB)@<=%Ags{+gaD_=a5gSXCUzkchag@HF8o zDv9DqpHnF$Ojlz4&jbyClh>9H6;u4-6W6}-EWxD$o~fki{g3FrmW5tY+77Y(HC!G( z2|hCd3x*yg3qZ?DFxwQtY!ivDcWP3?rLK2>?Re^8DniKUPW)qBPkqR3pS{hIP#t7A z?NQZxU21qMaTN2Hc;USCc2E}&a>|z06^Sr6Xowg~NB65@c-GGbtGBEP>mzDTdplEn zPZP7WWbOrdCyW`?2`$Cn5>{GEMyDL&YSzS!&1?r13`0d^)$t~A69P~DBA{yiM+$kKy8TM7cCz@br&BXOH4#Y!BJBFRP}a&#GQA}a zh&zVERXsM;!&poTXM*u^Qd>rpyJcezUYOtMgVi(#W$tZLcczF~O^c|}?%W~O8^r!2 zgxmrt(~0%x>WH_Ge#Fan=Nb0p_jg zZ*@bN@cW{`1g}BYwzK;~p=3wg9OrZFi6<1ze)_#EzG9}Sp4C#b1vC8(ZaBODTHoI- z5lrK(k+)uL1c4fPU`1lZ{ru;x!W8srzvkMnvbOCcakRda*)YvV_-d#3+pLRFL7sb{ zs&Mv?;R>|R%j4Zd8_DkAXb}9Y?$%~VZ{kG(81Zggw?duq6=76nty9zej`QqkWwH8t z^>JDwRT3CUgoLZ*)!A9Zxm^@C<4M>BJNb!*twCM~?A?vT571NJIPSv{Plu#}^pzwJ zp=$OO#Hxe=9Z!|m?juBNVrCk4c)w5s0XPbt1G4@VhE*s0-3zcoK9S(5biY0g`YPCE z=5&Z6POAg2V3Wr~_;d*3nO) zdTcLB4$S!1W%Pf2{a+N_nm3&Mj;RLPzSUGc6~_y1upC|fs3I7A85}j+Hk4H7Ih*2q zk9h6na$BwGe&pMD^t#Y1cyd)3`Zg>U1%+XS^T}NXx%Q|_-#qYuQ~$)lFThf3k@@_X zu`E>0^dUJRB=T-(Sm$D@G3Px(iRfJ+(R}fzL;<6AbVg=|e?Y7mnP(uVc@O&flSfxx z@vCMSJ;ZF2L-$unns%yC(?X^@n;>Hb8w9Kq2YHWW|)oMO6ryB^Y?WL+${fS&tl(vMUAk zCS_yU>~SOY8gNK!vL5*oDWC;m?o-&B*Np{%Lq{w65IsUZqEsh^Y+zj6Z&U2JK1ypQ zwp7mz1uFRCeOue_K&k%3MP+G@=BT2qwbb{|#Yz3+v`dWCl3RAls%JzCHyTCMhnT7C zl6pSAr^lh7&(1pUfEisiz#XE(6iwBFiE(#6#~$3g=)5Ap&_iMC7fh6!B=gyY-e|BA zB?Z30C4&Y|#3A;39LFGQR+t*eU@Xv3c#=@3iTeiZYi%ok**IvdrQ?aiU|e;m3^TYFMJj(*o+mJ(W87cMV_^0DwBf4#uw zHM0*v!@O6q*3_&_yWet5XW5U+KdH6wVC^o1u^3+FJKqjbSRq)lG^&YV$TrW|XVBH2 zDpM1@@pAXGAou%PBo8-$?NAL9g8y|}{jV>sOEMSqcmd&%h$7>6gfkegAUq6oOX*K4 z{KV5r4IXqGXiAu*g@Y4Tc7S~$32};RcVW6y5hEP{Q|2|dur~`lAHqdrLhXdD7V=bd zL*5J#QZjV2${7iP2gU{*K17sYGN6jBb*PG21rD#gMV`_Gab< z>}X?z><2R>AaBUPG!)i4nv3(ui9-GuE(2MZSU8djt>*+e8n1xY03?17IPC}=N!)i|(ql7q3b(rqPKm$Ttk=RVqef|)8%s(7qqJ_N; zG3Fy~;X^OOm6|AOE;okxp`M&p9W15T14V@DbU1f>hiPS-e%TdGHsrd$*5h&*@x$}v z8J~^(-`i@m)DEya^puhdjn4IZEq>_DPaRosCtnx1?1$cKFxr+Gm$^#iQU+-UobuVF%p+JR8&itz>fmJx39#G;T`|s6{jgY}or-_^DQiy4lL<*5%IlWC>fFSERMA$rMZ+!5ng!iE#kA%r z7Futwt}Y>xg2+%YV;#emnP5YQ3aH$wHedkwvg?oG7zRG>kB7vjBO+3YknD z6XE_Js~Rfe8lF2vZrudRXMNuKGS+IDl5GtxoGr_By^Js@O8)Gb_Ca zLX~}B25+|!eE+S8A@2Dbr4QXd#9i5WnY$O%;hz_(?Oxa3{7cj2$hy0DPE0?x z7IyE6Rs8wx%e@}y8RR)SrZ7JIy2s~c3@rWetlz+F^!VwSlFLS_W&ekYF%%+gN`>Ab z)ASFD2WDg~usPtzAjq*dpOazZA`Qr9Es~?2NGLnV>J~jdP@RI{&0mK-ihYwF#d34g zIbX`eGSoJG*kNw+-S!PLhT`4m$!`~&o()otHzb^09c{c@ssHUo_ z@@&;`I{gb@ZZr|25d48npNVCx7TDVd)I4_wTv_e5m}sp!eih~^FhkT9=K;3pS~)>l z)iI&2JO#WFcJLrVHHJuwLS~L0M96s#x?i8PJNCxXEC;TF#PdHcCc6gfBMiow6#HPG zS2+7h9hTG%~b`zrNjU$Z{w8GkRpHqQRh z*jQLh*Sk}hmjDmJ#@@6S^WvbEO`C>N!f}v&Gs@7xw=5NA|7Je8=If(yW=O<6b~G<9SLgjhd&B^^>_5 zwggCz!Y3063&&V8ab3H<5o45a9uTpVCvN_IJhm8 zKtvxIMo!xG8wUqv;l!{Va1{~09Ue|ZmqXZVXs?51&De;kcsXkRPW`BknG27&s38^= za2lPX&Yz8%_OyWUrgpc5y+%uT7+M{ZV*~=U>ghl}kMYf@(%uzX%Q~eF@-f&>S6Y@< z!x}n5uBQ$u6!3h(tZ~2cPAbmOJ)a4chPE1?vZe|K2Hu69h+DZ4Wa9WNVr!-k96sVX z-@kMtr6lC{#c6o+&@V2!_@UYF*o+S-?Qpitl~IGW3klc-PwiO@>`hkXZ!hu4$kzj` z$p}jpa%kA+ahPERa`@IGs2edH3Y%0x#k{EMxLyq4>UprU7gcFPa(Fj6E%1VBdL3gd z*Z`m>K&j$CDXEw=t?m^AEBiAl6CA4CPkgGJ-DEh;G(e2lTzE)-F5Lq5CM0)m3uap% z6lMT!AtDLEkj_Msp>V`zx%vTa$7o>&#>|Na?%r;9S`%KzyRO#r)==R0lkst7Hk%a{ z_DVKCm4~ceQuWti|CIq`A~En485;HSUIn3kxq5lU9?bk>V(Je1Oc$ki{dvJ@*Y?H28R)6Dt%ouC9b7p<^b#aMRVl`6XMTEjK(N&jQ*xv$E4clyeKz% zBzBxu&>s{`?`{<*gm&@8ky;_QWd8rv*H1|g-->;*bzlJa*^xT`;`lRL^uccF2b@s0 zSSh&NE8?-lJqrO+)2u>J7t7iV^u(f5AzuODfXx&V&euBu*&Xd4L_}lvGenExV|y<@ z5*r#cUZ|4g37ifC*~yB_b`e2d!pb;>6BRaPo2zYH-r#76;=Q9HBdJ*q2deGc!zoZ{hg(|oI zJsI^vE5bjCQ{?SAmG?||P6b=S_X5%jR_u5;Yo8#hOIovK>~X6?&`mkh6d?nJps~N)68l@oGi{Za@tFR z%H{j$q>x#gMD?}T#a>Sw@)1N}-&}ERSicDyu06bIb*dCj=*zC>Dxv_XU!Tk~kBk5L z)$_b)g>$!U*{8(g+H*Hy4bQ&0*sa$4VCGpP^nC|=#H<#RoNui)EQ1ktLb4B1rLd)E zjP;;ap`Lv@SfXI!`IJIjBm94rv|TWDZ7>i?=%_%|rz0^~8N5 zZHC<V0AC7mWqThe20)Hi>L^5O)Kx><(~_@m)jB5+)i>#m>!>#zEU*`Gf} zyC3w#_ZX?oneyUmvFE$0F`^1;$cU-~+~r)OLFyejtJbqS;)#)Dp$uLKS8b0fV2g8K z6_jQJwHIjx-IH^Dj!kGSD5Z}jWd*buTn*rX&zl6KNh_*2bNAQS-3b|9+-vn}G91Ro}ht-^ju zaF--g#ujXlX#+7#6B4~pL=kIN6gP!F51c!evLGymcSlH`z^uYnN^~`#&}B$^qEaDF#2wp~lr(~U4K{mG6;onz_bg6ZgJE5f;JWqNHe<5I)>@-K8r zXz=zpi#^%sh>Q_Op`O;4DtnCaS;TKTgZPw;vTxl`duP&RHNe-M!;d+OjLfoYbkFYoj@z z7~|4nHqnR1tOeJe6>bJttuS)xcc{wsvp&De=ge;7j0ihze30_G_ZRE6V&aPrzJ%R` zy<`unyXNe_xeOiHPCyVI(wbVv-MpfXLf%c_U$?=r@X*4zf`TLtiQS2`;!p8}K%e-jMqx18H?ym%rEdodrIjflxGh^gqwnN+$_ zMv^_gNRs-RyH??IzZMm8O8dT=P+{^=l;Q4HpAE7bmWJvTSPXf-o=|DHIz`n%oXqP> z-LFUSoDLQ7IY-(?c&oIOv1zkFHphr6AR{yoW2_n-LMNl!l4;J18Q(eX{~SeaZe2Z$ zT|0wj~Cw) zoPnv3bvv0jlnDl{gyoB@Ah(?U_Fk_58yB~uCQo6~7IyB5R#YK}7WV>HwG^Pn2tLC% zU$+^XZci1F4(SV13B3_+%bF^sUJNlHA$>;kw{>dENhff%NhS^F5Pf6YD*;&3lI=FY z;)9$ZP{sJB9LiB*0M0orY%jhcOi7!Fs5Ml1GB$urk_^w?F1$wHe65C;*Xybf-GaO( zkzm-{gvZo*kO!=#)#McXU?A4UB6C3KtJhdjw~R9u!vs!|0iMG4>%%^#TLzq_b8G>8 zL|{hi<3MFIl~clEu*j{b&2@nJX6k(I&&Va-`m^_0c%`)MuM^Sfg#GP_yTla+1A!yQ zCk|5QGS*SY74}ElIctLx;NC8*AA^6mPUGW}BGYSvO`jXtmUN`Yk$zdfC8iXbCQtSy z`dDB>%4GA4`Xfr9sXdxCeSqk8z0D_Lr9tqD&|Iq$^N3V0U&$NHHUxUUfj%R@KA;Qa zPdBmV&`X)2j4vR|U}f%I{Rv@S@2%XPTnvt|+>Jqo<_>fObW^eWiA_sm#?L6>tNhc+7WCa(UV5B$aALJ+c9n9PHWLU(>k_N{SvwpQr_!JKWS zWTLFkxh=*F39^=0lWIX@g}crs{TA-pAph6JBz2oWTlO5yT){a%cP6aA>8ug9mBYb> zCwahG7(pfmaU*In)43^KYuX9_Qh;7H+xV9uJBpM0lP*SykxNV#`i6lH*J^CQMfp?5 zA^S^6KD8$w{)7q7&kqHuKeo%)Qg?!&n+qB})rEt`DM=t$XKZ|LyuT){Th;m*%OR{Ko+;e??IHZOS9`+isDZP%gC#XDPV)(?D^ZQ#hz#cxhI08CTLJSL2&@_)f zc4zE$5OB69tPY0mKE?@+B-~`8ettK-{meVdopS2z?m*I9@z?_hgjjZ^gtLCCr){+8 zlgf2&kSCtuJD-`JD_Z%^c~#tta-J?b^i06!s4_nrC!|u;dn_lc(1aXCP;IAFW#w5n zTlE?146gO0w{B!4j7S!}0W`SZsA9f7UAg~|Li03#$QC9&CdBZU$B@>SZrU8Mxf=Vk z$SPol&e`x)P>R#wOFM-?_wX5^E%J+rGCkTi}Iy}bR8$9WP{rHIH?4?l*tcUj!vhSQ?C!OPDgl`cv4)gVs$nFqs%FFQALYUIsgWG%4Wd5+2W- z6jA7HC%M-kzyQ{iZ)%wj(Z`( zbkc0_6eQO7jgAaJsGFJE(q`nhFoDD!Lkq0#nf_yvx(V+&hiVKpX zbtf&;!Cle!mWGXMImkA;sB=a{)4&h6Vcwy_|Arg&g9Kz@F5y&uG|FEvwz84(VyLPwT3eVo}&5qqW^1klue% zO&sR-!k`YOY$>=2-#V;@G4kkq#=>HGy>Xbbh~T0VzQUzV>HG-^tP+~@o_et@9n_!GP+6V}Zes`GLoOeo-7;V*mBc?Sm0-+kd_5o4Y}(5p^!_(W8A>SsurcM#DRKa}v&L_=ovk2RawbI=^ zV`3Z$X&s5Pq7~b0&GmP|UIM_vxt;RnF!EVh3CDx`TM(E?d z%M#6DyN!zG8CV*44$_9nZ9wu8*m@Kfh`f6@Rrgl>&2gEC46fxvUrPhqOY!&pDApn+ z3-2kW*-%ddFjC%)bA8qaNFFKmxlTk&0Ph`DmOJ7~nKuZda>Pq9aZ%rR#N?RuG z_QQ%sxN!%%Gq6|DMIb2KHwbfih%u$?;)ieAFgBhy8t2Sqofdw)0-T^en6s2eyoF^9 zCSD2Y62RVn(H>hU-q)cRw1msRv;e3GD-7 z*6VyZVT}bGhep-CCWY-a+(yD>d;dH6?9@v^Pd_FPR)P$MvxsO*fefeDcS$RaoD=HzNQE<#DS1ByZr5M$YxLWx z^gFwd=ce2yd9T=7&?x3-`NhgXEO$_7`|F_%2G#=S)<@DAPK#1{(q9GxP$WBd2-{_j zO8cR_ZulpW!Qpq_=*F}`MVqJnT_Oo9i4(Ws!gNO)EEmY)^FwH+JYlV>GO5;c<-Xd67)FzfXk-F*u+RFo$ztW=P?- zDkR=bm*|Dw#OXWeKbOr0@`C2=&ZOXHpRVJ)J#JLC*G#RH_t*9;JCn9-dn_Y= zd-&#-!p`&j-nZ)_ehe@bXxEzL5!uu8i5?AGq0HCYbXO!<9lr~;mvS#gPRRQEYW74f zP{{4Zyw_ZCMe8gTg2VS)xvazn-X)ydq!wSk4+n`Gm#`m%rr_>32xJHUHP!MHkQ}mnTDcSwF%dD#z3&Gs;rM5Et9NaE_ zMvE`y7MbgGRx9lJ^z$eDjSi$#HR?%VABZoV^2Y~Qr_QGP6>c&|CA*8&VwqXZH4bX) zqTugj>eh@uK9Cf9T^bLr-DZ#pId`N9_5qRMJH zKMGI&oit%Ol-VREQD}~c^n(c$ETyllyyhROYkI%yS-C-Xtp!y)?jG-IcEdcNGQ_0y zM z-FAQ%?w2}?!ltg5IEuw?1ByvP>{bt?>Z09sVk!zIad6EJHMmZq|E`W&YgwZDe5$ct zO8h4-m(aBX)ecolhc2&;-?uwy39^>BgVp075-g6p(B~#4`XC{rH}odg`_cCDFqDq` z`MTlvpX-aUCXFw5_1b>?%qtsNIwYpMf!yFVdn2oQ*D>7yVC%mFWdfdTG@^}4p5xMxa>bl&0PRPqU z&5WJl7Z-InkfG=NMC*-|PSrJoo3NY46qS??L~3+nEiaE^N--P*5(ZL5QxAEBC)IhY zkSh+(Y$c0fAoAp6W5yAwhZ`zIM4MbP?3^ef`Yw?UZiw}4x}Z_-$JX(1p{0^NcNpyv zZV#C#TwGu%#j_PLgzQ3)usx(b($seVPr(>*8Qm$o(KP#J0LdM}1fp~ZTO-q%6=ngLs*5;-FWEQT}e4a6tU0_H#ZF;@$xQyfxnC$|83P?i&Rsc7jhk|mKN zb5d%!siz3E%*pKGq3rF(q=wkLoC$q+ypAv~w+(wTQYu5Ia3it%$6rPna^S2D06n^< zQ16+jID8BHi11)>P=ZI@*U-=t8fJwXWlQebme$aI@@U1Ng=ti0F`@8iU@P%U3LH1r zB*nDPP6O?d`p|eT9AQ)9EcFo^tT`SHYae&&_=>43GR|AR_1Gp0S>hi9aS@r-05E(d zK~ZryfaGuDud$}|`a-zB9dWgN`19<9DN|mRY;7!!8Yl0x7P=hH4ZJUc~#H8;%R3e)G+gnPS~gT_tBx`;Xd<=IS8m^5b8*Y7|u8w`}ZDF|mKBqK&+z{ZCoEg7Q3Sw^@%AvZg> zTJg|pE*qf_?f}b%gyqP*t+(dB8uVCX$0Q*sd8N=;tS|VT*GTdMW3ta~HHT~@S-S#> zVxgRGC>m7{eomN34*?ChE_+CiZmX6}B{VFhB5=RYPb~73vb*n`Jv625y2_fnWCxc% zLa2FU@aY&?Vk^||-VlP7W$<;&t=?oXfa2e=6_o0a$C~$s?P`zO-kPG`Qg~c{Bt9qD zasUzaW9bA^SS-fqg`-*upOcuFp>EmGXOP}sim}+16V{H)i*%qN(IaY0zfH(Y^7N25 zg2>@s4Mpajx6I9wsHF-4#>-^Jd8@Kf0*w|no^t?f(bmcfFzhFH&*ya_ei&-FMl81> z%FFBu=0ci;M2l8F+z2LiMinU&aT?)AtGjwph8qnmu-_ENyg7}jFnWf_wDZBk)H)-E zbGV!Z=3p*r)f`J$z;}ua(#W7(miN7z2XQPZ@EX!psU!Z%Y$-1WB~E3w8-oOreqs5T z?MNGpGRpPA$ab z%~)?CMRt{LG8$^q#Y(GOD*gvMZ*+NXo4JoT7Y(~H#VHOM6>b~(B_RXL4|vGq|wb_brlgf#iey4bpy$;)q0R_9VeBqZGJ*l@>h67x3pt6C@@4 zyahrd5B5EXfbR{CLZWcn(&~@+7DzM$uyq07()cc&{tDD4GV=6lBO&N%GJ2}lWf?t< z`@8l`D(%2!50tODUQDg+Yor$i2qC=k1c?4Oo?TViEh2;4xVv;Yp=gcYgm82pzm3!FFtcB z=aRZ|!*~gG<5J|QyLjCViC2`S*Wicxa?rn~X8DEx6kPm*cZD31t*VBOljYZ1=4ogH|Fx8o?I(E8^o!{ccD4SE5H|LRl_axo#RBy30qk=xT zQsC2ceS1t1V2C&BR8!5qRItYpKnp^s@OcyyLfZ<*CLbLU?stta@tK+2PS=W*_Kjgj zZ^Yi4=;?TOotAycD^*)MXL!i$jmYGO&_NTim#K5l@|O2aMJ)IL^=&>?`-ijdaPLh~ zTCq;rBO4}Cs{22V=V14#_(}I+3w2P(^dCu$NRRR4kB=zklA6NR+X=g}cS7;1`H;na z<1cEnBMd}yV)AB$vjp4|Jh>5%)XEl^Jkr!Vx{dRM0jJ>yjZgQ&7g@0LDnAV zd1^#FBH->X3R&l>2P|T|pL~(?XmO4+&8oNV$j}(jJ|7U;<@SXy%kA(@K;dD6)e>|b zt@vS>RfOx0n3Og@XZiqo6vYPNR2IL!VtN_avv&|N+l|b|3fiTAY{DaHz1PQN1HF9s z{YF{FXhUJ8yxqQEr$}9LAt;^h6&bI?#aQWI)HLx%^}Gp>^d7IRgWKwn{>rOvwkzZT z_FDDTTTSridH65c#5kJwG)$RXE{XS%w|!=TVB_G7)YQ!*ddzCaCZ6_&X8$vH3cl1j9`cHtA5XDenfsrZb*`CoT3Cw?Y8P25mci>n`e?e$@O-{ z?%=$$A&j zf7H!{E?7jVQo)=+2E6f*vg{smq>XQXJT;h<=v>bM8MmOYHRxKMe>ohT7U{M@w??-7 zGXou0!x8Z+keJfK`D)Gl^~oe%Le$Lj7$(EwHO)&lz^w|Ub`GXZv#q~};OkLC6j36rm!CdfHw&*`Kan*nY&~kWgq|N9X$Q@Gkra_( zzn!z)3*(z52WoQ8Fq=Y4z+qY@4IY18KCbzvbMP+@&(~p`kQ68~sFOmJOFVcDRHi%+ z;V-qc2?6n8j0hrrh<}Of>sg+s#myrNAd`rIs89*Xb{0ys9-png4ZX3oKuI6sqz2P; zeiF!u*Dc5x^RpbEsXLH28sB58Hz#s%@q$)uGLZ`4s{0YvlHNwFQ;A9CBVx1dvXIsk zHij}GnJ%I0G4>|$ECWT(3~bKCqECZhM`-J-Oomtze2gFg5D5v$)>2-UO_F!8>NJMl zfy+D!RDT(wIZ=agj0n^ttIme`*}lyKRAnE$=E-0!A7f=1;-mg&@uZH-UDY7qH!USm zuD?vn>x?38NA&XoT1WV&`A1nIk4h_$%7*P}UupfT1MpW%Dan>Q(k*>Ul71lHo z3W!*hdORSue=Q^U@kj|fif>^vQ=0Ct2C>c*r{1Az>3v?!l&`@n=3XkR1n3S`i;rrNt8V3xuE90yL)(+n2LDYEakXx++15OPBK z8|#2G47{1dGkJqU7aPk81>%jgyn6ghD4sxaI$7q>98f$zn7EaLp$G7qrz6W8Ze^q= z#O_<3r1vQ$R8TU+ybruvSL(*!4Yfpxg~K_an1{FTWvNcsO@$xEQX^wZnSc(DF{igcrNsuX$KS#*G&&mX+OnLT~Ez!F$)lZhp zS|6yfEe}f3OJ)bcGd@ONfz(^bzNh#6X61Uh&VFh3**z^tApVbC|JJm0HyRIlrpym9oSPL?F4IL`lRqy$)Eg`tvN_d;!Y>*KZd^~1HoJ8SVg6&So)HtA&b~lT^;o0;Jj?VhjoO{`ij%>pn1d1 zab3Psl2~G?%Y1x5Jz_Edh62f^frKjp<<(H^{h#mkoD^5?9mAP^17#wW<%kR@5!W*|dKdFzj2%UovZnV$n9= zje*dicGgPUNlRdBy($fxQzpc8S7ZZ9XKk-*!p>}jbW=n|S^l#q<_PK@kJ&!yT;=?Q z2C(zKrZ9_#!uYpxeRNSR0TI($g+t^n?}Xwbyq*v`SZSz#b6hK-*^64)AL!b;og@8C zUhcwf@)8KbUAlLXzyrFKU1L5n@!j}u9t&wMjzbL4$rO!d44x)zEr_xcGnvN&WO*>V z0_&fF=l&mMU{!MlmN(`=3&St+kB`-Gvm*;t#l9mGzZ<{*u~6F7!t|kyMBOMXa$H`0 zPWr)z`s_;54anEmyFFozI#}K-IJiv)+`@>lUGN8V_amS7S0H(y>GOwy;Tube6yS1v zV0g&e^^h{U{h7o&P5b}N$=)JDwS_63nBt~StFfHu72pP@?PNl5P?vhoHnM_a)1LrS1nueUZ64uGww`lERH)bVQrU=gsx z;BVy9MPOHg_LTwJS0kP8<;L(2`Hme2op#*j^3sV?2(CaLQ0gsv@jfnFO={nBefx-p zwN*UQjj-#~}<2>#cPA0LBTZak=-5rtoN@=GJe&+{3o!L>+3)J_`>e zV!tVhxJFPK_&jRagBYU8wRE&NuQKu~*`8cpK`|f^M7J4@ifV`$5j(lx24rBqANwSh zJXBc*rf!|MIQLq=Oi z%18c+*DvErMvcESp&v(<(p zha8QUXOn;wVmNPydl^A}9F`DYD%QOH!t@t5uL`xWJ`ym`H= zwsw5^1XHUxzw!SasoNp1{(S0q1^>l7H|Pcv*1#}WHh|igWOcT%boq0tndQ+!$`aV% zwS%#`cHWPjIw?08^mSOC<|Z1)OS=LOwGN?~rSc06DDNm5>jqn-|O zjQgVWzY$jctBH?TM=~TV5|=tdzYn$v%1%oQ#OkZ<`IV(*um3|7fXXeFrA$Z1E%dR2?b&XI3G;`jz!+p=N z*^3i{W8G5SK8$t2-8O%Nz51M_s%M2h=RQnVu0C1kDz!YT27L6_99=v1;^E&qUcZMP zT604ImVxYawt%Du?_K^}l$4G)ya3(Sb5Vlc<>pmAU)_qo>6I~mn$@kJo_%Q9XpOkB z@K0FIGOo_HHAbFBA$Q_n-MdQXLYkUd>e?t34r@+tOHiI3ETCsWNGQc}j{c|02Nv;@50 z$<#Q-sp7NlC_Amwy739_mG$LN7a~3SEvATDO_i|S?B7Nw6oS73;*U?Z>-U}qaswcS z@LnrFWk7_sDA*T`C=1^*6({0=QeU?3q53OQ*S_+O?=#2!TNb?i^Jc2J+g5bwje)Ja zMz(P)zhYXvZv~H@>m8}Es)Tm!6Drve|EUqT_|=XCad6k*sM^9AX%p=zl@6fy)PIz3 z_V){AQh%KUnI?wXyr8he2GT3Xkm37(ZYg@7;`?LzxG^fIERyxdbH5MT|KP3eO^i*R z)_p7xAbL?6PYyrs*G`NFZY=fLtw=f1(Z!twjdd9$cxFQWW*$FEG*DPrs7?8@iQbR)5DnD4MG-Wx* zdKM2meP&6kxoN{Z->Lh@&c-@8v1!3;*1T8e{g@`~H5|vymiw)aNG}p>(Z24r=W2^a7^!oCO+E2aAeLNo8Nfo%8<2V;H*NRQZ)XPmNlA_VQ)_N;*QWpYhViQ%Ug^Ua1i$uX$ItR&zc9^$@qX*Bc*hU^x38;>51J z$8v6H2JZMVYm{PUKq?NNjlY>8->1fXeGmCqDefcgsEC0ay$BuBIp1L4iWtoQzaP{M z$=Cp}9ETWv-j^b(#2ClQ zXZKrKro@)_D^Qlc6m=XkK0}<4{$&5oT;q-OWI=AamciiIyzv`wGj1XYAeM%U5fU9bsIHn(?3>wl z*2PimV%U4Miz@)G=6RH2>~&8^XK4nPa=s9ay~R;{aAfCSOh0X8|Nh^?r-Bznh3j&v zcqyz7IMeBM^?!e8cd92|D10GU=jO-K|X?pZhcrd6rllXXM?`C9!gtI0J`vmVok)|*e1Hts#*R&P8w+H?8$QuA`m>VQkgE7}SxK}aSE{>} z4yf~q45hk1xNyU%saP2K>YK_Xr0n?29H-Ad75OzPk-os$b;-kzwUG;@LuH>6gi-QD zes4j=(4!-`Xef@tNt|!Syv+`q;Hw~#iTcbn(#(z-a=O3{O#DQ<5M!Y9j?N2m{IE># zh1Tr**v0Z-l5wZuNtgB;l%K0g3XSvnx8tf+bH9!>pqX7k95OmBbU z_qp{W%rCUd(m&{c&P&=m+y)9O9&&$dFsUcGqnJo8{^tB3VyG7C@CU++~e{ zkHXXA^1jo?B^SAbNPj9Ftm-ex@ z3)}?* z6$Q)7ZGV_rJ7OvS#_mxY-5qt(sK3rK>yJgWm4uqMF@*jv?>;8g72ZVAl5S%?pUP$W z+)HMQx={0s{0%J3%k||L5c*_|I~vQEIni8HGsTHyz&IgSCCwh}#tMw3KRRtY7H|xG z19IbvVjz-uw*H!A@;O1X&FKK>C67{H#dJ}xQ)$zg@BysUrgbQsX(mv#JSn`g#|ayx znbae}(`&BS4AI$^1YBq*+%S^(gpyo9!vw{WLkI}#W3FO!_ewo0;?kLub66nA`d0LL$s8i zpFSQjCDO`$HSw-r{C4VZak9ucd~C{!X}L!}e-vLmF=fhs{rwb9nX)@vRb>kKTZLQs z8Cy1GiWX(QEBV(~KlZ1;ev|z2lqnAircC)~kbC!CR=nr!SEmVc{_TqcrPl=?04{&) z-YHZ5*+6FZT{67g?HB+1pPTXI@4v5j{TEYq@77MitN;Gr?z>*V6!rE?- Date: Fri, 8 Mar 2024 18:20:35 -0800 Subject: [PATCH 14/18] Updated README --- ada_feeding_perception/README.md | 32 +++++++++ .../food_on_fork_detection.py | 2 +- .../food_on_fork_detectors.py | 63 +++++++++++++----- .../food_on_fork_train_test.py | 38 ++++++++--- .../config/food_on_fork_detection.yaml | 4 +- .../distance_no_fof_detector_with_filters.npz | Bin 12255 -> 16801 bytes 6 files changed, 110 insertions(+), 29 deletions(-) diff --git a/ada_feeding_perception/README.md b/ada_feeding_perception/README.md index ad7e5aaf..6dcd37a1 100644 --- a/ada_feeding_perception/README.md +++ b/ada_feeding_perception/README.md @@ -91,3 +91,35 @@ Launch the web app along with all the other nodes (real or dummy) as documented - `offline.images` (list of strings, required): The paths, relative to `install/ada_feeding_perception/share/ada_feeding_perception`, to the images to test. - `offline.point_xs` (list of ints, required): The x-coordinates of the seed points. Must be the same length as `offline.images`. - `offline.point_ys` (list of ints, required): The y-coordinates of the seed points. Must be the same length as `offline.images`. + +## Food-on-Fork Detection + +Our eye-in-hand Food-on-Fork Detection node and training/testing infrastructure was designed to make it easy to substitute and compare other food-on-fork detectors. Below are instructions on how to do so. + +1. **Developing a new food-on-fork detector**: Create a subclass of `FoodOnForkDetector` that implements all of the abstractmethods. Note that as of now, a model does not have access to a real-time TF Buffer during test time; hence, **all transforms that the model relies on must be static**. +2. **Gather the dataset**: Because this node uses the eye-in-hand camera, it is sensitive to the relative pose between the camera and the fork. If you are using PRL's robot, [the dataset collected in early 2024](https://drive.google.com/drive/folders/1hNciBOmuHKd67Pw6oAvj_iN_rY1M8ZV0?usp=drive_link) may be sufficient. Otherwise, you should collect your own dataset: + 1. The dataset should consist of a series of ROS2 bags, each recording the following: (a) the aligned depth to color image topic; (b) the color image topic; (c) the camera info topic (we assume it is the same for both); and (d) the TF topic(s). + 2. We recorded three types of bags: (a) bags where the robot was going through the motions of feeding without food on the fork and without the fork nearing a person or plate; (b) the same as above but with food on the fork; and (c) bags where the robot was acquiring and feeding a bite to someone. We used the first two types of bags for training, and the third type of bag for evaluation. + 3. All ROS2 bags should be in the same directory, with a file `bags_metadata.csv` at the top-level of that directory. + 4. `bags_metadata.csv` contains the following columns: `rosbag_name` (str), `time_from_start` (float), `food_on_fork` (0/1), `arm_moving` (0/1). The file only needs rows for timestamps when one or both of the latter columns change; for intermediate timestamps, it is assumed that they stay the same. + 5. To generate `bags_metadata.csv`, we recommend launching RVIZ, adding your depth and/or RGB image topic, and playing back the bag. e.g., + 1. `ros2 run rviz2 rviz2 --ros-args -p use_sim_time:=true` + 2. `ros2 bag play 2024_03_01_two_bites_3 --clock` + 3. Pause and play the rosbag script when food foes on/off the fork, and when the arm starts/stops moving, and populate `bags_metadata.csv` accordingly (elapsed time since bag start should be visible at the bottom of RVIZ2). +3. **Train/test the model on offline data**: We provide a flexible Python script, `food_on_fork_train_test.py`, to train, test, and/or compare one-or-more food-on-fork models. To use it, first ensure you have built and sourced your workspace, and you are in the directory that contains the script (e.g., `cd ~/colcon_ws/src/ada_feeding/ada_feeding_perception/ada_feeding_perception`). To enable flexible use, the script has **many** command-line arguments; we recommend you read their descriptions with `python3 food_on_fork_train_test.py -h`. For reference, we include the command we used to train our model below: + ``` + python3 food_on_fork_train_test.py --model-classes '{"distance_no_fof_detector_with_filters": "ada_feeding_perception.food_on_fork_detectors.FoodOnForkDistanceToNoFOFDetector"}' --model-kwargs '{"distance_no_fof_detector_with_filters": {"camera_matrix": [614.5933227539062, 0.0, 312.1358947753906, 0.0, 614.6914672851562, 223.70831298828125, 0.0, 0.0, 1.0], "min_distance": 0.001}}' --lower-thresh 0.25 --upper-thresh 0.75 --train-set-size 0.5 --crop-top-left 344 272 --crop-bottom-right 408 336 --depth-min-mm 310 --depth-max-mm 340 --rosbags-select 2024_03_01_no_fof 2024_03_01_no_fof_1 2024_03_01_no_fof_2 2024_03_01_no_fof_3 2024_03_01_no_fof_4 2024_03_01_fof_cantaloupe_1 2024_03_01_fof_cantaloupe_2 2024_03_01_fof_cantaloupe_3 2024_03_01_fof_strawberry_1 2024_03_01_fof_strawberry_2 2024_03_01_fof_strawberry_3 2024_02_29_no_fof 2024_02_29_fof_cantaloupe 2024_02_29_fof_strawberry --seed 42 --temporal-window-size 5 --spatial-num-pixels 10 + ``` +Note that we trained our model on data where the fork either had or didn't have food the whole time, and didn't near any objects (e.g., the plate or the user's mouth). (Also, note that not all the above ROS2 bags are necessary; we've trained accurate detectors with half of them.) We then did an offline evaluation of the model on bags of actual feeding data: + ``` + python3 food_on_fork_train_test.py --model-classes '{"distance_no_fof_detector_with_filters": "ada_feeding_perception.food_on_fork_detectors.FoodOnForkDistanceToNoFOFDetector"}' --model-kwargs '{"distance_no_fof_detector_with_filters": {"camera_matrix": [614.5933227539062, 0.0, 312.1358947753906, 0.0, 614.6914672851562, 223.70831298828125, 0.0, 0.0, 1.0], "min_distance": 0.001}}' --lower-thresh 0.25 --upper-thresh 0.75 --train-set-size 0.5 --crop-top-left 308 248 --crop-bottom-right 436 332 --depth-min-mm 310 --depth-max-mm 340 --rosbags-select 2024_03_01_two_bites 2024_03_01_two_bites_2 2024_03_01_two_bites_3 2024_02_29_two_bites --seed 42 --temporal-window-size 5 --spatial-num-pixels 10 --no-train + ``` +4. **Test the model on online data**: First, copy the parameters you used when training your model, as well as the filename of the saved model, to `config/food_on_fork_detection.yaml`. Re-build and source your workspace. + 1. **Live Robot**: + 1. Launch the robot as usual; the `ada_feeding_perception`launchfile will launch food-on-fork detection. + 2. Toggle food-on-fork detection on: `ros2 service call /toggle_food_on_fork_detection std_srvs/srv/SetBool "{data: true}"` + 3. Echo the output of food-on-fork detection: `ros2 topic echo /food_on_fork_detection` + 2. **ROS2 bag data**: + 1. Launch perception: `ros2 launch ada_feeding_perception ada_feeding_perception.launch.py` + 2. Toggle food-on-fork detection on and echo the output of food-on-fork detection, as documented above. + 4. Launch RVIZ and play back a ROS2 bag, as documented above. diff --git a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py index 58ddb01b..6b156a07 100644 --- a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py +++ b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py @@ -631,7 +631,7 @@ def run(self) -> None: try: proba, status = self.model.predict_proba(X) proba = proba[0] - status = status[0] + status = int(status[0]) food_on_fork_detection_msg.probability = proba food_on_fork_detection_msg.status = status if status == FoodOnForkDetection.SUCCESS: diff --git a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py index 44744e45..33d85e39 100644 --- a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py +++ b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py @@ -563,9 +563,10 @@ def predict_proba( statuses = [] # Get the prediction per image. - print_every_n = 50 - for i, img in enumerate(X): - if self.verbose and i % print_every_n == 0: + if self.verbose: + inference_times = [] + for _, img in enumerate(X): + if self.verbose: start_time = time.time() # Convert the image to a pointcloud @@ -589,16 +590,47 @@ def predict_proba( proba = self.clf.predict_proba(np.array([[distance]]))[0, 1] probas.append(proba) statuses.append(FoodOnForkDetection.SUCCESS) - if self.verbose and i % print_every_n == 0: - print( - f"Predicted on pointcloud {i}/{X.shape[0]} in " - f"{time.time() - start_time} seconds" - ) + if self.verbose: + inference_times.append(time.time() - start_time) else: probas.append(np.nan) statuses.append(FoodOnForkDetection.ERROR_TOO_FEW_POINTS) + if self.verbose: + print( + f"Inference Time: min {np.min(inference_times)}, max {np.max(inference_times)}, " + f"mean {np.mean(inference_times)}, 25th percentile {np.percentile(inference_times, 25)}, " + f"50th percentile {np.percentile(inference_times, 50)}, " + f"75th percentile {np.percentile(inference_times, 75)}." + ) + + return np.array(probas), np.array(statuses, dtype=int) - return np.array(probas), np.array(statuses) + @override + def predict( + self, + X: npt.NDArray, + lower_thresh: float, + upper_thresh: float, + proba: Optional[npt.NDArray] = None, + statuses: Optional[npt.NDArray[int]] = None, + ) -> Tuple[npt.NDArray[int], npt.NDArray[int]]: + # pylint: disable=too-many-arguments + # These many are fine. + if proba is None or statuses is None: + proba, statuses = self.predict_proba(X) + return ( + np.where( + (proba < lower_thresh) + | (statuses == FoodOnForkDetection.ERROR_TOO_FEW_POINTS), + FoodOnForkLabel.NO_FOOD.value, + np.where( + proba > upper_thresh, + FoodOnForkLabel.FOOD.value, + FoodOnForkLabel.UNSURE.value, + ), + ), + statuses, + ) @override def visualize_img(self, img: npt.NDArray) -> None: @@ -619,6 +651,7 @@ def visualize_img(self, img: npt.NDArray) -> None: labels = ["Test"] if self.no_fof_points is not None: + print(f"Visualizing the {self.no_fof_points.shape[0]} stored no FoF points") pointclouds.append(self.no_fof_points) colors.append([1, 0, 0]) sizes.append(5) @@ -626,10 +659,10 @@ def visualize_img(self, img: npt.NDArray) -> None: labels.append("Train") show_3d_scatterplot( - pointclouds, - colors, - sizes, - markerstyles, - labels, - title="Img vs. Stored No FoF Points", + pointclouds[1:], + colors[1:], + sizes[1:], + markerstyles[1:], + labels[1:], + title="Stored No FoF Points", ) diff --git a/ada_feeding_perception/ada_feeding_perception/food_on_fork_train_test.py b/ada_feeding_perception/ada_feeding_perception/food_on_fork_train_test.py index 42ac52a5..0104de12 100644 --- a/ada_feeding_perception/ada_feeding_perception/food_on_fork_train_test.py +++ b/ada_feeding_perception/ada_feeding_perception/food_on_fork_train_test.py @@ -444,7 +444,7 @@ def load_data( x1, y1 = crop_bottom_right fof_color = (0, 255, 0) no_fof_color = (255, 0, 0) - color = fof_color if len(y) == 0 or y[-1] == 1 else no_fof_color + color = fof_color if j == 0 or y[j - 1] == 1 else no_fof_color img = cv2.rectangle(img, (x0, y0), (x1, y1), color, 2) img = cv2.circle( img, ((x0 + x1) // 2, (y0 + y1) // 2), 5, color, -1 @@ -588,11 +588,17 @@ def evaluate_models( absolute_model_dir = os.path.join(os.path.dirname(__file__), model_dir) absolute_output_dir = os.path.join(os.path.dirname(__file__), output_dir) + # Create the output dir if it does not exist + if not os.path.exists(absolute_output_dir): + os.makedirs(absolute_output_dir) + print(f"Created output directory {absolute_output_dir}.") + results_df = [] results_df_columns = [ "model_id", "y_true", "y_pred_proba", + "y_pred_statuses", "y_pred", "seed", "dataset", @@ -614,14 +620,24 @@ def evaluate_models( if max_eval_n is not None: X = X[:max_eval_n] y = y[:max_eval_n] - print(f"Evaluating model {model_id} on {label} dataset...", end="") - y_pred_proba = model.predict_proba(X) - y_pred = model.predict(X, lower_thresh, upper_thresh, y_pred_proba) + print(f"Evaluating model {model_id} on {label} dataset...") + y_pred_proba, y_pred_statuses = model.predict_proba(X) + y_pred, _ = model.predict( + X, lower_thresh, upper_thresh, y_pred_proba, y_pred_statuses + ) for i in range(y_pred_proba.shape[0]): results_df.append( - [model_id, y[i], y_pred_proba[i], y_pred[i], model.seed, label] + [ + model_id, + y[i], + y_pred_proba[i], + y_pred_statuses[i], + y_pred[i], + model.seed, + label, + ] ) - print("Done.") + print("Done evaluating model.") if viz: # Visualize all images where the model was wrong @@ -675,7 +691,7 @@ def main() -> None: # Load the dataset print("*" * 80) - print(f"Timestamp: {time.strftime('%Y_%m_%d_%H_%M_%S')}") + print(f"Timestamp: {time.strftime('%Y-%m-%d %H:%M:%S')}") X, y, camera_info = load_data( args.data_dir, args.depth_topic, @@ -695,7 +711,7 @@ def main() -> None: # Do a train-test split of the dataset print("*" * 80) - print(f"Timestamp: {time.strftime('%Y_%m_%d_%H_%M_%S')}") + print(f"Timestamp: {time.strftime('%Y-%m-%d %H:%M:%S')}") print("Splitting the dataset...") if args.seed is None: seed = int(time.time()) @@ -708,7 +724,7 @@ def main() -> None: # Load the models print("*" * 80) - print(f"Timestamp: {time.strftime('%Y_%m_%d_%H_%M_%S')}") + print(f"Timestamp: {time.strftime('%Y-%m-%d %H:%M:%S')}") models = load_models( args.model_classes, args.model_kwargs, @@ -722,12 +738,12 @@ def main() -> None: # Train the model if not args.no_train: print("*" * 80) - print(f"Timestamp: {time.strftime('%Y_%m_%d_%H_%M_%S')}") + print(f"Timestamp: {time.strftime('%Y-%m-%d %H:%M:%S')}") train_models(models, train_X, train_y, args.model_dir) # Evaluate the model print("*" * 80) - print(f"Timestamp: {time.strftime('%Y_%m_%d_%H_%M_%S')}") + print(f"Timestamp: {time.strftime('%Y-%m-%d %H:%M:%S')}") evaluate_models( models, train_X, diff --git a/ada_feeding_perception/config/food_on_fork_detection.yaml b/ada_feeding_perception/config/food_on_fork_detection.yaml index 49275769..2a86fac6 100644 --- a/ada_feeding_perception/config/food_on_fork_detection.yaml +++ b/ada_feeding_perception/config/food_on_fork_detection.yaml @@ -30,5 +30,5 @@ food_on_fork_detection: # Whether to visualize the output of the detector viz: True # The upper and lower thresholds for the visualization to say there is(n't) food-on-fork - viz_lower_thresh: 0.5 - viz_upper_thresh: 0.5 \ No newline at end of file + viz_lower_thresh: 0.25 + viz_upper_thresh: 0.75 \ No newline at end of file diff --git a/ada_feeding_perception/model/distance_no_fof_detector_with_filters.npz b/ada_feeding_perception/model/distance_no_fof_detector_with_filters.npz index 99b0ced3923cc7ff0585e7a19faac5339e41d9a3..ba4cbe12d3a248767fb4196c36ac332d5d0c61b0 100644 GIT binary patch literal 16801 zcmZ{M2|QF^_;;IBie#${DwSm4jb&7dN=TBjj3k7tV>e6brx6*IWUP}^l&wea>8V*t$)A)22;3 z#QWh*;K-u)tJa$~Et5BGlHDY~DJz}%vPW6j^|EEI z@`ElRs{Xrx%CfN`Kklu;)DR~^dQFD^SV{tS0}PKNu;(~0Jb_L=`n|pH)8DwcmpWbR z)vhe?8dq#^%(d(q?2Y7#Ru?2-19P}uxovu-y3?ziryE10)xtKKeO_`d0#?vF(w(ur{2g^p&ldVMNiyH zeE?qmS?!p45%*;5XQ($}Hf4Lus4#ln%ct{1UB@y5LMEkXDm3GjI=e0>^xxlkE_vwA zHb!GN{NAE&$>eY37k{F#ZaAp=wiM!soZhvc{Jgzy`Tb_X_}eLo1yPJ&Au2ULcAx~ei^B5}ol9?8 zE=q+vin5S{WE;ozgH6UJmzJ#`{o*|bzm;tYX}dx^E-`&E-7f(-evbNf1zR57z31>G51_&QdUnD)7dUJ7YCy`vIiY6!CMA7d9 zt0XBVDmIJr2IGg=BQ?U%*xMIDHAPW^xr-%}nDw*ZcR$R|C&b=ye&^)SmdzQzI5tFd z#pM*+mQWW)<#n-26gC)5PVz-DQh@(nI@8`VT&H1>cvPs1CA~;u1ZgRzcaja3xVmaGLEA)TpB@9>G)$O*1!KrboK5oIrn3ai{>kptSqrp9FYI+FJ|TbbYu&&PRciYM8p8(S+a zRAl4;BqioO@Y7N|_Z?Rik0vGDfvG<~%0tnUE;+e*IGq^z=uAJxmr%RYTF&t+NSGm>)x~dV-Kf-!Gu(+CE`8yUd9(|+ue5MZyA=5@6}=sc>Swme zTpy#|hl9%|5o!l=8eUyN|2+Q1b5K|^7~|2Lc+={Nn|eGl#bKy#_s>-F0>C7Y$N%op zGW;Uf^8I{5rFq|n`C`kj(!)E!H9rPtTAhy}26Y?Jc&p|~$;8hzfu?5^@w8lXV3_HS zFtacRe%riVOQg4fny>2;dCJkZdk;yr&_3)kQLCh9;H7`0M~mdpL4U6idyV+p!p%I> z@n=oH)0Ys8qE|{#ZpwO~t<8D(@lO{%jr=-fUe(6I7Hx&K&BSy9hJD*>hHCA{FK0q5 z54TeZ?VCDifx+v?4qv&U58+wL9CLdVa^q|0(9csXg0=FZ+6k4Tb>UICEc(6&9V?AX z!AV-nL8+4=Qt=8AfMQubN2>M;r060zDP(c<2vF7pZzwi2ZN`j56B`3GBaVDLXhs81c@o`kda=HacJ}(07l zkS%|LT~5D7Ezglwe@RGV#6?P^-I>+8gCX8~N90iJ6L zM}s50L~@VkX1_aL!6|uBD@~(ezuLXWMWy4;3G)`)Pk4?=_tB{P-wc2Sv9uo^?=E)X z?gpCdKX@XZC)uUG(YI?K^vX;s*wI}=3JVYN=s`c(+amMFsq%+~?$u?Uf{&7AwDqOs zWX$vnx47XQV1C@w_90x%#b@xu`APqIZ0Mh+#J-t5i7n;QOGCeeAHiK0-i?LKn8uLO zltkASX8{i;NyK*exz7%-Ix|&jYH{hSJr%k2Vj0YD6W0G^;xs^>1b#FiB|J9vDEfrGZrVQv8D_M3O zi!78dCaj#!_zkpVuKH%(GHA29Gi@1DsKNDGh-fAH)XOO@H44Dbr?E8`i=X;m$^Kc& zD2htkvlj{-HWP>%_MeD9>viqoSk|Ey#Ai)lP}H>#ld%SaK1y0@C+mF30aEK`d*q-k zANm&pVoZ|VM+4?(<R|kA`x#C;R;{TtoHC<37(!NLSs= z_Y2R+Ja5i4CfwE1j#~L^*5RXr^XQy}v(qAsI~voxDx_lV-blWqYgf<2T?!AC2Mo8N zqv-f{;CnjmS25NA`%G-!H3F3#$MyZ|6Tu&OS{4$OtL{URZu5mk<{tGGi;x*6L;j7h z8J1u8VC%LGy?#*y-u8ZSPB51bpVB&=T)ltE?ZoVj50kk)<;K4RyJewor@k#G%(iXA z&~MKxUUN~eTjV#y*!2#a@cV>(0bO{#gcyNq^dtx#+2pEuXBp2^)VpBcWoTjMmF{_$ zMxe~+rQGHPP$R2z?ezAp>V%vM_|G!FMbhC@jSd3vN#{OLfB3x%%gsHCyS+;WPoTgZ zAlUE9D$(4FrC(Iz;ay-`pTxOT+%dHSap74k3_FW60~t-Gl|zY4FWc~A#fm@)7LQSd{T2w3mC#vHUnj4&65-9K!WB>#0_7rZjv55_p(^*|Y_vs&`NY1tuDQS~I~ zboEtwA!ymI5Z%O5>RyOEOwOJ$=q5iLzINdG!Tjyxku*S799Z4jr?<*|=meX=e*C-R z@H1r`LKId1@xtjs)%TyK?5D8E{2t6~{Y0mr#oF`w+)N8{356h$O|;h}Q} zt_3$`(_1&S=zLWqeF(FCIXT?@{Y{9;>E!TZyhI$`#?qM0v=A|t>q(}X@|C!{fho!X*GKdW5Ktt!{ z$}4jMzD292hyO-_ztAUSHApy2)CxNsYLw~Q@XV(Pq6z=3LY%}Sb6;Pe z2=_}zJQc&ddS?C{y}B%A@LdIyn6eW)5J2o=D;{i-m0V@2L>_{SVI+tdjci~_T{>`D zmy+6uCSzNOQe$RlJn=*Iv&n-;mdbU$HeVj9-lO0ZH<0wb?1O$wXqq5Kw0`D6U8c^v zNKxA(s9g(DTGu*o)FXo}7}B9%*Lq!WEdrCjGTdr=G+b0OpS^ZJaV3c;3cvmMmv@)C z1^>57+}M4kUN)(#h&TPUt9q*R$lRs6cs#iRP}pO=ps-foWCFtz=f(Mby$Sn$%wHdg_B5ao-sCO_S%y(`8aIK+z|!&r>TnnJpcx zO!GA0suWgw#VY`1l~Qfn{s!uOSl1s__Z&D4#!l=NEwk>ik-%v+N@m;(7VzhJjjFct z;l@zJ!kxVsnM-wFZ{B@4L-v4m&k2s79}~Ga&(MP%>o54_H$MfiOsec(O2@!^2DFBi z&r()eI7hZi_UTJWH^bH&&cM3?9L^`~TTKJxRq65km?n1)h7lUy=0j8M^f4zoV(Bhx z7yiN3RY`x|rFZAg?W=~$AbvvPL$3AP4e-?jh(gxn`eN|Lp0c35MAG*3YOH6Xn>w7) z|0}pqnr*${{!jlev@POhvpnax2>Zl-nJE>iiP4*mrKHl?8_9L${S_5;69{v>H$l?E zJn(yiU7-TR3t?PMcjz^~Vx`fFtJ91mgN*rm(j3wbIL*E|T2EgWJUC0O~RK4fE?OPmK8T^=G$GKY{$$j544=TYD zo9JVfJZ07%*QkQ8$4%E=#czg^nv|=)Bz{df96UNBeaIsvjlP*4h+-KbiAcn7ozr$N z9p-@F7&x*}UoXgl7f^GqY*ka!biUGQcG*QAnVAgaZzn`H8;CtyfKXEOt4%QzRuaWl zL$`^(0YKX*%UhQjTR0Ms0wqXA7Q+6zhFAcHx&W+|HmWm-tE!+oPbRpi1){j-kO6#d z38)Xiilmff8rj1Nfd5vhTECepeE&;m#Tbj~uI;-DTrVwrbBlUcN3fOf(dPeKTqH4t z%;mMo`gzEK7%-*G!O-6O8F2L$r87NO^vB|JSA(NP3tpQx8kS_zJZW#|F}iIjyXj2M zwOFq7_7>{!U48BOf*E(Fn=&FE?J{T0`Te>W>4xIB!te4fHiGR^`N?99r*!I}oyV8S zu5&>iEl3t99%yB|syd?k5CpbpaoLz*?}~AzNU`$vrBtV!ESCc#f$nb1gS34FPqk1Q z=k;qa(7@~~<+WmP!8QEi#|MG;X8iLdzLo|1@3j))+R{})M-%L>&*5zo4@w|aKl%CJ z|1^?yBt^9qkhlXvJ4`5cXH)Msk4GiF?$<(x8%%^Uo*v?)*nSPWZy$Zc`D|eda9)W} zZ1dVm#oC4${kn{&Kb-ykz+kUad9=^O#y867eB!j?rKx{+i%3d(VVDIm6FNSaD1H^{fU9C zx5iqmSV#Emfo2Ct^$8a>U+Kb@@S+F372YmqB>kjS9s{E(4%S@2!lcr%=m1KYl$TDz z-J55lpO?A5e*HDUjaks(L=zFJ8{zqon0^fXa-hxl3gmg2p7`Io51ij&U{7agx*qWu zkgY>Kg588ypCReFJ7d5d;JQzw(hs#uWG3|wVAEY<(M85d(>W4 ziN5o3io?p4ZrCBGrHI6b4Mo>N3lDxtJPwTR2pA4nY#=M>M4zMdBha=YUlc4hFF$6T z9u`w*+c@U=H7VC_xyTH6`-@hE0@Rc8vC*44e-f+n4OV*xYpV%k@hW+|os_Bwn{!mk$LqqK~)NieE8B*~okzkQ!H~zuH*! zU3pgOypzlMSbKUIX@k-x!5yR4Y(J_d!%t9X$XlrYBl-jXRNZ-YebTLtHhK#cV~DrN z^(!QNbfSoj%UZ|>-8A?fN?Bw5a5_oR)Nz)E@I?ugD75^&_^w6gl}OOa$GF$sEfqKPVH;^Z7H=)=_UwjHk{PA=)wl`RqCZ8w^ zp}7!>YYdRY0+BA)lFg(sZc1DK1N+c#i?)^Vl}1=X*rU0mk*_}?SAsH@Q(9|@0BR51 zg|=w{`H%EBfW;=rn#2d^eZmCFGSSE$O9XI0kO6;miEbMpQDQjzrMo^7+#)`OuwzD$ zI}wIFnPQs{qP^U$5Sk2O3KD=g1nv7Pr7=bjc0q0%l>h+kTJJfXb5q(|Y}vmpl-Poa z0E_Lsk(V0!$RhE>Z-LB^2~*Cx*trXjq=SB(3A`zd+0N^KnWc|(Y6bk;ak0(cwjeXw zz6Hq#|2`($^S8}*k;ZUfahpC;x=q|AgtnhhtgMd=`vyp`fY5d>$mJjW*gBN(_1ec6 zWt%#??k^Ew=@EKgGe+PY->jB@x#M~mZw0BNz6#1D>)Q;sRxXa9_xi)|k6e_Ou5a(v0)QWdqh6AbK&~r0VKWXuB2DJ_N&D;- zRZY1EqM$G63uvDf08iHnWc{?Hp$Ukr8?01Q1I;C0Jd#lgZsJ4}4{UYxi_AxmEo+i9e z1(~u4M3Et?X$?kH7`u_5WN%|gbuY@F5vx)ZAcnam!JDOwGa1 zT?ID4Q#23LDXN)Bf14I1ZX%@M=Kyub5|a>#2*C9}+c!tjZQQ=IaM!R7#H*GN2^e}B z0ie8qO37O6!dBQ)~c z%2vu@ef&o2%2ucnK^7SS7JsoAm8DTaB$U#B%)IKJ^fwGXu}(&syJ@4>SCs4bA0^+% z=VX29ohMOme2X=)Pft3ZGz3PuoPDyd2^?g+csX*D0xfxsBX;IRf&`^NZ@AUifgC z{MMBp!vu~Ye;+?#jcJHF4NKN=5%JR9&jr^2wvs zV6`i59v-RtVmgSd?vpiFSVWgRwexPV2PzjG1kwupJA|C4UxYt*g#FQv7=NnY6$d;Z zQXROc#eQ~eN@7%Tc<0j9lL%hV=4YAlCVzrFlYH>IVL(ui0 zs|?s!ds@;UvwK{U!b|>ARbv;l4KdN*T9xGfpkJ*4bnt7!OTU->2O3xtpKst!o{wn1 zPbe zX~9i^9CkN5U{}rlnKMRrixi7tpF9Pstk734|8EDwRKF z)RbtOADOP}XJfxq9^0}F&o@JjMnX{{@lF*hQV#ZBzksGc(C^UkTMiIyUu zLIJoleiHce=02SLK+SLDqeMjrfiwwKi_sct*1<-q?ZD;%%Bz_m>uFK-f09epOrOG3fGd0JuA4xzW%bX9{5hN1RhZj!UI&fbCe( zx7se@DfZDD?*BMH145q>rjlkrjj^LPaR;vs95v_md~d{Y8b0Q{|J7Rijk^^pMKF+j z%sjp3Z-kV=Fi*D=D_l>z-&RrPbiT$=y{qC=s2xm@H3G-kcs^701rQuBGq@9USS$GE zZ0WO6k!xoXCLg>rlpX2W@jBwEx`{^>1iv8py=#^*i%7+m>Rb)PyLR3{xZ)NIOediP2>)c3%fC;>t0f@W>>#qVhr z#i537sKk-W7zRDvDovhcNVzVfCQ0{2vAoc0Z-X#ZE(riuW6i7v$0~IHvH3{Cluu~5 z1#YH&?1T%$?{9QU8XS8!()3Mzl_A!HC%_?B)+*{i`X@JOk~U;*3bZSp-^R-JusP#n z3R&whvd8I&JtZ7$O$-}d`|(N-4V*qgxlXO!UM)ARWS{_fncd5QDjiW&te}F74zo#Zp2p{2; z<(x2DuD{PW&)Mai|8z|a%<2*XsE%_62DifWA?=F<*;*rH^%a1Pd#%j%XHyDUWgur+ zqS6VNIf3K*c=?zio>>SiVh~)aXEyS!8fC9ca_(l8<@*(Fr*8_u-G+tvF+>=aD_r^& z_{Io(@iPC`AU?T4b+}|o-TF_Z*jQw?b?^fzWq}C_^bOee><9zm3n1ksydqM!)RD7e zC7~+47#>;b49!i?+u?${Debe3ejc53guh-7l0>EV!DWCZZ|+qL`w8`VL85mRmn<&- zJ{k=t%uZTZQXKT{$9k+Fr&koDlJYvN(z+np&m$`dN8sD3{DW|v;X+GiC7+v$kz1H0 zvT${qFQ(~D6%UC-ett8>XHzZYAp;N4euX$~R2@J7!8VD#e(J(o z`^-3!{NcZ_f*}R%IuQT)lb|Z@ELa#-b7eODOM|2)&Y70OW~6mCI&n|(jDFfnNL3ZO zPej~tOpR(j{jsa0ReiOp?Qt#3?=-@Lay+e92EILedQ0^zP`m2&q^(Cuw?F%=m){33edEW#ybsW?G+ke))yq6u4KDGBzdvHv@=+9L*6<}AC$izKhYhwK<|KdtaqJ*VJpwbDB15ASi;mMJR1p2N=BO+$maI|DW5w%KD$swH8)gpZ;zpG-ku*p%_l z#6QY~lM320*JuudRlV$;wY9^T^mea#n0_q$ViCIN1|b4M! z$+cDT%R}mpQBd3%!zT)n-C*k@soBAxN-gYDsMLmye~9^5X0w5y2g&_}OGqt6gZ>~I z&Xr9zZb#r)#bETLv)AWyneM|ogrNx1cC1~OOtr@!e^PWaTBd)NiDo&2&VwnVqeWkJ zzI3NAowIl6m8q7V9$w6H5a=YhW2C`miSygkiqMLmscAEP$6!KLvnzV+N1EPC&wT>+ z!UVK9tZ8RCwd&aM9}EJ3yAMKhApF1)0D>N|DEQjrPU1Z8HmGLIHk+iVDr7UcXj^fh zBgg=*nH8z+5KHb2f~IbE&(+J+zG6%YkXw>lVv{FUJ4$~w+BQ(!G!4it#HkX8Lpm3m zUy*XfSGgr(0j=zPAD;F}=iU5CnjR(5n46s2rq=?%PPeM|33z*4Gc)T0#gE{6#0aP! z|KXA#tT5S~e5$LkmYXM#E%ZF-Mtn(tf4pDBI?2H{TjCk%6F%tqnlIj|lU##c4 z5K7M!=8=5~_R|~}v|c-anS%Cn62rxfxh1;9NbUJmLbW0`vfAIE8Lg%8+<+C&cIpaz z>;G`DJali9_w+&1lO0_Kj8yU!g6yp#1R{Gb+j4(L)4Q3MJ4P2vkLkffn_@f8W-XuF zRyFtM^~|X(G%vb~3>C6I+8H3;eRRxt&{*l1OadYLxECZ!Qqy%W#TR@yaw)349Dr;` zaDqZd+K=+LTUWc+%zJj8nEvN%K4!_`>-jLX!dTsD;zl0;mQdkdqL&HFER*^`+9arf zBXz$BhRzO#{|N5^utF#_h%ZJTTDhQguc`-tbzG`V5i@yUw$3?(PZjAIkpE;1u?=^G zx7*(4H|gY;Y+QdiE>9}J$x`VMC8$jaZ}FA>ro=^|SQDIz)cuFr*zxFsP-{4s0k0z~ul) zey)1aZPdTTwToyu*xFzkQ3mGUzw_(~=tcHk@=0ijP zPaTA5wD}8|+j~D2W^xA1YA8%>C8u~hu=cMCOM0=`~VbmKDA@c(CzD@0?3zw9u{j%d9EKR9&X7!fb76O zpGyj>rrF*`K{J5--32zURC@uuHs*vFZ8u=#F)tGu15gRWf6svv8a*7%iPA2BAQ7JV zuo>$sr^{ub{fbPfHRw|DT@5Ghl@X?UH?d`8K8u2RgQ%Y3>b z?%`^^G`zWqxE>>S=}0Chd(8iup!ONVGk=6Ru&-v4#-Q*Ivb?HF{hUk?svJE?ll^0Q zXME;a3SFBZpDS9>e?)AHYr)`?a?BBWbql|Sf}~Hss*m$Y^Z^r!o`bk&-eiM*Uph6b1Xo1w5JPsbO&~D z!yPZI(Prz_)po@ipH*x)w(G_<{d=IHX@y|(L#O8ae*ErMH#(`8IdNGq-QJkBRf4nv z6I6#SolgFX6EER@z1DgB=4aBC3l`ue$={)F{jOXJuZf=zFhtNL-Mg|ur`Fl8ZO z|MOS!zZ*Ox2qr#MH)?vaIln{P}4^ZwbT8ms-s z~5$I){tK}&RfJNsMiV_^y*>sv?BF_&&h}blZyb>=~c)VtuJ}h zAbD1uG5(+Xi|KjWMDn17*df!dbi|1!;cb(e$rp=99Lsk<8!i_f(G1K3b2dUsPnvCY zOyFi828vRS=O)hH4u=0?mY%G}y&950x@~XyL25}nIBgA=*)gpM_t`!#L72+oC#)1q zRF?gb+>8*TM>p%M53H;s7j1^e=G7{>?&&j_KZAYF*l@EA!L5qn;_zfK%8V|NNlqw* ze#Bci4Wt2+;?>kJN<(dczY*2nn5{&V3>*RmLVvwH{lE>p1WT;+Gd(!_gSTjz$3Bv|2DSRN|8YX;$D_$j@kIu;YNu8zA1!)juZDHHsNG3w4KHw*?)gi zRVM$I@Ne?YAU=#We}Cn?TgD{K(|~yQV;ARbB490BABj3lIZVZ35=qQ|d{0XZ@?_S1 zCkN>2jH?-n|Kjt4Lr^G9gW%#ED7I?6qZ1{)0D(5)2eI|9a8aXjuF`sLqL`t@*EODx z9VX@g`*MI>%Xn#pzK}5PCzc*LZzW8r-9%wkDa#7_NWEkrRF+_%gyJO_*r)RnrbL0#A{z)nErdqHvUB4e zFNYhaH54M=V!SjUwB1(WncC_OEjO7Ic0JbuzT#Nt+f2Zi0dEKnTQ*my+V=;0bo$aFSni4OpVRMg<-tMc1qy7+(A^KCpcOwxqr?aflpnyo%#=XpoQ zzwS1~1JT(JdYsxPnoj_U3a6XQ$^^Mw&v0}*bZ*G6_C;;sEk*IHH!xR+-RiRkFY2E~ z+nSL#u)Zh@-X(qeLg0iPK2aK~RG@SdEJ6NV; zq^X2afy+pN>_G)I3fj~~; zDcH4v%@Df1*YG{e6S{PNIEQ;5+dV9^=0<5QG67kUGcM4Q`nQhMZdJ*oJ~`z~1|AkO z^rKvl zGKc|H%ZSodgAfcTe0k93K3sne^@C*~@AuFrJuwFL{ObiRY&qA^Q9 zP=M*F6Xx26Pg%&$hY$?hv*@6*{0PK>Xn2w3KY}T`8Z3|yiOKwr6u)aMb(WP9eZvUc z7jyTGW^80>^XUZUBB3v>>tyw;0kC`y)@6p;pJ){E=$e;1+NcWvIiBm+cT~)gCkW1F zx(af(oiy6+)*N2+auo{ho!61su@6A)5SOL_T8SgEe!m1BdZy@CYQiBaC0U$(QDAC4 z3W_j?uNILBo9!aiI)6;ejZS{Palpbju@CDw4@hD!v0;kn#!kS-v8Bw1)tS_vlWfAu z*i_7PeVc_c)W0IGh1#~Uhn;u5wq-1Q{a9;YD|age&SV~Bj-k~V0Vw{}WiNy!U8WNP zR6QjWJ9A@A+05t}$0KUQW=sSq9k{cg_SVv7$c#^c&r6v+CN|Uni$^K%PWI~q;(@e$ z3STM`#DtMyrkOoTCn$YWad?Q2LEtm$sTc06mTzlK(_&tQ^+Za{fBhRTZn&|(<+cU( z;ajXci=1caHNV&m_AdBi<3}71f`Lyu zkg~7VYoP7D!`p6y95j&PWq`NRr4-6M&itZtXYW{WPq9X3?7`>t9!k7y??I|d=QFju zE!8t)lXIp{v8BHL}=7cI=C^!kRC6rETtQ43kq>!ioY^lkn7@ z$#Z?8W`O5JVIT8kAZu|SoHq$n2vb{qN%5atXBSkz5L(Sp^na*w+js9l6zmOC1YluB zu1L;Fuj+romq&`N-&p9l;gs5Ah`Xy;jZN-|VYCc^nKZT43M!l_VYs|!ERj+f4%H&V zM?%dt#xj3f`yjNr#l1~nxSa99`OwXQw%&A0iPVOKpILTFOqm_>0FW76y0!K@(g$Q&rF* z0w3lZ4hIFYM3p?TCknV(XPfELjyY%5~M*`{vDA=&Udccq2a!PzsmaF!FR zY_HBL9=amBeP_=}JTwYxbIN^&r!g-9(15DYVYWQizLcc72trk0>W!I7nz|p(9%tAk z_da9S-i^R^7bs~H)k;=yLmb;}NUm#43cqmCm#JP|(f;G?HZCRRKEybg9Ov#!m}_Yc zxZs@!gzFJjc(-86M0KIJEwaFW<&9ub_4r?=x~dP*U;$wlvJ>u$T?p7Caj+5t0ANV9 zsT-RB3Om(=2+5qc9O~y{!Ex;rtRgJKxnmAnFqOIe3!Y}bcdEk zDAqDWF0}x-%SE1tV;Y*Sh;-L{DP=O^N@yk@U=QsiMh@&r=rfwWR5be7Vh7$k-uVbU zOMGC?&Tb*1?#LcDhx#nopHayI^4%-6USYe01=W5b*vH+{3PJ!o`FCJ4`+m&L87V## zPX#Wu{@n#nSiaCAoF24jLyhRV9z;&)9($J*-y1h^`c>vm$iaG&BxA$3aP!JmpYTq( z#y`~;DtYEt)|B+|f)@HP?|Y$g8PNwoy}EXyx~1keM(mLkPYZX4dhU#lg{YxCZ&OZpZaB{JKYsk}$Wu^au;LGoo|KbFGkghdv5(SG0GzE&X{ zCu8)CO+)7#x*+eb!_ZBqv?!jp!VW_S?lTGM@zPNkSqebRJlRsvwyne)gu}kr(ddA= z`&hdbezPJj2J+3Z>qlU_@W5J61SVzi{ggFcsb9=Nujvjg8p!;^3M7n>h3bS6KWSJI zFY_hQ2st6vnLTtrv~8!w_42_yf{b!V97GG&>wVx&_Q!v1o7>zJKqV5lVHdingpzC-cYd#MEh8prSn9nBU43+1-2|0Nj9)4~A8?=UXQ zzmdN{O`=M-gDOtaj0TGx0P{ z%ap37z3K^pMDU;9!pF&eg_+GuCTzFk7yr%7qu>7DIW>`(ogb3kIWA}J+c-d>;rviS zOR?Zpi;3#v+{POSJ6IY?eUnIaxYt1P5$svnFk~!s1IC2NarJGg!^cv`3cc=DqjB5% z5)aMSd(}3F#Z`p1@qXHDMX1w}jYIeX2%4rh{p47_mQGXdyk4|vlhR}0l5z!+Ec^yw zw)|6s@eH3$h>Ta0w2@p%qMEA-zVZ{;`*X?IcCPAB7iY^*o1o|ZW{ogoaGBd!3CVF+ z;!7~54z~h104o{OdyI9VlxckgJ=k!HQrQf0u5!)S1(i4SAG=CZT@K>ss6NYs6%)I! zJv}4NwXyz(CHXg@4ylj)n_YLFb3C`t{Y4oELq6#lD zgh|OZz;n$mu?-@xlW0x2bm)DN?mVl){9Jl^S}^mc)m z^LezARHyI!SnQM(D7{=Fz=F|%9ROwp+7EmHhmm4-qsf9+fDHTihGo63!F5`acifj| z1-9|o2*QuFovGDS-*?=8efxAES2EX6TA!Lva|YbSnDhpva^uuOgThQ^o$jSN_v7)b z=(QCCq)is@$0YH#baNrEuRjnE11|#y>Q(R5etIy!@u0d0$mdKm>xCASN@l1LAC3Rklw-418vouX{rc+<$lkX%u+77gIgTOQ#n*bl~$pv-l~f&3z=L30#}SNq)fS`>^z& z897aU0KtHYVam62_}C=&CLrS!xDDpp@BCXS!{X+p<$F_0p^p=&DT&7*16sLcU=J&# zNi7RF|5y$WDo~EMvzDITTNT%)=l-_4X^#f-9qZ!Xgu=(zc&yWMLY4iYqA9MSIq|_c z{x^v9%GiuB?*=O%ggUTepTJ~t%zi70jA-6Sqig%~3bm;wUK;aT;u)rpCYw}NEPJb{ zT<;!PZmpill!D)-j3+l0nIgijfo}NQ=y{r6S^jr@)m7BS!wB$BoH6~MWd|cX42>9$ z4_jqyfgi>?zXE>~`dXFN>1n^~oasC#dwLr5DDeoSU725Su1TC<{vpVQ z>*M+5X9lkX4Ai}zcS0jN0F0+o7KLpM8;b`eI6J*NYrUumlDGI0c)o72&uky#7K-Cd zi1bmga9c`HL9DZH{8>Kn7Z<=PP;|R2kE6x~L_&aagZVDXamLX>?Xn!wrk3zC4CeDF+u zg{|0?H`lM$ySI8g0*=!!QetoeGAxYM?Fy7|7$s&PJ0XK(MA)#h5%xh6(5XfS;V;Oi z2-%eg&U)4n(nebSCxQVYo7#IzcoMRfwOZiTgnPjAbPV^Q;(PdpSWbJ5*`72Xt05#xpBh_NCCfohZ&? zj3P{t#I(BJyE$J=dYYFFgdKiE^1%|`V*hj~r?pBC&6puuoWcR~iXyZ>EFYXkRKVsJm0?4nvTq~XyFubV~Bc!r$^kkjd zC)7U)cl@QHYuaAMb_82LRDCGnsZxa1ZtD!-QX3x}PYWUxmquFc#3+-HQ|V-$X|(=O z$}(U^c+pBSSB&IuB)F&7);2LXk2r@#GME3`qH)blqekzxY}zE;x@nW7c+t4u-GKjE zD*pGQzuVvHzuTKDj;_B>?RPq%W&+&-KaxBobGKz*<&h(=&XvF1_8{v(;B?E#$kEZ` zdBR97lGWf zO=ca3)Cq4!>MzCmndB31_ZZB|+n;!=dSUV$!0<=}g?vyprs@f%GtksXWc0aK)9k%_ z$e!^G%^&5gCz9wZWBq%Ng#iql=(@wFMo4eYO$bkxJ^Uo0a%}MafN8Wxf40$8+wtV3 zA-hbo;Ij`@8*N>l58gO$7WZ}PiG)Yr`H}bEOkWNg_s;s<>dbTzXCWK=oWk{hQ?~s& zFZ19$-^FD8d|8Qp)waiyRbPMRU4MOMr{8HnkiPzkv~+mu&AuhsF_V2$Pt0z1ezrU} zHyF9YJ}>qnApy|( z`nO6un$mnqPW871wbdla9qQVA;nx0a)rdm8{_*jh(i#EV`u3+)K1x(^eRmdE5PGqA zNAqKq?FU>xAtlZl$lNjy{IfOc%O(Bl^jbMx*#afgpP|ZI9!O!Qd*b!DM@A#1bdQb1 z-aS1;%B-=Hsz2JdQ|kC=WMA9tgUFMBRi_%`GQj?%bLi=pmOsxQbyTnWso0daLs7eK zDEKX1r{(6sw{k7Yii91fMLzHH&%B3RzngMHx)#7`4ZGC6gYsvlR&F&xYUzBGEleg( z&=sKB%u5K29rWl3-|BXZ%2^F@J?f| zuJMjMb^TeeeBREZzm$~>PCuacjok16sBOs&zwEGii~QFA-wz}FtIU6o_cs4M{*RwY p_>#oI@5fujf6-#8bo%er{{j>ROL71J literal 12255 zcmZ{K3p~@`|9>S(LL!o(5-R0>o7=i+rI0SQsdmNU8P@k?UL9fwad>R^3eYwB*5R>FBq!s7XaJ6>(IZ2{Mx(zR{R?>GD7a! zE;6=`)S0(P2ObUT!rk`msp5k^s zowm{+i&qsyOjLSO7glGM*FjVM>xC?JER(bNj$F&xM$osMjVgUS`^wDK5MVc^Z{H@#gD4>JPh(_40<7wh^z*zruLD^RQTKXK$AVzS>Q>-*)1L<@~mRkTs5 zP}p-98Vcs8W{|AAUtz@gy5gNX1-}%la%v|%KB#6?^p5CSD1<$NFa9HX%siP@11Dbl zK&(&szaqnttl8^_o^w~LD7O0%XG5!MFd~%J9Q%?2GfI{6_+C$;`9lv+ArGLIS^*=8 zH79(pzigjx*fnsZ<$QEpuxmg>x=|1xgM%#(;kafxqRe2 zkwc@}0~$q7NK=Hdf)Qid?D zY!s3HbB=c&67&a5sz&1j6;p|3+Jsxav(>i#iP1!E_pfo*I61l=i=V{Yr^Z?LpY}D; z6F5v9BHoqVtd3mFc4+*sHfZdsrm~mQ=l+#+vvF2lN5aa6$W)!~wE!WUOlTn|T99B@ zb2-r%e0eY8V{J#EcXvC$M|Fa_!f4Xx@98wn^5pQ%p;SR>7Cyy&@>K*%V`XNWz=4MwF)1 zMw)z)z#?RwfhJwHYSparZ$oIpdlOLhSPkaGW^^d4x*#&)LHp!+#6G(xo`+1}oQ-vR z;kTfvNT0qU?$t&g=bx~s4b)tv`1tEgnPXpmC06I@sma}I7N1Cd?6nh`KOLr!LWDg) zk)PMNmz~Bv^PY(&n&o=i;T_0FmH!3A0}MTM-fxMzQP8_11UhMXqzT z3HM>$3r6H$vxZHS80PX(1(mQDB)dB|Oy2<*8E7=S8@}A#nb_sEPYs!zVHCjl5}uAw zLWrNnp1BgxIU+6!UV5~*r~CWHuX``&5HeNYOUnBXaBJ^GjU9o8L@QDzbFH6Z=G26& zY3Ueejq07ODPc54c5jLP&LCOB<}DH9xNPbS?@)pfQhOem+%c|;`s|iD$AgZdPk(DP zB(I|72R=~!CQYqQ?K?a6ktLg(+h>l$MS7svZ2(3Rt4UCC+__T!fI?X-+?FcUZdxyd zRFsod4|`XoG;3P);(bY?v=FK^QT-T?D4;JBnz&!O{(8XFOH;y&4`Pd^O9zkUD3D8X z5Vq3Fy89~Y6LY5U3Cz3Rp)tmE{)*ow%ey=Zl_ z0A8izTVl;@;B1W>iX0EjR3n8Irx1ZPGkRZ^^3PMkI5Gx^{4}|fVPi54+;L-j)#}ce z?)DQrizt;^&&N!QhUqXX608U?cjRoABq_`)1&OV>>k3J|&@%1wWRrE}mo{R%n4$I_ zvcwHb!`?xN9R8zLftbyuU$hvcZ&iT_w{SYYbH{N^-|T3AU3<@2lS@j>pVmDNOAUIn zOdYou7K|SyN8o>c*`TRl3l#Y!8clu)YmyiBSImEK2>uP6n1^89SPdsmr{C6Zv{*^G znqigJEVVOE|URl-KtGNHC0RaioU&*YZ)fG~>e z;hc3=1UHP5=nOSAfd$_pyrA*I9eKaF*^X5VT5!@Nt zmAogW@`I5+h)v9UHAcm1!B}|XT79B{hbc){rL+`I-`nmb)}$M%g1t8!(@%X<9Fo!i0ci>S`QCHt}ZuVW~O@J4I~kk+nd zT_W{$=%;+eorcU3JAAbpX6(3OCbXbGS1dNH9m zV?zlE8)x71ED?W8eN8uFRdMa$#?X7%*8`N0{9>ul?kE0-;8eYy1Dl7HLn&)dFMLSY z-I39It;CrzxCVdavv@2cM*Q2yu^CC8}yz&-NZhjRro zoQGWwGF=gZX9IC*%LPtmwl#$-5gP+Ny5F*bG}WNNZ>EI@0FSc*#HH)Ix@9^@i6^3w z@{DwSBi*~SBKwKkaPHv#sd7(7;mn8M?~O*HGC_V4j=?Un15b>>%o~1X%;|c1#74)s z3=f{suUxrMZv^UqRg@)Nr0tF@Qr$qmgS+9^f2~g@MrWx3SGoOm*!8i0K1Ch?3C$EJoeXV##G@G1VhYpPOfl1N?#*INpGQ2y|-weK<0SgFflux^Vb$ZDGzAa%IZC$AEABD(H;f}^X0 zm6G9VGX2NTG2ZIE9-k=c*H6AxvBC<*{dJyQ4n~bsN5c=gqYEFN4PV7+mr+>ZmI150 zowsx6Up$0~AM-uLX`K|T`qiUMUGv_lwol_6DZ1hJtH(ZsW2@ev;y0Ni@yDaBYwFv% zU(t{y(w}A>hxO075DP@r0ZGn>i7b6kQ*gXC&|srIauY6B^w{iNPNEA3@;x29Ro zLZCV`4j!d*851p^HktYNDw%^dknmUG^6}W$C}=~0B!{w@S(j75v%K(fPOrA2e8hgy+>DDqGwNrZX_aS zf(93jiv3_ya~0d{;YblHLj@7ZS_8^4yp53V-HA;`PNfaM6B~oTh@%AkDwp^9U`?=T zG|RHVwJ_R~8kIG=H}Az@!2?%6O8`cm!vx67rVY*; z(W|(F_2@&+6b=xgOR5&b+lY@>^6;fqV>VwDngJoA z!*Vtw4^XxHpo4-bIqLraYK@=^6nwUO7Ckd)K78O&w!03JiwA@}PffGfK3kq+?)(f$ z*@Leu`hzGlpVVwDE7roXwD}Q<>DoTJ;Y;eRO1&)fP)t4r82o@Ft6_4sJ4z*_d`c#7 z$Vt~u&2X6T!k6drj&_@ph0jK4Bf0JMxJ*>lo=icJhW+6x(2`Gb;XL;|iSSprkZ;A{ z+POQG@SbAbduoOouEW#MsHBldZJ$divmpFbn%sLPGA zRCoC_cJd}o1iWmr2W4UQnaVPf@ePU2%Vk{O4tEY(FxQB(J@#?zc;$l875Pp}<1O7= zb8Ld~-4w$!2G;`E)#3gfw&D^1qod@_-o}*6Lhh>zpG+FY_BO1a@JG-sUJR`fnEiE> zw$Qii%13&2^~6jVK0Ox21vtbk2nS&b+jGph>EZ^LEN zH9?pYo*P{_*OS&+!CMZu%I%FBvo+4kzN-stDdETvpZhhz)&O?yJ-2ic+q|+hw2+u) zfYCv^wn}KGIy?6c#a|BYSs}Xsc^_w%l3uph%o^f(Pm-N`$-bZ4pozTk zV1&K?{Q&0K9kVP@eU9TV+C6P#$y?Zk5k~Hrv5O})n&1W0sG6%@C68u6x|`ZoDB~|& zOtcnjW$VX@XpIu-Hzr>!^QUQ{ffxaV3>4pk*8=HSpD{fXZgcl@8(PyJnjufur`tGs zjeBbdCBVNz8*}_aU1Hmeyj`6$>HC@LhLC5}XyCd8>V|}j7U+q=wFY%g9 zn!=SxvZNHR6e6=wGQ8p@PxmM68ST1TrfcLu?tKysr;W7!0OYDKJ>*vQ<>3bRABrlM z_Yr^~LHiE_aAXz~JMd`*AuVz!+@|AqA5q0)TcklSN|Qu;p@ncZQTj3_3ew^k&f{QD z186cB)L@-jhe_hPWbN+R(#AYsu1??E zUi`80N*wsdW&2b{Tltm>)sUinp9Gm-@hvWqBdg6SJHI#+k&LHH0zv{vv?H2G&~y6t zU;ge(SLTntr=teK9oRpJT5$FjD@Y`V*$~+I*%EwN&jNo0!cbfK{lN(PXzB7|hk{)b zNN5!fL!mz~J6dqu}I7~)c# zi)5jt9LeatxR3{^rGK0Zb}m_rpSK73I#JCn8t-OIZx7DOIFPP!-Fy)2NUK=hYdS3B zcQ~%T{V`ocX=G853IT?|C;PY^(1wV2eu{%@Sx-DGcB*s{%A5xBz7clNq{oyGrlM-b z{MEE{>hKwmrEau)q!-G_5IWe%--6VmAoqp5{1$q5ep8O^YfQr&jXdF?!6MZCsnTc{ zKE!&j@8MxVpFGxR~hbSXG=-~I%9IGzC=A&-vE%ZbF8`jU1UZ#ra(`44H7k_Ee%W|VSNa~Vq zTgqGz%iT32nU2v_OcuB&0ymGOueMGG_I2)DNq=E>g=xSQAQfjm0l9UscqxP z8hY_Nr`EWGEizScvEeKvmmOCt$I(nzHS=MX1&zZpf`V%z3-*ETx`e(TSa(<2j20(+ zTt9pK@_Lb%(d+wqgyYo_L!nhBR91X_5A{|`M2St*NyJMO4$CWA201Gh4IbcPt}ezX zosAV11BpX7LIdPQcjWPXghoI}`%}m8dfyt&tAom^IqL0zkn5z$l9t-wnrSsSHvfh; z5|Ihy(D8i?t*Xug^zW)eSjXXr)e-SE%t=V*A59WPEO}Q_sQ==)o5$F!HZ>MhPx(b_ zl$ezv0h;>w=_wq&C>}J&^Jiz`Lx7 z=`Wn~D0#G5A21oMuhx~9Y131%>7C|%V#>kB?vnhQB@0@W+N5coc!w<-T^}2AaPA^L ziK+?4Gy%4sc1hH9YV34qXeuz9>jh+F^Z zJw%wl_H3GuX~>c^p5JWor`nMLkE!Q|@kF78+QNjB3J*|W&w#{@HePSR=K0Nr_{H z?~`ez%W;krTK`7=Lk(FegV~G6^B57w92*Am9#V6LYOP%()0fQhjdhTqtR=mUwnh23 z;+;nOXL-E%h|cOouGt%zGwYvlPs;&seRJXsgG&W`iqF@F+B9$>t$JZc-YK3O_8Hs_ zlYhx=T9Tmz!*^`*+{K(fQAM^}QgR@#fqatOW>#4^bt$nL-J1$ic+rgq80kPa`d%4@ zWtX6{dO+tI6s!tWLlm0H%hVP#6Z~4l7Gaiw_gX37Y~fvVdY#uIy3v@|^!n^Bop>Xu zt$_!o((Fs6n0T{ut9Itt6Le!+%Y(vtiI+glR2HyM?+ou2@A*{;9{$nz39qSBi20NW zD_(|lpatavZ|BCHeTl)Hz*5Z%0SiY8CocHAicP-QlpTq0F@|g<*LJ)bad*nA92B0i zy0bOwC)6-)svtgL)&{(=aD=3$GSB5+&v5sB5Wi0vEC4 zHfU5Pvs*R6^^E{TGLUi(pH$VFbpy^huX1~?2%lsZq$rAN;sO9j;QIGeLG)Vy`AVD# z3P|!I(U0lMOG9n9Mx4&uj+}`~xkw}EoUO|YKgr5{e;9g)bW{+>?&JdSJpRX9Mc}BZ zN{X(CZcxShIHZNFAQFor>TdXJgB4}5;1==Wr{6t24@JViKeu^W_x6kWuh^{OG^w}I1~Jie?)yhnVLKe$mn zRE?+}0J}*OhdIr0$w5B@ZtqX|4~eJ579 zh``VEc!?p*pc`vzoEL%Xn5#!sp&J)V{WW!4+kfjo))kFoEC2jDe=~sT1!xT^t|8yM z+Xvs%fC6%K@H1JiD9(G}h7qZE$*K$3`@l^u#Ox)v6|gPGml4TBrkkMoys_8>LzBAc zdt+dOQ(zZq%B`MG+|l#v+N8G56n8~&(kSi)aBJ-WD$?YCvpEmMOiM@BqmY#Zl=`QV zfXVwvF!zz|d3}t_*wG}AHd357l&m;0rT2z?NfY~KGhqI7gAG&t4H89hHesL}gFr$g z_mf=pok84b&QV+r9PC*oF2j<6-y)Ppg!nX^y~_NYLa17muxmN#v@k_$%KH`?HaY#| zHSL=YQX_*EO^FjI=6n(w75eF&dcA*3VkX*MQD8z-NQP{!<)$b=T37--j6}r1?8ZiV z0FgWRzQ1G@-$(8S>`da%UoBPyO(SiX_j>bq-&}v(>({NYR@_;}_x140`NXc94IDM| zmjJC4Z7{y@8s=XAagTI!H|H5cH?TTLYrX=kLuv!3@alal8I9)c862<82%SqB)l2mS zM@9%qf#bb?jE^hMxi)8ejAXnbK$WKz*hCWfkJYzd(V?GQYfXHSbC#A4>7n^WRFznQ{enO9(}3`7Cm|#{0|;Nn&$xSuDH=luAvgb2 zDbM@a;9g+-Nxfbvm+f4|vd)szMj=Uj5O+%c7t9a;EAL|WLYc}bIo9z@%!PMuD6=!9 z|B$v9DN5FVvI5=iKZv`Zq^e!wi--zZiVAPcN@O1XdgERF?GkfL_tfs+s?VZ?{?2eE z4R_RzYl=JK=vt`ArdK988>9m^O#p7UrQ~E~0Jq0dl^_qZ1Sp=%iWeIA=rWu7pX|$M zPsAR$Hh$)vs~BNFbi^e|bSh%s0Z zZ_Wyk{?tyc;6!m!m*gB>}8RYz_#nWx*sRuabK3*=%};|V(8o%fL+dR50j zam0X0QFa8Bw;$Dn0WYNEv!U9!wK4IyZNa5hLou9rFJsheepc(H4CxYbNgkXHUB*N`SS%0KG>Yn>L}8=6J(+ekSQvPKuKHcBtJ{ ztfPRNxl=PBPy*U)j_0d`U_Qfcr5Ww#2}7Aysh5)Pv?;c&4{g2y)lS~=iLf&@oBb!oe<>?eT}E}5uhR>pDv5cBH6)LS6cSNl zHFunm&2b^=z+p&cPqvN$)TNqPlNSyz3^ftY!N!q&@jaZ(OG4GR7Oj$V-G}OhF)_)I zLLb6G%>#rzQ0B?Q0||0EnX)k&(ZFpnzU(s{F?SnRa(*c4`T`9u-|PQ7GFe@}cZ zT?{XB==D2qi#kq<$_dj;g5u%+dN509;6mScw7RBrTr&n#pE$cREp>w}= z+P#7x(TeT_;=y_c)>u4fJ}QroWOKE`TU~r80rD5z!7cIw#6i*|KJ&?d{+48q@OB_G z@+J2Sr#&VFF+Bf|Jv!PCZv+Z-5OE8o*dz=Z<@~3ka$26Cik0%0VZd}Pa zGh+M(4RwiyrvujmN%`*U5y&V@a7)%bLzew|XM}rg8TTx+9U}tBTFTCct{KjVdnp=kIHDx|{=Aw> zbI`vucW1gDb3AL7?TFY?Tot95?}r!}qJ?lX3=uN~*A%W{;{Q)cCk8Tz;4h`{-Hf8o z*xSvZn6<-LbUq;v0vz^PRXmrhbzLXWr+RucFQ!Bw(_mF27Mro8VPi{RT+J9vV6D{d zw4=Hdjy6YL1pE#Z#CYKtGHdOKKn2jOC`#>3Pmsa^ggk$fFDg?-5th}E5ch9b53GKVwp(dfo2fC57`ZfT)_9`X`moS z$pM@f+(^;_U%ae-a%x!?m`@DhAHNu+y<5e%W}BQLTyiK=(w z&d%OPuuL!UP0g@F(83YCRu(P%IqM~m@&lI^f=R>Nn_qBrMZuoIaG`2G}AU{aW3gff-( zV-9eB%9zxvm2w&P0LA$BbTs9Mv{v72WV^%U>93bj9b`e&BdwCRRW#*t&9s}8uE`5UXy<}S78||5_g){;3{@m)g=4!qcdLozP^;N{ds!_dKa~(gJY%= zcSNiF^bDr+Idyo6DotD%#c3jauf-)vEj^f(RSg#Zw>P{a zIe79T%Lg;RLrHbVhLc9g&w*Qf2MhY+38j2eJ)IJEYh(-Zw&Lt+eXaThe}nH*ij=Ku zLj`=mLe=U+7iRD?ga=ro;0RLhN@@_(iuLk-};?_cp!mAGCgW)`qm71}HZuzO&__7gOqY&oEiz}6-JQ39)B61Dje z=x6uwN&-;_x0Xs|;>&oaaKZ}=R}}muaM%*1Q|70QgRR^*o$h@Zq&54mW0O0?5~UXK z?@Hh=2CXR6e1b;0M;@3V@2&Q>+whL z6?s;Gp;kwE>wy+Kf=0txVDKptEhA_WVCE|UIkFuA#6)A0ft&&-10>=D5IznFy@+^- zGI4D9lE_XkftW~v05&Vqf1FCw%R}N&c}X+n;=BiZEfsW= zoZ2AmuWiRRDpQmhXymaPT&&-o{D($(W25(m!>R9vc~jcxP*R zpXpmF{!yO+_;;ev46LJ(eI=s4BV3uF`e zq9k_7KBToI0&-_5Z$TTB><^H2(N$=f^egD`Ml^y%uLT`+A{P9|Iq#3BB}@84*53UX z-MZh??Nd>1ifQFSxF`B?n=(_77|!tcT@DdFcXEKj@$)W&g|0PH7lR$a=(Y9Fa`XSx$u&j3}43S6!mK|EcCuF?pT+=7cs2g>l(ViYVE$hX3eVq>r}vDAyS z(AqNU8p&{JqIG~mEhC6fC1*|MqNavQcQs<`LKucgM^77eCj&{6Q+6Js{k}d(7*nJ{ zD$;`wX<7)`P2a^$#UR9q<<5?^^PIzY2`sBnPpc~{f0efj6borYP56d>U(?)@ncX=# zP4+-xJEJt=;I~9yegecOwFB5d8s_~d`3>>u@{LviL5UctN;B0a(d4yojJDB{m(&FQ zMN5i1NNB6ml_2mp(V5cN!-8{&~h}xhanNz6>kIJxx->M%8GB*)S17Q{pp2 ziwO_e$XF5HsbK#t#7S!j%={&S7=yiW&}p+UWGMAiF6e z%l^+@n$3hZ(sa-nf0nH>zQ^*GFT2VMW4%y2f0*0uQ^b04);Mmr-VOL`+Y<5MD2yKy zBTPqGz2kOe9aHC|j*cWmmZyMHm8?i1vXMskz{r#w?A5}wnA!oN(2k2Z4J`%RSj)83 zKM4O4w2W(`pTJCbx(o$6iu-KVM3N>uJ)im%O*1nWhYqL;nYXmQqNZx|Z6ziBmx&Qv z6^6MhYDa-Zb(?ZWQB{AUj}fdrP^>rDyja#phA@uP8r64q#DUe&)nx80&X*nQN(u4| znFm;7Ql~<Ta>|*mQ1pu9Si9l{h)@>w(%%y<3%`-bqyr2YzH1 zUIt$eIbN|lLppf=;Lxp+?7E6RV&bvB&$!iFQl8$&`n$SBM?If^)VW=Gw)EbDo+WfG z`RKa46mSFBh3lpM%sbJj+uwBjFyd~a>0!$0*J`_o&kH7fEYID}epz-LrF-;fgkass z15Gc+{?%h~0c~=c9^)BbHYkQKO)ZU;NhV^h)JuV3lqGah|I7O8!dvI1s-%F+QEO*} z0D=;#gUWhhY=e~(yScj$LCdP`1;vj3m{hg>b4VxF_S&sAAV61HC5S$I)(rsNgM1xW z=lJZLSh8?T)6?YBm-3ukHJ{|Q)W>IKU+8U;Xey78Jl?+hy4%qtg@6oPz};F&fE9lK z>tpdnap8h@zFz?Xd@Qo}o5soSlfCm3DR@Oo+|AH$Tp+08re;Y(m87~v`XT*(U%5Rm z-eG1t!>m~+CkCX`um4=Rk1WK>d%=zcT~BwHeqBXOk101M-Zh-dc<6m=Osg_pv+-i+ z*Q9Hot_BpJ4>OZEcRwI|=%$QgbmOU;D$&X3QVvIRvA2_B?vnFI4-5c`4cB8PQ{GG9 zf3=sW%#}+!y_<{OK32>ocHQ2dNSoK7ViB1Feb1mMcpuijDRFBpt$ppSV3k8?-Fb2B z4$Ez}DepHpg&EUqQUd=! zxBCB@&41HpyZ@&DkCXlX-Tc3=k-ts;D?HmB#CO5}&x*NqLvY{U>^=NnFrVJj_{;qd D#=K>! From 693ab308326ee5e4c9884eb57f39a14d4b885f74 Mon Sep 17 00:00:00 2001 From: Amal Nanavati Date: Fri, 8 Mar 2024 18:23:38 -0800 Subject: [PATCH 15/18] Added launchfile --- ada_feeding_perception/launch/ada_feeding_perception.launch.py | 1 + 1 file changed, 1 insertion(+) diff --git a/ada_feeding_perception/launch/ada_feeding_perception.launch.py b/ada_feeding_perception/launch/ada_feeding_perception.launch.py index 86c99620..be16da0f 100755 --- a/ada_feeding_perception/launch/ada_feeding_perception.launch.py +++ b/ada_feeding_perception/launch/ada_feeding_perception.launch.py @@ -155,6 +155,7 @@ def generate_launch_description(): ) food_on_fork_detection_remappings = [ ("~/food_on_fork_detection", "/food_on_fork_detection"), + ("~/food_on_fork_detection_img", "/food_on_fork_detection_img"), ("~/toggle_food_on_fork_detection", "/toggle_food_on_fork_detection"), ( "~/aligned_depth", From c6029337b4c55fd10e312d935b2e3894efe84c4d Mon Sep 17 00:00:00 2001 From: Amal Nanavati Date: Mon, 18 Mar 2024 19:36:48 -0700 Subject: [PATCH 16/18] Moved to forkTip frame and changed distance aggregator to 90th percentile --- .pylintrc | 4 +- ada_feeding_msgs/msg/FoodOnForkDetection.msg | 1 + .../food_on_fork_detection.py | 9 +- .../food_on_fork_detectors.py | 361 ++++++++++++++---- .../food_on_fork_train_test.py | 201 ++++++++-- .../ada_feeding_perception/helpers.py | 8 + .../config/food_on_fork_detection.yaml | 2 +- .../distance_no_fof_detector_with_filters.npz | Bin 16801 -> 51525 bytes ada_feeding_perception/package.xml | 1 + 9 files changed, 484 insertions(+), 103 deletions(-) diff --git a/.pylintrc b/.pylintrc index 94e84468..c628deb3 100644 --- a/.pylintrc +++ b/.pylintrc @@ -202,6 +202,7 @@ good-names=a, j, k, m, + M, n, p, ps, @@ -218,9 +219,10 @@ good-names=a, w, h, r, + rc, S, S_inv, - rc, + t, ax, ex, hz, diff --git a/ada_feeding_msgs/msg/FoodOnForkDetection.msg b/ada_feeding_msgs/msg/FoodOnForkDetection.msg index d752c038..fd91d003 100644 --- a/ada_feeding_msgs/msg/FoodOnForkDetection.msg +++ b/ada_feeding_msgs/msg/FoodOnForkDetection.msg @@ -7,6 +7,7 @@ std_msgs/Header header int32 status int32 SUCCESS=1 int32 ERROR_TOO_FEW_POINTS=-1 +int32 ERROR_NO_TRANSFORM=-2 int32 UNKNOWN_ERROR=-99 # A probability in [0,1] that indicates the likelihood that there is food on the diff --git a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py index 6b156a07..0af4eea1 100644 --- a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py +++ b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py @@ -627,9 +627,16 @@ def run(self) -> None: ) X = np.expand_dims(depth_img_cv2, axis=0) + # Get the desired transform(s) + transforms = FoodOnForkDetector.get_transforms( + self.model.transform_frames, + self.tf_buffer, + ) + t = np.expand_dims(transforms, 0) + # Get the probability that there is food on the fork try: - proba, status = self.model.predict_proba(X) + proba, status = self.model.predict_proba(X, t) proba = proba[0] status = int(status[0]) food_on_fork_detection_msg.probability = proba diff --git a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py index 33d85e39..e04bd8b2 100644 --- a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py +++ b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py @@ -7,17 +7,22 @@ from enum import Enum import os import time -from typing import Callable, Optional, Tuple +from typing import List, Optional, Tuple # Third-party imports +import matplotlib.pyplot as plt import numpy as np import numpy.typing as npt from overrides import override +import rclpy from sensor_msgs.msg import CameraInfo from sklearn.linear_model import LogisticRegression +from sklearn.metrics import f1_score from sklearn.metrics.pairwise import pairwise_distances from sklearn.model_selection import train_test_split +import tf2_ros from tf2_ros.buffer import Buffer +from transforms3d._gohlketransforms import quaternion_matrix # Local imports from ada_feeding_msgs.msg import FoodOnForkDetection @@ -55,7 +60,6 @@ def __init__(self, verbose: bool = False) -> None: self.__camera_info = None self.__crop_top_left = (0, 0) self.__crop_bottom_right = (640, 480) - self.__tf_buffer = None self.__seed = int(time.time() * 1000) self.verbose = verbose @@ -130,59 +134,114 @@ def crop_bottom_right(self, crop_bottom_right: Tuple[int, int]) -> None: self.__crop_bottom_right = crop_bottom_right @property - def tf_buffer(self) -> Optional[Buffer]: + def seed(self) -> int: """ - The tf buffer for the depth image. + The random seed to use in the detector. Returns ------- - tf_buffer: The tf buffer for the depth image, or None if not set. + seed: The random seed to use in the detector. """ - return self.__tf_buffer + return self.__seed - @tf_buffer.setter - def tf_buffer(self, tf_buffer: Buffer) -> None: + @seed.setter + def seed(self, seed: int) -> None: """ - Sets the tf buffer for the depth image. + Sets the random seed to use in the detector. Parameters ---------- - tf_buffer: The tf buffer for the depth image. + seed: The random seed to use in the detector. """ - self.__tf_buffer = tf_buffer + self.__seed = seed @property - def seed(self) -> int: + def transform_frames(self) -> List[Tuple[str, str]]: """ - The random seed to use in the detector. + Gets the parent and child frame for every transform that this classifier + wants to use. Returns ------- - seed: The random seed to use in the detector. + frames: A list of (parent_frame_id, child_frame_id) tuples. """ - return self.__seed + return [] - @seed.setter - def seed(self, seed: int) -> None: + @staticmethod + def get_transforms(frames: List[Tuple[str, str]], tf_buffer: Buffer) -> npt.NDArray: """ - Sets the random seed to use in the detector. + Gets the most recent transforms that are necessary for this classifier. + These are then passed into fit, predict_proba, and predict. Parameters ---------- - seed: The random seed to use in the detector. - """ - self.__seed = seed + frames: A list of (parent_frame_id, child_frame_id) tuples to get transforms + for. Size: (num_transforms, 2). + tf_buffer: The tf buffer that stores the transforms. + + Returns + ------- + transforms: The transforms (homogenous coordinates) that are necessary + for this classifier. Size (num_transforms, 4, 4). Note that if the + transform is not found, it will be a zero matrix. + """ + transforms = [] + for parent_frame_id, child_frame_id in frames: + try: + transform = tf_buffer.lookup_transform( + parent_frame_id, + child_frame_id, + rclpy.time.Time(), + ) + # Convert the transform into a matrix + M = quaternion_matrix( + [ + transform.transform.rotation.w, + transform.transform.rotation.x, + transform.transform.rotation.y, + transform.transform.rotation.z, + ], + ) + M[:3, 3] = [ + transform.transform.translation.x, + transform.transform.translation.y, + transform.transform.translation.z, + ] + transforms.append(M) + except ( + tf2_ros.LookupException, + tf2_ros.ConnectivityException, + tf2_ros.ExtrapolationException, + ) as err: + print( + f"Error getting transform from {parent_frame_id} to {child_frame_id}: {err}" + ) + transforms.append(np.zeros((4, 4), dtype=float)) + + return np.array(transforms) @abstractmethod - def fit(self, X: npt.NDArray, y: npt.NDArray[int]) -> None: + def fit( + self, + X: npt.NDArray, + y: npt.NDArray[int], + t: npt.NDArray[float], + viz_save_dir: Optional[str] = None, + ) -> None: """ Trains the perception algorithm on a dataset of depth images and corresponding labels. Parameters ---------- - X: The depth images to train on. - y: The labels for the depth images. + X: The depth images to train on. Size (num_images, height, width). + y: The labels for the depth images. Size (num_images,). Must be one of the + values enumerated in FoodOnForkLabel. + t: The transforms (homogenous coordinates) that are necessary for this + classifier. Size (num_images, num_transforms, 4, 4). Should be outputted + by `get_transforms`. + viz_save_dir: The directory to save visualizations to. If None, no + visualizations will be saved. """ @abstractmethod @@ -214,7 +273,9 @@ def load(self, path: str) -> None: @abstractmethod def predict_proba( - self, X: npt.NDArray + self, + X: npt.NDArray, + t: npt.NDArray[float], ) -> Tuple[npt.NDArray[float], npt.NDArray[int]]: """ Predicts the probability that there is food on the fork for a set of @@ -223,6 +284,9 @@ def predict_proba( Parameters ---------- X: The depth images to predict on. + t: The transforms (homogenous coordinates) that are necessary for this + classifier. Size (num_images, num_transforms, 4, 4). Should be outputted + by `get_transforms`. Returns ------- @@ -234,6 +298,7 @@ def predict_proba( def predict( self, X: npt.NDArray, + t: npt.NDArray[float], lower_thresh: float, upper_thresh: float, proba: Optional[npt.NDArray] = None, @@ -245,6 +310,9 @@ def predict( Parameters ---------- X: The depth images to predict on. + t: The transforms (homogenous coordinates) that are necessary for this + classifier. Size (num_images, num_transforms, 4, 4). Should be outputted + by `get_transforms`. lower_thresh: The lower threshold for food on the fork. upper_thresh: The upper threshold for food on the fork. proba: The predicted probabilities that there is food on the fork. If either @@ -265,7 +333,7 @@ def predict( # pylint: disable=too-many-arguments # These many are fine. if proba is None or statuses is None: - proba, statuses = self.predict_proba(X) + proba, statuses = self.predict_proba(X, t) return ( np.where( proba < lower_thresh, @@ -279,7 +347,7 @@ def predict( statuses, ) - def visualize_img(self, img: npt.NDArray) -> None: + def visualize_img(self, img: npt.NDArray, t: npt.NDArray) -> None: """ Visualizes a depth image. This function is used for debugging, so it helps to not only visualize the img, but also subclass-specific information that @@ -290,7 +358,10 @@ def visualize_img(self, img: npt.NDArray) -> None: Parameters ---------- img: The depth image to visualize. + t: The closest transforms (homogenous coordinates) to this image's timestamp. + Size (num_transforms, 4, 4). Should be outputted by `get_transforms`. """ + # pylint: disable=unused-argument show_normalized_depth_img(img, wait=True, window_name="img") @@ -312,7 +383,13 @@ def __init__(self, proba: float, verbose: bool = False) -> None: self.proba = proba @override - def fit(self, X: npt.NDArray, y: npt.NDArray[int]) -> None: + def fit( + self, + X: npt.NDArray, + y: npt.NDArray[int], + t: npt.NDArray[float], + viz_save_dir: Optional[str] = None, + ) -> None: pass @override @@ -325,7 +402,9 @@ def load(self, path: str) -> None: @override def predict_proba( - self, X: npt.NDArray + self, + X: npt.NDArray, + t: npt.NDArray[float], ) -> Tuple[npt.NDArray[float], npt.NDArray[int]]: return ( np.full(X.shape[0], self.proba), @@ -341,12 +420,27 @@ class FoodOnForkDistanceToNoFOFDetector(FoodOnForkDetector): test point being FoF based on that distance. """ + # pylint: disable=too-many-instance-attributes + # These many are fine. + + AGGREGATORS = { + "mean": np.mean, + "median": np.median, + "max": np.max, + "min": np.min, + "25p": lambda x: np.percentile(x, 25), + "75p": lambda x: np.percentile(x, 75), + "90p": lambda x: np.percentile(x, 90), + "95p": lambda x: np.percentile(x, 95), + } + def __init__( self, camera_matrix: npt.NDArray, prop_no_fof_points_to_store: float = 0.5, min_points: int = 40, min_distance: float = 0.001, + aggregator_name: Optional[str] = "90p", verbose: bool = False, ) -> None: """ @@ -363,6 +457,10 @@ def __init__( for comparison. If a pointcloud has fewer points than this, it will return a probability of nan (prediction of UNSURE). min_distance: The minimum distance (m) between stored no FoF points. + aggregator_name: The name of the aggregator to use to aggregate the + distances between the test point and the stored no FoF points. If None, + all aggregators are used. This is typically only useful to compare + the performance of different aggregators. verbose: Whether to print debug messages. """ # pylint: disable=too-many-arguments @@ -373,35 +471,39 @@ def __init__( self.prop_no_fof_points_to_store = prop_no_fof_points_to_store self.min_points = min_points self.min_distance = min_distance + self.aggregator_name = aggregator_name # The attributes that are stored/loaded by the model self.no_fof_points = None self.clf = None + self.best_aggregator_name = None + + @property + @override + def transform_frames(self) -> List[Tuple[str, str]]: + return [("forkTip", "camera_color_optical_frame")] @staticmethod - def distance_between_pointclouds( + def distances_between_pointclouds( pointcloud1: npt.NDArray, pointcloud2: npt.NDArray, - aggregator: Callable[npt.NDArray, float] = np.mean, ) -> npt.NDArray: """ For every point in pointcloud1, gets the minimum distance to points in - pointcloud2, and then aggregates those distances. Note that this is not + pointcloud2. Note that this is not symmetric; the order of the pointclouds matters. Parameters ---------- pointcloud1: The test pointcloud. Size (n, k). pointcloud2: The training pointcloud. Size (m, k). - aggregator: The function to use to aggregate the distances. Should take - in a size (n,) np array and output a float. Default is np.mean. Returns ------- - distance: The aggregate of the minimum distances from each point in the test - pointcloud to the nearest point in the training pointcloud. + distances: The minimum distance from each point in pointcloud1 to points + in pointcloud2. Size (n,). """ - return aggregator(np.min(pairwise_distances(pointcloud1, pointcloud2), axis=1)) + return np.min(pairwise_distances(pointcloud1, pointcloud2), axis=1) def get_representative_points(self, pointcloud: npt.NDArray) -> npt.NDArray: """ @@ -439,11 +541,23 @@ def get_representative_points(self, pointcloud: npt.NDArray) -> npt.NDArray: return representative_points @override - def fit(self, X: npt.NDArray, y: npt.NDArray[int]) -> None: - # pylint: disable=too-many-locals + def fit( + self, + X: npt.NDArray, + y: npt.NDArray[int], + t: npt.NDArray[float], + viz_save_dir: Optional[str] = None, + ) -> None: + # pylint: disable=too-many-locals, too-many-branches, too-many-statements # This is the main logic of the algorithm, so it's okay to have a lot of # local variables. + # Only keep the datapoints where the transform is not 0 + i_to_keep = np.where(np.logical_not(np.all(t == 0, axis=(2, 3))))[0] + X = X[i_to_keep] + y = y[i_to_keep] + t = t[i_to_keep] + # Get the most up-to-date camera matrix if self.camera_info is not None: self.camera_matrix = np.array(self.camera_info.k) @@ -459,6 +573,7 @@ def fit(self, X: npt.NDArray, y: npt.NDArray[int]) -> None: f_y=self.camera_matrix[4], c_x=self.camera_matrix[2], c_y=self.camera_matrix[5], + transform=t[i, 0, :, :], ) if len(pointcloud) >= self.min_points: pointclouds.append(pointcloud) @@ -505,35 +620,123 @@ def fit(self, X: npt.NDArray, y: npt.NDArray[int]) -> None: f"{all_no_fof_pointclouds_train.shape[0]} no FoF pointclouds" ) + # Get the aggregators + if self.aggregator_name is None: + aggregator_names = list(self.AGGREGATORS.keys()) + else: + aggregator_names = [self.aggregator_name] + # Get the distances from each point in the "val set" to the stored points - val_distances = [] + val_distances = {name: [] for name in aggregator_names} for i, pointcloud in enumerate(val_pointclouds): if self.verbose: print( "Computing distance to stored points for val point " f"{i}/{val_pointclouds.shape[0]}" ) - val_distances.append( - FoodOnForkDistanceToNoFOFDetector.distance_between_pointclouds( + point_distances = ( + FoodOnForkDistanceToNoFOFDetector.distances_between_pointclouds( pointcloud, self.no_fof_points ) ) - val_distances = np.array(val_distances) + for name in aggregator_names: + aggregator = self.AGGREGATORS[name] + distance = aggregator(point_distances) + val_distances[name].append(distance) + val_distances = { + name: np.array(val_distances[name]) for name in aggregator_names + } + + # Split the validation set into train and val. This is to pick the best + # aggregator to use. + val_train_i, val_val_i = train_test_split( + np.arange(val_labels.shape[0]), + train_size=0.8, + random_state=self.seed, + stratify=val_labels, + ) - # Train the classifier - if self.verbose: - print("Training the classifier") - self.clf = LogisticRegression(random_state=self.seed, penalty=None) - self.clf.fit(val_distances.reshape(-1, 1), val_labels) + # Train the classifier(s) + f1_scores = {} + clfs = {} + for name in aggregator_names: + # Train the classifier + if self.verbose: + print(f"Training the classifier for aggregator {name}") + clf = LogisticRegression(random_state=self.seed, penalty=None) + clf.fit( + val_distances[name].reshape(-1, 1)[val_train_i, :], + val_labels[val_train_i], + ) + clfs[name] = clf + if self.verbose: + print( + f"Trained the classifier for aggregator {name}, got coeff " + f"{clf.coef_} and intercept {clf.intercept_}" + ) + + # Get the f1 score + y_pred = clf.predict(val_distances[name].reshape(-1, 1)[val_val_i]) + y_true = val_labels[val_val_i] + f1_scores[name] = f1_score(y_true, y_pred) + if self.verbose: + print(f"F1 score for aggregator {name}: {f1_scores[name]}") + + # Save a visualization of the classifier + if viz_save_dir is not None: + max_aggregated_distance = max( + np.max(val_distances[name][val_val_i]) for name in aggregator_names + ) + for name in aggregator_names: + # Create a scatterplot where the x-axis is the distance in val_val + # and the y-axis is the label. Add some y-jitter to make it easier + # to see the points. + y_true = val_labels[val_val_i] + np.random.normal( + 0, 0.1, val_val_i.shape[0] + ) + fig, ax = plt.subplots(figsize=(5, 4)) + ax.scatter( + val_distances[name][val_val_i], y_true, label="True", alpha=0.5 + ) + ax.set_xlim(0, max_aggregated_distance) + + # Add a line for the probability predictions of num_points over the range + # of distances + num_points = 100 + distances = np.linspace(0.0, max_aggregated_distance, num_points) + probas = clfs[name].predict_proba(distances.reshape(-1, 1))[:, 1] + ax.plot(distances, probas, label="Classifier Probabilities") + + # Add a title + ax.set_title( + f"Classifier for Aggregator {name}. F1 Score: {f1_scores[name]}" + ) + + # Save the figure + fig.savefig( + os.path.join( + viz_save_dir, + f"classifier_{clf.__class__.__name__}_aggregator_{name}.png", + ) + ) + + # Pick the best aggregator + self.best_aggregator_name, best_f1_score = max( + f1_scores.items(), key=lambda x: x[1] + ) if self.verbose: print( - f"Trained the classifier, with coeff {self.clf.coef_} and " - f"intercept {self.clf.intercept_}" + f"Best aggregator: {self.best_aggregator_name} with f1 score {best_f1_score}" ) + self.clf = clfs[self.best_aggregator_name] @override def save(self, path: str) -> str: - if self.no_fof_points is None or self.clf is None: + if ( + self.no_fof_points is None + or self.clf is None + or self.best_aggregator_name is None + ): raise ValueError( "The model has not been trained yet. Call fit before saving." ) @@ -543,6 +746,7 @@ def save(self, path: str) -> str: path, no_fof_points=self.no_fof_points, clf=np.array([self.clf], dtype=object), + best_aggregator_name=self.best_aggregator_name, ) return path + ".npz" @@ -554,10 +758,19 @@ def load(self, path: str) -> None: params = np.load(path, allow_pickle=True) self.no_fof_points = params["no_fof_points"] self.clf = params["clf"][0] + self.best_aggregator_name = str(params["best_aggregator_name"]) + if self.verbose: + print( + f"Loaded model with intercept {self.clf.intercept_} and coef {self.clf.coef_} " + f"and best aggregator {self.best_aggregator_name} and num stored points " + f"{self.no_fof_points.shape[0]}" + ) @override def predict_proba( - self, X: npt.NDArray + self, + X: npt.NDArray, + t: npt.NDArray[float], ) -> Tuple[npt.NDArray[float], npt.NDArray[int]]: probas = [] statuses = [] @@ -565,10 +778,16 @@ def predict_proba( # Get the prediction per image. if self.verbose: inference_times = [] - for _, img in enumerate(X): + for i, img in enumerate(X): if self.verbose: start_time = time.time() + # If all elements of the transform are 0, set the proba to nan + if np.all(t[i, 0, :, :] == 0): + probas.append(np.nan) + statuses.append(FoodOnForkDetection.ERROR_NO_TRANSFORM) + continue + # Convert the image to a pointcloud pointcloud = depth_img_to_pointcloud( img, @@ -577,24 +796,26 @@ def predict_proba( f_y=self.camera_matrix[4], c_x=self.camera_matrix[2], c_y=self.camera_matrix[5], + transform=t[i, 0, :, :], ) - # If there are enough points, use the classifier to predict the probability - # of food on the fork. Else, return an error status - if len(pointcloud) >= self.min_points: - distance = ( - FoodOnForkDistanceToNoFOFDetector.distance_between_pointclouds( - pointcloud, self.no_fof_points - ) - ) - proba = self.clf.predict_proba(np.array([[distance]]))[0, 1] - probas.append(proba) - statuses.append(FoodOnForkDetection.SUCCESS) - if self.verbose: - inference_times.append(time.time() - start_time) - else: + # If there are too few points, set the proba to nan + if len(pointcloud) < self.min_points: probas.append(np.nan) statuses.append(FoodOnForkDetection.ERROR_TOO_FEW_POINTS) + continue + + # If there are enough points, use the classifier to predict the probability + # of food on the fork. Else, return an error status + distances = FoodOnForkDistanceToNoFOFDetector.distances_between_pointclouds( + pointcloud, self.no_fof_points + ) + distance = self.AGGREGATORS[self.best_aggregator_name](distances) + proba = self.clf.predict_proba(np.array([[distance]]))[0, 1] + probas.append(proba) + statuses.append(FoodOnForkDetection.SUCCESS) + if self.verbose: + inference_times.append(time.time() - start_time) if self.verbose: print( f"Inference Time: min {np.min(inference_times)}, max {np.max(inference_times)}, " @@ -609,6 +830,7 @@ def predict_proba( def predict( self, X: npt.NDArray, + t: npt.NDArray[float], lower_thresh: float, upper_thresh: float, proba: Optional[npt.NDArray] = None, @@ -617,7 +839,7 @@ def predict( # pylint: disable=too-many-arguments # These many are fine. if proba is None or statuses is None: - proba, statuses = self.predict_proba(X) + proba, statuses = self.predict_proba(X, t) return ( np.where( (proba < lower_thresh) @@ -633,7 +855,7 @@ def predict( ) @override - def visualize_img(self, img: npt.NDArray) -> None: + def visualize_img(self, img: npt.NDArray, t: npt.NDArray) -> None: # Convert the image to a pointcloud pointclouds = [ depth_img_to_pointcloud( @@ -643,6 +865,7 @@ def visualize_img(self, img: npt.NDArray) -> None: f_y=self.camera_matrix[4], c_x=self.camera_matrix[2], c_y=self.camera_matrix[5], + transform=t[0, :, :], ) ] colors = [[0, 0, 1]] diff --git a/ada_feeding_perception/ada_feeding_perception/food_on_fork_train_test.py b/ada_feeding_perception/ada_feeding_perception/food_on_fork_train_test.py index 0104de12..84c9caa2 100644 --- a/ada_feeding_perception/ada_feeding_perception/food_on_fork_train_test.py +++ b/ada_feeding_perception/ada_feeding_perception/food_on_fork_train_test.py @@ -15,8 +15,15 @@ from typing import Any, Dict, List, Optional, Tuple # Third-party imports +from builtin_interfaces.msg import Time import cv2 from cv_bridge import CvBridge +from geometry_msgs.msg import ( + Quaternion, + Transform, + TransformStamped, + Vector3, +) import numpy as np import numpy.typing as npt import pandas as pd @@ -28,6 +35,8 @@ confusion_matrix, ) from sklearn.model_selection import train_test_split +from std_msgs.msg import Header +from tf2_ros.buffer import Buffer # Local imports from ada_feeding.helpers import import_from_string @@ -259,11 +268,19 @@ def read_args() -> argparse.Namespace: "until the visualization window is closed." ), ) + parser.add_argument( + "--viz-fit-save-dir", + default=None, + help=( + "If set, visualize the fit of the model and save the images to this directory." + ), + ) return parser.parse_args() def load_data( + models: Dict[str, FoodOnForkDetector], data_dir: str, depth_topic: str, color_topic: str, @@ -284,6 +301,9 @@ def load_data( Parameters ---------- + models: dict + A dictionary where keys are the model ID and values are the model instances. + This is necessary to get the transforms that each model is looking for. data_dir: str The directory containing the training and testing data. The path should be relative to **this file's** location. This directory should have two @@ -321,6 +341,8 @@ def load_data( The depth images to predict on. y: npt.NDArray[int] The labels for whether there is food on the fork. + t: dict + For each model, the requested transforms. camera_info: CameraInfo The camera info for the depth images. We assume it is static across all depth images. @@ -349,10 +371,23 @@ def load_data( absolute_data_dir = os.path.join(os.path.dirname(__file__), data_dir) + # Initialize the data w = crop_bottom_right[0] - crop_top_left[0] h = crop_bottom_right[1] - crop_top_left[1] X = np.zeros((0, h, w), dtype=np.uint16) y = np.zeros(0, dtype=int) + tf_buffer = Buffer() + model_to_frames = { + model_id: model.transform_frames for model_id, model in models.items() + } + t = { + model_id: np.zeros((0, len(frames), 4, 4), dtype=float) + for model_id, frames in model_to_frames.items() + } + all_frames = [] + for model in models.values(): + all_frames.extend(model.transform_frames) + all_frames = list(set(all_frames)) # Load the metadata metadata = pd.read_csv(os.path.join(absolute_data_dir, "bags_metadata.csv")) @@ -368,10 +403,26 @@ def load_data( (time_from_start, food_on_fork, arm_moving) ) + # Sort the rosbag names in chronological order based on the first message. + # This is necessary so the latest transform is accurate. + rosbag_name_to_first_timestamp = {} + for rosbag_name in bagname_to_annotations: + with Reader(os.path.join(absolute_data_dir, rosbag_name)) as reader: + for connection, timestamp, _ in reader.messages(): + rosbag_name_to_first_timestamp[rosbag_name] = timestamp + break + sorted_rosbag_names = [ + k + for k, _ in sorted( + rosbag_name_to_first_timestamp.items(), key=lambda item: item[1] + ) + ] + # Load the data camera_info = None num_images_no_points = 0 - for rosbag_name, annotations in bagname_to_annotations.items(): + for rosbag_name in sorted_rosbag_names: + annotations = bagname_to_annotations[rosbag_name] if (len(rosbags_select) > 0 and rosbag_name not in rosbags_select) or ( len(rosbags_skip) > 0 and rosbag_name in rosbags_skip ): @@ -390,6 +441,13 @@ def load_data( j = y.shape[0] X = np.concatenate((X, np.zeros((depth_msg_count, h, w), dtype=np.uint16))) y = np.concatenate((y, np.zeros(depth_msg_count, dtype=int))) + for model_id in t: + t[model_id] = np.concatenate( + ( + t[model_id], + np.zeros((depth_msg_count, len(all_frames), 4, 4), dtype=float), + ) + ) start_time = None for connection, timestamp, rawdata in reader.messages(): @@ -430,6 +488,17 @@ def load_data( num_images_no_points += 1 X[j, :, :] = img y[j] = label + # Get the latest transform + transforms = FoodOnForkDetector.get_transforms( + all_frames, + tf_buffer, + ) + for model, frames in model_to_frames.items(): + frames_i = [all_frames.index(frame) for frame in frames] + t[model][j, :, :, :] = np.array( + [transforms[frame_i] for frame_i in frames_i], + dtype=float, + ).reshape((len(frames), 4, 4)) j += 1 # Camera Info elif connection.topic == camera_info_topic and camera_info is None: @@ -451,14 +520,49 @@ def load_data( ) cv2.imshow("RGB Image", img) cv2.waitKey(1) + # TF Topics + elif connection.topic in {"/tf", "/tf_static"}: + msg = deserialize_cdr(rawdata, connection.msgtype) + for transform in msg.transforms: + transform = TransformStamped( + header=Header( + stamp=Time( + sec=transform.header.stamp.sec, + nanosec=transform.header.stamp.nanosec, + ), + frame_id=transform.header.frame_id, + ), + child_frame_id=transform.child_frame_id, + transform=Transform( + translation=Vector3( + x=transform.transform.translation.x, + y=transform.transform.translation.y, + z=transform.transform.translation.z, + ), + rotation=Quaternion( + x=transform.transform.rotation.x, + y=transform.transform.rotation.y, + z=transform.transform.rotation.z, + w=transform.transform.rotation.w, + ), + ), + ) + if connection.topic == "/tf": + tf_buffer.set_transform(transform, "default_authority") + else: + tf_buffer.set_transform_static( + transform, "default_authority" + ) # Truncate extra all-zero rows on the end of Z and y print(f"Proportion of img with no pixels: {num_images_no_points/j}") X = X[:j] y = y[:j] + for model_id in t: + t[model_id] = t[model_id][:j] print(f"Done loading data. {X.shape[0]} depth images loaded.") - return X, y, camera_info + return X, y, t, camera_info def load_models( @@ -514,7 +618,12 @@ def load_models( def train_models( - models: Dict[str, Any], X: npt.NDArray, y: npt.NDArray, model_dir: str + models: Dict[str, Any], + X: npt.NDArray, + y: npt.NDArray, + t: Dict[str, npt.NDArray], + model_dir: str, + viz_fit_save_dir: Optional[str] = None, ) -> None: """ Train the models on the training data. @@ -527,15 +636,21 @@ def train_models( The depth images to train on. y: npt.NDArray The labels for the depth images. + t: dict + For each model, the requested transforms. model_dir: str The directory to save the trained model to. The path should be relative to **this file's** location. + viz_fit_save_dir: str, optional + If set, visualize the fit of the model and save the images to this directory. """ + # pylint: disable=too-many-arguments + # This is okay. absolute_model_dir = os.path.join(os.path.dirname(__file__), model_dir) for model_id, model in models.items(): print(f"Training model {model_id}...") - model.fit(X, y) + model.fit(X, y, t[model_id], viz_fit_save_dir) save_path = model.save(os.path.join(absolute_model_dir, model_id)) print(f"Done. Saved to '{save_path}'.") @@ -546,6 +661,8 @@ def evaluate_models( test_X: npt.NDArray, train_y: npt.NDArray, test_y: npt.NDArray, + train_t: Dict[str, npt.NDArray], + test_t: Dict[str, npt.NDArray], model_dir: str, output_dir: str, lower_thresh: float, @@ -564,6 +681,8 @@ def evaluate_models( The depth images to test on. train_y, test_Y: npt.NDArray The labels for the depth images. + train_t, test_t: dict + For each model, the requested transforms. model_dir: str The directory to load the trained model from. The path should be relative to **this file's** location. @@ -613,17 +732,18 @@ def evaluate_models( print("Done.") results_txt += f"Model {model_id} from {load_path}:\n" - for label, (X, y) in [ - ("train", (train_X, train_y)), - ("test", (test_X, test_y)), + for label, (X, y, t) in [ + ("train", (train_X, train_y, train_t[model_id])), + ("test", (test_X, test_y, test_t[model_id])), ]: if max_eval_n is not None: X = X[:max_eval_n] y = y[:max_eval_n] + t = t[:max_eval_n] print(f"Evaluating model {model_id} on {label} dataset...") - y_pred_proba, y_pred_statuses = model.predict_proba(X) + y_pred_proba, y_pred_statuses = model.predict_proba(X, t) y_pred, _ = model.predict( - X, lower_thresh, upper_thresh, y_pred_proba, y_pred_statuses + X, t, lower_thresh, upper_thresh, y_pred_proba, y_pred_statuses ) for i in range(y_pred_proba.shape[0]): results_df.append( @@ -644,7 +764,7 @@ def evaluate_models( for i in range(y_pred_proba.shape[0]): if y[i] != y_pred[i]: print(f"Mispredicted: y_true: {y[i]}, y_pred: {y_pred[i]}") - model.visualize_img(X[i]) + model.visualize_img(X[i], t[i]) # Compute the summary statistics txt = textwrap.indent(f"Results on {label} dataset:\n", " " * 4) @@ -686,13 +806,32 @@ def main() -> None: """ Train and test a FoodOnForkDetector as configured by the command line arguments. """ + # pylint: disable=too-many-locals + # This is fine since it is the main function. + # Load the arguments args = read_args() + # Load the models + print("*" * 80) + print(f"Timestamp: {time.strftime('%Y-%m-%d %H:%M:%S')}") + if args.seed is None: + seed = int(time.time()) + else: + seed = args.seed + models = load_models( + args.model_classes, + args.model_kwargs, + seed, + args.crop_top_left, + args.crop_bottom_right, + ) + # Load the dataset print("*" * 80) print(f"Timestamp: {time.strftime('%Y-%m-%d %H:%M:%S')}") - X, y, camera_info = load_data( + X, y, t, camera_info = load_data( + models, args.data_dir, args.depth_topic, args.color_topic, @@ -708,38 +847,36 @@ def main() -> None: args.spatial_num_pixels, viz=args.viz_rosbags, ) + for _, model in models.items(): + model.camera_info = camera_info # Do a train-test split of the dataset print("*" * 80) print(f"Timestamp: {time.strftime('%Y-%m-%d %H:%M:%S')}") print("Splitting the dataset...") - if args.seed is None: - seed = int(time.time()) - else: - seed = args.seed - train_X, test_X, train_y, test_y = train_test_split( - X, y, train_size=args.train_set_size, random_state=seed + model_ids = list(models.keys()) + split_data = train_test_split( + X, + y, + *[t[model_id] for model_id in model_ids], + train_size=args.train_set_size, + random_state=seed, ) + train_X = split_data[0] + test_X = split_data[1] + train_y = split_data[2] + test_y = split_data[3] + train_t = {model_id: split_data[i * 2 + 4] for i, model_id in enumerate(model_ids)} + test_t = {model_id: split_data[i * 2 + 5] for i, model_id in enumerate(model_ids)} print(f"Done. Train size: {train_X.shape[0]}, Test size: {test_X.shape[0]}") - # Load the models - print("*" * 80) - print(f"Timestamp: {time.strftime('%Y-%m-%d %H:%M:%S')}") - models = load_models( - args.model_classes, - args.model_kwargs, - seed, - args.crop_top_left, - args.crop_bottom_right, - ) - for _, model in models.items(): - model.camera_info = camera_info - # Train the model if not args.no_train: print("*" * 80) print(f"Timestamp: {time.strftime('%Y-%m-%d %H:%M:%S')}") - train_models(models, train_X, train_y, args.model_dir) + train_models( + models, train_X, train_y, train_t, args.model_dir, args.viz_fit_save_dir + ) # Evaluate the model print("*" * 80) @@ -750,6 +887,8 @@ def main() -> None: test_X, train_y, test_y, + train_t, + test_t, args.model_dir, args.output_dir, args.lower_thresh, diff --git a/ada_feeding_perception/ada_feeding_perception/helpers.py b/ada_feeding_perception/ada_feeding_perception/helpers.py index 6e334ad2..05389a10 100644 --- a/ada_feeding_perception/ada_feeding_perception/helpers.py +++ b/ada_feeding_perception/ada_feeding_perception/helpers.py @@ -155,6 +155,7 @@ def depth_img_to_pointcloud( c_x: float, c_y: float, unit_conversion: float = 1000.0, + transform: Optional[npt.NDArray] = None, ) -> npt.NDArray: """ Converts a depth image to a point cloud. @@ -176,6 +177,8 @@ def depth_img_to_pointcloud( camera model. unit_conversion: The depth values are divided by this constant. Defaults to 1000, as RealSense returns depth in mm, but we want the pointcloud in m. + transform: An optional transform to apply to the point cloud. If set, this should + be a 4x4 matrix. Returns ------- @@ -204,6 +207,11 @@ def depth_img_to_pointcloud( pointcloud[:, 1] = np.multiply(pixel_coords[0] - c_y, np.divide(depth_values, f_y)) pointcloud[:, 2] = depth_values + # Apply the transform if it exists + if transform is not None: + pointcloud = np.hstack((pointcloud, np.ones((pointcloud.shape[0], 1)))) + pointcloud = np.dot(transform, pointcloud.T).T[:, :3] + return pointcloud diff --git a/ada_feeding_perception/config/food_on_fork_detection.yaml b/ada_feeding_perception/config/food_on_fork_detection.yaml index 2a86fac6..82fc4126 100644 --- a/ada_feeding_perception/config/food_on_fork_detection.yaml +++ b/ada_feeding_perception/config/food_on_fork_detection.yaml @@ -31,4 +31,4 @@ food_on_fork_detection: viz: True # The upper and lower thresholds for the visualization to say there is(n't) food-on-fork viz_lower_thresh: 0.25 - viz_upper_thresh: 0.75 \ No newline at end of file + viz_upper_thresh: 0.75 diff --git a/ada_feeding_perception/model/distance_no_fof_detector_with_filters.npz b/ada_feeding_perception/model/distance_no_fof_detector_with_filters.npz index ba4cbe12d3a248767fb4196c36ac332d5d0c61b0..70a91b3d0c7bf3d00d76f095916a86d1ce157d8b 100644 GIT binary patch literal 51525 zcmV(-K-|AjO9KQH000080000X04QmaW5C1!007zm01*Hb0B&zzW^ZO+aBpdDbaO6l zaCrd$5C8z$00000006+m00000005lZ`9G9h8vyXBl%>UzvX*I4v}j0@^o!M8T-zth)PW%OJYQ!r<}2sP==6HnuN4Z+O+At{0r~%OP}ZaInI6VGv{23rc)+X z#uVEngm6O4b~pDB*Wm3M#O<0M>f3h_w|fKzhXy+bI0Xi~xi7k|vtNiic!-xX%^m(< zL1nKBX%}&?;x1ww@&EfzNMyZ&CduMMs~(A&K@-gCw1G=+?b!C#u+9sw_qto;hkY7@J< z@GKDV{^;Gh-AKoT;66X6n@*S=aUkKm>m3d*VttnGh*#>hq zDYoYRrDJ+W?E7%=v6qvVRcvX9b$dhjxz$OS-rUb+J@m#Ltsjc^cRUgG*Yb_2YmzWQ zs0{Uh6NbI+Z#ULM?66UP8xa^^XZrU$INMg#d2ppWW-H~puUiY_uM9~Y8UWuSqoQ)! z0a5tcgem{4hni>Ve-uKO_>p+QMi*_|pBmrNPOk z^NBWgdWbAO6n^?Z3MLGioV5gJRqGk*2)JYNgRB5EP4J$=gb zqf|_o$vMF_^T!0Fr0exc9g{YxZ;>@k#q_4~d(!6qm|3E5?EPjN%ylI8EvLYE{+Mkl z;2E8Q$GeVe-~JiA~`2hh%-l%}$sXv*OUna+rtMxSb8o$$n64kl=+Wjk78-72vY_ zANGNhSwX~KOG6Mf`r7T+*V8efxjgQLYA7aXs;Re0_#;k3{&h}cIwm(NY<&k#m&n|c zq3DK4Z-S~?o51U9d%uHor<;w-!>tj6XnEoCjdV=EN(x%K55_;)5Vayg1#vF#cx>I9 zfyvw3EJJ!jF}Xs1#xl+Tlg3v)Kz-m_w13BgGiCf!*2_3yhUljbh5igom%Do@3!HlW zl|g%q7bYAVY!Q8sf!Q(!`bFS0-=6B@zzvkAstsylL_-q#{D{Ew3HR!99Amxq{RG zg#DFnF+s$pqFS*P;QQRW0>B9ePS52=ZNbc|&x5{5Wnuckkx>6Om|xhZ`o|$l%zoB- zbP_S4OIH!-?>$t)db5|Gr?34k2vWArc&dcw|?H_#MoCY7NmCeHJs;kBfaPs@3 zkNCdAdAr-a94lsHa_KVeev4?#X*Ou(+4vxO*ShszDOs3sVr}p@nRraJT(V#NvR&DjP`2`|CCtNJwf>d-UNc0pFZ(&`mW|oj zGAX&Ncub%?-mi(5U_yFSHpd-&_n>46I5+Xs6)975%xN&)(Bc6;kan#coVB&-hOB@K zW<8Uyzvu}bq^ZpUr)F#{uAPNA!T*Px?ghSfZuGy!dDhjG-|i1UB6~md_l4$QvfEtb z=c5UjcpY`@dhd?74xNsTVc;vOR{sSb-`FykwkH))zulk=R^(u&`LwbgClT{aOqWXh zOhP=VG*Ziz98ApZ|6v49DqZVS)j>yeEo+gBl{uJxuknsKcvDM~U$A5x5^>$eORdVm zgr(<_ZNNqLPw<_-8i|34N4g)8<`#j#QVTOoY_bAoO zTsT)&R{2jL{~R^Cc4&ftc|w{iWwXEqR=zz8PFFG?szT0 z6?Dd&l6*%J3!WR?Q<%BxA(dz4Y_o(K@xEDQT&Q=`2}s zcXcjirr1kA+L4CGntXcWEs_y4>KU*p1Gr-S{R(hyW2Ky=XcQv3c(R&5!u$_5XI};9iO^k@v}lNZ z;rGfE9;|bn(3NG0t(~%8;e9K{);SH7(n*_?;T6SjADCrl&pX>_1~{44V&fR% zh8ekOcHS%UF;{wwTUh}6ww5cduj`LFS1FmM{P~#OW_bA;xa8C1+2U0pnAj`byiXt> zGhMK2Blttdu5qcpG{jNPbZRh$`E4h~?lCj4?l!}3JtZlKaYRqC$OP8U3Fzww=US{C zVnsP2LUu=#v1&f1E1qOhry(MgrF~P`2hSBguBZ%7xW1cVa$`3p{AUm( zsg{q48;;MYfwMnv99c4Agqi(AiakOM%pU5<@PC?u=k&Jkd+n8k=&9^lD@Pc=>v@^d z+YIa_TxVLepN`09;=?tZ@*#eD+pB_iUGpB!S`~{3)tY2ED(r*QcX17HmS%+Do9YO} zy7fzt&l%pAk@Nt8Gy77s^z=dyt-s~bEI6HCI86tf=R9WB!t+C8xhw~>O$^NZ@o0Gq zKjh(4={k0XR(PyavB_!+19SIUjtzo~tm-xF3Ub9`11p1jz{!U#3m=0sO*mi25BcG- zryuql+zRuUSeicvXXw9sIG+-X$6gP7xCTzJw-kN_-lV#9^Uu{8i240Vw^n)h=P%4Hli(hwMA=&t z5)n^w>FNb=;&AKZ*Wla@(Xsq}{z#p_WaqFttkX5lv2t%F<{T`X>0IuPL_{JPx(8rA z)p$WRNN%t@>$6uVG-K;$V=YSvocvPYv%U zrXyCaIKOo>JQx3Yu;FknZrU39?Bm6FM4Sy<^UWAO-_VjG5vOcC<|=mXCOI07eK3>u zG=b+@T{l<{K7W~I8~-v4F~02H_5_@|uWvyHTyoMxQa33G>Hic|F*Jq!TsL)n6F5zK z{F;oe40wb2hnWn+UDYR7+=d*B_5Xvb)|@e;wBy3(=jKr zvV(!?TMDSs;M{v=%`!6fa4rVvap2^$8>EQfB6o9x28TQ_eV8@<37jZeGbj&EstV>` zR~(3`&+`pjI^nq)YFRtMQ*Qn`Y4IfmDL6EnHM_w3mK%qxhJ2!=B(~qLI|;QoG58c+ zVLcz`Hm?OAt5AHJa)yp5F5b;&!Kv!SLz3Wp2a^^w9>t4c4cXZ5IGPPkcttx|20kVe<)1H@f;e`B3xB}LMVAj%gP(tAGiv`l5s~di zfA~kjJ|7#Ntpktz;=BJ?WF#WR1hz=NgZ=T$+rH*eF6K<0O^B8aMLlu)zFFY(hP{v1 zf|JWnD7fDCINMYlgeLnE}o?@}6tZKXCHciX~a#l&_PzHUl2GhtKa~?;wmH_ZOWI z&cd|Od(Y0D4#dpWhJ1&HV1LYh-G2rCHKFW7Yjy^bw7+I-nGNe99k6%##K1$9hBBJY zX~@flZqg0T)GFTN4z6yX+Cg$nK&0A(IU@gHouNgc?tk;~?KfXe^$Eow=2g*|L~!c% z9ywoda%Q8u$MtX|a`iR(0?r)&*-HcOQ3%<;>UG7*Fe4^7-VNm(R2{!9AW4kI6X8pTYS+Ye)(>Gs)4;OJV|i~g?(s~ zIw%cJHO*pK?S#It%qA-AHOwD5gRg7kV8-kfsaK&vm{X;i`Wl>U`!A#goK`JhCo>#| z8FeBBwzDw*0ZD~6@Y7nh;=A^zAi~rJ#RbsRelo+E^;r=;}xF=BD|vu{HX)y{hb>EXDj!#Ds=*#&6;% zSj0zh+t!tVi1yTLYfDm7u|X^(`6G<3b3M;B>d;dzbuo1Ti}mq#u5V@jE1g_JC)+__$-a zaxkJP22=jGcSd*SgX^zM6}opW7!jjn z?~G?aKO3`$&&h{|iKQNcZG0h!BV42%Kc0!n&CNfmox(7C9r3K5j6WjjMXGx~h5Xle z@WKsn^5@_J(cNx{5r0C7@(jElA8iMxmSl@I$5|u7P0g(boJIp6pHBH8|$w8my5ag&jTp?QC?eC9 zCrUp--5y+I)BtrmeXa0{Z7(g6dY!Jyq@nTC5{4C)yx+Gz&yg}rIOr564qnC9zB zD(*p5Kg$o=Wk9_0ZeJp|7&rbI8&3DQVTI-wsZSwpkUt7DgduLwiM(4$bbs8^+M;g! z2Yz1t23iMBICv`~P?d~X{1TxpKj6L$-+rkJ_kwD>hCIyYftmSVw&(r?-@T$UY|))h z**LE`fhiYPonE^J?n}9G*k`yel^$)~4CA}B1D(NHLvGZq}n$BcrKpjOBO9JN_Hp%T?0zW5| zM8BVxfypbp=4-&olV-DrO(70<`iL4`g!@vc(`!r!!i03=mA}omAu>AXEO!ac|7#gV z_eH<%QR|LOAg*i?6ub;|m}vSK4V;XY3ybPPoVOwb5E|iLs7fbE6~XvpWmB?C+%Tu3 zr*rRDxEHcApH3{^m-m8yI2-*D?-{l2@6sHo6HFxOS>c%2WB=tW$qiA(k2K9J1HU%Z zmJLqUa~ipyVvX2_@-+i|i|60k{R}wwy-8yB4}ZilKPSL4h5l5iX8Fdr7|d4a%vKO_ zN8IEHqhbp96WuaJaN_-dUD;+fh;YM#K{o@hdPUv`&PBr)$eaMgy;*N0Q3Cy--1>^2 zYIIC|=6##>$sMs@rcNv@I*%6k51dV1R%LlD5;2!v=@;vVKJn!&zd!VwoLiv{dnyBA zow_;P2XLOOn@>f8)0%fq20!pX6xw>fdk^9KF)rA~gOk0w<^5jUA@1oJ!@2?JAA3{f zQWpE!k+*jQ51V6V>#(e8J@iLM{%*HSq+|L+r*`orE|@k|Q>VrP7q^+S1t+WYmX*Ks z!4%;{^2P@6>Fc+hz#~IH7g!$-MeL~uHAWNAPx&v~9bE@`BjESh*8xWnA!5yr*_Y6F z9A_Ra04Hdf9hKl6!i;khf&-IK|DQ}3Is;Cgd*=06ED9;SU9#>OKio$}3pstbr#-~` zSuWL~P|wfoG!+1UaF=TgPBFbv`vK7qO`u=91DqJ7aoGZ#`CGg6bFC+0NHo~)gE&A~ zSLbRAPTZ_9>$8H2_2)M_#hilpP;PSiusqzSZs&5#Ctlc#pD+9)I90#HN)KG}+GyDE z$S6eYEhP(9!T1-HNiB#EoNS9tMq*)zIGV5!1I~RLf}>6AzgCUXo#-K7u`*Q`Ing#yf~YV*)uO*DCBt|y8g_5 zb!CV%q9!KOi!LzMR>ITA^x!zoeHEx@&_mas;MB}W)YY>$bEhm1$D<6A z{L5@`cF_KoN^p+OIjP2pDCBj3Pj>;FIonCQ2F@O?G7*gpLuBn&HMEDYPA7_DBRI?T zW^$lZ5F#3O2)_a+k3M_Z0#2Sz4?5@XjR=;PLahd1oyOj0+rUMZl|4OPMMY!w^e6Yg z30>dJyB6n9o?ma4V~SebowPJKuuhGnmA&AE%;erLin}ps)8P9<+9xsFQ2!HA3F6{+ z`##@8R+zNAv4#aswAHWO2F_LZ8C#rZ)y@;g*T~|Q6|w|r zo0FJc#Cx^V7QFgufatDJTwKS0SN6n7OugoHSqEH=vgF-cRx+ZfZhB4hhVeI&YzvZe z@ZCU4uSsGe643ZNcM_aicy9F>@Y;>Y!o4gWvC)$SJ|9?5cvJg%@P3EqqPveqqez__ zLJ{C}>jz<%!FlInIA5p25XrD${Tpz$+KgfqxX3f9{M)HPXqMu?+0GZ{k@)xg8aP#r zc22<92US@gQ+fbS{ULF(5uDjnD_NZ9jHveV8psdkc}&u61!ubt?KEYYAxW1dx((oj zmSex#z{zFp;a~JDa7*P_`_C6AAznD%&b74D$lC=oSk2q~xbR%>ccG`id4)S( z)0KQNt+gn70-XCIVs{BR)BVfG;oL}EY}%Fn=OxT9_&B-}ylVgFbH}{m5R(*F`UNN{n{kN?!Fem`viG>gHCw@)fNA-df)c0Isvf+&kv6CpdRjhBYp;)Mf;O4To;a* z1(B)sb1;6(-tXPuu_jwMRu(CUHgfk>I3L7|(>d0^bKD?aP1wHN6@w_33O?`SPsQ|- z=&Hj|4=kjfFXf0QA)^27Wkb@C$6YtPt!Q<}mQw9o8m}fGk%k(F+cJ>%MLJI00hhcg zFfc`lLae&GdoLe@`Fk(q<(c_o1y*j-0ZZu9V@CpQ_P{+KcRRmn#sjZ-xHZyiOCn+{ z4W0F~hk0%WU0eh8cCoFCi&1|ZB9rYI)(-Go0sRGeaBi5P`<;XoLj2!V zB`StXp+4u^T@xJ}IV^uw$~#BR)r zeUSup{%?n)T2SW?cS&tH$csnJ3F?}A$>61HpBw}Kb8>3umxO3U6Wq_NO94ms{jI=7 zoa;5N3Wq~{Tdh)*3jQ*FsWZ6l70chR`BD-6M$OCWQ}A4kZ!@D%N42S3`7fiBj)<+x zSL^iVVY0t;tn*?W^{P^MuXG$@Js)|$vo8-bE0<_{f=~79UzoN_MXXJ$)h_;qdHnna zTnbXK!j#sYo!gTUf&ADt^$)lRm*E9&V3>50J4Z*XzWuMit$;dV()YaPV!hGL(>02X zLu2Ez3tmvqP}5#GXoGhgCC(0|r=nsMlI^*Xfti;qT2Jyr{m?XV=z(Q2DmJt_HV#gx zw+Jr=kKa;y>fWYARD66tzp)(5bK7F?g~i_k%Qp`tKaWGju2S6?oO|DbR|al9$UoNB z2>USIKW}>n=0Ez-WFj^bKP=9h^G`}f)Q?vk`oXFHo#3AWKT2JQ@Ad5b5%C(QVEN{P!H?5J~}5p4Eq+Q zbU3r_#Ot=1a6>Se@e zkT&G0l4P+!d#DFSA*FzGi0cavyn;M+(P`sLaALEKxC=PXsmWqV3goHsgF7r7px!tW z)Z+*DV*SB?4UTC_a$!GhcD<;13Hg0p*;y|QxKCU^di{?V zS}g@#R&q0tub-SNy97SL`m{XyKn79}4>1}5KO z{ljswJ>V+LjV4#0CnFmv;$I9--MD4fL-274wYkpvL^Lb&vtIcJtlz8W=_7DHxpTW( zmn9(j#vzw7aBhQt_7iaXHNBy4E2EL*rmO4L%|re3TkPNqaMs`X+cHMssA@|}PZ~H? zr{(PwxWI?)%Z+(Kh`h}qW*(fF?{N0*;`o+pXa6YpqA>+EC7+**@3qu`2TnhC@I|n# z8Mg6nbtv>diJ4I`F1?VK>88$eioVWRB&5)rKLGOSiPP&ji*>@MqFb51p@`5|uG*=Q zfC(ejIzkQ(Shh4Gb+u6fB4@Pt`P4!lq#n3nw$}=m8-DKC`Z^I2*IUhYv_s#1hc81k z?>N5Iv#nEGAq5f2KfB62hCC(32^yTW#rk^(zmC>J-aL>lTCf4~j>k&P_mJ0$(;M5W zlpsGIW5!9SK;C&~{?QZim%-~5l%{o%AJ_HeH|jwAzw&KQznB+(|Fke8`Woa%+txRw zy3o&BoMpZOS8tstRg#E6q?OmD^3OvbD$RF$2jmf>@Z>84N0JbAQ^Yn}9n@i-OV_<9 z48md~`A)ejAZ|N3J+!TdI+Eev^%h)U#QEgdt#riOTkzoP1~})ZEdJ!cJvFG`Swg)=qiZq{xpL!E(&Bw-`oochdqE#aI;i&D9~1O^6dLnk z{mPFjZ$cgzV)zW#bcX>e@DAVLJ+xoUrd`b_~^yoZr~Ym zm4+jSLJ{jjKm(y98#CqASoUd&(2qD#U(Fj}_Iz|7VKp^$>Zuqb|if3KO0Ve$4?Vklp^hwLE~Crl%H;Tf+F= zRTkyor5m^&el=NXoW`DjpbZFw9f47*QGfD@{9HC6Y^BZBE=ubB!M zzfJS-cX0MgoVZ04=1bnm3a5`;fs{Nef9Sg#Q%584n+^mtv)jZQ0bEq4Y zmXHMuz$29n$m@8#*FxC=$n_#XSI8k+Wz=Y(4 z$!7bM-L0Un-jcg_Cpc5<63rpa3$rpLwwqXk%ZZMwfiqV84if+8k13kpL`xOm-eoK3 zE&J_**={#{!#2AidK>e6jyw4Ev{C05L74R4E;r9scyFPPPD_20G5hR=JC)${$xXr6 zUi%}S?RdA@SEEy zP}hAl>mCWm+@k5=liz(Y)5-qk;2rSd>`xqUYRvl90CoW4x_9MveuL*uSIYYCi@^+u z+R=#@?ugAeD|hufc)CMFI5^ugdA4-H7BT*#HJtnbuDDh=Y0=3JdViwHh&rQtBzhja zuV*|LoNQvGeT4rACW~$uasCPJA0Jo(&iwexz5S>i7Sa6TaqJhkuqs~#IN_;hAuq`T z^E~d)lYWCYyeVca&aX8TL3a(r?1GC~l7GN0F7Cb!PTNI4RCPEKk<5Q8O0R%;nE&MI z@O@bSF9Rd$Ugf{>i|gSA=QMrt!4yKoVV)e!;~1~n0`oAm3pIR>L?Ytof7R|g zpfB)Qdu?rIO^YHsFN*q&Qzbzz}#D|Kd+1? zVS%S9=duEV5i?l0JHHh6&GGTAT5#gp$>^Ozeu&F>G8c9Me5qmVb#M~xR@>qIu834$ zMzp^O>$%c)s0EyUR(?6F#}d&V_?u`m!3|XY-2o?5T=$q-uZY<1_Qxt*f;{!Hg53#D ztGn1fG3yO=u+5Q;i+_)PbDdTctdnaK+GFe-gn2azTb9RXV)Exd%M!rpQ?l223r3iD zgfo+O9h|M)e}e+sg7e}>%k!rp?j^Ws+ckj;NST&_ zw+ug4j#?9iXw83qs@;LU?C5wc*(VvRFYB`4tAIQ>a(DZNHt<>F0A27NWmZ`JK^h`_ zWmql4S(uvBzQ+ih;H`e^=!_rqOnHe$iB5W9-e$axilpcQWB+ zD(1wwINY1?#Ed61O~!&y$8X_YOa=c_eLBrWGa3;Sui9O)hIvkL#63U5IeMd_v*URf zV&u4nWF3d~gudzV11BpCE}M%BLWE+O>;M~hFUzHI!QkwN6Dc8wd=Rbd(PeX6m`7Dc zITD;;EVFc3f-~aQW#3Xe0iUn9>U7+que;RFvNJ`LXr@;b^y$=}mb-M;!2P~(s{VcN z2299tRB>GF(`hfK48VyC9pCqPT3~jm>>usLKIFB3DFvM5tXnV<>4ItXM8|i7DR`gOEE(vkFeg&-ca}7SX+KY1I`^?{ULtSro{}}J-NaM zo?E!frWTw&K2qSW>5FNfEsni5$i>W7FQt~_8JObu{M0ZZ7?YNXt?f6=#Z=O_nLFUr zfdR*GSIE!eoM$YfTuiP^yx0l;=c~)#OUq*rFV%PTjV4%+o%=JLV|h68^yUH0YvG8S zBGG>42CRS0nRG*Nc4bA2WV;8V9j;{z7Uf`~##WzPj~vWi#eed9Nn{#6=a5a3KDa3k-3fhX zS_LEaw#hfoI^gpdb)ts+liq*@G zxV~#zVBlC7W-L`amYtP{iIHk^Yru^puIbD8#vrED(UC{*b1-d4afa^5zyh9s%jDKa zAhOuo(HkG&{ka*f$>2RVjsI7e{~;N%-rsUC3l#nv%jaYIb>jIkEx!v0nT@1k$X$7KDj zgZ%?;5QjD@Pj=*EX1sH&=V4fv_g%72x<6)(a*Db;^D(t&g||QW`yuV{A-@>Jwhqwz zvMe7{?&8G%Oq3@%biffJV~g_PgmUcs++J?#ia1pQm6d3io2Xgk;} zfRoeAelvxSBaU+IQ3rv1EaD$Mw4xIBQ{3?K{f}yhw!>T(3Bq$@o>T~ebC+2Z+0Hs* zf}n1K<%fLC9a3#k^UKFP?V9aBwt8VM|D4MHkNKFG=HaRdPBMIZ-)|7sxo>Hv+b&pV zw}kMj+XYzCu&-`BAp#K{XKy0(Yl8i6Z2NwHLkPAheAATq3EuPAGCsY< z?_YK1*A+)aVBVPy&)?w8Q&o*d;OxE(R?{0B)YDzW*9CnsZ|A>+16+9S?!6)nxmt+V z=25G<_Ml1M(E{*yt0dE5KAv8+(FIvg%u?8In*>hz>HBW+ z`H=@XUb*d|m{W12gUVNcsZZZVSO3k&^XEj)%t=LI{R%1BA#i4%?6&&F???5<61Zxy zXpE6`I9G{*Io;w4Z@!+y?C6gH&9f0`EX|bh7o2&B@Z%l$*beIRyt5&Q8!P+5e-8uG zZoKRM2+q4vcBa2L0L=!!**yVH-u?LWXK>Q`^w5|;?uh4gGuDIz=ewfA^(#2{{qSW= z_6aoanB3O}&XuiG`2kKpvA@+#_z0S}q)6{khUcCxS@LUfJqmhDUuqq}q*ToZ%gSN? z`{8kpeBh@qerTCKfoX>xGM#DQUCz1|zC` z$`AWvP}f;!%qfDuUq&-p`6vTXOZoNPZ6Keue<4UAZ(J51thA1z;T{5)=4=4^I zfgcr}SKVNhg2?hyzYmyr@o_7j;x8swq355nereel!;pAU!Y6A+is6P6GJd8jCO zM$pd(Gg_nD+#ACYJEL6DG6cr+{=26RK6`g*WyHQ<#OgnptQ895&r{VY;6?7^3m@UV zSVz|n>n20q?hVha`nqnosSP7Sodpu7^ zTx$~lT{hGedN*}Sb_V0Q4K=5>GE))bv}ApKJ2-9Aw{q|)uVh`Z;5bC;eV{aY9_oR; zrBesH{jhrY$~{}ZLVvX8b_Tl?^7V_uRuGlD?bvis`{3dlg3c-1_`1%C$$n(|GSHYQf+Mb2aLJ_H0?)UR? z7|$Pd|0cMCl-&~%7aHP@@R!|t3i*{Z71;sK`6r_m^W6incIVmiZa^LsknPa zD);E$ilboauYjo=z0rs^R2yk^4eHuZxib1*E8K51uM~7A4bl0pKA1X7Xq@v@zJfxug-mo zLEOYTxi#YOzFPgx9dZ$P*j!)@M=TwYe;4kyK9-9KuGE|Tu`$^3XLaZ~&2&UL_9g#3 z9em~tWz&-cyq?Xxdefbb2v&vB{7$eBD}*jjib9`z!+bT9k&Z<8jtI2=f;ypRezikE z3hr?oos6GON0MQEJjI#-;0&@ zL6|JFU+Tv+}cn)vq5V$&J!5ZT*`Z=hF;Kf4@({SUwfMeXY8#R6PT6-gi?g zXBn7ip7`=3dA{132MLPxaC* z3|#){V1utv3MyXMxYjA905dwA6PAN}VHxQI6NyM<;j149oOJ$|rNH9%tXhum93Bcq zR95r-we#@#j)XV9z3heQ4xYu_>6n#c}*oXfQ6)w=mj2pM=;KM)!)P zz~}YG{eYHcB9`Qx&!E;PA`+?R&nZW!8#itZ(PYJA%Q`+{)W>)vVs{}g#tEGLgkK+= zoP5sk>@#mnKJnt5aty5FN9TSz_~p$^ua^G8K1w~$~Zz!Ld+`}OX-5pZ|e!%)O+ZS zUF7c`Te6IfC{wf=Zz1T zcSeO^qP|_*RxR+r_|W^?{IKNJ{wuP#(~wAsGCNHN`ckWLS9vpk{7mqP(|CLeVvkCB z(R87Ytz>m*f{R!y+h_cSy6y>2`iU8guiHLFHTTCiB|Ey_O{XEwnTU|5sn8E|qGSgI zLvUnb?oIcI5X_jdzDM;;!}NkU(e3d8m^`t^G&3p^<{M7GpqY*d7hB@OUVC7^(j6gh zH)SI7)lBxC;xx>*_;+35VhHXK8V(q!NkJmgCbjuz(=fq^pFjq`++Owma9|RmnUO9> zo=byzH2aDn`0Vkei2rj0rhmB|G8+r?hdt8zP#uWH@-;U+oPjvAoBA{88sy)BoT3ud zP+Zq|t4Lmzj#!UYJl(~D@m-Qxx4~)ERaY;D!M>%MbIvm$E}hUi-T`rmy0)UPe{&|{ zl7n?E*%_E^F1Gv2{ZPzJ*r0m&Qv@cQY>C}^1^QCMH~tlbAl#+x5jt&G;2PyaV&L|~R-v{i{HN`lbN_29+#7NWa8LO-aSTfh8!7ACLXq8YsSz1B)~#h4GUZ=|MF>Hyrw zXI`3?yMi(0tz7dz&sae#YX~8gORiR+|r=!I<5Vw>;h&#>;kW30wR=;rHnY$)o-_G!wBmY*=VYfae~W{BIrPg(|U*O+im$Fr{yEC7)hC z^tWbl8x12d^_{%S$oWh}@%GQRhCIt887w~naYp@$+>#w0!I)v{CJ-14<1@XE*;U43 z{fz0Dr%%E$i%vE=9tVAm?efB#Y+pU?+xO*J|W`H0Hv+LuTP$NCohCo^53 zE?v0UeYFqf@w#&Hz9Fn%F6x-%5Y+R9`ZYF#ahQ}~9{YT$GiK}k*x42h^WQEMtAu!~ zekM?17Dr>2;42N0_fYrhQu*fACF0ueQ!}rKIfx9P??cnsb z_)ZKSnc~bVQOZW7=JtyZRpGg6xi3TZX2R$2Lv(b+3scBL*8|E6FuQ#2%`2!wh#|tS zorY;R(zN;hOK_&X$JICBjH6q+hYy9}V#o7b%L`W!-Pt`XZvf`40R#8WU_@ujIRGgIVWxsZBVzAOc5e;?x`P2GR!= zaJFC68on-b#67<9q}Mxeq3DOs;Dn>9Yr``I5%=uF?nHQ-TGZ&nAcob{^}vb+x6y!*Lp*-g7j}&)5}qq zq~Z7c%q!@RPQHlTNDaeYwPub!Qt_A(Wb%kU1)k?Bw*#EHDtP3`L^!5i+R+`m5#sH! z>5NK}@0IQZ%v|=$$e0Lm`1QuFHgImWVm-?n z>Uy=-rMV=Cdkr!Rc^1)FeWiaq{aH9BDG_@7k3#)_GrKN#HX7@HQ2D7$f&1(9Y^Ajh zc&dU?3AoL`e8{WL1WaYLm}=>QTXw%G2hX7HAwQc8!t|S`&2QyGJ$&k==KaO*|G(RP zIlv?ai@a}Gqvs28@5{rW1Tm;@`Nvg`n1^G^7Nhce%sk8#m43csKOK*y*sM8?!Z1hv zVc9U$rOblrF>|O(DeS(T@^2x|m{@xMs9pT`Q)Wxz&C>C#kI#9Fz0sK3^!|L`Yys4{ z%FjBX?iKl^)oNoLg+zh}HtqO9$Mj^T# zL>oA75>neu41#cvwPklg6@0!*Z32R}NtnI1^nopSMuVV^)b%LD`z=6raDloDw+J72 z5rp;S8p#V9VTii--9BB{WX%3g^X5@-&SL=)=AJN2%jqh!Npj5Tfr%RZb*)9fO__KMoLB^oM&Oxk9)v}G|5^=_AdUr`;Asb8Bkw! zEf<-CddcmzVx;dU=wHGJh6$PA?97{g!HHInLMV|Dh;nU`?3I-Y@p-j_pb(t@f&Gn_ zn`xMPadf))B-CSP8}HhCkW9WwA<5q!R6OA27_~#cvK`s zcq8UQDbuD8{A&Xx9-Mt>yk3q$MeIG%Q{;YFPnXHZOmOndfj4uPO%RuAt)Tb-{M5Vb zLU2O$aHH$nEl@A1_=!FQcgaw^1Ww<5Q$Q*p7}KoFVy+KDJ$d2x#eqea&S=cmx5V_! zDCN1A5C=TxpIrPGfvJP0163=bF1}?IHa-ciRv2*=oL=~}YvmVT%zmfb+VKE6K*qlc ze7VZHW^iua&&RXea7-|HOFlIX^<=p(__n2#)k*NBb%?-vnL`DQ{=%l{3<7fLm6yA3fOicgtod6& zN9+XQv?2wFSKF$R@mwsf3hCW>y)hOsYo;aQ6~TKPB>TX5!qj7%AB7+?;p9Q%o#3nP zAD#qfrk?p)qF{zdMgLkOpkHEl9_AeqTBp+x$coh6V z%ko>`V>z}O)R`bmtrND`q67Za|7*=>!tIQ zeG#=Lg6~E|CMMd{oV5mLQ6Cr#9(O^!hk8@zA~P}bWC7J4oVk~8_dP3!lQQ?pNj6X? z`?4j>W#chb#NtrRKXXKA2<#Zi%EDB++Ej1oLkVX^-V1h$BgP22d^YWGv!u|t0aK$lBo;_r>rzSw&^qUm5pjo-}Yr==8l!2%bJq$E}gWd2a$1z zIYZ17j>ZRx;5J<)oBcYYF>mGJ@XY+h?~xjL za3TJ;q&|F8(;Ei)_4uFvadhY5Pz$aR?SVEE|Ln&*9R3e=zg;I>HSu*yWvG0tX zu?>|JYN#Z{WQ!JOlF*{2g(PW8Nu@~rN(%3H-oJXDPxm=<=G=R~%eZr9M;G+P5m${X zpxs&-4^mLi}%h9I_qazkdJdj=l6$#QoABW2K#oS$n^GuNBF{>@vS2 z-_4T|b1v}x4xL;~Z%-h~gVPD~lI@``h^e?Uby^a}pK=mdqz?DruXpKdTg(u1=iK~@ zHBcwdIpL+?1oOe@RbMqR)ADxgEh(tmS31Y9;(I7>p?Z5P#I2;Ekb!)NI}iOEJW}w@ z_`Hn@yAlx-ef0jlhu;@W%p}@n;p&y8M-yJgAhP8}?cu#JPHyzoH1Lu$)%mX?BM`ye z{V&HT5Ay_;_%Xogs;zf+N`@d#xZ>T5`(S-y3YD1PJX+>=Eq7l;%XpK|*bnoZl7Dp) zoReSaI8jbTq>^&`VB!#=sbSWI(Z;Q1WIl>+4 z*Zi;BR3Oi4IjCO&r_4A!v)vPb$>v9VWmWSrb(h0#F1)TJ?K%^n5;VriL zn0QAzV2%a-Zt+fs9!GhI56>@3*unhuFK!g9$igh=zzQR(6`a4K;2CfZTl=*Tc!}g{ z+0ic$SGOt*AJ;FybgJDcs}6Wy_TrN(H$q+5aDI2QF!UGkI@3k3(r|Q@NX6E(a2}(x zG=`F(fBCsG`Tj!&W`3x1`MWz75z@%}I_NO|^NriM;B6bt*57#(foKIYj+MzU&lbZ^ z{osS{pN1Lq5X3vf4$DY^^*m`?{tA3*zvzyOd;Jil$|uJ!6~>7OwtNdt>N0EAO>;$@ ztHkr>Y5ebVWi9y#&Px+>&&q)~d28^xPCAUUy`p^roWK!~xMAM6o7KyFDwP4}SL%A; zG`N_G@ssK>H_Sq-eq8g0_q&SK;`ccVlUAsEPw4q$isk*AWj+O%nyL{*16TQ#Ilp!x z1jDOjB>NU%@@(6tNN{e>_b5@Q8wVGT`yN+@ekaO0`x}4%iYws{Wv(UR!IhDlmu`Z( zE6v*YC-}Q+v!5xiQju5?w1KrSPw{&$yJm86F44WD^hz=!g+CvXzxbM3T-tQ5qFyH2uC!(1^nM`v~noOP;^M+E0KK2Cf^jl@|`3F)j| z&>z`sUU&ih7jHx7fdq&r)K_mli5tRseAsmDHFy^FmrX%rG@@V17wowK>pn-qqTKNYg$UO! z=!SGazbw4j%#443NA(U_$~z&_P1`fp80KmBaF)V%U!mWcPWut{wh%#&1MjOMq{bGU zcJI1dCdm&|6h+c~kHC8B6`ecal7mZ>@pN1itpDcE%vazn=~^ob@aQq3Zu39{?$zin zJ8T8-cjnGA8*nCX`F*l7)Yb82wbNbDN2@3?Q9?E@sjSzJc1=Q5as4e${LgRGBbo#Q z3b5SXpj8sf;}CiE*xTJ>1(>+=(y`^>^eU@V&M$pD6RB;k;tl;?W~YTQ1LB9qI>HwX zd(4bkvFHpqhwHsy2F@IR{6b_~EcOw)apBGo%=7g5?gZ#VX_vLvnVd+(M3GbMZLeUS zF*jpV!71Z!7)gr)5Y2vZ`vvIViT59pA2h>yY-ou;c z`;iT@w_^ung0o1ZQv=`x`yrcU(_2ulZASMDIB(Q-?=UzgFt_Z|QZuY)>qPX6hw)Dx z|N55y_ebTOB1a#3;K70&7FFM1{MNP$2G1Z~8ox^Tl^Td?MPdTdlW;uYnDriTNMec1g7IQ_NCLf*P4G`|1bk=Z;ZW@dy@!Y28D$BS_&>Iy}Adqb`K z^O<<+#M2Ft{J(SlDe~8R6M(XI@3$TXr<~XR9Su%By;W)ZHV-tYFKu(U0N&SC=KVPS z-#*@A>xiNHXYyu&SZHaIH9vDZr6$(h_PcfPLqQ=;Pki~r^*_1 z5be?5cd6?jA1S{#6(U0Y{Cr?wx$8m9T{1ElAOrV_lFy_BII-#Ozo}I&m~6;-WFrgr z!}^Jn3Vfdz&8!di!L0DguHACrGPGUl-~^5ITUzV%5#h=i8&^+=hxJz9w?f}Xj}7?! zgK3P3Bax>Mc!4KOb15v_@O)vGjMLz^teEnH>Q%c6lHwCW!3K6 z@{i|qJlM9!5>Y)={v=(2>!ZTtxM?!P{kG)&iL(nGYdWx5*neH{t4M^(>BLU83pnEPG~@!eSDyUxNh%#WcI*yx$$@B(}U5N6Ru_P{>VYNzq*eJ?gb~t z`Hp~71*i2!mbhT%lWOY;aE{!9=x1>9rcKJqAwHO}Jm+A)5#0alQd|E6U!^dgS#BSX zsAj`xJQU8?ir6D>tK#v@E@CoJki4z*^%JJUwcKt3C~ipO6=_s zVUOzZkSLhv8itoFc+HW8WZk|L#8q_LdaVkMPd=+G57$peyGORzNjhR3(z|>168Mon zlS<%adrm06Y=^!qO2jUs8hnHGbro=qs0*p^Ks2IMz8?>~4F0n|Z43DLYgKgMWf&s% zU5~Y?0l&N4LYM!&?Ct%Up4;>hSx!&m@_x8JWoM;ib|qkP#6I*g#TavSH<`;DgMTh= zRtD#Fwlj3ZoH6yVB&`sf-oEvSHu(6w#Gx0YbR?#E%k2J382><$g)`J?;vIXWeP&Y- z%Q8>>>JY4dn%5e4aAMGWN!PO=G$Xgu>*_HWU$`kR_5mGJSDa|o{o#pxbT(=!yMT`f z+tb0Pd-Q~TyXc5_dMGU-67CnVWPKX{^IMU=#vif?NTsgx=Qudo%!d#O&dgOYThkDY zXdN{kPEima(=EE=z*#W~m3=A>h&#UUqL%-6#!c6XyVoRRvWMjj$H!!(H~*QX@QMHT zxYe!?!Rc!Dk478!;%bQj-{XAm4N!jy&KV}u70NhbG1c2T%RYmj?)mQpIPs}p+hCv< zrthx%8_Rb;CC+Pb^AlC&*R)}MthaB}n+N~)K{$Z_Ik44pU(>%S$lh!HiCS=$O5d{( za8s7lwzWp#D7vA;Duz&q>EeE0vcSoP@6UwP1tZSwsyh?>eRvL8Ud;z5=oZ(Nm`Ned zBC7{<0XY8j?1xHl`uSc7jyVMjNg5dZ1SdRyTU!loev`Cjn{zrc9W(e<0P&psU-Ol| zpmbdHY*SUNN-FaCk0>n2f3D-SO7JuAfzNU~I6vr!xp?WuNN|E-8R;ds-r`Nnm5B+6 zE%8PF6W`y8PLF_dbi^BrC1cQ_64%m68s?dn+VmdW)OG%uVr@8@(Qfg149-#c9sU`d z?ZF9(c1vptvXuHz_6^kvg zP+Oe~<52%`Tll`gyze_>A5v*;U42HP2=iEhx9bOBeV*685oj~SwBEDH!jeT$-&toi z^S$D+&4d6I&yc>B{yh)l6OvR$+R`yKE-d40a2ldon{7~Th4r~}f4j~5OnmdR_HfCr z6y!tIe0vI<#l8Q-0bIsmO8fY7I`Rn+J-6Z-ti#BCHWmD*gQcICSse0tt}b|9r3lkS zX1x*xGH`UZVQ%T$NR%}yCL^T^-WaHo22N;Gt=|+KirCZtk+Q+5wr@XWgA>&jzmGZS zj%LI-$AZ<0F!^k6z)5hrNV^4b(i%w3^YQ7+=ct?{fb4$_xEEE)@D8 z&Of!L58$i~rfs5pzm)HGBQ+IeweAa-w1#!|A$ZT&Gw{Ci}hFeAjmljB80pz59&USJ)apN?WDG?rxSor%PjfAt?7gghl$l5GcZ zbv$t~cclt<;3;uOv9>n{GuLF_zUaKJd!fk*z3Q~CR3UP)7~xgCpX1%khxH$fj{e@8Y1@>KDmy_1WH zxroyzcIA!?)DK=qrR~Bq@Xs5B{R

i1XpO%4OMn%nLi(@5JBt^5|vb&%F`Qw=Vnh zdW^pxqx6!i{QW?TZ#a$X#$q1x)R!En^I26oY8{XlZvL0nzC z@nRs_K#6!MI3bXkbDJ-%f88h3H^K#Vu5wl5prLPXG z^ZM%sp(m2C^!pCEDpok+w&LHV{t!vz0MeN-K5+E-0QC&8F3Fz+AzDNEC$*Ct5J zxAjYNQU)g9zG1czd`c+(UPW*W;-uxW&6*&Nqy};QLeen%<4kz*@(9E!qiAS1!#K>K zJR11JSn(FK^~s2~{DAJ3+nJai;-B;LdK$KVUa=;3AOX=7h1n9FnV6U8Z#oN}MU$5H zyFf!U-=iD4x-v20l7G_58)^98)-|_u4<{p@LGs+gUzwP?=@+YRJOjV~wWFbDMu~AS&JlPJfsr;;=gk5odpUta}D=s%%`k zWHGFteBbxR5?e%c5VCF<$iloQ23l^QUbb&82a$>i5GDEoAGBXm7PJlBlwvl!;F%aPsi#^x{uS-Zujvg(*0a34=+q1F|>#cF)^}8^Cc|(;%@Pp^l za}17UAo9>eQ&~5x=gz;6Qo%R&Xtv+lnufSfi&_$UU>$ASBeKCcCJk>2$orAl1|Ma2 zc%NjQJJ0InbDY?=HuJxa@Rt2ZbGJRFYCfD&&4d2vuJG3D z;KZU?+vWie%+yJ=70!qGi#EN(;N#8)jaQbZAj0Q9zo}<%zTAI>2}&_>WvA;~xw~{k z$@sKDZG!P1pK&xikdG-JIX!N^LC4$1FXA4x$?L>GH+TMDOKdDzW9ZD*t;81y=<}7=f6X zL05IW4E=s#L&E8XTx@#-R^eUtxuA1_bv!8P@ zXUon082>qL zTYI+&X1(v@E&7p*#dh4easr&9T6*Ag01ZP2^3Qqz=3^Fhm^YMI>+uq`y-|m)%$f_$_jV1FiukY}O zF7W&gq~7))9qun`hS={sOdspdZ%ctbV7rv`=}9Nd`72Z$wvdOp--f-Ofk$3FuqiMn z0}-A?+AFPx^{TW9etQb?_Eoi&uXd&&c1!E;_X_!#sKQ$P5!_n4bZ+%(7{A)qq?-u+ zxc}XEpTId;-(6q7gMQOiN?BwR|9krv?#+VJ6$kpQLU$vIX>0f-IG23?%p5p@^Ze2( zqBour-)Ht=CFI|#Ukc)vn7B;&NNd1r2BK%|t(DshecV<(mA^L%anZ%j>hsN6h#UQG zb`G2v>HKF7Jn`cByw&b$i0-U(hNBAg$-hgbf;VA4^%3U^4jEz2bJx~9odPUYD%Ya` z&U&$Z7jwb^6MGgd4c-dljO-~<0xvr)CuW+PfvN>e)<0Uu#8hsBGLct^GfvO_Y|&3a zGe5@y8)TT6X*=7a3?92K=;H*egUYwoHAGqd=ZXraRlo_+%Hi%$c4I5SPfGuZilw@oBVk3;gH#mkSxltoFn{+pjI9gOmR`1_}IEgyqg#DJ>s|ak?Xa zANU4&{G_+%q>&Ro8zTJUsW04L%N4w@2|(Ta{?I}C*<)CTn60!~72?0OL|COD_;($P z2JoQSmgKK64kfZ==@S`QWARknUGu6rZfy!;x{qIqEQNTgTXjSFZU7!!9iO#& z6Xcx{FG0mY@Vp&2j^7T&yWWbWo_&&lNOBgnEBMcQw^sU{18iBj)k`|mJxw<(-Vn}XUyJDY1-Nc`0xjY*_KTH@vonpQjYe;l%5dh*fs{HYnGpNDGtHZtSy#H*1hz_?6o`2q(R?JEE_Gp0ev?;Mccwv*cFSd=eaWS z7?}Fl^+oKiWd1&-KEI|8VX@`_YQZzeFLG{F-R4xxDJONbX29!vN_`;kKPNosaIp>Q zb|Iw$YsBQ>Jl`z*((w=CU5dk`jAuS(+IblrI}nMOausRhdRX_kCDjdEZLs9!t>+UT z#v*#kqs-x#P`B+#p&x_(s5;hM_DN4HX5AiYeW(j{ozAXTjz8k@p^&)epWY`U*7Zf{ z?=B=_g01YWzI+qx_Kp2~*`_o^@|W+p=S{~1u}0?MeTOhT<{xSEbrZ}z=O!qIlA#{c z`%vn(8WFNb_exJWW6G4%?Z12{u5!NYvKqzuk3CoR&Ol;++IK1?fO~9g9E+!5R`2Vr zk3PVCkymLslL($Pbz@%w1(P;NzYiDkLR@7xi6v>^_ukr?BvPPW65f}y(g6`@whB{x zf6?O@$=`SPT2Pkzyb<(=Xh%1He~szmp3lL_ACH9NVD3dX{(cLhzx9@D;^zGlx)ZPtR9VzV zIRVGNx^Z#w;1Nt;_bE1Bf{ds|uNv2vft$NnoOpQzvl%g$wg`G-v5>ZbH)p{kS07Ux zI)W#rTYLlVKwZ}}vz8m326?4wN5`)nIOPjNj+&K;h-q&-w_b+V)s_^#qGN-znw=|` z_J$yq*GZ;&19e{)+ zSK!X(jGN$0`d0cR(+`Qc*4CB}gZt?gd;#a_EA1xdyCO>MxocUk!J}nP$b5$JiIVif z9%0NuS&xss;XkJ|Rvryb*VrId`r`=1+4xrnc;Kvum6yOP$2~mSJ~NP5`Nf{{&yYtP zA6ssPJi>0ZzNk1Cgn6-3!bg?C6;orHu6yF^rMEAxU!8-- zcLN2EzjY<*1Nik{AKm{@@(^26{RGn%@{wPS!sp$-*lSMRUO+qtvFz7g93XF3%hq}y2I%Hq$;gy?l zIU*0vJ8fvs$!tvK){y%aXjtQ~W#^z?4x*|JWZbKPI=|D#j(su&`#hb`$&JiIQ#bra z6FQ(icU2ROhj`m<+hlD}nuiEYj1BMqKz%;A>C{R_B)%Y=_4JAhjPp5QUEeJD^BTjo z;3-{B6ynBg#8I>mZT$;<2Y1VRC2(5sr0Dv|K+H{Z)mML)3;E^gKFQ8dtkkD@MZPQ# zu}s4*$MS#IQ;H<@th9CLQVR^-ymmG%s{o)Fvss}}woOXBT z{irOw?`c<{V{k6=k-vJ)-W%#OU4`t})Li`hyToCP7>Kwb@6LU2o}`{39XzG+(O-qO zWW*_s{-R8TyfauEQg~h+&8%MBm-rhQL?<1KPiD%`(9K&r;d81^$r_2ham2t>*(_h;4CZGx^i{I z%rV^mlkJNrs!kOg{&Oo#L;0;`>WKDX#Z<^8D&of2y3{Fy(>K3tKckN5b5#G1D04); zPmwR##Qz<-)hEfP)lpiC>DnK&PC_oFNlXyfBfMrz53y@g^7Z-q8u9k6{NgEzr+n`I{3bxd#2a<*?waa z2IgF=qH8Zi;pVF@8HM-3i)EUh?}YdkQt(1IGXbB;R;E{NNk^pErPk{F=b7pg!}OrO z`gveBu|*&qasBrxebvjxoX0Qss>1PYxe_*;9MTcZ@cG`e?F`InUU^B?FBQ+8Uq0rq zoQl|vXK88Ip>DKK^3eik(B;m{v}YpL3DNqkb5J)1xv1#9O~;%DJO6=N6U??hb#hlA ze{&G0|HtD< zzUzfHF~HeF{`5;W`A94#oblVB2vZA9PIEQ0@Ke=G$;CG_(M*|4mxUqRzwIX6w|w{N z>bbEq2eEsf6fAiT{fl+KvJ2G7m8k;iOll6|CE1*FSAu@L|JJp){O^snP;}iha}Y(j zsX8(c;+}RNs}$lSZ|@p%sZ=+Vv8KeF)|VnPpe3fqqYQ z{zmUWDqeL^ZJa6_;c38b^zwXF}|&FZ-(>BQ98$a6OES|sT(9{!u7!5oRrr{!UQ1~ zgX50QxbZ-+RtCg#j(GWjX-#m~YPn8uQlK1hEFd3|Z2oLNSp#wD=ht(LW*4lRJpPZs zhCWWQYoGNMaKe3~wJk1KXUz0)ycOif&Im^L6dlu1*G;WTA3U?qW~sgu192Ceb=cqG z_@XniCg9i4yW-!2nTT#^Jaqd1`v=itkMX}BDi9RiQVRED+?JHoAN>8?OkPHSlb%)| zGB?jd^z{pqU;0xpy;#vaYO5P|+MUaN%1A|1IA(CAUNYv~Usq|?OvC#BQO);TK!5$) z@zGDdcbA*mfj?E+7D))pL)<+HIBy;FS9>8z0Y)gy6R3rK&ACsfcOgcC69``nP); za#C+XaIycZs?C&SM9AA`okNA!?Phl>f{*W`9?(@yggCkBV7M!Ir>?IixZI`$4oNZ= z@z&m>v=+enymLh6q?d zXYz&;h|9h<=~isdL4@_Lv?e2{SFdPR{Q@_AaQD@t-3&yUZNQDRG|aKC@w5*Q#o;Y? z+4_meNGv|?;0TM~KmL_EMvlb8S$D_oWF;cf6}$ZI3h;v^&A#AjKaI>zlt5kgom)su zO~>S+uPSxR!|>qPC!@5sR76?5BI{dY8q8licYl8*-acmYUzBqWB8FeO|NIohH`};X z^5??v!P#e)NnQ*@-N!TBatGpR?UwE}eo=Vu@{ki%8d-=QaWh$}3+5m9z+Dl1m$b-> zzUg$tsw%lV&-a5qi!{OO)o0%KvT_mYWl-Giez^Z7JPqdN`QI0s4&0It*KPdgmSf_X zm^1P+Va2g{EOyZ@VufuMVqfBz7)yZD3&f?sl~&z~ACu33x~ur5rX;x1{!5DBI$=s_ zogY#WbuPev%^L8oSp!Y*YSVRU*>;gw?9^iA4_l#r&d)HWKp!36#F@4Ior0JfHtz^< z&B83Bg;=d>I_B=n7%}UMz~o%YBE*FJlCV}a7xGkex0~bzl9w6uZPleq&im@c zVxBtp^@Ape&rY6KSlndn@!0Oda$+)K4?8NpU*PX^<>GPx@)tcpvC zw?|#q%jIE~gY)Mt;6mh1Rq1Y62j%>#lZW##U0%fgo?RA}CS1QU*p`He^=|f8HS#ez z#9{becm}?HlH;EA8sbdNmaodeaD371(PGH|ZU2_nyxN?Ex!%jvY@Ffvn0S(UMHXgi z{}=7E0M~Q0WAm;n;1?yZ$xJSu@z^GDe|sz@w2L2&It_KWwA9rdQaN}~`INOlaU!O5 z-KRO8f%<=Di>Dzt=bh%r6?P<=5-mEZ_z~*!FN4cPp${-k`PyJ=ABuP)yALcLFTlLB zD_SJMFMP_WK4p@G2xoiqv}5Bjp)T#y;g@@HUDHIM0MtcRDBQxy?2|B>DU5lzwj= zx*mj0&sUlKR$yXET>D8A9^~^6UAY_U!*G^wd_ea_CT8`o?DSn+gimz#=q;B>L8SHP zzKGoAe{K_S?C3IA+%eH6A9^GW@ig1)PQHZrcDPxrAM(ORhr-uQrpcJ%yes4E6Ue(O zMzXl~!*Sy1iKv(QnTSaaVlIKYj;yt@ULNYY-chOaCnm{wYI@_UZGRY;y!^XB>39p~@+eSejHMlvS#{g5MeCSj^v{t>MJs9SFPi{^;OV_LjW%|=l- zOnc615aREDc&qnZ9o+AOTbCYupcabg9TAbAKfv|!w_L5i#vae$g@Ngtv6$XpHSp$1 zGNzjZWmX8eVpe0+H=ceHrmZ_ky8jg3?@#fWHt?*2P4CtQLmc{fWx0bo;BJPZ9Yr^8pqJ`4wRoLw6qOvlupw|?}mW@3)zZoPY{;rQX2HXlwwCL$D8 z<+r`$|NW~shBKFneU4~|pAMqqk~;=7VVj^Ycz0`QbVCHbQ1?=2GsJD8b0V`kk_mB2 zcvnet0ha8c=3H!LAkMc7n`*@hG55iVpi&9A-n{e6HI@cp&fMRH19b_QV5TN)ddLeu z5Ax9zf^}mC=iRxH2Gnd4N(s{eRlr>@m%rsf6^zSvEIE5e-%|a z<^;;EwIk+X^2*N3F7SSbkF1g~R)O~=xTO563IBP>{taqo(U`W)t7PzIAQEH!)7(=D z_wTK@dRB0qQ?{wNHLvqTdZ!=uUj?TUmaVV_r#@Zve7qJ2x5i?c`Q)dOJgD={PLDs#O~qN8mCr_T=!nHQCrz-- z#B`0Ox0=W3*rV^_b1}&TL~01083QMHpSiRZTzd1TLBAd0n8d!Mt07&8nfQIw16XI) z$^*PqedsH zBye)_QD^hrWW=f@^O_XFNALV71|JtEHLMZ|M_fySo|!H`pHf`eHLjR5G}vHv*9cE_ z-3@!E2mRo=g0IT8u9$E@;B>0A7ov8=yzn>#d6Qi5+IG+l)0e)xQmyWQSVBRg7Kh=! zFczQ&@%>k#)rmu7#5>|Psc#N`IO1J8-#we!ms~T#q==6xzMi?5uzb(3wiQed#6Uh`H<>$c<^N9kg#$wlWF#h-Hh()7{Mx1`;o!WFD?RO|gAr@|oWRl+ z{`ViEj;@&w#B_aok=_3}B04R;b*L4*m7~9p?^AhqaJ3PpDladZDuj3yHho{v)eCb{ zKY4b%bi}OSx$;*<`IsK#c~};lob|9`gzJsiZv!nXzQgM(6%<^w3&Z5EMn6>q_93EB z=)krtz$fnUk~D z5`jFp^utYmaC%eCNScivE|FWUasiyIMG1)FkJD-r9JXMGX$DLFNsGex_BUix!NpLI zU(3xH#NOSZJq`U7p;VU)Tgw5~Ep6nQKkxRmq6>pl0!0C#I#Lk0LRYL+!irHeqCa%`9 z7I1lPYdtuLU43i&cMqJU8ueU#Bg9GZs?&xLCu!Pm{`4+MN9?jz_N*g}zq#nK9mIhd ze@PAHogt`ARpVEFAH3fLm6Z3~1k9Bvcl*fjMW%aYqy-;=AG)hB1vroeIP>9@@Xep@SlZj*kSl_Ca@zTf!pc~@@4L}j{38*Oe@rjc8iRRO-?>$_ zCK(4{kxfylv8Y;TS{?uBI)(_N~Au5AB;KD$bU|FtD64t-{z=f zptj809^M!6Y2d79B3#!Jw0EbJu*&4=j#qr23|hI=D-pAPt=rkDXpP&JW$`SIf_JRE zyc(Q_rN#HnxM5Rbq(B!qA-~#K9-K3_WpD5K5ET9V!k%&(%)dyfaK;5**Y`&S!P^gw ze=1n9I;4>Qd%KSF;8o5Kjvcs5N7Z&ZslEK)wQTt~lL+yXwR760Sv~yB3GDS|fGp=~1Sm;_zdJ*P%@^+N{OvY3W zwQ*?B5Bt>pNczh6?FIss;Pc+bDc6kBklv;Ejsu&Epx-&C6ey5^_a^Oo)!!x{caC)U}Xb(8)#P&AZem_k8_8du+9LMyHgP)bMQ*f`cRAK@x4N;ae z&py2i^X%_pB}HXHf22^;XBvelJEe=udmxXlynCV;oF|eWF8|9K(T;{Sx)~hDobrIq z9mUXJn*Mrgk)no5eC+S_gR}PVQVsb&OPmp}J%rn$40)!zz&}{+Hv$)PivF(tHvm=F zCO$q&f%#~48tu3Zd8}F;eO6zKX5s~UHz^;-#P>aJ96#u5e_1#0G^AjmAgOCc^~W)f z_AaxpISq@6C$V=8(=fAq3vEve)MItIVwZ`jn0xwpoXEUCBKbeaOdE!J`c-X`?}h?A zQQP*x^lKubur3+wwn)JQ(x&3hBa%4rapi`=zp04l*e8_W0oR$2L6Z6^O-#6&+Lh3? z2~p#8!cP5wc)n7$yA$HMb^pWD?`_i%DRhzKTm$%(uYo7N2V#omnel6l-iU0tX=$Z0 z^ure~`ZV;qVJ_Xvn<5g0sP7A2-YtWAiLuH%nZKX^_a|d>joQ$+#ps7_&cxKm+ZkQCDY#kI^XZdG zI^ryQxY6%S7A977o-7#vUt;Mm5(V{!i$?*sHXHLo%_{<6eW)$JY)MB_5!q3s;ryFy zOpWx^TW6k*Z*FX}!GHeebaBZQSRdz9$yqC?=cm(WY`$mX zv^8~Uz6r^Q;%lHWVh#EI+1WZra23B_J!eW25jXsYQKwA~rZ!!px`OM)ZOz#+l!}P z+DNZlZ2E{E-X9)~==QsdohqQ8oq0p?YRJW`TMajtt_w#j=c&J_63)xsbV2|)@93@N zwAf(8b*psUa31Q+Ts3wG_>5og*UhhBocoEEU;6SeZ-YWu%}_pOpLrYJV;_O+Yxe1s zR6w6KsJdXzf8ORrNrG1{)S-2;+sdI%q4@{6g-aVYju;9TT*^-8F>kfrCYI)DPHV+Brv(gC_JP%6elC;9?1%R`-NQAyUffZ3YGq zXK#J<32&xh?&l)my17uqZ2zIQk^g=B>;9s2aMMeQYcy`ac;QQi{Ed<^xirVb~IrK2dVK3EZc8(<+VcwxuC@K>UuwiwZDtHhITX6%+r<+Ftu~ zWeVcnc8q+pl!>RVmQHPXz{G6VTURf4CLv?7~xhrfG!*aQ!GOf28;f@)}vfV3PlPe=fR$!8SC^o~j{jg?^An z;yLB;|K4#5Gm>kLWJp=a_ zEkN`H`I!f%r98S5Rn7li=!!?j;W`(J+xM&WaU3Eq`f}m3R37FQ-?HxuE5sL^8ry|S zAkGNiyImYvfLXh(zbAhc(@Lf`#qYY7RQzB@{!1;rs+=g4GdYz8LZz~>hmrQm%gU3ni<(-CW9 z{Oy(oxZVy24O@kz;mX#O(YKUT#NI_VEM;e4szcD}qu>tTz0$kW(vevHk~Xo&S(xSG zW1Pr;zB<@`alh6vELLgV>_OsIw)0DGeM3Db{FSeM|&crj_qdh+p zQxU}>@oVQ|=$lTM2?^?C;u8Cnr#WIFXsS_nM1MKtow4QT6~Kv`z8V<4^TwPY=Z@)5 z5Ld;ZHZzYI*(9ew}zR60HurTbfFI2{qI zPA?YO5B=AXs-2qE@ILD3H%E{^rWd^K*VfFzyvYmS7P?@bJvyp|0-=~(QF=~l3&deB z?MqAG`f@wh5yW1W0rBuc^{og7CLWD=ng2Wok1H^Ir(;7f;jHkUQ-QgdxR$AMN1uUv zd0%SOhM+FKeAhlMC>K+IR}c4sS63XKaN8M+rOwG3;g}V|Cp)18jQn);$nv-br7Ee z&*j#D54K3_Ds_cpva7oCnbCYqj@bFK7~%#+>Zn_$9MtdB7lZNd^D$M$KdlVBH}W)d zB0K?$xuoX0eBjpuWm=UR_@5&Nyr~|e<0)q?^4_t0%*%f?bP3$_UE)%uo#B{LD4txl z3gSaRaGe#zlait>wetDUf8>2g7KXlQD)v#5E%@Nx5sP)B@pvk`EhQ10oULhf6rB0T zICe!D9qVP}082o$zobrrvrgr1asubN?M#;GPQl#Os>f7LFfq-d>dhJce$F38FSRa2 zVT#)!$sG{y*wWg^10XJCeGs@~Y8j8C9p!Fb0_Ql|dIW<%oE8fXw4~!|>j`)1OEB)) zxNV`}gQ2YW?XfWa;hQV7`JWrUWi5^1=P#xGcb9yMMOh@T%e|+e-qTj47DIg~RKarI z93P3ed(GGFIs^4yfY_!o@M@7B9imDo;`JVQy5AG}L&Y^m-OgD;{5!kd!`dJ5D4Q~5 zyuss+=@){tkJK;AvUfwAK>__qAModwWI5oRq4=wI?MD!c`sV8$KXA?O|Gx3ZSzH$2>{Q~ACYHSV*2&HE7om?e`zH)fkEJJQt=^h(`z~1ca-B0Z&`hc%Qc9% ze|3~BEp2gimqbJVrAWjnU~JcI2e*zFq=OTRvQITgdSc=}-Lvy{F_`egdi68tuS^36 z_r_dILaayM#tyH9dTh&?he3kS&&N{Lb2i5zy6uBAO2XioqgTqoA5xt&l*LmJ;TsV< z=q5qGrmF4bDB%(-0@)@`I*&$k#$`C!Jed@QR;BTe>yV5og}kE}fc%smrBX zRIBMY{%bVb_-HyJJlJusyaeiL`&Z(5P^YCym9*5Y%0jH^eXn;?;r^PIDGh}C#o7jM z9o?RVcm`j_V#*+&zI(dD1g`)2hXXJE3S}U|p7KM^<@|jOqOTtU=W5IJjYLJ^-VVRB zq&euz9xR+CdgfytljD~pUZf!2?n%RB`v^=hwxgjeb5vJuEZ%g2jtIQbc6$f#E=z^C znda#8?ls$Ms9A{2JruF(9)Caly!||NgSI1# zEJTYX>1HoL{q*_{^D|th_wUiusMHK37B;ZWpHP6sCX_tBg3~MdQlCUQBcklzLp$f; z{CfSHSzGQ3eSm98qO1v`7e6RlMS%IVJ+;%~d+*gNW+6KX(c1|}1)>>a)pgAWFTNqZRQBEpg_-VtW`n5dn4w~dvBJGaj2NUUKXw$ud4;ZQ#G zC!&cR;6$V9C4}-kBsO{FRMtl5-vG9cs-J?uQbc~QmhQ524 z{L}4XeGbZ+`>?H%?;70q8Q^-h@;jIG=OCth;`7)4;J!wrn+|(ZvDoXvyX$(g(fIqp zu}|gDpALTrXSSu|fcA0qvdL^DR;ai1^{yg_??Cm( z5{tC#Vjy0UX3f7U$g`DmF@{0=aWU$-Q}%^{h=+RyHm>FWPTc8JS@BfNDU}uTd=!r8 z#_3*v6{8@J&eYJM-!VO^o5HiAA>M79)<+wl9zODTc?md&ZLj#l&;=1nd(z*xf_tr+ z+kYJL)8l^%B6kiV-tyd#);92Ck_Vl^?T!`qW6|0%%0@sy2 zFGyiRJp{3vr0nwf&&`_kdRIwBVCFx|0}(V|#Cbn`CNc@?Y8lTZjo>uBZY%L@D&nnq zJaUW<{%O(qTj0FS*Vkz}SYz^K_nNh-Q1{pl#__;=*Z7miP&A_SZLfLs7W&ZUb1R;) zAdil2vpD-W3=wBm?P`4oZfkRH1YAt`+neCk35XWyGxt><`s6nRNrV4Ybms9;bzvMI zUP+~zC~2WdrII9sBxgiuv!#-)vF{oC&e(UxQlw%MZCXYNEj&|6v@l9VDWj02k|?yj z&-~@{`F1;V?>W!%`_0^Y4UhPm|i zq7EtSXRk&bLRT$_IWK7lwDUUVG1YjzhECMaxyHab?PG9lmK|`muJEv`LGGZkcvqe= zyuBChFugyE@SB;h`lGQf{R_$a+Zl`V?K3QKJ{&k2*KQgg!M>v*S8Tm12?q5)C0=?K z2_AP0EXss+X+edlBG#qFEq<1@Ude=UgC3%{0d>pkm(m+9IKuobFVBgtN+XO~ts}cv zVBS5`clcZ#3f#ueA?bV42xouJu*2aT;E8(aojnr;MWLVKW+^2S&VQTY*Q%mkdbjha z5so8sDadQD1dFhb?-#VAkDy=maWwfH2rk{ZH=S3rz~phryt}oSzcU6;js=H9NNZ}v z>m$iTpdx)!O6cozHBCN&3?=DYUi zVivoPdV*lOio(P-jgg!4Y8l+MK7@YPXgB?708nhVEH(0H0QK7s?gK-A;4Pnu znBIf@#KP*2$hq70UfLpy{cif!%;afUC#&`a1!JA$e${P=nROWZ_l*7{s+eC#Do<@e ze@Zva|G7wS(ZDLE_#E2p26fc9S6S~v zfH8Ic_W6qmz@v;V9H)msYQkQ5^Sm%%4D7o6;g4{?xtRx^ZHff`G`(lTZNb3UyF=W_ zE(KUA(X&DvSorsy&Ldrn>(E65%JwNhx$Dv%DcoNye!Y6GQ83Wrl^oAjqykG}Fhzj< zkx_ldNAU`tU)SA7vujarj|Jve(-OdB&zsXO3gN)_{&La$H|o`G?@x&oB?0>|W5O>r z8u$rU*J%F1crbhKFdez9^Og0-i(-Jw+mvd+M7>(~%CH0bESt75Y+w-!1b0V%$lb(v zvl`i0Jdp{i%2iu^>l4X{;-(ih!8yRpD_a?hK8T?%wa9iN3aG}nmdLJ22G%Q zLG|5SxO$TX+_&5clTfgaek#sJMtosqvwhr}brBhP= zd92T~)3#7JflysU+p}e9JkY1sN~vg|9~{mOs^5#gQ?}&P!6orPP5C!}nGKGAa8vQ= z=t!W&*{oA+h=6mu8mBh>%>{w_pW%QDaiIItZ1w!17{Z&U-PRzMj6S6$>RwAE2yS`D zU;koBC`Ic?~JL>!*!>;u0Ou0-H43nc*q}(&H?V} z-u*?$Q>XGZt^W%mbSIyi`j$BFH2RJj6J6kVPWxyf;znp0TZcaHL!QZGs_fJSmbS^kR>_@8?XZ~uyepi=m zWh1?vEd4?|XL~<_&=PWvvdr*&1h3bfFxCa`)l&^`PBREE&Y<|;7xY`QK^>U~>4dI! zyTaGgl<*X^WnPXTFF2f_f}C<}^Xh;Q)P{JQgAA7Vg3r4!$t>xqT%0`Iu z@{|LKYQK`qay^y1gJ?rwL#Sv7dX6PnzU zfkfkMP<{M&@D1{yVkOB7`YfV4!#&Z}1kc}as8)bntiLIF-KHo)AEzi7?Z^iHt>?+_ zk<*T7kBfc?CFZ@wptuv)L;cRa0p!}-FF3y{3dBCHVLu)9B(w73%8$soLt5p|M-F4Z zYn}RloW7#y`zK)>zG3;U?oA<_>Bb!SF^qejdFb)MWKhXlS2yil3ZZ$_OLqw0Kc7Co zc5fv9`$NYsYVrEO3=Ep)NXL5E*f-DUP#QEG=wH}2E0u7M_YSW$#60!SN?I-a9w6c7 zczL}Wp^w_GaF0p{p2(A!8|dpbGsO(V(O>XB7l+S{&j8ki$Yp_YnNaR+Ir`*KD#q>H z3}bEva9;T&uEpzi+oEQBTpjg%`Yk=Bstgchm2B96e9bJWMvv)OCsW-=C9h@xO`rct z13C49#N7;DGWx-+kggf%iz(hWf5!(2f3FO_w%CI3o~+zeJBD#ER+XZ?-41B$9cEQW zI05sbh+o)G=Y?<2o$pj5NrPXb{um-d0M?rF^Nwf5T%QXY!22ZoY~$F?|$fmPVY zA9lvvLmghX-#<~F8j8N@#peenP~Sv%zvJD>hLIb8V-ih+32VvUS^MrLg5ZwijTe^a zn{V_ukN##7{_GN4&3jnKrm3ZOA!h}~5*kIXa$#d4P)!clb|W_rG_XB!jX_wW zZ>A=Y(=wuzdyq2*X6_uJnG=3r^v+lJ6M^1(>Q66nYpLm1pU(>=lyJ(v57)3StauR4 zwafuorvtNJ-3}le|1x=++QZ4Zo5vnoypj5GU>9%(KpP0qOEM> zNthb@a&o(pff-UYZwc}d=^RmsTFhU?@wWl5l7W5W#XC9VoYiGT4_2EK>Y^hmRo=K*8ZrkG9L$-pJclU5+7FYEss*zQAkslBtd2=BYSQkSQGJO?J8 zoao7v4kff2rQ70-P3OP$XOg;SXe!?!gdpElk>-?4rl{G@%(jTvMK@)w7MZ+wD74v|8$)DvSnhZ8B87m@3(g?*UIxc;8KF}KUqs8%j>z?fh53Wxk z6w5>84|3KceI3a=!uN%WuHuQi1Cw|3fpq}-!QJ*EDJHvtCX;@xR*VVUnHkRv0+G9| zoz;)rd}iwrqr@PfO*{4FItTsHkvHzKuPi|}b>R*7a?}sACvHt^$^zO@?9)q&<3Zfo zQs#|C77^UqObdv^Jh~R|N-gq+IePxNexX@}ZsR_D<3kqkzMp@ibRZC@D#;1g>4$+; zf4S|ZqVV@G|H2NhL@+m%?p-A70*v81H}Cdi-8LbWzUWiNG%rkFb1{K1#c3;tw9@jNiE z;LzW$41{I{i*klK#?2=+NeSfT`SA)sd*%@4>s_Bdgkrt2 z_&#+Bb;7%)ZQh*VG%|9kCz?`@>peHSX;vHy5=)noNWb>ZTkN0Bp@Hice7&S^;8rmeV_GwctjNj%ZL zh&uA4Mb@=y;d{#W{R(}JIzh$j$`$0i6`S|oK;ESAv3AABqfl#j8R)4i5 z1q35rPg)+Q0;l>b@9XXm!j9@IGo6mQZsj8U?MRLXeHsZQ}Q9T}v z{%fgtJ&nqbAnbSZ&J3wxKN>$RmxY{dA=}&j5kFV)<^pSD%$E}~?B_4B?zbO%v^mNV zn9gfTZ-?XYmAc*C7(X0~3x3Lf%z+lDKg&S)zKi9F+1AIrf!A{K$>;9|M8I&~X;qd9 zEdB7*=KDUtStx3(a1?!RmtN{EQS^zgUsA2m_c3)2yiNV#0?huP}>tj%Rum7T8xVbTTzCS0PP^}*< zmDq;sa#~ucUbrsw6$gskScJp8t`{Zb0o(`8$VYne9@O;tK$!j2RU_Bgz?13xuL=F8 z1ns{bhD{V<3|pV_d5q(S(ZU|^@%XJiR_uDe3M0g*FMD5rug=8XOrI0z`i}`p_all9{<-UL84YDT|xmLeNJy{_8 zbIGq57+F+uTP@X*FgV`V3a2pND;0|kQUCYtP)KXrlT4Z=ioGo6Vw{g#e++$*0Mr@g z`xpyRM=gne)rg#-O1}~&)Y= zM`~HXT+>&P+JX9QBxLV}Wq!cWIlOn-v>?JeEz6XNz;*w&cx9H*$8G98$_w%%th9@^ zKajIeJ|4+I&c1r0$s*eq=-R5cM=;*#2d(q&qb?fpTz34YLLe}XOE&UUeZ`#^a$gSQT16XFB>Mlt2`AC3zP<@`3CjQ8}39x z^PErm`Wm>7uV-ACjl8?1VybdF3!261*j32Q_l}2Ak*k&@E35u?2m1aqHcH7@FK!#T z`if`+b9-i)#Y}e)EFWT?&JeywzR>7V_cq9E-hI%lJ&Q<)bpK_<=K}ld#)b(6jJxd` zoe9eV(Z|I9KG%qOA$3tUP#=Av*2Po{vq;SE&OZ7k^cU%--(`=ZPSIPu#B4(>$nqNA z9}O1X=QG1Vn-K?{7OTEyEe?kXCuNcAhIv3a+8jeyNd?RJa3+5;m2i|EEZuStby`8f zv)fUJfy&%ko&O^W7++e>PFi9=_TMp&Hs1s4E_#?f9*Y9rkxup3(O5TXmme^~^<{j_ z9}@c>1+=Xn;PyG3&p(qVd~kiKTlSv{bcuqI=Pk<|=i$7qeU@6E5Cm)NXS|F?UCF+F z_mA!qoF8xcc6;^#;FVu44udShdA07)MVj!wg7>xe(4V>ez4J1nF^zBox*1P9F@9RC z>TU}C)4YZ^?e>QVxBo0M+QW@;{)xc4rz$yD(vC2H&Q9AYJkMPLDuDXA`9_}A z+~gqO?2GMD2@>vWHa_2A$8O;64|;h+EF5TS6yy79aa^fj+moC2LD5uoT1ZAXp4XK( z|8a!RS+{i1Z_z>G+!fhxqT#^kG|u(zLq70QJMz;(@R%GrxJD!#*r}eJQ7YEkn>sQF zPdNb3jpU@xjsd~U$q=;x;OxSw**& z6%CYx*jp}oc>YiHe_yS1#Q*=TG0-s->iiZ*d{@T#%zYspCI|zH*^(u*&N4{q^1xeu z!hQ78CEoW=#Q^>8t#fm2UHI?EU~YTA``HqGJ68++n=lqCE@*AdlJkWK3f4#Za?R$LJaDM z6E4&Av`BXdV?AFq4){K*=k*70K1Is6b>Vz+1leCN6ZBcLvfZD?qMlLrf3bHg4z3!H z{YamlM5xQdRgGB4#U67GBIgeODb0lhLesT1+wu*4+S#jiTclWU?pN`ah6|WGd4(~A?yHr*VifCVh}o18a+9%==$CErg!$5{>+uZK1G|HJN^u_S zY{inU6|#t6n3U0H;ylRl&sQMtOnfH045EmM=sNFeA^)NjREgY;QWEsRGlitq|KWPk zuzvo1)R=&}LUY;UZ_z80iFs$=EVVqGx3n$gFH_^eaOM%uLG>h3ba@^pY|5AT;NhMxaXO4UYjxX`#K4maEgmhBQEX+a9k_zp+ zfZU|yz0Ue`{)9hy;M6ZU9B1Id3mqJX-)Wcs(9er#&o%J!lSf`V?GzpP!y~Fq54=(c zHFDpT`i%uZKdqLK_ZR)v{7i?Bf8q(JbX88d8gf~Yxh2SVKf9q6@qk4Jt7iXOs9pdZ z%fXJ*$P0eCI*d6akvi*6KeiUm=cNTN#D&irnhrM%-9AiM0+Bgk?eV~yb$FMjWCYxn zvvukg-UmgUl{R@e5-96~*A*>u1+mFiO^y4}gp={Q^D#3LSh2g(uOR28J#hyb9=}KQ zxc{A4%%7m<@ep^AY`>;I)r7}4KOHi>7YnRYJ6F#R#d^TSvM`?@FZ zMEuQAtlx`5)u&Ad!JCdn3uTed3fY*AoVLv0?nk~qq0JhYskkW?=>ED71g2rYeiiz{ z&e)6a7ZNw?qE*Q6+G?LfPJh?*Ye;er z2-?(rvvbj>yNGE2%8Un=?V`w)G7O-7`BNN}mjWD#;7Ljr=8^fClw&V^h~Pa(ap-*p zP^~f}_UN#|B+u%=44niJByZbTH3$93hZ?yzYr{d+a7T#Y1^ip|JU(C}OZXnUS} zzHgVVj57$NpZiSrX90cWl=via!JTh%T)zmy>j>J`ErEI|fAbvKbymPXZ2kSqP%xpd z@}o4*KyGzg(-=8#2{f;F^C!Gu&xUI=k;{-nA;?*|yL7wmdJ=k*b5!Xp>gF$#Q4muf<$cqiR9mwemju~5mDWSVtPlU`yZu_9~KV>WEbL_X;KORGPf`TXF z%dqbs(vRk(?1wSd@b;McIKmsQw%)iY3n=S$46o_42EOeX%?N)y|E%*J5?aVFn{G`( z&Xbred1E-3n7=)pHzwrFcGnu@-0Ok8Ki#pusg#%tw2`Y>W%naj)$Kg?YpEZh?v~kG z?}(o}8uYYg8v6XA_Sbuv)`U8dQ@MT%9xrn|(6-+iC>yKp>jrNoY?E})MY_m4|D9rEl0SYa>1$+dnod|p_3==pS$mxUN*xG zSjQX}X3_iz{kN8rVK#C*#XA+qBaCPNS7?w-&T*&Pnd+i{w|MXPZSoL|p5*yziX@W3 zPO&YGLN4W&PMbOekB^up4^6}n=GuP~SGEe@ujlmORjEoRLdsP|o|Bk7DLCzFiP;h3M8{x>;j|WsBUpRVGBikJq;nT~% zY_=f+k17!d;d{>IUAOK=PU&tTG*3FAUaOeB<1Ak9s!ni5KGu4a>EfGADE&{{J#FxO z77zFQy6FMQ(Ndf`LP~^YWA|D*SlT0Sg z&Wa3`N1i*BT6sAb?&hYjloJyPzv-Xpu#n%}r(KJj-?sR%;^KIcsyy?|>}=!-g-zQB z{bAx_J?l_SEMb|7Jc~!p>-rdDf!zG&c29rpND{`J`1dng`1_EqmOXOrgC`aVH$w!Py|>{Ki|`O{2Yu$BQ?~2iQ1{x;le} zoYnJ4CLqpR%{pouNJ-iukuqe(Z2e1_~<=6e%JV> z@1+rNlYcc%j*EHpMBqNF5xH@A_h01Zx1=W0XR=7$GuK~%8tB(bDqW*rg}@pOJ*V8_ zNWvaH*fxlq{y=6y8glbQhr9Z}!U%0&q}}Oq;=2?@4oTv2T%xvU5>(4*Gh`JN%EyjD%GdND1$)QEa1p`yL ztLE4di8lwRVaQo8ix;j!&eGQOc%^JeDE~~ien!q)|G7<7$ZtrURZb$9S4Lh=XYu?K zNvbaL#Z9A6_L!xSPA$1`+8eyy*EMN@=u?{SHm(y1jwcdxcPF}<;y8E3d48KBfoI>+ z^_3P%BqlQ}E&`5o%wtAn3Q)n9DSzT?|^&=NJLk|jPqp$H=U@_3YAcYiNyB97zr*f_n*D|JCbyIpIf5Qg~#j2?i@zW zycO{)I60JzT$I+%cFqTSO~rb9MiitL+&mfBA4Iq>#pWk~J zlGGm)A10AgB%I=uk<*uT{`XwqP8bV5-#Yvp$JzKqRU0`+Lz-Xs(w=B*^ya)r&a%-K z7$9fuJWt*S?jl9!%^izfah!^u#ku&olpL9+k7=r4a$moDjvJ11DpLO>a_WyWu>+-P zg!1^~ojrxPF8)=eA+$sgyQUmDvND3C4!#7W{OR;RSV*$Ig#B3`ykWjzGSPg#0 z@zvDlwT?#tXEFPzp_(t@&0x0KeZlcnYHPcY(|)|mnq%lfn5!IjwhOt^7KeW1bm<>7 z`(OKjA%1DXV+6-vI%CzGA5pL^W>Rtn`ir98Cv1!5$ODSabI@lU-nzQ$SQGlS@7F2! zk<%{4$s9pmWbv_*b~TuoxWrhCiKFj`gbUlxvVaq{&qwFVe!_Np?6xkv04Qgg_4j9> zu5TUo-n>hl(BtcSOOeydb`Lrtrz}j+dpT19s68u1cSsX3jQk}rw8qVyk3NoWFs{D=bv=EgqT8JK6A8icTVpu|z>4`P zdjA^>m`i#0^a?#m(Zt+09&DV4f&1+bk(*m`|@<{9bESZsV)OO$w1$wQ`p6@AnaE&x;@X~ z@oh6MWXdIA{Fb_9%$sPSjEt4P5ps@8P#$uQf#0a>a!c@-Ch)a5kK7;hiiG>dPb+)9 z?VBTXE`FqWU&yyDo>79Ft7rEy?_LBEEZ-d#@FN)YHOFU%Kmq8JQ~Rd%hY`W=n8swM zAfPN+J$-4Z1<v27u?Gc2Lr+(f4P$sYr?URf` z?jaSf7iS(qINhu7*fEg1HD~7|S3DmT+aT`gF5Hw z*|w9bn4p?^|KE%$)J4xu47LkU=d7JdIgdQi|7re%Nfv4Lj0t%ehI$~QBew1q6Br}P z)KkIHgqIO~dUrS*=)H>CjmYc%R8L&}8Aj?Z`S9-`XK96xv>~U?+S=O~9z^Qeod0MF z_qon`bndnA`4i6cVZ%OipgY{uQO?6Ym=UFa1^Zpc>caNmvc(QiT?rP=jeNgJ%6 zJyFR;PD!6z_6NCFYv6hA=_FE=obb_19qV?@vJDLEcNCDcx2aY|{rc>ueKU@;{7||t z`bS>a$#d~D_5+vM81NK1MgF~NIC56MNL{__E>h=UC*Nj)<5cv~9$>o&eyT6#$L9H>~Mz zBCzRp`|^MFz8zIJmK z>VmeTL}fKzm#4M;E3BWCSdS;+#Rfp}KEmH}2;=SD=^LY{dnr*j>^*PV!y1(_u~knn zt{$GLa8`B%p6{N|GumuH_4k3r&xVkn^t%=()VDJYUaDsr0L?(rI#&37_3nM=dQngE z3gmh}M;n0llG>iT894vf#S8iVzNlMPEZb(F028t|S?1$7|GUOc`AM-rknt$;l!6Z# zIY2#q8|Q(NbTVy9I1lVH<*D*OLhBa2)pscwD8J8iQT(@Ky_XUTpdTh2iEqrc8^lD^1^09;s*^XDD2&ZsO>WX_QK%rK-U0b^o233zb zbCghb4JsJT74An+P*XckX(v$fa^EEsvk2$3iL_~#@Ht7IVdFbf=u|qez41&SQ9Yuy zXI?jQwRWwZ_ol$U61hp-@G#-_Z=Cf<$ZKAtZWX>a!0zC#WgV-4^-pf4rU1F9S9wam zDcn}i+kEVH9ARp(n#87O2=`5{zoBG>@z|u%UAzj|b(S?wbCApJ6j4VX&71pImCo)E-SDr)%s{UTkj+BbGOAZ1hHc{rdMcrS`ycIp@}5Y77+dpR2As#yIhC zowpm~$K>X#nlPhy!uVTFlR6^YXDW{MNj4bfEc)Q5IfF&C<<5^KBWD>7Z}^G4{Of?l zU|}So>Yi-=g`DSmpht93Fq|+ddT>=EhHy=ct(~iI96fHlh4A_DMFA~F@}VSk8@~i- zSg#I={^&=aQuiW#%iYrfc)g7Q8q0<6L-(!thMc{|*f!GAhp4jZjLsvcTvZWo*I?rt=P^aoPjx# znN4`Sn%RgR)+=_0YpYDP2Qe3=q);9pS9x}Hr||nRhJVJLj6+01{+mef1L5=32e$4< z?xI=|wo4&`n7~c-(jGj|Jx6@5p{_PJ?fG-;axm$9d2XMy@IB^oYBNFjyMWK4gh3sD z;xTeGG)2gVThBg39=0V-X~CW_!g;O{BswYFpJ;HOD(YMQf{X4O*`8#LkIt)5FVw5w z^sHM@-_kWLM=wn?BPJ(h6fx0Sm&z$KrsOFLxr* z%Zsd0_J63EfZSrSVXW|bd$q^Uo5mbLyX#{}X(84(t7w{BT0GFcKG&{yb0Cz@r&_-h zVt?dU^{T%>-Lb{Nq<)4LnA3jG2#Lu7fm!~FUwtxqd*!NF9!`Qy<WTP!0Mqy8}7>d;ZSLGb0GU;Qr;=3hBUiep1Oiv3 z19~3B|G2-j`M(U*Cp~Ws6tO-y1Z;VToZb5O*|qLeLYEDXTDdv{_|NTUJ`wKYbVe(q z^m;O(i%Bn@wk88OdvSw3G8Jbk@E@79HmUH44a>43@)o+mx{tb-g_eG(9HY$1ZUpD4XT}m(V6EEk@8#uuNDu1{X#Ik{7 zxX`u_`6$(+tY%#nVSDc=)7mWDC;I;EC#iWL`jK<6Oe}-254-}6#Z;-PfUy>j5nvcUb^5sY)E@lb21;I z%*r0@Xow-Sdz@kh9z`%eahSpV`l! zv&$UkA!6g-Nz@y%HC~KYS5R-1^o~hs<^c6<)vR^5b79Trn@KU2S!CqzaNRP`Y*78& zQkjK1$XxEW$g=ergxkj||A(A+EHaFZJZw*WG)zw;%!l*YJzl71jMi_@N6v|Em^}0j zlj*Jwqcf8u*rsEmE;;;5@7!`R{rTyfc;!82y$; z1Yy-*?M!oEWW8Je3qIz{A5e%u`UZeJp}H zq0?=WIuey0FSDTUuI+~+7=B#!5`h4Aj=4Y2;Cps$xsdx`v& z$NbnIt?^`}AaK#ypI9I5I)BJx{ja-}*&khvb$zitBfTE`c2hLVvOB&u8Q;|EWTGTtNcRAFlWiSnW&L z#oWP6ZanZB#dwq9Nno;ae8XFvP{LW=AL?9?2)vLnLxZ;oFk)UXFg)Ty*xhS=cJpvt zT40gwy(Abp-a7AdtuLYeQncIFih4S``CpY}GH?~hJhw3yLfy*g5qXRAFr?Wjy+0Wo zq&7#(#3T^f)bxniA8_6urZn#?O$L)`hbW%+gJEK^`s92W%s1!$xYid5V7){#ci~hh zoa>Fbatie}y@IR|px$O4s|`PI=u9{|Z@)#9Vt>(@)jU;;am4l2X;{6Fur{Yx*mKf= z{#iGWQit{6n~`3bvhe(k);#XZ0G89IJ?1)W_z|m;QQ?w8c!h6+zcF$C6S;)D@jJr)%-?<=|51pD6Z7Qdmj-HapDyE0{!7f`ofkZ!2)+YY8W?FWMC z$%OW5e;wr|=0&$!L}#xlG_e!!&i{-3RLLS_SjZi;A8DdK=b8Vl$bDu2)CJ`(wvxj4 zblv{r%W(kC{-UlUpKO7twRR$H1;*$1^Aq=@89+Ia^fsW+7C0YvPM>Fv^K5VXp}Nxv z*tDlr$GwvY)ypaAzHKH@wx@~8Pjdl92Qny!M9)r?xdgbCJjP(Fc)Be7kQd^~xVc%DIEbmKOlUH*T$`@O}e@U&Ll-2w2}d zUNu_*xnB48!^qkD3!m@fdjiK_N~S}r02o?*0Rr@uUdAmeRs)OhEQ;i&3!iuMRZHDK ziG^lqt?FRqB%<16W|yg)1oSn(RaO_oLWi&F@c3oS=fz*cV(Zg^#rAq%dek5IA`Jsl z$SF65;%*IO0&DqDmFe98=v3`s`l(~x6S=UFua*Ri|3d74x~Id0=jzAXN0SL<^vA*| z%uilVj7CX9DojjfJMPv;e10WV;sMk&@MD(jz9r%4Lo7@nK@UWoB{z1$`0eQXNQqJ za;x?R`8~SO8Iz#lZ|hH3#HP&rQzTI2V?%b>(22wx?P;T^-#8I84ZmkN?nf<$1%n5H zTM%8fz&wkn`Yx5YvMxpVyH(e{em7tos5Y>jH~^h96DYMSggRemXycV&7<8=q+gO`P zXhTJpmkIZe{1djvmy!*gQM(gUJtB#Ded5iP5Ak{{zk3$H&jHTX&4OVwD`1v~MC|QO z2Z7h0UGg$)VE&7|@wwdzs3(_3ZF-Xq^l-an%aKzUuSNSKy@7k=ZuG*p>A*?3HM#;h zogt_AMJfR3*&eZz$VZMWZc;?9G0plI`)wvsRaqq?^Ev~}8=q@$#Cj#Qp7KBn`zBBE z(ZUJjoTnO+8pv67PrHWQ4PeAa{mU`*zx=HpHf8H_p-xRyV~%?WFe^@Lcz?=3AEXiM zipNX5uj-s}I|8UBJ2dwU^$~;!LrBPsocYak^S(Pv^MJ1MF%YhP=C@~ zU8g(zbR{(Qfcx8RSjQLiefxxZOk&w^0Cimi>c8z%XO**o5u`gb7xkFzvRT<>Q8B=J z*S{leeKs&_9dAh?x2x#Aw@Ew;^?#Y|7R4N3eU&;eaVr;o42SGu6Rd~J6%;$pVVyi7 zv2^P2b{I}x=VGIe@t>cubNw{b?MW&=wn|pu^5$*pB-TmZ`y`1);>eAw3eu7D@5wT& zexM#ccsZj^2lMn&@TgU#Be30aMwfke1IkQ(F>%K{UAVf}K->j58w9E;L0&*HTa}br zf&9dcyv11GIDcLTi;wvMLwTRd;TY77&qiN8Rd)qh9YOx5@i4-xemK9Z8GYaC#mB?t z{eWrg5%niDi0~%r4rjJxW4~yal`DKNU)f20yDtZU$u>=&*@nmW6km~B<_DbPmtzLL z90rE$I=vn~9>2Mdy&L(tjEcDhg8@)iBDZZP9oH|<^@HZD2ryZZfA)?e>N(l^2j#x# z2actlUCfRJ)w&~I%O*mB{_RBR$dzcIjJ$XlvfB+jOxi9;dpYFx$FoB*0!?6vSZG`Q}|u8 z)+e3_GQ^HQTOI?HW4S+OOZ&mt8`+=P9f@Sb+sHXB6Lkx2X2CW|l}mAiHsHAR<$uXQkCGm& zZHWZVz_K&97RCT|qpfC8Gp=LPzmin11Xy!+$nN)o7%)Hm^GeXiOrR;Ks;~N+0G;kH zjF-QR1bY9#1HUGWt1~}BWAxEC9F2A-B|*TR%9rsHzK@sjW~*^~G`#wi_TQ)9SU)?o zbhAEY0o{nDyX`1|iS=-I z&(!_xx0+zNx@Z(Gu5X>07va!w|xOvh&0cV7L*5N-jj4Rsp z2D6#pU4h!6+c$>sKuIOEO~U(%^LAd=`*09=$5m$ih++eeePe3*Z6>f(79>Z0b%nb6 zRodRsc>W(|U0aV_px+Yle%KGRjdm+Ge8Rd@wy%!+(G!?^zK44cy1|;P#V%eU7(W(U zE>RbHfWQM-!Us zXo=Wa%-;$P4b_=Bz&v;3^t4tVV!o@kdr zvdFm$4(}FEU_7g+-&rYq{?ux=YySKcqMFWGbmAe-=hjOi$As@oREGb`-}u0q@5PnL zZ!nK!{{FOi6bY=ot6Fj|FbMC%8(k0Kesxg?#9UCHwARHP-1i#e*;I4>-!-YgYnNU5 zVL=**hpx(dn8PBRP3N1so?!gP6;9|#MnJ&sozLWh;t9L)fPS$K&hx$R+bd>9K$M-g4yLsdzFN_u*}nP?wryIUPk^N)dJM9CBxou;S;G zZ$iFMiBg7~n`G0xVn;Bs9w}7&V}^e3dPj1R@cC%Zn5CbdG6{3ze`W_>;rVZL@|uCy zMZ03A%Bl4rYxaz_JVH)iKR{i8oNnG{WzP*J^b+Zpv%cf;+lLD+@p@Gc%fG7B^(Xuq zk;z!(oQpTztdVmU)hwvX_atn!3R`A0>ai=M4KM9jsH2C@t&!Y`bzFNi6j~P_Gvoan zL&hT`q!B6QF(C$}#6%tuYC?$181KBF5eZ4C@n-0HmPcNr>p3Y*nKTR;Lx~U(Bje&5 z_gi<}ue;W_&pKzXbI$L#_E~%V_J3#X(bg|3pQF#m9NAnLww78*?bWiQ>T=&;s`44A z27?jz4g%@&E9A9N|(F!{YLk2dpb4rg;mu!sv?rD>>bNex%&Q#>0J&`XN1 zfJ#@WWsxDta@7Wd{1y5|bW8Ib@n*uqE+!#q1l*NiJ5veUg@j(6iEnsnZ1N&(L;6vY z2wD5o>OjL|RPyjr1f>aN9(-T_`4s`VJlrgPHQ+&2lUQAN6KJrC6j6W=hi3Pu_HchW zw9?RIVSFi6wOreC_AJbEXW$Xx0eq)^3FJ?D*tDi&cZ}DSJ~@}g*^i!~OTHw1s`+}V zai{{ydY;)hce1~tOyy060o`gGQYd1Iu)P-k-a^6P+lo#0GJyK9$t3!)5wG!9x92wB zG;*ym__G4pMW@4yoN&2bagW`x^@)n`xCb)k^}B@acT@I8iz4`)okL8H1zob-Lym)# zSzt#VAHZO)Y38sY?PhxPxd0BZwQGI4m3MC@#xYjk?v0maRNXcu$<0}uL+1(I1;*B`jE38erLU{i43VOGzd14W=lqe7 zELP|VvC9&@b(E7``bPZT#j4F|;DUk7G1tD_^XHo1xMKvkOg3AC;No#8O=9Qr2NBlI zF&*p z2_x3el{m_fg0Q58q0^`bmAgfL(m^Agiv#gnQ3*9LI~Og9?aQl;rq=MmI)lKP)9^Df z$7mnDAEt+G%rMZa)wkz~jLB-rS&Q7V+A%|ILFC)GkB@{2h6^}6U9VZh5{+mzDkXq? zXEa+y9|Ng;Im~mg1QC57}9aQWGu2ts%CcU2)1 zp)j#2b;D(^pIf?XHk;N;Gr9_~6MMUdn&69x^P^fF7-nLAKtR-7A6nMVa+8Go z)_$)|hqm$*ZSHgw0w!N)X5F7V^<%(qb}-hQxa1r#{)Vj;LQ)TbU0wRKrrUj5DUFpx<*S@DaPqj<2$d4cI?HhezVOV_x7(ye-pNM^RJWxDkn40~M6b6QJ0kvEA2BqT4^0 zSnV~1pyK&C=dX2e<5;^N5u+!>H&_OnwUr5S7sPW6+B=W&ZG>Dm1!=><(mv+;c1Pmu zmurF0Syg$FNG7g9fFg}$E#f5SJME*KrV*vZt`$n)rTfaxaE+OEW5j-hy zIj_F-1FFME<>eh3`7UZ8ANwiE=H;X7eM&rE_y&W56C}^btK zcGck^sWkioGctHHlu4W0xv3w`TDntNt>XJb))||J>7UgeUF&mtdC^t&6VLFNf-*7H z*aS?D_$XJRmX%`N_wmYdbRtvjlZk1^@W?eOXh%VUUZ-CwUMeNoOo8;NcUB6q-QL(g zf#LjM`J%Y0L??q5i{%gFOZ0j=@os`Xzv>=;>zzl4a!S3HFpat_BvX%4fk`@wk14I= z%UfAy0$b{DWVrIEX0SloVg>_A>5&tSwyBWi4HBa`blzroS&T#Pjkt8%qZ9-a%jrGS z$6#t>k#X&Y@-k~msky<;hz@WPuFTD&H}AbjT5Z;=xtDvnPY3()Ha7wZ#EO1r;S>u^ z2I4Neu_A?m^B$FjFyH`niF^1DjF#eYkV~JSy6dfYux4QoueFQ3b~+XEDHn?LG@s}I z-qdh9qMk}SQ^J$)b-$}6U;KwoR6Nj7xI*CVvPG;0w_>uhQCKH$10bq8L9>`=aZ(T3C4DXVpiRV z5)lu+o#R&{(1Lx8=~L+qI>L7}$jbcXx_)Ziv+;gMWl}CxovfCDg}dcW7wJ+iD54cw zC=lWkzHHSNDz<#lr|ZT6ck3?c1B1MVdzjzxMwQ{_-giQUnq{`S)ehT&`46s5C~uW; zhA6fcN5!=723BS6SpDQO7%0p^X)rPsFzdclTwTDQQDH=vu6X98?3al5z$ z1Y(>$JpA1}oCAIRF<56Gx4+fCkJ-0<{J!CrBo?GaUiVv)ENcof9rB#Yu!JHk)T_F- zw5T8(V`G(-D^ZBa%H$IbF&k9A#F--Dp?IJSxFz*Ohp&lGj6= iF5rKYeoe*yk{GW5|2Hv~W}IC6SP*-(v3*eg{_a1eIL31T literal 16801 zcmZ{M2|QF^_;;IBie#${DwSm4jb&7dN=TBjj3k7tV>e6brx6*IWUP}^l&wea>8V*t$)A)22;3 z#QWh*;K-u)tJa$~Et5BGlHDY~DJz}%vPW6j^|EEI z@`ElRs{Xrx%CfN`Kklu;)DR~^dQFD^SV{tS0}PKNu;(~0Jb_L=`n|pH)8DwcmpWbR z)vhe?8dq#^%(d(q?2Y7#Ru?2-19P}uxovu-y3?ziryE10)xtKKeO_`d0#?vF(w(ur{2g^p&ldVMNiyH zeE?qmS?!p45%*;5XQ($}Hf4Lus4#ln%ct{1UB@y5LMEkXDm3GjI=e0>^xxlkE_vwA zHb!GN{NAE&$>eY37k{F#ZaAp=wiM!soZhvc{Jgzy`Tb_X_}eLo1yPJ&Au2ULcAx~ei^B5}ol9?8 zE=q+vin5S{WE;ozgH6UJmzJ#`{o*|bzm;tYX}dx^E-`&E-7f(-evbNf1zR57z31>G51_&QdUnD)7dUJ7YCy`vIiY6!CMA7d9 zt0XBVDmIJr2IGg=BQ?U%*xMIDHAPW^xr-%}nDw*ZcR$R|C&b=ye&^)SmdzQzI5tFd z#pM*+mQWW)<#n-26gC)5PVz-DQh@(nI@8`VT&H1>cvPs1CA~;u1ZgRzcaja3xVmaGLEA)TpB@9>G)$O*1!KrboK5oIrn3ai{>kptSqrp9FYI+FJ|TbbYu&&PRciYM8p8(S+a zRAl4;BqioO@Y7N|_Z?Rik0vGDfvG<~%0tnUE;+e*IGq^z=uAJxmr%RYTF&t+NSGm>)x~dV-Kf-!Gu(+CE`8yUd9(|+ue5MZyA=5@6}=sc>Swme zTpy#|hl9%|5o!l=8eUyN|2+Q1b5K|^7~|2Lc+={Nn|eGl#bKy#_s>-F0>C7Y$N%op zGW;Uf^8I{5rFq|n`C`kj(!)E!H9rPtTAhy}26Y?Jc&p|~$;8hzfu?5^@w8lXV3_HS zFtacRe%riVOQg4fny>2;dCJkZdk;yr&_3)kQLCh9;H7`0M~mdpL4U6idyV+p!p%I> z@n=oH)0Ys8qE|{#ZpwO~t<8D(@lO{%jr=-fUe(6I7Hx&K&BSy9hJD*>hHCA{FK0q5 z54TeZ?VCDifx+v?4qv&U58+wL9CLdVa^q|0(9csXg0=FZ+6k4Tb>UICEc(6&9V?AX z!AV-nL8+4=Qt=8AfMQubN2>M;r060zDP(c<2vF7pZzwi2ZN`j56B`3GBaVDLXhs81c@o`kda=HacJ}(07l zkS%|LT~5D7Ezglwe@RGV#6?P^-I>+8gCX8~N90iJ6L zM}s50L~@VkX1_aL!6|uBD@~(ezuLXWMWy4;3G)`)Pk4?=_tB{P-wc2Sv9uo^?=E)X z?gpCdKX@XZC)uUG(YI?K^vX;s*wI}=3JVYN=s`c(+amMFsq%+~?$u?Uf{&7AwDqOs zWX$vnx47XQV1C@w_90x%#b@xu`APqIZ0Mh+#J-t5i7n;QOGCeeAHiK0-i?LKn8uLO zltkASX8{i;NyK*exz7%-Ix|&jYH{hSJr%k2Vj0YD6W0G^;xs^>1b#FiB|J9vDEfrGZrVQv8D_M3O zi!78dCaj#!_zkpVuKH%(GHA29Gi@1DsKNDGh-fAH)XOO@H44Dbr?E8`i=X;m$^Kc& zD2htkvlj{-HWP>%_MeD9>viqoSk|Ey#Ai)lP}H>#ld%SaK1y0@C+mF30aEK`d*q-k zANm&pVoZ|VM+4?(<R|kA`x#C;R;{TtoHC<37(!NLSs= z_Y2R+Ja5i4CfwE1j#~L^*5RXr^XQy}v(qAsI~voxDx_lV-blWqYgf<2T?!AC2Mo8N zqv-f{;CnjmS25NA`%G-!H3F3#$MyZ|6Tu&OS{4$OtL{URZu5mk<{tGGi;x*6L;j7h z8J1u8VC%LGy?#*y-u8ZSPB51bpVB&=T)ltE?ZoVj50kk)<;K4RyJewor@k#G%(iXA z&~MKxUUN~eTjV#y*!2#a@cV>(0bO{#gcyNq^dtx#+2pEuXBp2^)VpBcWoTjMmF{_$ zMxe~+rQGHPP$R2z?ezAp>V%vM_|G!FMbhC@jSd3vN#{OLfB3x%%gsHCyS+;WPoTgZ zAlUE9D$(4FrC(Iz;ay-`pTxOT+%dHSap74k3_FW60~t-Gl|zY4FWc~A#fm@)7LQSd{T2w3mC#vHUnj4&65-9K!WB>#0_7rZjv55_p(^*|Y_vs&`NY1tuDQS~I~ zboEtwA!ymI5Z%O5>RyOEOwOJ$=q5iLzINdG!Tjyxku*S799Z4jr?<*|=meX=e*C-R z@H1r`LKId1@xtjs)%TyK?5D8E{2t6~{Y0mr#oF`w+)N8{356h$O|;h}Q} zt_3$`(_1&S=zLWqeF(FCIXT?@{Y{9;>E!TZyhI$`#?qM0v=A|t>q(}X@|C!{fho!X*GKdW5Ktt!{ z$}4jMzD292hyO-_ztAUSHApy2)CxNsYLw~Q@XV(Pq6z=3LY%}Sb6;Pe z2=_}zJQc&ddS?C{y}B%A@LdIyn6eW)5J2o=D;{i-m0V@2L>_{SVI+tdjci~_T{>`D zmy+6uCSzNOQe$RlJn=*Iv&n-;mdbU$HeVj9-lO0ZH<0wb?1O$wXqq5Kw0`D6U8c^v zNKxA(s9g(DTGu*o)FXo}7}B9%*Lq!WEdrCjGTdr=G+b0OpS^ZJaV3c;3cvmMmv@)C z1^>57+}M4kUN)(#h&TPUt9q*R$lRs6cs#iRP}pO=ps-foWCFtz=f(Mby$Sn$%wHdg_B5ao-sCO_S%y(`8aIK+z|!&r>TnnJpcx zO!GA0suWgw#VY`1l~Qfn{s!uOSl1s__Z&D4#!l=NEwk>ik-%v+N@m;(7VzhJjjFct z;l@zJ!kxVsnM-wFZ{B@4L-v4m&k2s79}~Ga&(MP%>o54_H$MfiOsec(O2@!^2DFBi z&r()eI7hZi_UTJWH^bH&&cM3?9L^`~TTKJxRq65km?n1)h7lUy=0j8M^f4zoV(Bhx z7yiN3RY`x|rFZAg?W=~$AbvvPL$3AP4e-?jh(gxn`eN|Lp0c35MAG*3YOH6Xn>w7) z|0}pqnr*${{!jlev@POhvpnax2>Zl-nJE>iiP4*mrKHl?8_9L${S_5;69{v>H$l?E zJn(yiU7-TR3t?PMcjz^~Vx`fFtJ91mgN*rm(j3wbIL*E|T2EgWJUC0O~RK4fE?OPmK8T^=G$GKY{$$j544=TYD zo9JVfJZ07%*QkQ8$4%E=#czg^nv|=)Bz{df96UNBeaIsvjlP*4h+-KbiAcn7ozr$N z9p-@F7&x*}UoXgl7f^GqY*ka!biUGQcG*QAnVAgaZzn`H8;CtyfKXEOt4%QzRuaWl zL$`^(0YKX*%UhQjTR0Ms0wqXA7Q+6zhFAcHx&W+|HmWm-tE!+oPbRpi1){j-kO6#d z38)Xiilmff8rj1Nfd5vhTECepeE&;m#Tbj~uI;-DTrVwrbBlUcN3fOf(dPeKTqH4t z%;mMo`gzEK7%-*G!O-6O8F2L$r87NO^vB|JSA(NP3tpQx8kS_zJZW#|F}iIjyXj2M zwOFq7_7>{!U48BOf*E(Fn=&FE?J{T0`Te>W>4xIB!te4fHiGR^`N?99r*!I}oyV8S zu5&>iEl3t99%yB|syd?k5CpbpaoLz*?}~AzNU`$vrBtV!ESCc#f$nb1gS34FPqk1Q z=k;qa(7@~~<+WmP!8QEi#|MG;X8iLdzLo|1@3j))+R{})M-%L>&*5zo4@w|aKl%CJ z|1^?yBt^9qkhlXvJ4`5cXH)Msk4GiF?$<(x8%%^Uo*v?)*nSPWZy$Zc`D|eda9)W} zZ1dVm#oC4${kn{&Kb-ykz+kUad9=^O#y867eB!j?rKx{+i%3d(VVDIm6FNSaD1H^{fU9C zx5iqmSV#Emfo2Ct^$8a>U+Kb@@S+F372YmqB>kjS9s{E(4%S@2!lcr%=m1KYl$TDz z-J55lpO?A5e*HDUjaks(L=zFJ8{zqon0^fXa-hxl3gmg2p7`Io51ij&U{7agx*qWu zkgY>Kg588ypCReFJ7d5d;JQzw(hs#uWG3|wVAEY<(M85d(>W4 ziN5o3io?p4ZrCBGrHI6b4Mo>N3lDxtJPwTR2pA4nY#=M>M4zMdBha=YUlc4hFF$6T z9u`w*+c@U=H7VC_xyTH6`-@hE0@Rc8vC*44e-f+n4OV*xYpV%k@hW+|os_Bwn{!mk$LqqK~)NieE8B*~okzkQ!H~zuH*! zU3pgOypzlMSbKUIX@k-x!5yR4Y(J_d!%t9X$XlrYBl-jXRNZ-YebTLtHhK#cV~DrN z^(!QNbfSoj%UZ|>-8A?fN?Bw5a5_oR)Nz)E@I?ugD75^&_^w6gl}OOa$GF$sEfqKPVH;^Z7H=)=_UwjHk{PA=)wl`RqCZ8w^ zp}7!>YYdRY0+BA)lFg(sZc1DK1N+c#i?)^Vl}1=X*rU0mk*_}?SAsH@Q(9|@0BR51 zg|=w{`H%EBfW;=rn#2d^eZmCFGSSE$O9XI0kO6;miEbMpQDQjzrMo^7+#)`OuwzD$ zI}wIFnPQs{qP^U$5Sk2O3KD=g1nv7Pr7=bjc0q0%l>h+kTJJfXb5q(|Y}vmpl-Poa z0E_Lsk(V0!$RhE>Z-LB^2~*Cx*trXjq=SB(3A`zd+0N^KnWc|(Y6bk;ak0(cwjeXw zz6Hq#|2`($^S8}*k;ZUfahpC;x=q|AgtnhhtgMd=`vyp`fY5d>$mJjW*gBN(_1ec6 zWt%#??k^Ew=@EKgGe+PY->jB@x#M~mZw0BNz6#1D>)Q;sRxXa9_xi)|k6e_Ou5a(v0)QWdqh6AbK&~r0VKWXuB2DJ_N&D;- zRZY1EqM$G63uvDf08iHnWc{?Hp$Ukr8?01Q1I;C0Jd#lgZsJ4}4{UYxi_AxmEo+i9e z1(~u4M3Et?X$?kH7`u_5WN%|gbuY@F5vx)ZAcnam!JDOwGa1 zT?ID4Q#23LDXN)Bf14I1ZX%@M=Kyub5|a>#2*C9}+c!tjZQQ=IaM!R7#H*GN2^e}B z0ie8qO37O6!dBQ)~c z%2vu@ef&o2%2ucnK^7SS7JsoAm8DTaB$U#B%)IKJ^fwGXu}(&syJ@4>SCs4bA0^+% z=VX29ohMOme2X=)Pft3ZGz3PuoPDyd2^?g+csX*D0xfxsBX;IRf&`^NZ@AUifgC z{MMBp!vu~Ye;+?#jcJHF4NKN=5%JR9&jr^2wvs zV6`i59v-RtVmgSd?vpiFSVWgRwexPV2PzjG1kwupJA|C4UxYt*g#FQv7=NnY6$d;Z zQXROc#eQ~eN@7%Tc<0j9lL%hV=4YAlCVzrFlYH>IVL(ui0 zs|?s!ds@;UvwK{U!b|>ARbv;l4KdN*T9xGfpkJ*4bnt7!OTU->2O3xtpKst!o{wn1 zPbe zX~9i^9CkN5U{}rlnKMRrixi7tpF9Pstk734|8EDwRKF z)RbtOADOP}XJfxq9^0}F&o@JjMnX{{@lF*hQV#ZBzksGc(C^UkTMiIyUu zLIJoleiHce=02SLK+SLDqeMjrfiwwKi_sct*1<-q?ZD;%%Bz_m>uFK-f09epOrOG3fGd0JuA4xzW%bX9{5hN1RhZj!UI&fbCe( zx7se@DfZDD?*BMH145q>rjlkrjj^LPaR;vs95v_md~d{Y8b0Q{|J7Rijk^^pMKF+j z%sjp3Z-kV=Fi*D=D_l>z-&RrPbiT$=y{qC=s2xm@H3G-kcs^701rQuBGq@9USS$GE zZ0WO6k!xoXCLg>rlpX2W@jBwEx`{^>1iv8py=#^*i%7+m>Rb)PyLR3{xZ)NIOediP2>)c3%fC;>t0f@W>>#qVhr z#i537sKk-W7zRDvDovhcNVzVfCQ0{2vAoc0Z-X#ZE(riuW6i7v$0~IHvH3{Cluu~5 z1#YH&?1T%$?{9QU8XS8!()3Mzl_A!HC%_?B)+*{i`X@JOk~U;*3bZSp-^R-JusP#n z3R&whvd8I&JtZ7$O$-}d`|(N-4V*qgxlXO!UM)ARWS{_fncd5QDjiW&te}F74zo#Zp2p{2; z<(x2DuD{PW&)Mai|8z|a%<2*XsE%_62DifWA?=F<*;*rH^%a1Pd#%j%XHyDUWgur+ zqS6VNIf3K*c=?zio>>SiVh~)aXEyS!8fC9ca_(l8<@*(Fr*8_u-G+tvF+>=aD_r^& z_{Io(@iPC`AU?T4b+}|o-TF_Z*jQw?b?^fzWq}C_^bOee><9zm3n1ksydqM!)RD7e zC7~+47#>;b49!i?+u?${Debe3ejc53guh-7l0>EV!DWCZZ|+qL`w8`VL85mRmn<&- zJ{k=t%uZTZQXKT{$9k+Fr&koDlJYvN(z+np&m$`dN8sD3{DW|v;X+GiC7+v$kz1H0 zvT${qFQ(~D6%UC-ett8>XHzZYAp;N4euX$~R2@J7!8VD#e(J(o z`^-3!{NcZ_f*}R%IuQT)lb|Z@ELa#-b7eODOM|2)&Y70OW~6mCI&n|(jDFfnNL3ZO zPej~tOpR(j{jsa0ReiOp?Qt#3?=-@Lay+e92EILedQ0^zP`m2&q^(Cuw?F%=m){33edEW#ybsW?G+ke))yq6u4KDGBzdvHv@=+9L*6<}AC$izKhYhwK<|KdtaqJ*VJpwbDB15ASi;mMJR1p2N=BO+$maI|DW5w%KD$swH8)gpZ;zpG-ku*p%_l z#6QY~lM320*JuudRlV$;wY9^T^mea#n0_q$ViCIN1|b4M! z$+cDT%R}mpQBd3%!zT)n-C*k@soBAxN-gYDsMLmye~9^5X0w5y2g&_}OGqt6gZ>~I z&Xr9zZb#r)#bETLv)AWyneM|ogrNx1cC1~OOtr@!e^PWaTBd)NiDo&2&VwnVqeWkJ zzI3NAowIl6m8q7V9$w6H5a=YhW2C`miSygkiqMLmscAEP$6!KLvnzV+N1EPC&wT>+ z!UVK9tZ8RCwd&aM9}EJ3yAMKhApF1)0D>N|DEQjrPU1Z8HmGLIHk+iVDr7UcXj^fh zBgg=*nH8z+5KHb2f~IbE&(+J+zG6%YkXw>lVv{FUJ4$~w+BQ(!G!4it#HkX8Lpm3m zUy*XfSGgr(0j=zPAD;F}=iU5CnjR(5n46s2rq=?%PPeM|33z*4Gc)T0#gE{6#0aP! z|KXA#tT5S~e5$LkmYXM#E%ZF-Mtn(tf4pDBI?2H{TjCk%6F%tqnlIj|lU##c4 z5K7M!=8=5~_R|~}v|c-anS%Cn62rxfxh1;9NbUJmLbW0`vfAIE8Lg%8+<+C&cIpaz z>;G`DJali9_w+&1lO0_Kj8yU!g6yp#1R{Gb+j4(L)4Q3MJ4P2vkLkffn_@f8W-XuF zRyFtM^~|X(G%vb~3>C6I+8H3;eRRxt&{*l1OadYLxECZ!Qqy%W#TR@yaw)349Dr;` zaDqZd+K=+LTUWc+%zJj8nEvN%K4!_`>-jLX!dTsD;zl0;mQdkdqL&HFER*^`+9arf zBXz$BhRzO#{|N5^utF#_h%ZJTTDhQguc`-tbzG`V5i@yUw$3?(PZjAIkpE;1u?=^G zx7*(4H|gY;Y+QdiE>9}J$x`VMC8$jaZ}FA>ro=^|SQDIz)cuFr*zxFsP-{4s0k0z~ul) zey)1aZPdTTwToyu*xFzkQ3mGUzw_(~=tcHk@=0ijP zPaTA5wD}8|+j~D2W^xA1YA8%>C8u~hu=cMCOM0=`~VbmKDA@c(CzD@0?3zw9u{j%d9EKR9&X7!fb76O zpGyj>rrF*`K{J5--32zURC@uuHs*vFZ8u=#F)tGu15gRWf6svv8a*7%iPA2BAQ7JV zuo>$sr^{ub{fbPfHRw|DT@5Ghl@X?UH?d`8K8u2RgQ%Y3>b z?%`^^G`zWqxE>>S=}0Chd(8iup!ONVGk=6Ru&-v4#-Q*Ivb?HF{hUk?svJE?ll^0Q zXME;a3SFBZpDS9>e?)AHYr)`?a?BBWbql|Sf}~Hss*m$Y^Z^r!o`bk&-eiM*Uph6b1Xo1w5JPsbO&~D z!yPZI(Prz_)po@ipH*x)w(G_<{d=IHX@y|(L#O8ae*ErMH#(`8IdNGq-QJkBRf4nv z6I6#SolgFX6EER@z1DgB=4aBC3l`ue$={)F{jOXJuZf=zFhtNL-Mg|ur`Fl8ZO z|MOS!zZ*Ox2qr#MH)?vaIln{P}4^ZwbT8ms-s z~5$I){tK}&RfJNsMiV_^y*>sv?BF_&&h}blZyb>=~c)VtuJ}h zAbD1uG5(+Xi|KjWMDn17*df!dbi|1!;cb(e$rp=99Lsk<8!i_f(G1K3b2dUsPnvCY zOyFi828vRS=O)hH4u=0?mY%G}y&950x@~XyL25}nIBgA=*)gpM_t`!#L72+oC#)1q zRF?gb+>8*TM>p%M53H;s7j1^e=G7{>?&&j_KZAYF*l@EA!L5qn;_zfK%8V|NNlqw* ze#Bci4Wt2+;?>kJN<(dczY*2nn5{&V3>*RmLVvwH{lE>p1WT;+Gd(!_gSTjz$3Bv|2DSRN|8YX;$D_$j@kIu;YNu8zA1!)juZDHHsNG3w4KHw*?)gi zRVM$I@Ne?YAU=#We}Cn?TgD{K(|~yQV;ARbB490BABj3lIZVZ35=qQ|d{0XZ@?_S1 zCkN>2jH?-n|Kjt4Lr^G9gW%#ED7I?6qZ1{)0D(5)2eI|9a8aXjuF`sLqL`t@*EODx z9VX@g`*MI>%Xn#pzK}5PCzc*LZzW8r-9%wkDa#7_NWEkrRF+_%gyJO_*r)RnrbL0#A{z)nErdqHvUB4e zFNYhaH54M=V!SjUwB1(WncC_OEjO7Ic0JbuzT#Nt+f2Zi0dEKnTQ*my+V=;0bo$aFSni4OpVRMg<-tMc1qy7+(A^KCpcOwxqr?aflpnyo%#=XpoQ zzwS1~1JT(JdYsxPnoj_U3a6XQ$^^Mw&v0}*bZ*G6_C;;sEk*IHH!xR+-RiRkFY2E~ z+nSL#u)Zh@-X(qeLg0iPK2aK~RG@SdEJ6NV; zq^X2afy+pN>_G)I3fj~~; zDcH4v%@Df1*YG{e6S{PNIEQ;5+dV9^=0<5QG67kUGcM4Q`nQhMZdJ*oJ~`z~1|AkO z^rKvl zGKc|H%ZSodgAfcTe0k93K3sne^@C*~@AuFrJuwFL{ObiRY&qA^Q9 zP=M*F6Xx26Pg%&$hY$?hv*@6*{0PK>Xn2w3KY}T`8Z3|yiOKwr6u)aMb(WP9eZvUc z7jyTGW^80>^XUZUBB3v>>tyw;0kC`y)@6p;pJ){E=$e;1+NcWvIiBm+cT~)gCkW1F zx(af(oiy6+)*N2+auo{ho!61su@6A)5SOL_T8SgEe!m1BdZy@CYQiBaC0U$(QDAC4 z3W_j?uNILBo9!aiI)6;ejZS{Palpbju@CDw4@hD!v0;kn#!kS-v8Bw1)tS_vlWfAu z*i_7PeVc_c)W0IGh1#~Uhn;u5wq-1Q{a9;YD|age&SV~Bj-k~V0Vw{}WiNy!U8WNP zR6QjWJ9A@A+05t}$0KUQW=sSq9k{cg_SVv7$c#^c&r6v+CN|Uni$^K%PWI~q;(@e$ z3STM`#DtMyrkOoTCn$YWad?Q2LEtm$sTc06mTzlK(_&tQ^+Za{fBhRTZn&|(<+cU( z;ajXci=1caHNV&m_AdBi<3}71f`Lyu zkg~7VYoP7D!`p6y95j&PWq`NRr4-6M&itZtXYW{WPq9X3?7`>t9!k7y??I|d=QFju zE!8t)lXIp{v8BHL}=7cI=C^!kRC6rETtQ43kq>!ioY^lkn7@ z$#Z?8W`O5JVIT8kAZu|SoHq$n2vb{qN%5atXBSkz5L(Sp^na*w+js9l6zmOC1YluB zu1L;Fuj+romq&`N-&p9l;gs5Ah`Xy;jZN-|VYCc^nKZT43M!l_VYs|!ERj+f4%H&V zM?%dt#xj3f`yjNr#l1~nxSa99`OwXQw%&A0iPVOKpILTFOqm_>0FW76y0!K@(g$Q&rF* z0w3lZ4hIFYM3p?TCknV(XPfELjyY%5~M*`{vDA=&Udccq2a!PzsmaF!FR zY_HBL9=amBeP_=}JTwYxbIN^&r!g-9(15DYVYWQizLcc72trk0>W!I7nz|p(9%tAk z_da9S-i^R^7bs~H)k;=yLmb;}NUm#43cqmCm#JP|(f;G?HZCRRKEybg9Ov#!m}_Yc zxZs@!gzFJjc(-86M0KIJEwaFW<&9ub_4r?=x~dP*U;$wlvJ>u$T?p7Caj+5t0ANV9 zsT-RB3Om(=2+5qc9O~y{!Ex;rtRgJKxnmAnFqOIe3!Y}bcdEk zDAqDWF0}x-%SE1tV;Y*Sh;-L{DP=O^N@yk@U=QsiMh@&r=rfwWR5be7Vh7$k-uVbU zOMGC?&Tb*1?#LcDhx#nopHayI^4%-6USYe01=W5b*vH+{3PJ!o`FCJ4`+m&L87V## zPX#Wu{@n#nSiaCAoF24jLyhRV9z;&)9($J*-y1h^`c>vm$iaG&BxA$3aP!JmpYTq( z#y`~;DtYEt)|B+|f)@HP?|Y$g8PNwoy}EXyx~1keM(mLkPYZX4dhU#lg{YxCZ&OZpZaB{JKYsk}$Wu^au;LGoo|KbFGkghdv5(SG0GzE&X{ zCu8)CO+)7#x*+eb!_ZBqv?!jp!VW_S?lTGM@zPNkSqebRJlRsvwyne)gu}kr(ddA= z`&hdbezPJj2J+3Z>qlU_@W5J61SVzi{ggFcsb9=Nujvjg8p!;^3M7n>h3bS6KWSJI zFY_hQ2st6vnLTtrv~8!w_42_yf{b!V97GG&>wVx&_Q!v1o7>zJKqV5lVHdingpzC-cYd#MEh8prSn9nBU43+1-2|0Nj9)4~A8?=UXQ zzmdN{O`=M-gDOtaj0TGx0P{ z%ap37z3K^pMDU;9!pF&eg_+GuCTzFk7yr%7qu>7DIW>`(ogb3kIWA}J+c-d>;rviS zOR?Zpi;3#v+{POSJ6IY?eUnIaxYt1P5$svnFk~!s1IC2NarJGg!^cv`3cc=DqjB5% z5)aMSd(}3F#Z`p1@qXHDMX1w}jYIeX2%4rh{p47_mQGXdyk4|vlhR}0l5z!+Ec^yw zw)|6s@eH3$h>Ta0w2@p%qMEA-zVZ{;`*X?IcCPAB7iY^*o1o|ZW{ogoaGBd!3CVF+ z;!7~54z~h104o{OdyI9VlxckgJ=k!HQrQf0u5!)S1(i4SAG=CZT@K>ss6NYs6%)I! zJv}4NwXyz(CHXg@4ylj)n_YLFb3C`t{Y4oELq6#lD zgh|OZz;n$mu?-@xlW0x2bm)DN?mVl){9Jl^S}^mc)m z^LezARHyI!SnQM(D7{=Fz=F|%9ROwp+7EmHhmm4-qsf9+fDHTihGo63!F5`acifj| z1-9|o2*QuFovGDS-*?=8efxAES2EX6TA!Lva|YbSnDhpva^uuOgThQ^o$jSN_v7)b z=(QCCq)is@$0YH#baNrEuRjnE11|#y>Q(R5etIy!@u0d0$mdKm>xCASN@l1LAC3Rklw-418vouX{rc+<$lkX%u+77gIgTOQ#n*bl~$pv-l~f&3z=L30#}SNq)fS`>^z& z897aU0KtHYVam62_}C=&CLrS!xDDpp@BCXS!{X+p<$F_0p^p=&DT&7*16sLcU=J&# zNi7RF|5y$WDo~EMvzDITTNT%)=l-_4X^#f-9qZ!Xgu=(zc&yWMLY4iYqA9MSIq|_c z{x^v9%GiuB?*=O%ggUTepTJ~t%zi70jA-6Sqig%~3bm;wUK;aT;u)rpCYw}NEPJb{ zT<;!PZmpill!D)-j3+l0nIgijfo}NQ=y{r6S^jr@)m7BS!wB$BoH6~MWd|cX42>9$ z4_jqyfgi>?zXE>~`dXFN>1n^~oasC#dwLr5DDeoSU725Su1TC<{vpVQ z>*M+5X9lkX4Ai}zcS0jN0F0+o7KLpM8;b`eI6J*NYrUumlDGI0c)o72&uky#7K-Cd zi1bmga9c`HL9DZH{8>Kn7Z<=PP;|R2kE6x~L_&aagZVDXamLX>?Xn!wrk3zC4CeDF+u zg{|0?H`lM$ySI8g0*=!!QetoeGAxYM?Fy7|7$s&PJ0XK(MA)#h5%xh6(5XfS;V;Oi z2-%eg&U)4n(nebSCxQVYo7#IzcoMRfwOZiTgnPjAbPV^Q;(PdpSWbJ5*`72Xt05#xpBh_NCCfohZ&? zj3P{t#I(BJyE$J=dYYFFgdKiE^1%|`V*hj~r?pBC&6puuoWcR~iXyZ>EFYXkRKVsJm0?4nvTq~XyFubV~Bc!r$^kkjd zC)7U)cl@QHYuaAMb_82LRDCGnsZxa1ZtD!-QX3x}PYWUxmquFc#3+-HQ|V-$X|(=O z$}(U^c+pBSSB&IuB)F&7);2LXk2r@#GME3`qH)blqekzxY}zE;x@nW7c+t4u-GKjE zD*pGQzuVvHzuTKDj;_B>?RPq%W&+&-KaxBobGKz*<&h(=&XvF1_8{v(;B?E#$kEZ` zdBR97lGWf zO=ca3)Cq4!>MzCmndB31_ZZB|+n;!=dSUV$!0<=}g?vyprs@f%GtksXWc0aK)9k%_ z$e!^G%^&5gCz9wZWBq%Ng#iql=(@wFMo4eYO$bkxJ^Uo0a%}MafN8Wxf40$8+wtV3 zA-hbo;Ij`@8*N>l58gO$7WZ}PiG)Yr`H}bEOkWNg_s;s<>dbTzXCWK=oWk{hQ?~s& zFZ19$-^FD8d|8Qp)waiyRbPMRU4MOMr{8HnkiPzkv~+mu&AuhsF_V2$Pt0z1ezrU} zHyF9YJ}>qnApy|( z`nO6un$mnqPW871wbdla9qQVA;nx0a)rdm8{_*jh(i#EV`u3+)K1x(^eRmdE5PGqA zNAqKq?FU>xAtlZl$lNjy{IfOc%O(Bl^jbMx*#afgpP|ZI9!O!Qd*b!DM@A#1bdQb1 z-aS1;%B-=Hsz2JdQ|kC=WMA9tgUFMBRi_%`GQj?%bLi=pmOsxQbyTnWso0daLs7eK zDEKX1r{(6sw{k7Yii91fMLzHH&%B3RzngMHx)#7`4ZGC6gYsvlR&F&xYUzBGEleg( z&=sKB%u5K29rWl3-|BXZ%2^F@J?f| zuJMjMb^TeeeBREZzm$~>PCuacjok16sBOs&zwEGii~QFA-wz}FtIU6o_cs4M{*RwY p_>#oI@5fujf6-#8bo%er{{j>ROL71J diff --git a/ada_feeding_perception/package.xml b/ada_feeding_perception/package.xml index 6967fec2..9ab76b62 100644 --- a/ada_feeding_perception/package.xml +++ b/ada_feeding_perception/package.xml @@ -28,6 +28,7 @@ python3-skimage python3-torch python3-torchvision + python-transforms3d-pip ament_python From 7b687045ab110a85ceef6e4f0eb647ed798cea20 Mon Sep 17 00:00:00 2001 From: Amal Nanavati Date: Wed, 20 Mar 2024 19:21:19 -0700 Subject: [PATCH 17/18] Fixes from in-person testing --- .../food_on_fork_detection.py | 10 ++++++---- .../food_on_fork_detectors.py | 14 +++++++------- 2 files changed, 13 insertions(+), 11 deletions(-) diff --git a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py index 0af4eea1..3bc81fb4 100644 --- a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py +++ b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py @@ -642,14 +642,16 @@ def run(self) -> None: food_on_fork_detection_msg.probability = proba food_on_fork_detection_msg.status = status if status == FoodOnForkDetection.SUCCESS: - food_on_fork_detection_msg.message = ( - "Successfully assessed food on fork" - ) + food_on_fork_detection_msg.message = "No errors." elif status == FoodOnForkDetection.ERROR_TOO_FEW_POINTS: food_on_fork_detection_msg.message = ( - "Too few detected points. This typically means there is " + "Error: Too few detected points. This typically means there is " "no food on the fork." ) + elif status == FoodOnForkDetection.ERROR_NO_TRANSFORM: + food_on_fork_detection_msg.message = ( + "Error: Could not get requested transform(s)." + ) # pylint: disable=broad-except # This is necessary because we don't know what exceptions the model # might raise. diff --git a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py index e04bd8b2..a01f972f 100644 --- a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py +++ b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py @@ -783,7 +783,7 @@ def predict_proba( start_time = time.time() # If all elements of the transform are 0, set the proba to nan - if np.all(t[i, 0, :, :] == 0): + if np.all(np.isclose(t[i, 0, :, :], 0.0)): probas.append(np.nan) statuses.append(FoodOnForkDetection.ERROR_NO_TRANSFORM) continue @@ -882,10 +882,10 @@ def visualize_img(self, img: npt.NDArray, t: npt.NDArray) -> None: labels.append("Train") show_3d_scatterplot( - pointclouds[1:], - colors[1:], - sizes[1:], - markerstyles[1:], - labels[1:], - title="Stored No FoF Points", + pointclouds, + colors, + sizes, + markerstyles, + labels, + title="Img vs. Stored No FoF Points", ) From 4122937b7900856d1e07bff27750e0f716caf32b Mon Sep 17 00:00:00 2001 From: Amal Nanavati Date: Fri, 22 Mar 2024 19:15:57 -0700 Subject: [PATCH 18/18] Overlaid stored noFof points on camera image --- .pylintrc | 2 + .../food_on_fork_detection.py | 14 ++++- .../food_on_fork_detectors.py | 51 +++++++++++++++++++ 3 files changed, 65 insertions(+), 2 deletions(-) diff --git a/.pylintrc b/.pylintrc index c628deb3..8ff70cfb 100644 --- a/.pylintrc +++ b/.pylintrc @@ -215,7 +215,9 @@ good-names=a, y1, z, u, + us, v, + vs, w, h, r, diff --git a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py index 3bc81fb4..34e14c96 100644 --- a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py +++ b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detection.py @@ -15,6 +15,7 @@ class to use and kwargs for the class's constructor; (b) exposes a ROS2 service from cv_bridge import CvBridge import cv2 import numpy as np +import numpy.typing as npt from rcl_interfaces.msg import ParameterDescriptor, ParameterType import rclpy from rclpy.callback_groups import MutuallyExclusiveCallbackGroup @@ -498,13 +499,18 @@ def camera_callback(self, msg: Image) -> None: with self.img_buffer_lock: self.img_buffer.append(msg) - def visualize_result(self, result: FoodOnForkDetection) -> None: + def visualize_result( + self, result: FoodOnForkDetection, t: npt.NDArray, debug: bool = True + ) -> None: """ Annotates the nearest RGB image message with the result and publishes it. Parameters ---------- result: The result of the food on fork detection. + t: The transform(s) used in the detection. Size (N, 4, 4) where N is the + number of transforms. + debug: Whether to overlay additional debug information on the image. """ # Get the RGB image with timestamp closest to the depth image with self.img_buffer_lock: @@ -531,6 +537,10 @@ def visualize_result(self, result: FoodOnForkDetection) -> None: # Convert the RGB image to a cv2 image img_cv2 = ros_msg_to_cv2_image(img_msg, self.cv_bridge) + # Allow the model to overlay additional debug information on the image + if debug: + img_cv2 = self.model.overlay_debug_info(img_cv2, t) + # Get the message to write on the image proba = result.probability status = result.status @@ -664,7 +674,7 @@ def run(self) -> None: # Visualize the results if self.viz: - self.visualize_result(food_on_fork_detection_msg) + self.visualize_result(food_on_fork_detection_msg, t[0]) # Publish the FoodOnForkDetection message self.pub.publish(food_on_fork_detection_msg) diff --git a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py index a01f972f..626de1a2 100644 --- a/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py +++ b/ada_feeding_perception/ada_feeding_perception/food_on_fork_detectors.py @@ -10,6 +10,7 @@ from typing import List, Optional, Tuple # Third-party imports +import cv2 import matplotlib.pyplot as plt import numpy as np import numpy.typing as npt @@ -347,6 +348,23 @@ def predict( statuses, ) + def overlay_debug_info(self, img: npt.NDArray, t: npt.NDArray) -> npt.NDArray: + """ + Overlays debug information onto a depth image. + + Parameters + ---------- + img: The depth image to overlay debug information onto. + t: The closest transforms (homogenous coordinates) to this image's timestamp. + Size (num_transforms, 4, 4). Should be outputted by `get_transforms`. + + Returns + ------- + img_with_debug_info: The depth image with debug information overlayed. + """ + # pylint: disable=unused-argument + return img + def visualize_img(self, img: npt.NDArray, t: npt.NDArray) -> None: """ Visualizes a depth image. This function is used for debugging, so it helps @@ -854,6 +872,39 @@ def predict( statuses, ) + @override + def overlay_debug_info(self, img: npt.NDArray, t: npt.NDArray) -> npt.NDArray: + # pylint: disable=too-many-locals + # This is done to make it clear what the camera matrix values are. + + # First, convert all no_fof_points back to the camera frame by applying + # the inverse of the homogenous transform t[0, :, :] + no_fof_points_homogenous = np.hstack( + [self.no_fof_points, np.ones((self.no_fof_points.shape[0], 1))] + ) + no_fof_points_camera = np.dot( + np.linalg.inv(t[0, :, :]), no_fof_points_homogenous.T + ).T[:, :3] + + # For every point in the no_fof_points, convert them back into (u,v) pixel + # coordinates. + no_fof_points_mm = (no_fof_points_camera * 1000).astype(int) + f_x = self.camera_matrix[0] + f_y = self.camera_matrix[4] + c_x = self.camera_matrix[2] + c_y = self.camera_matrix[5] + us = (f_x * no_fof_points_mm[:, 0] / no_fof_points_mm[:, 2] + c_x).astype(int) + vs = (f_y * no_fof_points_mm[:, 1] / no_fof_points_mm[:, 2] + c_y).astype(int) + + # For every point, draw a circle around that point in the image + color = (0, 0, 0) + alpha = 0.75 + radius = 5 + img_with_debug_info = img.copy() + for u, v in zip(us, vs): + cv2.circle(img_with_debug_info, (u, v), radius, color, -1) + return cv2.addWeighted(img_with_debug_info, alpha, img.copy(), 1 - alpha, 0) + @override def visualize_img(self, img: npt.NDArray, t: npt.NDArray) -> None: # Convert the image to a pointcloud