From 161b3b35e5cf3d252c32a0dcd490f7f82717322f Mon Sep 17 00:00:00 2001 From: Peter van Dooren Date: Wed, 5 Jul 2023 10:13:27 +0200 Subject: [PATCH 01/24] timeout should be float --- .../challenge_serve_breakfast/navigate_to_and_pick_item.py | 4 ++-- .../navigate_to_and_place_item_on_table.py | 2 +- .../src/challenge_serve_breakfast/pick_pour_place_cereal.py | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py index 6e24981f5d..fe018f2a87 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py @@ -31,7 +31,7 @@ def __init__(self, robot): def send_joint_goal(position_array, wait_for_motion_done=True): # noinspection PyProtectedMember - arm._send_joint_trajectory([position_array], timeout=rospy.Duration(0)) + arm._send_joint_trajectory([position_array], timeout=0.0) if wait_for_motion_done: arm.wait_for_motion_done() @@ -52,7 +52,7 @@ def show_image(package_name, path_to_image_in_package): @cb_interface(outcomes=["done"]) def _rotate(_): - arm.gripper.send_goal("close", timeout=0.) + arm.gripper.send_goal("close", timeout=0.0) robot.head.look_up() vyaw = 0.5 robot.base.force_drive(0, 0, vyaw, PICK_ROTATION / vyaw) diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_place_item_on_table.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_place_item_on_table.py index af9d0413e7..f2f76bdc46 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_place_item_on_table.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_place_item_on_table.py @@ -42,7 +42,7 @@ def __init__(self, robot, table_id): def send_joint_goal(position_array, wait_for_motion_done=True): # noinspection PyProtectedMember - arm._send_joint_trajectory([position_array], timeout=rospy.Duration(0)) + arm._send_joint_trajectory([position_array], timeout=0.0) if wait_for_motion_done: arm.wait_for_motion_done() diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/pick_pour_place_cereal.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/pick_pour_place_cereal.py index 2df5eecca4..f92ed5c97b 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/pick_pour_place_cereal.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/pick_pour_place_cereal.py @@ -25,7 +25,7 @@ def __init__(self, robot, table_id): def send_joint_goal(position_array, wait_for_motion_done=True): # noinspection PyProtectedMember - arm._send_joint_trajectory([position_array], timeout=rospy.Duration(0)) + arm._send_joint_trajectory([position_array], timeout=0.0) if wait_for_motion_done: arm.wait_for_motion_done() From 0c84eec64f0b3efe5613f5ce42a35b5545674dce Mon Sep 17 00:00:00 2001 From: Peter van Dooren Date: Wed, 5 Jul 2023 10:31:28 +0200 Subject: [PATCH 02/24] add userdata to callback state --- .../navigate_to_and_place_item_on_table.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_place_item_on_table.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_place_item_on_table.py index f2f76bdc46..349076db3b 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_place_item_on_table.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_place_item_on_table.py @@ -164,7 +164,7 @@ def __init__(self, robot, table_id, table_close_navigation_area): ) @cb_interface(outcomes=["done"]) -def _publish_item_poses(marker_array_pub, items): +def _publish_item_poses(user_data, marker_array_pub, items): """ Publishes item poses as a visualization marker array From 7df6353ca1d5943dbd85ba4f8bfd2e9d188158a0 Mon Sep 17 00:00:00 2001 From: Peter van Dooren Date: Wed, 5 Jul 2023 11:38:05 +0200 Subject: [PATCH 03/24] adjust parameters to place on the rwc2023 table --- .../src/challenge_serve_breakfast/serve_breakfast.py | 4 ++-- .../src/challenge_serve_breakfast/tuning.py | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py index 0663351258..ca9944b518 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py @@ -51,9 +51,9 @@ def execute(self, userdata): def setup_statemachine(robot): state_machine = StateMachine(outcomes=["done"]) state_machine.userdata["item_picked"] = None - pick_id = "dinner_table" + pick_id = "kitchen_table" pick_area_id = "in_front_of" - place_id = "dinner_table" + place_id = "kitchen_table" place_area_id = "in_front_of" exit_id = "starting_pose" diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/tuning.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/tuning.py index 1a771f2383..3fb6b78f65 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/tuning.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/tuning.py @@ -54,7 +54,7 @@ def item_vector_to_item_frame(item_vector): - frame = PyKDL.Frame(PyKDL.Rotation.RPY(0, 0, -math.pi / 2), PyKDL.Vector(-0.05, 0.75, 0)) + frame = PyKDL.Frame(PyKDL.Rotation.RPY(0, 0, math.pi), PyKDL.Vector(0.75, 0, 0)) item_placement_vector = item_vector item_frame = frame From ab63b5477f1317eb650410791fd3bcaef554b21e Mon Sep 17 00:00:00 2001 From: Peter van Dooren Date: Wed, 5 Jul 2023 11:55:05 +0200 Subject: [PATCH 04/24] fix table name for rwc2023 --- .../src/challenge_serve_breakfast/navigate_to_and_pick_item.py | 2 +- .../navigate_to_and_place_item_on_table.py | 2 +- .../src/challenge_serve_breakfast/pick_pour_place_cereal.py | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py index fe018f2a87..d4ca4747d1 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py @@ -112,4 +112,4 @@ def __init__(self, robot, pick_spot_id, pick_spot_navigation_area): rospy.init_node(os.path.splitext("test_" + os.path.basename(__file__))[0]) robot_instance = get_robot("hero") robot_instance.reset() - NavigateToAndPickItem(robot_instance, "dinner_table", "in_front_of").execute() + NavigateToAndPickItem(robot_instance, "kitchen_table", "in_front_of").execute() diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_place_item_on_table.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_place_item_on_table.py index 349076db3b..6de0a1d3c6 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_place_item_on_table.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_place_item_on_table.py @@ -210,6 +210,6 @@ def _publish_item_poses(user_data, marker_array_pub, items): rospy.init_node(os.path.splitext("test_" + os.path.basename(__file__))[0]) robot_instance = get_robot("hero") - state_machine = NavigateToAndPlaceItemOnTable(robot_instance, "dinner_table", "in_front_of") + state_machine = NavigateToAndPlaceItemOnTable(robot_instance, "kitchen_table", "in_front_of") state_machine.userdata["item_picked"] = sys.argv[1] state_machine.execute() diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/pick_pour_place_cereal.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/pick_pour_place_cereal.py index f92ed5c97b..1f895b24c8 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/pick_pour_place_cereal.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/pick_pour_place_cereal.py @@ -101,4 +101,4 @@ def _place(_): if __name__ == "__main__": rospy.init_node(os.path.splitext("test_" + os.path.basename(__file__))[0]) robot_instance = get_robot("hero") - PickPourPlaceCereal(robot_instance, "dinner_table").execute() + PickPourPlaceCereal(robot_instance, "kitchen_table").execute() From dcdbcf9ad809b3cf494cc84988d1fdf186a34e73 Mon Sep 17 00:00:00 2001 From: Peter van Dooren Date: Wed, 5 Jul 2023 11:55:19 +0200 Subject: [PATCH 05/24] fix visual bug --- .../navigate_to_and_place_item_on_table.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_place_item_on_table.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_place_item_on_table.py index 6de0a1d3c6..ccf51e102a 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_place_item_on_table.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_place_item_on_table.py @@ -184,7 +184,7 @@ def _publish_item_poses(user_data, marker_array_pub, items): marker_msg.type = visualization_msgs.msg.Marker.SPHERE marker_msg.action = 0 marker_msg.pose = posestamped.pose - marker_msg.pose.position.z += 1.0 + marker_msg.pose.position.z = 1.0 marker_msg.scale = Vector3(0.05, 0.05, 0.05) marker_msg.color = COLOR_DICT[k] array_msg.markers.append(marker_msg) From 801c3cd4510a3d58f70e675d1d4dbfbd6bb21bcc Mon Sep 17 00:00:00 2001 From: Peter van Dooren Date: Wed, 5 Jul 2023 12:14:17 +0200 Subject: [PATCH 06/24] tjooning --- .../src/challenge_serve_breakfast/tuning.py | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/tuning.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/tuning.py index 3fb6b78f65..b66d1e48b2 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/tuning.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/tuning.py @@ -15,10 +15,10 @@ REQUIRED_ITEMS = ["spoon", "bowl", "milk_carton", "cereal_box"] ITEM_VECTOR_DICT = { - "spoon": PyKDL.Vector(0.03, -0.15, 0), - "bowl": PyKDL.Vector(0.1, -0.04, 0), - "milk_carton": PyKDL.Vector(-0.1, 0.3, 0), - "cereal_box": PyKDL.Vector(-0.1, -0.3, 0), + "spoon": PyKDL.Vector(0.0, -0.15, 0), + "bowl": PyKDL.Vector(0.0, 0.0, 0), + "milk_carton": PyKDL.Vector(-0.05, 0.15, 0), + "cereal_box": PyKDL.Vector(0.0, -0.3, 0), } COLOR_DICT = { @@ -54,7 +54,7 @@ def item_vector_to_item_frame(item_vector): - frame = PyKDL.Frame(PyKDL.Rotation.RPY(0, 0, math.pi), PyKDL.Vector(0.75, 0, 0)) + frame = PyKDL.Frame(PyKDL.Rotation.RPY(0, 0, math.pi), PyKDL.Vector(0.7, 0, 0)) item_placement_vector = item_vector item_frame = frame From c03464611ef3d3b35b99f59923bb795a0d67edb7 Mon Sep 17 00:00:00 2001 From: Peter van Dooren Date: Wed, 5 Jul 2023 12:23:10 +0200 Subject: [PATCH 07/24] unneeded speaks removed --- .../src/challenge_serve_breakfast/navigate_to_and_pick_item.py | 2 +- .../navigate_to_and_place_item_on_table.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py index d4ca4747d1..b90eddb859 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py @@ -101,7 +101,7 @@ def __init__(self, robot, pick_spot_id, pick_spot_navigation_area): with self: StateMachine.add( "NAVIGATE_TO_PICK_SPOT", - NavigateToSymbolic(robot, {pick_spot: pick_spot_navigation_area}, pick_spot), + NavigateToSymbolic(robot, {pick_spot: pick_spot_navigation_area}, pick_spot, speak=False), transitions={"arrived": "PICK_ITEM", "unreachable": "failed", "goal_not_defined": "failed"}, ) diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_place_item_on_table.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_place_item_on_table.py index ccf51e102a..af1b890d0b 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_place_item_on_table.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_place_item_on_table.py @@ -129,7 +129,7 @@ def __init__(self, robot, table_id, table_close_navigation_area): ) StateMachine.add( "NAVIGATE_TO_TABLE_CLOSE", - NavigateToSymbolic(robot, {table: table_close_navigation_area}, table), + NavigateToSymbolic(robot, {table: table_close_navigation_area}, table, speak=False), transitions={ "arrived": "PLACE_ITEM_ON_TABLE", "unreachable": "SAY_PICK_AWAY_THE_CHAIR", From 1d6239643e88c294a779fbdfd8629a79760bbf26 Mon Sep 17 00:00:00 2001 From: Peter van Dooren Date: Wed, 5 Jul 2023 13:25:53 +0200 Subject: [PATCH 08/24] use grasp detector to detect succesful handover --- .../navigate_to_and_pick_item.py | 38 +++++++++++++++---- 1 file changed, 30 insertions(+), 8 deletions(-) diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py index b90eddb859..3f30be1e97 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py @@ -10,8 +10,11 @@ from challenge_serve_breakfast.tuning import REQUIRED_ITEMS, JOINTS_HANDOVER, PICK_ROTATION from robot_skills import get_robot +from robot_skills.arm.arms import GripperTypes +from robot_smach_states.human_interaction import Say +from robot_smach_states.manipulation.active_grasp_detector import ActiveGraspDetector from robot_smach_states.navigation import NavigateToSymbolic -from robot_smach_states.util.designators import EdEntityDesignator +from robot_smach_states.util.designators import EdEntityDesignator, ArmDesignator from smach import StateMachine, cb_interface, CBState item_img_dict = { @@ -28,6 +31,7 @@ def __init__(self, robot): # noinspection PyProtectedMember arm = robot.get_arm()._arm picked_items = [] + armdes = ArmDesignator(robot, {"required_gripper_types": [GripperTypes.GRASPING]}) def send_joint_goal(position_array, wait_for_motion_done=True): # noinspection PyProtectedMember @@ -58,6 +62,11 @@ def _rotate(_): robot.base.force_drive(0, 0, vyaw, PICK_ROTATION / vyaw) return "done" + @cb_interface(outcomes=["done"]) + def _handover_pose(user_data): + send_joint_goal(JOINTS_HANDOVER, wait_for_motion_done=False) + return "done" + @cb_interface(outcomes=["succeeded", "failed"], output_keys=["item_picked"]) def _ask_user(user_data): leftover_items = [item for item in REQUIRED_ITEMS if item not in picked_items] @@ -67,8 +76,6 @@ def _ask_user(user_data): item_name = leftover_items[0] - send_joint_goal(JOINTS_HANDOVER, wait_for_motion_done=False) - picked_items.append(item_name) robot.speech.speak("Please put the {} in my gripper, like this".format(item_name), block=False) @@ -76,20 +83,35 @@ def _ask_user(user_data): send_gripper_goal("open") rospy.sleep(10.0) - robot.speech.speak("Thanks for that!", block=False) send_gripper_goal("close", max_torque=0.6) robot.head.reset() # Set output data user_data["item_picked"] = item_name + return "succeeded" + @cb_interface(outcomes=["done"]) + def _carrying_pose(user_data): arm.send_joint_goal("carrying_pose", timeout=0.) - - return "succeeded" + robot.speech.speak("Thanks for that!", block=False) + return "done" with self: - self.add("ROTATE", CBState(_rotate), transitions={"done": "ASK_USER"}) - self.add("ASK_USER", CBState(_ask_user), transitions={"succeeded": "succeeded", "failed": "failed"}) + self.add("ROTATE", CBState(_rotate), transitions={"done": "HANDOVER_POSE"}) + self.add("HANDOVER_POSE", CBState(_handover_pose), transitions={"done": "ASK_USER"}) + self.add("ASK_USER", CBState(_ask_user), + transitions={"succeeded": "CHECK_PICK_SUCCESSFUL", "failed": "failed"}) + self.add("CHECK_PICK_SUCCESSFUL", + ActiveGraspDetector(robot, armdes), + transitions={'true': "CARRYING_POSE", + 'false': "SAY_SOMETHING_WENT_WRONG", + 'failed': "failed", + 'cannot_determine': "SAY_SOMETHING_WENT_WRONG"} + ) + self.add("SAY_SOMETHING_WENT_WRONG", Say(robot, "Oops, it seems I missed it. Lets try again"), + transitions={"spoken": "ASK_USER2"}) + self.add("ASK_USER2", CBState(_ask_user), transitions={"succeeded": "CARRYING_POSE", "failed": "failed"}) + self.add("CARRYING_POSE", CBState(_carrying_pose), transitions={"done": "succeeded"}) class NavigateToAndPickItem(StateMachine): From 9ba44de43ec9e505dd3242bf1316a88b1d9bd8d6 Mon Sep 17 00:00:00 2001 From: shanki98 Date: Thu, 6 Jul 2023 16:35:16 +0200 Subject: [PATCH 09/24] Change pick_area to dishwasher --- .../src/challenge_serve_breakfast/serve_breakfast.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py index ca9944b518..585309be11 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py @@ -51,7 +51,7 @@ def execute(self, userdata): def setup_statemachine(robot): state_machine = StateMachine(outcomes=["done"]) state_machine.userdata["item_picked"] = None - pick_id = "kitchen_table" + pick_id = "dishwasher" pick_area_id = "in_front_of" place_id = "kitchen_table" place_area_id = "in_front_of" From f2df145bc2a4b9f626ae91c136db9b0fd4a9d6bc Mon Sep 17 00:00:00 2001 From: shanki98 Date: Thu, 6 Jul 2023 18:52:54 +0200 Subject: [PATCH 10/24] Serve breakfast fix --- .../navigate_to_and_pick_item.py | 5 ++-- .../serve_breakfast.py | 23 ++++++++++++++----- .../src/challenge_serve_breakfast/tuning.py | 2 +- 3 files changed, 21 insertions(+), 9 deletions(-) diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py index 3f30be1e97..346f56cc4e 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py @@ -82,7 +82,7 @@ def _ask_user(user_data): show_image("challenge_serve_breakfast", item_img_dict[item_name]) send_gripper_goal("open") - rospy.sleep(10.0) + rospy.sleep(7.0) send_gripper_goal("close", max_torque=0.6) robot.head.reset() @@ -123,7 +123,8 @@ def __init__(self, robot, pick_spot_id, pick_spot_navigation_area): with self: StateMachine.add( "NAVIGATE_TO_PICK_SPOT", - NavigateToSymbolic(robot, {pick_spot: pick_spot_navigation_area}, pick_spot, speak=False), + NavigateToSymbolic(robot=robot, entity_designator_area_name_map={pick_spot: pick_spot_navigation_area}, + entity_lookat_designator=pick_spot, speak=False), transitions={"arrived": "PICK_ITEM", "unreachable": "failed", "goal_not_defined": "failed"}, ) diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py index 585309be11..ba82e37e01 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py @@ -9,9 +9,10 @@ from robot_smach_states.navigation import NavigateToWaypoint from robot_smach_states.startup import StartChallengeRobust from robot_smach_states.util.designators import EdEntityDesignator +from robot_smach_states.world_model import UpdateEntityPose from robot_smach_states.utility import WaitTime from smach import State, StateMachine -from .navigate_to_and_pick_item import NavigateToAndPickItem +from .navigate_to_and_pick_item import NavigateToAndPickItem, NavigateToSymbolic from .navigate_to_and_place_item_on_table import NavigateToAndPlaceItemOnTable from .pick_pour_place_cereal import PickPourPlaceCereal from .tuning import REQUIRED_ITEMS @@ -56,6 +57,8 @@ def setup_statemachine(robot): place_id = "kitchen_table" place_area_id = "in_front_of" exit_id = "starting_pose" + table_des = EdEntityDesignator(robot=robot, uuid=place_id) + table_place_des = EdEntityDesignator(robot=robot, uuid=place_id) with state_machine: # Intro @@ -63,9 +66,20 @@ def setup_statemachine(robot): StateMachine.add( "START_CHALLENGE_ROBUST", StartChallengeRobust(robot, "initial_pose"), - transitions={"Done": "SAY_START", "Aborted": "done", "Failed": "SAY_START"}, + transitions={"Done": "NAVIGATE_TO_TABLE", "Aborted": "done", "Failed": "NAVIGATE_TO_TABLE"}, ) - + # Main loop + # StateMachine.add( + # "NAVIGATE_TO_TABLE", + # NavigateToSymbolic(robot=robot, entity_designator_area_name_map={table_place_des: place_area_id}, + # entity_lookat_designator=place_id, speak=True), + # transitions={"arrived": "UPDATE_TABLE_POSE", "unreachable": "done", "goal_not_defined": "done"}, + # # ) + #StateMachine.add( + # "UPDATE_TABLE_POSE", + # UpdateEntityPose(robot=robot, entity_designator=table_des), + # ransitions={"done": "SAY_START"}, + #) StateMachine.add( "SAY_START", Say( @@ -76,9 +90,6 @@ def setup_statemachine(robot): ), transitions={"spoken": "NAVIGATE_AND_PICK_ITEM"}, ) - - # Main loop - StateMachine.add( "NAVIGATE_AND_PICK_ITEM", NavigateToAndPickItem(robot, pick_id, pick_area_id), diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/tuning.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/tuning.py index b66d1e48b2..aad8aad04d 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/tuning.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/tuning.py @@ -28,7 +28,7 @@ "cereal_box": ColorRGBA(1, 1, 0, 1), } -PICK_ROTATION = 2. +PICK_ROTATION = 1.2 JOINTS_HANDOVER = [0.4, -0.2, 0.0, -1.37, 0] From 1e43416f60149b04f3700aac108993e1330d0442 Mon Sep 17 00:00:00 2001 From: shanki98 Date: Thu, 6 Jul 2023 18:54:14 +0200 Subject: [PATCH 11/24] Hot fix --- .../src/challenge_serve_breakfast/serve_breakfast.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py index ba82e37e01..6f12ede5a1 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py @@ -66,7 +66,7 @@ def setup_statemachine(robot): StateMachine.add( "START_CHALLENGE_ROBUST", StartChallengeRobust(robot, "initial_pose"), - transitions={"Done": "NAVIGATE_TO_TABLE", "Aborted": "done", "Failed": "NAVIGATE_TO_TABLE"}, + transitions={"Done": "SAY_START", "Aborted": "done", "Failed": "SAY_START"}, ) # Main loop # StateMachine.add( From 3ba0762b4fd61a11d136959133282335c71feb74 Mon Sep 17 00:00:00 2001 From: shanki98 Date: Thu, 6 Jul 2023 19:09:26 +0200 Subject: [PATCH 12/24] Added UpdateEntityPose for table --- .../navigate_to_and_pick_item.py | 3 +-- .../serve_breakfast.py | 26 +++++++++---------- 2 files changed, 13 insertions(+), 16 deletions(-) diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py index 346f56cc4e..25c07c5ce1 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py @@ -123,8 +123,7 @@ def __init__(self, robot, pick_spot_id, pick_spot_navigation_area): with self: StateMachine.add( "NAVIGATE_TO_PICK_SPOT", - NavigateToSymbolic(robot=robot, entity_designator_area_name_map={pick_spot: pick_spot_navigation_area}, - entity_lookat_designator=pick_spot, speak=False), + NavigateToSymbolic(robot, {pick_spot: pick_spot_navigation_area},pick_spot, speak=False), transitions={"arrived": "PICK_ITEM", "unreachable": "failed", "goal_not_defined": "failed"}, ) diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py index 6f12ede5a1..7c80539c5d 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py @@ -58,7 +58,6 @@ def setup_statemachine(robot): place_area_id = "in_front_of" exit_id = "starting_pose" table_des = EdEntityDesignator(robot=robot, uuid=place_id) - table_place_des = EdEntityDesignator(robot=robot, uuid=place_id) with state_machine: # Intro @@ -66,20 +65,19 @@ def setup_statemachine(robot): StateMachine.add( "START_CHALLENGE_ROBUST", StartChallengeRobust(robot, "initial_pose"), - transitions={"Done": "SAY_START", "Aborted": "done", "Failed": "SAY_START"}, + transitions={"Done": "NAVIGATE_TO_TABLE", "Aborted": "done", "Failed": "NAVIGATE_TO_TABLE"}, + ) + #Main loop + StateMachine.add( + "NAVIGATE_TO_TABLE", + NavigateToSymbolic(robot, {table_des:place_area_id}, table_des, speak=True), + transitions={"arrived": "UPDATE_TABLE_POSE", "unreachable": "done", "goal_not_defined": "done"}, + ) + StateMachine.add( + "UPDATE_TABLE_POSE", + UpdateEntityPose(robot=robot, entity_designator=table_des), + transitions={"done": "SAY_START"}, ) - # Main loop - # StateMachine.add( - # "NAVIGATE_TO_TABLE", - # NavigateToSymbolic(robot=robot, entity_designator_area_name_map={table_place_des: place_area_id}, - # entity_lookat_designator=place_id, speak=True), - # transitions={"arrived": "UPDATE_TABLE_POSE", "unreachable": "done", "goal_not_defined": "done"}, - # # ) - #StateMachine.add( - # "UPDATE_TABLE_POSE", - # UpdateEntityPose(robot=robot, entity_designator=table_des), - # ransitions={"done": "SAY_START"}, - #) StateMachine.add( "SAY_START", Say( From f031095c4262924eb2c0b7bcb6f3bc9305dce5d9 Mon Sep 17 00:00:00 2001 From: Arpit Aggarwal Date: Thu, 6 Jul 2023 20:15:40 +0200 Subject: [PATCH 13/24] fix(serve_breakfast): Remove handover check --- .../navigate_to_and_pick_item.py | 24 ++++++++++--------- .../serve_breakfast.py | 2 +- 2 files changed, 14 insertions(+), 12 deletions(-) diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py index 25c07c5ce1..9bae14f347 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py @@ -100,17 +100,19 @@ def _carrying_pose(user_data): self.add("ROTATE", CBState(_rotate), transitions={"done": "HANDOVER_POSE"}) self.add("HANDOVER_POSE", CBState(_handover_pose), transitions={"done": "ASK_USER"}) self.add("ASK_USER", CBState(_ask_user), - transitions={"succeeded": "CHECK_PICK_SUCCESSFUL", "failed": "failed"}) - self.add("CHECK_PICK_SUCCESSFUL", - ActiveGraspDetector(robot, armdes), - transitions={'true': "CARRYING_POSE", - 'false': "SAY_SOMETHING_WENT_WRONG", - 'failed': "failed", - 'cannot_determine': "SAY_SOMETHING_WENT_WRONG"} - ) - self.add("SAY_SOMETHING_WENT_WRONG", Say(robot, "Oops, it seems I missed it. Lets try again"), - transitions={"spoken": "ASK_USER2"}) - self.add("ASK_USER2", CBState(_ask_user), transitions={"succeeded": "CARRYING_POSE", "failed": "failed"}) + transitions={"succeeded": "CARRYING_POSE", "failed": "failed"}) + + # self.add("CHECK_PICK_SUCCESSFUL", + # ActiveGraspDetector(robot, armdes), + # transitions={'true': "CARRYING_POSE", + # 'false': "SAY_SOMETHING_WENT_WRONG", + # 'failed': "failed", + # 'cannot_determine': "SAY_SOMETHING_WENT_WRONG"} + # ) + + # self.add("SAY_SOMETHING_WENT_WRONG", Say(robot, "Oops, it seems I missed it. Lets try again"), + # transitions={"spoken": "ASK_USER2"}) + # self.add("ASK_USER2", CBState(_ask_user), transitions={"succeeded": "CARRYING_POSE", "failed": "failed"}) self.add("CARRYING_POSE", CBState(_carrying_pose), transitions={"done": "succeeded"}) diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py index 7c80539c5d..0a92177845 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py @@ -71,7 +71,7 @@ def setup_statemachine(robot): StateMachine.add( "NAVIGATE_TO_TABLE", NavigateToSymbolic(robot, {table_des:place_area_id}, table_des, speak=True), - transitions={"arrived": "UPDATE_TABLE_POSE", "unreachable": "done", "goal_not_defined": "done"}, + transitions={"arrived": "UPDATE_TABLE_POSE", "unreachable": "GOODBYE", "goal_not_defined": "GOODBYE"}, ) StateMachine.add( "UPDATE_TABLE_POSE", From efc67274910ce2eb199cbbed190cf7027c3e0e31 Mon Sep 17 00:00:00 2001 From: Arpit Aggarwal Date: Thu, 6 Jul 2023 20:18:33 +0200 Subject: [PATCH 14/24] fix(serve_breakfast): Always say GOODBYE before done --- .../src/challenge_serve_breakfast/serve_breakfast.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py index 0a92177845..c68ce508d5 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py @@ -65,7 +65,7 @@ def setup_statemachine(robot): StateMachine.add( "START_CHALLENGE_ROBUST", StartChallengeRobust(robot, "initial_pose"), - transitions={"Done": "NAVIGATE_TO_TABLE", "Aborted": "done", "Failed": "NAVIGATE_TO_TABLE"}, + transitions={"Done": "NAVIGATE_TO_TABLE", "Aborted": "GOODBYE", "Failed": "NAVIGATE_TO_TABLE"}, ) #Main loop StateMachine.add( @@ -96,7 +96,7 @@ def setup_statemachine(robot): StateMachine.add( "NAVIGATE_AND_PICK_ITEM_FAILED", WaitTime(robot, 2), - transitions={"waited": "NAVIGATE_AND_PICK_ITEM", "preempted": "done"} + transitions={"waited": "NAVIGATE_AND_PICK_ITEM", "preempted": "GOODBYE"} ) StateMachine.add( @@ -106,7 +106,7 @@ def setup_statemachine(robot): ) StateMachine.add( - "WAIT", WaitTime(robot, 2), transitions={"waited": "CHECK_IF_WE_HAVE_IT_ALL", "preempted": "done"} + "WAIT", WaitTime(robot, 2), transitions={"waited": "CHECK_IF_WE_HAVE_IT_ALL", "preempted": "GOODBYE"} ) StateMachine.add( From 50fa72d329e1d2df3cd6173e822aaffbaba649e3 Mon Sep 17 00:00:00 2001 From: Rodrigo Date: Thu, 6 Jul 2023 22:26:56 +0200 Subject: [PATCH 15/24] Added say state serve break --- .../challenge_serve_breakfast/serve_breakfast.py | 13 ++++++++++++- 1 file changed, 12 insertions(+), 1 deletion(-) diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py index c68ce508d5..a51906c4da 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py @@ -76,8 +76,19 @@ def setup_statemachine(robot): StateMachine.add( "UPDATE_TABLE_POSE", UpdateEntityPose(robot=robot, entity_designator=table_des), - transitions={"done": "SAY_START"}, + transitions={"done": "SAY_OPERATOR_WHERE_TO_STAND"}, ) + + StateMachine.add( + "SAY_OPERATOR_WHERE_TO_STAND", + Say( + robot, + "Operator, please stand at the RIGHT of the dishwasher", + block=False, + ), + transitions={"spoken": "SAY_START"}, + ) + StateMachine.add( "SAY_START", Say( From 5a3a331f550a986b68974a33e0146278ae179de8 Mon Sep 17 00:00:00 2001 From: Rodrigo Date: Fri, 7 Jul 2023 11:21:10 +0200 Subject: [PATCH 16/24] Serve breakfast tuning --- .../navigate_to_and_pick_item.py | 11 +++++++---- .../src/challenge_serve_breakfast/serve_breakfast.py | 4 ++-- .../src/challenge_serve_breakfast/tuning.py | 8 ++++---- 3 files changed, 13 insertions(+), 10 deletions(-) diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py index 9bae14f347..5152a291da 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py @@ -11,8 +11,9 @@ from challenge_serve_breakfast.tuning import REQUIRED_ITEMS, JOINTS_HANDOVER, PICK_ROTATION from robot_skills import get_robot from robot_skills.arm.arms import GripperTypes +# ROS +from pykdl_ros import VectorStamped from robot_smach_states.human_interaction import Say -from robot_smach_states.manipulation.active_grasp_detector import ActiveGraspDetector from robot_smach_states.navigation import NavigateToSymbolic from robot_smach_states.util.designators import EdEntityDesignator, ArmDesignator from smach import StateMachine, cb_interface, CBState @@ -57,9 +58,11 @@ def show_image(package_name, path_to_image_in_package): @cb_interface(outcomes=["done"]) def _rotate(_): arm.gripper.send_goal("close", timeout=0.0) - robot.head.look_up() - vyaw = 0.5 - robot.base.force_drive(0, 0, vyaw, PICK_ROTATION / vyaw) + + # Loot to the operator + robot.head.look_at_point(VectorStamped.from_xyz(0.2, -0.2, 1.75, stamp=rospy.Time.now(), + frame_id=robot.base_link_frame)) + robot.head.wait_for_motion_done() return "done" @cb_interface(outcomes=["done"]) diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py index a51906c4da..3581f79f48 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py @@ -71,8 +71,9 @@ def setup_statemachine(robot): StateMachine.add( "NAVIGATE_TO_TABLE", NavigateToSymbolic(robot, {table_des:place_area_id}, table_des, speak=True), - transitions={"arrived": "UPDATE_TABLE_POSE", "unreachable": "GOODBYE", "goal_not_defined": "GOODBYE"}, + transitions={"arrived": "UPDATE_TABLE_POSE", "unreachable": "GOODBYE", "goal_not_defined": "GOODBYE"}, ) + StateMachine.add( "UPDATE_TABLE_POSE", UpdateEntityPose(robot=robot, entity_designator=table_des), @@ -93,7 +94,6 @@ def setup_statemachine(robot): "SAY_START", Say( robot, - #f"Lets serve some breakfast baby! If there are any chairs near the {place_id}, please remove them", "Lets serve some breakfast baby! I will be asking for some fast handovers.", block=False, ), diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/tuning.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/tuning.py index aad8aad04d..841394b7f8 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/tuning.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/tuning.py @@ -18,7 +18,7 @@ "spoon": PyKDL.Vector(0.0, -0.15, 0), "bowl": PyKDL.Vector(0.0, 0.0, 0), "milk_carton": PyKDL.Vector(-0.05, 0.15, 0), - "cereal_box": PyKDL.Vector(0.0, -0.3, 0), + "cereal_box": PyKDL.Vector(-0.05, -0.2, 0), } COLOR_DICT = { @@ -28,7 +28,7 @@ "cereal_box": ColorRGBA(1, 1, 0, 1), } -PICK_ROTATION = 1.2 +PICK_ROTATION = 0 JOINTS_HANDOVER = [0.4, -0.2, 0.0, -1.37, 0] @@ -49,8 +49,8 @@ JOINTS_POUR = [0.5, -1.2, -2.5, 0, 0] -POUR_OFFSET_X = 0.03 -POUR_OFFSET_Y = 0.15 +POUR_OFFSET_X = -0.15 +POUR_OFFSET_Y = 0.2 def item_vector_to_item_frame(item_vector): From fa1cf68dd196ab926c0272716ac1dae78c57727c Mon Sep 17 00:00:00 2001 From: Rodrigo Date: Fri, 7 Jul 2023 11:21:20 +0200 Subject: [PATCH 17/24] Serve breakfast tuning --- challenge_serve_breakfast/images/spoon.jpg | Bin 89312 -> 113282 bytes 1 file changed, 0 insertions(+), 0 deletions(-) mode change 100755 => 100644 challenge_serve_breakfast/images/spoon.jpg diff --git a/challenge_serve_breakfast/images/spoon.jpg b/challenge_serve_breakfast/images/spoon.jpg old mode 100755 new mode 100644 index 55e08eae1df5077d6df35780c2bd058904dfad13..05cea6b7b5e2ca453dd71955d81e34b9a78f4a9f GIT binary patch literal 113282 zcmbSyXIK+q7v+S|yBLt(TWHdyS3?O>0@8~JNJlydNE2zHcSM>%=tYFkQ9znV@6x1K zL69N>!Un%@cb{i}?QZhSk9XdgH*=HBnRCxQ_h$BH86bzNsH*@V5C~Aiyn&l}KpDWt z#l^$L!N6A=;9P~0VhFwinFGSJe~GqVeDF|+cq(bIE3fbt0niHeFc zaY@Qb2+IhFhzj2>0wN$FASNQFCLy5~W}#;h{(pYmbO3koaR6`!7{m%--2s8`fNr`0 zCIA58V6OJ|g8%yhVS%x6aPja72#GKUpveI&5EzVw4aUL2#>N~Sh?xhl@8D3d2r1&; zMLfl0b%zLtCcVRFQ>yKx)Ezry7qRkqML5qz|hFp#M19Szs;?zuB~ruZf)=E9{oB#IX(M*{^#O0E)W3z zPgwsevi~ElJD9kzu(83|c(-wZuzWEa_zpG>ix4h_A_DKJ`(0MyP<)6|(!1JD0yYud zLrN=;F+wVK(G`xP+tB_+_J0@HtN*Xa{#RiCJFYo^7!1Pvc;GvLJn-XaIu@Z}9Lt?Q zY7Z2ohbjP@NbY<^1qea`2ZDHHH3owKsr8KY^}rlL1*#1PgkX?@5IPOa?)udFRLoqx zRR~1}B(=GS1?mpt&d2V-LLw9hG?3h)#5fS$Q7i<~gd2b$G>`z?Oa})7t&P`UqcQ_1n<>Itmgbw!<7)daz`ovHe>M~P=(VWz%mOUV>U=Flv1|4 zOv`eDYk3v-m7ElH)Rd&rsz?Kl=|{QR{*6`y<8R+_Nl@mnKQGssu2Cj1?v$o)ih_#D zm~*Gt-T+x>eizOrefwXJe-F9G4htm6Y_{f*A&?R)DqUCkOjW)U-Ja4SS&yBoqcgNx zV_*4N28=K4>VE4re~T9)?1UnX;EVO(9ef$=bNCfv-))o9c>~CyQN}O<+XhOB)^8%M z6K%?rlTI`*(Z;!!cB&+aWbngQ7pu)Bm`z$Jo(%22j8K*Nu2fE&t|auBLLO{kvq6|# zZ?I+KN?Eqo&{Dt-uXO9G5y+1fncp*uO(vhEsWQ?&$e5uFMi?$6RQl0%9SJ3?p-lS| zjtsC53^HvqZ(ig`_hjKrLcUz*@nirJJ+@&_rXo=fr2kQ^B+IoZ;Iqv>9f)AJtz z#FKCICDxFIW%KPPxa@mID*HK}4r~;|r>8VI^D;hFQN1{iC+baO^jD~BJGhtvC|#ms z)0kiJe&p%@wSLg&j8`Sm&$grE*Hmhon41=-S3=fYg`NA9GC;zlx7MnN{^+L(#ULfY zSv9Ppc9H9uJLjA>Jo4GYx}P#xnT)(G+0F^#m47lpTJt^JqHn_;tnZ+B&>dZQC}Uf| zyZk{i=q|Z?=yVKdz|25Orko(1Yu5H0z35g!x>${4i*>BdE zgLx=urAkMwP+0Gb?=isCH)Fj~R?$KV7LM|gs{RP6+!GM9j)Ow!)jGqD+-Pn=;$5qE zZ$b7Cc)x`kw6r`_^5A|?V=`UbVDMa7;L43mvKmVzeOEQ@!=QieRK==sQG1J8A+e#% za!_&o53e5NXMj;fn=*AX-&N~v((Xw?qV9AA3k+J64@UEII%onALhgK=eRUPdf>1&z zH>z0hv=9Z+0WGB`r-u-77laU+z)b+S33omg2L1kRVH$HO?acq?5aY4BI+&d!m@{sH zPj?IkaPVUWa9jtdJ%B2L)OX)Kyh`eG?Yxyw+der>55}-OMC2(_Kwcfqq^JA$Hed*7bk} zcuptce@2eW{~};d+c7R=3b)VugY#Zyg&VX)AN|~7oQjDr8Am?HzikOLu_#y;8o%0> zqSWLR@S=ozkuHLAJ0p*xKofdZd!1+q&b>yrbB;^Ys*BeIC#}hGMa*j*!S*ZZi-cYF za$)+K3ec6PzM3lKQdRz;li#EoG9N_l?y3(NIvFdiBON`omF;`Di-zYu_l)wtH>Ps{ z({MJqQaQ$yEmd$WD!4h`xtl&;zgfOGC-p4T8Z1_MbT`}2NF`gZ1!|%&^MIG)l(QZD zxkY)W(cP?ht|DoqshUacjf=Mg$}@!Q3H-#hvFAlJ_9G&p#U49tO@j>$bDB>aS4#SS zBDtuCT$BR|yF*$|81}+U=`xz;6ag<+lW#G~ABA`~+MBAUECOR0BcO&P)AGG#=ofSjo4)Q6_%}=&Z^->h&*_bjO(0p+IyY>dXQ@Gb2ht=F+v&8Q)$;pT=66ewb#k?y6k7p|flg_o&vkkAaiaH<;CS}0$71CIJV>MzfE*6*NCDk!jg>D?dx zp>Sp``WE9}xUlE@)s;$Z*f?azB5x%a>)TF4sRi>$y!uZQMut(=x>z9{vs1_IjU>yc zGr+cO2fk%yZPj=dSi~Djkq}xa)lisqI$p+5JWLmlLdPru<&JdElA% zO(eHNS3F6oOl)!=^5rqMJY4csAC3p@BC@%YG9%b6&-Uf}9m6YxSCUpoVw-n0ozB#9 zfDaLLSg6Mpk~KMO*q-$DNk99?q>!~hpDc#UKAVbdJd+i5GD*3TDsL&5je3KD>RD&q z;HOoHK*vH891Mm2uOn==J z^?Q(^cCJSn{pq&OwUXF|j~edyfz!Q;Kndf9EeXr2r(kw9`eZq;4b*@!vLWU=LQOp+#nb(Qd$pW zpHFx@G}8gWAec{tK|)A`!eu73;nXz#O+&8>r!@V9@H_*ZX2cZVLh;akys`b?^^|b2 za@)%aa(aZw7*E=Vn0tjZCan_jP!gU!59oE{Q-RFQdiE{2Gt)|s9ph;cu2;hr6F;C^ z&u(A+xkgrEi?hy!|G8aKrcDjX(U^G0#(m^GYkst9)TE3@WbYj9HJTtEq3=&$Kc_$5 zC`7Bq_bi3SkXk0zFkkjVTU)6N<9Czr%0m65u2S}ti9K^iq>5B_k(3%)Q{Q>+>A-ox zeOBRj;@QVPEsFG&K%o|%Yk}j7f7IIUn-S_Wr<&q7db#r^d+?SX{@ADdq2<@nOJV~< znPt8XrG6zLQI*3me|e&N@^%ro0*noD^C)1tAO>HbF3iOcP#m`J5pZjQ!Uiw!!?Rk|Au47!K2 zp&n&;6dd?fzYFG@sT1O&OJIuAb9i%+J?SC-$M`6&J6kWnF!#3@J1z>jvD(|qo1m*rkdfflQGJ|ESXSTYjLf=w zY@Ov^TyPM{6Ia1t5NA6+kJT2zz_T%wS}RERLY8MMa)~4K9=kKZD98)Hu-8{6Z}X7d zn~c4Sl;q$Vvvhdq^>k5AV};SKNv=(X`I0*=IFu=Q%ah`yYD~B2p9mw&l_~KSpX87|QG! zPgi@#Y^58kC&;scJ1EuJ+1_=QFDE+;XgR%OPm8y!E~&ecnCxzFFMQ7avhA!!Y08%~ zk1hWzD9OV3@FUi=twQid8THAIMYD{BcM8jakdZ81ZJYks@x7?~0?)-_BARTu{N_sD zS0;N}B-FeRT-Z&Kaf!`N(%-)VH~zILNjQi{PZ7El4L&QBpj4j0EsC2HNpmK58e==u ztXCH3UJhcP7HEBEYV^68`nk+6p@(JlXbL;|zhyo#^;#VPwB_T{&AwK{{>ctiA+z+y z@N%_f0|$1!lz0D*yKV#vo7v-&BZv^5$jRMM#$hP(m6DU~50 z#l6Zq=U&-nfw(}=*I-f&*^*p3$!#3#1(WuA6ccmUkT0!43D#_-OFen}Ue45~32(B6 z3Ly!=y2^pO2POm)ABz)!i*G~8OJKwRWpL`ZO)VUHywK?OjTBUC5MGDb$(Ns+^-!EW=v%Kkt!=TT#n0IL_OAf7v4Q- zF>LRsm*ZDI79gIY9QH`pk@zXV-BH64d5SAdYj2>;kMhJ8bHb&=e_PZ$QY&&S7gM?vFAs67a3k2wP8mS)2k zO7j7Psz3LC_DLaN7(y>Kjs&<-MfupMeHcH06+elX4k47nP;-dxm;w&82n7LjFz62; zV#kqi0O|>YbRb|@NC2~JB7vHN109N(kTz=Q?O)z69N5~-H-P;OAay!_^wwB@QEa^t z?6UrOY~(nfx>F1bomQuOPHNrRNjkoha-Lr8sSWJRvNexvnP)@{?{Ub5 zkWE$85ls%1D4irWT!r?@Pgkf_)t(;&SGfq%)yDVM6?fXLfqlhujip zo}yP#>0!4C(ocBi=gm-(&hYA^#L$!X8TUX0f1)PWIS z<@o=d9?(~gxNOGUhg(_tjNvf)yKb|1v7_9wTJ|-f3nD$tGGjfGDr)(7Cy)v4-g`*9 zAP3OGc>rsVwgQAO;s(&VH1GYjOa`wjq~N=^EuW_H+x~-aEzO8YeBrjRrqmLVU}d?s zB)iSDMNSENy{c|QU-oip{%a_!wHxnzE?V!=6m9SFiZa^+HZgbq=$xRGk|AuTO-q~P z$7Ig>&3tplQv`nk^59i=m7=4Ov%)G04CQKQnrhdpPxl=|vu8>eSYz4KzS5?}3K?Zs z$A$T<&DES!t*aMHA6$;#8EK@cyboEFk$Th|SgxQ0+A~X!S$&(sC|f$8k(aS&Ceg4I zwG^Yi@Vm@4jhVesaYk%8SMrm_ck+HVmoB0Dwc0A8?@{**saz;HXP9Hps`=Obo;jE| ziqIzq%rJ0^9t>@XP9?s|&2hK~*^r6#sv0CSIoE6bQ3p-A2M;b#T3xqA|VP`xu7HwdQgQOG+mb_V03mPC|L$6pNhu;q<>2G%CX5 zjMf94hORVx*=LA}Y)GZngD9t+W(t23$a(fsNDUU&u+lAxo^G| zA(|upTkDBvO}65K=|xal=UVpEyr$CX#9xiHpCL}!w%?;q@K3%eV|10)UiTUKI3Fg0 z1H3d(d`VV?V4)jex<+hL%&B7IVYcBn1??hWYpKeCsu^=_%H!omg@T>=$-V z^tUal8+UaTlc;{g8sgZW=2Huus0u0b67Ms^#5beR6bvB&l2-h=zF?_eJIazG2=oq=^^-J zwb$R>AQBCa3BKzb{n)|S-c$ZC+A+XYRc`c-Ksuxl>JM|oT5T)y68;B7}+RGIb zH53Zl0Z2hI2B!-$P#6sugUtvH4CnT}6NsBh7~p{gT5LR}E504fN>%+y<9 zSp6+y_eJevfd7__W0YeUW~C7B9RobM4;eD6;S9{Y3kq7hvw7&w?TqY0j3TerOTh2;CzZ4-f zPV$wGwAkXIh1CHQ!~R(qK}ZC1RmyWU#afw5O=1d1L-s5;K(zZ-?T*5jp7v%(i1duZ ziq{PQ>)Z>MFS`L~S5Lm5pY$;Wa2;2FRY+weC+O%HSuuZMQ7p!gB^8Emoisz4;0fjx z1b%g6o;KSqLhOnOVoFy<9#^wqv2W!p-`?n=y~L{YusIG5%Cb8)8or6A6c!)Vs-wTw=p4J>HD8 zbm%+%E1qWV3$r_-^H$I4z@u4vtaaAt_6jcT(C~hVJ##O?tFZW~$&#lMipyuMXSvyDx`3^(c|>xySgznzBscUPUypt@YinwUJnPV!iRM~@Cdcmc7J#; zQ&tRUfRLxM%3bL-O#Mxk@?f*eb8+3C3@~o3{)G5NTatJtel1wG<(hJEH{(%8H8}Vl zU#%R=; z|A|(;3v!T+Nr-``IeB4t=!d}Dr!o4+_prHjN^)(O6S?To&$h)f)=Oo9 zu{~aDcr-uFWA0EjvW(d=t?6feEAD`Y9b0-`%;aTHU+R#vQ1WpeY~5hWT~cXXipU_ zZy#};S{ZGf2t6Q`b(#QrA$8EZbAQXS*$k&oLS|a^)l1pUuMCr=f{|f+KP~!fDI`L4 zaB=KLe61Fx*}u7~Oad1MoW(0BeJJ{K$jjwZ7`z<2-Ua zK9sgt^jS=D6KP+9NgQa`-+TrsdKrKUwV`1AQ4(I>k{9Eg-@r=2o){mQe=(Eg_aNx` z6{FwYqZ|SFn#1oZYpu77DFI$mQ7<(hf+E9%YF}ohXOJ(Ijvlr2T$<(+5Yjs{E}`pI z`IQ2Q46s+C*w~iZdRJA_eSNKra@A21it=8~k3C>9Mly#YTFs62l51J6V?Wj>UWTpbdFN$g6J)7N?rjf5hll9t z(ruOQmN085V4zRqq~I20kpM<}#sHz{t+2sZ|KCYf$6HBTNYx*}h};+?ji1!P8oMRN z{}WeH|4#mo_CbZj2;sLYncadfLL+-z2Wxzs5VP;LQm3aWl{ngK*hCY3owh;yA*o^k zy!V%Pnrnk@$HK4*ODsCF9qXCc&X6><=+tK3s1A!NngPZoTV@aRf({(~k-!@E*hxP2 zzG23-;!u36rp~Tp#n=td7m9aT9Gd!Lfis8ggof)>Z0g)TvR;LKJ;d+AkiSI9?!6bo z?8(K9Vj)!n%#0iYGN<-qUmPrl)mQp6Bz(o1#)}#(B9FwTpSqM)#|CrZ*15W_CNGEe z5Bb0mPM#7yv+Dxxv!j&NuS-TcbQZ1vVS(0!mD! z%O%X#4MzQ}qLL#+5!*B5ea^@$N*$ilo*%e(Uy<1DGxQC3`oH#lknDo5z&NGvwU=s! z?K;pRQT>$9Xtm_>F=Ii+-22-8k8eE|5zS}i$>**^RwJZFzk7U{92#YNpiLnstQpcz ztzR+Td(8G*#%{d9Wk0-9!Fm4N@S$DgWmg@VD9R_NiHm_(vbA8PP}t^;IvX;!C0s0~ z)I5`BF`FAKA)_yWE-eP>!mI-EH=CNxM-_^;<@(xqx>zuzI z;P)|AIhyS8eI1qs?ZEXpCLOb-7^EN7-e)HaFCsf8b;|uXIh&8)$L?i{MZTQsTewKyfQwBvHk+7u?321wJ&%n0^;lETRD$;%ot~~ehkIRj8tbO+@^=QFU zv+WRFKhE~LR|+{hal{T^LKly{O4}@hU*@L7y3~rlrWjvj)xpID7%Ga5H68|~4LWRN zFQ`6lThX+J=rpJl*PC<7&Ug#Eiv59Rqp4CYp1BZzyU)SnG4%M)@dJi$RX2dZj7&J{*M1-s`q751LbGL4X_nH@WNni>G6A53uB+2{zSTE?az3SqV;Sh;-Q*CoA z*?9cE68~kf8iEmkc_I+cxi@MPgWU|o5Pf|CV zR&hvO`gv+@?&SGXKgw)q$C}vqn}L4!5y_GsHW;&wRkakkz4vFv$>CJcDU7=awXdT` zfwY)R#pg!l-%7t2V}eiqtxy1Qza^CzcKJ{5<-ouvrf`Q5A5?DD2NRN8m=q-haG)5m zm_P$|-w}9(fC=0h8va94aXGNkZ*>S!9jbq72Gm^zGf69?fjL_Jmg{2Fj9Zw-2o5B~ z_?(xKm`uG!VA0m>cdtCpsifRajo=YsQl+GXBu)OKA*>uVDNl_Ae=GXJL>TqjQmiNZ zMPC)bRU&GYia_##rKYxTfVJ+E%aVlNGX3ocJ~O6+6!o~f=Sm0Xr=TsHt?jeTuU_@>Rk2t zO^FdE_&z$^sD3{r9v|>Ot;TwK`T4X2NTFJs9d6=sw*=Mbk2_y&7vM2}SkLxdZ7W`U z?Ti0I7z{?9k`X)UsLNKp-{@xxTS6waFi6FjO{T!C*}UgR{il1=3ingF**PT{Pf=%q zyL1drs+x`6&1|s-giu;|p)F@?K3|q6x6E>`Q|BplI=_mSUYarC%y=%FJ81^54KWMr zNBcIHnUs$nCQ6=rLoQ$f;X1;=y37N%r=8e$G$lj_k4?nfxoiXC!v&Ljsj%rwWel!@ zg;(2-JLdAU22F*e3#qX$3Rsr;s7L$L8`{>Bda>NcAcr ziPy<_j%yz|HO?@ZETh@}#byh%qAoo2C8S_^1I61ie`t(e| zN*PQ+jr)my>L+DqNOhyt)NHh!pchpA@>JypP|d<8!sB90n@i;7HIe2gYnM*4PMA3P zbD+H>6EK}WdQkftKVuA_5JCVzXd7wC6*hi zEPtcDDHo~d5O*LrZdrJg0_DN}R4O_8`3Kb?z zVe{Wa?-#1=`>f@v%N4(ys9ai^JM_NmMjYXX!tC_3DingBcr85RzVztw z^=EfaPS)t`lv&%f6VvnFO>`m|Do{HA1(D{&e$petK|GE~|HYKgv|iEm^PF<2f8GqP z#(P3in@~N16!G=-IxIpe(8)Ur_}q|s9V{PILF{c|ix2~1kW>Hx=kECjZVcN684!RF zDn)AoNRLA8cN7RPMlOsDi=l;0MW}+%XgD{dz4TUX#boLxI#3LPrebUoXGN$UjAiUU z`8p;ycgLU~0KN4|^kAd_Osx%besPwAy(kD0wjs8e%kjvu`yye_BKadDwo! z^lMIQ-_F&XSVXUbs)-dtypVc=qnWp;4whGuXmKp@D7H)AbUj9~O$@jocZ|lZ{)~Y= z{_CB0p-!D1Q9olS0O`nU*<0o5k?FSk@4hVy?Ui2x^kJ_Ec228~`1;PX>Kxa!`s_SQ zA4VC8J=F~2Nbw1nMkL!&bHoW&cDq#u6H2Ojx?b9=NtQ2`MLla25DZ(c3C|J3{tT6Mj z*(%6`hfVY#$j)*Wy!CiOPO+!_t%dze~5gw+wIHq&t;G`tp&H`aEN5%At^;YZ*6Jwc-_tzM3J61Wa1dag>_FwQs0gOr}v*iu`j`0 z##Djwg#PCr*c1-pOGL+aB{-YIR-2-h>8HJi(VjBRN&`^y0xkrMp~=mk7FDJmMMpXO zZBMvE{Y^Auea1C2(rBRUi>Tw6*DlmJy9D{OEyhoBIo7*|C1-GkbSpc1rfkokP_Lg) zp_1(U;VNIz-RvzCWGaqF}{7F=IJXGOz zLHr2@)C6up2}92wdBXUq^MQW^4U-`Qsk*mj*IUk)P{scrD)-Ny`p^FbwWmhhrqd?e zh4h#;urR6cm^#K|K*E7p1N^VJ1hM*8M*2^6N@Fe*V+X?smLXs@dz2{X?rnL-sJ9?; zcBViczAR(X^eJ|&RFv6HemW-<32bHgK$GcpLwjKWAqgOQiRhKm{kOLor9Ufj z#>tgSqG#!D=yG(%xmH`;QM*F))YI$8I#!4&vqm-HbFHNfX>MBAOL>~9`R(A$8grsw z$mr*f^#>o1S|WZsY^jFaU!<%>TA!5hDo0P&pBJ?1Ks*9@9ft?RLS7c4^rs>(JdRAJ zzee5L(PhCY3SMAJWBCws8TP9}DFr){Dp8neQz68N^yRrf*}-^lmo#V>J-QmJgD3v-0p4$iPls{JvxXWCaRo7; zuMZ-ufK##1(rRJ-Pg}*pFY>}lZz=1g(0yz3?-~25=^s;#_}utcVvrF}h=v+-KfzB# zXfGansI+QB9PtvqJ80Xzg^@s9 zhgAtIj}!n|2NR|w9nVq1adEY1mt)Q!(m}UCYIx~($!>{?H$7>3u4VHpGdyCd(~-W!eqb;7c-GRQ45yS&`i3 z?A#cR0fPAC-{xo-o`OK?VKT1N_U(TK-+v4P!C6j^Vx~H->_O)R6>n$nRhG-sT08nUOs`_~vJs4~1E^EN~nwEcOm)ywj0lUKfVtvcL(=)Vw#`F?0ga6?$1!`wddGwmRP#1CIl)Z~tn>_Mggdrsp=HLmx?tE0`;{_X9PhD6QOOemvj)2_VM4}>F4>&e>FE#Z=o z7^N}H-~O>KJ@n!++G2Z^Q*IKpWx*c!+s2!6^4y9^pi4m7wwdHv+v3B7vrkpNbL^&k ztKiFmP}+Rm)l@{!+zz)rR>Mv4A&{nJ-M~8{eq6iQ z*F^Cdt6B9;uhyDzBW+6eit^g71Kfe8+319zy1=``(jonT2BWD)K2BW|&>o#JE>L^U zETFBYl$E%~Tieo`fA$qk#@QVGoFgqpx>js-uc2~Tf}U`TMomK2DHnC%t;kD!Oidpl zCiCF9OObRTV9MiTeOHHpuYE&`GznMtP_wRe(s&E1*|?Cjh#cl8`dk@{6u zugon5UPo`bvCIMSDPj}`D-01)m@buD>j)}eNe8OQ0Z`vQ|KTRmV+sWDTa3VTncRvp ztN(gd>M`vr7^$3}149BZIZggk6*q#D{BfohPX&6_7#W19o4P}BOH4Ss2-6DnkRRll z<%oD($f@~U;?IlfzFzy$bL3(5g!&>OK&IkJ>N z23*v`!2Y#p!PytWRmOG?zZ*c-o-!6T0XY?Blm_ee74s6~FGe$>%jfFV`;mgUWSmLp z<>vW~SoeuPh|&SxqMX@Z_$NONo{p|tcf;|<-*82txHxr%gCmbi=`2#Q9#(tyl`w6I zI?~c=6iD>?#A`d-7Mn8!$4!z|^OB%TtjLD7TOZpQrJhmuN^T~eNRj=xd}u!6@hNmq z>&~nS?lZk%e?x(}%2{ecU?0&?==RsU{#W0ox4YWb%-csFB)HSj3PAiJuUc zfR>}FX|alX(|W8P7(Q&9(0!*x9FVy)YdAXh=wnb0ov+w&&TCsu6;@KZy(bFi77BAp z#9@sXUZX3n$sv^-8qSZQVPv=E3lO(xadHUT^R%89ZJsoJ{`+rH?o0QdEcOO&<9dYX z)eeD|V!eyi>U~f>9KeH#xx{1bUFd5aut}u}(^6Qw$>EG?L^d41DW7V(I?b?rS zfCTCrV3BewomSawE-=3d%;)z5$Db-ob=JD?5#fMz`qzleMQCs4BF}5jth}pWl=J87 zvY@n>vf#dp=}8$SxzzB<AW-cC%rR-Q9MwBvME>y?Hln~FFz^9KEFRL2Qc@*5@q}L^L1N6kb z=@>DfoU&J@LL@vj%RojurJCIUUln+3$7ZM;PKvbkw2%n(NBIS*I`*L3LeK36O%dosT7LHB*}B#Hs{n>c+Bz-JJaYY>Q7ciS zA7#Cdu&dtG_$kXHHlAfKdc(V`66ps&YTZm5-&fw>|C(RqDv4@rOW)Masngsh((R`D z_++{T-@D?ilYV3DvNaQY0Pe}i!-!({xxO>)$~no3)`iE`HNL+ASlc~_|0v5k4PMhZ zgcL4)*vM%pJ7fC$a;B8KE7bUuhZO^Wy_6b=!1U_C@|7Lqtj|B{Wy=I*&RoAc;kSF7 z*Jw=WxwK$Z1+SB1bP+?4^GvY`=WOKoYj$I-9HattwwyW>)gvHL2m#SY;s>P-STyWK zU`oE4o%7&4$Mupg*+)yo5BuW^^yuuyn-&ox^T@D75}%Z3me%`b&SxJ+Uf6W*?HElN zstq_P1u(mbEVbYJd<3$3O{zBJ=9BJG$J_}P+cB}R&@YElca#^`^JH;mEpjSVf^eI^ z?$ac_NwhIEMp~;-d+=;Ph9mntLg{#lxF*L@eacu!-mZbAIp| z*bTa&0 zIG3KBfzgj0F+F#oIMk~cJq8bM0(Dm)Q2d|2{H-{xt^orWcA%4)7;c48X)q#U+~9$iUJ>8Bzw#0n)pBo5-p$+O9eRGh=$;;ZF8zwO;*ftrk5N=-L*1*J#BGVKhlI zCCQ5M6}8z6kxC%#O&Mv9UW=EeN1pw}>1Q9;04Ex)9gD5V(X?v#ts9e)hkTQL?^mOL z?pif3fE@iQ6-}OfATc6Ynmk$L&rd`7Mxcx+bfdrIyBN*nq<5O?nx1>sABc^?gR}M~ z38z%NT^{l2A8RyDMGPMgOWYp#28<=`8R0#tr5Red<&6X~+Qofe+GELnhu;I26jcTU zlg|!3<{uFEe;Qh4zhSH+{GRzj2kQZR{mM*!Z1m!exszA5X-}cJ^)5HAd%j+651}B` zA(;zK2DiAbx1I~3c$;A2BUzlJKqBkdlmGXe5=>ZYtDRe1Y)Z*69KqXMST8;>8`p9% zQ?T>tXgyES;&~g$BB40AFE#i8Ilys`M5skCPOL>AG_*@Ch5QS1?&((EF`BvBWjm}Y zJr4~^B`VY1=wQC9e@4}bhpY-@e`Q9zS~=G&$Rg|Xph61M%xJUQFHU?sWLc+{&q@K3 zg*or(=Bg@?JjLZx6??r~Dq`Pzq!R0A^jXBx(6CTYyj&H&8dhG4Q@3xP{;IPw#r2Wy zyQs4|$N9Sk;?Xr2X!;IMF35=bzGEIqvn9taeM%h}EZiE$ZZ##B_IdB&$6DY9C=R(s zFYZ*t=wIk^mA%0DLE+CZ{im2m^?x^*&>vDqlXn$nL{3~*?mdDsZ&wXUT(GE>Dm2(! zXs++SwZJE^=kLnG@X%IMT`?ppM>@o_+(S*5b0P4Jz)i(sjUALa=< zhu2vx&x#yq_Z5I1FYa%YK_IZtW7JO(vKcBg~Xn{ z3lo%)$+fLCI>s0aQKr>w2#dfKiQnd}YwiB*Y#R_3Rt0E>4vqj%1a%?g2ZomLYPGJh zP1kPLYR*S(HWq;$DqFLU8&VXWX*kD=kC7(fnHMG@1K56Ui3LGeROxlmojsH*6Rd{1 zz@BMh9~vkhRZag=F(Al|4rT74#@x-s&v`@66TCMZJW3_{d;CGmhDldCZGXS!%W4U! zCcfFAT1Nj+o>oj4{+MyNy9SS(0RJ%@GO(oU7Y^RYzxF=qi|o6CuU-&(EaakCG+vSF5gw8A36+NI?oDJcNb|(ABpw|4%yT&1%{E#unIzl96ST29KX+wdoDuKP3BCN*0YHgn;Ldwwiz3zIIT4xc5{mE@NSbv9+i&>FBkDYA1) zmAS>JJ*gn?O_vG>o)V6z8^B@YeA1=bL1PSZnO>AalyS}JXpoWR-Kxy&N1@|WBV)PQ zmbLeC;-^|B79NAsrWR z>UOjfu(iQtrpw^*MGI>=kSE+T-CX#jlohw{6J&k-e$fut-5kDmhPeXo_W_}%K2i}m zFFrLVDc=BIu}lM@*%ar#y4GQ&cx9p$EA6niSS){Liu_!16*^Cf1$ky=?ZIJB2%aRR z)CWnH;f2+Z9hJ&uip@u^0po=@&M6)Fq(U$6_|^-hxu4tsd*d}>nGZ(f*LkZyPP%mNzGF~ijEaJYDEdzCy>hJ!&MVWfhbL^d+kWWc=mNwD& zfb7qhTipY)2xrCKvx|cv(Q}V(_ss*Y(P=o{8*Pey&uvX34P!0ef$y4=&6Q$QPV){@ zFKNCCNUu+$<9ai!=m?t*9xog6Sk1Mi{F#zm*LU`oL^W=M2Tff3sn))tcA19j0)>rTd z5tBSBbbEB+Avylyb!o>dVf^ag9*wv3@!bYYAum-L$B0ye-#R?Q+v~^F!tWCA31i*8nggMk=(wpFRB{LA1~ zTgj?4W(CQ83-8q$8snWTB)8j0u21%|zR@-J><8zCMWOy4Di{0cP4%3(zvBdF{!JdJu97RP1=v-M+{?wD0N8?vz<8B;wyAS<{S zKaViK$TVBOiwvwRpq{~$NWYkK@Yc0J_OUNhzPQxeyzlV|Vgfm{0$a!xG0wF84^^R) z7-M6){5QAtt#!(3Muh9)L#wBb&_6jiF!?(|XJw$$=VS*=JLY!je#6DSd+)*DqN{HJ zZR&<6D7Sl&!BNYMTNg9$jAKo!1G$x8S#T4$^?y_Ef2M!1*^`9R@QHfAc{d!L5ZOyZ zYraD5Bm7}*e|mZ%1|<1MU=If z=QDgf7jgN7Ram|iJd&HmkD3b9I&A?DZLIdoj;se~w*LbcLFm4V00`UF>Rhim#{W@mVI-1B%lK zpi@z>u0et+!ll}@ge^M^W@&RvwP{EcSPJt=g{;}61Cv+oKKEMAo+87F5*Jdg{m;_2 zAdGnmPh3`PR^%|qtwkV5igp`f!ayWdkZPnVSN1vr2r$aRV49>^Dh>7{UNxL(#`(iD(t84 z9{4rc__qDD-woegA;Y9+Z`ANVQ(rl}uPd{;B$JX&IID_AjqbU3cOhnMXV4N)kxZ|+b0wQs_hZe}^mt?n~W@tjhDnqwvNrT+U7k6Jv(CzoUR(?IAc$^hh0 zD+%)f$tUrrW7DlJF@xHSXOTb&k6KQRjw#gAr2N8wEDtI*896l^n`AhRMKTaXtDc$X zHQZ}{9I%JOcKV%*D0WlkC?JJ7&l%)#{dqO5I!}gJunr(DARpo#pqyeIE$i+zR zrlcs>4Y-bR$pg}p8OZdk*_qb(e_1y%`4hL!y&Ke3>+97{cMp2vEu?5?M^aY@sH^u^ zjUWt8PAXXLY=3B|0}bz0Zgof6LY!u?8tJ!v?nOrPlafsqV!18E%_zYq^QuyDpIVwf zow|y#HMS!RMJ6<5tWrqW8T!=AY82#}yKG{O%E`t@1k`th6|k%i(9v?zEZMq++A7O9 z0fx7S!xW90naCzyC5#49`#l~-MBr$&oxO{nLC{(tKoQU zG(mim0&qTD_a?c;P>Ih|TGv{`-Pon80szN3&T(0$CU(Fa3L|@JLKzoQDqLr!Czr9g z>rUVbV?q(f6*}0n#;#5Q=xQFdax4D;E&&rDAapbg&t)kiu6i6(O+HuiBrHG~?NOQl z={yf~@OY-pRFSxqAa@uw?4BY7>5hG?$i5uf3%?b{#DA(%-;YZ69}q5d=|}q}qFap| z5}KD8sL*lEO09v6Qa~6!l(^!6a%w=lQvyA{wHaJ@sn~H*FrWySanhe^;weL(f|$mT z{{X9hrA)RQcQ@^I8)?^v8D0<8yUi0*g6h##7#2VQ72|d-hLhaaap2wUB-lO0WR;$V zwmasX0P9?*i*K%)$>6aq=D6Az54-POD%iUWlSlSCvC9mfdcIc0bbRZmcso;(-e)Y# z$0eI5HIH?mUfHhqLyufn)ADF>NVwWRD#+BlD;3SNp@~Q%(ylznmZHy`?5`!Xon%HK zfv;)s?!20YlN`H->|uwYuQu^7g>JOXK$u~6jmhCgaaKGn{h?`gA@U>${crv4eZi9NU>G1%6gbMO)MoC`myY3#D?OuVQNZ;A< zXRZYlW5~Tq#?Vp2r+v=Fbwvl7j(tg9CQ;PZH<(Q(`sn6oi^z(fVh^aT(dws)>h14Q zBULTVE1w4)DcjGjE@p$-qoo(IAL11M0JcZ{;asnp!?~pULym;g=3@3}>jlyu;uNCc z4@MQqikv?PkLW5eQTOa=L43hf3&bUYHCFC9S-&Nqj0WjO<`jh zEGnd)BvtR9TBO-FOR2N3->sgVBbEaIlV37xH|?ov*Ec1J4(A#4918FJdE*&wE#A@+ z!+un^w|esf(zSwpOyuswCo~|-3MyEaEmX-ZM!Qy?4k-Y|Td}lj+t_W;Wu3q{8RNY} zWuw*p7wEoCkK0`bnK|4E9N={Rr}3{)0{{VB&W2*Jv5Fyu3V}fUD{4JPBE#ktmohZv zW{O5w`&Fpm0CQBL)UASyy5^@Eln405T4bvNxV~8 zhSN+6(wwoV%_Ncy+?rvX0Of$85=a227Q)mXd|CU#gEE!i&;`qBFlzeBJBrS=`?;%G zq%>cTYxJiW#yVA7cELI5Dbru1K<;2MNsQ*aZFH8pW9QJ<%=goouI85`=5lM-{wR2v z4Wq#u67qbb2cWMOW*Ic2s}m%*Kfg}DcvsSX8M?Mz8WrBT2s6*Me9aq>`5a)^O=;qt zM%LeAOu=fJxjj#H6beC0nqwC-*3(RE9a5xUsGH{v%vAN1QCJ_eCOiL3SSQEvs#rt zM1;I2{hajtI#Y zG@W^-FaVQQBaFJ74nWQ-zIo!TK{t~qd}kd+07uiUJ0m`|c57w0#L#1D>IZ75VQ_g; z57K}m?^D~xBvxPIJ*k2=^vz2Ya>l`zIiLjc08EC%spU;rZ9?)`1+j14@&*SdHDyve zq{FF62e$^STIsPXZ+BCUK+hEUn%Jnxt(i_6UnVWbtx+Q+wsDizwXd6b*o*>>wUKc& zP^nPCpWC%UBw;&wqs9fBz zd8K9}rf3Tq4InH@#U}OJoQldbKdGR~$M}r{G}=Y=6w@;HBC~wP$5TnUk9q*S(y8xE z-=39N6P`^^8z3N)KplU>>yu;RSX{AHa8g~e6GVlr{ktGLE}D_ZIVjY-@G*0P<0=M-EDu6d}L@f-aq z@*kMf3YS(;GDzu3jysgCWW$rvy6+BOJ)=7z>T8vT%23~Mf%LA6Nrj_PxMQF2tQ)bh z?6wSLwpTsHTG}d(pFDqLOc9J#mbg_Mn(0qN7D!YIiT06-t2U(+X9d(Btw3)Bo*N>I zp%L9^wzqCxL{e%vd^ci_7(~2Pp>W;W#rsK&ca|@A6&0U92p5yMRJbq0ak1d^>r+XP)AzMvHj)8J-M!hK2-v=gj3wY zq?&dy=d+l7&}%k(Yrb$Ay3G30ZC2_9Y@(5bq}jtsZF8Pf)eF+_Tf3BEap_))&_w-E zepOz5F4|y0LCs!-*`GLS^1S!YxmX40F^ZwL*w@hV_%lwGi7~G}qN~a9`%IAJ!x{eo zfQou|5={B{AtwMFn%UE|OY5};D`#MTix?H{*1iGK?U+B3oN_p=s5ILm30lV zHpDrq21e_+)1`gvNvIjHIIej+v#u)0d6oMy{OLUDM@K)MLSBvaC0LwX&OeR6I(OSA zAI9IESMw+iC=OIw7xyFh+w-XxQ@S6)m?hzbu}XRif;9fm88ni%=?G4U5(-5C+-bByg=nh3TvMQeQCz&-zOfw>Zh8d)rRCwH|=hC|4syO7V%TE-l$L2K@moh_+ zO+y{~$0O!Zf)A@ajF2v6>W9PbNphs?S+pO1=NPwHynz`+B0uvk3xr7 zfT{V0O>*8Q@gx?|NZxXQ2PZY>nvaV_8OqPW|RAN{#?Ej?KxrzxbIHXG)c7g z!vllfwlqCG?jXrij>OR9t#R_Z*!JPlotkK+6vR6;3T-ZE0dq^5Z4?0dP-&T^%>XSF znWBIfJkdZjPy*7@3Mc@j6qHZ`($i^k#Q+52yp!VuLEBH2NIOfZ_2+N+8tXi9;+cFq zZwZYz8A~qWe(nJO02=ZAcf}8`74yLuIqRAdZHco3c~i|eOaSRo$m&lO3m$7iOFnoV zDGdIVTQp{XEPbYz?KN7823n5#Xj^n_RMms6T$RHFC)A3~qJS?pt8jV*U!bHqtA==Hdh{`xgumVhN|nVb;Pvjfxih|768pAX?B`++AITeMrn4O z^rhH+D6kCXjGBJK=}WNVr4|A@Df>+VHZ<%51vz?}QVR8;RDkhUH1^qh6K5D<(x~RA zwqhs<17)ZQ_>HRkcP?w>h^Gr1Fi%~!bifvQQIVMo@v zADoiJl23C?ZPf~+?rrSXW2v<9W#z@}D)Ukmi&Xjw)|{K%#6PxS`!tE zT7~hAaHo?{TLEzxc|fW&&F4$cK~f0_U7(N!JAu(zq!Fk93T5@AS1}b~^u=Ub+&VDH zIIU%$dJ1;~gT20=Le$hqNrjsjHMe&0-B}4#@K++Tyme{kS^1-q1y=Co<6UU#jM-&e zQj)p|wwX$6fU+_Z$f%6U#~Brk;yLBByvSlQNUXHhCB{nwisF;AvELVUbI>%ERxZOC z&MRj%&3ImRp3FJ!Nv@AIy*-i3Q&z|3jMRCh-OX!qEJ>PN)LW@RqTymdX~Il%QD&2q zQrILtq-Nk66%Tp=RUK*>F5^zDDjO{#W&jGw)FsCN)92LU0|CWnNpP~UJAtT_(X1fv zsRJ`pS=yy8xu%k*(z3a|h<6%cCae&&)(8h|&@vw|4z(G&iB1avRJAshMj_8V>V>_H z%%kSWA6i`2I;qlwSCg^7_PBy>3=h(yH;PUcpodIgzdN78t}TpFjxuSfBMHSP?ue6a zseHlfN#v;MN0aDi(3B^bGuDmZ_oVVqtu(^Jp`-)Lf!>fE$AeLr8kJ&UKof>4K@HNI zmS)W{k^Sm>IM3Psd;DK0rrj=`O+nGl1YOZ1&PY093(&vW#E1>YbkM?srILkIU z#dp$ZmWU1j`r@Bsq*@Dr!~>4Tl%$#*Q%>hIsA=NxhG>aV?MZDCS|-&@W3_seHZ~GO z5UP_=OX0f*ZNWg#wJu#OK4)^SDRErHUNo?it8G5@dM^{{vSSk{`te&C+}gz$s!{6p zasi2y=iaO(-MjRaPJQVCE-0hSL(zpUM`9=d6nCW*Vt^8gTw<3L0F=3-6k>o3(MBl6 z02ET2 z9LTMTFlxzE>?qp4l=&EQ6@WCmO z6@4kh8Zk?ib{)v}44xLG}E!oE-GvUV05XHJ=D#;IH}h=c;cFfHdnZh3=V3!6=vj|imRS$ z8LKj*u%PScxYloKTs{Y7WGV4k|lX+ss$sb60Lr zN!v|D5#t>zWUPp6yccqVS1bVgQhOS!8Oj6Ft=NoRDHNr!M{}Vu{Git@tXn*{Ta`(! zr_2}t^sa`_!|>f(tc}!;n67z6y$#_mR(S(j$T%o-^r+3V41A|QO7=-SB?;&k@~SiV zIz6O?T>UFQWX-**JhsXrFW@-oASd&$V6Z>vsq_`eKZXk441Ws(0Q%Qe3Y&NpPXr3q zoLae!X(?L8-SnI4ube$;48zv7<}k5u%*T3UlkHQ@R`b2;33oE_oKegcEL+NClh>Ni z6`5k2PEUH$UX^ioK*uTOwC$gAV4jtjD%G@`TNKcUwaa01r%Hrp0Gi_bG#cJ{pdjrG zMS29_NfROH!xfnZmlOoJ1FmU`+Made*a{}`!3MYkD}jKy_|xf5f67J8@kL6Iw;+V>PQRd4N)RqNlX z<@KY^P`)(?pFcGIocB9@aF1F)i3NO4zW z`p<~svITdjW6^WgxyIMt=aVS|*w+_xJoj@nvr5dzoSxMhyQtxh=UlT=eNL#wE{AZp znHk^u(+%sR0vy*IE~j2M8h6_62<4d8T#vb@G1xAoSsyjL!|oWqiHPyWVk=ZV$qo}9<0BFUxB-bLk%4eM8=|k$M-7`zx7cx4w)Z*Mm z>W%f7BjC8rak6S4hinWD2hRoZ)s zlYls`Nk{|D{AqhYvC)i%sn%aCrY)>i*h)l+9WPpoiuuz z#@OmA$M&p6cMx-2nAI1$nt%4RL#ov(_UcQdnbE$uRQ!r-GW%JcZUJOpV_9vg!d9rs zeyrRa3R0@t+;OInpl%83?0%-NSu-ifV~?$1M>;bPn0|Go7NKtn^1ycML|IZw#`@jd zA^BMGS7OwzKpU9;b%$-MTC(TNU(T!@O4#&utyG_LHyHLjrC3wLdzz#sKD70kyN^7! zC3NWQK8CDEsoqETE*yR}o#tkoB&T3DqwyA{A0pw8)~-k69ZE0(VAaiu0TiH$EC*u` zk1kgM;s@zkFnIY08{=SW&q3y$oSagyT=dv{Z(#obd5Zl-XhY(iI$UC9&(^$*Q~B&o z79G!Kk6E&l7@1GwRu=LG=_>wp;;Sp68(oLcnz0@I)MON$$Ky)DbJ^BZJs4AgQ`}dO zMXu^Gk&Bi!ejgR;5#uZk8imhM!1krZdE7oVx?FESN3~sx#|y^zm{1oxd{MU*%tPZV zNdVkP&#hgH#P%|Dlu>Xa@s+u`@V26Zuae9@pk#k4`LcD}JA!l1HT1pyr)P7g%${nM zbRhHCiutbfe7mMmRS`12DKX7B8cfv)vj^P46!si(NosckQkCbPmDLE{CTA_kc^zo( zO-fJ^%_h^|y;mq)kGC|q$)}j{-hc)%OO!4~21%!{%E0PV4_u-pOU zihsgS4t=KY?b5HxK5lE)^&Lh??!2g53ZooXW1FRDMQgjc;^Q%Krx!UlWbCcGJaO-Ny2dJ;D>~G#l3^xtATaIhSJ}LM#={k|rt)l+` zMwtBA{u5B->ONVmOTgnJRy@&dt+m}h_$QQ=?}`HCgI0%Ne;Nqp*#TXc)a9R;!q=FWi)d0>-F5K`t*Gr;l;w1CjWU%72qeq@ZRj8nZgGRTG z97?;J87Dm|mZ6~#Jlk=f_G_eN1ke-?y(`m}9u0EX;Z>xa?s@aV@v&A?2&ROtyIIpx zSQ>O2T{+{pu3KhU<2B~i!@6>@-A<~KxXr$mEOC-LRfw#lKQK~$l_`jT0R$R_N=sW6 z&Y72ZFrd{X88xSex@>pm_N3eL4`b*(Ei{*bjY*r@Joo}5>q=^WTb zf7uo1gydJD=|A!hkNweD#L&OcR$is4+t|cjXH^5%w9iW6e0`=#d8bMuBrzNxO0i1m zXl1vJH09KvGN@eRaXb@Q+SkM@7;r7l^VE=duO7G;33ACM;Oa;q`qN~JeV~}w1Kf(! z*`qZkdNh9%pf9w<-&(q#5banDqYCnv?b|sjMOq2~7!?wNG>UI?*fd`jL91#BY>Gi* zde@^{*~VfSP)V-`@B-(=Q2PcyrF{bj5HHfAD$KbgiZfcr6J=?jU{#Bw^Hp(L#K)-N zPl$Zk6&R^wJk4YFtTA4PrN#sq z#b4OH#bGF>&EqDPhYzD^Qfbf_h-?GKYe~2@(a8!rkU*@-^!D6Jjw+*~B3EwaX(F0V z1v=px9D)vNqZVUKo06=9f3;qSh65Fzk($3|q%g?hniDM~OxOTbT|>i>-^Rt%7CyDm zTdHjs12tm<6?PJKJS)VW8*MUHbV3t6iswu}m3!W|qNb#nC<#0q*El{Oz}*o=bIzM@ zL#7oKwLGKA&%Hfh3OTP)li|vB2!A@vyYM8jpOc_#+7 zPMdVSVPp7H8qQ_NXrDhyT8z!|j(8N-g!)#2g_QEF2e`#2m&YK{%oa0DMw#|}=ZexX z0%=4e6x6IPQ!DJ;^rSZAbQPx1(g*<^Df5RZo}rVc6(Y?b9Zg*p!1WZrW>7j*xh4rR zvfWIW=B4|5fK!?Q=}i!hn5CfgBpRHn=~Aw+!>ZLrhMHl>;-$qg-I@nlLD<~x3(HfnEn&^yHHmM z;&}l70C>}77(VqEL&a{ABIV%(qpA`3Qf*<>5nTu|k-<|+B8`SNEp&4nb~)^xl;Fo4 zR`XdvM=92$I&HZ<=;lFV7#eVT)jCof;j#6m9UZ$mnl6Q6hV$z{W16v1fNX$``I{-#FHRsy2TP`?U080INuJ?H6 zxepN_7Yst+2L57%1{P@#T0=?Rs70$XcjMNskbOC-R(bP4^{o<^Cl%X=SBaGLWLU)~ zdV2y-N=$QF@{*XsDA-8iq}#s$Idh~4q-aE&Q4hoUU>;-uA zVThI`drq4CkEpLKEi5CH8na)Gjn4|{%b@sW8)yT4e<-(}YgL z^sJJ2uc4=TH&R=(@yy>4r%_Ul(fs<0k_g9YzjbE^i1azEZd4LffuCN+vq|lmlG^31 zXIII_c^;y!r8gyYx;Zcyw}-2)&qw`vA3p2)1`|w6?B&U z&zBmI^sBel#w(dZ#KJ!@ww!T{@%mLzIKix?O~t#Nk(!cBV&o8UU8bJvHH>VnkOwu! z;11kXyA48H8AB;1GJa(Bt#I`{o7btGXmhO&$8WV8K3vomckte(MF$2q%jwE z01EXKlUf`OEjt<7yz2#8bf#c5gR%@s1(aopO^73i8z77_mdx+~6tXX{SZJU^zxYF{dLjsP^cp61}TSh=QZmNx>}hAc)iN>g^+aEiI+w~-`l zR4yuz8Lb=f`@`0#V*-e~qiHKMtN46B;-gM@3TxjWape!CeDC2Y-rrYA6R6F4&Az`l zMFlv;7qc>%)7%`rL)xoBa&8bY7|6|7$gNh!Jx2FT_om3;DZ!v-R-uU>097@BXQgOK z7?JX67TcZ;Xpxg-Fk1#;n$m{d0O?UIWqZ`|=eeekiIp+ZtS)g;M}lflz)%DBh8)nO zr2&OXvE*i*hAK)3=CK^f|U@~h2g{iy|`p4Fc# zFPP11C|jy8<%9Dh9Gl@`LiJ_9(Sgo-p1YyLjDxBZiv5?OQPDbUePmwk5h!O z-N)9SajDw*3-lJe6kDB!B zp8>!XpJp&SR|Bu<&!@|`04XE^Td1{U#mt_@1cVkisEs|irX1$CMBM1bJ15lAV~Sj3 zy=rof^Bi1`h!(5if|O{1=YJl*@aHGF&uo@ z`ijmJ>;sBc8Ku4=e)5`kl@aI5Q}nFdVw}6X6F?W5(gW5!eJQ`$_U)bs{4-DqAN$Ai zsaEDe{8{?Zb^}{Th~$RrQMQT*;l_Qt)wQ{N462b&7hb4814f}^Ikb5|`A%vk((Xd! zCUM%fmgzbW!lYZ6iN^8|(vD$S9PzQZ2kvyFXeC~;n(7urBkw8t()noLz^Ca?m@IOb zAo2*VYs3Iy#t0(@y*S#!$0a%Tt{2AE$qccyYkrAW(g22Dw{ zo`W@F#xicAOcDzWinv1ZNSR8>vs+H^`^bwaA#!*f>)QM|;oq@%S?*+#MUUyIjcJbIC8!$7EL0uTOsq)i?jq1-fRiz}{o|`4+_BqQ* z=9U2@+1yB6vE-W4x3p=Sky-6*TJ;eegpGi~>6~?~m~O;Z3vN*S!#lCwyo}cx@bv!x zb-OsS?6Qt05h+Vm7i)Kad_JiAQ?sByxzwdBCdSUr^KB zPJlln@$Fs?U7Od9U*5Z?{b+j`hEa!=JHiUgtSYr&mD(iTz*y)XE z#{{8G;P&a7%^)ztC_hnG*Fc9<)8vdFEtxjtcLu(~q-d*3X!-oN8CIm7B$kW%M-zKz z;eRNFy9z-5ELWB5P+7;T$d+y-hmV+a&$VdygGQf4)aA6e-SV;8PjOhrA)Yf@)~R*N zzneYWJtV#2&Bl(=Y5xFe4nFSeRygTevRuyac?LpL(2AyE!qyczU966{rnexDSBdu{ zGM`X!Rt?nhvaGVR434LYjKxhO^r(!Q>JBNL{gg=!q9S7$>+4hfYYRfw7FgEWVg!J2 zeQS8vu}(@+Ry?|qag(?Xl=U4dHN{G&@~dWKcS*k1MfC=}jzq++r?DcvcIs4)+D2yD zp-(5Zc`VEt;!+0%i65PK*{!V;(!g~i+0V6FwgGYpz%;PJBwm$eZLy3B@sB{)@cRQS z$PcDDu7E~!#dF#!7;g&pBD!==bBc*>G&(r;^Gf2RQNW~NG3!WV7~+G-!4)Pcq+rkl z82PJC)BRwo2ZL9vzVM|jnB%#-VI!n%gWj#I)3R(1+kFA5HmCPT9;Ui&GR0a2aypFH z9HnD;#^z*plE`@mtuByc7-3tfY>V2a3ZQhT<}^`8HKvNNw)4rVo+FK8v6BFO%IOVr z-YC!5WWXniB<_levphQg0Eax)4DnaB1N*`aP{w-J^!^Z@=U3oJ7JX!^bP7-EE7&8_ zpfN8T*OK@HjajkB%l$=rG&%CcM4qB)ScNT`A%x^p@Wc2`P7gG>u88b&OLD$gb~O0Q z=cP<4Wc$4ZQ6)J85yuryWaN@-Mq`T2nZ9ZmBM$QB<|#;xm=8*cbvyL_B5R^pV}444 zXa0CY zT{$L9;?dBn3Xxn^6gvHkxZ7}t{sb!GYA{GRl~2&t*E2N3^G{Y4nzwP5;eq^Wb+|+P zRPGipsi{=e1-M^YnQj-3MHd4>D&9iJ_*QgNDLrb`k^vuDVk^kon9|$G5>cM@M&kY} za7#F@O8dtau-_%LE*?zs7oeza#Us?vsZr9U`F#a&wmvXdMc<6p)xU_Xr0T#>rkLDW z(2c&7?kg@WP6+_RsjDk=jnRcw(5zeHmja*@Deq462dw~10Hwu6<_}t3{`3faA*LBA zH`4*;m_-}t+$aH_UVBnB3VMo{aHDvjWf`po30k7aLl8x5I|2=6UQCg0B#qS)h|?-g z;x*bjnuaypa%urTpDD*Rbp{r*DGmac6qHa!#J-F@dUnY&-j?P==`k^GF9{iheLE zFmh?&;~dZfyL6|8rstlt;C*NT-8iM~O$|;I0HAu)hCL~{rwRl+=}yVVQ%nY((0b4V z)<*}2VffcO;^b-VqjJY8anr6x{{X7DJkOg3vb;vVW|-Wcm4V~yLfjt5nw|-wogl=H zJqf1Pq>4WEbXMd&vK;p2xyAd{(AbRHEG7(?y8z&f8u4?VXUhdO*YJCu#z3T{In$DH ze|mmswzjer&SX4fbgb*GLR(dn86k3^O7dE|gu_M;wPWAfCB!!ifsn+5`qvbpLXD*0 zdo{hJ;M88WIPe^e#BtE{{$Gq$psIJ#uFw3L z=UC^CXvRm(K!M+Tgh?;M-ZkU_{JwQEMRgEFa2O&zcXi6uy5^BsUu)SAY()+9s%NQw6q zM*iyR`{moVKFeM5#KOl4!^-07TANQ}bHWr2c`!C}_DE5RQO zpwn%mxW7=+ec-t1UY8URLl{WWRR;h8TvBOhZj)!qlIYi3POKxjiIW+@VT{(aV+skc zRrs5xTMZ$v0;rV;VaFqoE6Wi4qZN#u*=bl)O+M7@j`X2(QZbZ-Q^=$ufFN9=lecU{>lDS+6cW*2EYFRSaXw9^H+5M zM24t$6}>%&JcE1-WWC{y|J-A*#%2@(NZ# zT$0@ETN(Eug|vq_`Av8)i{^jrryIz}q4%$#FP9dQA8PsQ#m74Ay!0RATG056Yiwkt z<;-X0naAT+qSv)3KIPP(_tj?RlQq|4nCM~gj;|LY;hP?{qX)z-QZe%tBDn0)nocMW zLWkmQ(x09neR-`oJ}05Z_?UeSd0uHptsJO#XR+J-OtL5DET=fD)BH)a`!-S8+Z-tB zYs3M?X<3imj(XI}HYz%^r`7ydsOqfB9LEv<6+EA*rubJ*I*zau^iWv-VzEH3%fJb; z{$~TA0GkzD4yrVrWgBk8)Nj^_Fk z^E(WB*65i}QBYj67?|K@nv)kQ8)toYB7?lu^}f1Zxiwb6F2FHbDx=U=v2MnEsAB4K zuT`giYq;vP{eboq(-NQI6@1K|R3FZX_baR*g2(`<*TiixaZJ*ei8xl03Hgmuj? z_Wi$hBB-{R5$T$Vw4^-^9PBw!rT+j41-3r@F!+w!I1Q6n^Jw`}0jf=+%8j^lOP)jJ zM?m_+OfepLsbgY{WWhS-9 zN|abpMHIvoQqnQNrUxzJ>z^*zjQ;=$uNu`k1&QRIYtwvdb(C}mlf`*?qVU zJhk*|xc>lv{#9M9Zc&b7Z_2${tq}E5`BV?5Lcrw(8jC~Ae7P5@H7*D|gIXD`Q80k<@)_ zuLkW=8Pxbq78pG$Hpk^su{l1Tl+1CO^_j{r4l_ymds6hE^{nhr+;L6}af%4dH>DsK z98%y=y-h#sO#tZAaR3aGYur8+_C-bkN8)MJVEYBuK6=D*D9 zp}S>8LYX7JXkr9z&OqJCs{E1i^{k7wytcT7^O*OpcQNOm{=Z7_@J-`aB}ru>;eRERA{NuGm4rxIOY8ldtp}3}{ z+anx+K&az#d(&n>GIPyJLuQORggewaf$nQ|##tlYK5-0bDLDLfCQahhs(n*RXATb~tb4*<&B1M-9XRK#!;3iHh_ zVwdUeam{ytHqpVydYJ+(2hB^pQF41#oif@9B1WD?UPwE*?Zr*1X$IQY%|P>y7f<2Y|aQnuW2io<)5x#t+}D#g9=k#K3I47Dj3_ohK8jrph~mm`B!Wt(Rp z2>5+W}a!nh>mq?=+r?n<3 zENB1@_0RaEDAVO9`=|L=Ku#-~@mW9F^7H&B`B2J^=Y(n}G9EEh0_Lw@{o|UXD{6ZV zd!5(AU-=5l{^%dAdqVLTuNwGfGpS5ZO{4kOvoHFw^sL{+OW3U6dYUO;?;1+!j>k7q z;-vlxh;^wC-K#{D<~*9Lyvn~?u`%mVN6f4Bsg}VV%|u)!8+RI-HOh*9+*cDiu4d|J z7Q$2QUpM%rw`=zv#0vUHT01o9PCHl3+Vhz;tF}M$(AM~Mt1_(gMs*>i28`EP&Mg$& z(V75wr}Y&WG~j3fdRCQ#5<=E+>ss1Po#o_$D>xcPJxCl1QdcT2%+LrFbBgMGD|sD( za^J*xt2$r9`>7!Fu8S8Vg#&?8w}y?Q5Hp{8=c=s}y9nvI`{!q2sKa`}5afYco>>E> zVE8{v*>fzcdJI=tJRkvqSSa0G(z}A4pl2{5pqc(mRpyMEr*jzq1M5;|TCrc0dSbMc z04lAVf4X0#TL9Ma*u$vcXr|!O^HpFSno3O4W{UvoOj6N64K&gL6!T3zC<3&19!#Y$ zG1zdGw^-f<$_F`Oa%lbgbI}$u*`aM`5s{iV3Cx z+L<%#h1<|mi&Y&`Z!XEsam4_6e~a$Sms7_DBj0Y^Pas$~4ta@ZZBx+e58iq!fzQqoe^hd2(jVvh7s0g5q8^`xK#B9m=C zgFq3K9+aM4NlV25L*?d>!VhYn6m6owR4^&*DmJr1IYIeV@+id?11a>#TRBDis;rtE z5(DxMeXDzDq}nL39K609iH=las!8FqlY(oq^2enih*4o2B$@=sc+FI~(e6Y~h0h%^ zUWQ;(+M|-y8AvKA>MI{H>oGK1jL72*8I+I2)^&CN01<43pNcNP7~WO!^&jF5arvzx z?uZvPqog=l_LGc?%{6mQeYZ*PT^M;jd@5$(e>~CABAB29oMa{w5fEm!EU4Ef3&@^SM@tNEH9*nOrCcJKg17umo9uo z-%XF5&N<_Uvg-By5zcC-ecVxJ)YGm`ZlZ{1Y3IiyQcX; zzS$7t`{KCo5?xze>T5N$s^G`8l|Axt{OY3Ux8#r@V}p$2gHtbuwHN2f2&cKg`S~jPY9w;d}GcDE|O~RO{g@qB)U8bUO6cRCzJWu`ld0=Y<|e zx1J~F9PlgWj~F$#{3V)@v{B@VnMOUhHS`{}aUX=d8FxE4^Hm5_>gR!q`HoWZNbbaz zVo5%xxfGP8DJ`G%bL_I(6Q@crmg#>;j1x<==BI`eyOEl0KC7Eo3ojMS1b zWzI26a{+~hMk$#a4r!)Lm4>XFPHJU4`*T%)i?vLrVFc$DqBCU0TcNByP!+fb)K^BX zCXXwOj-s$NkgGb3VY}8iooTYE?q{nJO3Y7MYLFY6dl8N~uQ2H(vus^PbB~x;uUMkJ zjAX!DDhXxpUO5TGs7GcM>l$6ehQbo8K-w{b?NK44Ps_L3RibQq5z?(mc&}sjV<_9V zXxusq&-+}X__Ot=eYvrQMQ^C6<+)cft~3RZlN{@xt|^e{)5JE9nEHcShUO+b!Uxix zlG>A>olmi+u#D5DPq*%xrE{j;WA2mBrF5$#Kf`p(pHWk*XQj$F`@)NXi*IcrTdI}8 z$4d3R6p!r4zugtVDRMsSE%Y_1ZLHo~Mi4~X2lsibWeb`{Ry%@4HJDc@o+owx09g|c z_zhW)#P+T}VpP_C&6+8rpvWS*&lMbL(h=8b{#9u;+gIR9Gxe%k#@#|cDO=@k3C$-5 zwTe(z%V&zEjEq;Z9|2k2TD}Sw9d?|W=H&1PlXy24^22kM83MJ8T2={EO^NW% zHW$-57~l`o*RkXGW9eKroo{2Kg)rbg0A(%Ky4dvyB!Nhkaz{+mN-Z%drVsax0;!Ec z*`;Ok6cOrinzosdcPPsG*2u%C_3KhM+^CnWO8)?MtqGK7>S_p1CtUi}^K(!@H%_4X z(Iue~dYjOUsHsZgn+O3#Oh6*IS=eFtk@o2_A7fuJYOlLgxMThE{Ojp|7e3u4Pob}v zuO#1hGyed3MnA1|Vb0Kqr;+UklR9_DgdIo6}W6vwls%}WDB$?0;*i-_Os-=52&jidsJ^T5mL%U zJ54eh26G?rb*W{+rxMLfBZ|s<7Y)d^dsPeJg0-j6b6K~?Gop&;X6R&hE{nh>r2f%i z)lE+nLtx^b&?5{L6#3d0Dj`ix4+f@PLMG~J7P5=`wHdNZ@NrF44pQ*DiNAsXP1M^s(B%jN%VVq{Ra6qm%#y2G(ahzdIOte=VRoUiu zav5iLJ;^nhbI%p1Vr4`tD;5jtCWmJ^y_x?SAfVAiU(kMuS#Lz9$J#;= z$BD2p1kY((zJg;B~HI~M^kYFO=|VxR31GHPrIbb~t|p?9zLFP5 zM{zGmULt*tHTr3$96gn>ipEpf9eYX6Bn z`N5BTMz_$b^rmW*lepUNQE%C}Q{#b|OQ(h6ZCqO3cl_(K6-FlY^&`&B4f#0iBwAWx zVnQtoeY$q?d9FKG%{xLAU6-b(y}W%cWRF3*pE*h@ik0q5@k?(~;__NrIXEaQay_G8 zgv(eBuD`4Zv^8w=qr(27J?g3wxlY}km`;df7u0yOAu0CfKTuLGXQ3NtfE1lW2OE*{ zEKv661C~}joey#4wMj?1>Vz@g7lSjLNju$?Iqt37ye&6(0+H%gEM{GIJba0g4g1{;K+Q5n8fu z(7|*on|TatUu`TVT#csS&!>%|+CqD|FP*mX*3y|g_Kk|HC!HuMpJS|iyFhv8G8{?R zk2oo9mG7Y-itcHna<)Fa-D~oS7loq?g~HW5J2Vl5B<=7t#P9Qg$Rm!Svw>>$Ka0m` ztHD9cJZbxjqU^eLwSIB*^CfM?Vx$wRIkQLsuxq_eYflNPoVlJD;)#@j98z&valEyGiK||a3 zxB6K8M8%LaWY}nI-yO`5`fu`Vbj+pH>w{S*%nFiUuKOmv3nHAd;Y^n<4w=m-WPg{x zszird?AU)YN=fKY7?Hrs#XfQvrRjiKWw-Acf9R8=v-x#RrY&>~F-8RUS`T|X1jv$( zTS?QVoKQ0Im3$QnPypFka__6}XSS!=}!&42bV zL!znPpO^0>GH#R^KWy>|K6-8fp>EzIGN5A;?nw~7XO%v3RD^MX>pK~2$&x&WZT1!e z^2yvaX1S~^Rii_X-{!RD@HS=1469mcOzFqG)F2>>l`zTXIoe~m@TyS^i?rrpAyR{ zekj%+QI*1v4Fz;e7i1IGCN;rT#(xu`%LcXi{LHxR+6`@K^Y;;Cxvu3*4X;eyS(MdR z%@uiHXziPA{;BR_(WrTtXo>#|pcBJs$}Z`r=d$mm{tRD-nm!x(zB9W)KJfeV*L%?i z-SgPkT4U)F&~va-EJqq<5Q;eE4<7i-p8Rh?dN52cCQM|go|zzno*Xxg!AAc zWG~}(p)~i~q$i>}8kYIZY-7R|t-+sjjn=Upxc)e6)Kuv?MNeWr(XLUK7DNO9K9Ki( z?EI9YYKm&)7{RWy`Buq@#3)9Dx$H{954~_rI3hq8#SM!LuFMk|LX`S{cxo(ykArRZ zwR7#80PJzS1(JN#+Mtuks@F7|D99Wcko@Gdk?ukQ9ownx2(#0TThOCt>lN>JivT4X zJ;8p=E*q+niK^xANoVk|cUvC$qBFCG!`1}#B~y0H)_LPR&-Th;T->;{;`By(BYC`0 zU}p|L8cT3OxSH`qXW(^L2^I|!`q{OnP`G?)Y$&X3N?2S+O;8)=azlYk5JTj4_4aGYc?F_B%A7%jbO+w4pF_nIS3&o6*=wbr$YUTSkF=*0LPK_&ML z_GU{I7U?Oy?zmKGHB@Q=&6ipe!Xxqb%PuFOz-?;L$o_;JQu3T`bweRQ`OOIjahpA?rh<<MJxo`yQ9 zv(D&#sdUfNpx)nM!n~rh7`#!SZ8|U6II(GF5Bnf*i7QSM$liY%hjFM(fshD$b*aCE z?{@T|dyUJy1Xru66A11LN4`FOlfYdB%1WS#$uSyl1e`|oUDX1_SB=E|FGe zlqNZ)C5_K!;$T#|eQs>g>@|I`LeiyV8e5Sfp54JB%5;=@AeDTo^q>XeJ;~zk4SE|H zRrSRB==trm&Cx4Ia!vn%Vvm;#@kZGKVoepl4xf{KHT4&r$?z02Ib%npzgl|RSox_! zgqqX8Y!l!WCp}etz^TpNRC%UL6~#4D^cnuFnh_aDx!T{aa87==tCgy;m+_c?7XaS*)dYuuBm>0GbO#`LTN>tD`u|c&vOy0Bq zJ}WqEB3v4f-l^UYsutk+94Z;JB5 zYP*td5Is1sG+R#o{Wqj_zxD$0dtd|_!1SK%!w_nrdBfG@GBAL5UwYUZ`mqEKk0LnwWHOl(d3>pzGm1tH949 zOyFQY?rst9`7@xPDM!CZ(M_4rAVvpUH_FIaQK0sh1IGPy@30J1-NAd3dEbsY=#+0x zZS?LPs^azQ+21yx=r7e&E)NAJo}k~ZgyirOFrxn0B--Y}T#cD0h9qqy46+O6EWf>= zB;+;wKsHmV`Sfr4&$5N(Wp)grQ=V~EH06#=sE2^)Y88?1!d^=SEl($$DpOqBpAM_% zmx)dAm#ZOBOJt8_Q&XF{EYY6Av}KjTTDjhy@9osrD!b+M*TLuFiDgX@VdS7VRNtmvQI!woG9#vQiNJ@Ix(@S2K>6J7T`r4ed2iGxSEe)AVQ8=+x z*NXl2EdJ;}(8Zp`iJuxUdmGBBO}B8b+Ac}#Wl%oTxvnpi((}B{trU9~WhB1-xq$wd zCQvk8T?I9ryypoo$Tm&hMz=W_xl87Ac!E~-{mOi5hmNLi`17}ez@aAKP9;VuH+Ms& zpYuCKbdeUsV_D%*HX8bbyP>>)ZPPT!?SsI3Mcn*cm75U~}6&@=sAk4Xd zFwl?`AR812^ahg4VK8hUTN3Cs|C$hRZ}9=}LO@RfV|=MvBp4+>T8fE!;la4~xH|nc z1_e=e{e}O~ad5aO;>O!FbYP~+VzF^Jbt>M5@kUp{RdINfc6Skuwya~g82^<0;#*C) zibLzCXj~U=m&cdY+Rjuvn$}<5klgL)4^0l8Y_Ro89cq&fBlluGl2lL2-y;eYpqI_( z=f9qcOBR3L8Kh0I`FhmBvZGXqCqBpe^^lVy#65vyyBiWevv^j-&m&#~d8i?qAlD~H zCc|^y44#C_MN7UzZUlM+#tH<8!6un!zNIcM1;3NHU#ZKG*z<4M1Hvm`hrJH_R(H}L z^Q_lsr$aIAl|dIqwg#ZP$~>FPLgpi|NuFLR9>%@`o1IOcG-++K(%L6HMvYx9Pf^Oks8-^Qm> zXhSn`&$+281_I{P3aRFbd-xQW)3*0 z(H`XRnvppIpCSf26yU^8F^Waq%VNX_V|@~V5QAP605;`S3AR@M(s`%O39K;q_pYCg zHuc$K+s+x|%>>@-sA`t^o>eU5UYi(G!(^`MQ0E5e4{!!uak(9IVaSYZ#CEFQa*!~e zA(uYPi;iq|eYR4qaEh&2=GS#ZrJX5ED?dS#=1xZfr(S#q*f~LFC1;kD@}+;?U~4B! zN42nlO}s=vb^?>bzgOIf>BF?sWwJbe(UK*(C;mt=B;ti z!(qa-Y~$ea8S2xLv13_j(!qgao!^hlzFwBcxX+e#@%l5fKL0D@`ZNdrA!CrPxo}z} z(&n?dqB(9Qj}Q}skZrFH? zU%?jngo|FRsoPs#%j(WbWqFn=iur6M5XGr2Q8k1HBZ{fA&bO)ncb-juXw z{C(!vSD@9*@#*6v+q$YB%{B|_x5w36Hw*vtq>h(`Ry4Y<-YBo^Im81GEZp2bR<+Sv zCHC8Q`a_%KD19+j&*;xKOkLf(Mx@u(b~h98B`=$FXJ2bqG~Wj6>6_)`cT)$D5hML^ z3g)ys;(G;0gM6fnYFjqT6VKM#PCTP+u}13q@9O#9!K$ZQbXpX@+l|Y|Yd5;~lxq`| zEau0LwVg0G1YQ6eK+M3t3Z`_aA0Cz0)1n+rGw&GN&d6G*yyQ8ej1T4ce?0ONP;c2> zvf7S~M;Fi6roQz|>R_~#;OOaKw)d_X`pQTav+Yakr=L$kn$+a^{&1jz)>e7yV)f%C z5R|`)DDzl=Biz*Nd^lRg-e)8q!J4ZzTCQzBykK70P0z-~sdeh0{MDaKxbq)K3$fe6 zQ`3!4_eb$JkWLpH=~YDM6VJG&5a7uxBjRKhGH;_{v&l!P^9KVC^S$P%UZT z#XnjcfEEV8BcQw(01v!{z{UhnnaV)o7cf7r|| zsZFacUYr6dokjN;_mv?2P)(}3@OY7a)!WNr?r2`|+Vy>D$}cee5DqmDvDhAGRrpqs zDZZwNC+-}CaF7xC(V94~AzcQyqRkIK74qEMorAs`9MrwU+bcg`m13v&Biu0Zyi}^j zaa`BxdIFcZD>F%h)}e+<7uZs!8QvmYrYiasDdHWcNc$|lO`tOtOSEtFVV7c#+k^K>Z{f1qFfR`1r`O7rC zssRG%L#Z(KN^&f`I+aXfSysBO_ybDC&1t{ctCunGN%Q7U;*z+A5r5C1+z~h;UgM3* zbMFg&NMMWMZy8K}&~a~ifSeQ=5hrfkB^yZ^KlRDA*hX??3}Xmp^07`;rk%t1n&&YLxDh%MaiKKFlkJ=>|H zwONmnDl3LGGuQdKF!`TaW?_G}^*CIav$n%c2Xm$a>Pajr$C{HLg{tu)n!U+?YUGw( zmvUBF;nwr!zEiG~V`imPs+_(oF&m^Viyx|sEPBHFwaQwlu&Z+u{6MB`iUT+bhIvT7 zRz)RfE92`?4w(4B$@I(%ESqLO$(5*g#3C*}NA{=PdsXwaJ)fzP7Zo}$`ZPopLCSWB zd>_FLFdzXLl=fmJzxrk$d@CciStPh=oNTQBKM?(HXfSe@GSDR;bqr8Ez92gsEC~88 z^fcyHr{rfz@uM*wJmEtqrxWk#iFA~Ly-&$B>5O8jm?l;NiMqYCJ&&A(8rCbCNratn zu}ww@5~c+HB1Zu_R8pDH_R|Ex`1>I?$?YJVV$OS+u?1S2V}9Etkd&6Qm9O*#&K?0}lDfO4 ztZLnU6_^oMa90NNNw2~W2kv)CplkcJS$HpEBLaAlSq_2~l73LB<(D-?bae+5qK_|# zc*n8VrIf!g*E?T$&yQarn?rDooOscxA=_r{d<#}{%n+-;0yJF(O{04`lS@BKn{0st`dW7oxwcKwheok58{D`Z|FbJF@EMp zr5B7N4SKh(Dq2O+f%8a{=msIJa{={0yuM$1#ZpnD>Ma-1ftB^<{>`ORP;^1xE1$(3 zIokvCEBTtrSJOS8yD04WlFI!^5hV{)-(xm4g(l`qX(pQK)cylaJVVx%yMcI@6j*BL ze{23Z*)i%-a`HV#zTes*2p&hb|Iez!BXGzax5R>Q2^MErb~ycg{2CKr`PdxPo! zJh2NSqi9lYpFxTa87XsU11C;a6cB&TieX3l4``W(zy{Io{Nti)$=jhY(~?r4ph5s6 z^QcdQ%=}R}bDADLf=}sywK1B-b%!JV#H)2%d6s~rJ(xhWZSqL`ZR>@J;bVnz`_GhCB31}>X)D+9J>()ZQ7Mj28kQl4WERT|H2}N3VfW?cob3FkQ-l+7ZrBX`sziUgwIHv@hmADc ziG?kC^^$ghoOF@NUB?P>QDQne0n!CR_Wn-@86Mn-2b+g5r-z;OKM#+o^Y4FH|&#G zJXGFJ3upYxabk?@Swjt@xZN%cI9IFhBY%i)?Q!WPj(?NwvY~>e0fw()Yo1|wCpNo{8r$-66 zaZlJVTbvIDOnv2~!r)mg{uP~34B9)2j}W~bfA-Al8;1g0H0Z-vNQ+#a+Gz^C#o7g| zW_vV;O!|6%AWmA-<;0I)CJ)o4L|8=uX-C!UGlq438RJXLt-qM)rl%Z>OHiD?cZOpT zDUSZ^d~x4>6|3LeJtZBAA3`N7hxG$yHwpq84BSwqEX!6ykLT3F((DBtG_qONTCN70 zO8LT9l|Mg(eFh0|L!ZaMRjOm_a?vL`gA**Ts*znY^mY_VG~uIIE!!Z}f- znXh0Q9BEpexaf9V-LL2hPLqK_y2-n`=VlJU$+`>u!xgJkk10^wZW9n7yx*wW zIypMb$1o-IX10CL_p5J#rOZ|P-n!V%KnhnWQe#sQ4z&$dO4O4+xPwBU?aBzFuwEu3 zRL>MggQt*>giA)5aSLBIC;*b9=S%c(-L&^ooE5w~eQCk*K#q2Q*{@#o=D<0NfQ{5s zd$!nK>OBr2@Dg!K&?Vh;2!dT1AJCWn-`rP4Ne;l#DZoLj{|X~?E9oCe69vV9os@ck zbUeNK#A~b;kXS-JEg6&NUrOe)-=+GutNDI@I$~I>B*HXX94nyEdh#go#SK?qC*JXN z&e^U30b}AYz9nY@2R}5{+GMSgQjs2BZlctzaa#0gOmB_kORY%R=<`0_QAg9)BlENl zqH^YN-8@BI-q`|ae$|_rl`xX5Go65RrfK&`d#kE+ z4h}MRz1Hq&+SRTK3+N2kY%YxmKVI_xH3vS&%*lyM*=+tXW`BCEcb~Np;AtVw=%GWA zDs#j}qAheN8wcw;(SXlt;EMdK_C@`NZt6*3dJ1k8Lw?>H|a4jE+?g}%;~Xn{kSO3nlXt&Rk161AIgb-cA8J$ z)zTZ+EBZF`R=aKAn&t8LRGI-|UF%k-gqrbs14ZYYg4Z|twuOe{Wh%7`G{IL{f66Ze zmS8K->Vr7c?ymYpo@)kHQjzHSoKs0wdkobqw%Qh9I~ZS6^gIhPd}MyH;uL$PnY*6ye>vrHM@hA4>;p-o6+Zol6wX=QL=r?3I6u{ zlIc$dqVR6@0CggfBuC&=@v22VpYFdJvL@B(u<;RU$qS`q%OA6qmd_PM{d8=56o8bt zK&trnD3N)*LLu@2pU426n}{L$#jDsaiLAHybAQ^GH-AMQ%vyyJtMmTCsp(j1x?#kk zwf_$kexaCqLY6m(uAzM+`5$N# zxov$Cj)JD?F_^P!1|#cfp^vVt z=Q-^8QDC!Qm-G3Yx%91Cj!`M0jyI#g>vYYXDXy6qzHJ7S$ORyvKh#M;bQl)<>ROEe z(l*PuX@ke&Nq*Y*X{F+miZ%fEP&`!qi67dx2>Bio6quA>T2ep?l3%*pN*P32h@c2f zjWvu@`TC^b`BTRv%G-kL40BHViJe=`vCv-wEu1)5_rK!d;RrbpD;DIpGByLL4m6{W zt-DeRjDaVk#!Gx5$@(&gy$%bV@nQOc%>BdjLW|5}o7fqJP2FFrQ9p(N@tgq))dz^@ z&XF`k_gJT8Zr5&%Q!iV_IkgFOdULyne-}OA-1q7vOE;SUQ=Ri?kI#z)TC%6>$s>@% zg(m$ocx9(XL(M}^0#bLY?TSS-?Qy0ook~c4Yh=dtXC7GGGil<8&Y_0$jK3SCpO!(d z-7uAO837}#o^ZvPp5sAL$7gFruQ(ObF2wG$t~ao*2=?|dQT$zfwFY#>$FF(9I&M8~ z{r9k?r@ZIU1|FqQgOIvmz*%frf83@%JG;edBQ}4uBFwnEYf_Y3nsMKm#X4Z34{1>Z z=`ba5h#J>hN{izUH&3rv1~`%^S0!aqgD#3K7~jB7y{eg!HUELANf91;cVK=`@fo%w z%HnzcAlF{Tx6!d58KhXZstkWgjHp(%c?su@tG)@|pcLL9HA-CUVYJrO>eb*=t&*P% zU*e_xrply~POv#N;71jdY^t;$Y2-wT~<$aYVP23tZ8afRIsyycZ#;(9BP}vA5`VdWwSzs|} zp|X$^gT{c#2|?;Wzl~blaDwCOtr0&b5nl#0j7s(fZ6kcL21%kkA5ltmSlwg+dWL~t zyazphIqFVO4Rt5}+ZkZaTx&{NH{San6&i;GkX611GT0MqUvEwq((zT;u&wtCtRd&p z%6Eqj=01?`i(cLP=Xu?H-)oMnH;N?dHvjB@|Fs}lU*I`k)0G6vSuBCG%w~{LbmKKW zT|X^N?&cxf2)))Gt5a9Rss_haC@WCQ`|mW>(E|Iy-fB00xK8x%R&1J>yJxzKdg-k( zI<{KrQv1edc>t6dNuJ$q1%!KXXPSpbCd^WP=gMk^Ou+-c-%h#+Jq%k%Ff-8y6|ap+ zdZF&I-29fwEmnFA0sbVJ3@P7{3R%dCPE#MXbHdd+Q|d{NYon{YV{t0K`) z{Xq(|pDzdF+-61vs~ZzT>_mr&@n|MpY9{MPDkN|2ceAbNs(=Okx&v2hS}$*XI785M z=PrNpa6sMXxx3Cefxl%po8QzP&^BXgAdd(8Kp)-Zm!tI#*M}AozBUg#7gcQaPvKM- zBw?3pD%8>al-|j9l0g_q%>LY6_(ws((npWUD5}fpwTPLr0~OkzK!{L%p2#pOa~9V#an}3NQ^YnAT;SqM+Sm*g|75BxO@P#I=&l~T+c&o4 zW!MfXh*~OwY+23{%}dHCR2wrh|4|}Ph|PYL?zsP~*n)=kGTs-0!BwTI@nta~;M1&; zkG?)kw_w`XPJ~J9nb~)WP^VvFBe4D|`;7oRVd|qGNkq;Zq>gec5tj5C`&%5Jeb@Ye zXrft02Y&s!(9^qB3~hzgeUJz&emee7p$Be8G=Cgi4>z)I@>O&bJ>SRf+4deE1=T)$ zk=y1{>dsrH=!iOQ5>2#_R3(KpOIN%8oyHF@uC{NSe#G#jcPS5ft+ah#A*RH`-3_BS zsg7UY8Z?X^$ZMDt)rF0OhLqpXpX9A`J3*e>f6Z3)?}W+qUnNFNA-S<*kgCWirzclG zu8N(BIvM^Ffuxv2)t2SeK%z;>%vt&FnvW2znl<|iUp*t+hV>jj4!Il8;o5%!VkmbX zC5mRpJTA3TU?pNLFqh@aMy;jj#JKE3@gu1cG%+WE0)Pd!Owp3Y1C-WsAP7QL`$S2a za8XfC3Bd~pu8VFw1=)C|pWImHC9tz`y5PcV=XIH~FsA1OO816NYs)Q}_Ezc)2&zlu ztn)S_=S8q)n-2qfzb{~6;XQw#nWJCRcsA_Tw}9JY@7hFHKThz|*1T#X=Aw|b!Nf5x z&bYrl-4d(rR(D^5SBB)pBm7W>VDX?;*O(1NI^aakGSts*W&OGx>`-Mxapfon$M8O_xD^HxBUy09X_j-`-90pXrJP8f5 z$NMPe()?r8tILRSw3J#Y<5LXUsXu`IphaRMu+yik+CkJa>N`7n>#cA8lC~FLwhn?{ z71t(RGL;_AkC2w~hGcG63VF9PtNWs?hR>9;e-_!!hS*^(^okp~>NLVfDE(8%c$n0DT$%^4OQ!Wz2XH8eH0}TyD!sb=a;-fod{fd7P6Xf@7@5sJB zvp>_D_7R^eyEm#6GNYhiJT_LY^_RI({Of+LACXDSq1c*7CHTD#x00xgJ?pB1{{`h% zo-dvREVxFnV?QA}c^_HK{LSYc7vzUOzOND_I)ynnT}^V|XmKuFYBl>>GkzuQ_Dm;& z3B!oO=%ZHy8^_oqw0VVWa$~b(*7-%jLVLu}q1%WVLwbIYf3K0Lf#?xoU{~{3HeCcA zUJ+xVXw*2Nx}9ifmV2*7L1BbZ`UulS0ZwLz3lB9o$Jw%&YfvETow!XxJIL;D<-iZ; z+3;4Y=~)-|>^hs&pzoJ`v_$kUOFZV1qw~T?Q(q|vmpqI9qLSR~t9;gi>@bH_d;a)< zef!F7iy=;+Q#;Ilq~GKgeOI~jxU9zV=|vHC!Zzh7Ysz}1?sBh~KgiHfVt=WFJmDi3 zDXn)y;Bna>&6y*5d={eLMXIN@Umxm#wG}K!z;#Yy&vG-KML=(|GZAmYyOgZM9@P3| zkVdz%OW>;H!+^ohSUIL<7G&ioW%Su>#{04@+R~&n8qD%{9a&J!v}FOE6^IY``&%dY{Tp;vl;FQHg}#Hbq54P)H zfz+FNX><%B1xOtEJp%0>m6$W6`uXZKsOumiL=k-61e`q8#HVZCT0?P2>Oo30H6lNR zS!OGlECm2V(NH4K{4S8-_~duwyO97OYk+%{`BJ!Sj)oO$50klLhYgN*;dCLmhdd3a+!nGt$L{wnbo!Ctoy6zMs(l9bLT-&-wXb zx!cB8+?#Qwi8?A9=FR`qU}GYjk=M#dR50T%D^QfQ6|VXr9!ssh z0LF@Qok6DLNWX1N*MeQHLGT|_zq!+=_lMiK4@#NMygEWn4ULVS(XGs+pq(Azlg}5m zL`;wnz79T)(uumn7b^ife;u;FNsCDAH&1etE6##7!NmR!qO~w8ZG>YRR~jFP27hW{ zoOp5?Ar~ovg|6y;TJmV_)!1i1P->G(%_)45ThmJBr}^b&Octg;$4fRU*`_NLnzd## zgssDXklhp4Sy>uSf{mIMCzNiVLKs+igx8HWos$_$tHL^On*~brTG^^S=}h0nW**uV z10((N!J?jJ9r~{N27G)hBZJWFbeYEFFQKPp&wMO#aS0InA8TYHp|-la;`CybCQh3@%1Z!OMXdDYRFOM1Nmsk>L1F}}6niCeDuJig zjrNvR&1RSZu?#q~TK;qQSEYN*5|!U})JH{XjEMmU!t|iANhl3@b>o*WXp`hk&lV z<-4SF8?shU*@ukVhX!3ao{FYPsOb^wkl}{!8?}>J zZ}KpHB*r!pP{AsB;7mM2xRG#5Wgpl_%hToFh0`~Gz6>WyvaXpU#KZy6~i zn|6q0c1>s}NS6}Cv@ts+&kv^YfA%UNL5aTA7T2Y!FuHKJHVVH?hwafkn9P!`V z<0ZVZ0&tS&?JkFHS%k+oN)S`#ui(>o zWk;9o26n}@BYPK6L8qlWwlW*885@jHOC`>(7l6HMDYJqYU*QVP%eMjz$47~y?VCFyQsw`f##v0iU~TT;CNZ4J1y?;GGjwi=Ay!Q zR3evicjy)lwR_K=$S#?3j>5wRr{w+9uAu%`bhLmY(<^WjY68nJO~8f)Ltd#0*K~Sx zK>KQriV`8$v zN_&Ufq%gsnoYa6D`k|)XrGX_|%*Z{8r%HzNSr?^T<}hj|7m*@4Qk%*}YPD5Xn%kL1 z3nqQ7&GmXuIW|OotMUX^%^n`C%0u}6mY1>X@;-GXxGTIVtmp<_yZ7) zx0=A}Fbnaf4&&W0_!lc&H%1GABTpo(V?K2TP54%-%c;td%UeB{sZCAr~0{jj=FpYLqbcg&6Fnj zUzI+MHzB4zXL=yhnoJtUu^1)zQB2wg^ZJq-p?*=yIJD`;E@|)QR;5hiu9ij~xrzWq zK)%O5FZ@BfgHZ{DOG4R(3jTeQ6}!;6TWMyJT8g1aP>Ks%R|b)25bZ+31PLJI0MW83 zD9ZpUsOd~pAiL@WRxUGTcYNzg3jr*lNKqfRrpkw>k3>0f^l8W>KK%>en50dzg@7fG$O7awz?ceui+BGNwQ~{@DD}|p zd+B>s_5JtKiax>;H+Dc_k4++&{>|I#(zX>jP5o7!VHR+rYRB0z!I>=PzMzOL>m=18tdgJjf;!-@6>7$tzt9 zV8jyGK)+QG&TwygkXZ_Gin(QaJkBr802pU z*jJ4Bl@!*ciAQl45~xHcFjNrAY@o0JNAy}c4b%hDsR|9vCIV;lf&`|}`HUPP{CXG{ zMYUJJR=>Tb?|qE9Cxh43t)9#3>Ks&u=f_&@>k6-D?1b=mjfZ;XaIHe{7tu*+V(>pz zvx@Y;PY57?P)(CVuy_gUK0^AtXLC(=^qVtipQ+5@)`RLri2QW4cRZlP4&gnRm^i<)D zeiyo*9tdkW)y&~$j3d!j;)u$agYt*;ByDWu7*&#e&u~XH(zY&Z)F{xkm)#k2)qbLN z9X0EEulPZSXRU>n#r`IA@m7yA8MamptEFU_SI2UNUOcifu^!vVy6>x)Pox?6$%un$ zhBk6X)Ch33oDGz|?{}ZByZJP$*mZ^!haMK5UCVAx#VjH6Be)(221dV=C{#8T()0q?(Qo|;Oq#zYd<;5@ia&XASA6R)Qzlpll?8wI zxT2WML&)N~nMY`MO4fVhCn~NMIproQC%WH~BeeW9b_`pH2HD9no!S_8^ z{t+l+{6(1L%8>}g&=+~B_FX;43(_ZdTx;a;lnn$Tq>FiP!r5iYsE`LX#~g3k`qvxXhd4MbOzm-bd#msq2u2t$0d z4%hJ#gserX^^NnHGpaXRg{sPd@F0JhN;6*8yxmkdflu2m1c&<;WA#ETVkS1%%!ueisK(Uj2k`J*x`*%lA2GB;d3n?B&aVhzgAYrN|6$EB5n76Da+p*-tb@W> z$kTYRefXVTI#G&j9dZ4R8Pj)DDYr^>KQY+oN zYeMuL+d_|#`CJu4Kl?O_9Jn?318mIVR>?ah9Hzxt>^__uY?#ZAd1u{v{gwLStCwye zaGCGyhzd`V{w}lhpnLSB?`uyYLl+7kbb$Rq8BZ*0rnoR-QjToG9Z%)o-VhiRVZY*H zu?MjN5?%@jFnt*LA{Zz-NG~G%qY}epF5KyU|4qcT3w-Wv@k>;mj0(`PG4j$7=C8Pb zQmmu`5a$!n=zp3tIS|)td!Q@Y<)sDThg-yuYC{!;*ieu09=V%n#E9eKv_5274?CBz z-p$`wUpfYg9@N6&&`_Nyc#iNM`Lp>YY6-ocs~P^YjMYsNk4s)6E=O(}+{tMJwC{WU zNlJIgsd}43Zf8XRQIU_wE!|A#UJiZ(ze@f)$lKGG>09qm680%kHJ#N_uP5J(QZ-2E z;~-ZU_()qum2S7{k3YUzb0EA)<8TRWdn*}OX{{(g?H&bbrl9qH(|xN8IzAjU`4B#% zlO0}aI_S>3?8=7kOE5vw6~%qb8%!EQuQ*UV>JKbZii`KGlqTqzjmdf;DXy@=@xS~Qdij5+y^HOpI;cwV1hLg+F2Ox1%cbM@8&Q?;blU+%CUyf7rpgg>K2%_)5H}wvGO67M>Ge zSa6#a$lgfN?M$pNOYVG?H8~P8@@EAbtJ3e>4EN78%ge5(feWCS`Fp9{HA|wwDenYA{f2dwQpyd-TMp#bG29d$1 zPSpC_S!qH?K_YM}BVOPGhXnu>aYXV$T%|?8Ag_EdiMmu_a7*Z z_3JZVw)l%o$dX%b|Sx4OOppJn>9`*-RM>swu?+_g|t?`#8)*7r3GYG%NH&1ycs zizI%5yBr17{+R0s+{on9e3{P&AbKy}>*@EnS78=_7eM-N{=0#|Fo8B%k=?og%+v|P z&wD}i9p57b7)cw;o}E|O-Z=$o-DnCd22Y-x=k0KgMaq+$1Yc9RG4~PDx=F}XdEdde z@3zk%`R|$@PVPr3WNbX1KKwb?^p_JFzM}tP5gXuiKa~y$0)ez8oAH$8nrl+E_bfFP zGjlR`LsBpF7-v5$9=imj1l5F43**kC)u?K-2)E~MsB}9Tlk;D1$8SR|m`q9;;K2H8 zsk60?x90s_QR$ot*Y}J9m(E$Pnew+iL9WVO?2`yh)?S9EDNwBhaPmTs_|+P7e&&Y* z&27*(kUw0X67y(K0@$`jaX&0qFAd?b7Taxqt@yjf8tpB>$M)oxD%l&hjj4+9pC48> zf}280NCM%-RP{6HQWmC}pVQ->v@Im5l3MZajO3V93g_!bS{IK>2bpt9f3Xi($p+zY z7|u94ikI|{b+fEAwMNm8`~Sq1AQIkVd%Eo%;I4v*eePX+G_a1$ld}p&*uO;!OOzSp zzN%f8U>^hR@G8~hc7k%@>+O_l$s+mU(|l{u((whsf*+YemN~n z=p=CMzA=LjmwWEwk3}TZ&HkM-zWD(3h`ws*H z=lnDZyuaxN&<%)hNd8{T8qm~1zlvSpaWIs?!2JyaM zP{npp@wx7&nBSR(3$xJr*CGIBMAub%IQkrHpwIP1rWN0LG3&f+9&8cVE*An6Lx+^B z0wF%S3zFe|mDH=eAFdC6Icty(E8y3U(1~Z)+CeONy!UML+|(IYkW7ie(nrwjM4?S6 zSLKggQb6qG_8nqA^P_l~eigI8lzZo*^WS^nM69w#(YYp#SCN-EMej(|;Su-pY^PtF z<%EM3$}x-@SO{_KQ)e>kPS-@nltjwCA_(g$Es$8px{+h-7*}Q1C<0}lQaKsQbuzwe z5nyJ(TJ#6j%~B5%L-P5dOSn28A>A2b-v3l+@I~QF)@7&kw>CzLya$G6RONz=V24kf z{gd*z+j2qQHwF3RahrRe%iQ})BKQsX9h}x5BRc-7L6fzzRYMNrrR`b>_{;d;e(?%@ zn8LW#;oD0)2^`h|LfT>yO+Kq0&cyO&ttV?_d@Pm~Y{^=8_g82CydNK*sNeK@eP$l? z$4@xAwmRA}a`^Uu8*6~P^Ok+b7E6*Eh1G^cOW?DeKh{d6#%$+jGG%-|`_l21w+&J) zF~0`%JD-&{`^{2 zj;O1mkb&bWN$wF;q(>oLSkXf;a0rSv+I6g~N5;RY2)wjkXNp`yy=PcG(MfvoZPM}K zwOKVq8gHW%oH2d^2=nwpQuGk97~+S#V|RR?*w6UqKM>(u@DrHUf*@gx3@$@x2uV$T zD*pEL;LCxsogb;;zMCr|}3 z`OZ)TsL{`6Lh$$5i{o8g4(Q5-t!aFSV!y;*>Ij|ormyVO;zIBfT?xIwZ?JTJkDru` zr{(owYd=4><7;J6FhHFK$gBDjmnA306n@#~iuY-xc$EJ?n!W-ks>l0&X+%O~QM$V% z7Nk>RX_k}{>6VZdSU^zMr9*OAx=TV*LAqf{N$HXfCBOg2=QsZumYsRPEb!jDd(XM& zo+DW%82^-ts?aHgEch*$EXk{PE-%NI-(;TF%%~+^dsPfAH&W%8(o!isZN5+4e_k*x z_F`-vptsa+c@-y~G@A{FW#waIF^U)*3X7@<8S(bl{;|8!$&AQ5phZp z5T4>JJr7)Wc2D25cT1h1&A@(CeG1bv0$r=*m1to#RsS=E5R4Ct!82-097M*q(`!4w ztW03%>m`z$;V*NMa}178U3@NfyuFvZT|Mun$4r~g+CsCfH{C0}W$Q`=R7cay-0}a|gnQ-> z;3M;ZHUbN+>%;}hFUW^rtu!PAc$N9$8kcVS$p(j?P9RRWMo0n~-wT{Frs(M1lm?Q} zr>A=qk4=Wh13Xavf5K$oNAv0hAIF^C^W66jzXCLn#r_|#Ap)t;hEXc?^xEyu)j1ce z2k3Sd7rq|{Ih#)^Gy)QKvSI2%`>b@3uamdtFg2QB6FKn^W*_%BYO~rW^?+@v93!FL z^GBEN~zbOTloQdE34|HotS+&g26G!vjYO-JVpufc6So1;L@2Rk1C7KjzLwLV?%V$yo z{aY?VaQdkp`&>|ou#;1`l3cXhX% z<>sHKpQwXzaP-`KKceHBNw#GvyO9rQR_y`Ix$E?Nthh1<@^zF~L!`FF>tzhIxZ%9S zvzs<>GW}8M#065nVXYn?&N}BfKUdJ>guPY)deM)FOhhHSeW9ebye-KQF5~d-R@{pr zvEV8&V~aQ|ruNo)G~h}&EdP5ey}5sc=K%!)eu*#}0*SS+Y1^xwm6G0{ZkrVfuW0RR z`9fC$qPcM6*xNUK=dNw?u4tEc@H@S{+}A3qzZs0^D&?b#7y4Cs*mBSA>K%gBx844O z)w-l;A_c&V+B%a9I|-lySm}t2#3`wPx3kAEBw+>D28D9nw3f-YxI7|I@)sAIHt!ID z{+h@jYPkZR$MD(L<}-*yF(F2%T!H5IC*=R)H)s}c7gbc$Ubj=W<<9aae~O<{YFyAk z7d51RdoI-Se4tH5a`LM6=Zy9{tiCxshoF2X_L32a=jj;|a@^vK>f_TH{Sz!m;>Yr` zYxpJGV`-e`i8Frn(A7_bDTH4I(dn#Zbag7iztex%5C(WHK20A|N?C2F=tIoHg;4b{ z<_7`Xaqp>#NMNjvC9~^^x)N*{HELSA^eSdiDUSeL!webGDwP#D))q%GaTFaWJW=bT=$6SEyrGVb6R|!hSVB z{!;}&HUD#eL+-*ArWP)juDV4e*OQJwaKOC$q@G2|K4pux-ccbS$62_#V;tSFEa!P> z=2*TDTcUgjcBV84G&sYsz#4TOAxVT>xk+PK3VDzuP+Q4=9u4=jnKx7(>%Q!?AH7a? z-jNpaSzj#Xq-L5CUn4QD`-L=CYd_9300$A*YD@Sh5<|eZTX7 zeLuXwz{WLkA;8EK{NDq>;oOe@RX0=MOc&cR{RK>ggbQ8?C>9ktJBs?A(C;(`ue@A| z;)xey8x~m6dxI9mVP8xa(L2oNmw)_Z7&IA>2Z1O0k{C=yxf*^juyan%U`cx`J^0{D zNe9G-vhKN6#?U8P83US3H6fE`t-cJ+u+x4d&N-bS5E`{q`unrJx)Qsg@PuX(@wZLb zo6;qRHqNv|`6sOdz~NJw9qG|P(6>#!O+z`6rC3Pd7~T)z#Gz7@<9YsRB(^{R>I`M4 ze_DLnwvD~{uFG?0SQx9pJZOS{eZlMpCB*5A5qRt~!fUons8X$ToGhCYU6P-w(&ph5 zW^EQ3rbe0Q?SE3!znYtFAK!eeo30hjWDVVn8*?IIjsz#wf$nF^U~7clG+crV9CEET zX^vV5#vwbZ5*TH2h)Ju0%{Vz_@%FAXX`A&97X&ThzQvn{eu=TNws5yfq8Bx2&-Er=v$a2_lrUh~QhaV9C^ zgmmO`9L6M5U?HcXa4(88ZR%m{apcI!$6OL+Y~B+HghDrAiheHy;=@YnMCz#-75J=k z_Bcm-c`5aOplz0xMdEk0*%$CzUgQyy=tQsf)H9+8VambvWn%$ICUimBXo>x$7eD!MQY50+{vL6UF zZ4#@Bt2;GTWgqZ|7|SDwZknS_B6*s8HX`1*lHJ8AUs27LT}^f>rgOB3FOb6I#e7Lg z&O8Wfe$1zQl%i+2xOffAr3mAu>Dyhij6@W^t#6!?{uT1(LPx#0MMy(GM$J^rV!(Jp zG-zl5&RgDkv}X<Q>aWu;bfqIVQpQHp(w-h#` z*9yPI#~yr_;WsAz9)EmKbkq+8>|axmbgh#k)^jidZz|vGvC{X_hHw4QsW5m;AyPNY zvt=^LQrDn3^5^Mn(0w04@-J|{v)SCYy7UX{+p3tCZ6V1@9ZM9SJE!fTl%^+or{65{ zuJf*D^r5?5vqS)M&io$~D**0tz?}sIjIcJpK;Zu!%SBj$ll0^n9xn@Traa+kk3nOS zgj(YnO4W)dqRPh|3jZ1X(Qww60kJgON*km8sqYOo8gfQ-2VygD*RZ@+#!iA!CDr}c zU})k3{RWUGtv3z8zFZ(z8g`Knt^@tw2+a|V3o!2{f8(j_`mT}w73txdlqe4UnQ6FV z_u`?(_ncH|VX%h+cvLL)Gv2>^GF@ur=fj(Dz5{T}Zc&D6x+C^Xnzk`%c~N7xzOZhs zn==UV;KH;YOAaC;{QJs*^>X@0w)t=?O68jmqk`n8r@P{!?-t?$C)izGg7cO#E@A@* zPUjLw-k1`Je#gi-{cvKaPu~1iK|4Ffn;z;!(8dTHNc&O*pEMD$yjIJ9u2|wKTh}79 zGb>>F-101HdlHMFf=jsw*o2yUkhhOJLHQ)B-m$vUye9Pv)0I&xfA{P8xJn_jCtJMo zPnA}*3{fyM>VgDq5@VZ0B^rtfcJBOqK}ZxJG{^_49+CDLz;)|?(1)r^rh_)>-}C1< z^X|NPb{Fo__s!dKJe1*@cAc@C?(^lk@n^xyXhj}2M8Iage)kI!jb3Lv{8fMKLWIok z1bKzaZ0AUPld19>G%2XW=0%O#xVZmAR#Ie9{J*J^oGAvp=5(pNhc~&#Ds!`csE+jp znZGu?_!t@AvqS%&pIG*AfuwX#Nqx`hLe2EljU~xSza+hsNYwJ z(<&Yv(%llL;yfym)D3!S7oNC=Voc^iy`(t$$%T63Is!2bhH92e>>HUHG(OmPkkdkZq=B*;woMCEkX+Dk3fzEcb?l*&Ls?4w{svU2O*2TXoYDCwx8rSfe zt3egWySz!s$Z$r~+@g-Sti@R&qE?#454m=_9TsbxM9fHK^H?Ku+9*1l8=U#2W;$IBYZxq@i%lJH zTLLA)RujU)^6J65*f1JXbr2puXW+dn20(p3h4|$|!r@Qi07@r-@l(Z=$up;V^C%+5Ws0Be@y{5!k2sc6 zt{dz|1UXf@N4I_HUBoB#CE5CKX?%pVq+wjZUe6fzy;^}ezX)cXN|Jj&y92g;uo2w% zR1(0=tKU!3fnGxwkN29{E91)t%c!P)Xykx6Q%p|_QJG&+hwqP8&G@mHI=mR&k-Rp@ z0$Q{UP+;#@1~{-zi1KV3v6fPtL-1l;&5Htq%wJG2e|n=}!LuU<#ZZy(^R2`A|_-i;wzcC*xRzZhc2(4%z6YQ+#+FPOCfU3hX33ie%D|4)8ndjQq zUa^J~R6~Bhzo;O`zA^~MI|Do*AS%7};xCqx^O+fvxxO(Zne*A@yB4tl_EfivVymFC zOqf!a|6lZjUthWN$8;cbRAa!T6GrtPEv5|U;<&m601QxIS%)Q$CQeg1tm8fylGC?j zxg_oUQ4sXG>W~BHdh2rLLw{GL%~wT3 z`%gSZzP(<~4~%Qj=%+bi#zrpSy{~UC{kE{aG)Q3!Ek~rksIRNT`}@U9TtYv#o#JM< z;V05CsZxqYH=3E~4E$M7PB{9*c%7^a}m7q zL`uqFVmJIGj5YjmCU@N~$Q%P`6msG0A8&qE{4MniUNOcq(9EYQ4MZiol$nawW89Vc zSWB~YowsxAYMx48)>-IxCVWAP0+A6+mq~%E+3X9(WzA2CgQ^tehz>uVm(RD6X}4J) zVwZpTHxYHyt;(|PTx!0)pD}1PyJNK3Oxyy+PK1p=tJ?^u$Xt-m<13f-VVwS&)A*E% z-BZzbENC}+UaeEILBve>MHT*HUXgm&#IGz>kel?30&SU!&$={}B#^ zPTX3|Xx!Wg`Fw1KsHQ#isK@0WmmK$~nm38A8Sv7W@OZU$HC&&firTdTSqZ{DeZKEg zer%uIXxr2qe3()L_1`Z|!k_$7RIicJJgQ|&D|2$IkAR45xf$%^Y zu)v&@(yg@W^pA4UOTmuB!H(Di$t5_&rJvJ7AziY5Mw*5&&pLyzICWEA58}1g+NFIV zSkFz(b@LFW$|T)XMS2L3J6E?jphhRj&AR`b2mYgnz!giCboJ;jY=sM$5fOC{wKf{WBxU+Vb`s}2#R)=x>(JjxDHNJ5b z?smhE?%dpfPdVBeW}SslKKvE8^qx zewh%^u*}zN=gn$G;ky*n_I0xrwdxl`PjOEpnwas4+saq z#Oms%_mz|m=u4^5z$jRm9@xkSFe#or$Q#o--!o=?>5l!|0e2=(Kn~IL{()*B@TLfi zsA)hX%wRn=Twrz$a-kzC39vrMnTT`lYUO7c+68uaM&+G^yE>gI(^`aaH5u)?T?TCxgVLRF~X#RUbQ zTJC$vVRWu@TjjcTZH{GgrD#9A8UA!v|IjNwyR~Nhj0%jNE zajtG$&CjRKK_V{L};d{w3BxmC&)SviUq>B1Uv#nU(`;Yy*;^+vd%+)(^=;&tD&likUJd;<=K3D z-V^B%GgfsM&Rbl!Is)YBYWAKK$E@0(!HCSK;51GJ#q04bFpMOce&KgW9dR%#%}`<& z4TSTt^E8*LeUrkii`ZW8cdB~vU~Bw0Y7ugG;Uq%z{Le+ZhmZ9;g|=M33I7k>c{d z)$OowV>vz*I$r+F?#;zdrklTv8ydP}XPV>bCuy>RKW@H`gZ{bzyL4=&up6^!HiG_| zn%Kp^O@J3hB+chEhGE*s^&`-*zwHwHB<#*F{A!a4^8}0C3dA`(<#PB@mT8hHf%=(| zxGk)JMOj<6E!1?2q<>q>K>tPm!v6k^TjkGA_cDoIaqrfUrV9TM4woF2t#65Yj~E9j zH^;ujAxUMlEI%QGwG8`ecEv)$0yTGuMM_+U8%_FGo8S0DSe?A9UshCFahCl28r!#Z zRz)4N4l*mm)1beqwmMM2i7v~`R>$sb>0WIka(}9aWW4BjwTb7X6yWC7f<{rRma37R zRH5+3apSZ}Ok!cFk2@|h0h=$zSX22x(Y_~lT$4FCAFy?XLeEPjIA-%GBUc80xmV@~ zSY#oCP1f&x$`$*XI1B8T3I`3uwFd@vXYC{?r?vxQ=Pah08y95T_TsEQO0ZPy&}16T z9A&i&?B}CWrF9FeoVS7%zz!a`j}$f&is6tX0Ljq+4s^iV9zfQk$D#5+|F0%Fk$}KS zZCv;FzmPm2$OhcYGRcSaCs|(dTd4IhP2M>`kkZ|As-~+ov;OA`vdTB(zPPJpvB_n* z$36*jukwopV=R_KjG)`joLAxvz;k38Qe1M zS!+fVstXW#6p|(#tDy^k0K$7?rh6V-;=!3bRvf{8V1q>n<9jFY!M9h_$d#iYfPhst<(F zXvEuljS_beU*O{0^p{Q=OC??BW~pU+=-0q>Q}e)$0Pk@BRDi}`MZ#8*y3F?l1^9)* zxd>BGUO+csP5L%e#FBpv_u*>B!f^^?G3CA=@`qFO!*?4G@yR+<;<^cXep?U*FRJ}f0qyO)%TcoH%74S*wyb!?xroV#hq2J)^ZzIU$7s<`|7 z)0R>?1$=`H2RhTJ_9h(=)kOu450?oPV$aH2!llajaTDRp*3 zlLd@q-@^2J)jd@CKq_n(*g)LZ``rOq{u?Qxt0$S+WBfvQ%uC2i8Y5K1ZN0tR)uX)R z4|Pf@KX+musfGT=FYnG<{-I$kab={rBy~(&#O+Otb6ukd4?#~s-x;n_M==^U>fLob z{2vG%rpnZoGv2>aVXdoZwm<4Cp8tw)`9)4qbGWn*-&*VtVr{c+Qb1(umH7af?x{$q zh~XTEO+VZ96j!eKyj1p|ERH9D;AZAeQcUSrZq_5*sQ~7qQlV!RwdB88ZEjK;$MKL21lX|Qm@D)+O-|a%MS{r`Y&`a!wl5b)1iU0X5nrWw{%w0K7 zJ@^?V70TM}zVn0JN1UyDm3=7q&Z6QUdGC&SOzD#0UWrV=u(4UB`~we};WzYpiM|eB zcTke!=M-O|G?-ThBZ5WSi*nM&s&t=t@KubI#*@}*E{~s)hY_Hr{B)+D@zMGuPsVvC zP&UfxjZJKj+AMMN4xRlE^s)K9(6f2|l}7V@fr^?R#r*c zSI^ar90lG&D4?Ang+7^X?tG#9f=Z=#FYm1bikSj{EY$TCcA)a%_w_Z>x_z@itz!p9 z*uM{BBbjT0NgjCKiB5DizfM*i`QQ`KwBc>}tK4aG_vedt3CrX)W21dHAO033)hwd% zLO9#Ax=DourBJ1Lv^bh&U8=1TQv?tK&0ls%2CoYICwod_sMjb=~)^)^+#w6oA(H8JIOjok? zC4%!|2w(1x$N~tu1YXb$GIG4-5pFEA)u&c1z~Nm*q~#S-9joDQ!o3Yd`E7JCUv7mr z^gi|}oC@9Gd0oZEs?2D~5>vD%SmrI`#7?JcMfgfV+0^t%pz zI9oh~O|Z#TJQF-ojezj$_p^GbmcOTO1T0m1@nUhdC5eU{F2gvf8Ixh3=z8vo*7!}Y zxg1VdM;GDX(Y2ZLN^598Ctug~#HN>uNVi^mFM(X7Zk6Y#5G&K)%H@@|fx{p0?2L8K z!@ps7$sHn<6CKi?5r~k)O7m^W^d+;EMxO0upUHEA6S}buMwKqF@cb(74{O9i?KnG+ z10ueTh}{KwUl~xmb7*4w_}0;Qtaal@0wP*VAaI{@W#-k>cS_CZ_Z8W~(pwf9ss?`s7pgNL9DCjIod6W$in)qjDy|J!DLRK7msL zcrDLYGQY3JBM|R$yyx9zpKS|eD!Bzc`#yUvEti{0Ca!QZ-@* zY=hwAMMZla$C||d82{tC`syO0>E=W(*?!?2>{#>n`(^|k;BPLje_1Wsy_$spQUZXK zib{)x+gvx;e&L+4M^Ys?PK~MuUw&<_b`u3G(0W1=zWvP_WE`3Rzulq~|K?Q?p&}1> zYJbiil*s+r^y-be7rG>UvD0lJahJ~Kv;?oNMYSKb%#EM=D8QzY+ZQ=mL0sya-0@dD zZ@?=bE-o&Oz*VhtfE*>Wn5ijnTJ>HlX44V>k$+2Yn}+~>w%VG@tf`WaY3w!);)o1! zVr8Y4(sl+l6df*n%~oItt$6y7#1Kbjr(Hl&|H2dtpkgQ(^W{VTOfGbpV70~?wdbx? zPt-Z!r?!)Nr#G^M8H-=WY9<;MSV>~V7Vt(QMmt8hn=VQ$?dQNCg6d-ELNIq^6m%Bh z?w`}fwJ%Qq{&T7|Ocw$H{rPPjM==aRIrSERM89ei1lAKXgA?n%wJ9(PBY~k5TPP9o zdJI4MdxoEPRKy?^UbQ(f*5vp_(B=r^v#dr~7iz(C*sd-ir_WwDa9@0wbI$H1ZdgWO zX2gz~eOpg#as;#$+jgjOlYLlv zeED2dum;LHB|wf5J6-y|B@h=`vw0>dRH1s}jm$2yaTGV;+k7<%9o$jD-_>JxGOlqy}9Ug^oQe zG+x6!1VdSsyKSBg|8d%3ZQeTo&RzU z$~E$k>r!@@)}EYdr9a>^awM2I_erSq?!iydgDWY z%p~^tTPa5ME}4iBWcHHYMHO6SQ4n6F(DkVg&+K~$3 z4&t52vjrc#&{hK08>b3}%{f|5v;NDiCuyu;=Hm!fx-pt#$~Q?M6>l>X)r{S^4@vho(?0oR0?*l4PuSRmOh`gr zlz*iaG{@t(k+@t65jUB_oSOpJH-hg)kicSIA)qp!2DU>Vr~zF)jxGynGVu&Id9S|u zkbI9ba!vYgrKL@2*QhUpNZ531Mz_bM>4Z8sGO=p9O;M=PYKCzwh;NRs7(|}clWA8X zY)VJI^1Z$)XCd`j(t3;w^QEqH(93r~unLK5TKpfQ1GZ=?x^??<9Fr^hc2tMNI5#j&Yl4aH~q)?L|q7y z^uf(8)K<46cE^w{NrWMLMV`z-N;{M&+?>vf3=^M~0T)qYPL9&xiM@zsqFV6?4l*EZ ziFx!y7H(hlFvvs6-6`?7<4AI(gCy zw(GZ*sApv6QcQqvK%9E17?@E%cHPCOv-9eOkQV>hFazO(rl)jQ8%;O=4l&6CH66V! zo6xV~X|qSz;ad1pDhgDr^}eRrANiU6^))^Z3gYWXg_5>?1@*2Wt{x|acGeh2tklBlB2?Xn0uTgt#u9c2 zc<}BimVj-s)GNL4aGrXCS9nR^PncL?h(OgCsTWw*o|v3Y`|xD}ZX26DwFi{5q;)8p zC%@B;BuuRhVcYTQ(MFjOnLRXpV4Eune=4$nO}awK+`=O|;N}vk$ze(%+D)WZX~3B z$hXAJ-E!KK&jFWlBpIHfY%6YOcTP|&ioaTfTobL4oAnW=@&DWzl$}l&9ewaXf^(iS zk?jqwo5w&fwWmB$t#E^3hHOvO%iTk|N`c7*Wv0$Dx^I&dW77^w({bZgqE-C4(N9(h zjG~lI%7Qm8#HlLypX!7wP!4K+z+Dlu`CV@eOsJM>SZt z));=9;iz<5Z;aVQ>;FK@tPijBQKx#1$_N*L{hMP&y6VbCAkt}HL}H5sy!Rq7H;A8? zju8|(G*c0J;oYD+_1sQq0-)3&oYx_@YKX@+i zoX8dJSu#VeAJO?7?r9XK6}c~q%Rk^m64k7K@Sx0i)B6}Jkhn;_QWwtCMk=O;rj{ne^vFjp7`O+>}L| zPp?nbuA8eaMj`RhP03fMamwFTGtuWxRdpkGcC)qgi>+wTtf-P{t=X{b3tYiD=cJTG zRqpwT8t|`5hbWfv2UNLJd9^=^Uy6({h()8sR+8eBMM=r%OAm^LiU($U?wrGqrgoK= zxNB3?ht3!Y7Y}0xIqQ9PU50K%{MHvEIUB3gksAty{V#qd=^JGNunB-G|Er)wRKc^Mjd^3YxIuB&oUDOXB z8N$j9uGVQ9cQs?3u;a4~9*>|&^D~VRX8)?X(o?7%PF6=A{$4xUO0S!l(JruWN_b`d z&GfsGMslpe)VtR;It%^P)f3=HL?kZ>5f9#QWbog)Da({~x zC}q6M93{#uX09Q31fk9@Vv@(2i=zd2e%ylyTLi{;F+FmVNK0|Fz6O)b3%sg8? zL)|B8aqy7ghdD;j)hhajX~MKh!SA>@L1YQ$+5L4H~ z^cFWZ5Ov4pR%GU%sn(8f&!0e6R8(Nh)`XKX`dagK<6F+~K>oL;hDZ)(h;V6t^}(sh zwXJtd`x-$d?{oF~>>vxQ2C7&#Y_&V$1!RLvvg!ru9R^1t+DNZB}pQUr|YrDz7|+xE{@_{7@j0 zL1Hy0L4m3dcdO9J3p+E@y0rGGwGNXmwvYf+#;Hw8zjjAqPcxn?7l}*_;q0TTrYFAfXTuk98K2UbzLIi2NbOhMX{zUVXb7}j)VRo%Mx zA15quD%$p!F~PTb(Jv_Ou!c-T$cB~p)fldSM>qJ74dgwrv&x1{z=tX5$En(w>h(1v zn)~E4$>IbiNy0|Fmk~oOVe%AET2haB9WNdcBduRzKgFUSKEvu;C%fM_#`jJL9K#VB z4h-!y(F_#Jkzn+P%K#0>-c0JuSAPNa&mC&Ba~4q9oAjRAuL9{Uj0{z>@x|0Da|7~^ zUo4b=KD-lM`1eL{>_&xX&YVBL^KgD}lJNqt0T~fxK4}QFI*~jpwIq-4$@7eOPk!P# zYC0m~sWOnBE;B8I@4qf#5w{!t9o8H<>TA!RONKvU_$$-OpTqvkt>w5OCzSY^h#{d(QIr^!7`Jd)HWhqT)m~Oc<*&^sj z*<-<1qq`+ zozvl_jCfyFBZ=gefb_k1<$9vTMq&mY!cFZW>JrUVcS1RJ+nDI2C&VJ#PJ2=+*U1AE zzestABVv*&70k~s&~~Zk4_2*z!k~LSUOeMdg~@;W!EPsE1Ejp{;4|Ks%VFv7Pgyh1 zH$P)-OEN~soASE+{>dcvfz^{C?GUlQfAG5bqsAMae%iMHU%%op&@wCTy2j-_HeC_Z zdZl09@I{z_b4%sb7pn77xnzx4>!cP`4>xbpn6#ZsF?4-Vn>G39k?=nC*|1Nxx={^u zL7l4rsE0sBr+^eD#Es!*$kP!;>Gq<_)CF57sFRF&CF9NhZ1fIE6gx~{l$lm5>XyRO zHX|8DuuQb`t?TW$YDZcP3uuifO4h_#>B~|>dfGU|(4t zRe3IPGvD&z-5GT|qr#Y>sG^xfuT1mwcyzsRQYFXDZ?4}Spu(p1(W+O@N!^Ru&KwQG zH#t8~hhL^H{vvoIo^L;jDI0bPaMdUpN&B61muw*rwOSG9-6x|AGV^6cy!Pv*#!k<# z4Vy%v&h3`C+`QCImHg!121{XRUSJEhr%~$#uAk_P>Ekwd^mM~i)537XX>}@$oT#&X zO>h<_VUG#fA`eIP|G~IfR1!m%IAw30DATGxqPJoKLsvU+?YT^+iz70O9UhPq?1bP?DY<;=m|;j@w|Xo>`lFyig)vh_DaBvxYEQjiVbA z@*jo36BgbUS&_?Q$B|rN?jY6~3!8A_ph<6r@ccbJtxl|ctp{=Grb;T#AF(uI&cagw zRD55?ttWyo7|$gjG1eL(rHh4$+|y8ufuad)cC>bOv_~OX02*b*#8DQ=I0*{Lld^}> zC`)6o)VZ*N17{lk1rvu5*Ad+L7wrxEr*r!n(vR>io}DSIq~f|#<2nkq73+Mp3HZ8@TX;8h9_y9SEd{;_J;$sCjkSQyW_Ni1BSuGs-fN|?8P=5O2J$F^ zI8~O?^*Re9&Ii8;hA@zocgNw57HACGzsuF(h3`H0VPznk=n7-odA`D*%md{ zX*Ii*oI93XKQ0T~iO)35gP9}&t4xnzK+(c}BN*Q;3diA-2M=ZxS0s9}`n`VnSj+oe z?`vk>{*sR^>xGs71L6Ai$n+o7bLFzLY}}S6vQG`U9;io*@GMrM5FM%RZ}g4Rnd^|A z%F?3CqN;xXNMQ{hPj6v|e;j8Q69|cbT`WWMmdAnLO!r!$4pE6Xa4+6i9GCbVOQf3{ zsgvauqE(E%JFR2=;onZ9C=x} zTUs9X{E=9nT-C~h%ziK@N*oN%+n_3C!i^kN6z1+WOv38K8FBL0?<=wky*eX&Yc@{! zJ9a~F;bn&}T#}?S>$g>GPbQt!yG18rBoORmTVI!MJIDuzQb~(>$T0>Mv%lnIZh{54 z+J-HJomCq8|bZrP(dVO$}X39R|IaZ#wA% z!CO>3M=2pEgGKM+2br9}j|r(*CmBPW5dw#)m3T}q6l9zyok7=4XB_dyxS5C=B9TTz zi^Y)xxUR5^Vtgn6c+vwF)%eZeIpKWbDZhYHEq7t;6hz znj-I~rsu}@R0BU3?aI&VyTTkToA;=cF`uT&W__QJA zU<~!KlA7Rmd-gQEX(cs(-!iiD9nW+*2Y+GYB!4Wc3vQg}0!73>ifjdQ!-K4VB5kX- z`t%2?M}7H>KyGqjsm{NNuV5?vhHvsksM(^=ew>?^j*a9#1@pbq2IZfrnH~l2iXino z=vJ{Ff9)G)z8=sAg-C3jlzBUit71c++hU$^qI|%j)*eoX8xnf!T!CJin_uYr zE1cRvg)87~(wlBbnV49!9qORB^VTQP`GT2>ub?)*U82%jeBZ6W>2);neFF9WKp(cb z+ls;7b>-0|c9T|@6``<7v_>J6E%Bu=_X42|ulBzUgP`f47~b5J-Vf=&R_UAB-2IiO ze5k+v7Ey)E1XM0@u#wNT=1OcdWN}0ynlr5RLF2L4}Vejmyas{O(wyjfE{`KjgxSQ<2vbSX)bQnY@*S!{?E# zs;(dH-omu~e*<>;78V}M!~&FO68nDz&Qlu}PQwYr&nnlA?9PakFhFSrG=UKqxNu%W zP|B%2Cw-*p9Jw#L7gI;`%lEWfOv}cKItFk#9WN>)~zC zH|QV(*M+CV0lbVFpamRrf+s~~sX1bi0GPj{fo+-P8(CLjG8x^(|1WiS&)#>xvj zZ8p7n>RdY)Al7g~=@fqg1c*xBLD)Uqd()hsGdllh%&G-85+wdYx;{Rl66~Poipw(x z6BRjjTurRK!TJvZX)U@FGc0V7!6pKNHqu2&Os_M8e`s4bKyQH};;Mdb~{@3~(^wYY7yj>&1U zGJPRobFd(J{0sJq977%UvjQwbbhfF!%#V zhYG)`E##s2)=TWlJ55CDR*cBM>F*_>7gS%xK z1XPC!j#wGq**faF@Dp*_q=W3+K+Exfs-KU0{jFHtm^g9>Or42xuh z`Gd`g%VGPQZBo#Gx_`p8Os`*$UX^(~=)LZ;ITM{!IJ)i>tdwoHm0JohPrO?2i4bW%?Z$d_k&PYZ~D=;g-UAr`yi)M1i*Y_Tr!d`Wvx(GNN1@EMOUAF=-W@iT3so7PIRT*iPdq@J|nc12?&x{3dvbzJWT z)yXXQT&(l3uXDTUuAa2JclnmfPFCf2e*c zNxIKo#DrZ-_KvAhHrb7;KMqHl@U!xv_&cP+E!UW+UKTQmfNozMkG)DW;NCtFUfcL^NoxvJ@lVZfrOKQz-pXv5aU2m zHKv~4GL&OrI_Q%OIkb23j8Wh6SJ6AsqwW~u>frz;iA9e~My;~Q-bv$^E^aPP*a}Wy z&lh=Eg#lWfv=tc__2!M<-eSVw=YF#T9vBv{G**=D0YUbj!7{iNBa&f^7v zlqz4a$vNl3RM>Q(%||j!@&R!X$_WU57H~=<&CN(RAH&An2M{T@n*t#Tpxm71n%YU0 zlPdn#jYzu4WE^;~it}r2e7N|c&Pqr`a9c&|H8)}VNd^zuc(v4nJURC6H`86K8h;X&6N-OXRZu0jm%Eh@CpMm#Qn^;f z)Qj4EpQvzuPW&W+-TsD_nlX|ldFb6ZfBBQkXI|y1M^&#dW&NIn7S-Jmx0~yChWj)# zKj}HnHFos-ZMX>5UHg!s6pbMcJC=48{;XzWFNZhEsC0p=vnv#0>wDP}OiCiU`Bb8Z zJqFs3CUee03!M|hI)6l-ZDw^_-$k|5tHJ+J-9K0})vZ@PV8#gm^&lx{S5 ztlQ@=`b+C2>w3+}X5~PPivMc)&dkZqmrvdg);)}C$&?IJH$EP!;k)R=&xeKY=+(ys zm|dgjVs?W`OgkOoTt?pUmx*N+Uur|6tidtu7ot0sfohHN(7#|4LOW$1!%0dRg)Pxf zq3C%FF}K{4%yZk7P;xWZJYSQoIrw5Ew)D~p17_oQvTxr9`~>O-9omS$CV+X~|6}Pa z!1L#WNFyl-Nb2vo|IhQh z+Oc;#j&1jSf3NHFIZqF_`qvpp&XUngN^RS3C2jJL@FwB0GQTKCzJ(_dD;HOWAu`Q#@3ZtEm3=t+PfC%G7oGz+dZH_D`F@F@KRXF#J7yx{y7B#)+XYY z=co|1R2D_NZ+4zKp+n`MN;6y*q`HZ88f8V~#?L~B_#+@L59x!X5+%<9%aY5hFk-yx zXKU>(H@t@nor%o)tRp+zC-#2OV;ia5nhirLW7ALLz)b6>qFnIyTCI_U(CnuDa21uY zopjm6j!g+}*kYACUEGo5OHT_mq%?tublCq($3y?Op$1|9S5y1{WFS$2LVKVs@(@Ir zghc{=+$sK4{1gI_dR;Fz1A1OYoK#&Oa-#+3isTKqkv@UWs+1szbDRd;nlp@UWm>4fG zN1ZMZ`4@=%$Iva#nthUu#vc0mWPzmmUdBp1U*pK@IZ#w*0-=KW`>OC`+d56P!7vm1 zCrpnb_f6~x&AqB z!I&^eO-LwtGq>UA&SjLO8L}Qb1;(NC)8oIzCxcUO z=UpCJ18ln@&w9r7AgP(rs{!Sw{nbmmS%&y9>fplxfl(Z!2l+qK`i@G1fYG~DRay)a zBRPS&Ectg8dB5&1{9oU>j=<}$<-iRjXu%8?iwMac@ass%m`78-zqC6kgp#U{rrN;* znsP#s_qVfK>iv6&dV0)uM6(~8(vLzj#shbMseOi`2Ez@=Jw9J~a#@E+<;Q^ML0!b=;vF9ksp08{?06( z@pbBkhj~@?dm;$-DgF=>ax{xzK&f%+I`0qnF2edXvOVQ>?SQP@gh@ zWL}w5MIT9o&t8Za={OyX4hIS~aP94eL7Fepz10uBMp@=u>!g)*!awOKDff=n$t4fH zw6a-X6_ir|mtK2qROD<&ZE_g1ZYSP{OHxQ+5x4!y5Ae7pVS6v zl}c1123(yC?ERi)k)QYW&5bUM$;^;3vFw7j1#QU$yy657_5t(`dLg9vz!=9vT9v3)tz4Z+2X3JKL(z~h`NP? zA56)|#68tW2xY=+=5?2Gaz}&gf3eh0!BfO{B$@c|>u(6dNQ3FL14O;qhQV6gov*5> zls>r(!Ba+Br-U_6qKWdi7t+xk))D2hY}&u{CFL|8wio7Mo+WU;M62g%X#4nj&qD{& zqG63jySdES3=au`QvpD2A)_LUpOrM2z;W=`MS8od6%yg;2xgZd@U@XvZc<0nVue5@ zj#RL!l3PMvh=*LFZkT5p0oW{9^P5k9J)K|GW%Y6qU=;DDH~WmyR1vly!rTijdS++` zoWBSuJO!tvB^KShJv;c5tP2fR4y(fkeu5kX&WnhO{4-30wwd@RC@|}8We+L|E!@B9 zaU(9P)KjSrrTBIGo5J6G^;QwRmN}8W{~ze99-DjreRJ~Rs*?<)>r-#F2L7L`l3k(EbI;0r_c7yy_G3e<={;U16Gm2Qk69_}E&q}sxk1CxC8Z&&b2BE^g+CuE z$%xsR=n-Z+h<5oAQudd( zms#MW&yFm2R*lw{N1B(i02%JtNG@ehw2jV4gr7vX`Bfa>Ghurm>XjN?`_gJJX(RFw z;f(a{B<3M#W2@Mhf=x(&xRsZ53imhur8G%^%Nw+XfHSO$7g%}wBU8WPsNn6_kEchcN`=^kH-VAo;Nyn}s%;w{=qg{vA znae&MtryKe&q8^iezGg z7`gv1SRC=c6r5!P~~H=^mmdpHXW1=FVYO*AqNs zgmyHR)V@!1=zL)z#EG2L@OHE`3EHABD_a#Kq?KTAe85vU2zTS78I9K@=HXwCAr81J zYIj!jPrj&dOsj*y7bNanOD^((cC5ET3`FtC6} zao$7v{4&IUlH}zu>;bIUTb8Xt?%05*o4*M4YyzIdSX02c@!8%(Dxyq!;m0$wVKMRU zP?$~CsBt!NFA=_JH(~4vIq^oU`BAbjM{GC#u~3oc2m1$N%38NEXD0fWZJ6^0$>m?#!wjs-WT+p zQqEDYD=8O!Iv8PBfCsdFMN@y^hWVp+#5Q^QzNN)ek&BS6s~-y;_HtEhPFh_Vff?gM z6f1~~W&dLhM3MBA>rue#_dfE|ME$TA|H7!Yg?wGkm=a%nOJa5M4V>W1+o&K|T)rg1 zPr>VS+>XCZT}w+}h-ng0H!yMEpPrk0#4tJlJ7!pQKV2ZomAN`$A?TJq{Za9Ipv= z{N4=_aU3{#x#+xb+O|y#4Z7WIriwXAu{|UFn47M}$ zbuh*ynFc#2>L=N#ptS+>?hsagioyjs4Qjm+vVh}66eraYy+@BeHVcx#D*SOM5XMVA zQ4%yCJUhQzWotVCrV8+v%4wIL3GTl?t|$+NyZ;`G=Kb=u>6rBm(*zzgR-)xk59d~} zjoF`M@Os@;sk>QZNjlx}GuEK`r@->VKjk%i7(_|%82oSEoNJ_esLWV5#P{VjR#OhV zavlo~pXM_rOk<8`wwZ0`Eu3vMCM?5KrJ4|cyNJ5stj{1_-ThT*@eB!zClr}MX|Re2 zKrSHizpM^`-sA+9yn^8{yu|Bw*Rxey|1MDf06}}LoqmwN&;1^@`^l#82k-p+lcC@A zJDL2FU*;A?p2yzWR9GdhX+jnX++NnMx3IB&_Iw-Q_f`i3@$hK(^iJ8O#VZ<~Qdfw6 zmj7P&w=%4IzQ$z5(Aq_a)t=y~T13gdU2v6Q);C>T%k}X2&SO81R?%Ui7C!?2D+#Ii zXOsGYnmP;0z8hssa(d2h1LiC!es7|l+Ps3=0dyNbnm+ z9$QpxJac(E@-P8}*A26A?08N{@H$8)`7v>%z3()_P%Wp{i9Oqcq9E;AP6`o0+>r-z zp~`#^mIfJ@jK8S_1Se?eNcW$4NTnG%m)*@!tgM{g@Qh zDZ_Jwv-8PTwe+Ortmy{kou?s}xO)2}5#048bP`S@pS3tg8m7Dj)ytNv{zCRG=RXjg z`=5LJ@v3hZ&$IqT)jy~XdP`Asu4qkHaPxwtbwBY?`-sf{+dhQ?IQ?Oq1{emc+Y6ES za+lT`Og~bOOaKt7Li#E;OFtpr3ZnIUdw`98M3vCiTTZ6p6tww3(OTWSx zJmt&nq+wGhwA;!7ZI34FY#ThRuZ<@f8RYSP_TFG7-NIYxu(WBRu-(p5u=IhnKxt(q zc?@Bm3CR6_ja{JI%-9qR+`bIb01^pK6VQef7aIL1yi6195+E<-S@whIf4^9a$NOuv zXG4geU_!8#*nO{u6XN>+PSHMsw5nSa5$3q~4^X3=?Q4k)jl+uLrHHF+Ib-9;-z&lj%X83bF8&L-1pHxsmxWK#oc&}`zj;{SGM0BKcf>f?d42Hrb6UNcWM-^-X&%9$DdkmW~~Wj{T-%$?FW~`N(L5pHKUI8c@PqfSAhU+q&K#A$4L|Ws4g24=& z(4c3I&ro|Q-9&R(fO{2v_~08`Z&!<5D^21xb!kh56XQr5>|(e5@pLn9aQ-VU<9jiT%AP-&9y5l4*zpXxh5jdN?kNgxNO(%dt-6c=)&pBrX zlLv=ZcP>gVU8~=EjA@&=3OjNND!;P;Z!rx7DU;~AFH&l)WpX6ZSIfzamGEr`>H@Ri zkB0Q^%laH^nA=nbBeSf}mnL&LSFuXvxP|BmDRy@t>1IGNpoPst5;z*U`y1owupmLH zQicETC<9#g-!UgK2h+$SL!?QONk(`-!K8wKJ=++l*4oUvYk+(>XgD6XK&c?{OSk`l zZY#&pDqV7ywNK9OP8J>XE?U`?MrsvO|2kc5FNzq(6&Pm<89iS#c2DtXx^*riGYQsp z%>7UeE0FenVp=NQL?r~ia8m0Jv{Kh~Epv)JplqH_Bs4UBfJ_cUy!bA)vztxOHZ^v5 zY)hEv_XlaVJ*u7wWA~i|6h0nF?QE4{S}IG%w75G7s*Dp*NfDH*XKsqVb*fGtfbNiQ z^7+H-H^j7AF}UNR`TR36Pr_wUrN`o8J#R2MZZSP6A(7JAp(&9{e2V)!e-jg&DR93W zp&DOxkFpICQ?k2-w*DBIF!#=&%Odo&)BQ}U{jP5w7d~!gxQ`~hdhR1FZ5Rwc zWG~k1eN8ndr zW=e0b)vVn0d(19_7RPBIVBrlX!sTo7Wm#KT&YUTY&5%S?JcR)TC#f+YRp};>c2(@!}5A?Pli<6>@co-9gre-_+iH-Z7v6ycaS5-$ zPF6xx2bndrYEyh5moCN7#DnE)E8dYr{BPcW=?$%TvQj;{T$ABOM0@(@nF}b|N4`)e zZwcXT<@s@2t@M%gMOZ*@H3!jYP0+qtBE7^a%7uS)vyQJbOXslXE6pqr{S#ZNV$+s+ zKK8R;>|TSI^i^t#zpgeC^6vlAJety?BG_!TzK*;qVET3*zw=gSr_!U(??xFiTktPO z;QlAxet=xOsi*wxhFq+P*x|D@#Px2Pug;sZLLgk2P)4^og_xh*E{<0{W_q4ymRw%D71P&qWV>e}=bx(LO3Up6^9f;beA1TrxYdXwg zz51|h{d>xmhc+{3`g7H>GZstaNWX(ybl(Q8x?1lFlk8u}YO>ve@DYg9i4oI!8^HWd zC$)mhK$B9;Bj?VbDwviJM{`p$iU?aAo@cHA^K-G!UKx?Q$JnI)q%1xPXpz^bj`%zN z#P{HMjAIbv5oX!hDnfzj9(n;(=?2?ps-Ktf1>GO~Nv&S9eU75MOWQ_j59~V#4(vP8 z9$*hf(!Cu8JIgrteq;I<)i!U`I$G7{O_96jza|_6P#1C-4UPKRwazJ$(g{+@gqoqt zp^F-v0?=Yf2wVwCP6Sxe~fRj&^Oou`yav?%-Y{;;)KY>sgYUF>7T+bm$Q1WO#%gwph2z%Rs z`I1z_Q&FScIZ|K|X?eiB-B^`_b2P4f)i(15Py z)1e*kyy9-u8)Nk|Yo7j$&2?-wC=8b7^ZF-^_b8ozFqkaG#V3MtJD2q6Ub`p|bBoNAc3MvmX`N%AYW>cWoQb>Ft>>6T1i$iW}$k zUsTy@Tp2(oDd0`-(^pSX>!gDna=GyV;C?lPA7uz?P>Y^Bg3!>)o>anjt!hvXulXrL z{1>cn1sh4LNs?@=_AnOjtlCyk1iiTC4$fiGbBVa?XZ1ZXFx;@*U0+Eu+F044_`7;l z@n*SY!NZG8jQnm}8RerQ`c_^wu`sirSvW|1>TeNlZ@j1h6a6s)dx=@*yZ#XcE^(_tm!RXWc+S7t_Yf;>hP){cHo4+7 zfUqSMghETZc%(q=Q0sKo?K-uY-iYaV;i_azj&fJm9APnOH5kl?p6@I zN2*BJR2(jpx^RJ}bUd|K^952|n3zf>xRhDEU|$H$_;bw)1SA<&iAzTdE5KPZ6BD!} zy|8Pb)ItiGJIJk>E}j`DQ4_O zplxP47O|HXyvhDd%N`IfrQ_>8#NjyY5F@_xtkuLr8z2NQhvXWNM6ANf%PI+fdZ62; z9n%<$uMuOZT5gtG!J9(R$-AUY6A%*lIAj>o&rI&c)C+EBJDBUFo63u!x4Hv@ zlsTV)DAj5>Td2U-+b(j1)zEyqp|ajkaF4?fwknEB=lr9Wj-{c^X6w=AR$u+pLdCO~ z@&f@(#_c;;q#_S|c3T;?N)*J+h2F-spn9D!5iqS{4yk`-EAD34S13e~1xA8UGs^JG!B+W!~-c)i} zJzsmmk4aYn)L4fL-$&m&nbtaJdy%OqFmg;Gs3(IE(<`1~oE%nWzXzd!pR_Ihp5uuQ zkL%CU+Iqch98J|hUp))KP)Y-ta|4E{V+)D)NkKpPXeepa#9hH?Q&YJ4N7LpU9|Atj z!O%ma3VyU9o@YAa8E|AI!kT~DwJr%OmpWgo`1zY8V3_qS82(nLZPheTg!=KC6sg7C z94S6-+Yc}~eDt*w$M~Xa^H4~glhM1|p}!vTIW({h@yK&@z%E-7lE={diB~`1qSH3ux`1DN0cHrqDHF>#^6NtweWnv*uA1l=r4VTk+ib zuzXoG3;QvIphuRJhfN7y7d5!qH|tzC#JQ_(dZL1M8^Kr(rs98c=673ZjXBnJP^X}? zhMWHfa(TzCeB6cM+D_;eG}}p8DvDaC7>K6D8Tt$__yg>|-RiBOG~kG~b=UIhzhjo# zUQHE2!>*pJVa8MRozgq5^IgHv1}Sk&RWwV!-o>w;a#7mdEkoz__D_z_#M=lRp_rt@ z2ijh&+ybYV2cdhnmqovJBbT+Y3H-X%$N3gdlVNd_XT&{{>07FQ0>^sVi|l2 zw^Im(mPH1~ER%waRCJb+^=N`hVG*cYc?Q}py$EagAgsT`Yte+m-`Y1<)PoR~ZIizn zBi_`GLQim#V|S7I0HEJBP5Lo_&AP`%|Bu&Cl6GzqZT8g^6H@qe)Yn9?T&;q77S{)W z`2#m6;vlz)$5QQu1QQ@^@c&4Y+seYJ@+YN02ZmimR4B!+wBtFgb|-8uv1%f5vK_5- zm|)#_D2ABJEPfzO9)q6ZD@vMfmC2c|UnX;NmBBW=Pf3>)nyrR{l_yLq3z1G1w z#Y4|9Tc1(JkIZDehYVIYOC4JsjH_hTL5Df+dYEe{eH8vwPtl)P&inT&lIl?w^vVY;GAAxa;PT>2vR*0??dxvJF^d>H7jqaHCh#4q4&EZf@$*H3gJmnaL+qQx%H_$-f8Wrh8q7ggDeUGaPEl@>&x zKNux_6W(OW+*{Kc7UF&+LUXgk(?;S)Fe{Ixl;+N!)GW&aPS zT{DDM?w6h$Qn_$CaZ1rVIVGH_t;tO-RM^=eanD*NY(*5@x@WU)9|nt$k`}fGnJ1@8 z`YIgSs)>SdOWU#?B3E-EQQB2gl>O|pp^PH4(y3=cX8(pyKh416_}F#+TF3vxQ+hwh-NXpa}o?hOvH{PYp+ z-J7>0NGl@z<(6w)! zE|+rNXeIlIE#S`xRq_>ACSE3X?s2fc5wxgY!&#_i;5TSpor%pj~kU z2e>AsL{N^fQ}xNyst|nVMM|QuBdOmmv(%4y$(c>?%{uXXhj{8SF)A{Gu$l`_syFi` zfsAI1TlD!XV{qsT*>?VXal=7DZ2Du90*sR7mA^idqZ)P-VTqWo>BlA1HcGqi{td_Z^EyfGFf)yDjPQLP~na ztOh4*w@1QRV^&SIC3%cFM|n*@yGQ)lPlYP$>9&7nbn`UQ0pkRzeyP}8YXm06^dp~! zzh9Q+zM{e_wB5uMEPd*CRUUk#>ZLX3jdw8DKgaT_De@@G6@1nxAxvvq^BF;0O98Iu zYq?AMF5CHR)axCmf<$A401duPLfJx!zS)?!>GOWq!nvlgJPDHqLGd6TS(SA-3s1*^ zc%AmY5n1}2(i%66wwqmo?zitoJer>-e+dJV^RyVp_~Pvh&^k{1zh=A5qqrdT@yW1q zrUAJ7E$NW#TnV>H|&`HULgW@F0(ks3ij=esBl{l_07@_W7BgV zu~~A`+z8iq-}=ed5FYv8Q(hl>pR0VEU0+Y*w4iaqbXo9WFTCXXR9uUD!&#b&b9$MG z5O(uCV65>nA{YQWEn9&AgDa8(B+CxhkY+3s!R0rvpq>NGmAgmED#9X5@c`Dh3gG=> z7Qp$2CPWI7EXNz#>w^-(iz|WiE4Slee?3UTn3v{%1m`XRSn72K0(F3Jeg@u|Z$r|f$=J6rv+KoB>=Pg_D3vs#9PA82DgYrs~iJKnfW%yM! zE}!n?#i#xQS)W#E;C_xcn|i<4AI8q5_UF*vj^W=GhQsOp%npC1$qyXJ869IHM}+Nw zbts2~`7YL0D>yieY-Wka%e=-+G^1LD#~7Z~=ap1|BYv&N1#o;wOkwb7CQ2ZAH2ns* z%`Vo`*&ng5s21q^_hYG*jrcjOV%pF;$-TJER?HF!qt$Et(FeTicgQM=0FsTo7e=!K z$La58S6&Kz7H``QywOrYn>{D@c$e$`_>16Is>UxIXsPKclTT3tLu(UmLyXRvDj|=g z%ZfuJtv`2KerbI1G3nXf6J~)cUjGaF1LUKx-}&{0M5Z67#)#h|+kgW?$U zbg;TsmO-XptJ{eus2g?D|xoqN|+i2oq7c@sjUlO@*|SKgzZYlKXZl17nNpyprZk`rtO3a8Ob-WSG$@7@=khHTD|*X$ zU17sD3VF_!To|`)CCQ1W#>2vd?sc6)_XlommYr?M6OWk`VG%@SI>v0cU+Vlr%`?E=#vL>ZNY1Mw51Fb`ClbIeyGLMCY8dkw;^ z1j!`|71ZR)>-y{n;n1VHmHD_SCs^!xFJlGc59vBWK}*R;d}%dbwYeN+%Y5o>H$mqU z?0N<$YUQ+haaM%syOUKxoE%?!o`)q{%N6T94zolH9Z!gpec(+UAqR3(@DH@9nnKH{ zXde0ke>b`$709ZLN#R5PA$W|2?AIdLiGYP3TXw`u)}pVXIrG8CijXJ@8HUjpqHjK+ z-LJoxGRvfme>rryak{--q*xD+{tra*)DP-sL#uteSoA(oa`y!TxA_c*+H&u<8uMV# zx?@-H7JJR?K}MM4XLEW9`RIGC$XmRd#rj?zDNsU4EyMN4^}p&$ntRsIUR|RU@_eHi z8S&Ule%G{1X3#7goqL)bUsiN=QHANJ6QV+@mH2EVd)_AQJ}>_dq=Gj7c5I?f?p-Cj z>?hzT&1=HAZK~gMXukbTQQdTiCrN?1s^>Qal)AoW-$;J9%>TyJ>q=joe#t%>MwP8r zzH|mehLoKcj~5~nU>;Xfs_YNP1h`I!DQ z&0=YV1f5Di1f+l?ai}Gxz6UP~{vRl%3LX3c*_uv@5d$3?2#_ybkP#12M_9dsysMgP}o(`4e68(g`)IT!y*?+_uSmBg*ES=l1ofww= z95LDNm&vS$)$;rEo9GjwZV!QZzJ_#0CAE77$-j+TZ~u6-oKk^rU(YdF;J*>#t%8;M zm`l32?7C;P&?iUSaCyGhsoxZbhxyft~4I z(SChjf`9+Il%70PhIll~EI5rt_zs2b)=KN)HwiWHc9%3` zx;eD%SD^@$gWhTEbg5o0F-;vJW?QbU-4d7&ZbMb&AP8!XTG)-*Lxf(|Ldz?u47*{ZaUm6|+eYH8 zLoOfxnGM6O;CB5`#^g|Qwod`d5A(xc3rIH*CbivY4~9sOS|9FEj*V%j{zWr!WEDz1 zoT*((ec|UT5x{@_-pjSl&Wkx5m20bLf|n2a>*4b9VzcCdTH>5ZqhtFcD*@{q3vX7A zB6{JvG_ycCn8pV`;TdfmL2|*cS@$p)PG4?mwhpBLuFV|A-w4k{u#~$Gm@uZzWfu~l zfzw=ZBo%mM#j9!vEA!9vXg++a)u8<)H1}Uj(!yTc!KbvItw;GDkDBe~cujh>j29|6 z;5!+6i&*n0%6XOq$di42hXG#G^x>Y7>M!J6UT>Btx2fjL#aI^rAnD*M4NsM2j&UtUrGQT=s!2L-sNN;K{rK~3!9urRVRu8caXoT!2TwyH-9`Ds z?V^dY=}qQIf)@Q-XiMlNivt};c8{zghp~B=T9J*LeAfa@5K<=I&MNb)u|Bf=EX_9(qBK=O=AHv*`-Hxu%|M7D6w{*$?JP~ zlfw}jH^$MQY6U=iK|sn(0iZaRrd^;49RY5ZwklDWmBED(-g^P58K9y3twd^d21#fI z?O_va&?MgRhh2adcH0t)TQehn$D87}rQre>m6s1$K11|)F7cF`aG32A-2VfKP%szX zz?*vi>=;mhNApRKzAusZ-)F`$rw;)ZqBfZ}ON%=0j9z|#~PkX(t^ zgV6x_K`ZyKl$+_wd69Z{x`EAWYk{zcaBb+mkXnx*eGm`3qP%=e zM()Bm0Eu8I3FfMp>1ZXaz>$xTD>hWqPEk%1r6eg-4-K`0qx(JbA_(sxcY;C#W`PRr zhk7)-9CXLjR?A{r64Y87HjiVtGE}ISZ{Xv)PGob7s8>cUlj&XpDnULf(kdIKT|6bd zMeej79kFCwHiKoD=xHjyx9DJpqheo+>nY<#PAg6xe4M0k3xzG+$`C2CM#)<7hKTSK zF`;DO=QMdtvqS3FpNIJ_6mv!td&%bg%0_`WZJXcmwZ8ZGOv;S&b^wZ+)fv$UCy75{ zeSs(#yFd}pJYXd?rnjN7$EM*MNwByx6K$m_(i~dsv=RjKb6!Zp9KK_l>71>g!T1|} z+d)Lq64UNBL&-iqVTi~W$$g8HV#_5lIrDAi3ht;ja4L;{uT;x%Zf*I5Tnyu!FI!{$ z1wXi_U^(fktgW|{nNTVL?%_`UK)j8Ahx5#s+R(}_4QGXrMe& ztj5dz@sy>f_k@F3oGG2%=8&#D10zEEe-41S;&ML_SMX7dtq->Tf7aF5;feXUd$_#d z`w!lHDM>S`WU1Qu0zUzRgNaFg+N>&j+-bfavU>Gtt^{7JJy1S{0#*cg#wmrgAeGnCLgb^TSpz;won#pOFh%%@;&=;cD|LSCzqo1>yg z)k(F>@7*Y8-}^^QgiRtB-8wsJF?}0p|A8K4^t=ff26T2eF!P_l+j$u78`4PweVjaM4AyrFIrU+e8_%6B?ZHJ0_T_rf7rZyx2G zB2BKvw29Gpt@t8_FC#)NaKl|wE%M=Wv)#6pFO;jx@OMg|##>I_9PqdpZrFWdXjlh* zm6lroU$Rc;y_=tuS?R^KZ^&$KwQG}L{ih}M_ld#hCgK*0bD7?F?dXCr`gV-nL@*t% z_e}J63cnP0`3hG-jE>~A7!g>-NN3=qlGTCW!VjZZLVnW2>4kO9b;K^`>CtgG+r;;a zlp{H^Plby*C8R`X?Wfr&6i^L{D4an8>f;D@3TR9*JvY+cpcF+|WMdjJjn{#lB`d${ zCymi<{^a+-w`hcGP~tV2{k;CO{xGF2_8E>HvmdY&$y7=Wi^ZD$d~jzjMQ2IR)FL=- zbAm@lN9QmoWUjyQgtwsjY1mxj*>Vy6=u|bL;enLOcW|z=N&Srmv8UUiEmgEdaO}n( zxxX6zV{?nf>uE&&#IMEm6&TH*cfR>hTj_12p^OpEc}`SRDObHemCYeyo)azfd_PFO z81mfes}GS-x7x~uQpJKfLs)>FSzePEzioXv)9vj%!q|%Ge`Y}-B{T|3Rm5Y1Pzm4-kPwVG z$=SgJ@tU77Q~UUvo5|F;FJ*`-TYVTMXwcB9h8hrRm__Zfcb9y{41r-0GbNSjN~d8K z+1D%mJVxEN^7CJ2yh!k)zpA|L38*<73j6g(Gu|n#KF~ickA5lp?_)x@-~3*yx3$hdToq~3m-+bn#HW6{H;=+cz^JQEc1n7hbW2AmZp92Fx=M6 zDZ?=L#N9#2)+1IE;&R*yL{+Q2^GHIL!?no~C>Sl2#cTYX_%Fnzd?uBCS(`;eaIgNN zG`*L*aYRnqk0nt~z4ZqhRke^M6M5XofW^!7-V?d%#~&e#PG^|MI?Co#N|XZX!upd7 zY>U#=z(cFD%R8^{e$ABb@lSN9wxE3pQ2?QUP(udTf~=wFM}QpdrP)iGp0|OrKb2wk zLzk%OJd@+rM{DXhSCz=q$*h}yzp)2I5DLObT|Izk`9J!yV@A9YK(6$N4-2988?q$bR(+C=ok^o|BGl~)x{oFV`# zswTu3pm!p8)*mnA=^1uytwpdJxc8WlS`mUt1qMLictKy?1OXh(Yj$5faid04Lq}XK{J8)jZ|l zE_(!NxuDpSfk!%O8eEb8YxEL;(|}=yzoxsuB=BMYo(9A{P+-?wOqfpv#*xT}kX6>R zgu1=)-oxeu2DHosiH6`ddaaHqU&)P>=T=n(7@@~cCKxwE4K}}f=&(FB8)1?*5d^U^ zceD1?!uP!QUWl~NS_eQhXKYmBz4;qvd0U9CXp_Vf0ddT))=JWyS1(;f6;*tCT#{aL ze2{+dnn+vJ<;`C5=t^ew6Qs#ED>udY`~#=Xh0m#l-#tienH(c27t(KEOyi8G>`5nu z`Pwy?^?DGddM7p9aEqBn_ipjdeyXh)`B*D&d=-{!fZk9mTgu6*B_AMke!{ROImb4L zK9%KIiR>n@JCo^zi{$rBS0&s-4~LC^Qu&*{VhlQvczmT=#@E4w4YVaZxKA`pAC!Ph zbmeRkwQV*mdyOqryJL6q-ZGoIxU-vu*gZIM1A^3277lv}6W~=W0%T=_4JeNMh?E2* zNH|nFlG;d;Lfrppk;ruQ(Gwtf1OXFD+->3^7^k?ZdIgzNj(Ns|)@S{cpzrIK$6HO! zgYWz7N~TC+ScSCt;ig8foN`p`j`m`$-QY(G1t#lLpv=8xl`;ZJDn)xxFhL%;h9I8@1Blk+h=3|L^*&uvOR&bfYA)8q;x`edjzD!Vp zAPQE`o13f$@gI<*f~UR&M_`@^mXXL%!p-rz#fpmC)p3dOLU*Rye#twP)l{rHNRA#P&K4a^sapl}y3L zem2L02Tun$6eHf8-M8I)K-G^X{Tmeb29P6*ich3A;-VyX`W5Wizr^j6-dt1P1c3o-J0Rk_2}jan+b~+{oNBgFy-bjyy3&zp!a} z8Z7Gf_r_+%zYNJvzImfPckw1pT7nSAO*2-|(9NtW=bkKg)!IH;I)QU$+O`=day{1lX}X7dA|YX=pv> zbVcjt`y#i}a$eNxknjX4B&PXWIOLGZRSCFGS#`3aA`$sc-eyiN-b6Yv*CO+%da=U59O1=Zb%4t5cEO`t@39{vwZI#h?{h7-vc~ zeuo?llnb!VHt*MjtmG;etP54BdbIbE`;|+)m9*t6*kF|UJq2#?_H?c%?AVU5w>OPi z+S+Agk17_`+sKFbVQ*PiGa8?ac#R!EPLRHQk_%1S%~~d;ml$^KmJS@P(NKE$A&mba z@2r$Ov)$b4HlC(Oi$sUw{@3(Gz!2byXcYfnUCnJm?16HcYYKu;P$~_W-Td!P&}4*H zp;n48Rvj`yxQ3v?paVg`i)$@31pdD5Y?{{BwJ3;H_()*N8fKleg zO)JfW6)^~nhjg>x5l^0wP-}*dk&{;Qiwx;F@)-Fe({e>A)UDkH3AkP*xPuy06pd=A z*!Dl5x$mn;P!dK}*3z8ArK#_S%LX?-D7mRB#Ls1eU}A!(VAf9H|JL!GP)D#LH+_a)Y<{GLA_e(Uef#B)Fh@LXq=2F4qq+M%qC zbO#0=ExBIwyS_R$*f&qDwfXW|*($yb*)>H(n?p|}5$UQ-u!TZoP*zUf=kp-r)zl@UcO&SIs2?93r@omq0lk>FFye(Ur>BWCyElYNq1*p( zJK2c(ZXd_==?0DYhR0{S42}K!d8A@>!Nz{2tuN}Oe(;nu`zuEqDu8G%CCrR$?swoR zRov+I_nzv%(;T;v&z3*D@3L@6ZBeL`$I!LCe&Tddt3CJ1-$l8CuAKxoH73auHpIR( z4DPV&E)6NL>de(`S>uC7Yl@Mqj0`#SR(!V=>u6uM7!mmFpr{XCVws5{mL1ZGD5qbz z*ZkykCgoo$Glkn?QN)?_R?k9!m}f0nt#vu!1HvS1)*tFz?{n~7<{YUz{QI99hYucW{h zzU($ZP@6_&5hxmQX-K{Pb88ymtH*Ijg^f%E!U(I5kpm#*gs4=hciR916d6)R*JSFc zU8n}+<25NjoFf&uv*su;xw!s-2)+qk_Ss~m@+V*+uKXP_Jk>;Fr{cS*uetHr19Y4{M=-bP zx?_66UG4pJvEwK#A(KC|lDPA@24#WVm(Q^YLDGGTGm<>EOQF&cr!~osk%f5Y(KC_h zBE>a@@allZ9;y&uDkj&x3B*hQTr+{wn+|ZYAwt%^Db-hYVN=iG_@IJCxidUmJ&rWp zo2RkxbnjGITQ}9w_I77%IY}P-TL={+UKP-;Tc>+wmEN_m_;4d=)sPe->;32}LB{BM z;xA!OkMzO4Y6B}aQ%MjZ1zhzT9%xa?oo%Ju$wQVcPF=`*CXd*{0`?D^{A@(ZgTJVZ z8svP5K{ov}C=g2MnXgl0^We8jA|nAQnIa~#l%8!VyK3|PHk5AOIA+&}|8-)bE}P&n zr|ti3dqYzpJkjLzMf%8&0SnWuhxQOGxva3(*No0?Cq%#3JPGJ9FQBiY8Db{T0D*{f zz5$~!NH_96Vt!goC_(&SGE}=oo7|ofFvKb2Vud2)=XF2UVS3m-Y6LAOC+d&37AjUL zuoY|?=I2W-esH%RA%MDNrub7_=6f_OS)WY~#mYM0XYLxv6`&17Y$a{A$kc)JFfb`W z3Iggr0K**R1}aX;>;~asGtm#hS;j+yV5i$?Y=4qU#}j7_xzfQRM5HuFz1Q+f#dmjffQpF zu-|gWZR+#1B`NOanR1gb4gSq&gZsQN?3 z)ZOEU=@IrjS=wZox62p`vAukQ_GwW?d}f)sYjzZQL!@$gRsU8KZSVYe_&a~`Or zqyZaDfS>P{$9y53v0Cc!q#-JI#M}#)G??mrl=*kxRgqt-B$}mXM~%J6AxzV`89UI1*l#toXsuOD7E?rjQ=KfR|U z;+mV28feRWtIKAUq9*-?k(iAVwOQhSzR0Sy)@;2#&g<>FvPX8q?eFz=F8HlL-DJvV zh%BFC-Y}ujXlC3YzSlV<0yj;U{tR+9ZL$1whHmwFIKih%&A3Rt@kS#SCBNA4Q%1{y z@9`^>Ib*)D?&kjhA3L|KC~G}K-)LX&>!@E4U^iBo$Z4c6wems9MUUUky_ ztO5_KNR)5Mgp)TsEL1=nJys5|SYT80p1@8D|Y zDK#B5z?U_iP7V>^3!&tn?WD}G6&IdD=mNxrhdCgW)pRAEfW8XF0DR_EUj^nMv+t@2 z{?kX0a7e}cJ7IKufWH2kcu79PpP^WvOY}wK!npaMnqs_*{F^k8p&_CFM`aSYIFY&L3>j*B5YpP2w7T!5l`Ka5JpQPz&vyTBGfPQl2MJ3R7E8&rUP5TqxGRd z&`5zv$ijeh<~#q7cDv4C@D{Fa&y)m*>y5 zVWC-ky#z2$=h(EXM7qUI0c14`8vNP3xx6&WH(aPiI(Idtzldoju?)rffcA?Q@M)Du z^S>1J#g_Y(5nKta^QFI<`0eXBaM#yOMr|M8Yz5d4#Ua`yqF!ZWW*XH_3BFqeC%h>w ztUp$cV6OOl7t_YYUF+&iq~j}&F?HbhkZ0~3s5Ii}97t-Gla&o0_t&Z64-9WOdx~}X zBBK3@ovPjr$v7Eao27{?ndfF9!woD04(b~XR12q{v4+s}4hn`hq66Qx4B9e>J)VXL zPavEgJVcO^#okFHklk6zv-AH)reunvMw@6uJi#Vfy7JS&yxdZFK>jZFk@h?Vu)#WB zsWxYB5i&QZJr@``TkAy==e?+uTu9e2td4 z6WF5dIZ6UH?Cd7QqG-v9<6T26JgN)&^Ko1$mXN1KF8vxE5-n*{fnPjdb5)ItxjW(W zSO)!l?qE=N`g(f1Cm4_5grcc~;he&F?i$IUwATlS7o~R=o!jp!<&X~PCXxKJ`0}1< z7SlB^{lH@0mf(L&QY?1ey&4R8`#75qVv=U%dnl>2IXYRTYB*OG4d@nCHt#QlT&98Y-rZMn%<^J$P} z@DU^3SGj;=u*JI6VEzxkefzQ}1lZ(15bkevdCh}%sVOJ9zoJS8O+iYHwp&bXspni( z46gLJV5Yw+9|H!3ZmOEi>o`uBqhZR`e}=DWrRl*-%R@NNxXPPDE_|1R*TCZMk5D_b zu#scL)4!0GJ3ny)>Gitz?~mF^t4PuB-u$+7o09j3+yX%+jOGB5(oo9Jce0ww@LW`x4pkUW*Wdt3?`EK=(uu2?6`*T`NRbjWS> z^xOH7PtRk9;)n_#z?84q_c>Exp-lRPN~11q0?pJD#9c)d8jg8>FEZ z;N~e4_(bVjX0~%zFu77({U(U=L7Nh%D?c!h&uEKB)U`-XlX?MSmXf8)JgZpO#Pr*Qdh8!ih z@$Oh-!Ej`~%m$=n<|QvJCIfNsZ?5>M$owhqL_=A=aVJiufRf$IhmD5L8g=k?5-V() znmC2Eq8nf4&-UC8>pZWI{P1a>Yw5HvBn#IJ8V_gQ9Qk&7Kk~iZrSu%t#5sk3IjS5< z#+2Jx9?O7d4Iu0;E3sG%mHdlW&gSG_U*mC~z1btAB8jyxEHqXrY16K#-r-txNU zBcxb_t`>3DQ??AI2jd>+ohs?tc-k%!Mw6gmIVP$A>CcMtbDcZ_{$-m zU#@=-S)QE<(WfLpz@L%(-sYz7+aA zWy>a5CpJE2VnAP>8GMjW$Yse2uqjZZ9p`f0i+ErU2-I|fg86}P)odaU5(48ckG%(V zCoG^`Y?Y_rYmgi29xbD0`lo7tGY?eCM-5irVr9`V13~^?1$(Uj*nT%U(HjwpUuiV zIu>Jwy1yKMlDQx~(T!tAiNf54d(agDp?VDSlAbkH>TDE4BG;8;)Fh6B|JGC?W&G<(0o8BurO`1u$AA;Tf zsbhxg846sov&h_%Y-{&ajAQ zUop+?c`UrM^Lw$ums7x;nXvf0YxwVXTECTBfi5cLdEDbt9J||p08<$Ef#PkXSq^aa zqRA{_+Yucbv649Z`i8hFM%>GgD|v&x!{q%6T>C43!(VZcIsO|B-B!K}=zEWhMu}`l z^nU;V>rLl#neElbRPg+@u#nB$OUwEC2L%kDXu^+L0RJoyX`7lspE;6H*Y`Fu7&~Sk zHh$P$8QO7-tkmBevCIxvcPu7;=el$iNPfxNi!iX{2eaJP<^KMXAxr(U9U>oSS6-1` z_AtrnN>;%yIdX07-Rf$_&E6=1fv1MMcrMkYa?+-4^>^uWjHIaZ?x21`>eDAU}nWbv=yza8~WCv&b5JmNiQCU`<{N1OABoN=zl^S$5B z&4L%f-UCWk!yiTp>tr1H-WKV0+v_a(IjQKTDm0|?@f9pMK_E`mB!OPEU1tucTB-@x zH^Q>KT{3C7=3!7VCmOB85Eri`d>$q8xU*7pbOIiz>2xtD2Kn>Mlprs4PUD3CtRQa# zHm{koM$1kBT=7H|8)*TCeG`J>oYgPS3SX3Uz zSW+LLXHxOpELpdzN*$Y_v9z z$AVlx7E~I77L{vo0D zO)U6YIEeF?SnpH1F#92if7A7UGFai_>}**6-!zMfO6#Bh9u@wRzN=8GCn5A6{ykaZ z)auEd)}MthET2C^4tD)4U;8Ca?|tbAUzCFu9-z!c-?n!C%&46xc_B1y30r*G=7s57 zm!&0mg+G4PHH0ivcqdkdh6$wZ30G8!Jsnkb|BXJ>@L( z{rh;N@?UTv=VHam-FbKpxAP~$IE-=$T0|Cg9 zrV>1sfJue{#jmA3di}`^$y7wjR}{0GCLn~Mc34eAD%EKCxx(`{`D&I%oxw*_kI}6r zpGPZi6ogl$|s3SBKp(AESI?WYIkOHR}syGKmgOln_U5x*#DG=C7(I?eO_ z%-H2?&|pYDF0M4G<*M6HOxhUGxATsoe5D*cQ?!unUF2Ba>D_1qy&;XLlK6NzdR2EI zH~y|&~&bJwn$xWQo(YM+@B-S)kZz1>)lO5IGrpmRT4I0j?%$V#nPagSo+!LF@Yi} z%|jetm~L1=Ttoi9O_Nd=E*U>rEYi17bQzKzAPOi4&p*N&=n?@c|Gn; zRT2}%wSY_fZXhWb?*dONiYH z_P6xS!*OkC62gPEScb5&!QSL%i?agxh)LlqcI>Xj=10!vd%GYvUTPiKHJ9WUk;lZv zi$(2KXs&cW-mK;fZm0D)K9z-DxmTV$Jsvwydh(Q>ood%FbOCGrG1!o8gnYHH!-{8REV_IZveQ5Cx$=ue^%*IOFP8f4;R5?KnFp$M;sJ zls&NZ7#kKHp7|j>|09NPlYf54H0BwYa4@J9O5uL;E1c^a18F!D`ljZuAO9__WsXTt zuDf25-SN=tg`)@MPyZ&S6N0kO9R3OQ80@@)azQs=#n}{a%FR~DUhZ&Nk^izvWwFl5 zcUL|@50lrH?QSk>W^E%4HY!(@+z)pIGDmdc_}N!KRdVdo4T(v;g*RJca zX*H9_He`2R>y?BIqZ-#rQajd)7c3T2{e0j5Ib4-S2Ew2TC-&cKHcqc0Pd#TXku8{& z+^OOY&ceE>2)>{mWWpEEbGaHB6YZ?(%`;dZMCLMtvV>bl)I^X2zz1h zF0)yhk)R74R3L&xM^yPTjo+Eu0#p(g?4+T|@g=A$KruR7t|}$I@e}7&;Wg8#YXH)U z<7L)y$B4KX*Abcy7a3Hvmhf+;E&(eh+<9u+lXZ(9MD0!@+IQ^a_~&1p?gv?r+jgGn z@sA$n7^dB>&8qGSRw3~RuuYDh`VSlC{L#UEF|s>IGA;6WS?-%^=Qx@pRoQCqsfEm1 z4q>7&s>hMD0SN?Hw+__erGiXPfwLrJC~!}>^4;6~`R09k*AXtbtD*j%lSv}zu2UdG)pPw}?i)(2$e|F~+*pX!4> z){6?}v)~>vyM#EJ>Y=TM1=>xLCpx0Etb?JSc|K0)!Ar2Sy_6o3gTfzvt$)%>34e5(uACtFsKE z*wC&e2z=kC=Kc-Jy7zj6O0yq4RUNd6_sKew;|?BlkE#&OLI$pF1!zel_q%Ej zMA`EXXF+mZnKkA_s#hmAaDVz}#F`n74t{B`gcc&RRD8=2Wt;73sg3MVNTN`@FhZ%q zIfm$=uQ=+%JzfTXstQNhMNQ6Rvrs=Wq?euQ(4GG_uCdlg?)WcHXdqv`@uS+FhSV=~ z%eM7fejik2kj7>wvhsBK=+UEolc*DQzo#a)RdXz-B2%yl=PU8tS1w?HTn%_HTdkIo zG*u|h!uOT1h5i5R8x3MldDCyon5eA$?<-J^m_&rHPWu=RCc+yF?iKZZHw=movQq4! ztpi*!H7*R6JaW%(>W{950o&in6$#%$c9gz_&riC7 z<={<25X({|a(WFg>7_9iS&&;ipC|{?g~$jKH)tBl;dsg?qwQze?~YV!h94AgbekCt z=sZy?fjt1PY}$&3kA2yyWfSMkVLCNNjIjN0?H(jJ`3RBI2Qs}1ZQOSX+L%geh`_O( zAO=%9wOV`5)|pxKmX_z2eK*X2j|=`?FcO?(^)#aUR; z*r5W96@BL1>+MFI71I{Nx}j}Zk+L0)4gtDCFrUsXbED_o+JFQLpzB@^+Sl?w>y{lnUH)BYeGW3G%`SV zFy|01UhYIsABZW>(6x6(1B@ED(gCKsNL8*x;U8GQ6^4e;P9>TUR{RTjj3;3gJSYFk){SkdR;0oxr<&#WHdwqt!g}XkE$}{t9i2R^arkPv#&NE8x`(M z>HTzVm+_HKoT!vi;P?+9OAfw~p8mOOO32oFuDjdl!6_U|JZ*<3CM z{ld8h@*@T6YyDgD!|v-nRFdt-tqc!X79p3DsHZ_}o?)H!D7pH^JHHzEQ|do|5)H++ z&K?kU?z4O%{MoAA-9&5iI0H47>h6+DQGcRCWSLj3Qhr^>QOU^ayXjZnU-D!%v-7T_ z6!;derjjEcyc|6E*kS7A2j7f4zgK;T-hMCerCnb6EfD^tWfj2|i_T)9kf++qX2qTavywJ1HZAeiiOl(Zhr&fx^vGUO#(hqM1k13rJs_jD# z34{or40XqyO`|S1Aq_Zjy!jc0&VK-*>$*>{R>@zr6&TmO#;s~Og2COlCvbf1jxrHf z3P)XTDYVDKk_9{z^?T+s_dDt8%YhCCJNR({Of_qSh3eT|)8*d3IGDQ!N{-|yl4R6S zA|txuvQe$=&nN%OuL_&B*L7!g>pK3kzg|eFEUMtqFF}*|ozIrp#vL7=nXay)&-+3M z**Vs>?S(LOPNRhKd5^C80QNvkn^^J+0Tdw7_RxGr>p<-B<2ZK5c z4mP#dJDkfa-pG6!`rbLENYq~)@u^G+(J;|H5LPz!!?yMYHO&2+wePF;%w>CNq$zbQ zz3qgIBF%JD=Qp_I%v;d3P|k!cYL|u{(PsnZtZMkAK;vGuUqWSn7^f#NLZu@MuCF;z z(H*#OZ}q8Xoh0}-VuU|2-imHsC<$Bn4(N{B?pHN*X!)JTn1>h+wI(Pn>Xhq7%jQcWnEe2fhqP;`=#hie3GFUzCBHL6aSf z+u)OO+bhA0nBYI>Vkw6hkng5?Yhr@ry{GGw5oHbquJ7_SyYHuvJo>KlHI06u-0O3@ ziu7AR)S&0z5*vST6TWs`O+?J{C`n1RZthhc`f*x!r^}ILRveJ5Wl3_(=5T$<{KDS* zX-?LO)m`nkq3iKm7C#F;_!l%Jo5&iq#DR13n5?=^K6GX*piW}aCSs>SOY9=S+ABFl#Lmn&7GzeT|U%B1QA1U3B7-)+D^0Co!-xtnQyi{c``HttMRrj%tjIRy1kQ zvYki{WNHp0uktcf%j&N`iN|I%2%6hymrcTVxi1a*f!f;Gr)wO|5QdyVQJT2NJnZxQ zf!Mw^YiW9YP0iAJa^xd+&%33hdipn` zgLx%-|1`)vz2r}Bml8yEcW$TMR4Se$F_AO@m83C*`fQ-;-YO?7`EN z8xwxd{0E>AO6mU(km(ime1LGHS~>I`MjWAKf*j zLR10!OuH*_8un!zmxh%R5CSJbNESQ%S(O5^bf!%z%#H^PDzLl9l1Do9P^ofrM8N|V zkq$jq)w@8BFJOXS*=Y4h_a3;q<{+;R26lv~5)f9UBC4cAFrA6=^pTB#PmHI&}k zSpiKldvCw`+QlZMDN@RN>C6UHAIekE`sYu{qb(!vefIRq!KB|ziZpy-Ka{RMpM!D=kX5jDg7W`SS!bF9E z@et@Q^sv>6IA{dX%+o(%K9`^|Jt-@)B(&1tg?Yg0QFDY&5$E2_j-)y|<0w@cuzD39 zzJHfoP7d^?{m#FAwY{A;9jbNtUs|BuO#22N1`$KVkG|?#zRFzJL{ub>ZkfW1G=}pJ zj+Ro&xMNxoJaiR2Bf`o(3;k-P5Q$6EIb6|akMK|Q%H)4U)sM!szPe@oeQ8-LwSjga zIczX4D!Gy6b7YKR{roQ7B1IG2u>5pnUnDI*?rq-goSC|Q1?gt4s!OKGtyRm1F*bB{ zfU|Bp5oa zLJ@A7H}G1N`Q!vYjXXXF-PiHKe^b75s&1#vx!ZEf%v68K#Iw0!5;9c2Sqjspvyz^n zbYQnA^9Z1*gzjp4sZ-NpE0~N4kGe{x-Wot9fm-_J+nV-%$Kfj0Fcw4gv2t`Wz@m{q z%T9KrQ80venkZ3Z_yk|47Fr+Lxq|2;!0SX43-zcaZ+pE|q*Q;g?AAzEbMz^}=$O^A z5)8!ol78_MIfUl?V%2*gw{GG7qE;X>()5#pi+7Re5E~+y45IyO1l^ru0eC&)lqBbv;#x>)udIjg z&nibqWc@S?$}uyf+g%jI@cBl0P0J4W>EfraWER?(+Ar}SC7Z5Wz`550lo5H3Z>K@-dYo!3C>3AEMK zr{DU9iT}Qfe;w2aV}!8o$MsJkCJU@f9f^jbL^*>A={Vt#ZuzLpvQZI8^sIM@+mp$z z>o@OsPkIj|lD=+30sVozY(4{>hoA0)L-i~0CQp38X zJ@llH{4qG~jRuJPNg;c*d64pug#@T#`iQryZ4O+)+peX_(!~BV9Xp5(#}x8e@01E; ziqHU-xi5YKe=b%Y(ZRmElr`Gz+yX-j0##Pi{=JCdvo#Bo7r%DUUN3cuoLNa2hE{B} z$?&Nq_kA@ShKhf3HEWsB9vB3;m!Qbt>!biFKZHM70XrSMkB}mvAUcPr9u$yQBm8eL z&Mu{`m>^Yh!m!eBQ?PR}8FLO;sdmd>6G8(R85FtbufY7ke$^(eD4qK-nR%h@9E5gk z4aL0H1t5=td~ZYRb=QmU0@GqB>%|UQlLjQ!rp+-ICJ)zZwYV)(^n+Bf9Pp~xdq>)y zOue2&kWLrS%&tho z5fd&Msm}DH(NWvxyIGUHm7eHXdPa0!9u;wN9D1^O6nWq!6PS{aHhUW zu?RrhV}saFZ}h;j{1>Ra@#C4oRV6Y_(eBQSeU*oZ-CH#lDlkzzWLT5l-0Cf{cGp2Y zSevCLIMftNf3nf8h~?fh%c3ko^z4G3n7-)EiIr3x!QnCKe?_R1%z!l4OgV2^JU)hP zSD33r$twP{II;{A`63>!COg_LD*(jz_=&+Lq0%o+hORda<4>5Nq{E5G;`v0KdCY0DLdp%-A{c*o>ntRL!Ir z4DD;2sRc_L+Q9;bzvCtbH6oNeS$W#hm3Qk7TN+Y$RLK|vj*z2nEL;D08&@`*NTb(0 z7SL?o^NeNeHMezw?J1@A$O^^OzJ%BAa(@@8Pvv8Px)A7Z$+QWUaT6L}q_QmTxogZ% zzrdR&pw%5H*S2%L2fo4}6`ZXD0uKnq4t(ykFoxDLOWrKnv{zCjdqf9k!f>?sT6b4o z+g0O1W@jxEvA9Uz3&xQuJ=U7t27}~4j!vdjK0d}1BR6-mgcTelGwRl3C2#D0{;m+n zQJ;B)DVy1q&?2XFb7tc=W`3yFIz*`C9_5YissmWtcGVlG=9X&V`4 z3gWC=^IzG=p=RYf`Soum|I9mD80^O47B6b4UV z$3L{R(f(lQ;xYyN(|qT7dY|8i{5WEYpGa4d3|>?n+A!Jd_YSh<3Ot6SDcc4T4Ar@lN!vFl8?cf~LnSebBqJ{9;LW8s%VQjrnH z?vVN}SYa?nL?!Vq(ikFTIK`AiV4&d(JR->*r8NB^fENLSV7bWvz1YY!=iJ!HD-2mP zn;ia1<=Kl=|1L0ugYIe)1iVAjyvWCo5DNjPxzrURBr^*r67b4cW@LXp}Miw!fYurKz|yjQN$kZN*Zh z_fnH#M2-YmN`2I@1PZNksmqF&N4ki~Tdd_^TP~PC0<)F+8?y;Zz8kr}=&|T{htq}G z>iTDD;y-zYk4~TSrwaXmWK0zN`4Wgy#{LQb(8xWMh*SXtu*b0fYwx~;0 zdnd*dYqPbIO7`fGS}4k8Wequ$4}A2kGC}uIrxGJd0HTmEY3LOOn@8g&D&%8jswQL?LFoXzy}Ddf_y2wNk2yyl73&36eNf zhIa?JQ@JC{RdTfZ+7*T>tr|*%n)mRW;w>B_SJNjO+Lz}P)m;gB+REO6b!#VID0KB) z66a?e;Y9b!yJ+%_^I_ThSDurwf8e4QQ zI3?IT@tV~Wdkhf`DoP}HEU1Jl+5`Z?-r~c$y_8nQV=xU~M@@PBAozt7r;=!L;c<&w zm0KV1qNX}9WZnX_mK+Le_g9U=97k`Yk@JCTJRQY z;~QU>9Mxf{3pog=9v@&C$D>nKLp!>Ib~5=sc@A@U5i5aqt?xrA<`MeI?I^F zv+sR_G-6~xmM!;q-=(^@W=l%4Gr*qzsJD?u;X=G)_KOoWqojt9o@nffI;vf88U7J_ zCuZT_!FaA*#LjhOH=S3K=B0UjNQtxw}!n&s8*4xH9@sEFHfw5QZZ=I#*b#Kj{j|myJM#iLC=bG zpxHlLSwoA4H_%<{p8+2h&u$fAbL-*7r6rmoJ$N@}wzg~`M_G1hU$~w-w?6Ngketh; zR)cN&dR8(&_Q9#uGl+)JnFMW`_&ueVk6m41Fa$4=+@sO zYcT_Y^|KUSG(}dhl9wdA-7H}(1H5;K{;^k>bZY3MwT@^+S!dzEk*OBG2t4@}t0Zsv z0!iqU&*9;Lo(#!Z+P(0g{wfc$Sbil)@k?`hU=o@(iyti~PL z8w{B{+CYr*6#h~0>mWcfms7-gi?r*YLCbI2hpCbD*)xy4B(i&54P=SVssJ{v1|u3f zO+a7edoqP+dEk-mR%CTt_4@XgIl8pX$#;8HV{~$j^xNa5zPU4;+TL5w7Nfwz63FeE z2EmX|)@9vMq~=|*5_=ZI0bI7V(tZB^ay4C+;vuxeD}S`&levA^Ur;ao}ja#-|$m&0K)P5G0*M%ewfd%5{zi~ z7@y2L1v0EnKRc566Ix>BRV-w~spdz5YNGNS zzARDrpqOY7ptkQ`?iG|1XEiTnN)e|x3zUBPbfr3-1rFioR7e@+Pm;VVHpuC4__ilvCHo5mE~FT1sD3NK+yp*Sfb z7)K3;TG^eDaIhYcB&tC#Bfmu>dTFBVojBY2LSA^qP1&*($nx=)TGN#v$W&wm3sYSv zOXKs}Yj)$#OftF$X`)RP@Wg!Fp?%O&I}cvW(#Z1YL8E4v@aRDtvVxDSJWQfEz*Jk` zMQ+dpt>wPwo*pNf-R#a%b0hIIYw&(x8Nh?A)KH$a_2b94p#EXvoT)wFAfK;j8nW@1 zVTE8Jv(4NV&|nv2;Oe}VX3?8w9%-JI|I2YtZjl4RuX=}Dq7|3F_%btMJ^Vi+{P(&_8`3M?W_v?ba@vw3Z+ z!tIFVsty|rMDm>Jw-989-+`^-rb|s}A zau|WeXJD~6y$^@vE!zOd3v(HL^o$P~bsl~7rq7hD5N{8sT&duggqiJ)GGwlv?2e_% zH<4u0F3I>PdQUw&TC%mZP5X#!qU_1YD00MBkJSaU9_9w^1u`VCoC9pD2)5a?e>n2qMR_ndPHkn_ut0a3K2P~CCqLKr9p&0hGU}!a3KVSmD#N3bh4M(`Q>Mp@lGMKhqAf|SJgf!Nf^p@FP1(r#K zTp?a+p}%meo!ov7SB+7T5W2v{Iyo0Wy9!UO>@?ED36|6xDmvXiJ4G>k{OTN({q;kc z9njrSJ!!?k{v}Bfp>^*5KF)bi(OSL8F=o=h@}p=&#~7vJ>;h=Q`dFBot`p;`2c|8i znHvLCK~oY0lA_!0t(wTwpjADG04%tLc6HrpjYjB=VhXpW<(;oG$_GuXb5{QmH$0`uezkG#L$9 zNspSvm{pZ72$XUk!_1j0x@vDn%>eNq6SM5N{Wp@{LWL(dKMm`Kbc_G;4=@{HYBpPV z%@iYpe<29)*`s1L*n@B&+%xcr#_}k{3+H1rNAbn4vpcDGX&Pm@=K_kke_Nue03AZb zrKB#<#CrhOU98~57o4E}lV^blmgV*>_M9cE=gg)ft0nDC_F>Y|vW&7op}Co^-c#q{ zYH0d9!>GFNOR)gzINQg{q+(OHrK$%~iS6{dk^QLoaBeICE{q^Pkg81PAT{lLse}tC z+o_#kAh|HgMQABOfh3^%t}}htUD>Nfv}XZ&qBDa8@7X)4dlYI|-+N*>KdSm{&g$mp z=rGA)wQf}5uYd_&SI>$)r&*ykEBkmgERbAUp5t?x8ULs76`_;aUW7G*n}|J`MxGUQ z%oy(_sgDa-NP4+;-mq_Fk~D&=&6ZyzuRbyI4V4@Fb3>?Q*(7O@$dXUbtrak*52oeh zOlUIzO;#tfg?Zv8Y(HiVN>Ys2X80+ZPcWY80}|pPv2}8_nZYA9!;Wo|4Dz#N24J&E z5ts=Yv4s+`09UCqAuVi8)sFNZWHb=pQ57N9J~GOCBSPjIUIpcI0rMr8stan)&Y620 z)abvE<*TVns~;_v%fbjVEv;$CC94~8&d)q6Hn3UxpLg;GqZy~k@0_>n@@K*zf1A$- zv)^0S%~aG+pKxUVyxL+kUp0aZCyl4n&5Ul7Z=6Z<*udlqtWh%kQq613Ry?HMO@5=D)*UrV!>cP{3PE0&6MYd(>cmQXD( zCc77>mkZBhmZ2?num5K58f3H!va}IjB7d#>2>h+GO}0h}el(VFqKOZ$N_EwZZ3fpa zZ5zn=&MqX8CSxT)m2v=6QAT{#cd7Z>_m6L&^%kFv(*`K9zJ`z*ZNhXKi{DTYFGKC< zi3xNdEfkwA^B`N~-dL#>OXU(?U}{XX_@X!GNx1tt)8tuqlFBmA2W&8)qymWyzQbcG zNijq#y1eG&VEya8hM=@J`<1lGcQz6$ohEojVcI&>9V`Mv>dXtB5v{j&tz|s(|VM1G0j$!v+8!tLGj%i0dN(jI=I%>M694 zcA-lDSYa;c?Pcd zZSN9I1|_5itKbvEyCyAigHWFOC~pLYbhorGSex7~+sP3*#-{w-chopUN_vu5f=cOaldj3xDtyfNvdn}(ULEN$TG}V9 zRLWADry;Glvy2<^e|~1rQJ!~K<@Z-I@b341Z`!C}ysWdd)kbZ@<8OW^2$k3RPO-(h zvODED8Sgtv=w5_*E_v})1LcF4{jmz>zA}PAk0k9A`|fvMeYLavU4PR@nVI+R+nI$+ z@>pgqxWB~~$I|^yF}1w9c0m_aBSF3o)<4dLtb&_!>glMY;PRNwX6y2!PQ6zCH$ zEs)krW5+rHwbNGp;C_&0ddaW}3{*SGBNu3(bwE3S%!Yk7jVfkbL?6iO;J=Wvm_~h( z8aS-wvP~ERqTsL=(M(Skm9a=OYH>vi|1)Y(z|Xnua~IF6zFM2?LJY^!ePo$8ZNCfGk!R zziocU=&3Dzl{#zuqChIk$Kj#quG$CBaXMj``#<~cYmpU55~s&O__H`=zeK_8M(P;# z{uNKgq-GFG)Io&b6D0&Z(Z3%sD6!_VHK(b5qT3&6}luvmxJGPe2R>aNitR?jTfp%IHZl#1+!gr`&@9}s#=Km}zEjlU>P z$QVM;N_^3--S0eiphs1j9CEWa*KxWq1nSf*rxLRCo>5iz=iGmpe=FqcHKl=r!wzt{ zu!Z-|bmCGQI6bN6eivk_kr1>ROE3n`%Ob)|OtKP;$dOJ$k)*OsOtH?fpzy|mkFoD- z%8WGl|4P^|ffmCBxnxWNwTa9w52{q9tUQbu&s<_vhw;6lAI&JC--`ZJgAV_3r&`%1 zzM&+^ITt5{svM3RW?o!;fplKtUDCSTGgQADZqN$9NHC($tF)185*hj0d2M7{kY@g@ zv#K@rc~_l=#M=?#of^f*n(Kt>vfGCIoalSyUuEe`?)QaO#tr|kqO%Tb>iz%lh*1*8 zP`V`rX+}wR4YtuLC9r`=rywoN5hD~PjE(_AYJ`A-IC|tjN<~sqX;D9ZfBXHrf6le* zT<1B@bKdvselak_Kq{O2s?GmB8hEFWYcG@~Dvs6gpbn69L9k&d&Zu)dJTS7JW>*_w z%0(78Mx_JaE>;7hz zS7)TE*Xc`sUZy4W)wt-qjH=IRG>)DVVG59{RB{$!VyICNdyxt;f)Jm*VkA6xQRCbq zkSyzkGJC*5Wa3dux}0mLUk80C+?Dpf1beY!d}1!j>Qc=_ zV17KKcVRMLFwOKy>!%d;$_UJ(^lUVqOQeVQW3x@Y62GRoaFpro8!2h@Z*8s z(G?5dCoidKggp02HaM zshClqUZD6R6hL1d(YFyja}8?*Rt7XkLX+&=6mz7-xk?$s%Tv@r&j|o+6P3A0MVq_u z<Is}AX`(;ew-1Nid{kZ75MjKljCz=g7 z*x}%2^C$;|&4$T6;enMYQ9R4|dJj}qN*w#0)FQ1b-=zi9LEK+PT8IttQJ~lOtUvdu z2MVYZtf1NT-4c{mWnBqIN{RD^;A9js_JUe>EF#A*KOY2F?%GK;WOeM%GJ2?XJ*U4%1fd+ccixJSzgiXm%%NS z3AN}1h#7FiPOF*>IZQMB+-j5gR8?tYUmDo*R(8}a2HTBryB;dHsQLV)l)oV&+FxJO zF)tKgUn(eB7hZuZF^F&`BG()hcsL>Lz&ey zuO9wugtipMRnI~+O?5;c;@j!wOVd{8@;9KjUu>=hS-P1pR6~NyN7=-IP%a5kf_xdL zdxdC~Nuo5@XhW4vZLJsBb?y_y2#QryG%+_Y3bG1l`!+eB3Lt2r8zzY@(&GVC%i9c1 zdu7Te-yvs2lF?Yiz+-I=^DZZ&aesC{eQx;FH5Vv#@8dk(+EtS;iXlT)n+XG>TpMQ( z=484#g#r;xsS3x`jz9ji;xvDDg&jCfM=i=d+k}>&WlreKJv}h3>#dE>0Qt*q20A}l zqI2VLrd;a(rm=*gJX5{T%VdNPbpo}evZM!BNJ;eJjPXaY3>h);_uagv6#zcxotT8<<-vwqDQ9v4dK5T8zQmZ;CKo z%W1t^W4Ue z3feDH^N=w!FUWsxumd|Rj|fW0mXfFi^;$h7`uBgrkf2vhU3i1e>cfu;D5=_rF*n2K z{6@m-qBDsr*L9>lRhfrWZqunEx<-Uh9BiMI3%R%OBBlX1SeWYS0_UPFO* z$|9b-QoXhOz`M?FLS%klPilk=$X!9?$H&`wQ02Df3S?P{Xn^L-TD*GIa)K@pR8Tbp zif45846B)SApqoObA?l-q{c2%0FEQ;I7B%vn&pWB3BVdzO_yX%Qt0LZ#5^5P5j2lf z=Yv3SLAnfjph3`TWf)nQFQSxDGzjI#-d4;er49njt(EjuH~9Yt!nX3i?&R$x161W_ znhae#q7Srqd6vJ7*U-0xWjyi&Ne8Nn=J-7vSZyarK{J|*)<2-cpnBgGq$?j=z)Os%r$HL#z_xJZSLv3SAR85@Cj z5&KJm5{f=X-xf&|xwnK4xYmd;|7b+CxW%4K_d~w9~hr_oS zkF-a9-e)32+GGfzhG{I=7h-zbwikWgZuHH*Jd*2djc6{Nxma7MCXjb&W~T&fp~>j_ zJv&1Ym@C`(1D#Q!!>U6r3r+Ux7=mm^ZYnA`2b98COHt}Z;~uU?xifXd&TXxE;)i%E zTTJ|((F-H-1V(V(tZ@ZSnlcm5E~Ds|%@Bfpshm~?xPgYr<6~+m5ka;V!5Z73137nb zJd=c0$)+8=P19H17S$`L2N!mwu{VH!B)wD@MWw>2A>PLr6u%--zY8XZ_^xV~HvsEa zY}>zeQ|+>D!|j^WZiby*5^8nUJJF-qZ`1=KktbmX+BEAB^R~_;xPJ%}S&` z-bh@Zpg)rxo&?|M3NV&-oB@}l&nKRkTBNwPadd4l|&=n(sa7cK@hyP75TuCrH%JO zo;y~GH@;NR77c**Q-b>6+TFaU+*hzt?u+z?N12dIoC`v$t&)aI=?#u&E|iCVuT}ma z1C*)Go2}P>sc1GyF2;7IfC(t4UjAxFmyINV%i9k!RxhPruac$r*|VT3z|k|IRa&u# zcU#$jZGsA3uafHF<~8pj-oE2?CmyG(Oyk8TNmkOD-w6K=)xC|WmWz^9NWhhBqwr5| zS1NXE-9x&?H!M(dv^2P$-&hmIYIZ+kUSfOaiF*c&Jsy4Zi=uXeyUIt1*4ld7sPD~V z)>iXoZdlRe=QR`D-27L@ z#3U6OM+JJ4)zt|MaQi-6=bKYBH+45oj7IX>G`JiU>2{^V8vd9FhvVkTxa-qjh(S?> zE@1}fS<32MxryQl7QSOcJ=MdF5%H)laF-w16FwREahr~U zN;UDx!w2+Ap90-GnBRv8Aiiv?lAJto47`P=lT~IN&(!zKLN{8_|3KL;gAr+JK1sD;KUMr|Xf#m|*P}g%eA3$}a$d%^NIuGXQ8eZw;0dAt*h&7C93vZuq;gCzqKK}eWVD*y^c$6x(eJ)ad#sHwmCmQDa&F;z6~#r@ zE3t^v*V9Bg625>Z=mewv*{<3fkwrKi`qXR7Sf_u=$L{*B4Sm^zx^rOYU%=bls9uQ# zC`p*+xr)B9I!n+<%_yd#A!q`y#6=yQcxuCi-TRF&b` z{ux=sr~d;q4!`25`uJV7et1YQ{Y}~Z2r0(0H&>2~;+sF+EeFJl-Fbi5p)=n;a5(Nq zxHcX^Rqxn*QAS6qEM?k>??zMo;{sM-Rw&>*_`phwsNK0ulxO#)*_D^-{eCYoo_fv( zsUm_bJ&UGjlS+_WGjdYYc{+fG#Fp4Ijf<*`yBW{Z9Ym7iqd09R#qKgo=(E-6RJ&KpOTekkZ|741j{|@cJG7x9V zB4Y62UMss7xeiy)>tv}7wh5+flKfWc#x5ws>mt{Yq2|}XHK%+~&cT-TDkEXMQ(fBx zKwbHD)3o#2{a%^tzc+$I$PeB=%|*|4t19w!zVOJHKt|l8CNTywFT}2jpWw z+I`#)w09wz zC=WCW6UzoEpu4#Tr6%Q#(Hbj8M}a03JQ^9ZNmq3 zJTk+9D@Vu{Jl6{-e`k3rA0Ze_RE&*wrT-S8YUCI~Oe=jx`fIto8^&q);NJW@c}k^~ zq9Amj6nYy(GdFVMaHSO6%A%@-jzxZ`GK)_Vug}}?Z=BAo^qQ*G9p+TPiZP0p#t=Ur z<3)0H4cp0Euf$H4N;X%Eifp%=`He)2(77Zg&sTuJU_^@Zw{{}P4=4Ch~j|sGBOMkQmzP4`T+ivpzQjwrmNvqATwCBh;=>#@6%zg z{noB?q$fd|^9u~OhVd`d1)gMX6^bOA;PD* zn%I^l($Y+ar=JdNx+N>Ljw)>IspbBVV*=+?98^8!?-~Kgy-aqJaB!MB@3K< zemk&BLGk^!BEczaU2t1=oeT*lA)O!0RJ$CnL~`y-ukbL>(dhxg!WnlSBW!iF(Kd=!RI3!9e^?#i5jYUruS*xlVsr`EN52TC|?Y$jxXZ zK|IB_1ycZq>>9HPlb|26G~41O`E<$LrA$9fcN`l0GsbsaJ%q<@?7-EESXp65UH!l` z?dClL+WZe<5q9N#wH`F*2j=fXp^t#B+dm@8*zM!_qAK|8rZd?kY1;DEcPzD_)UFn? zV!SWSWhE$~vyu$ZQBFQ0D;H5?P)t^W^XQp`5(40^vfAewPn7Wln~<<_*H)6n@$V^M z+PfbTs2IiV%z|o@jIIM~zztot312>(6qkE5mJ`)MWugSB@#4%ag5h_EH_Den#@zf? zv|W~0qXm4AkCm{PG8R*3^k82EZM@1~*}(QMlCy=sqeeN_g8uW{6>Cd1z1otLt@Ka| zA>w!z)hwubV(eoEKp^1G*j{gPwnV3AahTxd$n;D9G|KjOw zpMVWUajCsFA70(_E&}D|pS=+&6i{2eG2u7$R4GoR4RBSBCaY1pirrr;XQy^`sjeiJ z{q(BuMrcEAm^eM-MvQ&3gY9^anl>qN*9?~>V|XCxm_B6w;rUDTGXmmy;Waw-11I}+ z*4Pjme3kZd^990t~%m{!t6?~U!0GAnd=T%y=)GK<05}1Lo zFtV*#!3Fbiho_@jjh`pqC)+T=(a1(0J6E6i)?DQmcYLKv6m6ce?0|wCqp2LHp+uMG ze=^Y;K?{Wel6)t2QvD=x^%~UlRZDgtO_Py0HL+eTLh(_#4bS+wQ18jw_HpX49E$*9 z`b#^MuWRw~@lXeXsZ{%yA+j=n>-&Av5(pVXmEg*I;QRpa^p(*n{9RFidPtT;R z<*j@_xa@`e1~&Izo??#DOzpa)=`Rn3NrE)GF@`duUlm1PM2QrFHVt21ki|cRZ8k|= zLXbwfqf#_hgT_;6q-lA&LO#UG#Z&>;sq$d$dUDa(jxMv98!OEa(Wn(|*YMhbv36JL zj~?%Hb0ZP-dCI#-Iw@AHI9D2NO*l@0Y#{dRqk1XuYtIJ76O_;tG*hKp70BS*G`x7l zlMh}3PW!|szlzOb)S?_6V9c)#<8!Y58Z%|!6*O;6bq&GdxsI0w^PMLga-@V6waMKW z>u*CM^=87X!3ehDEPA45O8TP0@RJE_OC3jH^I7e`>G$-EU97dM$k;xP)c@H) z)38|ac#(?~&3q27x>;yND3?h1J!@3yRg|MNMQ0z5b+?PlJ2c~1goJ{J2#SvJU`AAH z+fibOsRwJ9sCWTqPhWi-aQ&TnHMb*rj+DXKX=~Y;9yjV31|9EhF}Igo+_nEYYh*apOPLy-uvSB}oY#49Zt`rpHCv^O z=WE5MYp++li+pK1PpO$Gyu1w{#Ps_xlSsTM)jRQgset*1UIi$$l=DdfqM<@i{V}L%Q8iz=Ym+e#X6Q#*f_ywhYnlvS!LM8Ag?%X zZ5sK`5aHsak+@u;U00I2dA*IMTXn|fnfd(tj;pS&Bs3$ z^g06Y_H;3OuEcqM&TzvOn#nli{7Bi;c$1mVH%xo)-QMNQdtXL87Ahe`Ll#A-xf62a zLfRkow&=FH5F=*4=oax$-=6bF&qbO{{EfhS6YY6(H{B;WLG<-}XlzO~03OH@1c7&?ood{lh8=cw;WU zqc1I3<#chBs&mQ(n2-l<(3U-~rT-}tWHUyBsWJyxGAVD?W>d=B46omH&bu3(V#d&5 ztOxq2#B1f4azav|cz(eqR|M(4=%*U zH}%0P;vo>JGdvxvnS)Uq5zV7(B+3KGcT6D51xsJuKtnTQAaqnU@9}Kwp4GE%1G;Uxm2AiGwRN^C`9GVv2Ob+e?M-BW5t=(!uOj0Ja*yc4z4|){=ZPP!e_QWsFuV z`Ukqh>M{JJz>cdLQiHQ8tuoQPU`3^a01;P}2uCr>9-DXhdVFxtxC*pL)jm6d%W2cgtkV-v|npRAQLd5G40+w-Ii7sKM^Z!^cFyk7Zy!m;@{=ld&{k`O9p%}-^elL%3((oTt@Bb zf7CzZ_k|XrUZcIEz>SO_KN&wpT&@X$JWq5cx-V~y*=;wCypg5UoV+;{d*q*pKX+sWb%4*W5O({3_F>8nso)S39AN zysu<57Z#I(8k{$CL~pPHw9T|w_LZNdI*j5N7+ML)5pVS}IvcB1WB@^f~#-ZAYnqMV$@%;3A%B zzpj*A7t#ET-=$gtA^!m(bT|aye}L#`JC@L)nIcUn0Ge7A?7D%qmb{k-NcMi6*|r}- z2KAwnjHOmtTp{!^vG{%^8xmC?%RocY$fGj>#VZ`2S7QSwDbVOCdhyqph|S=SEUK#z z`es#7!dHUmn^N#uW%AP%3V8@b<7YXGJM&r?W;qWZjLY}?qqwW62k?CN4Mon35}6ou z<8ZhBWBBn|gMYMlxw*r1MdWBk?*{qyEPwxroG?22*7j+&DvD}B%o?@{rqTK4)W0C$ zIP>Dw;LH%H$Y-T7T4w*B*a@Oslr;YM5`_shTT~lTzWZ;qL&autEEw@&^SN-^J&JSq ziYvus`A95Q`ar3G?@s~-j{D*`!6PmRuNSo~2DA4?)1h+zc&xHMk=P^O!hTN}e6dLU zRrt&QzX6Mkfy4Rd=i}SIVE^eVKZoYE>)M{`nJ9P1iH7ckzWVk*0R8mOl!~!686Qb~ zamU=*tp5S-BcAH7g!wAXj)4X9EmpaCVv#Z|ugk?%d(Vw$7Wh|>R=G8Gy!6@m<%8r^mg363y6JWXsmm3_)oI12 zL*g|67L)=>M|tK7`yHS{hNys4Az9wkuc!!iU)q>tI7ARv$nmJ};+Hn#DU%@RPCI*v z@$^$@80j61#F-kjt;~3zBki1d3<)00Xw1TVPw*pS8ie6x3BW1hbrLmy3Q(TI+IY@Jl=if+1cjY?9$)ChV}!RNd6+{PgjyhSY2${5wh zuktOEifCYOBsz#%ohJ$(=tdgmD0hW}o$n9uNxHHOzV&<6t!Vx~fKmv_dpkBmlzl4? zOO@N-wCx7>?NFNn2G^nm=C0FZMu`)+l99JQ5q!eQ*G=c!It*ctm(w{zuL6A*d*U9l zz2plc&}X1FP6-vwMIAS8XYtL>e}VM>qMMpa^Msi2{hmwOfsdLfSf)Gz^JSL5&ZzIJ zeX}8dUpE^)BHS-9Cuf1@8i;^GDa7UnYuaPk>gRQsan5sr&mqo2=PGO;C1LGfVv$a! z!6{((B%8$^JY6=jQf_(_kKXtx12Go0i@{dm743Pm753nVW!HlpL^*}jhqd^&s{BD) zbsvlVVu-D@$=Mt=BE$nR#0`2Mx*sfoj#HSS7 z+{&R%G>Utz;6R?_|BK{Fvi;6>X$#`^!%SUNLFa=u*WF>48}; zzW+4s_g~)CdK*`NMPw|1NBx2?fS>6vQ_Vxa`KzxS-ew6gi!KBQYw|@@ZsbsENiFNn z)!6pqx?0D0lrem0Y~ddtOzlGIk&n#EinPDxH~-_<`W)(mv^#M=Fxu`lkZx=t@W&|X z^F>-f4;ZNhEifvipow{B;>kM3CjE)T*bW>mkCK^i<8v|S}FWBx~f zBR3w1u&Da%ym+M$iu5VlbE*7lfU~o($eX5pQ(Eh#9>Au)3GS-~n2}9~Xrn_b0@h;e z2GvxjuH0B)NA5>I8o58inWE6G$p5}dd}i0xZL_5dcT_OUm>tDQC(IhVXT7>)a6?+X za1yW%h?xTdQ+@5;^-B^fMEC>{pHq~74(53ZoR0A0+QRq|ib^DI+IUbj7Ftvi9q?1Z z>O_YJ5T`M7AarsGi}F~2tDoa@zHHgkczDF+0Sbpev==4o4Z76v~$mp zU>gO%#jg|SWT+vz_f<9<90Z}{m??Uf32^Ptj~gtln|FJ4+@O7>EbpM#epp{?kHYuS zX0+(uHlj4=!p3l#KS23hU*X`aQHJzeA$9e$ zVJB-8UDnLoC#>Y`tJ%TD^(KzZ7WGng)&N__bE+Udo+tvehN5?l?t?w@4po*1`6 zAsQ)Kup``=txG1+L!7Hov-n)jIAo?_2=1w);+&PBe?uHf24g)=D|eA8?&C;B#CT+F zD;XfelWLHnBCItR<-$;H$+WOdke_YFLgb}wO%o_ng zu_8P*N0G?XaQjk@alTzdN7m4BBfUK^$jV-5tx$yPd0>tF*gC_ z-Y}Z!(t=bbB^d_O{eY%8a2hJSKC)qFs_v0RXCk|T**Q367u4?f@S&o!#~^nK_pBWT zVxX2hccjmiyMy}6m_(|UF?wQD*6r?twk=DF6^2^4uH`ltJEXkn57qM+1g|9`5{{)p nNVl%>6%lL;SbF}>nE`w;ts*xCAho0`v!Lno*=>99fG@iaCdi4a0woQli+vBm;ZeKbB{dt z++KR>otmods_GGzcX;{wvIRhslaiGJKtMnMWWXQ5%Qgvyq`S2R03a(%4}b#z0Ehro z2*^Ju0lbF>#_(X74(=EbPyh(9eC_xUFn?qr7!&-(m0(Q!*9H=dS;4-@VA%lfY+#H9 zmVMxk3Hk3h)}hdU##sXEslxujVo>0Dp#cCFV|y33_m%*4MJ8!pb`~kXYruc3|0AVk z6;(*t-mjg;mu z&IMyY91sAW8~`4S1uE{Js5QVw(0{QN7(>MWV*~M;Ndm&3m_C8^kO}|H6$HjmfAvwX zzJGBN7{mOv$pm9y!oM-V|HZE%ApEr{1lxQ{00K2X_Q;XJcXIeO(9^PEuBOJ`NT>PPYH0?jG!D2DVQF z_gAU?SAxZ#asHz({A&jU&-8C*kl^)tof$w10YLf>2JfPQ>+`AyfxF0m=~e#XKR$oY zSFp+dvaztSa=e}k|8B)u*%TDy#8`RM6-obK1#uQuX+?0luh$6#cx-ST!D|HpfCPU4 z0QJ{>a3rrKY5;Gb{^}*c`_O;&6JY&otbZZ`>tX*!{vE6b{v8_SlK8I#5A{b+`&Y93mH)06;PpI%_*+--5D5BV2Izn)6q2KVRl^51u+*U-Q-zN`Yo z0dTOeKv)y;cee5*i8y=5@g!ykBn@(C9E2WUQjF zn5xD=awjY{|M)yO3bDFgY_-{QN_G?H0C)tPH@JBCRMa%Ibo3mYT--doeBu(4QqnTA za_SnITG~3gAX77Q3rj0&8y8o%4+2sF92y=O9h;k9SX^5E`fX)1{0Qz)=+H1^tgslOsz75WOma4VI4rUFyt-a^3U;+~ zY!l~M1RP3^ZK{jc)c$1l|1GhA|6iH?kHr4XYXyJ=1->HDq0j-sfSX4(etJ4fGLfH( zPN`j-BD&;m(}m(rk0+1^23_qmHmB1UGT(%g&DduSmh85Gs2wrm&z$~VyE>*YCbR@k zIhikjU?&ChR^hG|58k6p)Ul+YxH^$s)0H5@fctzN#U)fKH(9E-g=hYw>vjoZ_QR)p6Xt;i2#UI+tOsT~5;1qOtJ4D#ETM?z=NP z$jNqj^aa2aPJG=rEMrPh9)E+?k6T&Vq3A61TZ{O{Mi`yK`@v0E4#s3UsVkYFCy20= z_qGUsF_9#lTqv3OHstdzwO9_w$YR?3z3*Ox?jrTT^No z${?FA*Ic{|DYO78&bqGw?Lv+YP@)1MNqZzKLI{^E(nkwIOk7yB^B*Yz4jLP$7$3d> z^cI>aFhYn1#ovERCE37c`ZnOi-9)c~tS+bIscCf3$g7t)sS^oES6sxkVNVCtVVYmJ&kzF@#)IVsxHdaA&+D# zA1dM=^T>6bf~}jQkXizCij$;mE%ItqKm$nSo#Piuu!IRcE!@ zqL?Hu!w3;A0mqquyn{m67i}Zcl}Z^d8RTQQN4($z+5H))%z6BJ`4xqiS`Jfh$#~yn}ChH$F$SSnM^m z-W*yx0#&3JEblZ!L|4)p_Wj7M7DJJ8pRA=n7h2LlC7!4UO;cw|V?hXJ7jRbi9E%BR zTnh)g;-pV@Y%%VR`l^oQoL8$1;W~*}M#dCuq}xMmLiCUZpo;OrW-`RqEtWJ2wQ$M9nlL zAqE|E$~$=`4AuQGI#zO-`!Z)pFX_|5TUMCDTVxr_FFQ?vRY|V@ob&=2kTVgS7nZ#IA=d1m0Sek!pw24u+tw%8tFImqRRr4=5oZ{}}B}{Et%2EYz z$D^pGiPC$Qw%{}~^J0C&^{^}wCI1ptR{n;&kCrI>5c!R$X}|*HQ`fE$z$26-OLI_> zjG2PDlU03u!*;jp}m;{0#{X$;cG;yF%ex! z6$|-g(uE>2rF8Z7p^Xn6uG2J!U#n@A9_T#bQ|GRaq$^k3V9^Z3>PR9H?zvA$%W(9& zIQE#N_bI|s#81{6Jua)^yBvGec{JH{V}mjL3sJSWC=F!2J83aCl0CT+Bm2dKG08gI z0{B@do->fyd~=l<)8oplF^}`^23fR_i(L|BIcErm)Vs=`AGA5`_NpmJP7w|rXkr-N zL}vn>E(13bpp#W}yB)1FN_8G2XN49MoA zA5{gcTZ&2WM())b{f-tiB2_~rkB^0lGbxqN${uYb1PBS|_TxUS^WLj%-K*n%rqpKL z2?OB@{Qiyfq2;-8eo3htEmfuk+7hw-ve@rxtG^Q%-#Z9E@|6P|MAX60W#UJv00m|s zHnKLd8qlTfR3PRv)fH@{yk^ts!h(|mBSg=%Q0Bbm@!045$a_v@dN8llo03jNhIw;Q zRG5Tu_j59{Vczz5a8jV-64UDkm$gDBDbPYnXsTzbM|~EiD@}dtm7YxYa{+=}M$c;@ zkBxVyU7}`zZP$L%l z4&KOMCM_Q2PFK+RU`HEjNY(XIj~v?^+kLj}KoHlt3l5Hu%qJ-UVw+*#!<1 zU(TVTc7>Arl!XY(M-{+Bgr-fhp@%Ns_Ew-%S!@1LR^XOpno;i40FtzVR^Uc&sqQ5H z`5xSgPx7cvB2jP~ak-ynOA#G;3r}wz+H3%DLfVrxLKfG-gg;SHO|}Y-Xl5?f)6i3~ z0nl+k5us(Ljz}DmN_w3OGv%ooAe8iZRSv~EjL(}+nmDO-C*A!>1l6R_l*k4rEGBb4 zd~_1}B5DT6F(~EKQ#yXHMxP?ct|pC<(|M;66-DRLQ>L{Vm7YW&+s3MNy5t8pw85v5 zRhJ%_xKbnn_Bisr^-`y3e9XL3zU&>+5nG9#Dc-0w?G_z2r|Q z)e7_Uvy5}$(1qet0WShSgl1*KsKMT+9!L}=+a}gfJr-y!%^%?o{9@tbw7l2*L2P<3 zu>eP)sBWr|nX&oG#=ECEucasqj|%+Qj(6CwHSjrVI-f>%B~_zO{pi-vKhKXyBTv^9 zsU?Ux1C4xPAy?jK)_s#m*@K62K#cXQDgNzz#Ay|jhff$c5d%kFd{nEZP=*zYl@~u& z%L^1_kXN|~yo;AZP}oa6OM62 z+X(}#z7S1I&3DLJdt#eCEtHhf1pZ!H5(U)AU20@$geZkJJLyx$@6g#dRU}dZqlgQR z6jDAy!~mhNa<5KR-mMKgK~BOWMb9kUP19h(=|OtVK}4_)X-8-tgpfo7-tzCq_~I*t zt|S& z7a9pwE(B_yRj{Y9EyI2s;wuCwO{cO}CUlR|n_)dynL)lj=td_A{kL|6Ze2@f08z&% zdCk7)WKw>AmbO$C1$ zvWTA!W&3%tGW81>4CAF8-@d+oJK=F%MW-i;Nw~EeVU3tFt;SzPKdv)ZP1YJrn1=y7 zgbUT%`&cpASc5cK^gcmg)IJ**Mf=2{#O!MuoX-!x0w3Wg&mu-&PhK>Z?`*ZDA<0xE zY2KIu1qw3RHyGwrhI@q9g3;EWiPu+X%=wjgiW2zEFBl@-d;HCMpo)E;+}`Fs>+f3P znoqu`b~V7x~XPSCk1ilgCh8wvY`sF?0&Q1r*BA39>8Wooy5l za&x`~s<`JubVeQh?@RZf!zIml5YG&_t8m4O3M!~UI}+(bQf#A6Yh{MK^RZ4 zlir*POT*;*HM=ZHf7CqQDB*lSwqtSX2vdMf5G(9il?(;InaxH7%aH|jF3v4igohHs zU+I0|!o28pQSX!$RKi8349sqMWEG@kCU*b=uo40Bb;m>MCn>83gT0ijww=`lYtL1lA0d3aY2^pw@lm$9ZQHT zv11C3A035<8i0LImB!xk?_E#E>V4*KW6z!u`*RxpTq-2 z-O=`ww>bHy%cVe(&#zDS+FoV9Bgf_~RJQ8LRHQpS=GYk{zEaYy$LhI=m+ln^3UtHc z%c+C1x@sy)LK`wX@R`|v=88D2l!M#@HZ>a`#K*CaC!F5BS*NJ$nPTm!W*!it^mgp2 zLQRS{JDqa2Sq}VRaHaO}j+)HRDaT-O8TathqV1Ss^+6#6wo!iovQD>(C5FF0edr5- zWT}*a&~2wGz_J#P*XkX~Ipzys8GI9!w3aet?oeGB&af3D&{sPgi~^28Ew!FCvCEQu zpu8qrwk>rB{d|7b6&TqK{u<|!c&A19jJU9kq)HLT?D&||*Nkr4%VY0Yce2ODFf$7M zanfTmxT^Zp?engsHUf+%Ed}mPZhWCBC&I>XXCiQKYca%tXNn=agW2}O9BW^8 zNnPQ3NR0nm^r0D#>yq7S1_Xjb1GA}p1+&wW^woC{I%3}C?Dp-^iDsCGPER%-b8FS_ z!bD5niuU4Gq&9;ztCC1MqZE0cR^C&s3SNv3ik}H z7?}M6kOPGI(XOF*&Yf-%9;_r$pBak~{)#xA^MbqFBKoSAWApvm9^*lEsjA8d*V5^# z?4h8wdU$Y_{7^v*$8i_<&~?*%-mV~XebAjOugHL{C79%Ub3$LQ63fn2q`V?4aV<|k z+0Yn6d0^w8W9Zr3?SMQe^#zSjWuVbRVELn^vl#+sA>3mg@=^8EJUat<@(v0S^=CX(qCR%d*C9fc{asM)Oi)<)v6~ z$CsArDo@VFHLf2MU%&1OM>}t@T@->Wk~y48&dk(GJ7uS_9Y3w)KR5C@ImQf!O_z$g zVkz5Uhq|3TR&<;dh-4B40yo15T7rR%KFr4clXAJe^|A&sFs;?Sn8 zlUpTnmqk_1%a`}q-rF%LDWDz88Oq0eU|TD0%V%Sq^Izu3ebWP244$vv-zV_U_fBcF zXBs8nkj5)-PPtf<((seTu5QzfrT%#g2mB?wwi#E%RP+u~i?=#wacb}}lryphIi)L@ zwtjlDbG>K_9#O7!i*&Sld7z1VWkO4B7*6JS3X0$*WL@Ul+j7R=V~k@utk<|4 zMPdbuBTLw7e76BZ$BMPb<%HL|1#~&X@haonPhuFlJH&?8SU=T&M>KJ8&wVp(PsjVo z_cIKQ^;+=wsp@pH+*y!vUDd**H@|k4Y=RTqZR`p^K77_n*$qwRqobbf28QA{jSz z3@g;QX$3N|ZnMLgtyxo{&yFo*YiY@Hd;#>K+8n9SBOzR|YPROk3kop3!Jg=mK2b)W z|A-@?F~U==5z`*m!l3){BQyi@3xK(%$Vy*-7{yr{d(5^ii5%Aa;UKDPzcI> z5H#TAOFSXc>X^OzFjp|xGxFt?&OTOAAUSF#%P+IT&IOh0}ZjO{kPZjMV z78&dmM@Du7@8+qaiDY(pN?3V?l6r(ASN!p~S3Z4IgDw<$J zdM|AdP4EIx)i)+O#>7Y+70sOCpiciHjZhggb&z7gOWgo3lx!fJSR$7uW14w$Ok2xJ z;K#alB{jL0y#}H7gI<}ati5&1hhu=ISx!Mc0v7LJBUBT>7Q5s}VYQw~A3cyA(B@4e z_f7+23`)-TVr6R9Uf`(X78>SAAF~SUp_6Uyb@) zL4rjxEAH0)GJ-b$YMu320=s68?g)KJvr=-bw+o{}X^yWTee&Kzd9az7w^nl$(poqt zvg+pqS&F%qX^fMjlD>@4G{($Ik3&Jl_oKm5Em>Wfc%wfUCOPenm(LvQtNG~f5l)Jr zr$F^z*g1*7Pf@#Rvafukhx83LAp&utH&?<$lNwW7>Dh z6a-H2t0b&@RD5W2t|t+8#ND+nS?z%?@0A}yoj`m1TAe6;A$)803<81H`*_5i(2#(w z#l2Re*9`0>9x@}N`vFov3(qt@V@|-FGjgR82VdqybitvD>S8FPer@H|zY5+&}N$HLh zXoRe0+)Ebk_8BPIVL9VZnfR!Pjk3cxxmjO-c;W-NVXr4S{jPaRXnXQ9h`JG=CCSzV zkFuoT4wedeXn0Fk`AZ>Yce_1P9o(?tMvO!z^&TjD#nD)-x#H!Re)zt81H9}&*2;>D z8>*-&OUWuog1Ij+Z~$i;;q97*gOqn4UudlVPv`3S(0jM^P0O zh5wL2|FgVZ`a`+_=9yl{`k#;gA2rBk<}RjS5{VRSC1UF6>3b@dv!F0oVrI{;jQx z1v}dx6$FwPm{r|)dAXtjv#5yxz*F4I%R}DF%Tqp>w_F1Ndfxx*?~n@s@Z5m)asTQl za{vI;AON6g;9s2ym|ATP1psirIT||~|Ct90yoIy?zd>1#0j`z8B$(w+2LPxo!DH+FZ}NVn`2R=U{*N|)>-UE%{SRmNM?ykELB2L< zFaZe#0}b;^LB4X6urM${SZHWicrZ=*+F)Se5x~sq>&_pp6zu%!1^$5pd;Kx_zuLU? zfw@wM6UbpG2ry0fAFdS4J3~OfvWl;z_|u@lQNcn0;Q;UmV9t>ceB>X}@ju63DaAir z>dRl|4h;$oJjng8-J{*%Sc%^kyYsl@>eW=0*I7O`_4;y&g#wYd=3nbFFp*GFFb`^x zhM06$dp(H)W|MWLQ>{OsB_UQvuXv+z8iDqp%3+tQcdas}4kvF@spiVbj4;x$5Hw_6 zsM{&wO#P6<-$o`+O9sgCdRCPoZ|A)$YA)kHNDHlRpK)~FiwG#pla3`8@T4dg5;r6k zaK8vznypk9N$KFsY%H!<4h#-a18Gu(R$H2&A}IQ$N@GBg!$?p< zVjuYc=4Dcv+>R0C7%apB`jV5iG*TtQF$eNkloRs`4nnNi&hLw)>Pu~@AV=azU1ah7 zmZ%EPb)0Y|anbBNV<&BnqffqN?;OEc%d`jrftAj30a4@q$-L@XY@7kDd7_i_1HhKUN>`6qQ$|$@P7Z^$FX8o=Y&ctHfMteO%ZTqSeN6fNicW1OaxP5 zrcc72$o4^LR4kU5uxu>74#$0mBz3VBo?7K|Jsc)gVeQ27+vug5HO2Bv0VHZ;QMCbd zByl#4!Xm!;?W_he%i`HvF$0VEJ+0ufM2GY`^@$h+jC6IGmWEMW!?M_UvyV6y!*GeI z(FigtiMy8qj+7xZPzr&lv3_Em64#k?j5sp-E*%b$OCI>bO2X#|pSDlil6>?C~#ORo!_tEGsz$}*%eJ_4Y>j8b4Z)}WMyS0BGMB-6F0kM zLfNBAt)QW=EmZt`8d+4x%Qzq&=OhHa9C!E6Lh}n%&QB3b?W#VM7QBgwsa=mbQ75m= zCL+W!vXi;+>-Sk&3hV0bxD-6dVCGZSEkYZs(qlQtFpFmeOk8j=QQUs5^ z>!?mr7jcPWTc*uO8K+C}X+0qd84eH2OeK%Ps5fXNfx`?xaGO7Oa=D5kx4}Th!(^CA zNWe^W_W&53Zx*lO9B^exSFho2zw)3n89rAvsR=1PIQrYnP9eoCKIE#Z%E@jvLYBK0 z^iG7l)4gz#b14F=@j`|^biPgdhd!g@ig)7+KmgOnfUfjGSD{}kHlt+hLW(ZPsQnRt3EtG5{zx7={LZwTfKrqoRf$7gtQ!3eBzbhBvdQSS$&rfVTh}AAQ4zT4jN0 zH9JL`w+r~o%k+2UIz;|`1BgVaLD~6YRo(A?AdEL=?rZK>(Nzo-$D^Bb_=lJsjxL>V zUO*oy8<0{M2FTAu&~qy+^)g5~G!$jv12q)NEQycs<#bw4lHAX8jhyN(jHQD|+hGW? zxTJgV6O=J76H+EN_%M#LR6%l*{WKE}B(e~s;S*+iN-h)Y?}*!E3|y-lZ??G#zI>4J zhZ+(i3pbj019iB{IXA63%RHD8k;z@0oL-yPqsC)~wTkhLE7Wazxww4VH-^sj0%$s? zPvRO0>rq@=_uclcdD4sY+Ve*=9*dc~N}Py4)SUBHEDAiPhPPNaKGiliJU-X3yw@*@ z!S4_(cMiM9Ab1G;s5SpIs-5>bN7nW7C%AQ0?6~oXGZ+3x!oa=HW}XFyt98XL>8H7O z_#zq3I1wOG=n!gAn1Q%R#gylWv@T_aDc!TnWHwkaarpVuhF*|MJGPYqs3xSFyGUtf zaDxa60ToTa3>wYq(?{u81Ry~fr+~Xv2%!9Z*`)N3)%&3rKvHlH^`}Xd#JGEPJZXeU zW<(3n2?tSbr1*;Js09i#bWli;tT;uI++vGuQF*ksIsFOTHkJ6dQAd`zq#xAt=AYLv z(l<~yDNH)fve%+913FaYT7BzJv+_DUR@3R;YAtMd`#8p>6SPA{MUt>k%G8Sb$McCF zd7$C~%gU47Dd8faalhD%Mod(_^R?RU(oYi=&-XJL@<>B&XHo{5sr(Ec(P7ksOWZa# z{W2g3U(U_x+NfG_s_)`?N=rZ`N-hEUSpb9*Q@MgDG0~D zKh#y_PTb4E?X(Z`83xN;#=U?7Q|DpED3Hzrie?Bss0yW!KDg8wSCh#oQf|WK(PpGK zC@z$A!((gJ9PK*7A0G?JOo1rTUm_?K5|Tcyz*Spb64bT0{Hw;O@2yDhS3*pn*&2|= zfPvqqtPnTVgeY+9(t!+3s<@{BbZk1HU)(gD_|rlB7ax}p2Lg|oNN!!8y4G1vf}g0V zNn&81GV)^jX9!@GemtKD9*N(74=n#*?Tzr=3>np8VI5` z{}8~WX2PYh)Gy-;wL~v5QRYi5r9d+rYpbUalI>d`!^e&(UK0En&1lpgsvrb7O)S1# zZGkTqPAbO9nvWKjREA89VazMd=yJmm7#vBA!9mX+2Tx3bjEIOst$H4XL@mpDUud)G z+Sx@Tmk}_Thh+J7$&4O>Ov){FA4%J0f+Q0&N!Y^da_rsfZ$a)fAS$by(&pH#PTtTD zNC<>jl(O3tyZOPf*{q)J99Cj7;;`z3A#-E6N-8}%_mUz<`@}x+D!K6&z4H+9X>8Oe z`WLzrk>--sCermG z@-pNUngRnx(fem%CvkXTMpaxXlPIZZ07L!*asr-_`ufzZ7kvEM6Z+{|18Xzo^{SLl z1oSm6k5|itbM{8*{a^GC*bVXI=GG4jt7zq{aRcFDulhS%jyhohpWy^Z9qm*uNNJ6F z<0BW@4G~z}K^U}`YHWTG^NF;i-<5naVuaMt~hEsnshXN9mTB;pb;jG?FJEWZx zBc8^o4^e}ymOUO%zu|MYqqRG)gDMaY+!i;HsxkzXNnsrN=QeOr@rsiB%V2H8^GfFw z_4G=aa>Bxl&a%iDDHM^W0mw1(AR)iE;IrX4P<*#*RoDIEV9YqWt(gcDB=J+ARD|iBf6#9D-N}YZ4Dub3P*$lmso3}5ExE~B-)$TOUDRZ5}ZR`h(x^bQKFL>gkP1ao5%$7 zW%2&qq+sIUTqPgzltS1}w5g~81!YoKfYvv{XMdjiWY~(?2*AU`Ny>dEWl@BR%f`!g2}{6cfeaNaS0LY8gxStOB3%!CGc+ zu+OI>MRU&LBi1jB>EZP*4yMD^&V1ZRSJ%_hnH4*YPaYH{$iQO8dTXTW9kbA(A<1l! zashXDtDZbl@xX$VfJ$Sgs0B_*2$&6$xKNran?oaoFXZ5_rHQXs$098;R!9;Hw9fI| zVydlx{#&$G^1jM$&`0xSMRLAUD*y`c9edXJxR(%tJ^r$t7>vG+h%FMRf)A(aX0kYF zTJ`GinD;$#3<>S!fDTZLPg_B4vXG~a3<6T?JP*!TG$@h;4#NzZ($Q1N0L|Uz%cNp9 zwx@|DgG&ilI2tEqbdM1QhRP##_&V&UczHy56f`2CqPK4x2J8<6F1AjNid#vLHGHg2 z0FSqgg1*KaPC5kV`^K+#hW2Wv4P$Q?%n~YZg}GXXbw-x!mRmNVr>H42lsb=xqKoCs z3eD`?lklwl>lWAwV4*|tFx*`~;nL5vLlWavaHdLy*lV3K6P`_%)|!a*I8mD)640S- z`%Pk)hQ=l15y4@@A7;ZFChd_pn@O~hDTZU;6cdl}S=*Ks3`k5TLcEK8M?SNzWoKW{ z))=ZsQ6&<*XfyVpmF`ryI&QebrJ!wD)yhQpG#fqj?b?>Wre+|>$bD=88Avg5eh84= zh1#VF>8nE4-369A*9VeUp)Vz6Zcpa=StuX}jeWr2iz0!-Cn1C*LMvaiz)Z3=zhP7) z2fYA9oP|z0tt5>iNtxaRX00smma%I$X#2wsQIAxvuq1EWM^aA1PpgOU3wgja_nnTtJ!#GwI69oL~+YnCiSf9r$C*sX6B*rtgQ4D zUFBjwi`FXlz?}3@BA;nDd!@EzCTi>6unzk|Z+gjc3+?753&c38?XtZ2aWi!j^Ab?; zPdgp@3) zxCENXmShtRWFKvr@h~kp4&8KTTZ$@;wo54^K}LbB~VQ z6YqC-x2qpFJDw>aavXmCJTBuYRs}RQWlOuOOe%H@|5nMCAouMml5EN1I{`cr8XqH? zoj^Q=)UfCvUZY_{p(92K11?`9xx>+1v|EJ{^kAz_^awJ=-H z>HK3I4WUf=1bfUY?fsN@eE9RFCnaws##WeI-bC?LL^bkz+PS*DEm?dbt88h!SyoD^!Z&y>QKM+F@s_DlpPcczx2$AH$EMZVD4E5;_?k6P9Hwe&}`aYth^ zyCqSmDB(x~TtaMUTxM)0V@H#D8 zZ9;YfhVZM168X@vytufq3$XK!4RN-4^|0jK3grBhrJ7g5iRu26y}W#OgWUYZ2`hBj zpJRoPy9!SXY$kP0+J8#LP~qfu9jP z`0kFbGBYx@abBWJ;!#wbAty}8uo4!*%ZjKCl`3_N=W?HM09>Qzp0yvZcZDF-NtZEx&Tev-*N=2t{pd(1`49vxq2yd}u? zam#GS3zhlsL9jYbJoC+3cc8aa+;hO4>IWB?U%Rp>ZYynf6Zmzaq232vWIefL`7$a; ziKGSJ{a6-r+hu4)A_{DIVX5dWSv#~z3^H!qHwaP0%gsa}0wJ|@zSVjVC!oktB)N^$iKT_vy z{??uRg#Bjqiow@yVre@4vL;I?qBv>6D%ukFgOJNIrQ_EJsfh%HxN=C5kby8Z9x$Ci z%)rHt8f)eoe9hWrStIvwHhs>>1X+edNosa3qe_itWQSEW)y-eEj5ZVXk%GABV2R2z zYj+-RkM7u=^Jg|$m3oDj$@L;dmBKjpyE5Tie6>7~#GJSwD+%}A$(8T|=-23z((vk) zp`7;%VDG!@C-J4DXqThvs3xKlhLHL$p!dn;3qV@cXMPv>^{$=v%ctCxE(yu{80k5M z)$edJDG^v`0fWJ55}+znq^Qp|A`KU`z5wLYKq;bR;d0UE8)IdB!UDLYk?vDg6iIri*Q`?j*b} zqyfYA^|RBby=O`9- zJDlTRAB`p)Tn5-u80C}5F_Eaa6n{m8#si-Zc_SF|$P7mnP`TtosIWog@>aoDf}qXu zCrV#bo8=;((7PR=UtBN&n{sFrF(DfGQWQeyo|e3UxSnR@w9G+cw?eiA9eu0*Fqc)7 zQ@G}oQR#M;Vd&%WoU(D%NtB_q%FJEHkRwqfJ0C%OH@aDPG%uyyz2D7!4X&`TK&%-@{Ow+rMTWZLv$tYsIx zS*kulr1xw`3rOQT@PECSlfz4TPW$$;_lOUOG@Hgx`hzc3%X7Jd`9t@%m;GLO@xs{* z_)kQRBlG|@iCP#4VjM0$Mk5i&6XkSi$b6QBL-y;uRur!1FdX>S$@R_ID-?Yu*@D_SzWnTuNeROmY}o z60W+`h>NUor8e;@EC%3LR=4X@3a)3O<0&E z&kM@J_3GW$D|5bbVg~7(ij8g!DYFz5rgD_W!jb_^Ymp=$3%H(`vO0cv83ryqN8aUV z+fFQ{#iL)J3EU1ks+;UcTzPUk?7jfROJ4xich8!e^h&mQQ|;v=1=iwIU---E%Qbs~ zh6^Pdn($Ai1gp?85&OM-Neo7o>{}<#CO1uuOE|pWWS|~h<@7EsCmw0EJjpd;>sC_E z4>q3(p@_r*#WY+aNw7H3AQ@d59SJ>3rX;Up1v&@&TRb|lFE73L*$02!L+$x$X6;{3 z{9v^&bvazTIn8s`5_grFt(^3tIaLPLNs?PYl@v28O_CWdev54)DF`9ic=lKTKXb13 zY#ju=*^bSH{PyB*DkFXjChOh$?sbc+KAXAx5Nh3zMO z;+%W*vKi5lcMw{4=v`K+Y9&32beL|=h&tF1$WE5enawq>VpceAGuNpyE}*1vemdx# zfQpA289ATfIY&EBr0AzGwddLPQJd;9&1l%Y@4X^^0nB$tKaA#398T4!X7PH-FLIm| zTz@#uX!s~8aXhX+AxaK;O+EWIs^s0Ob!d^u{!?4Ou&l=ErAb%pou|wCqowrOIEl?K z&-NUFcbzJEhLDngh^5~H^%>T-1k*b(-XdQeQ}P> zWvC<*5syAIwmnvnKm{wQ#9+fAg69)W&iqf0d0i8e{H(Ns4Vx{-a?gnBnwH=88NmLA>@ z^-LVg)EV0QZee#!B(cg~jt?sA$)L5eromGy=G?7WVaWrcTOYT?BOh4`ldyBAKq@~` zd?O>I9+8=TCCzstdkyQ{_mP)5x|_b4KA}d1-BI_4oz&D1(Ipb7nm1C5!Fo*it0hFT zU7BT)QCz~r4~fW4L}!f;JXKHGpi@!D`CXd!ix&WESN(3_X3QSmldhH;19`}|gy6!` zIv?qxCSm?-j_#vuUZE8EO8k)Pg4}#^;v!rG>-6=uejIjuuY|d0Zpr?Aesdw|RuW#q z(8W-0Z~b=<0(Z?b*PafOx6RpToNN*%$(~Tt!zIse8J}+n)gQEne`EE`5-SI%LE=Hc zA`s#c!dVwC-_5O-KITaOq}lT=UF%S`k(%i^JvCCK7i=8(vHnvlg{~H}x@I%IqFbQD zRcT(#gUu_OaYb~aJF))Bfj+O&X4r7h;p5)#{-Z7x`;L=!miwm45fLbEamcL)-D&?D z`!3EK%OhgYgG+p;swXe0F%@UnR5fvR?8FLdR>4*0N5j}t)SlC&k4>4^cMZ#R2e#7| z(6=k<^946U%|vZYUh#wcrV;B5DA}LsJ~ zRj^{9<6XBzT(@#`zt*PlC>^ss|uA%ZZ(7hMenF91&&%J9V zvOF};^L{Iwll^N{{6UC9U(bHXJ2^+_TGb>(5(8F+J_1{R?5;-K>eKsG@rlDLUV9sd ztokmCqrJJ*qrLLZXV9-@r;@c@-x&}0-z5!`S|MbF8X}4^wvale#4*VSOD=k659Uv5!6s7}?Do2!DMs9D_)_y6L6C2KWn?2@S+a64LL#LW0R;^XXY{YDG zuI#KxL8mWxu?4ImTh9c=ioblRY?yo$b#*r;^~_8~AkI_^4LD0C?JqP}ZiI z`pWVZB8jj^eX!?CUR%Fi)so#8T=6<+zsV-lN|5e(YU&CAVd5Wad^!xb{ zg1RI=*7Cp;r-p5}gJK$IEnRr&fZ~n}M+7bc0s%uoK79Nv#c*(AWZ(TSBEHD27l71Z zjsFAhPocD!ap6Wm@uvEe`lgCEQ(VkIuELKlOMIGN>=#&p$fEOXwEZNBwbhH}NFiXUoi`KBwz z@4)}g>h8HZcPVvvso70a#f#%6x`H=nQ>%02PwFo^mdR%{@l{QZfdR;132S_W#uHK; z6*W!@DJpX)vw+s~r9)z9F21np$h4D6BUY4@q9k+z-Bf%y6bg37CF?6X%X;9lt!4Dt z4fEa$ApZv{a5E*Em3QZNb9GwB2neMUVV?GhcMDgO2EkWZDE<15cev|n%6>;tJnkD7AqOSaCr4L1cPnaYVgBMKQ@y$>2k`rTH-dC` z%ZE$dP-`jC`c*591asLPvPWs$;fV8mdy30BAp7ZR&c1@>@uK#+W$&yH&(R#HmRWrU z!(+={9SOI&E9Q|#5#Qv0k6H^QraWFMX!I128H>V-kFt^m4284z7C;6gYTl?JK*N%r zTTucDaiM|o7Yu0$Y1m?_j7WTNJdzl_P<|!@;eH;6YzF=IPgl>kPmgEUCXYFe)dtNR z`DTkJr`9JbS*)7nLrDRvME3L3RS&#JPaXHaN>cT&x2ql;#)(s>4^h=eFy9jpsvrih z1Ro(CxG`#2li}Nc8?QbP49$K^@2K)cg2zsklGd!34-&zMF#!#Wt6I~{h*Af)XNH#= zQZytRh>_;DrbtTO_42BP61sH8^D%hwH*8|MvEpOfo+)DMHIc4?Fy;O2_Y@aD5Kirp#} zP}XiXl|G#83m*MHM15sYo6pxaTCBxg3&GtXv_Nrpw^9hf-5rX%1b252UbGYsrMN?J zD_-3C=J$U-ygQr8OtNy{yJu(5IeYDOJ}ruREKlV3N;E^nArnQecIrBb@YuhIKWuj_AQ_eSwhE7U}{!x|Sjl}SXfIn zC{lDxDl}e%N_lVeFV4;qY<8@Ul`49)GDvU3;Je?Ovp1s%&0>m zyYUs3Xmk3o$)9FERgH&B$RjepvEEgx_g^Fx(MNN_U8sb(?-k4$6@&Hrg_|Uh;zBV2 zL#)Sj!3c@;OTp#~Z~eIRJ!M_5xt1RmB1IK#DhBv_=TJa%biQHQjQVpCj*Q~RMLS1E}CE z25@8)9{w9#0$MaeIv!r4_W%iWVtQ_VNj?D*21Y?RVhSCOr$R(U`iEeJS=<|u)@s}f z;n5m%|Z%o&c9x9O>IYImtRDI>gX17quH{sAfK*inI z7%O4Y0+K~NT_I_=^?>_w9l=nI@gwgW47DBY=-hy0)rIUTZ|Q#sm6uE-;rjm&cFSUA z$zZX899gH)S?2;Gt5E2IA%wawH}XO*R{qUsU*d?I<=ruJKbm?A)S$3Ai(37 zdY!#pePG?pi0Fb5^`syff=63fbffZ6NxF!cZDXrpoh}|0qAi}aOx4a{oJ>sUz;(6S zKLpOllvVe*H9-X>z}qABtA{TZ^*RCrY1t%6+%pYB5g`ZG*+qgZv>wnc9SMe#Y|Z)B zrXOrv1lfkV1oR7vPEOLkayL_f(^ElEq~y!N>hpzh8J!8t{2LS9YDf1e)(wyxdFAe+ z2-Li$(%qfI)`G(pF@U}Hb%LG!eVyr(n%=|5mbK{IeoJgUIl7pC2#(2^k8-s$J)Tv@ z@x3HWhP-_WnM~@Fb6=7@*N8>7%y6UBRBdFclfL-MF9xMkZ!Lk`7@cEt=h-K<8>#mO zwn>p)gVA3U`1FAS_b?6)i#X90#qS)=I$cNMZGZHTx?EZQ&^2lKt(+~IMRM^DX1hU zp!qeZo(8VUT5#}b;}%yXYyCbhQFkTJzZ@^veuXjS9CdyZ*H>LFJMPQLqaNh!bQP-*8{UOhfL?lt)Np*4GM z(N$!1;6$VQAHq$oWN{p`oy|&Dst1yx`S<4hW6bJog}U5&AeNti%JffVD!EfCG>NI3 zs@i-h9l!P&%t;$!RxU5w0TzZT<+kC$QBb@YFI9OI=yfmsgZ@&ac?j%N@75tG z;@JzuRGY+^2%M;W}Cvlerk9xFzs=<@g~Ij7%@zuksH zJA&x#CB89@9;FnZyzO~Rvu&>_`;%fC|Bc364NzN3n1Nm|XMQO_u&xji8TPT_(;`5& zz|k&^tD}f}@rN!p?`*hZm(J?C(_V{*RNI(QIk5Em}c2%zHr&h{455Ap_CUhHm#%y(GNgGp}%c|`ZZWX{0C=qGRp20n#Auyz!p(6QWK0uQx2>pTk1G&oZD^lEju!@!DW${3(glh{pwX&n zArT2o7imaelaZM;Y8@8So(uNTlv9|AoO%}j8+dJ^%^w}d;(@wa#_a~<13{}n z5KKLDrHpOkcI9Np=ud@vU3xAxr(iJh4lB*%Mo@UeK$nY{xPQXwVRwQMje<`YPTkfT zB>Gpov6(7N9dL^>FQ>u)mLt7JdhjlbeHJpJc;|I*kx-P@w^jWQL7wZQ$8F3q%X@RT zRkF==7Ou6(bWJE^$$QtxGkaXo$laNE7S{+vC0rm=|4$fb{3LC4#JG4ED3Xug(_)h} z{3BS;CaN8!<^2&ksCLXEha;^$NzZ8Asn4ihe#YBPN&V#>3(<@GtC0_m>J>B1S_EI6 z%7|$E!gu?2HuuHr$IqDK|D}q*9Njk;Ie>YeI4#jR4@^hVp&A*r3QFEG9bYc%%z0ln z=XjMPInJng=Ux>_6UT<&N92L3V^ac8lg2Kk_NyD-7)W#a-1I7~xm9yonAl8H>Zcc|gmEfD1bt@L4*hdask?>+%thwmP|SIR*5kmnoSS-$a9|kSLh9tTtVlYLXAH8r+R5QTQQ4piE6mQj zEEfO5(yJl8g~pLS9zL=*`J4B->hfw}lE7qEOlmrXj&EmRe6^12)iPj2DB+j@bwkfa zs<6!2o@#K}xT{{(*%tzd(0LRs8(Z^T_-h~DGR=Q~1Ur5ypy9v?vWZ=pB@#%FFnHHm z&E{##;c|N_Y*<7F%c}04;e{rA%ajo7Fp&FGX*=(^=n#N=7Wd?4XuP$Hnh*vSBibVk zO*$Vi_&kt(Qm(A;kPEGknl?H0(h%S)KBml}J7XeBU34!BWM!-82&uZ^pC~_T{dGpS zOYMbYx_r?*MReQv)j<3AL$QwNXmP?JI?01?I6`hA89cRMzg zd|zQY=NukwINgfqvDgdGT6x|lrg~V1?ht=@Dz1U)5^Kgk1U|7sgc1Mp7>t6DO41|k zr06It-d4=4YziY0he^xIa~Z6e(k?--!9b2=wDLXQw2^blh_!RM2Qjsh+z|p_jh`&> zPK0}&Gq<_}8*hI5z}!;WQ`lUoF_-leYB;gabOBSS#nvOnTUMgEc#i7-Qb{L^EKjgjeHS)jR0@aRDZFFf`gEeeAMp70ea=+F zxhT21D~`nSORD%4IiYy?KZIAQyyA8(kq_2I_{a{vxA+ZUX4&jdZ&eL}p5v`@F_pGr z+`>JwgXF<7u{z-qtTig%I#avR5{=F{IgN;fj{o#lhV0XF4|CWT8zZA;_oE*GVpGE9&eYA z<#H>4{brJQSyc{r)lEpsy}ud2kq%?#NIE2p5yz-!W2tBUP>zS-&MJ;fYw=zyurg>@ zKmtBka~Jn_-@3uX0CML6jOL!AR#((B>RsxY%I)|Wgvd{k`jho;x1K>}I;nM45xoj5 z40So*uEpesHz10Jy^s8zNV;;S==|)ovj`1`oAr~2Lt$#C^JZoOAI4|vaV1bN$1kT# z3snuK;m6{3R6>YOse%m2gugMP;3kE6ISsZ%fzNl2S>moQinQ`Waqi>TpH8fI7Puod zUWYNKDmbmAe>?H~Z4VAwp`w_s!IDqha&(M&QP_rtp#bea~C)Q-7SWwoxBuy}FpT@d%0aUQU>UM4=4yo&vX<~`0b zF+MHw(VYq5LlvrLZsMnH+#uPPTE;NkKNRDrLgR=6SuWvkB1&#aymU6k+n=kmKWe>F zhVA!dnQ{@Y&Wl%e_hxE5!p1kXd%NejXC9Ai(lmYB2M-AS|HdwmI(a^%diZ6V{07K{ zi6q|UmRbXnv|{`UR?HBoFj*>!{)8c*`$$^^a1ADJHn5#n8txIB*>;(U@cWmKG$=Qm z#DxTbJ{H1NwIUcTQg)_R;2QZGjpM-Yx&;D3bFJ44_jVQFmG=BQx?RzMt_m_XHVnu& z0o0XVWVwk4h7UdLHT4~r`-LP!W;LIBGk&XRTm+BLgKAPT1R`7A?4nHZqvpaE!o$N8 ziUbI?Law6zK6yEtj8J#Tek>jVB+ouAg98eQqf4ZzW|507V$+9&%!|#2kx=>Tnx|@+ z0&GJSTfA%I;(o7F?Daerxl~qn=*=0IyBHX~-%CrKSDa-~t7z$+O`J2PE7u`8=;%Gt z+c*ghQ6(%74AXJ zjKxBX($0QsGIQY1iCOL0xBd0qBmTqgbtYrvTjjsYs3Rt%xkkqOo3?@74cK}-xg!ruS6*eeC>oWm+i?1W&6GA%+8wVpu4W- zJK_K-Z=avEQ(orHxoc0z`c$Z^#oI&Hq^adXqI{6h9diOxc{gcTT{RK$X;nWrC_{hO zd(I_BU%}=F*4ko&D$7p}A5Y}mqS|a^$KGf?9_#d_z?H_v=z-U!g4K{%hOO_xVi!~#Pbb$Mgmr8J|hg*9?HBHU&XzZ6e3_NIKM%*B0jYYhF0y2}x=Y*8Mc z6o0Q{nXdmkRuc4wH(u)Mz}j_~h>(frUcIOP4l5Gd=1x}a z1N*fbj3ww~8=4q4n@qD7T7>Rn7-sB@Gx$N%)z_AoxYOWJ#4%AW04HSC>^j?*C`3Ij ztsIw10g(*Pcd782QZa#~o0o6_A^3{wuSjx8$aff8RMuL?e7!DX=1uI6%Gy?sUnPy2 znp~mC2Z&-tWLU|TT17VGPaZhTyZmRNb7uxl{M22)&9r-aW<}?_>q8;hiwno*b?!Dd z48tN*v%@|dZ45>O)@R&m3IcD3)#nH4aQhWek-q9cJ&!!cy~5O$r}1&EH9?}Eksc2Z za5GP5{fj@AH%9s>!;)l#AE>py**49xF_8Ws&@eDEv(F2O(wE4R#4nB=kP z>dt6=Kc(DbUQ+nm1wEdqBw=Q9UrBxsu zzpEVDU*mElZ{7*HmkN~aS(S8GzNszj z3+T%T18c6b&1C-QOxIW36wlpW<=g%_of-Oh5T^N=*)D~WvJ|;U1*J8?P4_o~81O#V zEOWS5ylF1ZU5p?*^E7lAo0wQmjoCJ8^zdMdOp%j*&)djMh(U%x%MiI6aDR=%<_hgy zziFDG*l-mMV`&4a!Gvc>r)Rj zWo!vc=$r0NyJ9iTYXjBfJtEa2V9}#r_&tM>4`^kggq$>`vf8N*U%49@wSm0 zS3@Y%YSa~_);J=2I2e-yI7}tH`#V?+V5{wez0tn$CvkS1Itjyw+WhcQc>$@@$zRHF zw-N~v5g$5F3*x20-_ZC3vBiY1ull@+Au%C&^C_-&&0pdx-FNq=cG=WS2#};tXkOVUc(ZnG(VrKTsy@`ko-fSa1mal+sxHWhx{1|bF{NS z4=LufZ+1CiY*{pikTF8s!u}pG1JPJ*?r<08w1BfiI>@x3*%f{B^uTlDb{Nj{>QyAL%sWCLIQ`BN0_DXnBOx;GJ zO!AFkuDmFBt7F}J)GHN7_4ry2Z{{Ay+)cuH&c+ps2VoR6Wk3=urvUe27Uhis55A84 zV(%E)2xnYo-Lvbry19?$A$VM*&8pSj9PJ+gQP5b(yhCl7n@^PEO4PlPlWo^**F1aE zWo(O18cz%-SAf&w`=1)iVl3m|sgUAV%5&Q=j0cavanROQcDL>y+T=x*c4-3I*N`Qk zvd+m9YPj5mDN&vl_V_0f>$J{jS=Zbv#KSu!{t&&;XDX*MzdAzP1is-@O{0qI^VqrU-wN!LdWo`J+Ubwg zA~7uQM~~J$<6J;ljGxNy-j$X{$ImhLT#Co8^=Y*;Zy>F)@9~#^sql8|77joo$`6-D zFno@b6RzJhwMfMjLw3nXWEMa`dXzb18~>X+8**TOIDB*&j?N~=AciRV#@L9--iYeN z9tC$ku6E9tsiJBpRi$uOEN`woLqEr{EV*kA%=5i^(F@GsLA4KQ?QVS;E3-5y9w7T1 z{^_rdwm-<~>Tz0NhQ;}D#P5){Oa8zagX64jzx|ELpTncls_aYGGc{~m+q$VIU+xNQ z_U*&~nLfzHI96`P28)q-W|N4J`wsWCg3;(-(hS_;Hd z#o3mgQ19j?u{h+%=sGS*>SpA$>1vFfpeoill`~)UTw0M7)|XsY382r_Mx2gvkX=gO zl1AT{nhnqD{h#U%s=jzRp1pMas;oiQUAX%kT-y2ZK9XWajb7_BJud+%Q)ACJ?%*EW z($guO4$z6Kq2m2n-T{xM@qQ^JJ%nONCy2Obi2(xH-|-KS$xm5pbzu%t??yr5>k`DA z{JEN<`J_}g5R>1Ftu)XRhr=s?pe;SZ(beSHs-&VkMovC=^P`4B#XWh6fk$49rNFLD zw}iH?|2UcklZuQUBy7R?7WRhAPyBmU|vyT;{s251sP}D+x>u#)DfGh$J zj|0j~%D=JYQ3m=tJcDuGa3#S)P~OK(5^}DC(2MSpa((d;So*9)M|V6;E@YL9rhFu7 zw8;h2V5fGoY_ApL@mZgj&p5&cqfy-~J6nwP=4$RpAirK|k67nvsz2wgC$?RWpN#lA z4A!K+Cd$s59G>+&}1yW!Oa6Z0=2ap1%+?%jaSzR2xc=mD7{=}NwL`-(I^-O90zoEaDJ!ccN+Aa%yPjGu5H0RekdG#Q+(x`|EGuK^0*b^F? zE)-@QU9%+^A5VKl{Xk-mG98*n7zPrhxZYiWgvp>oiw96FZhw6`)uSu&7+BUE8N3$! zlm`7hd1my1kFuq>IPa3w@vRQmnaaWs9N)jP!_ZYB$XS*aC10|3ui^u1g|3y7s6WR{ z0ULlwhoh{xy{~hKS$vDlzbB?%2M#3B>Su~Lw@zPnxARvr(U7C^*t!zLPfafu;M0XO z<^oh6#2qzu$EraAFLDGi7bvOB&yi&@J;4Ow27}L^NSVWYDR(w($@o4u2J7209}^gU z&XO^p+wpvg6FS_Z9=B%##)@)6q7LnHEvj>^UukhXuWu%NYW)pPZbH(uu0BNaL|lRk zVlQB3Vnh5}XjtJPYKf{o=y$d6bUZlI6&N@x)62>MjCwZ%`UWGC>!si_|3~0Tl^v+! zT}^QNy1;-?B+^dWOQ#u8D%G9<|E}`x--L4WcHZ~g(|7stX1*5Qq_%9Ix7`ep^>qoH z%Pg@d(i{Cdzpni4usfm7*FUOlS5x8Gc6w#&=+^Ny3;dc!sry%v737bx!}>KVr~RsU zCnI~&D1d5LU_5ea9HB~-amRg_8f#<|&!x*q%U=7P*jSm!Mn9EPsP&=EVq=BzRX#bE zXsa?pgyEZ&sxGBiFkkfo&K@c9GF zU>%fBSd*CFHTpw_jRfng?)WQ>9Af5}Q=6cWmDewisK0gr@4N_FFM1WcKZ2%w+r{RO z`bb-Ovwuq{zs2iBPmV(cWK*1#*xtDmX%9Y@n-_OP&KkSMyXjTy>5fSiV7tX!uNSkN zrA?HUc53^rrsD0XaGqb!{HDC(Z{a+~!Cd@o!`3Mv?$}K2BP~f$28#V@bFpMn6j%97 z?%6pqThTp(*YpKZwA0zl^nDGlf$u*Abr#!=VsCc0mIOv6p0-ssdXV+*a=IIHZ2bHf zf465^3^dyoD5#21{_`sH9oW?^gbxL**@gCqHX3X3el$UB$;km244J2k9-_e(?gtvy z`D)9xiobVc^XF1NyHJvN{UTUp;@V|g&0?TAo)bjYv37JMtkar$VZ?G|a7vDRF|XI* zzySLEgN?kr%0>_K1-U+fks>r7RRQ+r4MdffHCWT+$tq(_bX`J!Y2mZo$#!$rMvYDA zb8opM%eH_0R=U%S{ZDpeYS$6K-G}hu{(lHLK0=h8^NSKkF9C|*d_i{Un3FVtVLyi( zlD?|(ffF8AbdFB9H;>a_Rap{bM)$-x<~=@S?o%(r?dN%cp9@1igaQJ&z2L{V*10JO zHG)IdlLm;d-k6e+20f%HhjCiDnl^!mzgn(3`l9PkZCWXchs)o%IgTM2)S_kb+gJ?-_FZ5>gt3gzvq8GGx(iZB}v)y{Q`#^7`bPcRZIRLIJn zwdy5Ys^(Tp*TUF#MX&3NL@NqVM?bo?h3Sf-nA{RPRS=9EQfzw63*+)~W z1S4>E!Xl}#%vdBde|T`I&fLp)*D{FyGJ}L0YwY^lSl?;fM8?~s*mJW7JhtVHz zHHNa%$lS-eF(=+fEAtm)(xanQJ)R-uN!P4weiZEH3|LRC#fUE&HJc7bIp<^T8CGvVfEqF zQ%^4~z;%sDxf1+c)fUOyPwTlj zf?ybD8|)v8{yy&#b@gkT$B(7{gPsoO3$@kU>;v47@275H*-KWPt6y@*z)76IVKy!y zM?P=}%*IZ`mi9Z^W|jnz3kK1OVT9t{TjR>N8H!3qk|$CWcH+caB-~s+C^mP3<3Y;b zbX9Dw&w964tt#4LWTl2rYps|!byv$sxEpo!IWK!5eE@wrqux?`l}!k}DU{jH zc_A+QKQyW92_c%Qb1xy^m*W{|%4%Xan$p`#@^h{an9^(FJ0Wa&(J3POHKzwNPcPCQ zy+sBMBn&D?PAr{rGDkAmU)wRo6>7^Dk4-CD2!t|$mveu!qY!VH0mni#Rdx*5kN0e% z0z^m+(Hqtb34;>>#oTdqE@^c?#HlXe4$Z#=AC(G?j@y^|u*ScuT$FmHkKSP2w*(~@PTXEPc2gJIQMLvP*VE}SR%xr~(tS#;P`lT(sngUy4eR;_ z44ax9w@q~W=D{2t0&WjDWUOBlAsP(5szS#)Dum((B5a`)nhdIryA<7df-$`yhC^^Hc~Uors~=FM;&YLlJdEHI)653{ z>gj$0X$gp?8ehPR_(4_Quzo>4tbPW97jq9-y@vTmU^!5bGzD`Gevw5{%`hl#p7S(* zQDUesk2dL~)PVaFRUUh$Ck_5u*f z5G|PdgV%ruK$ACbZP2ya$YHo;);Gwj^6ieX<>YcFIA&#h!^=HSS8t8&-9XZWveq;? zOzGIBJT7uX+gxYvVzIhQMOqP(zeiTqafK-`bY}UaK2BO?{04iOaNfh63#ekIFL(5F z9E1S8xT`DS+4~?IqN0>fwZN?9H@^|T^3qDg6%igLLKKEXW%1bYHJyl} zI|~UPsVkV=;Kv{|sWlL{IKL;OGeOBSAQHnj1 zO)nzUjpB{lwjn=h9UTQp|4`i=O&C$SX?wCnE z?>a3N_DR?2H(P3?tkpTleHxBA$(J4b#ih;KYbLKMnQi4G&ShfRza18^ez4SfI4`c$ z3YI$_;p7LC&`l(Vmuuy0bqo`vcdA*Eq@^MNOkhif2IP+9Inb$yzu9e?M$Cu1HFev> z1+%A(!|GHXhP57?0|E%FF+Yt=4ZcNGp!E_|^X6z(XSeHVEdn9)Yb9>1PMmR93EIpo zcC1t;zz`BH2PAIES;rCwaT?2?*iRs6S9XE(e)^;aP@fH5h~?|4;D(M%q4I7zX21C8 z4MW>2aqH#<&is8IFZ?uJa>xL7_BZ?6w{IEtyT7q4jGOlouw`u4@CV^uWrTn>)0tzS zOfhtX&#Fqfx>{5FxvsZnPF?*6>?}9Gm=5!u%$HrFBG-_&JSX(enFnTLb*hL7ZdaKU zp?Bo5%-lrPr>RRfT!7Cmvg0-475@4#6T9-0!MXYBdE3TV4N|$I-|(~EUvA%ORt$Lj z5CR5y0?RQ;5HxDcwAPM_2{!zWA7Iv}4&A2U&WWe=iW>{g?;7*u)vtPd)($ShV=B23 zZz<8}hSM$$RF>*oro+Pg3sCL0;+K26xeoDhGjv!`ftmWug;UoCk+uYLi2d^GKb3(* z?&}L03$sswQp11jd7IY16Cl3H7OmC(Sso(@e$0%H8n&4~&+RAmr`V_R zmDa#;Y*oW}k3o5ou2_0(pHWZIKu3=X*!Q<-CHH9x|K^8W_lCGts2Hc53EQcyvp_m#&g=! zr#IEn%J(0d|D}9=J@XZ+?I%pd?P6>5OSvKddGExt9~ast z{JZ29hB)ZNL3VXhfZ$HggnzS3w~&@wk(|->U6^yy=sskoX`4f`sw_g!?@hUu=Uh;V zbBT0%_XlTUTm;U8vCCG`>|{WaU#dou-!F^ME4SRa5l71vAznG~6Nxxpjsw*2$hvY+ zqkn2XEv>_74>6TMPOb}6VW6^ZUPWj7+!MEX?GB8?0DTp>^Hl*ZZ_pn-3ebIic*wd0xXCDBAmeE&B3kC&kl+ic?b>*cvCCYFG#ve_YXds?? z*Pd$+a^nD&5!tQi%IDbLzn6)-$j<(I&~_Uv7xaNgdiRlp*HJRrgn$9RVW8@-{gY3ebS{i1LlolnTq$8`f`y^ID%juUSA;Hpm4iF;t0E90zQ$#sYE%AODK6 zg9>6~((aAT2n#eU1yt_9DXEWM(5Xg{@a%5HnZbd`AkQGY+(;fXzHQzRjw>dK4gPiU z&Db`H9TNqfMgdS;w4u)cyX7oZHioshJuE(EU?z)#^bM|o5&QM{8t0Q?yr1?>X$&kR zzl+so1yw~=XJ}Z~n5*rHUue?Bz}YNqQo3RG0Jjs;Vl_t1-ITgwz`)t2$Ft_Ru&<-P zcRB~>9bgQv9!Nxg_=KCdf9DMvwf5XO9M(SlPO)RLSP{r`q8Hqol%cU^Y3!--jE6_K zk0L7(-){%yycb4$du)_Nu-z}FWt0K>LDuBYVb>dqO{H7xsEZ&IpCIbmS9Ak0eGlyS zK8dGZixBt~0O?=KA@ps>LdPZXC=#>JKg9T3#oE|&fvJ?^b{-Z{U3bCq2W8v_rhPN1 zKjGh(1yd6+@sKf&D%94R0Gx~3_vZi@7-M7}{f{SyH8E=92BziDo$S19_b-sJ5ryzs z)@~VJX-5^R&jC$zDtW{|lehV02^ie%Iy-UhkD3xbGQA+_N@=h$C$(K(aK!iL(gx=V z66@;fc5?V9b=He68(IJ_N-*%tsfWC6_!UL9-*Zk4rtA!mh^w&DpDQ*ag3j=rSiToFGk* zpQkb=KWD&g-a>}JPv`n?J1d2-IFnlMdEcNcwjTXdi>oXm4PaAG;5O_xQB$?GYMaS4 z`_biI*8PY{HU~7h7A<-2&RvE37uC#+K~V z(wM53oGQ}YTTG*`SUvRp{fhpmA#GoV)3YqW%%}7CbC!W$LOtqBvP^pN0C6~~<>g6Y z^NPDq^b87?cG7UpFnu9-aU!j5%z0%NYzZV|4Wqr;<>!h1Q{jhh|GJ+-ZX z^5;;xWyDC_%*~RZygBfM+-Uq(ECPFH{VKBsv#LZ4njF0)(b|0WaqF_6B*|UDJ8Sf? zvonkfwN!ZnRC%lg0?9=-HGUVr$iVnD)gpTaIM?#a+;!qPve`pt0I)!_`u*G6^f)Fa zNZ%i()hT553yK?qZMNj`Qacy@JMIYu6+1Wdd+|SWnAwpgUC*U;|=itD~Mgc9l84m94N z=KG+a-^wM|zrU|jD>`j!Fd-5_`nrtmG5#UQ1i=CITyR>_|H3lD)BnZfgd^(VVF6Ka z@loG@BB14d!=p|}CxJ#p&#OTUF#8{t9?ncEj(7rvaSehq)`<=L7(dU+OM)LXN&8T` zaPKlkyJ*a>EO>kbP3^$x2Jq~s!Esm|L*tQdYJ0g1KK<->e@_je#AGgxh+*6L{Nb76 ze*4x6KY;;XhLB%Fh7g|hlKvsQc@@5cdEH~tFr^bp0$a1pLfw)b#q!zozrK>BI=u_pr{xmka_uyRkQU zN7bG5MGVpM!YEFyI?wN0x0iz`s9~GQ6Z@{un#&I-<|KX;K+3Rx2pFaWR}D>3CRYpu z(fx7$c3e={Ss>_v%k~rsJK1(&>kmX)eo(U7<@g;u^tY}cwJlI`{T`>^l*k)$QXIqF z@YTU2ZMzSVHU0C|i7Be%Gt=L`9~v^) zOaxzlKx5g9+odiF0$z#yu{O6|@R_f}qhm?8mAtl;E@SQ3dk0~7@WEn^#zu}N&Ag0N zRZ~?X6HbnnlI|wCe*`Qo6?76r%MiM(3`;VSW;OvBQLF~zng9gR^h)0Y-=!M_ab#Rh z!(Fd1X89Q6h5zP=*eoki0Dr>L(u`OhvI4uehr-yME^wOsv6^ma(WPYY&%zE9+~#@Z z$4Ae362Tk)5Z*r7_dc=r&e8J7yR!QU8d%ZFN0ln1NNz|`!&|%+$BX?Q0P9RQFh7yR zv&b?BQLyhavS3R3$s0|8?oFefnbtDgy9n?Gw_TWJ;*UL=g29_`Cr4`!H3OEb@#GwYVf88>y#H1R8EAmO1E#G?eXYuUL6P4%$0^mMBQg!mHW|XMF>K=0%erYg>-EC%pJJg> zS5wJ}BqO7{uI%s}13)I`LsQvLJe9khb{{ZdDOfeA92!i2mhB>Et{?TwRuRbJzg7XT z-U98Tzr8=VSDOnbE7CNV$&IBTXX}MaB{EqkYUcF@F&!h2R6tu!%MzG*HS$1RPIGbd zWwL(pf+ua+jT2Ojk9E4OX`}SGIvEY^kr!69Z!C#;iXGcTC5eGzx!G(by zZJr6GZfs5&=ebp<DDNIx3y`W-|G6)BeXd&cmCq=fQ*JJc4e>@d z=!z`z+yd&SQNV9r`*W^@Nq+hm=!ehqG7f zO2fJK%Tis-13r{pw^#-!=W88*EZFfY(E9ZpVWV7m+_A@H;l7dl(WgiD=SNK`Y1QUO%-k|j*F7sz{Uh?NN*3laS;53y*WkhdWfbrBHQCTU9j0>|P z&8&(?i`i=;JogTGNCk2ooW{x#dX{27IetG%jUh_W$&`|VWO8Lz;Q&6ta4xq$JxURb z$@BYr$<4B=vJSjS*Hw6MSL^l3++3c^(pNXLK2^FEYnZ8!%yK*uoK@Pj-kG5)ShcwDAo(^!5WhhO%Dz|s?q`Ld@u0FPEWf&TTN1X-m&R#t&B zs#3gTC-F5aH7LYVIc>8p89h0%b6P|*_cW=$h+OW!{Yp9tdb{asvF$?5H)G+FAKm{8 z5(jBBU{ai{KN&;PAOlmX!X=N;2I?Xp-iaTMzkDk;I3^z#!7QJELE5B29Ib*Q+=@I; z?jS*B+Qgxf$a72?ZCSF|Os{pZ4Z7tQ2JVWe=EO*csZWK`I#59!$T_Hs{@}1w!_Ji0 zh$RVH<#eB>lSaiu__)D*+iE9@gz8T;pisb9C^<1`W|{~ku$cL0%|C>&*4h^(Q0A^d zEC-fmU|D{bsHdnxiaLi9kF7r;j3MF$!p2_-4K%2|x?ou^!iC6wo*akNd=M-Z1IQyG9d-992bX_jj@j7J)l$JNB4 zkiteS>q<`N3M6KUWg#O5QWpVN1y8Xpi%o{!n-R z!J-8wvI>yJdv;dHs;EFRm$_o8CCRe^HO;dlT%8=mwAL81+X^)GFo2 zYEu|0lc3E>ORuE=E$5SG{)jj^weRC{s^5n&p6s(gU<}UTvC+}tG5EXe`VRih5?~B4 zZK@k{oRmpd+Lq%>YUbzo)QWbjV4L+A;alrU!LIqgz3;y*o9Y2S8GMf}N1*m*PflU# z$sm-74#2((TOPf^mZNi%E{`5f=2+!bje9tpvwNGpc+2$RB#3Rez@d0WjpRMtarFVcVgv-pdDN5Gh8`y z8mvF~E4?e!{E%Uu6}z6zK_lp%haW=n+vXj56LbtZ*3?WN4d-J8-STSk+FHXJ`2Hwo z$MRa72eLh+u=|N;IY>`vI84uqI5C}B`x?{LMz9hpk}sb!8UTq^r7R8b=sq5i$7>3F zy9*pSE_+U7fFzB=RjJ}=E~4iJ19*M=IB)x-b>4mJNAno&frxf{sIo;{=2+Z>q^$DB za6@H_Xb^zYj?D^+4~WhWWk7^nng+K8@fw+hx{7$I?4C>=x(o$f%ge;=0&^p2M_qvs zi&6y$NVY~CS*Ic8iC}bNZ8TNE$ufla<)^Ap*7aNyp3!+;FY6@Zfch#cDoFI0lk ze7N_?z#?-Q93LN_t`HB&8Xe1zw=`mm8q8IsZRz6As>-?%`!NcBg6n^n%nj*pr#ANh zWrx~2>7(s^bea?t>?xG7>?!nPygyYH1;_$MKdi{$nY74ET@fq1^Pc-ZJy_s^g)*#{ zb@dGiqq_sDUo)X*RCr5U(nvFi-9Ckk-f~Q~`TcFr!V#rs0Oap)2M5ySSjDB5w-J%s z(a(7l z6H5#)9d*mDZzMKwLML@;9u`H5PYwGa6IDWhM>ov)LBGjSftX#t?Ur3ki1UB#W#NOs zLmQp0yV6m#(rxG9pBW@J4tTC6shmH~d5yTfsVfUhpCb_sP*;qoWgG*2((?W?1)C0DKfOvKUJ+%#(V0V+~%(A(^W7 zzp8B=%dXFSyqsJtbpO9Ka&AITO+EmRa$G0x(^{tsfPjE%;}Y;~&vAfV=D#i-g?M>+ zUlE&>%Xs8_e`aMIL`RzsMdNrUpZ63`gahdIWgg@^lU%}x zf2EKPhee%qIoUW+y1@KQSSSWd}kdANwvP@1zU8OB^exEV2|k@7`#}%5H({ zlW{CyvtgV1mvv@l{`6@=@@f9^*QkYGodMfY-%STaYt3cpWEmL&U!$Y8;p(lDMVu0R z#x>wWK)!+Uk?2{aJ(>tg^G3d^8P3r91oOs)cagkKdtsd{ni)RyE{iOK;(z5Vq$Aq= z$yp)GQO0Ee9&NrYBx=mRb*-_)JRHNT`q6l&oNp@?-o2GHf=l7xZQE#*IjT6SLqNkb zVVf}t+JJOKG~G}*R3`Qv0S6S&Eq{Nx#fdcv4vQsTwvSB=W#<>Bo<7YyiM1aq9;R1s zkEWq=_9sd0l*@|-AmjDBu+y8H^Q#cAJK>9oY~FM3#d_8ocVxLft;PPg*q)#R(#Z@h zUKYh){H$6ckqMBv36+RBw&g-MyRE+4xB1DnWYIZ+hiIh-QfIB{l(tQDbyBA|)*o5Ku%wKm_bKlpwuI4bSmL8Gn zwl&<$EJ0fi9kieP<=~aCAb)A1w7lFryyuc-5?+}zykdam8|Ua$RcDY6;@gf?5YBi~jkYpJM` zpf3Nz+Y5<9k!|WZ;6_H)?!!o4tw+@Ub^b9|+wM&9hH_m+Me%o+*Z;tYA!|RuLm$lR zimyzIOiiZjI37|If^PJg;lQ2mXO@TZWJ_0n>He8>>^oE?310R{vVnycp|gP!G@`gz zLOwY;>A{l#$#A1iPfw@kmx3rxyhqplV~Y!owO%;%tVwz-^bpC!a7rs`*R!!A$v@qB z1YLTrSLzR2v|9=(m>wjr$F9}=1jdp7du;l4$6I=N``#K$Yp_%F!RrKZH8dILYHc>I zu&b=WC3FlY_xW+J^|Nj?28FDjsjy^-L|Ymqtn}lY<8ZCD{ZW zcd9ixa8vbit%w;n#A2;Wd}nUnd(&dy-8&^RWEJL-u%zDo?C|?bJ;{>4nJF{3^vp8L z!p5$#GT4~cpSITmp~^c7`*+C-lh=^r%CFksIv!i0eq=0#_DN`uV+9s&tIuGiRv|M2oJEJh&z;ayMtRH-;N zGrj*`IO|#M7Sy|b6mU(d*XlBgi+Sma?3ekCjX@}3RR-9VkWu9UlFeLTg$qJk2fP)! zBuo!2fE^@veq{6HAr>n3obrfHZ!1Oeo99(&zv4SHW2Tz8_QdqX4L-Wh)jG6k7LXJ@ z3|&VnFCB@fU-B$JvWl@0SRR@W6FLC&wGH|uXBkH8Pu80*p&-gLkLtD!mPCM&J5?sO z{0a?OSG8SyxCgXpsD)k6_|+EvO-FI%rkPh42D9G)nlQ!zv)D7z; zLy^Y)ejlOA=McL(yMiXZ@5`SXxf}fE+zohOXg83o$ToMr%Qzf0o}3XSYnM>L)y8=3 zRj0do8E!l`KDN(1^G^L9@Qu_hs*t$5Nn(lTPg+$k(h}f;y#&?TlfU_BbF>%unQt-6mf%;b6|coiPvZmQLJy=S z*S&=KlSspKp&$tWEC8@7f9tnqOY! z*KVT*wemlOuIZ1xWTEP+85>iZ%-jmvvsLhTNL@U&So=qhtkptJ7u_LBYnJ}AEV7Q( z@%tcGMOLG<0fgnn0p0g&cM~Y2_CGux%-x25T+&W)LuA!%HYi-^P+?&CaIsD0Rma;^ zd;UsQeT;}sy~%yXPK-KExvFCE?$YD!bc0u4ilAz5t&hRjOCCk3=1^T@)sEM7^VSlR zy-Z9<>U`!@mj=+TLTz7ECC0=o#+%J(I#iTjHrDv{w5l`r?(HQTNiVS%$Uxir+nIOh zbRg&N&z{G^xaPe0TUh@w_v@>i_L{T}o$lt3aa0~}F;GY85B19yVJ`$DJvVL(=imGU z1^&^QC`RdU2-H{3*=XGnGWJP3#So~Pz$S=X~crVTeC{!IAO|}ijvW#Nf zA2j&d?O^eC3}#7w1KFxdfK9e{2Dhh_T@Pu?pJMVS9G~%A?yF)1u3Y)O4(&7 z*qdZ;=vEj8$01_9wis;fwMX~z1@{oIud@A<|L{%=6<)X1-#QYhnkei3DHsGYMpqjA zMBIZN%Br#->(!)`C$iCj1g@wpGT7*%NEY81o79Xr2G`xiO8$AC{vzB1C7HOr;X^8a>x|GDamol2P>e2t20rTKJt$#I;)UKkqd;iW7H@ZY6G zvRG9wey29q3#0>^wH`AuuukW?S?LW2n2h?>3Gpo1UjkJ3;djlL=03hdipamff1bFy+IIR~bHj)4 zvas(b7)Nq{iVG zUI2KzCd$o)OD%=vl|86?ikZ+WgAWHH^}|K&hE^Gi#Km#o4z~-qjM_E0@NHGO7~%Nk z)V<4>$3ZtDw`)(?P*&QR^nxS1qyU2Wy1a^@qV#(`ZveEhZC6$1if3!|82U;VdLZAN zWWRi%zdbd5^vsP{tCbCvrHyYUXf8Mm0ZJAUPcuW|AGJ&~DgKA*0^cg&HfCX~?!@al zOWL|nTdhx*mXBR(r+Z$1qLHA%L2S+xV)GghuOM}mdAa#V)hTA76M@x!;N;Qu+jAQC zsSlfnYz7>yn3Z|M;+dYR8R~R6N+5%u&?(AY!ObhbMuXSIyJL+G&CB~g(4nYYGcF}1 zw#_2y*fX7G_Gybalp-1GUFP_Z$yCi>x=B(}k9W zF6TQueVcy-hiiN$t)&)ufqPzHQDBifSu096IxE#6@t%H9>r$3|pswkca$nVJ;gz{U zl|RxVFGaP|_26AvI%d-Q@m+QfQ@>rtQ~vVsPPJRgDrA-E{I95^g;Pl)AbddlzaJ4H z&Xe)~sU%TzQPD^c(Q)?-UKuXchMz6k6JJTb3`uR8mU7r69&T{-FyTY_HNIlO-*T{8q*tLQ#P zO=fY{j1}XgVW(p1$+-S{X}`=^J%JkUa4Qyk&WudWTOdC9WD` zD>`?;ZHIUY%cefI5qd;}lZ5J_6Yy8+Z)xh?U>;g7v}wVdH4=0d3oVzyc5OuHU$bKa z7o+~eYmmB7cZBu(*PmSm-RPSo$oFDdMu&+@h9SDO^f3I#(!v!D$tDUn1gvPjr6 zEpB8g+dimWW%jt+?1!+7oz#caa%6Gw{t>ll z@)bU@N7gq&`Kj-Dfr)hW!X(;)#sO^rURFnB^-hVb|W&*fqNqd7d9P2MZgBtuQB5gZ5|Oa zOKq?J@Cw_npdy?am4gctts)fu733{COsFRc7o zRUUgb$EbQ`*NDQJc7Qs=ps7am`e=1T0=WFNE}i3sqN^O59lY$5tj9rb}q; z8S7~&%khxwK?j*yLpBB0H~ldl?Z3YfaR+9!POy}0Mv`uX&>C~#zD3VLr-RGT$IK$d z!taAIb!r~crczl8n=NCi+RBpB5){gX;`6(jyGPWS%+m7Y9B`}(<%i_k+iazpH$7Uj zhAIwL|0a4NbD;_apN?*Hq$2m)Za+2@zB;f;vbxESI|c~<=^+sKD~egzijF9Oov{Xm zS;tPu`QIdoupM0-mjGg^(pXN(Drm^on1<5cF9_ie`}m>F6H(#0q<83qh7U3idq1NL zbX{KsyQ`!(`Ks{S+S+^6Zz-ZtGoTgajp-`$n1<(-`Z_|tBwsIpDHM}2-Z zd?kz9(hAj{Zqy))P?jPlQ}pNy85%2+q7Iqg)R^n2tt5^6*W!o%1lS7QC3}wTPhS^( z-aAw;<>8_fX6@k~e@V8Z%Ym65*5W8SM9_bS4Y;Ey=y48paAoJk)9j#Ka6-d!lSI3?~}Tt;W_|1NhWA}{`zI=>W|+Y_VP!Abp;`m zL17lM?yrlrTf3kiu<+k*{LZ-+P0oc@E9oyjo^0#n91^Dho_TBgf1t$HOl0KC7HHC9 zr@m2i1}UCDksmHg;%G+dYV$k8DkDhDZmCGJ2fggO|r z*F*zCC$JQExWKMOp`+mOE4fr@(Rob?DxNDL@&0H}8JPU@Uq%A#q({WbST!-YElt_V zbPl!n`g@#jK&t2!;KXHA=odSXZ+#hG8m%s@VapSKF6RP)+wZTn_zgW8|eb^3ol_X=xC}(W`|>=*Yv|< z3*wTeW2lh{mNRkgal8INE1zZEwV9%QDg!$t^2?2V29C)=J!l!YEhCO&61Y9zM<1Tb z5Ht@@ysi>Z3me5%e7=UiV=JH^G9MikVCd?yBVU_g$ z-`kvAy|@LVNV}CnOlW|66^>4Aca244PhX{2+?GyX*)&3XiMtJnzA}`Gi95JsR#FFn z1v;NjF_8+OnWg z+*{2#TA;64>TT#()6wMLVaxtCZkt-3m1;(xgMuaq18)n117;NlX+Jb6#K{bJquxrv zvRMa}7~rj|6x0>y)73=MDE{ug6r%5_ogPbX8=(|jxqTc4h%kLdl<%7@@s1BhzV*`9C~CFzEZUADCrJ zW_HrpeNK!b&%^wRv@lUvm0T2XjahQ?k8c=Q_$GQ{Z8?c~dk|N_Xnld9Qb} zh-ynaPV`CrsuBI<;mrb*x|8Wt$9IlTLlJ3=kv$m0qkXZ<3N=H0|9`Ji&y>6zwa;Yh znf@8$Q_L^FOvkBS+U1uku1)pk-K!Jm8({dXrNpu>e z^S$EysV%;WOg5}^5H&BPm_3?RbxBC;*u#k*f#;qwAo9OznrF{3l-18KH&gU{b?C9T z9b=affc+(VPH%U!lB+e2{7l5+^%VIgW%VQiZA5OOR{AxI>*&@(QAl!aJlbyEQYRSW$Mbq{E6NuKz^xa=_ z){SyQSuD5RLe{9liGq6A86|pr$1%%}qiEO!T3+~Hv@I|Ow%jAL*)}A;u`OteK9_Jw zooRth)O~C-{(7{pEAZgAlhQ+3jpQG#O@w!XUflEKfTqCBz>KRQIi1=u`1T|l!Erlt zIp{&*La?1p3{@tvwACC(SY5s?aAA)G0gGNlnh8|EQm?isIe)&>27eizLCrKL#IgaG zGipf8XNL((VQ~)plt`$bRrXnCVReCk~8kV9<*4eT|F{g6qLoRM>)jVx=XCH%$U80 zZ<{(0KC8d9Xawxi&$-}l zm1IU%plKB2!I~mu$O}`|(Z;kQaxSx|{Lz!67@GyEri=o{Ak<2WyJiH%ueb`7Voyr# zS6DtiDP15@m$^t_eZ2AYX5YmGVyRvP=7R}^9;Ph!9KLg;h53uwfu56@6s(#2Vk^p9v!u6UVZYk$6&Rxtd{C$k2 zp-1~cQ;tRb7qXU$P}A++rczzv{dU1{R)C0AHFh&-*G(Ulu z2H@5fcKFXL^Ul<7sXY78ZBed$CeBQ%&1lA!s?B2mbG=l?@CK+!|GXc0nOuWRV>S><6#_&F$7lVH{ zd(H&0xKz)k^BQT?!DK#xouxQRYa@3pFgKalYLYTQtz9U@-2?SED@{OU+QVu82TU_T zhAr=)VkAilZ^3*PsHNw58K6-l@qinsrEbaim5|L&nF>@&kg@s^y$JO(Mb*%$PQh#e zf#hT;$cv-B;M^;SWaqctJfBIC3*DkjZPYZ;LU7uX_d>-}-a#@98r4Au?Ft78zQe>R z(YzaPLZ@FlFJN3LMrLq^91-$5>5HOKC6Sp;`unqYHSj1K3H)H)jby^5N;}oMNASYw z-x$B0QeBPIZvq;0zh^x|*a!rg{hkE0S_&-GA2gvGF@4R9s81QG(>>5NTMkDu6Q=bq zX!8CI$XdT>OP4R@pvzt5fL9P-BYuPhoaPIWG2(B(@{{v~rodwq(gRz#DFj=gFdg0E ze^PP{<^c@tcRk{s|H06ofSj+-+p~dL331V|WP*M9GpISoDaTIpz+Kz}KyA~lP=5mX z3rmZML3yuKr^XtQ6pGHr_c%de?zQ6?{5L*0O9*KF_ke~nqB{zx#Unm*^LV4C1W7VV zn_7q$jLo!}8hq6KmR{LY~Pdc)}dPhf(kF*&3ilHEQu(>8gv8!*E3)ED-^ zYoxbUCi1c3Z_wLJ5w9UT4PEzvr*D=-A+vSb;IGhv6%F{&V6jlL{8yVn$S63)umY&9 z6(zdwZbAROsb0$Hj}XY!h(WTOIOE3A&>L%pNnuq#XwJTH#0hSFpk^W#ar-OyC|AMSm(TvWlU)L?N}Vk%jCY}6~h zY?RugJAM3s=#E!NEct0V@x~CL|c$A;5y=E#Zzwx zRT(98^(1XF<}(#V@<$8rbVdm&hb;yLQ%#j@?FF9kv_CwZvQb}T_�h&^#LIqoZyu=Uf0)b-$qAGIp)Sa&&H&*%QlVEP=@6r$%*dW+xSbA zTMrkOT2(j~Wr0G`L>A@pqULVTAM?Bs84<#2<8XclPjAGRQmhMB{G~J1v*R+j^~=L;>a!l@IaIZ&JRC8z)GRYdM=B*JeXJLP=Y` z5NkbE2XKtFs1{?QaHk_%;!)Mu>6MX#N`SKig0;(XTc|iI5F1S7`W~hxTn859p`BzG z`h(`!c04)!B7;nlmR-*j+m`hkRR!O^z!L0vvmdzF22#3u>i)5ix4hCi`d58#MR6VI z7)oXIbQSVSf#jg#sF&1*_(S7=cnaAMhfHCoKAsN-i_T9K-k#(D5yh$JM>!D+99o(W zw*El}#s6 zBj`fP$1YW2$)b_cB(bYcQYz+@7k_kF5%X7P@IFBpCs7Xq*p}q|k5C=8&cseJi_o=H z>Vq7j9&2D@j}h(`KP(iI)8h`vIQSg6ND(-PwYE1aMZ5d3Epm@4aNa(_jBo_5aI}$s zQIxg*H|eTDwdcmE)@)wr;kHxWtoHjqyiBDmm%WQhY;?nZ%B8^I%j}%kx*Qs;%jh$w znyoQ!-z4~OqD9E?D~V-5II5sNXb6KBf%M*;XEfIv@v!O4_*}4e)kR07=_c>zdbi+%h=I~zu?*qH6CQRw$IB9^IvoU* zPPi_oYh*uQ36%U0rh~9eT!(_tYvzoFBjdO<4*~0##eLO-$9v4G4HbVQ0xtXT_i)lB zdd4?!3i!4nk&M!(-3_Ha1n>ywEmWAQFy>_|%kW1N-l>~Jam%CF=4wyVj45JAyq@t2 zOOsM7m%nEvC$Y|@GZ%leJeCsTS_~<-*UkLcVWffqM)ANmiv`I0mDWN&>uMmqhjb`9iv?maZMA zPG@8-^I0v8X>%w=St=2j@#O17H8q;|Ta*2?>PAY38HYfNRTYWlaO=!aAW-ctI1K*J863n;U*M>A+aAm6r* zNS1f9L1{+1foq@!-S>*eVOpC1RTs4gsl|a(*SsG{=Siu7#tRk=MHKOXZ8?Azzp)jO z7tx`E)sBw@YF+Jr60U@TXH)St-6K+38DWv=fNd83Jc}-vZy`6c5N=rQE%6#)&wY07 zr0VxE>!3l%K}Nu1W}ub{3aJc27FQqUJ66|1m(vbHYn$Fluc{SOZu za`Td+jFP*Nc}*JZx8LM_;FmnHn%nEmZe%XVMd|##4q9BCLb6|Pg10McH||qmpc#5n z0aCK0TBz|LD=84aG&fgGU)G*)*J#}}r_E)zC4v%sIw1ES*Fbu{;N)1NfsO;gzBUm> zF6%m`;0!!82^l6!8D}FcvEo%S zHooTsbiSpKm;AS@TVLqv2Lg_?4atn~)PspwKXs3II_pG*zxE2fczE{q5=WMIjzY&h zDt&7p{Br*5h~NwCRyu<7Q;IBW17iTA0$w^w)_Ut8N#(A0c+n8g21VVs>{Dm6JptAd z*0B)w^q=q6?fbe<>)gTcWFkEq{#h$#8bwkg{vF?{#TWL}d>h;@WrE?L(UO3XPsw*Z zt?WXNq=>vO^GT1cgd1;+3P0!*P9l+{+EVAX-f#=-VlvJUZe6&Ac%Ku3EX9yonQXli znc)B~uQ^B5OSdd8);=W03*V^dbFgVO_o0=^yv4So_uQ-w$1m<%(+T;Qn>21X`O(7{ z3M46Nlx}3VHW)mpwk^v++LrZbD!#p=Hn4d!NkPkYqsUdi#Xo}O&$Px7tY0`avDPZ`l@iy-#9x?-_?FOd<0 zkZ1edi0!K1RLLS4h^r9KoLhVW&7#9Lp99@m%!CTsU@(mrqPmxt#)u;SpWh-Xp5#;N zp&j#eyp*Ah_S4Kj1^!iQrE|!zSB-m{cDTJVYE@;CnJ=!jxhF3jZ-BbPIUmBB zTuAUNYyv!dE=T2HC8>oY8C1OX3}iryC;F2TRm;O~-1*weTjY4uf@{ltYfaw zXQ^;)6w=~myt4SQq)5o)WyWVoG($5tUZUi%jBBnTVq9@Sv$S23kqm1KC?xPkh9hQX z%E%H6i&Au28=*qTpaHHFswh8mSMf&~{+Ntwm<8imJx0hY5yfR63{p?LsaybcL0jJ< zMDD-5iJyqYJFHQ$&IuV+z{T@0KgI~Pw)98a*QUPLcA4Mjbs{bWPrimf_IV#-SX34k z79wEAqpp=kBDaWN*zqvcCP+#Jt@cHnYj*Un&f&JK(u~uXLR*h5plK4ose!et-}0AJ z;FJ3nf>NkaP;mt?Vf^Hsh_fZS*-k1EE1)48mfW@~c@d{83oj^&4(oo9)t)b72?v!j zZg!K$dPp(Jl}Y6um%q^hp@F6kIG`Lh9S02W^@3yhlXYHaWFW$|i427dgaCzql^U$x zXpv7?Tim<wo2!ET`E2D$}XAh2<6!VvWdGseAW}h;74D{m&>iI&8i! z?Yd;maW2K~33h6hN_=+@6{q3t@u5`wZqLUruP|%!TVw_O#~X-eamH1^I%tt&E&)}U z*fIgH7vL)I3AH>Ic$p0OpwV|z_#TE4vaO)$u;$DfSCJmm_@GU1tSePRF<79NpC0@n z6jd!+-IbXz$=z9(1W4>0E~Nyfgk2JmH~Urn7|aO%@({Zf609*p$LP82BR+?Km@+r# zi_mag08nPU{Ncf{uqJGA%DP2HN65PRA=J8^k8_0Wtn#({FZLAAOzPj^&G23LNH?-=GMY4@H~FZ<^KuhpdN?pljGHbc2pa#yX8Ve6;V-Gcm1bKV z78*bzooDLWHmiAb3bU_lw^_ON!Vmgg{>CcvAC6IWC8nfTd%t~4lgf2XCR~~<5Ld-b zXulXIQs^?P8-Acg3#-K+$>gF}%Lb$q%c*?G^h~O>90xyn@2TAr92dgMt$6L|>lm`4 zmB?l?LdT>tqx-}U!EdY|c0oUCvt^2_na^JH%=rmJfS7X-PYH>0U^e7oCC2Ya$HNPY z7k}~=B!Za^vB7wd%`zaNJ!0}0u0rSr=}Wf!Y^Kc|oQpYq1|(?)5f|EKOOn5Pbbo;V z_*KRoD)fDc_EYh`Hf)%Mb-X=9-8$IE6oqNSnwEMs$BXm;KG*uiG=1GEIbx0bSxHaJ zCevOv%MR2o95*eu{)u5Ff;O3_Nuv5@Kh|Yqn~6@61U@_g(FO$zJ=aQh)@rq#MFDPv`72NH(osKSir%F zS@BC4l*`%{0HJCOfy^|~F~T-rQ#Gvhh_A4R=-J)<_y?mnLzfG^u;-xHX7$UKfIXmb zDm(Y=)x+K2!pX6}S!WmfSYoHziORoR5{#|@gNNfEOW2L3q!2LZ@~f* zd3{q0CT@r{Ffux5=O_?H^k5VK!bVmgJ=kFdTQg?nu7+8ShN0hK zm1c0QkNX&E)3@*}sVfGPB%%qr2UxomV%_EH2mt+N>Z(gKC@0z6W#U|5p}*X?=Ud{O z+5s$IdbCHg-crDl5kk42geo8YzK@x4RvVsix2b9s9y4hxsTLs)-94(yS>W_%Sd7&HvsTJ`5nZtjw~lI zyET|K8%$ecN+O`$pd<`hD>=Wj*ShA?W6J&G#g70&VmiY*HL>)f;*hXNd+Cupc+5Lf zB(sJvqs$LZVC&9KNnR@JG99M)YNWzES4J%5QxCMB%P6qdVi{VfbI?RhWDa=g4x0rI z^w>H80@f`77F&srqP-U&B%zM_z6TH#a~`K8JPYhU*$=ckr}nE6f2q4ZZIlP=bH~6VOToVMSf{KGfmX)h=vrL?)2o3jdGf!el-?*6+T} zk|**HY@`8@p^S`-fpBYNK)dj-kqm@IrqDo#G2Sx619vqaDlR)A(8rq|CKORrJjy+|f|?%t;!~F$&{qjO!Ejj=!R9ndLFjf?LcC4(-LRGyLsOVu zn2nxRVkv#SsNc~gG@bJGWS@n=;}cA`l&;0=x*TL76)H-&vyE_!Xi}n2FmfXsRIjyT zgRX-QcXdIv%qH_N%Lf=Vgd@Verd}-6P7<>PN!uOcthcKU_UV*ghTv3E(4gOh-$O(; zDJiI?^+pW=!G@l@%z);OxZ|Ag;sBc&7-pFSm$EZTXUk5feG7%<)v0qdQ5xI0$mde^ zF{K1NqtfOehsP$ggO9$BEq%KRH$V z|6D12RW1}npa9HAlde@)otKuM;Rrf;!?0TRT2Hui6+Te?g>1e?)c(pHPK)QvA@gLJdh`H~ z&Z-GSzl0srb*;-x-`Ci#1-aXYA>Y=u%H8mvtmEpeC+y{*_cP3#th$uVUe^-iVBy_< zouqY_N2Jr7r-73xU^;&n3?DPinjdUPdxoBS+#&4(X$UDRa3&l9@yb%`l0PiwjTtZ( zg2Wp<#)ycRgzP{GoxX?!!zWpUGco6)QX~(tvTd;Q^pU?E!~du!hZc4(vlFAO9?k#oB-6FprOwLLX+I`= z6-8xj4lJiv~+cb+GK{VHVAG z=)=(JLXqb$(l;8YZ06$KSg06Eb$xQ%ENAt935|J&i0DM?9$2^Y>@c?!8WcRW>`k^- zC;lN(U)Z0nu6h1_7Z0JnO8Eo**TC%NR5hO_rJI?|#Yh&ph=VSJ6Oavhbqk|kmPQ&=YGZk8sJ)PG}tPFH9hzwIwfUlLO} z-$DMCnqJcV+nyC<7O=A6vaH*$ku1 zF?jM;B219v+oBc5C-xj@FGVXDVJR(q@0Or0D#0$&X;g?T9n$YbNRl)kD+XxghJ^e?@(RdQP;RMKYjUYuTUsQy&u=vz ze^2h0xSA_4gv(m@sy!!4dmwzlspFK*mp&^@G&sK<DsNS$<)GF17iZvOF&amL*Q7%=n@gW)WQk;+SS_B?A5I$z;%V9v0Y1BLuBJU>pF5qf~8@Fg~t#@tn>+@F>7l%Tv zMf~)dq_&Jyd!rZGcTT3Udb{6RtbRLZ#rNX^1CF;l^w!H33<@Yf1J;(8cPVHhnqaqtNN9gDO99q@^O<4w)F*eMV~F!xPH&{-%$JFmGW69$Oqr4wTWJNILcPAP_hZwZ zq|gec-tpBIr)Gh#mY7;_?pmAM0nX$Ksmm5y2zgFy+2I5Fc5-1ThHr_^1>OK zY@<(YnXdvS{Jtc3fA06hW^&=BxH}aYgpgl*_DWaWc!Xkykp_-n2%v?%)%sH`l0g(J zW4P=^6KXu4A<`E)8(kHSm(XBsK~SV(K6oTSP+Xx^4coQDK-Qa^|GL?~r>1l!TI?9- z%X>>_e2||tF1}456<7Uibv~!8X=?ZR?rZn+keZD>8VzLiZ|liasNB!uPVeDZ`u1*)l{;`4;OcMvWs zek)JJ(wC%pCZ1(#x7V{(Liz-&h2>!^Ij}2(7S=Tm*J~mpxW?X8Iiywj_6F<`@K1b>~?at;pq zH#(x?bV44yg|F_v{Zxr;8}@e$aZWrSu~)$mx9J^~9<*P;B_v92aFe@kY&JLYrmN*G zFB^*4D^x8Lw8jTlrQPW~Q z8X%%$Zf#T)8Z#TafZAc&ki6-hdgzgoh^Pz{eVAie7?{M&*^O_L8DI}a(^EMae0^Tm z`XseFZ-fkef~X;|CaHVOfcYSPIV(V??l_(!k@>e=OMr+ga zKm6B59q7lWIX(+6=*uLsMryx6TJiLB3(%8uDHM+;cSC#;#7N8M#M2(vm%wJVJt))f z(ts4>GYp;z{ftSM)thTo2+K&g5UWA+!yOkk17vD-qjM6+dtX-D*_DtWKkMH}6kHeZ+4j$<5x;PVJJc@sg;4DyF`MO1}XiXcpp-$ma z43O-)!_=`xW3Be!2qxx&l5I=06uCLXQy~rDxkn=twAT$c8 z&8-{MRZC6m{i~s`E^_B>)!I}?W@8Xin>yFjQYlxbK!dt)gU73gpusV*it!H(V{54o z50(XcF0jE=+tHOG?+5gQ<#amttb}{t1!!0mvvF;rV($5-d;DX^mQ`atRNjm=5~bl( zIK&gY5fq4J^il%acOB-#(BP1P)04_xPYwLG2H%xv^uwjJlAeK1x2`mj3j}B06xvvCW5Yn(ZJY z98$NotXkqsTe znFs~Am0`{5$(87%ZHM*ab;)U7O~QtE?naNOhsOu!Xs`II9~<&t6qVfA}TMrF&rWh42xDQndDO9qpboyP0U1`Rr`6X**Rv5S?MkX17@L zKwpNQXwPfx?{HRVCh<(V+n$+^<PY6sxHfaTEt{2+4in( znDjc*wU2izC0v>6L0yhh)yP&7Qisp>Nudf#9Q6iE7GU^Lmv`s6`c3)YQ(L$W-m-77 zYTlXi_zmM2>kWd7$-mBAoxBS}4){9#a3z=2cOvZ`-zNlqDX^2)wKyOeyQzR)BT7f?GhkD6p=8Xv;vc(4bAIwAaC$f3IzBCJ&T#dul14vTl$wk~2QXI7is; zH&jEFIQoku)RbZSN_%|R>cIW0fp#YWwNnA@%b+GE%V_~|blxBz2i-qp=8?MMn4Fwr zgUMixQ2Zb~;x`xHYIs{Lqcf!h*995s1p@BFH^eWt^l*f^VD8ahN19+D1^3*0a`Kjh z8SZlXU}AR=bcQAg99c+-H=wEM*N6AjxTwyPG>h(pp~|kD?Y%Iq=`ml)fWh4x{Sj6& z-e`MWKRHFNpA_$MnG0uXwdPJCgrhH$m$RU=;7T9DKT`xrOa4+X30XqhC98k%!i3)y ztLy%vsJ+o%dibey*nV~yE(T;f78)65rlWOy5hd1ZPp;r$jxHbK!$-Vo^4@uunMNKt zUFQhzrQ5Kh}Q&JJxe*u6aJ=pr1+QoDG3T&|H|n=McGZml^FOD6U3S5^rE3p zmHO@h(c|QXzjK~``W}$d)}ULyi4g_9MLMRQF;?|p$?q@RARcR}NM)UYclwFDaGH_E z>9Q8Vu8`a+@#o^bE+y+TM*gC1sOqV-JwlT8VJ^=$0`|O(%@|{w4+%FZNcUz)xiOvB zJm2p07CdN8Ypo!ys#L>So1He4$NFOt*lq9lFP+|yNYU%541c3s9cK>aaXRH)1w-{~ zGAC&wUI&7|YN;K1hTS=(@4^iJ8mgM(`jfx5?im12^6>;xbS_&?}J#*#2ZEB7( zOD#oIaBH|N1xH$1IK#4BXgMl1D_6PFY?(I9%=*6k-uI7}3%I!8I&jY6bDrmX?&ovg zH^K!H&!IbKCUBx3EbCxWl_!bc9)dTozm!%@MjX*x?ZQ|Hu}#T@+*46820L;zo0*+= zie24rx@xLyGS(t`>7;FT5y<+k7ue7G)TD1~^!%r7`D$S382WYZTFfk~dt>lXfr+3zHMG7_gY8-Tmn zqGWe(QLXldf+8rSt1?wGQ!%|cbxhj}^Y)S(zPYrRWp=MBtQW)$4diN9TIyI$e z`R>i}II|;!`~@7PQCFDTN)0>&387^|I|BpA4z&Z!Ro(NN7))!D){t}Zy5B@c%!5ia z^MoXzVz_>ce_8dfT71UG7``%P!+MXR z4K|3(wIeJ<0_)1PJJq6A)pj-@)t8AEnX@Nz*F`5z6gj_)-_J}A<#-k* zAmc=ms8L?y_JArhe~i@kVcD_4)@7+&eGPqbSQAIKz2XAwW4u(j&6Y0pUaDOhJsg#y zD->;E2aEMb%}dEM?P6HwXF6%-k>OlgUZa+vp+jWg>l!yvooG^Njr_jvkhwINpdg{p z>$))~79JMrD?26NXYbo{QY_zx+vaERiV#Zp>C&P>S!6U&^-zaV%0fbyrZb{CPTF?> zJ_uZ`)mrzy*SBnj{yeGirgWe9Q&yDI9oKxE`6OLQ$2Lx*uHTmIBQ$mY=2zjViv=uB z&||dBXVdiUhpgLJ%xU|k3nn5sHlPvhI1(~xw&cCJ4lvvKg2?uZ2z>U7yLUY2-eT+>-# z#+D^3I?7B>K~wMxlAbJ`$$o*GrY-_>W1EEwVuM^%b#99;YGOOSA7w&->IsO87}+JE z)H};iZZ|fg5=~2_1AW>SfL_PTLrXpT!(E%-b3Nvd)g7|qRcpx4ngX`E*>n=s6xYCD zUIk-GjKFE#Gr<0OfmdmmAgc?OSn7{lZB{F@|CFLl=Y9KWUw@qz$;!DCr>)?@XL)?v zPsSfFQI))3Ujw~)X!Ed6H!x%GRhO3ByLDcO(OAc2yPdQWpF$5pxW+|eU0t5jFAK!E z)eMXIR_p~|i}RuO5~ecs&rfA&d!>V&DH2lmPU-njlSTDLdhZ160BAL+dX`V6&P|Pp z!Ggi$N)PP_5Bu01sG}D_i}1olcG&abWT2c_pk&#){qD0D&K(J`j<}>5&AfxEpIuv6@!h%I#FJ|fkJkH*Y@vwbosU?H^MixA@?VT>c7#>d(-9ghbtN)RssuLL(Vq0 z`Je8Dd~#rL2Zm*=BG4Ic-(3m(bN^ecuh)@&;>RYE6Uosa?$wTb=}Urh`&gΞvMR z;V#XUO+|~K;-#x|jpJ;ZkEcqG8JZsbA0Qsn{uA){#n{P@Caa^xxqCMHPVV4;^*w3wmV61a>C#V}NhmEgI)foljYAvR@5Q zTgs3+X0L?)Es0+s11AE&^6u>)1c~d;@MnC`-B9B?`boKV;hdIVt}PlCRXb;-slf{P z!cZS_a!bj}Gch|S8pktudxg$7xOiqr7?H7>*PFT*b*=rHUc@iop)c?dJT!`9rpqMt zjrBeO?dnH4W|aJPonoLYSZ@ zvBxw;)ZK}qlc%ek&3c&q?a|H;1)eTp>~!*fcb@X1cx3F~nv;2oGEk@pylz0Y7mUp6 z(8m-tO0sNE8`PRxtt@XwLd)tJ$Nlj2M>q2EwFj`jbU_(AmLZo_XYoBc?Ipx<6TZq$ ztD}ZJc*WIYf-dw3I(r66Uc{vbo+8BGn0C9pZf5-`^LWEVV8KMgq|NGh+hTb-YtB@d zd|Bzq@?BkxGAjQS=TAnXJ8kEK;_#h!2RlYY*pldLI#c;!tMP0<6rcR{1fJ##m5Z?< ztcdS=WnB8?@}4$yrG*IW(Gw%cHDg-7+L>6CJ$}O4;dsW|w7Izkrv(6WQYy3P zeiL5ZZxt_IB3@QUHE+)=!dgGo_|?Y)=d0dL z!Z)=V#`hTEl?a7@TWWL1U>hEi^n`WP_1hKSS{jD(V7hkEmOuGM&*OMoQI8KPGi&3T z?t3+&m7#vZoicJeYI3XAK0D?;z;Ln!=4R7zu$B2CI&gBBj-NX{6VZ_T#~Lf`Q9D7+ zNfiH?=d~(0tx|J>c|jX$*jOQ;5%pK9XsX$GwtlE}Cn2lUplS@yj(-v-)TTyX_;XOB z*5+9nHp)Ugxt6QS1pt9%xComW@qV*ar0U)IB&@CN9cxE1ZY?eiV}$W=^qnKWJ^Qk? zmT0*Umjqv3t8`y}?JtjHVwm#|+$nrZa9H~d}yFm$TFBa7$Zi=xLEyi_v>h^sr z$fw-|j(}}%W=R3@?DBDv(3^kLVW|`Aw?qZvA3X3}$#s`v>MX>evYZO-QmTHfk6!K1 znk*lwdw#$H&jXHnY`QUx+~nWBmw7&+GNqWxpJrjYbOqF+msQg=1Ha{TBMcsp(I)nk zqeiF^;}dasqp~T_(RF#)D2y?*04|5Ea-eg+P%lfMFnrRIXWrSy-F1U{#fB*gYI#1i z>c;eswq{urKpj0BdQ63>^$JA4#(T4#Ju__0F|{I>X1ZY?Y0{)j*tT5aR>QCIcmd71 zFU?$Tm+73$3Z`(dFeKlOPmgu4xajw`;nEgd%=vXls7-|qYI!wv&IKesjGmgj)ETpSup_sW z*QmIr_Sv5>SH*;WYUwUbp=yWpq}VsF6B`F8Xy;neoHfpagRtY}OYZ5JQ#X8eeU3N! zQkf{+BNINNt5TS#DtZ%|l}>c!;jWIf69|ydfC#kqB|kTjp_tqmsZOCBnjZHq23g~NnGhNb-&z2bpnm@PlLiIugY`O{7rqB12TI-qX8Rb*A zmf@rpI;H8|*pg{jqJ^@0KK7OY(gd?k>fHT7a&|M;nBjoe^IK`ehHkM~cE{*yiDKsz z6eImWHb!VH!EMv#jG*3)Ut2KMYy~5dUP^^~m91%!--Kia=8RR1E{9r}mEn$BpT0;e zT?vi)&?RhK9=aquA)y_|Ip%f|mf^0V*nVN%WOdQ*Rb;L1Y!Eo=ATLnP93H%=IrPe4 z@B`4!ZFQVm)YR{{N``(ImyWx!9ZdqACM^bYsDXxuJNJQPO}#wszS4ppb4%Yo1FQ0i zG655oCjp677V26xCIDdHjXPo=EHzS$|0(`pJ^lx6WHCiPn)GA}-`a960z_M$ws6!^ zKPv(faAGRX_Uy%3_rgZb^2Yyu$M~g+Pn5)UcS~0(_?@DAN=uk2OdnTr=tv5zV)XL1 zF#NkJ+Y_Mo22;vfzi{4FteUX$Ty3*dkR3^1&^dEYi(>CL|5NV~gpG+Ms!Tv!4-I8} zXdEq=Qsm_FV&GCGnldKSgkxl)Df+Q zy_qAN^kFuC2+}#?wGQV$qS#Ci*8}Wyv{LHvxx8~)xfzS@_6v#LcI9vMHVMLSZ%+I0 z@il$+am`deLW^yMa@s;JoNKk`T!{)k_4IQ0Xoud0QmHFH%XN2$^QHCc`p|dXZC_PG zKe8CcHML%-`8x{SHry|*GnVU}$->g)NMR*4Eswd_H=wHJ>fUesN=eJeHw))sg&_~T z6V!aVWc92U>~1!AyWZ8~9w~12bP4O( zn`iLfIfE_S3BI0erE10G`j)1zj$0S+*C;%(!%C>sa{7OQ<#tmZMa`YHs1DrJhtilj zHR~>?j%hdIBmY?R*&Diey!2x{ssA^PGKw_U7_Eh$-P6jwqo#Yhp|8reuX8@#DAuQm zl2Qlqu>4WM$Rp^sRC{XHtr*B!DLyfq{Ka%T4!6-77C>e5q_(^c&((-Qhgr#s{A2O}EvD zbA)dN>DM**!W$n|9ZWAo3n+9y$l+$Z2X+}h)>WHXD>zP;KF_mWFCir|V2^<8516i$-7a@&lO{VHVV8t}Ab{!$R-roEs)=OI|nD z8S1OXO0bc;YZpPli;)S=BU!wc(naOh#AHlt{yLo--tpr|oPWdOc1Sgxy__$(Cpe9L z>S-+AuE9=XFwx8?WtY(URn02NDl4yV`fj-V7zG#4?^W?iUbed096bG67xRKBaqbt* z?{k17uSbK%nCDde z`=X(*RP%oTTzkD@@qBK80<;OxG@7?~VhTz6TtaTIxBT{moHZXc&v^3mo*QX$gLA#V5 z#6QX(OQ5@c3|%~N9aw(mL?rB$zry4WejAH63M^a-n2PYa?zbg$)4F2ir~Pg2UU@*{ z8KV@{#0#IdylLkxFStm!@!t(wNSN(;X@&E_um9|DgAVx3D0!|?b+jJOb=GzFI25n2 zcsA7K-Czw3RIz9^-B++riR~iNXNGQ(Bj-3i*;#1utZTP29s35DHJ%*NGzNd2dgkUKBSZ56gId1LS7T5e;e68}svOT#8Mtaq9v2eEBMmbs_P*ab6 zMH`y_WusxrI*@Q{E;dTZB=7R5;y^{>Hw}zg;>UEw{QcY+ZPixn-P<>gBtk4NfxYBz zJEy4%`QP8I#I%&Y!8uQ>652_Q^s1 z;2$q&_S1jqq$;W!mX)#29&zZtWGK)$^jODbYzyy?>vblO?l@2-Q}ubBd+g(74PBl+ zttSoWy=>s2Z`jK*`Yyowf~3<&Z>&=w78P9Txl-gnHBH>~VaB{bnrjIY zhdHCaRv|(=h2(T4CSm4;T7#BaDc3>hMtNs3fqa2+lE}}?gh0;vPu4pMo02V7hKiM9 zMcgc}_+6^rldncJj{CAbStTuNx^J6q5H`J*!Md7#t5)u}@#Qx-Tf8-VF5AO34Om-t zCK>Ou&%z9T-MD)!?Z{OOw#8gHgY+t!$24>3O4g0lf*}vBQ1EK{9qrM_iHtDm3#P>>6A^2QmjtZwdacwU z&3_bJj(Ahnftu&M{p+(_o$eYU5Y9(l(YLuR2&)ksI!509U78Sk$#nkm!FQQn7pbRN zU9(}^b-*7UYc75b(Qd^lQlO{ z&>70Lr~j>bpENj=`*fMN3VW+|s4reLdqW&O1Uc39LgMQ>Tv5|9`bUY}$^QVsno^QI z6G@-a+1|?NU^Y?SSt9M?kC-&&?X6ZDP*d?&gvARh@t-mj|pSS9dSMs`V_o zNDRpz`O8}~4V@RgE#5R){<_AFaO4^Klsg$T-DQV06qxbd5omA&%&K|_?9p@+yXuT%-h79tWl_ji+7-Px_9S4Q!_RHQleXD8l(paGc468a*4gmS1yCNTCz$@lEtOqr#l@wg}j5uwDW>#UHIV1SISY6WyI{;zOBbeP$`n)2`eT~{gMjp)^kJIJX1^hRSNm1Xch3 zztEI=P7Q`#)KMc&T0iw|iEgT$60wNfQhR^t;lr?iWT{leljzL6$=Cjhv3&2PF1v*l zrUei$PsC`c)etT7@e=ll9J|6MA5HE09!;*#Ox~s@oDGJ$I#dW_Q=a?uPuPVg5dE7M zZDeoh2!?umfEF5&FL&BQPIMNtxXFA@UN6ZNm4eB&C(1bL#9HO;Wv0Ss>$5mAxk*!8 zCVm!^Dml>(4yUof!r8u+Xx$+0ws|FIH%=j}yLj~6rS!Rrl!&KZ!VmFt7|ZP}{Xh0B z6{-Av3I}nhEUF<@JY7}H8R943Kz6XJMwp}o<^Y|~e#+ND$^R1YKQ?oo8&-9pMd1%NnBs8rc##>BF0IqArG387Xu8!<>X?6&%k6?oj*f*C=-CK=nz(q>ey&{~5zG zx8utQ4Hvl|*D&(?CLYlntvn?s=H!&s{8g#a#TVT8rWB^9m8_ze9_Qi(IfV1imuCuz zl+HaFmyr4CGU6s~KLvQ*G8Pe?D2FCf^|pnDNmP7Cj(CWs36r{-F4@J-&?KRk#eg-k>fna?riC=N4k(*a9H5 zpf6)}V+wPN(=43>@G=HH+hpFswNvh^N(;dx6()#!%N;e-dUc?zlgPsKduxFDjVBRb zEBxlHI(_y!^nNPox~F#!--F+|53WWH$-m+Paw>|v(ye9kr~gJB%4=iSG#r#d<6<=x zZlk!K1fkN$E=-+Z2#&|y|0R2_>ZVX~kXk^?t@cDk0S#+sV=1L0jN%0jDC&OMTRZum zdY@riZu)P@SD=JfLCae5=bcu`9Nd`pC*z?azG_yr(Sq`Gw-MzskL|0Xt~YHwhx)yn zKt(R=a#mf*7nYpd7+(+H7YB7=*wTe5CIIgjU+rPixUDho(w>J(C{3)cdM z@)w2A-4<8RRuoVJbvzgL^C)er<=|S-Igj)m(q55K40V7`d_FNedwEw}L{+q+s&Po& zy`F`2OLsAQ7G(Vvc^qH$tD~{rKNP_QnsfZgU%Tb3RsT?GO=ce#8Y86CU%D9<CCT@(ISDmbfHr1ndNY8Mf zWi+p%i+j7m3)Cz%T9a;4->2W~{B{MDZQ$hP!4~^%_QQjee(`g&{%K}CH~o=$QH6(D zO*W5=ZMv&-e2cq%2+|SQRMr_fpFdnkAN1e%2}sEl3)hD)J0dEVZRL9|)fQ)a$fk#d z1(;di8tJ94gU5xwmHAvzYH4#GXfdbE<{gxQzccQfiTze7uFnnpMR}twra>A;y%AUO zu(NbKYBK%bZcFDjdKk;zXYwJD;u3o=VwCUr{5B#R?)`2ekoZ!KPu+QV_{bW zxN88ofQv0UjDR?=T1$YHzzAiEYm*f9d!j$qJ*ai4!gM@SH$!W^A8C#5(te<++}!lE zDJncnyWA)>?5sGi#-f6NakZZtkt0WvB{h^}R5gix9q-2LEpQRP{;nzMaT|+EU^4QU zhzu~RFL!FWD?VrX+s;*`kOm$yTEFJR?;5d%`UqBM#0@pA7uHc6L zAh;%K%=MjR*~Z_R8Xa1-RkT^KL+KKM%iY%u_W-x{xVt^mU3*Xtk2gZ8W5&G2xmy2Z*)6=F~u%+Bj(^U+j<{&A4c|2`L81OIL1uXh0A@* z3u49iKMI#`l$J4Vl$>4^F23P(7vuOfZp{kRE=0+wwl!-d*4lne8ZWP(`sZS4#|!mo zl^D(gLydkOp&q9@Ua1i1prp6j3?ruHWWzy@!m9rA+OmTah$r^&=7YS!X2A} zl>O+H%qZd!o!;N4okekYoB~`^6y?+X$SsYbhGy^tR46~1iP9p$N5CU3%UV=aZIQ+YN^>+&ZP;Bi2EOkIFIcO!q zBq8aX9Fz>peCP;1WHz*JQuz+WIt`4sPN+C@ks7gHm zm~nBlx5T{^0EBUf_Pztma4QZcwdn;h$lTeNL7I3D9%0h7!IBw_O*ujX$wGPp0Kl}h zv7#z`AvAj#@QIQE7)yJ}QyP0oraFL!Se397aK?JO+e)Yc;m2$>GDLKOq6vBRX1 zaz02ePNh?@itD?relimC$Nbhj4p9uyPFS*N$N+T@p*DcU3o*SzKfnJ6xD0nw`$g4p zIsgFyH~=U&$N;%S1+!VjMs~>Zk=QAQ0AEwYUCI-N}@Oeex*(+4V#Sn{NWL0007VR4+!>1()nW2 z-5>@q3nDM4WC(oTp=HJbnR@WgsQP?X0}{Z2y4BJ>JN z7pzNbLb7uKIi*INKb}CosRcsOK=zEY1JsCuLkxG$M*xIY0L7XlOiEAQY(f670OB~J zR0OO2Yq>GMs?n;MLkS24S-4s_SA&8=MtWa=s8p*A0bqgb@IvB{%`qgj0E39tL~FD? zAD6hh)p1mU z5TcRE8O9O9$zD-PIh;#FoZ!a1p8`SZN(UC230Pn$7D0NAP_xj0c_T_WtvIXCz~4?) z>3(SqJa-AF3bX*gumJeNV8H^i7=$ER$SF@>o0wlNwz<(8Pne|Zm2x9G zEr6vIA$P}vg(rF_3a7$TwSqbaAQV891OSXyz}_Jw5D${nmx|j!oPsf zkp{9Ixi~=x5iJC45Ksz6RLm%8JxfLDl~MMltJ$%M4kTeCp;%<8>T0?-uo#O3M#dI= z?`O#9jhy?0K0RA(ivSGrJ{?2=3}az@Kq3gh3467&yZNHP*LETB`rJ>r3Hlp|$Lpd& zr;D%}$f_8GD9wL`R+ijBjtC&yOlI_w&GrL_;#_CYX`Jr^gG>*Sph=vO4-xE1Lj?uL+O;NN=T zIWkor0Am(Ns0BjW3J)-#X%LP7uzv7?feN4DYc3~)(dCOq=OuASBKvL&+2?SWO^m)_ zD049bQO?u!F<13%O%PIgQ^pI)i37r17U_eLxHEna087QffYK+1evRFOSO65ueK^Pt zAmlgep!xmpZns0oL&GJ2Qm-!w)5=b_Pugpy{vQ&_WQt6 z_VO44mT&-O@_1^3?u*zC_aD1Y|^b0 zxHzV8kuTvcJMLj10E`a+0|SV7U@-@xn770?@Xcj|EBdZ71a~6^_Mrp~B%%SO03-km z+Cd`$7FvxbC1!ooMDdz!^$*-}i1h!RsX?6V?*Rd?{_nLx8fVjDBb4K|3h&_6<{<qqD?7)ALnJzE7i^f0&XIZH6-SC`YmH?&Q;lJ@DjAaAm6?+&-_0Bx zj-L99K&!47K)3gihH%yCvVvz!VZv{p-KFf>9X0{Hq;=rBUfs|&lIq_0{QpcCLn}zd zA3Zg}IAn?9dM(@1`XEAnU3V*J*YyA?IdA>w6Vkgh6St9Wuf4Q7;YX%? z2%^>3!A0u-vlMi(hI{+0&hT$W_q&NTWnLxOJ3^Jo%9K9lhUCHk|Ioj)!@#eV+jSj9 z&*CwMihK!UaO30$@xaf^#Gy+aU%#X85~YJ-m%QlnE9)h2oo(xN*BjZJ%=}Z_!^z>+#DV!&;_%Mb9sP6Lv8eD|eEWm8DH~^H}5Ph-L5(r{pIU zYzd#BHPUgOPSV)k%_^bXP-|;U1k>Gk_p%7h)L;$ohMxM(uJk)H784VVK)blO0L4W6 zBD&&=Uq#xzx0Gp8SH*j}Qt5(gK-V?P;Q~Lz)tr9qidL+a(B5a=!%YwdN>sJl9rK%A zWi8wcJ`#t^XNI`eHRg#~HKVxJ@8+nO9m9a!D3&u?anWU1^D?|}0Nib7Yj%#-^?VB!Y` z(5fDjbCnCytDnSj28N*h%6xvkS8cw%ArOMr{>kdcmGC?;(#mFdI$z6vB((b(C3S55 z6n{;~=x|#6)spz8(Qbnw$VRNxfg(Te!3ESY9!H(9%6=`?tFX}BM(4_CkL4+>vQ_p* zhT<@T;qrC&(>OEB5Ap4XUsKM&^MOpi4!UeKzF<+rh3symF+JLe4bnA}V+-C^_E!Lz zr?kKKt05xP);L7(!dq+`ooUjeVe&NpEF_M9=$kUeY2*$ftK#IE-exkpjpYcxiAC}f zuf*B;dTWZ6i+wx{#7EaDJvw7^$5mv++frNt5rI5b3Q`mC2e||X-+6+_I1;=WY9Ng~ zoAbkoM($#!2m8XlK&#O!mShvQeujc84oR~mol@}%9X^uUT^btTU2Q&4#&ly#ib;sd zy%*frMC-#LOV5?tyGck=83{&^@>ITj&A2E_>gYB7=KXrtpHK6OXiNUt z%zIN^T+BQbtt}SVY4wLd&QI#)ctdf=+|_@OABxd|qwCbt)P~iH&mT5gvim63yQe!2 zW^6AZ%l&NRxIDb3Q2#Mndz|M;@SkR~ zvA>iCviN`Q@ooJDzEZDOpp6p*cZ2C{2DKKlM`(atG5Vu*PWfm9S?WZ&JZyQ2m^*G6 zSEiASbHs1Jevz@1PvSv(PkeVurNC}WxyhYCE9AM{fFV<6Wi0|{ax&guR`-!H9Cd!| zpVDW=lA?ysra8wjjHmTkpHJI3RXqw{jp*|;78k#xKGI};{lK;p46VFC0x2jU$Sb5> ze9OKf(|=O1+Bpe^H$dX9oqD#XxV|EE_i_B!Ow2KVq3T^5XWCsaX}Hlamz9D%h@9mo zMG3a0=SPJUALzY$mYy7C*JYlA6jnY&%=14G^C0)yd(77gIgXa z{DbdYhv9TNdgTMeNMdP_E~h9wGOL;wyl$f#TNJxF$XxqlN;xupo;SwELzvpD@%ga0 z$gL7!O7=|a=ZiC~(T;x_+?sW%(PT?us-cce=SvBy=Hh_?Dw8@YM`~INx0Vo*y6*n4 z)N;P$nSTjmg}6EcL4`m&4?Hg8)er?Cwfb$Mzf6(Xu=FI?`N9oxcX%MaAhaASV z)(>^#b>l_vM)fWI9|^SbrK&_Se`X1nRY$*(e;{4IdteRJIuY#1pU)B*slR^XNtMut zpQ}f$Uzoh?>lJt!{gpHnJ|>u? zy~xwJz!xja`0J*{87Fk5$!48UAJy} zR$VIYHMm@PTnMslg}@^4w&9jb(<|9O;N`%~0D_~`rKBHttM9>}Im(@8#J2rn zjgV5I3j3N)xv8qB9gz4dO^Nit*zmb4m&E6ryE~`Y{UkoUstaMUsw5Tfh*1_8;w^8p zR|pVA`lQBy*8CjaTkNuUyY+#Cl0yz1_WAOOY&I&SN6|GUJH<#4*`itIm|1D+iLU9+ zwsTe}g}$Lr*|jGtQ{yxVZZ|m{_?8W?wH#NNAG$Y0PC0put<_$W9~=x+ASsJcp?ggb z^eM>L=n$B+p6`Y-g@(jiW?3c9@4hm8mypJHS!_1kQEDwHWhBY0?Q^1gkbRJP?`% zjGq3)Te9de-IW>8aVq$K--~se?)@YDP-vc)uabrV=W?qz8ck{DtL!@`;Zus2g6NTYc3`aET=^uUO|B!9okY2r37ViK&Np zH7&A&GvNm{FBP`QLH_7Y5=R={iT%(jBc2zYmbT(i2P40ux%9jTsD21~} zy>2Z5meaUnFHZR3tO~Q&y!R)2AS%&b*A*Y-+Rn+(DbIYfcwIB1fj%YQcpi0lndvJV zTqDi1p&MadI;qh)snIVcY00m>8?783b1f+H48N5$(|+5Y?KO${SE@#ygbrd~<|kdu zP(VE^$dA_VTDxaFDkZv9UPpXu{2hq~f<<^vk)y;*K1#KLXXNYezxT?9FKEh61PAfD zOy~9ke)I{GiB_MWy9zeP5C^(}iJo05AUB_^+lv_q^ z6fv0fp(siBUhp5GXop9>SI(rilyGfaHJZl(6X^(Cga-X{PMaH1ii)>djY42Eu7%v0 z@9HpkBbg(8BIxN`?sHuq(MSpi`5!>*QRqJQw)F4b(No!G%FTt;?BO2@qMtv?h)H*J z24zbgqO7Y8^DieoHr!9st=VwR6v&~qY@2Vs-aS`v^mZs08zsr_0n{pKS-8%t9M`43 z9i8U*uc&oTr3Rk4{YHAGyW4pVM-0+~-^FB^o&eb%C0%EcF3AM*qiIM|NtVP9+3Q8y zv<*HX-mjFSTw9*rv4@njPVQBv1PjyY<&d-V?bAV|Ctco`%Vq3N;Cgc z8~R^D!%k_q032N0|1YCqCp7Z92(*rcOOSIsEu*AkXl>^Idu~H_BX9~%f-JW`vfzR| zLAa4Lggn-*g_EjfN1zJrgxJjVX#SJ-iW4S>VnG3&*kkX`$;E$F+t~ec0QyHq-Pry#iZV-;xL6i{koFh2z@`J3x6BdsOOicdN~B^(DJvLq&puCu zy)&Uj86?TDD?n}Dh;x(WHG}$3AIn+E4Ezru?tKNXC(fsxnVD~-ys(gL3F9bKXjwPPX^DW9BapYQ&j0?_}Z#8Lx z36sr*bp{CMLq+91A#310vwq`uWE`^85LU{5##S21FkaLej#VB>!HwREC`=mUJ1^sQ zqhlx)GmLrWXx*w4VFe-@D}O>)*G}3_qjT(^rg-|-%#m+?hp~Q=acX?5C&i}UeMG%O z$XUbY5*jM51OheFitbj$@?v18qXOXhwfzuKj@K2xG^1g7wnl;y!837fyUFCagddb) zFExBnE7Kq@G>(Zkx!$jfs70KmCQ=F+M_M8?S8gUJdy3MVg_3{1H<>;QZYvKHu}<^% zi4y6T9nyJ`ZySAEDdgsXl7dXR3nn@FMhLvg_P1LIdkXpd2E8bJ>xAUxh{u^{mF!j- z#OSxU54G2y1W6`m3h1I0-xT&ASCfb5k~Hw%JB|C=XJ4LYNZaaDdh=e$+VsvZb^MK zB<@I>wcDe&U4=J&b_AD|M53TEqpHVWG(_Wo!BKl(H$RPESTpOG9w;8&9Mkx~iNz|= zgJ{gGYZF8HWe?mI^TR`|XBY%y%Vgr}_S@N2EnyYQ}4kLY&k%5W<8tqCfk2z3;g^E3QmupFI z@^f^m#Ff~(I1KA4o>ZkXfr~bv9;>~C?PypQkix3~ zK0K8@^U0vE%_+PykaQ^XmuZ}vqD*``TEjnRa8*9{NW`U{7*&!v{|KoveR}r${)LVB zRJYx!(pmw=a(w7N$k>L?`wsE7Xcygo*XlYF7_akLyYH=J`S~iFB%P-=rtOnaV?m+R zfV@DYJkO!oUrM=&6L@Q&6ogbd5bDZ*aKcpnYTSJGFx8DH$A7BG+=Fn?rY)AU>pUBg z@U4jU%2Yb|>tliv*=v8#@zJ%qTmA53)ybI>*Cn$3qAg`Mp}T)hocNX?oi9RpPy6}f z(&25LWOn5*YZPvzQc18Du_ioOVdady6MWW*(&*?EC4$aCCd8-fth?ROST*fTcK&Vs z&5nOOweTo%=#r0o4Rl<7y7(P7RilG_NxfTZ^wd}})$-sWoofRE zFkF9$r!*Tygn*UR@nbKR)?J#9;4l+&kO(|rK5^}NzH;ut!DM*ySDD`u4>mYj>+R1Z z8(PntFX5Mf(UQ&YecwnGNe(z>5`jq!$!nzUGLhIlYf%^I?MKCsmajZ(3-il+%58}G zKl|@Q^2mNyqwf~g_KSbMHjw*3g-%{zsKLU_@A70V%vS)bBu4UG9;P{7(NBNq;Igh@9yMT^z)iYty(Xq5BM>DlTy_wMRfa$9Ng3!Y= zg4>f>n=3$;|%`5V>+Bc##dEpd-@O5}*F9Ys;Cn^hMNQ0v{LXLSFwqS@c^rbCCwGhAkqT zM~SYJ8eV1vk8P^0M*_z*RHhiy^(*;QiuP~f)ll#*;jj{hQ!-PUND#Y<``MZ70QrQ` zDz4xuf9K%_`US9LMGIpS7h+1urIB2wKSj0T3z z=g6fTPN~AJCZ(^?x3_renlRf~|C~-THk~MJ9)4d-k?>bXEf|yl(GdiN%FVM{Kg-s4 z53p;Fh$5|5uY>pQzDQm-EZQX(xZ&>b~1Gk3>y>q6ptbnz+FGYym$S}M*`M2;K>h%HAEWq@A1=oGg)9F+tc$PH7)s?c1_fgQzHg9J& zXPaA!u;_H8Queok*!+EUpa|hFjMNE+AyTR#&@kgYOO3$(1I)7ZhW`VE(@Kq9 zMPRCM_ z48lurM3r7m|A6$ipZ^DJjLuP=8B^AJVg9C9zYA1(R&I|C8GdhLYbgACKg@Rf-f6Jq z82Cl-{PZ6nNv8m0=zq2TS$?~*=BWlqrd)ufIfJ=BT#2#fM&dsWZc)1aWJSL zQjRkAa?f6=k(MIJrTEHRxFg^GMq)LO#F})A9_E)HSEwj|r#Rvp+4Zo4SM&$h8JQBz zK$B2aB%Wn?<1pr0XoTVCn5kW~nTi-$sncpT3oNP!T8_?w;K-zvq1%=Tf(pI8s5|ny z_uwBW9^Sp`{I?E5{T5Bsy9QqWl5o)eZJ2`5W1j$Hi-{nZyY4-!2H}L;xyP6<|H{}` zVvMuujRPlKNBBo(TF^~FofC5N>om&DeFaL}sUt@MwEMMfyR?Mk)#v{Nlz+3;CBOU! zsQ4$CQupgWzz}!j-Gtitw>y4g}`C#wD2D0j5{3uM1(Cv9bPwKb1jp&SlmI&?XS#L+$n^h6;Mlv#gCb6pk&_KdN%TG7$Zl$dZ+9h4a$O*QCX zl+c)qL2@)a*Ac6#WG-5;5^dAO>G4M{A zG$F3Xq{4Yv@4>LPJ1DU|8Yj}&TE{mIgdwDeanF}ucb_U>qHhf`f|~dtwmmaO(VAky z=t0&BB*k=0J>Yp0)H#|&C)%u0Q38n%Lhuw(XZKnlf(RgzM5oZ;VnQ}$q?pTNh3)J` zkAh+JZa$PZ0qj#2TZ0=&x@d(QNO5KrFVo7vx2;-Xb(X6z}wRE)-wLi`eNZJ&HKA^e;z_McKfbHw(~U z*hFJw#a@I77}^ktVOX2;`@#?*!N>H36a0$AJ7YGlLmL_#U1m~8BRWuQ#EiNw78LqS z^%5Nk8Wc#B!$AmJhwv_rf1@EgEo^h&ku7X{7+SH=#NIue;J<=|1x(c;bVON=L^Ln4 zFGQXO;Q~f;gwH?GWNL&I{)+whpJG}TgB@8pR;#my+8lN04NXv00RI50s;a900IL60000101+WEK~Z6G zfsvsQvBA;dATaRp|Jncu0RaF3KM?g#RP|3(^-omwPeem_LD&bCYADbyn{V+hsSp}| zk{ayjZoWxO3sS4`aYu%Q7X6aPo_}bRbnSH$XM|fPt3{S$P1M7swZYthat3rrk&q zp_gDB9j66;9%V`fXs7c6YiDh&&9d_-xMcM12l1+E*T#1{2Wu8@j1UA z$8Y1e{=(LS>Q;w3N}TIJ@9q%W9c%EyW8n}{^AjCy(fGMaqUl;O-?svbUoy!}p$GRl zzlBw1B;C#+kBCx*-OpqoUVk?<$w7u5t^%_K^ciRi?-2ZnVO+(l4^VBn>JNwU9IgH$ zP&tr8q5+_1&QM$-X~qG$kP6pu#uU#sqKjGc4U8Z(lpx#)h*k%RmtZ;KE+;-Cg2yjp z^v-GZ4_T@&iOU=VDj#+$TIO9C_L>h1t_Ts-@PHv8isrYgh#pq1;Fc&kh*_$I2ews| z!Td2`Z`@eCD0d5btxEb@fI&lvU0Mr)xbC3+UGPK&VepPamHB`Gyy6X&`ISjnPuTuB zzaPQHIlmK|@%(oFJAdXjR7;W>NA4ISa;5{};kEf84|@jR_cX5F3HJsbH?jJ;VB@M? z8ET>_Y9FY9zV)aHbG}lp`{Dxf6GsoJ@r8@1Ro7w$Mu#Ge)b-C?At;NSAG(O({{X-i zJP^D93=YT4x2Vvj>`0wh@L3-xei>yutCRxuP?Z`SWV=9|#VmhQHva$;p(%bDbAWwI z3by55S05l^7sPSRBnDb162h%0_c%;J->GVfRHYIghOw3)rXYX^gaJnw9ZO6(4_7cE zijFYw(MQYw0QLn+ytmw=pd%A#g#cBxMlv#4W-v{aYHW)tB>?66g%-;L#JDlrPG;_F zLKO7mJ{ zdqBP-6;3Vzc!DSyRI^|PAIGYCr>aqlAske{a5mHZ5R#d2BtIhT6IeD|4;2+!sG~(j z1`)vG1ss!L6IMaTBSj;n+SZXcG4PeW@krA1Xh~2J^{^C|#$7SkkBEt9(Gp+bW#V5X zw4mO}L?D%O(2XjDtklmitf^oJVQ!#A@IMmA(4|~KF2307)TR+Av6r+~y&zr}^#P73 zxch*jEyOFXQ|eR7@`+0_kCHABS=Ig}>84!jf%JlR)8yi^&auROtN?`(V~jL$lmSp9 z-(Xu`!4mx70rkv4qq`=_L-^+We+Lxi{7!Gj@!RL!x7FE{V~9a zUrCV&yy_o`bIrH1bKBL*;QU143hHkL=!S~ms4;?}*%(}TacgbN#43Hw;q?;4tc(e0 zMPlI_vU;bgdZBPBi*|;enPTPRJ*C{=aS$5faXre#SQ#nz1Oe)l1hDy*3?DZH0{ete zKH+AI+z<}0FlhTu!`Je%+HY$JvUh4}qwRnSA1qur`Tqd4JYIP}^A9bbPx*`$M|J-I zn6%mAxA!-rsyYS!;HZfLt-9CDL|;p<3;~kj>QPPq6S2#;3A~El&VBwX2JG<2NdS~LN3o# z1>q?0N)7=2JO2P2{vXdCC^kPL9e(DBXrcKwYQCsoK#1Vky8@_k<7}<`L(p!r_W=+p zIbbyd%u0lV2K}OJ2OeTCN=71}1vfS;XUIyxP6nmCBA#1_KJ@-!>#|D~nz$$pdG#^^ z7kWqPQ%Mh=XS{?L9;Mm(oT_nbO6%0(fI{P+c|}BWhql^EK(qJ(T1bFaA2Hf5xl8(G z%Hf|v2~uBa4rREHR%-tM@hDZnD4a~@oOFT}1>_Q0liniBwtf<1d_z7;mjl3wac74t zu@XI9HJf!-L8BQezE}cNAyD!ZH{1m1nk`ea6M%Lzt0jNgxhAYP&4!R6_-+&h#Z2%Q zsY()}2oEG+v1riBKrJ>S<_$m?w%h7hv53c^{-rL6+a6SbvbtoV9?lY=d~!-Us4N-C z`Tje9;otb@@cvE*>fi-L7X1S?#qfnlUcn+305=-p6feZOw2JtQ4539ZI)bH%AcNE< z#NMS!65WKao!n@LNN@`XP?znM%R}NR5xA?CrZUn|cWly&hF(CAN9C;wgYyjIUYm$t zjEvkU+Zu`Ck9`RseA;tkX`j+(Tr`b4Q0JY+gV;W_#Q?f z;#Fgjm4vVX?2nL5QG_JCu70A}kmR^6K(9dsCSM8LqvIlG@=M+z3m1#lAPYJ?!TRk9 zmC{LY4)UQF9FbpL(Qgeeh|foMc>rX z^DIg8Iflp=equ&Mxj3-NU@Tc)^-1m)2n#%-V1uB9S{`5$wsDP^E=Y%gj#)$0CUe|T z#uSjh18N~wtCk577~$?20DX)IUHC+lItP;|pX$>5L_sc0L-h=f4-IS;=qv^e zuq>&l11YkaLKTwNkAfizQfxmfDHg2ZJ=7R59YY#}`0xJ!nvT^%rRoR`)Efk*QVl*O zuE$YTjg8-pg7;N^b`DEo{-8=-g}-wkDdu&`WxBeBa*(d@^#+|tRZQ~&O&1GPw;LMZ zfdgd?QbXm;1=wsBw9*jg10~x=#OQcp;(7-bgNAM>QljGHaC`zOU#o~9t!qao+^LEJ(imzLb;`Sf!B(o90F)jHs?*|a)H|36 zAi0$VnEn|MCBj(Rly09=;X+FQyqvEPosq9?3xj}1CJeC&=$`%K2*HAar8Q2Fjn9Tc zTRu=4fx7bnl)jl2R08w4Ptt50ClsVmE72-t!5CNn0IoAjh^2hS0HDYbSI7PYZprGN zsGt^D7P7@inekMByh*A~_M1c~#1ztL-*{xJ3ZiaBL&6I84MfXQ^s*!)5UhLJ)U@jwZwz5A81mR;1K) zH^=;JyI$w?Aq%|d-|&@*ZA70OMWL>v7*-3n26?%vVJPTfn@^|=N!>)i4uUQX@J7u~ zArPZSbDT}|#twOilq!PyocowE40=*=rY2R4Iyf*p0yH@|moZ%jaf-#c2NC|lf)BJL z54BK1C!J`)n2#Z0mCD^lFbswPDQ$zQ{ z1qKagaVUH+4tq#v;t3D|k?5R} zzaFKKhqwce!}#s|)Gd)%L@MYr{{V}MT~iqm!UF!0`tqUmJBCny6B`HgVY!sl3v@*t zB{Wx*JlL|?^&SG2E##I>sJSV!9}^S{Wg7xu(j`iYTo2HKc_C;iE((F%uZC}DQm7fD zym*#jrlW57h`AgJgg}ZGEK3`c4)N_&7xC&t>JMA!{{Td31bK&>W0PThwB0*^fE9T! z>Miv%v%8*1?1};TZjNyI%tnzvoXaz#G-@CQqdw4K_56^6L@7u z!dT$BT)gx-9go=U) zR=hJDUS*VZVk2R+^NQO(*zhhPa^ffr*D)PcjVIy`nnQudW99?by~DvpO;!&iFbHcF zKQXm#CaBQd;XkP9be_I4BLRH>08y?OXC|ItC;tGlG2Ud*NdVQuC8>Y_$GF=JT9sv% z?FhPu0JgG)(%dQ0`-W@Ct#eQe#<8h3k)@arSrA1uD(qQQ@Z@-y0SS2A(9mq*QL*Z| zY@tS8Y5`2ZM9}xlwGexSEj^4r6?eag`-zK_H!BRL+3qJ_8W3eZY7!vifs)1NWuQa??R_-AJ#`${q5 z3)n`{i}4WIq+LKo4KQlrgMN{q@veJ==p|EP8V&Of;JzYwvPpEvwTiTCjJLA1p#p zLE9U6g0Yn;cFHW~U8>uKU|@|)DPj&~6}`-&ar&e!Um*=$PsTf2LEv2EaVs2ZR@Vu2 z{{Vg=aNee%-!TG`SO`G2I`qmUkEmlt`^bT^7hf{#cmwJqV!HP?1=v-SirNh1%et5#*)s)-V;HX7uRC6l0*2JKM7Kpe(7sw?IgX)I=il8`IfK-DG9{5I z6G(?Sn->7e;R;)qpzm=AJcwxB;(mer9}0}cxi1U3Mqm^Z=7HC_^SkO4)dRJ1y#BxxYqX^BemLU}r zeM^aI--rUX>43`mj3bDOoI`aO4q~kc_Z1Ko?YIS|$OQ^2e4<+zrd-=HQ%;cr%V$#{ ztu69Ho71g=G>IyxlVU*eC3QD;E7T34*yyX5DC}Uodx{kOMgfaiXgonkY{5`fSVbOxxKV%j!NJ!LiNd>%@aZ-M_`s@P2v*R91M-Bg@s2l_h?yGh zJ}h~P?6Te0h}c~<4i2I$bb|n>1Q^9G0jWrgBs{@!2M$XpDeQ(6w|w}Dx3>}HQ3?*n z5h@68Wmo!)4LCt)*>MYTog^X~xDYJM4k(XHjhYJtQ52@KI@4g~H|NaqrOS#0DgOX- zZOr|2N770aTvBVU55&wSIpmQsw_0JTLH3GB_=2D+JC6w_K91Nst9=dE>xoER@DWtg24k58YVijS2pHj!!x;0AI z^%Te+;%++Oi7B((8MW&oT@9$c0)p%STC};}TrwJk{lrop;=BiF+S6pA4Jq*xP!r9f z5#!=6QwK^nQ27iXVF8dhQGXGl&^z-5sf41(4(3&AhXODY9VPWfz91Dvf}N`Ta}tCf z#N4ti0lI7w%UpOIK}aA*;b{+(Q-lB-e-IY9`GG7b`JFDftL89}Q?n>2fGm#@2#qHs zD2R^7d{qP}SQjn`-`grHwT(zoTXXMaqg&z$TKSd-2$nR#0ToxN$>zHfRd3Gq1Pb=X zwf_KYcCGt~rGx?II<6lPxUGutDJ~dP9XU8lc?~y8+%{c6-WXbA0t`vV{L#&9u-1Rz z30>B5OQlA;gJa1E^akT-3jW|PgRB!kBv9n9nO>Lf0d=TS0KLv_Z}D(AFvVWH%jJE* z_mYYL5mIygz$n^`C6TnYSfba47bsk|htJFaTBTJeUnDf3@eM>Xv69MNcJ~EPZPceo zA28G^2(%3jo^CFHhXA1h34Fq}4$8+n z86b-7sB%&%_CTt~N^P`xVEFSLQ=QDp%yEpODFGq(7!&Ms3fFAF1TN7s zb6?^N+~mQq)MsVeU+F8ikW^0IkWm*Xj^kMI7q}rs^UTl)J|ZaPU=q?nOod^qSDDM< zIKPk5{{YaC&j7=5U4ONph0_?&MxCJKk$^hwmlp~ z2Xbr?*c_fF2*Siw69_I9XgrWqyFQ~!)IG$gEMPCRy^hL_t8TpV zmqj5)Z^jTE4-qbKMNki8M;RzMkArZ0c!*s?+_WheY6rFmw-z1%GRB&B5u3fTfq7Z4)!ehA_7 z%tq6hXzDd*ZD6{POf7~1(5MT+3=wwbb6j0*(jM53eF&hEvBY4zlv4PZgo#K`xfB?Af z8OpMA1(hOI+X1Mjp5g(X{YRoATB0E)umJPDF@`mr3wEY}+(Nr{;SID8>L_)9+g2j7 z;}o&ms>)?IDa8ZCx(DtkF5o;sd}J+))x1iC1W-UBR3Ee~;nMJSG0kKp0q`~ABzvyN zb(w9pK)}v!vc3drE|eR=_bZ+*lszp#fmb?>5X8m#VTa|HTQckhB}KK!hiR5vT2V<) zf;7>)?ij&!6b3;%^uu@&%kBWCrHE{p(97s)r~)m-07MWA$X3&(JC|nLm&8tlzYGYZ zU+M=NAS`NVA7tE>ZY$x)-oNe*$G0(LtLAPg2G=B&m#=nCXmcJRc8{DuD{nJPJSGWe zaiH@F+Wf?9sLyPSC}~6hN6ZW`Qived<_L9vFp4Osy4C{V0q^1!D(%(4>!M&WcD!P3 z7h2ieeZIJ8=t9l`eGj@<8bs1qecoiF{mor&6jBT`3(Bn~saA zNE_1EaEe}71Yl1^Z2Un*wA-f$*a}H3t50(51xLvWbSOa~MsO8t(H^a*H{8_a-g<*r zTor$Dk6;Rmlt8|F8kW79WDuoB;rgjXD!dS;yob510tXwcY) zPlh`=<>pw~;F|4Q@f_uVtOTKe8oA4mDIHD8O4H0LN+nc471hOzH?AT??rRdkexrLT zAzzeE;^B64c#iTcj59}3G1C$`PCz9g{Uhmbh;W*gIFojSxZz<)#kwF!S|NIYZ0tvf z#8;MHmf2(nV2V5LJ~qE8z!V`hclISplLluc#uw2x{U(rOVq~nkmC+WWmU?H!z^+^aQA+Rbay?+p0_V zDPq8XFde}~R~RDVo?^ik%3`zSTKk0+dHs_CMsh#Ay4lIeK=&;P(}LoT8E_yPj^62y zme|JDx7;-m)?*6kxD*(=wqaG_a|Zk_8RT(rCD%PlsxA@!{J|*3wvym#gQ~?lyu>?YMD-u3tR7_>XFQ_!Si3&Ypm3JJW^o@J3?g|fosbWI~!jB)zt4mpX zCrziQ1S;P#iniA36!;vA+G<~LIV%$RFiFKL7FXPD{b(?k5m0?$LZp|D5Z zik96^xq#s*HOk03%_eJX8WI3NnRWvkP(U<9N^y74G)XP+O($QaWd0;=IrObCv}_Z0$5J;FJP zaS(4HA`Ag4zGCVO8R|@nDz6ZVe%>NCHR@cl!Y4?3jR;fBR)V2q1;9p)fkK>fEC{Fq z(s(B)Ul8UqAyryVK!(5sa8x|RS_sP273x`9O|U~5KzvwNY^n9YlqjKpQK=C+Z>9W0 zmt&Y)wDDB|;)?>$q6X3;?Nxu4BE($~$I$FDJUr-i8x`z8 zma?i&7+za1Q+X(O8~BTPw{|*~LVuB}=~8)?uvzmwq+)`(3rj1Y#$Qh<`;{+uYJv($ zXfc?UDZmaD)MChBc_Rvfgoe{CffUi{jNtsv0=J1(Myt$6(F;pDj%^6rgOIa{g@y}l z92o5s%qlK&7DDR$MA$vHSiG04dUycYcolhq(H;PMO$DzKvrtYF*e%WB6!6>%f*^aj z(RB`&7B<*KfvN@?3l*GQuQAN4&TQp;#AzoH7z4yWpdx{3{t*j-Oqdqr3N}9zu;-}8 zFtm?z>~ipUp%;ByRrzIZl>l%~Etdjl0=k8(APVX?gva$Rov_ka5P6gpef&W{r{$Cg z(*_!JbixbnM*#6EgY)qcq#e}emQ%M7(hzN&#wn<7vB)x++-B=a0JH8l-F_zf>lCdC z_QYu+1`S6P5HicJFwGEA$J_x0WxGEzta~NEpjiAv2I=!E$uUG#k-)628yQ^yle{;X zP^U=s68bLuPBP9mQk!hOPflwt1Ljp>`C?!!81& zT%tA$jR%O7p4{+5({LcyvNG-idHy3xeo_dsRbR|vw<%JngKY*|+;V%nA^4O4{U(!$ zLBjG(f^^FX9nP;yJkiirtWd=0j`uDRHH$k8CHS6wCUCDWPY6f+1HlSei=o7L<9E z$VA#cpbVf?75%ZWQ?zbe&8~+~Vaz381qS&dU%tXHl5$fnfUmfHs&Oh{y~-1=BLtv4 zqSzM_FN#|H!0HyRR)c)hbrdWWE`BA9RBaF%&KLfW92cId4X49H++yAM2}&C~^9y#8 zVifQM^MLIPL|fKdQ2k2*vpdCLCAy7mka$0cT8Df}^!bp(X|V+W=#87qq`k9VY&0o6 zk~O3M05Ymugr#Hv@i4duz&CQETChM?4iya?uo0-D(%0doC~8*;6%Gh#=G;4!mP?FT zwFeo@vuPVppM+W)cME9F##TVJPVQx_DAip=XL=B2-FB8mueeB!GSKi^WZz@*L_#6r zlOFfpDg|e}q>q8xAzD=(_=dcEu&!o@k?|F%*iGsmw0Be>&L44QuOhgy*_#Nojqp!$ z*l=9p;l%^sHTZxGJ8Ot(!{(Av??+KN?wB&e%S&y73&p0-tGPnkEo+7pe33hNF%@7P z_ZS~(b=BvnD@{n~(+i1L$Eb!BbFe}q5CsFDQzg2D(QZTvigOeV*1_j2Dlo#(+MsFk zI-^=f;we(Vvl^zp63HV~DgMrnap-M=pvg!OE{tyrOm3~cCAnmT>=+zS zWoCOmBbP^n_!Jz6K}1PK7JfkeLeg%{D%!T#g8}49m(~DbUe;oRblKO4JCcd&sREdf ziBAFMUC(yLiyn=FfCYv-v!0zw)-v{s8kNH37MN+WG^~oPOYsG$){x*%3M#%J1Yc}M zyh<+j8m;0Ck41M2mb&vS(n-gdwyRfCud9dxMpuu}ha9(X)ByDag|To3`bHd#3j^~l z?)pNbD!&t#8MOtmwgtGW7zvkk71D(sqB{V2u40uXxQn``K3<7Ig{7_38*#dMiglGM zmGcF3`jr4(%u2$1q7^JMA6CY2Q6j-5-p2CSfh$hTS|Si?7n*7zwQz*BODiaC5mwW;kwsd2DSJd?T< z8cgs_952f_EIlx*JQi;RV`nja*r@?_i|(o@6iW`iUzl*V=-@?^3q0`_mRJB5@eUQ- ze#`C>H+m7)hc_Ja0uTaL>Ix2bs6}!J5-HhawRqGnL9AZ;g`4IBzj2`kH4wHWdof%i zmX>$b6<{H%4l7uJvm@ZwmlMFA;h~{?qz*$*sAFMgnT1#!0P~Yks^aDv9fE*y@h(-I z?8RPIRVAUXn9zK~P#FX8z-+&W#0|Tbf)josPN&R3utSony&x$HFat;4B0E=kSODtL zV&D$pvK4MobiXq8`KqFQO01q&#r+^I$N+Y0) zy2;}HA`4Y=c!QFtiX7LTpu{9QlcPoTFSt1tk~7otF6K0dK@X%UvA^;?v!v?_wmR(A zNAIhpIGGl|sFYP#gBG^f`-jUci1{MqE$%mf%Vzpch6re~=C$gjvu1)}A1+=VqSdjO z5+J9uCaG9>)WtWifZ27Z)HK%FL_2vNQxR)xhR8B3rMaI(f)IT%rd zup_8Tk!*~$o+@4eBd;@Iv7laMsfum}xw%rE%OVkAVjj;>fev4!zmfv2Tc2?aLzGK< z05(T01uZ=uVT_=ncdDtu2L&Hs5fGtOBf{H`;9olx3sZm;PDzh?wSoa+9m1p&12ADa*^UIaHBExe+oe-hsrPHx|uq*b)Em@P?d%zo^Aq{u@Rgl~p%Y2tAJ z*S&-q1yn4}mHomlv){z=Fkl0(#K*eTSh~Nc{jAFk-Twe^WrPnnKiT0b#Icu16jQqO zIB-9U0cXJiN7WIu6=Ld%Y0&QuDqIJ7qo`>`2R>u&bsQ%u92?9NK3^!&055_UWu(v? z?1u1DUV;G8vXMor@dF@kM&&hMDDf^JHVzoU_AERRi~@N`KZMt^4MnUlTNGd}JHQY}RN(T(d@(u4{Xt8uIeL4X z#j1{1m{2t;lp*9=f))#_MZPPTRz|{28lE=S-%)IPOCD#snH`%Qn7}MCb3X@i^)2om zaRLor%(^jU=2V*m#=nFi7cN^?MCQyOg98Dyj@CB-2}qJ1fdHm5{tmNxl?!sC(DJOh z)?0+D!(nj%qh8}pwXVu{?jQ~VrRA5?nY$Gi02{-^1q!4oZWHEQ4?@vb+$}|*z}!b+ zK~mf2;wS}t>{<>ria`+c>|>YIK4(!$uwzO>sav8g`cZBxQj@IAnwvEnZcj>srHGMO!Q zyCB}xx_rSXQr*j-XSfI^ve&}d<|0y@769}+j>rl&Zm+e*HU-s69zm2Q6%yJl=z%GG zR9ytRIS8udti$ySCx;Tuf5m7HVn2oTPq90`9KF?PN^V`f0 z#>L?AO54g#zzqp(;_heK{ zL;8n9VGi3Yc?RJ(ZM$jNvcj)vL{F%4L==Yq0M5(6x{9_3m@Ng_MP7?viEMLV_){#P zxdmBQeZU1o%U$!R0>wbdc&g>kCr5IEVbtSk?Sw#{i-M6-iqN&yO$ptU8j|(~qA{+R zl^tRXxT)vy6-L(pg;seZsNcMoCeKl&cKLu&oAVTe;t6cfKoNdb1}wd(v!eImlm~Fv zQrbneVZ7cnK!JUzv8NEn|#D5384B#48y^y4RWEa)qI`d!+JXuqi ziU^ODhlq_>d)5XdQ$WOEkZ$jpu|Z*Rz!6pXoCQZyK!(2&F7Ao26&J?1P85et^%QY% z6&x$vXr;yVv1zj+I1z$IU&Oz4%`HvRd_(>dLrUd`iw6$lmJ2cTf2qWA96q9`K$~cy z9qNM{-MOOyVpmG5VGe-{bdY4e+E0;44#&zpNta71QdfAS=As1jufkQ3$|lzcU&Ob! z{U~svlKK^84ihUzoI`Y5T*MHkFcPw&CCLM;9E<{G%#Rd8HDew;%2g_T7!cWGq|&V+ zqTu|^!s%xtXaOt&0-|eSl&#x}vBz-02D*z2Ga5s(CsZCGXrRhH%LD_Ds7wZg%fQ#n zpg3X_*AOmv*w>vVsP*yhM)E7m2C5`lpbw?@GE%X%l z#B~*(nM7N=xnN|{$o^yGxhJ~#V+(SXan~d6KQMoq31+@lHGNI-`y+a80}V{h;5VjR zQWbKv=qct3X(k{+>(8jZDy6O!De%PrJSR3tpeydR1=M&0Z#4wui4(kMcRnJRaazyVnGJ6977kvx~>-$OYcDOhv@kdY3K|?8XfP z)?TdeN*U5nt$LJY_#>E9xPPp#Nbs$sHM$Sfv0aPb6R-o%n8LWOBIh|-aqS~e;!p~{ zgdEF%sm}xCi962V!!I7?LQ-{gGC=3TED|1O03JsXi$FQ3!Rp8XQxDu#E9sgDjB9(M zDj+4rEj`RA54ovYmOYm(aX~f)BC@0R6#~~0c16T@6`wNq1IM_QOY=JWS8Z?k0;W}^ zGsLu|uf$$5`G-?uUSd#UXEQJdj>zj+)Ka3u0518-R`sRL1efDx`9Tf_QIu;a%DUs`dd#Fund!(Va=@B@_T`dGNWZydZWx@ zWP0mvrImoMOuI{4*!Yzyu4QC{U-Jg(;qos30B}I4%cK;yjE^s_a7_#GbBMq`?pMS* zP1qDl&y*1EBkn6oJuWf13Xd?OHmi1QbVoE(xO!dG+kt!BpfAIS+^ecX&W*a9I$VrL ziFk-Q9k5-A#v=(;)Z#}5;P73(=G8+u!!ah?u9HsQV5cWp9iiI#)hh>oGwpnopO1q7-<PYli-!&zzLx+cX& z!nA#3XiJ2}qX`NQ{K{QvqDlaFyAgpOm|~W98b}Tx28Nlkg1yAbZ>WTV>`)M-FXCI9 z0r-@nY@QK+T)@|>d*@moF%Ms%M)=lUd@n=!XA#&9Z_MUa@AzZDyWu}69?{#$puR`U zq{wQ)enLCz1r58>J-R9YG0>PI1@A^71lMEp8^|z^>_X25H-C^8JT1JKPp)c%#8F_l zo}jFE2b1Pj=jK(arHgzOr7%Gtw-sy~Hai1HQFN5Is2!Dg^dI#(ZE3I;2_ay*WzPVe z(_IwEnQ^EeiIL+uktl>N3Rp6vHv^Tw`4G_?`z!QBs1_68i6)Ky75+u&{J!D3ELY}k ztJE-QM4+{-PUwfsA=do?!dW-8)0 z9=fpY26dO(Q>ns$*1f_a-X+8Xyu)i3FN2V!4hh!>s)JDSml-i|=O1T1YyNE0x z>2>oGxkknT8LlPWP@1%qz9%F=4K;Rv*HL1H4vtYIINXzR~1 z#l393_PB?{9gxy3tT>`D$5nq4ERSx#T9rb@mbO0f7scsc%v>nCHRZ7b3t91Oiu;#v zj1O^e!G{O9KZG>Y-MTm21w7U(<_KAWN%@G=oKlDJ5T;L2;IZORY-KeCB=(Jkzft5{ zdx;cjE5t2DCY)c0Di_*b#cCdG!}hCl8GI(Pi-%%69l+kioT{%eC@WcR@IT1h;%#|@ zL}pir5$xf{2#mY$r#mS%Ac|OUs)6RASD=69H89y_tp4TW6(2b-j01;haeLBW!z@s* zGUbY+j$#JF0zC(~tf^`a5yFvdtR`%uX*dE6#dVNN7Y*MqTy$~~ghJU4wxI2cLhcg2 zRZM^`{lMq1uk{OGP`95ji{mgC?m81-M&HbI=$7wmuboz5}VTIjxeMRuUxD+g& zVhk3X$Q`fA4P$vn9843i@P*0@bJlSzk>JSG!V2)CY%WCWG z9)`-~*RoRp#@nmILz4x;bhES*g^Jx)ml$O20k%;EYgG8%Iol3;}Y+QS=DabpmKZW6JCS>r=fNk6Jhf$d9`r>`d7qCB8DxW zIqoMlTKO>(8Cb#cNmVc~o=!$vM2rkoLGw8{#LyL$^Bv=Z=2VIitCl(vppJ11Y+45o ziD)2J<+d@1*heF#rBvXYCHg8Y-BG~!f*X|NCsczA-D{w!R;Q)~OXP-QWE_(FfKdmS zbdCp>i%xi2;v3J#wXDPnAxS8ScwQor6@)kqp=_9yECGj}%my+8Bx>S)!Gq2EI71NK zlWG@qSaXQbu%FSzBNVc?^fcAB2Sd@(_W+lYn1R~{@Poj&z9LPCohiE&{ke*HADF{X zURnuws_ro{&`^LpUfE@D$V7^*b1gvV&T$`P53&$kyu(l~Mxq|0s4d#KDAb~$PU3q( z;sUh~5zeVAO2$|wiq|oi4cOW6$Tn>)>7ok8ZE_h<8n4WJcuJ&R&xINS z22qth2uDHi6E`i0C?2m_nFKtUE#<>;U7GqO!T?j0ll4*C1#b*HAI*0z1sqf&Sd)QF zE>?;$BVXp?g?8114D&h3ifCHttkeJ(2^Xl#MN-r*0@MQ7o}6wP@ba1GBYj1O>j?p(6)& zmtv1GxA8TRRY!GhSn3Cj4r0Nuv>i``HM~TYeq&^l`?D3O&?FQGr(5asdUW#JDL}7LW$>)MMBd z%RHqu2&CHN2Owz@G)#IfR1pn+VL!ILxGBdlQ&9n25zsFs3oZr&Z@E)ZHzVU~OW}j8 zrQ-Q$B+4j+;N+I?C>3ZJNA9^y4nDXthJ!lA7$9OS~4 zaUN=yJ-#I-b(Zh&ORyE456Le70L4_V+SI5G=2uyMVe7oqc&|&0Ojo=GI$M=4P;woP zqT|-Wk^`-b19@=*cSvLQ+Bo7P6)gUcB>RTY7Qi#Wi5m%91z!&^5n>)Z!6>oBKp=M5 zZK$}Cy1C5n#Mf+2L|~_$suF%6Z{WVn`+!o_1IzO9HX}5}*M*M6 zu3PR@iXShedTPS+7BrMQkK=65GPcn9TI{WRt^s?gsC-&~kd}w7KT!>AcuV|`y;{fo zq%1>J30V|Qn}Ak_^%Ayuw1N|EmR+lAaXD@G5KSw1mLTCwjX`Qs_>N{BJ;4E?#5yB= z%&BS6VUcYZZ6yM42Z>Ao=b3w^nZ!et9fn|FpBBK0WmD8sO}2xXaDA-m5@3w7gj(>< zK3omj{V_aU6561OF+;=^m8UNV39T#KMVnIHRe6du2yfzC`Qrx=mRCew#>Jt?R2fQ! z%_ZWok)t8xY0XquLFAEsVvR9qto%o&Vw!!49~3Pz{E%BcEp3c7sDjhX;DaG)*IyB9 z0wd7^ahSp6$Vw%Y@G|nJ0$W;K04~3&#iSsow0cB*F>`6yMjEN=GE-gQ&Hn%qD1+%K zv-L6(`-Fdrz@L$e0a77Ju0R@HWL_ewFC-uh9m4@p?j=C+1EEj%6+_she1KvQ`<wJ?+ynj*I>E#0Vq602Qq&~YE>W$BzWg5ymdbE;xuPAhLn4M1o& z$zk_!w|bC1{@}-y|>_xAhDNg(JjzfoSf6V1fZcWx#&%?r9VE1YQWkOR*G&;TWCz<}f7IG^pk#n#2mD zniuXY7XdlO10uf>!1uusu|*N&VG;!vnIh{&@SP8FgHQ~)(H(+Nrr6XDVTP5o#?6m0 zRD6j_(}w0TJtOS@0C{W+EPqI`!N8T~RI~jweGn+AxDR6<87&PvX^WH>LB|or$}Z5$ z?IV%4qj^reXyP!f{mBR13w6b8xvDN|)8-&7dS_lBnnje+O%{AgP@)=sUzn}vAKRK6 zgw|5WV5g(Gvk`#rbyw75CoILrlLcOKO5SxwRjT=|xS{|vXAf7HXISR?g()cU3_*%X zLjdRu9Chmjs4aPzSO*ZH02=Z(E~(mk0hkhJ?T5|B=^@Xk0#q;$0Sg`Zi2w~jFj+iF zxnd(?Dx*PRzfoWpC1Y%Oj#!nDz*{RwjnM067fi7RF)z|3dauE7XH0@Dw%1c!I2+T$9wg|)#%dWvJsa4DqsBs6Vj_e7j zl)_HLHMtgKop&SBMQ->UO!!>G^*-S+H?maL7%ySO66-k}&W?_?Cal|SPm~KcEgBCH`AURRxAhS~w28w}AW(XO zLu!cKv`TZ5x`bi0PYmSu8%-e!4fo;=0p_`tE9HXSw|NPr6e0mlxm2wX7I=8>EP++0 zaoj$mv%t$V3iA#s*kDv+Hk*}4Q8y)OzZJ~FK&Z_c#Mar7@1+ZwXjd!$0JPA$l>if& zaahaE0E2)Za72Dj;6asMCB3^*ArODe+qjj5^otY&rIjFWxbHhXnOFhR`jyh*vlk__ z%B>5;Q&KIDfdDBC_73CayO!ONM7m>K_1Nh`_=P62W(vFZLKIi%VnJ?;Hhnfo>J7TCdLGZnc;gB;)SR; zDYM!reJ~@%{3X$ZZ+g6b5+0sft@cL`3lI++&ENu`?JQ_hVm0a;cTq@EFFe8t^yMMJ%1({%w*g8MHFu;|gL_Z}LVZ1=*}9PvEZbl13h>*~T~5oFl# zfR>GlVFfh{mppo9&QO+!H4}0xm$`Jdzi_&OK>(;D-u_}LeUK=tNpe>R61!(t2MD>c z7XbMtlm=f>Q8jVUhy=SoGOCFU`Oponvi-`!AbfY93~G&ZI2RwxLvxu41w2J27d=0z zZ8YC8*oz7pnb{q~x+kbk^IgS=AOIt>4}drs+4{HM$ zb8x6DbD&G&x)7ei?{YEd>mX|BAeKJ@O1pw8r_6|s=N*S>XI35NiVy_zJPU3)u z5Y7e6TFcyP1YKN20;N;L4K4eKDG^ZRrjzj~1nTO((6v|qTbjr|0?zzH1^IPsk4(|g z`GZ)6>;C{TOLU}9&6ONJ;2L_ydFwTQg_x3gc9@C>kf}*#c$9RgKzx}=+*5Bb1gwGr zQuu+<(@V%$QKOH77FIa0;v$1B+5N!d{h<7p2rKPHM){Tn8ngSF zXz|X=4KN^+3u7sPsxrHd!j+3E8ya;sj^IFP2IY`1m2=KxV*$d{Vo)mP9|d0)!~rd? zK>4@YP$QN`*b4M`m9@oUX2($MFOP{qLH7e7V&Mj{@h?CHa`ll(nh^8x3CCj2DqBDf zrE(TTtfLJr8*LX>Ifj!5&Ipa7r_c*pUjR*e&PYE?s+-O ziUfR5p1Z?bMno~XuL)7}Ce20Hglq?IfPhm?Kh| z5K*IhGh%Jm5aqVb^E(kP?gXm}vxw*#e8hpLA{xM&me#J(B_vv0^WqFd$u<}GTtpa;gsoaJ&Eps;x6~3ARYc{a zyJ}HTTnRCWYz(Sj%r(H(ntwBpW*2!4ZE6dw+mna6wQI#hKPmtUC9`Y7!%TLr6OUku zZS#2bG!O|P@H|5nQ=~=QY3;Zc*jXJ23@r{wsT54oioxD}#CE0?@WGK3oI5c zI*nbuFH(S5ffq?lixfEXhNvtj%)ic0J1PaJ^%0Ry;_B6t2Cz|Kv`dL-Lh(^3M_h^W z2pjFDy8K463U%-m&B6d~HBY#u6TG)BA4LJwsIr7n?=#fD6LJ3l#9w%A5Q-jeGLD3K zAPY_G!!Z?M@6>i4ON^B}uA|L-KBbFqtA}h=Vc>!)zl6jy%&HBz87)%rFh!%;mE_eH zqhfGIU1)XgEoJPsR0G5g2r$q(U^WA&Gd_~IO9)Ok2m@+eK<*aqk8+j2GOO_wEQG=U z(RqHNciNJ+r7>;LYI_i#V44N-#5rmVV=9A2fcat5@9B?ImcCxkB&|BN1CX zMAJP=c)t-nt!9ukq%h`E)$szr0D@a|d5Kt}&Zn7B z)k?sl#BpJeRImz)T>y(i_XcQ3;^&xAfk0cgf;9m4rwKI6Uog|En(+^1wAgr~ViErU zoc-|w#P6Wwwcq7G~UDQ)FbL>8I9 zR|bfW31YMpNwKa9M^%=yVga;eDY}l#7&4@y;tU@kTngkoOC_z5rq&(cSrLR9LWT); zM>5j^!HWVJzT!}bu5k{v7;A(eG+KFu8dX-&o778ZqF_k^tW(riiV|HdB?{7@NJZs! z8E|!o^D4sPLUppci|(ccta9}f-H`ZhfIAU!MriiWCY3rp0t;Dx9s%nG4dXUs74>j7R>XE9{4 zy~*4U3}DxitBvo3K_kK~_mIZipr440Vtve9wc-fb{Y4)FGhlH$i>oee#!Jh1f=E%2 zg8^#6SK>$++hE@Zqr_tZr%mXbdn7B#4C4ydOh_0Tb;Z4DQY)0ib zb>=WQcsW%d9lJJtzb zx&_ej0RcZTN*5c%K`Gjq)>keGVO=orLh@pUP_!E^kT?^dgJ#PnGOwAwJAkEj)y{Bv zN_vt&YR)5AJ?kP>&d&+Ij;#>|Oa}<)EriA%IJYgwKDe)K;U&>Zs zC>guQnC*TfqGt|c0kClf0irNghxiUc6_Poz2NN)%hXmsyqAjb6$(zR!2m=8CH3aN| zOis_JE=8VVNeJD`iUu*RA+|~;k%QDkvFcFOA}0hfWrT`A#u}5QN-g9^aSeD4>l_4a zQ|5c&lmH<>=$dln>bKl_EubT)zzupOV5_ZWm3O<0qe`0PY515(e8fN=$$v+Z*CFjf zxH^fkHq>PdS~e5m8nB|`cS~5Y;;ea&aGPD0OEqFmL>LLAgz5@vj5rt?H55y`wRMl1 zsJXanmzf6I=-Pyl>R8v=DeE^8At)tEuaiFzHej>f6J*iK>QD*P_8YPoX;9n#CAf+g z^DY$R6mD;b^}_YW3!}^@Qt-|;_Z!l!wn}jiAm%1JwusLn-j^sVb;PhJ%!@_}fshN= zrdSvq_?J?GwaGrp7cZy^PVj`r2b$&#X+iTf+UMFHD&yHJ!d!L*h=5&FQ8>|qutDl? zAbEq%a8w^)Xk2^o4B{$tBjNxu{jflJ7^NW466N`q7kCdb5vI9>jXFLfz;J>hYTLbx z=~b(O8Jv_Zg>h2iT+POzv3ysSb0~J^J%d$wgJ?@-j$^cPhb!t43=}=oBr}9S#`6b9 z=>@x~$02|)kM1K%Mi7Jn!sQ5x;tD2SE4Y|aZPXyiW7G9GdyN?SdrK?6py9y!i7p!f zy~Ad-6;a3gk8w$DnatANh!xD?bg6J*WIX{wqGc6KW}Wv5Tn*dm7?rGi%}t~*4?&C% zXucy&!{ddqLxrQ48xB16)bp$!Dlz#;x2DolpcbTJ)ed4Qhhb0%NH)Ub$N{keKr@B^$WN7C0tR^pG(ZY(%5)}fTJzMCQ20ntK%UpYT2Nm?pajqM5#bS zkq4-Nn(gi>F9cJrpzxPytA636X#s&?{YoQwEKRs}yg(Yqq=vM+)rtg-^VAzl710b< zg&t5Y?(I^Th~myAoZPDCVRD5`t_qYU`2PSSB85ZP+%43L%=iGY?VKz&wAdvEo z?E$Y*h$Sm!ofqvIsIsC%E}fNE#3g%exXT`R6mR(vz^rXUkHo*`V}+wbn>dCpmDa$- z)=o$oYH)vS0j|~|O?qHYl2^Ba(yDc%qA*^zg>%Cq$bhc%jy7Ydg6qze?p&h)slE}} z1iQX9YvJBWRu@|O#I}t^Dj`6FcgZlic9yPkaw5@vsF_$D%QhY5U=Jh?CRwCmej)DBf(&|qT=)eR``Y~Ij&<*ZE@x&1vwE_ z2=zoOHTN4Rs0|>qNRLn`0lG2^J3+9YlkNja(UloHnP(ki<{~V<8Sd6>N?E0J_4;U(xw?kg29iD(h8F@ix)9Keh?!6Z3dMJx!604vf| z8tYw>oz=kc4Gn0+oAVE33Lc`@ok6>vB7|_}HdMSywdurA<-3?IE4Zrb@f8hwY5}QS z^3KkeFqPq9R|N%Irse6m+%|*CmXNvJ|ct*ygRsL5|xXUdmFn-Rb)Z9X%uC6q$*Hb zY&_kJxYS;dq#QJ)TF6rIC~%ieaRKRe#x1l!RJ+V=BzFWtk;K)N1oiH(AXN{72DL>e z87df$9wt3S*?eue_YVZ*RMuB0d5m_jYAZOX2U5+zrr_TmRpuktHsbp!kCa!7hJk?O zI7D+C66(Y*`IQl2O>Axyndt0FmWil*Md ze^cBN82U0=vDTM_q!&hd#Arf=^#HXO{{T<}T<7|R0>>;SJ{?VrE56{U7CGKKFsn74 zy~fkF?Ed8gMW~=!a!@G$0O9~uga+fecvI}2A+S}3`GWWGrkNUcfzMD|)sRpacz~j> z;ab3ef>N)jD;|o9xpPq|bi%M!;$M+Y1YL7AY7Ds5vcOgHK%$uskh{L+-T=L^Dq-p? IlD_Bv**3L%G5`Po From 60b1eb26cf2e75d9e124b87a3253d5c8730269cf Mon Sep 17 00:00:00 2001 From: Rodrigo Date: Fri, 7 Jul 2023 12:00:41 +0200 Subject: [PATCH 18/24] (Serve breakfast) Tjooning --- .../src/challenge_serve_breakfast/tuning.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/tuning.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/tuning.py index 841394b7f8..6cf208f9ee 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/tuning.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/tuning.py @@ -18,7 +18,7 @@ "spoon": PyKDL.Vector(0.0, -0.15, 0), "bowl": PyKDL.Vector(0.0, 0.0, 0), "milk_carton": PyKDL.Vector(-0.05, 0.15, 0), - "cereal_box": PyKDL.Vector(-0.05, -0.2, 0), + "cereal_box": PyKDL.Vector(-0.05, -0.2, -0.1), } COLOR_DICT = { @@ -47,7 +47,7 @@ JOINTS_PRE_POUR = [0.5, -1.2, -1.5, 0, 0] -JOINTS_POUR = [0.5, -1.2, -2.5, 0, 0] +JOINTS_POUR = [0.35, -1.2, -2.5, 0, 0] POUR_OFFSET_X = -0.15 POUR_OFFSET_Y = 0.2 From 328d6a1504957ce4a6c2eebb96ca9d589d669e2d Mon Sep 17 00:00:00 2001 From: Rodrigo Date: Fri, 7 Jul 2023 12:24:41 +0200 Subject: [PATCH 19/24] Breakfast --- .../navigate_to_and_place_item_on_table.py | 4 ++-- .../src/challenge_serve_breakfast/pick_pour_place_cereal.py | 2 ++ .../src/challenge_serve_breakfast/tuning.py | 2 +- 3 files changed, 5 insertions(+), 3 deletions(-) diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_place_item_on_table.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_place_item_on_table.py index af1b890d0b..d455c16985 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_place_item_on_table.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_place_item_on_table.py @@ -84,9 +84,9 @@ def _place_and_retract(user_data): rospy.loginfo("Placing...") item_name = user_data["item_picked"] if item_name in ["milk_carton"]: - send_joint_goal(JOINTS_PLACE_HORIZONTAL_MILK) - elif item_name in ["milk_carton", "cereal_box"]: send_joint_goal(JOINTS_PLACE_HORIZONTAL) + elif item_name in ["cereal_box"]: + send_joint_goal(JOINTS_PLACE_HORIZONTAL_MILK) else: send_joint_goal(JOINTS_PLACE_VERTICAL) diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/pick_pour_place_cereal.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/pick_pour_place_cereal.py index 1f895b24c8..4c5e0923d7 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/pick_pour_place_cereal.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/pick_pour_place_cereal.py @@ -53,7 +53,9 @@ def _align_pour(_): @cb_interface(outcomes=["done"]) def _pour(_): robot.speech.speak("Hope this goes well", block=False) + arm = robot.get_arm()._arm send_joint_goal(JOINTS_PRE_POUR) + arm.wait_for_motion_done() send_joint_goal(JOINTS_POUR) send_joint_goal(JOINTS_PRE_POUR) send_joint_goal(JOINTS_POST_PICK) diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/tuning.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/tuning.py index 6cf208f9ee..5af084ea95 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/tuning.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/tuning.py @@ -18,7 +18,7 @@ "spoon": PyKDL.Vector(0.0, -0.15, 0), "bowl": PyKDL.Vector(0.0, 0.0, 0), "milk_carton": PyKDL.Vector(-0.05, 0.15, 0), - "cereal_box": PyKDL.Vector(-0.05, -0.2, -0.1), + "cereal_box": PyKDL.Vector(-0.05, -0.2, 0), } COLOR_DICT = { From c604e82f08cbdb78f632f92617af37987d4b85df Mon Sep 17 00:00:00 2001 From: Rodrigo Date: Fri, 7 Jul 2023 12:53:57 +0200 Subject: [PATCH 20/24] Serve breakfast final --- .../navigate_to_and_place_item_on_table.py | 4 +--- .../src/challenge_serve_breakfast/pick_pour_place_cereal.py | 3 +-- .../src/challenge_serve_breakfast/tuning.py | 6 +++--- 3 files changed, 5 insertions(+), 8 deletions(-) diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_place_item_on_table.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_place_item_on_table.py index d455c16985..0f01c50992 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_place_item_on_table.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_place_item_on_table.py @@ -83,9 +83,7 @@ def _align_with_table(user_data): def _place_and_retract(user_data): rospy.loginfo("Placing...") item_name = user_data["item_picked"] - if item_name in ["milk_carton"]: - send_joint_goal(JOINTS_PLACE_HORIZONTAL) - elif item_name in ["cereal_box"]: + if item_name in ["milk_carton", "cereal_box"]: send_joint_goal(JOINTS_PLACE_HORIZONTAL_MILK) else: send_joint_goal(JOINTS_PLACE_VERTICAL) diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/pick_pour_place_cereal.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/pick_pour_place_cereal.py index 4c5e0923d7..a49624b6cf 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/pick_pour_place_cereal.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/pick_pour_place_cereal.py @@ -53,9 +53,8 @@ def _align_pour(_): @cb_interface(outcomes=["done"]) def _pour(_): robot.speech.speak("Hope this goes well", block=False) - arm = robot.get_arm()._arm send_joint_goal(JOINTS_PRE_POUR) - arm.wait_for_motion_done() + rospy.sleep(0.5) send_joint_goal(JOINTS_POUR) send_joint_goal(JOINTS_PRE_POUR) send_joint_goal(JOINTS_POST_PICK) diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/tuning.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/tuning.py index 5af084ea95..97493d5444 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/tuning.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/tuning.py @@ -45,12 +45,12 @@ JOINTS_POST_PICK = [0.7, -1.2, 0, 0, 0] -JOINTS_PRE_POUR = [0.5, -1.2, -1.5, 0, 0] +JOINTS_PRE_POUR = [0.35, -1.2, 0, 0, 0] -JOINTS_POUR = [0.35, -1.2, -2.5, 0, 0] +JOINTS_POUR = [0.4, -1.2, -2.5, 0, 0] POUR_OFFSET_X = -0.15 -POUR_OFFSET_Y = 0.2 +POUR_OFFSET_Y = 0.15 def item_vector_to_item_frame(item_vector): From 8489a4d459bb3957a1d8065751735ec2a6733d15 Mon Sep 17 00:00:00 2001 From: Rodrigo Date: Fri, 7 Jul 2023 18:30:29 +0200 Subject: [PATCH 21/24] Stickler for the rules forbidden room check start --- .../src/challenge_serve_breakfast/serve_breakfast.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py index 3581f79f48..68315b8c8a 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py @@ -71,7 +71,7 @@ def setup_statemachine(robot): StateMachine.add( "NAVIGATE_TO_TABLE", NavigateToSymbolic(robot, {table_des:place_area_id}, table_des, speak=True), - transitions={"arrived": "UPDATE_TABLE_POSE", "unreachable": "GOODBYE", "goal_not_defined": "GOODBYE"}, + transitions={"arrived": "UPDATE_TABLE_POSE", "unreachable": "SAY_OPERATOR_WHERE_TO_STAND", "goal_not_defined": "SAY_OPERATOR_WHERE_TO_STAND"}, ) StateMachine.add( From 4d2a48a8a9421cae3adf6a96e3c862acd6288ba3 Mon Sep 17 00:00:00 2001 From: PetervDooren <19806646+PetervDooren@users.noreply.github.com> Date: Tue, 25 Jul 2023 18:24:06 +0200 Subject: [PATCH 22/24] fix typo --- .../src/challenge_serve_breakfast/navigate_to_and_pick_item.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py index 5152a291da..2de0ed6239 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py @@ -59,7 +59,7 @@ def show_image(package_name, path_to_image_in_package): def _rotate(_): arm.gripper.send_goal("close", timeout=0.0) - # Loot to the operator + # Look to the operator robot.head.look_at_point(VectorStamped.from_xyz(0.2, -0.2, 1.75, stamp=rospy.Time.now(), frame_id=robot.base_link_frame)) robot.head.wait_for_motion_done() From 1dc8fdc3d7b27de563ef075aad3b3f24c3da353d Mon Sep 17 00:00:00 2001 From: Peter van Dooren Date: Tue, 25 Jul 2023 18:27:37 +0200 Subject: [PATCH 23/24] change back to impuls entities --- .../challenge_serve_breakfast/navigate_to_and_pick_item.py | 2 +- .../navigate_to_and_place_item_on_table.py | 2 +- .../src/challenge_serve_breakfast/pick_pour_place_cereal.py | 2 +- .../src/challenge_serve_breakfast/serve_breakfast.py | 4 ++-- 4 files changed, 5 insertions(+), 5 deletions(-) diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py index 2de0ed6239..23dbb828ef 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py @@ -139,4 +139,4 @@ def __init__(self, robot, pick_spot_id, pick_spot_navigation_area): rospy.init_node(os.path.splitext("test_" + os.path.basename(__file__))[0]) robot_instance = get_robot("hero") robot_instance.reset() - NavigateToAndPickItem(robot_instance, "kitchen_table", "in_front_of").execute() + NavigateToAndPickItem(robot_instance, "dinner_table", "in_front_of").execute() diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_place_item_on_table.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_place_item_on_table.py index 0f01c50992..4d523df030 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_place_item_on_table.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_place_item_on_table.py @@ -208,6 +208,6 @@ def _publish_item_poses(user_data, marker_array_pub, items): rospy.init_node(os.path.splitext("test_" + os.path.basename(__file__))[0]) robot_instance = get_robot("hero") - state_machine = NavigateToAndPlaceItemOnTable(robot_instance, "kitchen_table", "in_front_of") + state_machine = NavigateToAndPlaceItemOnTable(robot_instance, "dinner_table", "in_front_of") state_machine.userdata["item_picked"] = sys.argv[1] state_machine.execute() diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/pick_pour_place_cereal.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/pick_pour_place_cereal.py index a49624b6cf..f8fa53780c 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/pick_pour_place_cereal.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/pick_pour_place_cereal.py @@ -102,4 +102,4 @@ def _place(_): if __name__ == "__main__": rospy.init_node(os.path.splitext("test_" + os.path.basename(__file__))[0]) robot_instance = get_robot("hero") - PickPourPlaceCereal(robot_instance, "kitchen_table").execute() + PickPourPlaceCereal(robot_instance, "dinner_table").execute() diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py index 68315b8c8a..bea8d7a9ef 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/serve_breakfast.py @@ -52,9 +52,9 @@ def execute(self, userdata): def setup_statemachine(robot): state_machine = StateMachine(outcomes=["done"]) state_machine.userdata["item_picked"] = None - pick_id = "dishwasher" + pick_id = "closet" pick_area_id = "in_front_of" - place_id = "kitchen_table" + place_id = "dinner_table" place_area_id = "in_front_of" exit_id = "starting_pose" table_des = EdEntityDesignator(robot=robot, uuid=place_id) From e7b5e504fec4eae16bbe1a2e2d6b320f0d652349 Mon Sep 17 00:00:00 2001 From: Peter van Dooren Date: Tue, 25 Jul 2023 18:29:51 +0200 Subject: [PATCH 24/24] remove unused code --- .../navigate_to_and_pick_item.py | 14 +------------- 1 file changed, 1 insertion(+), 13 deletions(-) diff --git a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py index 23dbb828ef..039f8940df 100644 --- a/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py +++ b/challenge_serve_breakfast/src/challenge_serve_breakfast/navigate_to_and_pick_item.py @@ -15,7 +15,7 @@ from pykdl_ros import VectorStamped from robot_smach_states.human_interaction import Say from robot_smach_states.navigation import NavigateToSymbolic -from robot_smach_states.util.designators import EdEntityDesignator, ArmDesignator +from robot_smach_states.util.designators import EdEntityDesignator from smach import StateMachine, cb_interface, CBState item_img_dict = { @@ -32,7 +32,6 @@ def __init__(self, robot): # noinspection PyProtectedMember arm = robot.get_arm()._arm picked_items = [] - armdes = ArmDesignator(robot, {"required_gripper_types": [GripperTypes.GRASPING]}) def send_joint_goal(position_array, wait_for_motion_done=True): # noinspection PyProtectedMember @@ -105,17 +104,6 @@ def _carrying_pose(user_data): self.add("ASK_USER", CBState(_ask_user), transitions={"succeeded": "CARRYING_POSE", "failed": "failed"}) - # self.add("CHECK_PICK_SUCCESSFUL", - # ActiveGraspDetector(robot, armdes), - # transitions={'true': "CARRYING_POSE", - # 'false': "SAY_SOMETHING_WENT_WRONG", - # 'failed': "failed", - # 'cannot_determine': "SAY_SOMETHING_WENT_WRONG"} - # ) - - # self.add("SAY_SOMETHING_WENT_WRONG", Say(robot, "Oops, it seems I missed it. Lets try again"), - # transitions={"spoken": "ASK_USER2"}) - # self.add("ASK_USER2", CBState(_ask_user), transitions={"succeeded": "CARRYING_POSE", "failed": "failed"}) self.add("CARRYING_POSE", CBState(_carrying_pose), transitions={"done": "succeeded"})