From b3106d60f0315b6fda3676fa34ef97ff6be2bf2c Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Wed, 27 Dec 2023 15:15:13 +0800 Subject: [PATCH 01/46] EFC fleet adapter Signed-off-by: Xiyu Oh --- configs/mir_config.yaml | 127 ++- .../fleet_adapter_mir/MiRClientAPI.py | 179 ---- .../fleet_adapter_mir/MiRCommandHandle.py | 967 ------------------ .../fleet_adapter_mir/fleet_adapter_mir.py | 416 +++----- .../fleet_adapter_mir/mir_api.py | 775 ++++++++++++++ .../fleet_adapter_mir/rmf_cart_missions.json | 559 ++++++++++ .../fleet_adapter_mir/rmf_missions.json | 215 ++++ .../fleet_adapter_mir/robot_adapter_mir.py | 470 +++++++++ 8 files changed, 2205 insertions(+), 1503 deletions(-) delete mode 100644 fleet_adapter_mir/fleet_adapter_mir/MiRClientAPI.py delete mode 100755 fleet_adapter_mir/fleet_adapter_mir/MiRCommandHandle.py create mode 100644 fleet_adapter_mir/fleet_adapter_mir/mir_api.py create mode 100644 fleet_adapter_mir/fleet_adapter_mir/rmf_cart_missions.json create mode 100644 fleet_adapter_mir/fleet_adapter_mir/rmf_missions.json create mode 100644 fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py diff --git a/configs/mir_config.yaml b/configs/mir_config.yaml index 389f243..6db6795 100644 --- a/configs/mir_config.yaml +++ b/configs/mir_config.yaml @@ -1,73 +1,60 @@ -# ROBOT CONFIG ================================================================= -# To init MiR robot REST APIs and RMF states - -robots: - # NOTE(CH3): This robot name is different from the MiR robot name - # for some reason - # - # I don't have access to the MiR REST server to test it out - # Doesn't seem very configurable from the code side? - # - # So for now, this name is the name used in the script only. - my_test_robot: - mir_config: - base_url: "http://some.ip.address/api/v2.0.0/" - user: "application/json" - password: "Basic HASH_OF_PASSWORD_OBTAINED_AT_API_DOCUMENTATION_PAGE" - rmf_move_mission: "rmf_default_move_mission" # This mission must be predefined - dock_and_charge_mission: "dock_to_charger" # This mission must be predefined - - rmf_config: - robot_state_update_frequency: 1 - start: - map_name: "L1" - max_merge_waypoint_distance: 3.0 - max_merge_lane_distance: 3.0 - # NOTE(CH3): - # If you leave these empty, the robot will try to figure it out on init - # from the MiR reported location. - # - # Otherwise, fill BOTH of these! And make sure that the robot starts - # ON the waypoint! - waypoint_index: 0 # Optional - orientation: 0.0 # Optional, radians - charger: - waypoint: "charger_waypoint" - - -# NODE CONFIG ================================================================== # To init the ROS2 node names used in the script - node_names: robot_command_handle: "rmf_mir_fleet_command_handler" fleet_state_publisher: "rmf_mir_fleet_state_publisher" - rmf_fleet_adapter: "TestDeliveryAdapter" + rmf_fleet_adapter: "DeliveryAdapter" -# TRANSFORM CONFIG ============================================================= -# For computing transforms between MiR and RMF coordinate systems -# -# NOTE(CH3): I am assuming that the transform is the same across maps -# Otherwise... Future me or future someone else, PLEASE KEY THIS PER MAP -# And also remember to edit the robot.transforms dictionary accordingly!! +# Conversions between RMF data and MiR data +conversions: + reference_coordinates: + L1: # Map name + rmf: [[0.0, 0.0], + [0.0, 1.0], + [1.0, 1.0], + [1.0, 0.0]] + mir: [[0.0, 0.0], + [0.0, 1.0], + [1.0, 1.0], + [1.0, 0.0]] + L2: + rmf: [[0.0, 0.0], + [0.0, 1.0], + [1.0, 1.0], + [1.0, 0.0]] + mir: [[0.0, 0.0], + [0.0, 1.0], + [1.0, 1.0], + [1.0, 0.0]] -reference_coordinates: - rmf: [[26.95, -20.23], - [29.26, -22.38], - [11.4, -16.48], - [12.46, -16.99]] + # RMF to MIR map names + maps: + L1: "Level 1" # Map name stored on MiR + L2: "Level 2" - mir: [[7.2, 16.6], - [5.15, 18.35], - [23, 12.35], - [22.05, 12.95]] + missions: + move: "rmf_move" # This mission must be predefined + dock_and_charge: "rmf_dock_and_charge" # This mission must be predefined + localize: "rmf_localize" + # dock_to_cart: "rmf_dock_to_cart" + # pickup: "rmf_pickup_cart" + # dropoff: "rmf_dropoff_cart" + # exit_lot: "rmf_exit_lot" + go_to: "rmf_move_to_position" + # check_footprint: "rmf_update_footprint" + lift_positions: + lift_1: # Name of lift matching the navigation graph + L1: + name: "Level_1_Lift" # Name of lift position stored on the robot on this map + # tolerance: 0.3 + L2: + name: "Level_2_Lift" -# FLEET CONFIG ================================================================= -# RMF Fleet parameters +# RMF Fleet parameters rmf_fleet: - name: "test_fleet" + name: "mir" limits: linear: [0.7, 0.3] # velocity, acceleration angular: [1.0, 0.45] @@ -85,17 +72,27 @@ rmf_fleet: friction_coefficient: 0.20 ambient_system: power: 20.0 - cleaning_system: + tool_system: power: 650.0 recharge_threshold: 0.01 recharge_soc: 1.0 account_for_battery_drain: True - publish_fleet_state: True - fleet_state_topic: "fleet_states" - fleet_state_publish_frequency: 1 + publish_fleet_state: 1.0 # Publish frequency (Hz) for the fleet state task_capabilities: # Specify the types of RMF Tasks that robots in this fleet are capable of performing loop: True - delivery: False + delivery: True clean: False - finishing_request: "nothing" # [park, charge, nothing] - action_categories: ["custom_mission_1"] + finishing_request: "charge" # [park, charge, nothing] + actions: [] + robots: + mir_1: + charger: "Charger_1" + max_merge_waypoint_distance: 0.25 + max_merge_lane_distance: 1.0 + mir_config: + base_url: "http://some.ip.address/api/v2.0.0/" + user: "application/json" + password: "Basic HASH_OF_PASSWORD_OBTAINED_AT_API_DOCUMENTATION_PAGE" + + robot_state_update_frequency: 1 + debug: False # whether to enable debug printouts from EasyFullControl diff --git a/fleet_adapter_mir/fleet_adapter_mir/MiRClientAPI.py b/fleet_adapter_mir/fleet_adapter_mir/MiRClientAPI.py deleted file mode 100644 index f3a6cad..0000000 --- a/fleet_adapter_mir/fleet_adapter_mir/MiRClientAPI.py +++ /dev/null @@ -1,179 +0,0 @@ -import requests -import json -from urllib.error import HTTPError - - -__all__ = [ - "MirAPI" -] - - -class MirAPI: - def __init__(self, prefix, headers, timeout=10.0, debug=False): - #HTTP connection - self.prefix = prefix - self.debug = debug - self.headers = headers - self.timeout = timeout - self.connected = False - - # Test connectivity - try: - response = requests.get(self.prefix + 'wifi/connections', headers=self.headers, timeout=self.timeout) - self.connected = True - except HTTPError as http_err: - print(f"HTTP error: {http_err}") - except Exception as err: - print(f"Other error: {err}") - - def status_get(self): - if not self.connected: - return - try: - response = requests.get(self.prefix + f'status', headers=self.headers, timeout=self.timeout) - return response.json() - except HTTPError as http_err: - print(f"HTTP error: {http_err}") - except Exception as err: - print(f"Other error: {err}") - - def missions_get(self): - if not self.connected: - return - try: - response = requests.get(self.prefix + 'missions', headers = self.headers, timeout = 1.0) - if self.debug: - print(f"Response: {response.json()}") - return response.json() - except HTTPError as http_err: - print(f"HTTP error: {http_err}") - except Exception as err: - print(f"Other error: {err}") - - def positions_get(self): - if not self.connected: - return - try: - response = requests.get(self.prefix + 'positions' , headers=self.headers, timeout=self.timeout) - if self.debug: - print(f"Response: {response.json()}") - return response.json() - except HTTPError as http_err: - print(f"HTTP error: {http_err}") - except Exception as err: - print(f"Other error: {err}") - - def mission_queue_id_get(self, mission_queue_id): - if not self.connected: - return - try: - response = requests.get(self.prefix + f'mission_queue/{mission_queue_id}', headers = self.headers, timeout=self.timeout) - return response.json() - except HTTPError as http_err: - print(f"HTTP error: {http_err}") - except Exception as err: - print(f"Other here error: {err}") - - def mission_queue_post(self, mission_id, full_mission_description=None): - if not self.connected: - return - data = {'mission_id': mission_id} - if full_mission_description is not None: - data = full_mission_description - if mission_id != full_mission_description['mission_id']: - print(f'Inconsistent mission id, provided [{mission_id}], full_mission_description: [{full_mission_description}]') - return - - try: - response = requests.post(self.prefix + 'mission_queue' , headers = self.headers, data=json.dumps(data), timeout = self.timeout) - if self.debug: - print(f"Response: {response.json()}") - return response.json() - except HTTPError as http_err: - print(f"HTTP error: {http_err}") - except Exception as err: - print(f"Other here error: {err}") - - def missions_mission_id_actions_post(self,mission_id,body): - if not self.connected: - return - try: - response = requests.post(self.prefix + 'missions/' + mission_id +'/actions' , headers = self.headers, data=json.dumps(body), timeout = self.timeout) - if self.debug: - print(f"Response: {response.json()}") - print(response.status_code) - return response.json() - except HTTPError as http_err: - print(f"HTTP error: {http_err}") - except Exception as err: - print(f"Other error: {err}") - - def missions_post(self, mission): - if not self.connected: - return - try: - response = requests.post(self.prefix + 'missions' , headers = self.headers, data=mission, timeout = self.timeout) - if self.debug: - print(f"Response: {response.json()}") - return response.json() - except HTTPError as http_err: - print(f"HTTP error: {http_err}") - except Exception as err: - print(f"Other error: {err}") - - def positions_guid_get(self, guid): - if not self.connected: - return - try: - response = requests.get(self.prefix + 'positions/'+ guid, headers=self.headers, timeout=self.timeout) - if self.debug: - print(f"Response: {response.json()}") - return response.json() - except HTTPError as http_err: - print(f"HTTP error: {http_err}") - except Exception as err: - print(f"Other error: {err}") - - def status_put(self, state_id): - if not self.connected: - return - data = {"state_id": state_id} - try: - response = requests.put(self.prefix + 'status', headers = self.headers, data=data, timeout=self.timeout) - if self.debug: - print(f"Response: {response.json()}") - return response.json() - except HTTPError as http_err: - print(f"HTTP error: {http_err}") - except Exception as err: - print(f"Other error: {err}") - - def mission_queue_delete(self): - if not self.connected: - return - try: - response = requests.delete(self.prefix + 'missions' , headers = self.headers, timeout = self.timeout) - if self.debug: - print(f"Response: {response.headers}") - return True - except HTTPError as http_err: - print(f"HTTP error: {http_err}") - return False - except Exception as err: - print(f"Other error: {err}") - return False - - def missions_guid_delete(self, guid): - if not self.connected: - return - try: - response = requests.delete(self.prefix + 'missions/' +guid , headers = self.headers, timeout = self.timeout) - if self.debug: - print(f"Response: {response.headers}") - return True - except HTTPError as http_err: - print(f"HTTP error: {http_err}") - return False - except Exception as err: - print(f"Other error: {err}") - return False diff --git a/fleet_adapter_mir/fleet_adapter_mir/MiRCommandHandle.py b/fleet_adapter_mir/fleet_adapter_mir/MiRCommandHandle.py deleted file mode 100755 index 7be617d..0000000 --- a/fleet_adapter_mir/fleet_adapter_mir/MiRCommandHandle.py +++ /dev/null @@ -1,967 +0,0 @@ -from rmf_fleet_msgs.msg import Location, RobotMode, RobotState - -import rmf_adapter as adpt - -from collections import namedtuple -from typing import Any -import threading -import urllib3 -import copy -import enum -import math -import argparse -import json - -from datetime import timedelta -from dataclasses import dataclass - -__all__ = [ - "MiRLocation", - "MiRState", - "MiRPositionTypes", - "MiRCommandHandle", - #"MiRRetryContext" -] - - - -############################################################################### -# TYPES -############################################################################### - -MiRLocation = namedtuple("MiRLocation", ['x', 'y', 'yaw']) - - -class MiRState(enum.IntEnum): - READY = 3 - PAUSE = 4 - EXECUTING = 5 - MANUAL_CONTROL = 11 - ERROR = 12 - - -class MiRPositionTypes(enum.IntEnum): - ROBOT = 0 - CHARGING_STATION = 7 - CHARGING_STATION_ENTRY = 8 - - -############################################################################### -# CLASSES -############################################################################### -@dataclass -class Action: - category: str - description: str - start_time: int - execution: Any - check_task_completion: Any - - -class MiRCommandHandle(adpt.RobotCommandHandle): - def __init__(self, - name, - node, - rmf_graph, - robot_traits, - robot_state_update_frequency=1, - dry_run=False): - adpt.RobotCommandHandle.__init__(self) - - # DEBUG VARIABLES - self.last_update_type = None - # - - self.name = name # Name of robot object in config yaml - self.node = node - self.robot_traits = robot_traits - self.linear_velocity = robot_traits.linear.nominal_velocity - self.angular_velocity = robot_traits.rotational.nominal_velocity - self.dry_run = dry_run # For testing only. Disables REST calls. - - self.paused = False - self.paused_path = [] - - self.next_arrival_updater = None - - # Robot State ========================================================= - self.robot_state = RobotState() - self.last_robot_state_update = -1 - self.robot_state_update_frequency = robot_state_update_frequency - - # NOTE(CH3): This is a naively monotonically increasing task counter. - # - # There is no interface to get the task request message ID! - # Instead I am just following the behaviour from rmf_core's - # full_control adapter. - self.current_task_id = 0 - - self.transforms = {'rmf_to_mir': None, - 'mir_to_rmf': None} - - # RMF Variables ======================================================= - self.rmf_updater = None - self.rmf_graph = rmf_graph - self.rmf_lane_dict = {} # Maps entry, exit to lane index - - # TODO(MXG): We should initialize this to something sensible, based on - # the config file information - self.rmf_map_name = "" - - # This is made out of RMF Plan Waypoints - self.rmf_remaining_path_waypoints = [] - - # NOTE(CH3): This is required for fleet state publishing - # The path is in reverse order! (i.e. [last, ... first]) - # This is made out of RMF Location messages - self.rmf_robot_state_path_locations = [] - - # Populate lane dict - for i in range(self.rmf_graph.num_lanes): - graph_lane = self.rmf_graph.get_lane(i) - id_tuple = ( - graph_lane.entry.waypoint_index, - graph_lane.exit.waypoint_index - ) - self.rmf_lane_dict.get(id_tuple, []).append(i) - - reverse_id_tuple = ( - graph_lane.exit.waypoint_index, - graph_lane.entry.waypoint_index - ) - self.rmf_lane_dict.get(reverse_id_tuple, []).append(i) - - - # RMF Location Trackers =============================================== - self.rmf_current_lane_index = None # None when moving - self.rmf_current_waypoint_index = None - self.rmf_target_waypoint_index = None # None when not moving - - # RMF Execution Flags ================================================= - self.rmf_docking_executed = False - self.rmf_docking_requested = False - self.rmf_path_requested = False - - # RMF perform action=================================================== - self.action = None - - # MiR Variables ======================================================= - self.mir_name = "" # Name of robot on MiR REST server - self.mir_missions = {} # MiR Mission Name-GUID Dict - self.mir_positions = {} # MiR Place Name-GUID Dict - self.mir_api = None # MiR REST API - self.mir_state = MiRState.PAUSE - self.mir_rmf_move_mission = None - self.mir_dock_and_charge_mission = None - - # Thread Management =================================================== - # Path queue execution thread - self._path_following_thread = None - self._path_quit_event = threading.Event() - self._path_quit_cv = threading.Condition() - self._update_mutex = threading.Lock() - - # Dock queue execution thread - self._docking_thread = None - self._docking_quit_event = threading.Event() - self._docking_quit_cv = threading.Condition() - - # Start State Update Timer ============================================ - self.state_update_timer = self.node.create_timer( - self.robot_state_update_frequency, - self.lock_and_execute_updates - ) - - ############################################################################ - # Init RobotUpdateHandle class member - def init_updater(self, updater): - self.rmf_updater = updater - self.rmf_updater.set_action_executor(self._action_executor) - - ########################################################################## - # ROBOTCOMMANDHANDLE OVERLOADS (DO NOT CHANGE METHOD SIGNATURES) - ########################################################################## - # Pause and resume are not technically overrides... - # But it's neater to put them here - def pause(self): - """Set pause flag and hold on to any requested paths.""" - self.paused = True - - if self.rmf_remaining_path_waypoints: - self.node.get_logger().info( - '[PAUSE] {self.name}: Current path saved!' - ) - - self.paused_path = self.rmf_remaining_path_waypoints - self.rmf_remaining_path_waypoints = [] - - def resume(self): - """Unset pause flag and substitute paused paths if no paths exist.""" - if self.paused: - self.paused = False - - if self.rmf_remaining_path_waypoints: - return - elif self.paused_path: - self.rmf_remaining_path_waypoints = self.paused_path - self.paushed_path = [] - - self.node.get_logger().info( - '[RESUME] {self.name}: Saved path restored!' - ) - else: - return - - def clear(self): - """Clear all pending action information""" - self.rmf_remaining_path_waypoints.clear() - self.next_arrival_updater = None - self.rmf_path_requested = False - self.rmf_target_waypoint_index = None - - self.rmf_docking_requested = False - self.rmf_docking_executed = False - - def stop(self): - """Stop all path following and docking commands.""" - self.clear() - - if self._path_following_thread is not None: - self._path_quit_event.set() - self._path_quit_cv.acquire() - self._path_quit_cv.notify_all() - self._path_quit_cv.release() - self._path_following_thread.join() - self._path_following_thread = None - - if self._docking_thread is not None: - self._docking_quit_event.set() - self._docking_quit_cv.acquire() - self._docking_quit_cv.notify_all() - self._docking_quit_cv.release() - self._docking_thread.join() - self._docking_thread = None - - if not self.dry_run: - self.mir_api.mission_queue_delete() - - old_state = self.mir_state - self.mir_state = MiRState.PAUSE - - # Prevent repeat and needless logs - if (old_state != MiRState.PAUSE - and self.robot_state.mode.mode != RobotMode.MODE_IDLE): - self.node.get_logger().info( - '[ABORT] {self.name}: Robot stop called!' - ) - - def follow_new_path(self, - waypoints, - next_arrival_estimator, # function! - path_finished_callback): - waypoint_indices = ' '.join([str(x.graph_index) for x in waypoints]) - print(f"Following new Path: {waypoint_indices}") - - self.stop() - self.current_task_id += 1 - - self.rmf_path_requested = True - - # Obtain plan waypoints =============================================== - waypoints = copy.copy(waypoints) - - self.rmf_remaining_path_waypoints = [ - (i, waypoints[i]) for i in range(len(waypoints)) - ] - - # We reverse this list so that we can pop it instead of traversing - # it using an index (which is more Pythonic) - self.rmf_remaining_path_waypoints.reverse() - - # Construct robot state path list ===================================== - self.rmf_robot_state_path_locations = [] - - for (_, waypoint) in self.rmf_remaining_path_waypoints: - # Split timestamp into decimal and whole second portions - _sub_seconds, _seconds = math.modf(waypoint.time.timestamp()) - - _msg = Location() - _msg.x, _msg.y, _msg.yaw = waypoint.position - _msg.t.sec, _msg.t.nanosec = int(_seconds), int(_sub_seconds * 1e9) - - self.rmf_robot_state_path_locations.append(_msg) - - if not self.dry_run: - state_id = MiRState.READY - self.mir_api.status_put(state_id) - - def path_following_closure(): - _current_waypoint = None - _next_waypoint = None - - # LOOP ============================================================ - # Kept alive if paused - while ((self.rmf_remaining_path_waypoints or self.paused) - or _current_waypoint): - - # DEBUG PRINTOUT - # print([str(x[1].graph_index) for x in self.rmf_remaining_path_waypoints]) - next_mission_wait = 0 - if not self.paused: # Skipped if paused - if _current_waypoint is None: - _, _current_waypoint = ( - self.rmf_remaining_path_waypoints.pop() - ) - self.rmf_path_requested = True - - waypoint_leave_msg = _current_waypoint.time - ros_waypoint_leave_time = waypoint_leave_msg - - ros_now = self.node.get_clock().now().nanoseconds / 1e9 - next_mission_wait = ( - ros_waypoint_leave_time.timestamp() - ros_now - ) - - else: - print("Paused") - # Prevent spinning out of control when paused - self._path_quit_cv.acquire() - self._path_quit_cv.wait(1) - self._path_quit_cv.release() - - # CHECK FOR PRE-EMPT ========================================== - if self._path_quit_event.is_set(): - self.clear() - self.node.get_logger().info( - '[ABORT] {self.name}: Pre-empted path following!' - ) - return - - # EXECUTE NEXT COMMAND ======================================== - # Wait for time to leave and robot to finish moving - if (next_mission_wait <= 0 - and self.mir_state == MiRState.READY - and not self.paused): # Skipped if paused - - with self._update_mutex: - # END ================================================== - if not self.rmf_remaining_path_waypoints: # We're done! - self.rmf_path_requested = False - self.next_arrival_updater = None - - print("Path Finished Callback") - path_finished_callback() - self.execute_updates() - - return - - # ASSIGN NEXT TARGET =================================== - else: - _next_path_index, _next_waypoint = ( - self.rmf_remaining_path_waypoints[-1] - ) - - self.next_arrival_updater = ( - lambda p : next_arrival_estimator( - _next_path_index, self.estimate_arrival( - _next_waypoint.position, p - ) - ) - ) - - # Grab graph indices - if _next_waypoint.graph_index is not None: - _next_index = _next_waypoint.graph_index - self.rmf_map_name = self.get_map_name( - _next_index - ) - else: - _next_index = None - - if _current_waypoint.graph_index is not None: - _current_index = ( - _current_waypoint.graph_index - ) - else: - _current_index = None - - _current_waypoint = None - - # Update Internal Location Trackers ================ - # [IdleAtWaypoint -> RMF_Move] - # [IdleAtLane -> RMF_Move] - # [IdleAtUnknown -> RMF_Move] - - # Set target index - self.rmf_target_waypoint_index = _next_index - - # Infer and set lane index - if not self.rmf_current_lane_index: - if _current_index is not None: - self.rmf_current_lane_index = ( - self.rmf_lane_dict.get( - (_current_index, _next_index) - ) - ) - # DEBUG VARS - print(f"Current Lane Index: {self.rmf_current_lane_index}, Current Index: {_current_index}, Next Index : {_next_index}") - - # Unset current index - self.rmf_current_waypoint_index = None - - # SEND NEXT TARGET ===================================== - _mir_pos = self.transforms['rmf_to_mir'].transform( - [ - _next_waypoint.position[0], - _next_waypoint.position[1] - ] - ) - _mir_ori_rad = \ - _next_waypoint.position[2] + self.transforms['rmf_to_mir'].get_rotation() - _mir_ori = math.degrees(_mir_ori_rad % (2 * math.pi)) - - if _mir_ori > 180.0: - _mir_ori = _mir_ori - 360.0 - elif _mir_ori <= -180.0: - _mir_ori = _mir_ori + 360.0 - - mir_location = MiRLocation( - x=_mir_pos[0], - y=_mir_pos[1], - yaw=_mir_ori - ) - - print(f"RMF location x:{_next_waypoint.position[0]}" - f"y:{_next_waypoint.position[1]} " - f'yaw:{_next_waypoint.position[2]}') - print(f'MiR location: {mir_location}') - - print(f"RMF Index: {_next_waypoint.graph_index}") - - self.mir_state = None - - self.queue_rmf_move_coordinate_mission(mir_location) - self.execute_updates() - - # DEBUGGING - print(f'MiR state: {self.mir_state}') - - continue - - if not self.paused: # Skipped if paused - # Prevent spinning out of control - if next_mission_wait <= 0: - next_mission_wait = 0.1 - - self._path_quit_cv.acquire() - self._path_quit_cv.wait(next_mission_wait) - self._path_quit_cv.release() - - self._path_quit_event.clear() - - if self._path_following_thread is not None: - self._path_following_thread.join() - - self._path_following_thread = threading.Thread( - target=path_following_closure - ) - - self._path_following_thread.start() - - - def dock(self, dock_name, docking_finished_callback): - """Start thread to invoke MiR docking mission, then notify rmf_core.""" - self.stop() - - self.current_task_id += 1 - - self.rmf_docking_requested = True - self.rmf_docking_executed = False - - if not self.dry_run: - state_id = MiRState.READY - self.mir_api.status_put(state_id) - - def dock_closure(): - if not self.dry_run: - response = self.queue_dock_and_charge_mission() - if response is None: - self.rmf_docking_requested = False - self.rmf_docking_executed = False - - if not self.rmf_docking_requested: - self.node.get_logger().info( - '[ERROR] Could not queue dock mission for dock at: "{dock_name}"!' - ) - docking_finished_callback() - - # Check for docking complete: - # Once the robot begins executing a queued docking mission, it's API - # response's `mission_text` will change to `Docking...` and with - # `state_text`:`Executing`. But once the docking is completed, the - # `mission_text` will revert to `Waiting for new missions...` and - # `state_text`:`Ready...`. - while self.rmf_docking_requested: - if not self.dry_run: - api_response = self.mir_api.status_get() - if ('docking' in api_response['mission_text'].lower()): - self.rmf_docking_executed = True - else: - api_response = None - self.rmf_docking_executed = False - - self.execute_updates(api_response) - - # Docking completed - if not self.dry_run: - # Below we try to catch the change in `mission_text` to `Docking...` - # first and then wait till the `state_text` is `Ready...` before - # considering the docking complete. - if (self.rmf_docking_executed - and api_response['state_id'] == MiRState.READY): - self.rmf_docking_requested = False - docking_finished_callback() - - self.node.get_logger().info( - '[COMPLETE] Completed dock at: "{dock_name}"!' - ) - return - else: - self.rmf_docking_requested = False - self.rmf_docking_executed = True - self.node.get_logger().info( - '[COMPLETE-DRYRUN] Completed dock at: "{dock_name}"!' - ) - docking_finished_callback() - return - - # Docking pre-empted - if self._docking_quit_event.is_set(): - self.rmf_docking_requested = False - self.rmf_docking_executed = False - - self.clear() - - self.node.get_logger().info( - '[ABORT] Pre-empted dock at: "{dock_name}"!' - ) - docking_finished_callback() - return - - self._docking_quit_cv.acquire() - self._docking_quit_cv.wait(1) - self._docking_quit_cv.release() - - self._docking_quit_event.clear() - - if self._docking_thread is not None: - self._docking_thread.join() - - self._docking_thread = threading.Thread(target=dock_closure) - self._docking_thread.start() - - - def estimate_arrival(self, goal, current_position): - # We do a very rough estimate here which ignores acceleration and - # deceleration rates - dx = goal[0] - current_position[0] - dy = goal[1] - current_position[1] - translation = math.sqrt(dx*dx + dy*dy) - t_translation = translation/self.linear_velocity - - rotation = math.fabs(math.fmod(goal[2] - current_position[2], math.pi)) - t_rotation = rotation/self.angular_velocity - - return t_translation + t_rotation - - def _action_executor(self, - category: str, - description: dict, - execution: adpt.robot_update_handle.ActionExecution): - with self._update_mutex: - # Get list of missions, get guid of mission - missions = self.mir_api.missions_get() - mission_guid = None - for m in missions: - if m['name'] == category: - mission_guid = m['guid'] - if mission_guid is None: - error_str = f'Action category {category} not supported, ignoring' - self.node.get_logger().error(error_str) - execution.error(error_str) - return - - # Start mission - response = self.mir_api.mission_queue_post(mission_guid) - mission_queue_id = response['id'] - - def _check_task_completion(): - mission_status = self.mir_api.mission_queue_id_get(mission_queue_id) - if 'finished' in mission_status and mission_status['finished'] is not None: - return True - return False - - # Keep track of perform action - self.action = Action( - category, - description, - self.node.get_clock().now(), - execution, - _check_task_completion) - self.node.get_logger().info(f"Robot [{self.name}] starts [{category}] action") - - def check_perform_action(self): - self.node.get_logger().info(f'Executing perform action: {self.action.category}') - action_ok = self.action.execution.okay() - if self.action.check_task_completion() or not action_ok: - if action_ok: - self.node.get_logger().info( - f"action [{self.action.category}] is completed") - self.action.execution.finished() - else: - self.node.get_logger().warn( - f"action [{self.action.category}] is killed/canceled") - self.action = None - return - - # Still executing perform action - # TODO(AA): Update accurate remaining time - self.action.execution.update_remaining_time(timedelta(seconds=10.0)) - # TODO(AA): Update self.action.execution state - - ########################################################################## - # INIT METHODS - ########################################################################## - def load_mir_missions(self): - if self.dry_run: - self.node.get_logger().info('{self.name}: DRY_RUN LOAD MISSIONS') - return - - self.node.get_logger().info('{self.name}: Retrieving MiR Missions...') - robot_missions_ls = self.mir_api.missions_get() - for i in robot_missions_ls: - if i['name'] not in self.mir_missions: - self.mir_missions[i['name']] = i - else: - if "move_coordinate" in i['name']: - print("removing {}".format(i['name'])) - self.mir_api.missions_guid_delete(i['guid']) - - self.node.get_logger().info( - f'retrieved {len(self.mir_missions)} missions' - ) - - def load_mir_positions(self): - if self.dry_run: - self.node.get_logger().info('{self.name}: DRY_RUN LOAD POSITIONS') - return - - self.node.get_logger().info('{self.name}: Retrieving MiR Positions...') - count = 0 - - for pos in self.mir_api.positions_get(): - if ( - pos['name'] not in self.mir_positions - or pos['guid'] != self.mir_positions[pos['name']]['guid'] - ): - if ( - pos['type_id'] == MiRPositionTypes.ROBOT - or pos['type_id'] == MiRPositionTypes.CHARGING_STATION_ENTRY - ): - self.mir_positions[pos['name']] = ( - self.mir_api.positions_guid_get(pos['guid']) - ) - count += 1 - self.node.get_logger().info(f'updated {count} positions') - - ########################################################################## - # MISSION METHODS - ########################################################################## - def queue_rmf_move_coordinate_mission(self, mir_location): - rmf_move_mission_guid = \ - self.mir_missions[self.mir_rmf_move_mission]['guid'] - mission = { - 'mission_id': rmf_move_mission_guid, - 'parameters': [ - {'id': 'x', 'value': mir_location.x, 'label': f'{mir_location.x:.3f}'}, - {'id': 'y', 'value': mir_location.y, 'label': f'{mir_location.y:.3f}'}, - {'id': 'yaw', 'value': mir_location.yaw, 'label': f'{mir_location.yaw:.3f}'} - ], - "priority": 0, - "description": "variable move mission to be called by open-rmf" - } - try: - response = self.mir_api.mission_queue_post(rmf_move_mission_guid, mission) - except Exception: - self.node.get_logger().error( - '{self.name}: Failed to call rmf_move_mission to ' - '[{mir_location.x:3f}_{mir_location.y:.3f}]!' - ) - - def queue_dock_and_charge_mission(self): - if self.mir_dock_and_charge_mission is None: - self.node.get_logger().error('No dock and charge mission defined in MiR config.') - return - - dock_and_charge_mission_guid = \ - self.mir_missions[self.mir_dock_and_charge_mission]['guid'] - try: - response = self.mir_api.mission_queue_post(dock_and_charge_mission_guid) - return response - except Exception: - self.node.get_logger().error( - f'{self.name}: Failed to call dock and charge mission ' - f'{self.mir_dock_and_charge_mission}' - ) - - ########################################################################## - # RMF CORE INTERACTION METHODS - ########################################################################## - def get_position(self, rmf=True, api_response=None, as_dimensions=False): - """Get MiR or RMF robot location from the MiR REST API.""" - if api_response is None: - if not self.dry_run: - api_response = self.mir_api.status_get() - else: - if as_dimensions: - return [[0.0], [0.0], [0.0]] - else: - return [0.0, 0.0, 0.0] - - mir_pos = [api_response['position']['x'], api_response['position']['y']] - mir_ori = api_response['position']['orientation'] - - # Output is [x, y, yaw] - if rmf: - rmf_pos = self.transforms['mir_to_rmf'].transform(mir_pos) - rmf_ori = (math.radians(mir_ori % 360) - + self.transforms['mir_to_rmf'].get_rotation()) - output = [*rmf_pos, rmf_ori] - else: - output = [*mir_pos, mir_ori] - - if as_dimensions: - return [[x] for x in output] - else: - return output - - # Priority... - # 1. update_position(waypoint, orientation) [At waypoint] - # 2. update_position(position, lanes) [In transit] - # 3. update_position(position, target_waypoint) [In transit, unknown lane] - # 4. update_position(map_name, position) [Lost] - def update_position(self, api_response=None): - """Update position using the MiR status location.""" - if api_response is None: - if not self.dry_run: - api_response = self.mir_api.status_get() - else: - self.rmf_updater.update_lost_position( - self.rmf_map_name, [0.0, 0.0, 0.0] - ) - self.node.get_logger().info("[DRYRUN] Updated Position: " - "pos: [0, 0] | ori: [0]") - return - - mir_pos = [api_response['position']['x'], api_response['position']['y']] - mir_ori = api_response['position']['orientation'] - - rmf_pos = self.transforms['mir_to_rmf'].transform(mir_pos) - rmf_ori = (math.radians(mir_ori % 360) - + self.transforms['mir_to_rmf'].get_rotation()) - - rmf_3d_pos = [*rmf_pos, rmf_ori] - - print("Updating") - - # At waypoint - # States: (0, 1, 0) - if self.rmf_current_waypoint_index is not None: - self.rmf_updater.update_current_waypoint( - self.rmf_current_waypoint_index, rmf_ori - ) - # DEBUG VARIABLES - update_type = 0 - if update_type != self.last_update_type: - print(f"Update Type: 0 Current Waypoint: {self.rmf_current_waypoint_index}, Orientation: {rmf_ori}") - - # In Transit or Idle in Lane - # States: (1, 0, 0), (1, 0, 1) - elif self.rmf_current_lane_index is not None: - self.rmf_updater.update_current_lanes( - rmf_3d_pos, self.rmf_current_lane_index - ) - - # DEBUG VARIABLES - update_type = 1 - if update_type != self.last_update_type: - print(f"Update Type: 1 Current Location: {rmf_3d_pos}, Current Lane Index: {self.rmf_current_lane_index}") - - # In Transit, Unknown Lane - # States: (0, 0, 1) - elif self.rmf_target_waypoint_index is not None: # In Unknown Lane - self.rmf_updater.update_off_grid_position( - rmf_3d_pos, self.rmf_target_waypoint_index - ) - - # DEBUG VARIABLES - update_type = 2 - if update_type != self.last_update_type: - print(f"Update Type: 2 Current Location: {rmf_3d_pos}, Target Waypoint Index: {self.rmf_target_waypoint_index}") - - # Lost or MiR Commanded - # States: (0, 0, 0) - else: - self.rmf_updater.update_lost_position( - self.rmf_map_name, rmf_3d_pos - ) - - # DEBUG VARIABLES - update_type = 3 - if update_type != self.last_update_type: - print(f"Update Type: 3 Current Map Name: {self.rmf_map_name}, Current Location: {rmf_3d_pos}") - - if self.next_arrival_updater: - self.next_arrival_updater(rmf_3d_pos) - - self.node.get_logger().info(f"Updated Position: pos: {rmf_pos} | " - f"ori: {rmf_ori}") - - def update_internal_location_trackers(self): - """Traverses the state machine to help manage robot location.""" - state_tuple = (self.rmf_current_lane_index is not None, - self.rmf_current_waypoint_index is not None, - self.rmf_target_waypoint_index is not None) - - # In the absence of a state, treat it as paused - if self.robot_state: - robot_mode = self.robot_state.mode.mode - else: - robot_mode = RobotMode.MODE_PAUSED - - # SEMANTIC STATE INFERENCE AND ADJUSTMENT ============================= - # See docs for more information on the state transitions - - # MiR_Move: Non-RMF Commanded Move-To-Coordinate - # (0, 1, 0) and (1, 0 ,0) --> (0, 0, 0) - # When robot is done moving, robot will be IdleAtUnknown - if not self.rmf_path_requested and robot_mode == RobotMode.MODE_MOVING: - # Unset all - self.rmf_current_lane_index = None - self.rmf_current_waypoint_index = None - self.rmf_target_waypoint_index = None - - # RMF_ReachedWaypoint -> IdleAtWaypoint - # Set current to target's value, unset target and lane - # (0, 0, 1) and (1, 0, 1) --> (0, 1, 0) - if (state_tuple == (0, 0, 1) or state_tuple == (1, 0, 1) - and robot_mode == RobotMode.MODE_IDLE - and not self.rmf_path_requested): - self.rmf_current_waypoint_index = self.rmf_target_waypoint_index - self.rmf_target_waypoint_index = None - self.rmf_current_lane_index = None - - # IdleAtWaypoint/Lane/Unknown -> RMF_Move - # - # Defined in self.follow_new_path's path_following_closure - # and called during path following execution - - def update_internal_robot_state(self, api_response=None): - """Update internal robot state message. Does not publish!""" - - # NOTE(CH3): You might need to use robot.mir_name depending - # on whether you want to use the config yaml name or MiR server - # name whereever the FleetState message is intended to be used - robot_state = RobotState() # Temporary msg to avoid race conditions - robot_state.name = self.name - - # NOTE(CH3): Presuming model here means robot model, not sim model - robot_state.model = "MiR100" - - if self.dry_run: - self.robot_state = robot_state - return - - try: - if api_response is None: - api_response = self.mir_api.status_get() - - #now_sec, now_ns = math.modf( - # self.node.get_clock().now().seconds_nanoseconds()) - now_sec, now_ns = self.node.get_clock().now().seconds_nanoseconds() - - # Populate Location message - rmf_location = Location() - rmf_location.x, rmf_location.y, rmf_location.yaw = ( - self.get_position(rmf=True, api_response=api_response) - ) - - rmf_location.level_name = self.rmf_map_name - self.node.get_logger().info(f'The rmf map name: {self.rmf_map_name}') - # Populate RobotState message - robot_state.task_id = str(self.current_task_id) - robot_state.battery_percent = api_response['battery_percentage'] - - robot_state.location = rmf_location - robot_state.path = self.rmf_robot_state_path_locations - robot_state.location.t.sec = now_sec - robot_state.location.t.nanosec = now_ns - - if api_response['mission_text'].startswith('Charging'): # Charging - robot_state.mode.mode = RobotMode.MODE_CHARGING - self.mir_state = MiRState.READY - elif api_response['state_id'] == MiRState.PAUSE: # Paused/Pre-empted - self.pause() - robot_state.mode.mode = RobotMode.MODE_PAUSED - self.mir_state = MiRState.PAUSE - elif (api_response['state_id'] == MiRState.EXECUTING # Moving - and not api_response['mission_text'].startswith('Charging')): - self.resume() - robot_state.mode.mode = RobotMode.MODE_MOVING - self.mir_state = MiRState.EXECUTING - elif api_response['state_id'] == MiRState.READY: # Idle/Moved - self.resume() - robot_state.mode.mode = RobotMode.MODE_IDLE - self.mir_state = MiRState.READY - - if self.rmf_docking_requested: - if self.rmf_docking_executed: # Docked - if api_response['state_id'] == MiRState.READY: - robot_state.mode.mode = RobotMode.MODE_IDLE - else: # Docking - robot_state.mode.mode = RobotMode.MODE_DOCKING - - # Update internal RobotState - self.robot_state = robot_state - - self.last_robot_state_update = ( - self.node.get_clock().now().nanoseconds / 1e9 - ) - except Exception as e: - self.node.get_logger().warn(f'Exception: {e}') - - ########################################################################## - # INTERNAL UPDATE LOOP - ########################################################################## - def execute_updates(self, api_response=None): - if api_response is None: - api_response = self.mir_api.status_get() - - self.update_internal_robot_state(api_response=api_response) - self.update_internal_location_trackers() - self.update_position(api_response=api_response) - - if (self.action): - self.check_perform_action() - - self.state_update_timer.reset() - - - def lock_and_execute_updates(self): - with self._update_mutex: - self.execute_updates() - - - def get_map_name(self, graph_index): - self.node.get_logger().info(str(self.rmf_graph.get_waypoint(graph_index))) - return self.rmf_graph.get_waypoint(graph_index).map_name diff --git a/fleet_adapter_mir/fleet_adapter_mir/fleet_adapter_mir.py b/fleet_adapter_mir/fleet_adapter_mir/fleet_adapter_mir.py index 85f680e..f772154 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/fleet_adapter_mir.py +++ b/fleet_adapter_mir/fleet_adapter_mir/fleet_adapter_mir.py @@ -1,24 +1,21 @@ +import asyncio import sys import yaml import nudged import argparse +import time +import threading from pprint import pprint from functools import partial import rclpy import rclpy.node -from rmf_fleet_msgs.msg import FleetState -from rmf_task_msgs.msg import TaskProfile, TaskType +from rclpy.duration import Duration -import rmf_adapter as adpt -import rmf_adapter.vehicletraits as traits -import rmf_adapter.battery as battery -import rmf_adapter.geometry as geometry -import rmf_adapter.graph as graph -import rmf_adapter.plan as plan - -from .MiRCommandHandle import MiRCommandHandle -from .MiRClientAPI import MirAPI +import rmf_adapter +import rmf_adapter.easy_full_control as rmf_easy +from rmf_adapter import Transformation +from .robot_adapter_mir import RobotAdapterMiR ############################################################################### # HELPER FUNCTIONS AND CLASSES @@ -55,229 +52,115 @@ def sanitise_dict(dictionary, inplace=False, recursive=False): return output -def compute_transforms(rmf_coordinates, mir_coordinates, node=None): +def compute_transforms(level, coords, node=None): """Get transforms between RMF and MIR coordinates.""" - transforms = { - 'rmf_to_mir': nudged.estimate(rmf_coordinates, mir_coordinates), - 'mir_to_rmf': nudged.estimate(mir_coordinates, rmf_coordinates) - } - + rmf_coords = coords['rmf'] + mir_coords = coords['mir'] + tf = nudged.estimate(rmf_coords, mir_coords) if node: - mse = nudged.estimate_error(transforms['rmf_to_mir'], - rmf_coordinates, - mir_coordinates) + mse = nudged.estimate_error(tf, rmf_coords, mir_coords) + node.get_logger().info( + f"Transformation error estimate for {level}: {mse}" + ) - node.get_logger().info(f"Transformation estimate error: {mse}") - return transforms + return Transformation( + tf.get_rotation(), + tf.get_scale(), + tf.get_translation() + ) -def create_fleet(config,nav_graph_path, mock): - """Create RMF Adapter, FleetUpdateHandle, and parse navgraph.""" - profile = traits.Profile( - geometry.make_final_convex_circle(config['rmf_fleet']['profile']['footprint']), - geometry.make_final_convex_circle(config['rmf_fleet']['profile']['vicinity']) - ) - robot_traits = traits.VehicleTraits( - linear=traits.Limits(*config['rmf_fleet']['limits']['linear']), - angular=traits.Limits(*config['rmf_fleet']['limits']['angular']), - profile=profile - ) - robot_traits.differential.reversible = config['rmf_fleet']['reversible'] +class FleetAdapterMiR: + def __init__( + self, + cmd_node, + adapter, + fleet_handle, + robot_handles: list[RobotAdapterMiR], + frequency, + event_loop, + ): + self.event_loop = event_loop + self.adapter = adapter + self.fleet_handle = fleet_handle + self.robot_handles: list[RobotAdapterMiR] = robot_handles + self.node = cmd_node + if frequency > 0.0: + self.period = 1.0/frequency + else: + raise Exception(f'Invalid robot update frequency: {frequency}') + self.robot_update_jobs = {} - voltage = config['rmf_fleet']['battery_system']['voltage'] - capacity = config['rmf_fleet']['battery_system']['capacity'] - charging_current = config['rmf_fleet']['battery_system']['charging_current'] - battery_sys = battery.BatterySystem.make(voltage,capacity,charging_current) + async def state_updates(self): + robot_updaters = [] + for robot in self.robot_handles: + robot_updaters.append(robot.update_loop(self.period)) + await asyncio.gather(*robot_updaters) + + def update_loop(self): + asyncio.set_event_loop(self.event_loop) + self.event_loop.run_until_complete(self.state_updates()) - mass = config['rmf_fleet']['mechanical_system']['mass'] - moment = config['rmf_fleet']['mechanical_system']['moment_of_inertia'] - friction = config['rmf_fleet']['mechanical_system']['friction_coefficient'] - mech_sys = battery.MechanicalSystem.make(mass,moment,friction) + def start(self): + update_thread = threading.Thread(target=self.update_loop) + update_thread.start() - ambient_power_sys = battery.PowerSystem.make( - config['rmf_fleet']['ambient_system']['power']) - tool_power_sys = battery.PowerSystem.make( - config['rmf_fleet']['cleaning_system']['power']) - motion_sink = battery.SimpleMotionPowerSink(battery_sys,mech_sys) - ambient_sink = battery.SimpleDevicePowerSink(battery_sys, ambient_power_sys) - tool_sink = battery.SimpleDevicePowerSink(battery_sys, tool_power_sys) + # Create the executor for the logger node + rclpy_executor = rclpy.executors.SingleThreadedExecutor() + rclpy_executor.add_node(self.node) - nav_graph = graph.parse_graph(nav_graph_path, robot_traits) + self.adapter.start() + rclpy_executor.spin() + + self.node.destroy_node() + rclpy_executor.shutdown() + rclpy.shutdown() - # RMF_CORE Fleet Adapter: Manages delivery or loop requests - if mock: - adapter = adpt.MockAdapter(config['node_names']['rmf_fleet_adapter']) - else: - adapter = adpt.Adapter.make(config['node_names']['rmf_fleet_adapter']) +def create_fleet(fleet_config, config_yaml, cmd_node) -> FleetAdapterMiR: + """Create RMF Adapter and fleet handle""" + for level, coords in config_yaml['conversions']['reference_coordinates'].items(): + tf = compute_transforms(level, coords, cmd_node) + fleet_config.add_robot_coordinates_transformation(level, tf) + + # RMF_CORE Fleet Adapter: Manages delivery or loop requests + adapter = rmf_adapter.Adapter.make(config_yaml['node_names']['rmf_fleet_adapter']) assert adapter, ("Adapter could not be init! " "Ensure a ROS2 scheduler node is running") - fleet_name = config['rmf_fleet']['name'] - fleet = adapter.add_fleet(fleet_name, robot_traits, nav_graph) - - if config['rmf_fleet']['publish_fleet_state']: - fleet.fleet_state_publish_period(None) - - drain_battery = config['rmf_fleet']['account_for_battery_drain'] - recharge_threshold = config['rmf_fleet']['recharge_threshold'] - recharge_soc = config['rmf_fleet']['recharge_soc'] - finishing_request = config['rmf_fleet']['task_capabilities']['finishing_request'] - # Set task planner params - ok = fleet.set_task_planner_params( - battery_sys, - motion_sink, - ambient_sink, - tool_sink, - recharge_threshold, - recharge_soc, - drain_battery, - finishing_request) - assert ok, ("Unable to set task planner params") - - task_capabilities_config = config['rmf_fleet']['task_capabilities'] - finishing_request = task_capabilities_config['finishing_request'] - # Set task planner params - ok = fleet.set_task_planner_params( - battery_sys, - motion_sink, - ambient_sink, - tool_sink, - recharge_threshold, - recharge_soc, - drain_battery, - finishing_request) - assert ok, ("Unable to set task planner params") - - # Accept Standard RMF Task which are defined in config.yaml - always_accept = adpt.fleet_update_handle.Confirmation() - always_accept.accept() - if task_capabilities_config['loop']: - print(f"Fleet [{fleet_name}] is configured to perform Loop tasks") - fleet.consider_patrol_requests(lambda desc: always_accept) - if task_capabilities_config['delivery']: - print(f"Fleet [{fleet_name}] is configured to perform Delivery tasks") - fleet.consider_delivery_requests(lambda desc: always_accept, lambda desc: always_accept) - - # Whether to accept custom RMF action tasks - def _consider(description: dict): - confirm = adpt.fleet_update_handle.Confirmation() - confirm.accept() - return confirm - - # TODO(AA): To check if the MiR fleet supports these missions names, before - # confirming. - # Configure this fleet to perform action category - if 'action_categories' in task_capabilities_config: - for cat in task_capabilities_config['action_categories']: - print(f"Fleet [{fleet_name}] is configured to perform action of category [{cat}]") - fleet.add_performable_action(cat, _consider) - - return adapter, fleet, fleet_name, robot_traits, nav_graph - -def create_robot_command_handles(config, handle_data, dry_run=False): - robots = {} - - for robot_name, robot_config in config['robots'].items(): - # CONFIGURE MIR ======================================================= - mir_config = robot_config['mir_config'] - rmf_config = robot_config['rmf_config'] - - prefix = mir_config['base_url'] - headers = {} - headers['Content-Type'] = mir_config['user'] - headers['Authorization'] = mir_config['password'] - - # CONFIGURE HANDLE ==================================================== - robot = MiRCommandHandle( - name=robot_name, - node=handle_data['node'], - rmf_graph=handle_data['graph'], - robot_traits=handle_data['robot_traits'], - robot_state_update_frequency=rmf_config.get('robot_state_update_frequency', 1), - dry_run=dry_run - ) - robot.mir_api = MirAPI(prefix,headers) - robot.transforms = handle_data['transforms'] - robot.rmf_map_name = rmf_config['start']['map_name'] - - if not dry_run: - # with MiRRetryContext(robot): - _mir_status = robot.mir_api.status_get() - robot.mir_name = _mir_status["robot_name"] - - robot.load_mir_missions() - robot.load_mir_positions() - - # Check that the MiR fleet has defined the RMF move mission, - # that this adapter will use repeatedly with varying parameters. - rmf_move_mission = mir_config['rmf_move_mission'] - assert rmf_move_mission in robot.mir_missions, \ - (f'RMF move mission [{rmf_move_mission}] not yet defined as a mission in MiR fleet') - robot.mir_rmf_move_mission = rmf_move_mission - - if 'dock_and_charge_mission' in mir_config: - dock_and_charge_mission = mir_config['dock_and_charge_mission'] - assert dock_and_charge_mission in robot.mir_missions, \ - (f'Dock and charge mission [{dock_and_charge_mission}] not yet defined as a mission in MiR fleet') - robot.mir_dock_and_charge_mission = dock_and_charge_mission + cmd_node.declare_parameter('server_uri', '') + server_uri = cmd_node.get_parameter( + 'server_uri' + ).get_parameter_value().string_value + if server_uri == '': + server_uri = None - else: - robot.mir_name = "DUMMY_ROBOT_FOR_DRY_RUN" + fleet_config.server_uri = server_uri + fleet_handle = adapter.add_easy_fleet(fleet_config) - robots[robot.name] = robot + conversions = config_yaml['conversions'] + update_frequency = config_yaml['rmf_fleet']['robot_state_update_frequency'] + debug = config_yaml['rmf_fleet']['debug'] - # OBTAIN PLAN STARTS ================================================== - start_config = rmf_config['start'] + event_loop = asyncio.new_event_loop() + + robots_handles = [] + for robot_name, rmf_config in fleet_config.known_robot_configurations.items(): + mir_config = config_yaml['rmf_fleet']['robots'][robot_name]['mir_config'] + robots_handles.append(RobotAdapterMiR( + robot_name, + rmf_config, + mir_config, + conversions, + fleet_handle, + fleet_config, + cmd_node, + event_loop, + debug, + )) + + return FleetAdapterMiR(cmd_node, adapter, fleet_handle, robots_handles, update_frequency, event_loop) - # If the plan start is configured, use it, otherwise, grab it - waypoint_index = start_config.get('waypoint_index') - orientation = start_config.get('orientation') - if (waypoint_index is not None) and (orientation is not None): - pprint(type(handle_data['adapter'])) - starts = [plan.Start(handle_data['adapter'].now(), - start_config.get('waypoint_index'), - start_config.get('orientation'))] - else: - starts = plan.compute_plan_starts( - handle_data['graph'], - start_config['map_name'], - robot.get_position(rmf=True, as_dimensions=True), - handle_data['adapter'].now(), - max_merge_waypoint_distance = start_config["max_merge_waypoint_distance"], - max_merge_lane_distance = start_config["max_merge_lane_distance"] - ) - assert starts, ("Robot %s can't be placed on the nav graph!" - % robot_name) - assert len(starts) != 0, (f'No StartSet found for robot: {robot_name}') - - # Insert start data into robot - start = starts[0] - - if start.lane is not None: # If the robot is in a lane - robot.rmf_current_lane_index = start.lane - robot.rmf_current_waypoint_index = None - robot.rmf_target_waypoint_index = None - else: # Otherwise, the robot is on a waypoint - robot.rmf_current_lane_index = None - robot.rmf_current_waypoint_index = start.waypoint - robot.rmf_target_waypoint_index = None - - print("MAP_NAME:", start_config['map_name']) - robot.rmf_map_name = start_config['map_name'] - - handle_data['fleet_handle'].add_robot( - robot, - robot.name, - handle_data['robot_traits'].profile, - starts, - lambda rmf_updater: robot.init_updater(rmf_updater)) - - handle_data['node'].get_logger().info( - f"successfully initialized robot {robot.name}" - f" (MiR name: {robot.mir_name})" - ) - return robots ############################################################################### # MAIN @@ -286,7 +169,7 @@ def main(argv=sys.argv): # INIT RCL ================================================================ rclpy.init(args=argv) - adpt.init_rclcpp() + rmf_adapter.init_rclcpp() args_without_ros = rclpy.utilities.remove_ros_args(argv) parser = argparse.ArgumentParser( @@ -310,90 +193,39 @@ def main(argv=sys.argv): config_path = args.config_file nav_graph_path = args.nav_graph - mock = args.mock - dry_run = args.dry_run # For testing - - if dry_run: - mock = True - - with open(config_path, "r") as f: - config = yaml.safe_load(f) - sanitise_dict(config, inplace=True, recursive=True) - - print("\n== Initialising MiR Robot Command Handles with Config ==") - pprint(config) - print() - - # INIT FLEET ============================================================== - adapter, fleet, fleet_name, robot_traits, nav_graph = create_fleet( - config,nav_graph_path, mock=mock) - - # INIT TRANSFORMS ========================================================= - rmf_coordinates = config['reference_coordinates']['rmf'] - mir_coordinates = config['reference_coordinates']['mir'] - transforms = compute_transforms(rmf_coordinates, mir_coordinates) - - # INIT ROBOT HANDLES ====================================================== - cmd_node = rclpy.node.Node(config['node_names']['robot_command_handle']) - - handle_data = { - 'fleet_handle': fleet, - 'fleet_name': fleet_name, - 'adapter': adapter, - 'node': cmd_node, - - 'graph': nav_graph, - 'robot_traits': robot_traits, - 'transforms': transforms - } - - robots = create_robot_command_handles(config, handle_data, dry_run=dry_run) - - # CREATE NODE EXECUTOR ==================================================== - rclpy_executor = rclpy.executors.SingleThreadedExecutor() - rclpy_executor.add_node(cmd_node) - - # INIT FLEET STATE PUB ==================================================== - if config['rmf_fleet']['publish_fleet_state']: - fleet_state_node = rclpy.node.Node( - config['node_names']['fleet_state_publisher']) - fleet_state_pub = fleet_state_node.create_publisher( - FleetState, - config['rmf_fleet']['fleet_state_topic'], - 1 - ) - rclpy_executor.add_node(fleet_state_node) + fleet_config = rmf_easy.FleetConfiguration.from_config_files( + config_path, nav_graph_path + ) + assert fleet_config, f'Failed to parse config file [{config_path}]' - def create_fleet_state_pub_fn(fleet_state_pub, fleet_name, robots): - def f(): - fleet_state = FleetState() - fleet_state.name = fleet_name + with open(config_path, 'r') as f: + config_yaml = yaml.safe_load(f) - for robot in robots.values(): - fleet_state.robots.append(robot.robot_state) + dry_run = args.dry_run # For testing - fleet_state_pub.publish(fleet_state) - return f + if dry_run: + print('Dry run finished') + # We don't have a mock adapter for the Easy API, so for now we should + # just exit as long as the config was parsed without an error. + # TODO(@mxgrey): Think of a meaningful way to do "dry runs" with the + # Easy API. + exit() - fleet_state_timer = fleet_state_node.create_timer( - config['rmf_fleet']['fleet_state_publish_frequency'], - create_fleet_state_pub_fn(fleet_state_pub, fleet_name, robots) - ) + sanitise_dict(config_yaml, inplace=True, recursive=True) - # GO! ===================================================================== - adapter.start() - rclpy_executor.spin() + print("\n== MiR Adapter Configuration ==") + pprint(config_yaml) + print() - # CLEANUP ================================================================= - cmd_node.destroy_node() + # Create a node to use inside of the Python code for logging + cmd_node = rclpy.node.Node(config_yaml['node_names']['robot_command_handle']) - if config['rmf_fleet']['publish_fleet_state']: - fleet_state_node.destroy_timer(fleet_state_timer) - fleet_state_node.destroy_node() + # Create the fleet, including the robots that are in the config file + fleet = create_fleet(fleet_config, config_yaml, cmd_node) - rclpy_executor.shutdown() - rclpy.shutdown() + # GO! + fleet.start() if __name__ == "__main__": diff --git a/fleet_adapter_mir/fleet_adapter_mir/mir_api.py b/fleet_adapter_mir/fleet_adapter_mir/mir_api.py new file mode 100644 index 0000000..7d330cc --- /dev/null +++ b/fleet_adapter_mir/fleet_adapter_mir/mir_api.py @@ -0,0 +1,775 @@ +from collections import namedtuple +import copy +import enum +import math +import requests +import json +from icecream import ic +from urllib.error import HTTPError + +from rmf_adapter.easy_full_control import RobotState + +__all__ = [ + "MirAPI" +] + +MiRLocation = namedtuple("MiRLocation", ['x', 'y', 'yaw']) + + +class MiRStateCode(enum.IntEnum): + READY = 3 + PAUSE = 4 + EXECUTING = 5 + MANUAL_CONTROL = 11 + ERROR = 12 + + +class MiRPositionTypes(enum.IntEnum): + ROBOT = 0 + SHELF = 5 + CHARGING_STATION = 7 + CHARGING_STATION_ENTRY = 8 + CART = 22 + LIFT = 25 + LIFT_ENTRY = 26 + + +LocalizationParamPosition = 'position_estimate' + +class MapConversions: + def __init__(self, rmf_to_mir: dict): + self.rmf_to_mir = rmf_to_mir + self.mir_to_rmf = {v: k for k, v in rmf_to_mir.items()} + + +class MirStatus: + def __init__(self, response: dict, map_conversions: MapConversions, map_name: str): + self.response = response + p = response['position'] + self.state = RobotState( + map_conversions.mir_to_rmf[map_name], + [p['x'], p['y'], math.radians(p['orientation'])], + response['battery_percentage']/100, + ) + + +class MirAPI: + def __init__(self, prefix, headers, conversions, timeout=10.0, debug=False): + #HTTP connection + self.prefix = prefix + self.debug = False + self.headers = headers + self.timeout = timeout + self.connected = False + self.map_conversions = MapConversions(conversions['maps']) + self.known_missions = {} + self.known_positions = {} + self.known_maps = {} + self.mission_keys: dict = conversions['missions'] + self.mission_actions: dict = {} + self.mission_action_types: dict = {} + self.attempt_connection() + + def attempt_connection(self): + try: + requests.get(self.prefix + 'wifi/connections', headers=self.headers, timeout=self.timeout) + except HTTPError as http_err: + print(f"HTTP error: {http_err}") + return + except Exception as err: + print(f"Other error: {err}") + return + + self.connected = True + + self.load_missions() + self.load_maps() + + move_key = 'move' + assert move_key in self.mission_keys, ( + f'{move_key} mission must be specified in fleet config file under ' + f'conversions -> missions' + ) + self.move_mission: str = self.mission_keys[move_key] + assert self.move_mission in self.known_missions, ( + f'RMF move mission [{self.move_mission}] has not yet been ' + f'defined as a mission in the MiR robot [{self.prefix}]' + ) + + dock_and_charge_key = 'dock_and_charge' + assert dock_and_charge_key in self.mission_keys, ( + f'{dock_and_charge_key} mission must be specified in fleet config ' + f'file under conversions -> missions' + ) + self.dock_and_charge_mission: str = self.mission_keys[dock_and_charge_key] + assert self.dock_and_charge_mission in self.known_missions, ( + f'RMF dock and charge mission [{self.dock_and_charge_mission}] ' + f'has not yet been defined as a mission in the MiR robot ' + f'[{self.prefix}]' + ) + + def make_optional_mission(key): + target_mission = None + if key in self.mission_keys: + target_mission = self.mission_keys[key] + assert target_mission in self.known_missions, ( + f'RMF {key} mission [{target_mission}] has not yet been ' + f'defined as a mission in the MiR robot [{self.prefix}]' + ) + return target_mission + + self.localize_mission: str | None = make_optional_mission('localize') + self.dock_to_cart_mission: str | None = make_optional_mission('dock_to_cart') + self.pickup_mission: str | None = make_optional_mission('pickup') + self.dropoff_mission: str | None = make_optional_mission('dropoff') + self.exit_mission: str | None = make_optional_mission('exit_lot') + self.footprint_mission: str | None = make_optional_mission('check_footprint') + self.go_to: str | None = make_optional_mission('go_to') + + if self.localize_mission is not None: + localize_actions = self.missions_mission_id_actions_get( + self.known_missions[self.localize_mission]['guid'] + ) + assert localize_actions is not None, ( + f'{self.localize_mission} mission does not have any actions' + ) + self.localize_params = None + for action in localize_actions: + if action.get('action_type') == 'switch_map': + self.localize_params = action['parameters'] + break + assert self.localize_params is not None, ( + f'No switch_map action in the mission {self.localize_mission}:\n' + f'{localize_actions}' + ) + found_position_estimate_param = False + for param in self.localize_params: + if param.get('input_name') == LocalizationParamPosition: + found_position_estimate_param = True + assert found_position_estimate_param, ( + f'No {LocalizationParamPosition} parameter found in the ' + f'mission {self.localize_mission}:\n{localize_actions}' + ) + + # Retrieve mission parameters + for mission, mission_data in self.known_missions.items(): + self.mission_actions[mission] = self.missions_mission_id_actions_get( + mission_data['guid']) + + self.created_by_id = self.me_get()['guid'] + + + def update_known_positions(self): + self.known_positions = {} + for pos in self.positions_get(): + if pos['name'] in self.known_positions and \ + pos['type_id'] == self.known_positions[pos['name']]['type_id'] and \ + ('rmf_localize' in pos['name'] or 'cgh_localize' in pos['name']): + # Delete any duplicate positions + self.positions_guid_delete(pos['guid']) + elif pos['type_id'] == MiRPositionTypes.ROBOT or \ + pos['type_id'] == MiRPositionTypes.SHELF or \ + pos['type_id'] == MiRPositionTypes.CHARGING_STATION or \ + pos['type_id'] == MiRPositionTypes.LIFT or \ + pos['type_id'] == MiRPositionTypes.LIFT_ENTRY: + self.known_positions[pos['name']] = ( + self.positions_guid_get(pos['guid']) + ) + + def create_rmf_missions(self, rmf_missions: dict): + rmf_mission_group_id = 'some_id' #TODO create a group id + for mission_name, mission_json in rmf_missions.items(): + if mission_name not in self.known_missions: + # Create the relevant mission on MiR + mission_id = self.missions_post(mission_name, rmf_mission_group_id) + # Fill in mission actions + self.create_rmf_mission_actions(mission_name, mission_id, mission_json) + + def create_rmf_mission_actions(self, mission_name: str, mission_id: str, mission_json: list[dict]): + mission_actions = [] + + for action in mission_json: + # Find schema for action type + action_type = action.get('action_type') + action_type_schema = self.mission_action_types.get(action_type) + if action_type_schema is None: + action_type_schema = self.action_type_get(action_type) + self.mission_action_types[action_type] = action_type_schema + + action_body_param = [] + id_tracker = [] + # First, add the parameters that we have customized for RMF + for param in action['parameters']: + id_tracker.append(param['id']) + param_body = {} + param_body['id'] = param['id'] + param_body['input_name'] = param['input_name'] + param_body['value'] = param['value'] + + # If the input type is a position, we would need a valid GUID for the value field + # Let's find a placeholder position GUID from the list of known positions + if param_body['id'] == 'position' or param_body['id'] == 'entry_position': + default_pos = list(self.known_positions.items())[0]['guid'] + param_body['value'] = default_pos + + action_body_param.append(param_body) + + # Next, add the default parameters that come with this action + for param in action_type_schema['parameters']: + # TODO: skip if this parameter has already been included in the json provided in rmf missions + # e.g. "position" in rmf_move_to_position + if param['id'] in id_tracker: + continue + id_tracker.append(param['id']) + + param_body = {} + param_body['id'] = param['id'] + param_body['input_name'] = param.get('input_name') + + default_value = None + if 'constraints' in param and 'default' in param['constraints']: + default_value = param['constraints']['default'] + param_body['value'] = default_value + action_body_param.append(param_body) + + action_body = {} + action_body['action_type'] = action_type + action_body['priority'] = action.get('priority') + action_body['parameters'] = action_body_param + + mission_actions.append(action_body) + + action_guid = self.missions_mission_id_actions_post(mission_id, mission_actions) + + def navigate(self, position): + pos_x = round(position[0], 3) + pos_y = round(position[1], 3) + ori_deg = position[2]*180/math.pi + mission_params = [ + {'id': 'X', 'value': pos_x, 'label': f'{pos_x}'}, + {'id': 'Y', 'value': pos_y, 'label': f'{pos_y}'}, + {'id': 'Orientation', 'value': ori_deg, 'label': f'{ori_deg:.3f}'} + ] + return self.queue_mission_by_name(self.move_mission, mission_params) + + def go_to_known_position(self, position_name): + if not position_name in self.known_positions: + return None + return self.dock(self.go_to, None, position_name) + + def dock(self, mission_name, start_waypoint, end_waypoint): + mission_params = None + + # Get parameters for start and end waypoints + end_wp = self.known_positions.get(end_waypoint) + if not end_wp: + self.update_known_positions() + end_wp = self.known_positions.get(end_waypoint) + assert end_wp is not None + end_wp_guid = end_wp.get('guid') + assert end_wp_guid is not None + end_param = self.get_mission_params_with_value(mission_name, 'move', 'end_waypoint', end_wp_guid) + dock_param = self.get_mission_params_with_value(mission_name, 'docking', 'end_waypoint', end_wp_guid) + + # Start waypoint is optional + if start_waypoint is not None: + start_wp = self.known_positions.get(start_waypoint) + if not start_wp: + self.update_known_positions() + start_wp = self.known_positions.get(start_waypoint) + assert start_wp is not None + start_wp_guid = start_wp.get('guid') + assert start_wp_guid is not None + start_param = self.get_mission_params_with_value(mission_name, 'move', 'start_waypoint', start_wp_guid) + mission_params = start_param + end_param + + # Check whether we should dock into this end waypoint or not (for charging) + elif dock_param: + mission_params = end_param + dock_param + else: + mission_params = end_param + return self.queue_mission_by_name(mission_name, mission_params) + + def localize(self, map, estimate, index): + if self.localize_mission is None: + raise Exception( + 'The fleet was not configured with a localize mission' + ) + + if index is not None: + position_name = f'cgh_1810_localize_{index}' + else: + p = estimate + position_name = f'cgh_1810_localize_{map}_{p[0]:.2f}_{p[1]:.2f}' + mir_map = self.map_conversions.rmf_to_mir[map] + map_id = self.known_maps[mir_map] + position_guid = self.get_position_guid(position_name, map_id, estimate) + if position_guid is None: + raise Exception('Unable to set a localization position on the MiR') + mission_params = copy.copy(self.localize_params) + for param in mission_params: + if param.get('input_name') == LocalizationParamPosition: + param['value'] = position_guid + + return self.queue_mission_by_name( + self.localize_mission, + mission_params=mission_params + ) + + + def get_position_guid(self, name, map_id, location): + attempts = 0 + max_attempts = 10 + while True: + attempts +=1 + if attempts >= max_attempts: + print( + f'Too many attempts [{max_attempts}] to set a localization ' + 'position.' + ) + return None + + # We keep cycling through these attempts until we can confirm that + # the MiR server has an acceptable position for us to use for + # localization + position = self.known_positions.get(name) + + def position_matches(pos): + if abs(pos['pos_x'] - location[0]) > 0.01: + return False + if abs(pos['pos_y'] - location[1]) > 0.01: + return False + if pos['map_id'] != map_id: + return False + return True + + if position is None: + # The position does not exist so we need to create a new one + position_guid = self.positions_post(name, map_id, location) + if position_guid is not None: + return position_guid + # For some reason posting the new position failed. Maybe there + # was a timeout or an argument error. We will update the known + # positions and retry this loop. + self.update_known_positions() + elif not position_matches(position): + if self.positions_put(position['guid'], name, map_id, location): + return position['guid'] + else: + return position['guid'] + + + def queue_mission_by_name(self, mission_name, mission_params=None): + mir_mission = self.known_missions.get(mission_name) + if mir_mission is None: + return None + mission_guid = mir_mission['guid'] + mission_description = None + if mission_params: + mission_description = { + 'mission_id': mission_guid, + 'message': 'string', + 'parameters': mission_params, + 'priority': 0, + 'description': 'string' + } + + response = self.mission_queue_post(mission_guid, mission_description) + if response is None or 'id' not in response: + return None + mission_queue_id = response['id'] + return mission_queue_id + + def positions_post(self, name, map_id, location): + data = { + 'created_by_id': self.created_by_id, + 'map_id': map_id, + 'name': name, + 'orientation': math.degrees(location[2]), + 'pos_x': location[0], + 'pos_y': location[1], + 'type_id': MiRPositionTypes.ROBOT + } + + try: + response = requests.post( + self.prefix + "positions", + headers=self.headers, + data=json.dumps(data), + timeout=self.timeout + ).json() + if response is None or 'guid' not in response: + return None + if self.debug: + print(f'Response: {response}') + self.known_positions[response['name']] = response + return response['guid'] + except Exception as err: + print(f'Position post failed: {err}') + + def positions_put(self, guid, name, map_id, location): + data = { + 'map_id': map_id, + 'name': name, + 'orientation': math.degrees(location[2]), + 'pos_x': location[0], + 'pos_y': location[1], + 'type_id': MiRPositionTypes.ROBOT + } + + try: + response = requests.put( + self.prefix + f'positions/{guid}', + headers=self.headers, + data=json.dumps(data), + timeout=self.timeout + ).json() + if self.debug: + print(f'Response: {response}') + self.known_positions[response['name']] = response + return response['guid'] + except: + pass + + def positions_delete(self): + new_known_positions = {} + for position in self.known_positions: + if 'rmf_localize' in position or 'cgh_localize' in position: + pos_guid = self.known_positions[position] + try: + response = requests.delete( + self.prefix + f'positions/{pos_guid}', + headers=self.headers, + timeout=self.timeout + ).json() + return response['guid'] + except: + pass + else: + new_known_positions[position] = copy.deepcopy(self.known_positions[position]) + self.known_positions = {} + self.known_positions = new_known_positions + + def positions_guid_delete(self, guid): + try: + response = requests.delete( + self.prefix + f'positions/{guid}', + headers=self.headers, + timeout=self.timeout + ).json() + if self.debug: + print(f'Response: {response}') + except Exception as err: + print(f'Failed to delete position guid [{guid}]: {err}') + + def status_get(self) -> MirStatus: + if not self.connected: + return + try: + response = requests.get(self.prefix + f'status', headers=self.headers, timeout=self.timeout) + # To prevent adapter crashing in case of error + if response.json() is None or 'position' not in response.json(): + return None + map_id = response.json()['map_id'] + map_name = None + for mname, mid in self.known_maps.items(): + if mid == map_id: + map_name = mname + break + + return MirStatus(response.json(), self.map_conversions, map_name) + except HTTPError as http_err: + print(f"HTTP error: {http_err}") + except Exception as err: + print(f"Other error: {err}") + + def load_missions(self): + robot_missions = self.missions_get() + for mission in robot_missions: + if 'move_coordinate' in mission['name']: + self.missions_guid_delete(mission['guid']) + else: + self.known_missions[mission['name']] = mission + + def load_maps(self): + robot_maps = self.maps_get() + for map in robot_maps: + self.known_maps[map['name']] = map['guid'] + + def me_get(self): + try: + response = requests.get(self.prefix + 'users/me', headers=self.headers, timeout=self.timeout) + if self.debug: + print(f'Response: {response.json()}') + return response.json() + except HTTPError as http_err: + print(f'HTTP error: {http_err}') + except Exception as err: + print(f'Other error: {err}') + + def actions_get(self): + if not self.connected: + return + try: + response = requests.get(self.prefix + 'actions', headers=self.headers, timeout=self.timeout) + if self.debug: + print(f"Response: {response.json()}") + return response.json() + except HTTPError as http_err: + print(f"HTTP error: {http_err}") + except Exception as err: + print(f"Other error: {err}") + + def action_type_get(self, action_type: str): + if not self.connected: + return + try: + response = requests.get(self.prefix + f'actions/{action_type}', headers=self.headers, timeout=self.timeout) + if self.debug: + print(f"Response: {response.json()}") + return response.json() + except HTTPError as http_err: + print(f"HTTP error: {http_err}") + except Exception as err: + print(f"Other error: {err}") + + def missions_get(self): + if not self.connected: + return + try: + response = requests.get(self.prefix + 'missions', headers=self.headers, timeout=self.timeout) + if self.debug: + print(f"Response: {response.json()}") + return response.json() + except HTTPError as http_err: + print(f"HTTP error: {http_err}") + except Exception as err: + print(f"Other error: {err}") + + def positions_get(self): + if not self.connected: + return + try: + response = requests.get(self.prefix + 'positions' , headers=self.headers, timeout=self.timeout) + if self.debug: + print(f"Response: {response.json()}") + return response.json() + except HTTPError as http_err: + print(f"HTTP error: {http_err}") + except Exception as err: + print(f"Other error: {err}") + + def mission_queue_get(self): + if not self.connected: + return + try: + response = requests.get(self.prefix + f'mission_queue', headers = self.headers, timeout=self.timeout) + return response.json() + except HTTPError as http_err: + print(f"HTTP error: {http_err}") + except Exception as err: + print(f"Other here error: {err}") + + def mission_queue_id_get(self, mission_queue_id): + if not self.connected: + return + try: + response = requests.get(self.prefix + f'mission_queue/{mission_queue_id}', headers = self.headers, timeout=self.timeout) + return response.json() + except HTTPError as http_err: + print(f"HTTP error: {http_err}") + except Exception as err: + print(f"Other here error: {err}") + + def mission_queue_post(self, mission_id, full_mission_description=None): + if not self.connected: + return + data = {'mission_id': mission_id} + if full_mission_description is not None: + # print(f'---------->>> {full_mission_description}') + data = full_mission_description + if mission_id != full_mission_description['mission_id']: + print(f'Inconsistent mission id, provided [{mission_id}], full_mission_description: [{full_mission_description}]') + return + + try: + response = requests.post(self.prefix + 'mission_queue' , headers = self.headers, data=json.dumps(data), timeout = self.timeout) + if self.debug: + print(f"Response: {response.json()}") + return response.json() + except HTTPError as http_err: + print(f"HTTP error: {http_err}") + except Exception as err: + print(f"Other here error: {err}") + + def missions_mission_id_actions_post(self,mission_id,body): + if not self.connected: + return + try: + response = requests.post(self.prefix + 'missions/' + mission_id +'/actions' , headers = self.headers, data=json.dumps(body), timeout = self.timeout) + if self.debug: + print(f"Response: {response.json()}") + print(response.status_code) + return response.json() + except HTTPError as http_err: + print(f"HTTP error: {http_err}") + except Exception as err: + print(f"Other error: {err}") + + def missions_mission_id_actions_get(self, mission_id): + if not self.connected: + return + try: + response = requests.get(self.prefix + 'missions/' + str(mission_id) +'/actions' , headers = self.headers, timeout = self.timeout) + if self.debug: + print(f"Response: {response.json()}") + print(response.status_code) + return response.json() + except HTTPError as http_err: + print(f"HTTP error: {http_err}") + except Exception as err: + print(f"Other error: {err}") + + def missions_post(self, mission): + if not self.connected: + return + try: + response = requests.post(self.prefix + 'missions' , headers = self.headers, data=mission, timeout = self.timeout) + if self.debug: + print(f"Response: {response.json()}") + return response.json() + except HTTPError as http_err: + print(f"HTTP error: {http_err}") + except Exception as err: + print(f"Other error: {err}") + + def positions_guid_get(self, guid): + if not self.connected: + return + try: + response = requests.get(self.prefix + 'positions/'+ guid, headers=self.headers, timeout=self.timeout) + if self.debug: + print(f"Response: {response.json()}") + return response.json() + except HTTPError as http_err: + print(f"HTTP error: {http_err}") + except Exception as err: + print(f"Other error: {err}") + + def status_put(self, state_id): + if not self.connected: + return + data = {"state_id": state_id} + try: + response = requests.put(self.prefix + 'status', headers = self.headers, data=json.dumps(data), timeout=self.timeout) + if self.debug: + print(f"Response: {response.json()}") + return response.json() + except HTTPError as http_err: + print(f"HTTP error: {http_err}") + except Exception as err: + print(f"Other error: {err}") + + def clear_error(self): + if not self.connected: + return + data = {"clear_error": True} + try: + response = requests.put(self.prefix + 'status', headers = self.headers, data=json.dumps(data), timeout=self.timeout) + if self.debug: + print(f"Response: {response.json()}") + return response.json() + except HTTPError as http_err: + print(f"HTTP error: {http_err}") + except Exception as err: + print(f"Other error: {err}") + + def mission_queue_delete(self): + if not self.connected: + return + try: + response = requests.delete(self.prefix + 'mission_queue' , headers = self.headers, timeout = self.timeout) + if self.debug: + print(f"Response: {response.headers}") + return True + except HTTPError as http_err: + print(f"HTTP error: {http_err}") + return False + except Exception as err: + print(f"Other error: {err}") + return False + + def mission_queue_id_delete(self, mission_queue_id): + if not self.connected: + return + try: + response = requests.delete( + self.prefix + 'mission_queue/' + str(mission_queue_id), + headers = self.headers, + timeout = self.timeout + ) + if self.debug: + print(f"Response: {response.headers}") + return True + except HTTPError as http_err: + print(f"HTTP error: {http_err}") + return False + except Exception as err: + print(f"Other error: {err}") + return False + + def missions_guid_delete(self, guid): + if not self.connected: + return + try: + response = requests.delete(self.prefix + 'missions/' +guid , headers = self.headers, timeout = self.timeout) + if self.debug: + print(f"Response: {response.headers}") + return True + except HTTPError as http_err: + print(f"HTTP error: {http_err}") + return False + except Exception as err: + print(f"Other error: {err}") + return False + + def maps_get(self): + if not self.connected: + return [] + try: + response = requests.get(self.prefix + 'maps', headers = self.headers, timeout = self.timeout) + if self.debug: + print(f"Response: {response.headers}") + return response.json() + except HTTPError as http_err: + print(f"HTTP error: {http_err}") + return [] + except Exception as err: + print(f"Other error: {err}") + return [] + + def mission_completed(self, mission_queue_id): + mission_status = self.mission_queue_id_get(mission_queue_id) + if not mission_status: + return False + if 'finished' in mission_status and mission_status['finished'] is not None: + # if 'state' in mission_status and mission_status['state'] == 'Done': + return True + return False + + def get_mission_params_with_value(self, mission_name: str, action_type: str, param_name: str, value: str): + mission_actions = self.mission_actions.get(mission_name) + mission_params = None + for d in mission_actions: + if 'action_type' in d and d['action_type'] == action_type: + mission_params = d['parameters'] + for p in mission_params: + if 'input_name' in p and p['input_name'] == param_name: + p['value'] = value + # Let's only include this mission param to avoid error + mission_params = [p] + return mission_params + return mission_params + + def update_footprint(self): + return self.queue_mission_by_name(self.footprint_mission) diff --git a/fleet_adapter_mir/fleet_adapter_mir/rmf_cart_missions.json b/fleet_adapter_mir/fleet_adapter_mir/rmf_cart_missions.json new file mode 100644 index 0000000..b7d49ba --- /dev/null +++ b/fleet_adapter_mir/fleet_adapter_mir/rmf_cart_missions.json @@ -0,0 +1,559 @@ +{ + "rmf_exit_lot": [ + { + "priority": 1, + "parameters": [ + { + "value": "mirconst-guid-0000-0001-footprint000", + "input_name": null, + "id": "footprint" + } + ], + "action_type": "set_footprint" + }, + { + "priority": 2, + "parameters": [ + { + "value": -1.0, + "input_name": null, + "id": "x" + }, + { + "value": 0.0, + "input_name": null, + "id": "y" + }, + { + "value": 0.0, + "input_name": null, + "id": "orientation" + }, + { + "value": 0.25, + "input_name": null, + "id": "max_linear_speed" + }, + { + "value": 0.25, + "input_name": null, + "id": "max_angular_speed" + }, + { + "value": true, + "input_name": null, + "id": "collision_detection" + } + ], + "action_type": "relative_move" + }, + { + "priority": 3, + "parameters": [ + { + "value": "plc_register", + "input_name": null, + "id": "compare" + }, + { + "value": "e2fc134a-56bb-11ee-a409-00012998f454", + "input_name": null, + "id": "module" + }, + { + "value": "0", + "input_name": null, + "id": "io_port" + }, + { + "value": "8", + "input_name": null, + "id": "register" + }, + { + "value": "==", + "input_name": null, + "id": "operator" + }, + { + "value": 1.0, + "input_name": null, + "id": "value" + }, + { + "value": "", + "input_name": null, + "id": "true" + }, + { + "value": "", + "input_name": null, + "id": "false" + } + ], + "action_type": "if" + }, + { + "priority": 4, + "parameters": [ + { + "value": "f65abbec-ea4e-11ed-af33-00012983ef2c", + "input_name": null, + "id": "footprint" + } + ], + "action_type": "set_footprint" + }, + { + "priority": 5, + "parameters": [ + { + "value": "mirconst-guid-0000-0001-footprint000", + "input_name": null, + "id": "footprint" + } + ], + "action_type": "set_footprint" + } + ], + "rmf_dock_to_cart": [ + { + "priority": 1, + "parameters": [ + { + "value": "mirconst-guid-0000-0001-footprint000", + "input_name": null, + "id": "footprint" + } + ], + "action_type": "set_footprint" + }, + { + "priority": 2, + "parameters": [ + { + "value": null, + "input_name": "cart_marker", + "id": "marker" + }, + { + "value": "cbd0de8c-467c-11ee-899f-00012983ef2c", + "input_name": null, + "id": "marker_type" + }, + { + "value": "10", + "input_name": null, + "id": "retries" + }, + { + "value": 0.25, + "input_name": null, + "id": "max_linear_speed" + } + ], + "action_type": "docking" + } + ], + "rmf_dropoff_cart": [ + { + "priority": 2, + "parameters": [ + { + "value": "mirconst-guid-0000-0001-footprint000", + "input_name": null, + "id": "footprint" + } + ], + "action_type": "set_footprint" + }, + { + "priority": 3, + "parameters": [ + { + "value": -1.0, + "input_name": null, + "id": "x" + }, + { + "value": 0.0, + "input_name": null, + "id": "y" + }, + { + "value": 0.0, + "input_name": null, + "id": "orientation" + }, + { + "value": 0.25, + "input_name": null, + "id": "max_linear_speed" + }, + { + "value": 0.25, + "input_name": null, + "id": "max_angular_speed" + }, + { + "value": true, + "input_name": null, + "id": "collision_detection" + } + ], + "action_type": "relative_move" + }, + { + "priority": 1, + "parameters": [ + { + "value": "mirconst-guid-0000-0011-actionlist00", + "input_name": null, + "id": "mission_id" + } + ], + "action_type": "load_mission" + } + ], + "rmf_follow_line": [ + { + "priority": 1, + "parameters": [], + "action_type": "adjust_localization" + }, + { + "priority": 2, + "parameters": [ + { + "value": "plc_register", + "input_name": null, + "id": "compare" + }, + { + "value": "e2fc134a-56bb-11ee-a409-00012998f454", + "input_name": null, + "id": "module" + }, + { + "value": "0", + "input_name": null, + "id": "io_port" + }, + { + "value": "8", + "input_name": null, + "id": "register" + }, + { + "value": "==", + "input_name": null, + "id": "operator" + }, + { + "value": 1.0, + "input_name": null, + "id": "value" + }, + { + "value": "", + "input_name": null, + "id": "true" + }, + { + "value": "", + "input_name": null, + "id": "false" + } + ], + "action_type": "if" + }, + { + "priority": 3, + "parameters": [ + { + "value": "f65abbec-ea4e-11ed-af33-00012983ef2c", + "input_name": null, + "id": "footprint" + } + ], + "action_type": "set_footprint" + }, + { + "priority": 4, + "parameters": [ + { + "value": "mirconst-guid-0000-0001-footprint000", + "input_name": null, + "id": "footprint" + } + ], + "action_type": "set_footprint" + }, + { + "priority": 5, + "parameters": [ + { + "value": "to be replaced with a value guid in the fleet adapter", + "input_name": "start_waypoint", + "id": "position" + }, + { + "value": 10, + "input_name": null, + "id": "retries" + }, + { + "value": 0.2, + "input_name": null, + "id": "distance_threshold" + } + ], + "action_type": "move" + }, + { + "priority": 6, + "parameters": [ + { + "value": "plc_register", + "input_name": null, + "id": "compare" + }, + { + "value": "e2fc134a-56bb-11ee-a409-00012998f454", + "input_name": null, + "id": "module" + }, + { + "value": "0", + "input_name": null, + "id": "io_port" + }, + { + "value": "8", + "input_name": null, + "id": "register" + }, + { + "value": "==", + "input_name": null, + "id": "operator" + }, + { + "value": 1.0, + "input_name": null, + "id": "value" + }, + { + "value": "", + "input_name": null, + "id": "true" + }, + { + "value": "", + "input_name": null, + "id": "false" + } + ], + "action_type": "if" + }, + { + "priority": 7, + "parameters": [ + { + "value": "454e65f9-06b9-11ee-acbc-00012983ef2c", + "input_name": null, + "id": "footprint" + } + ], + "action_type": "set_footprint" + }, + { + "priority": 8, + "parameters": [ + { + "value": "mirconst-guid-0000-0001-footprint000", + "input_name": null, + "id": "footprint" + } + ], + "action_type": "set_footprint" + }, + { + "priority": 9, + "parameters": [ + { + "value": "to be replaced with a value guid in the fleet adapter", + "input_name": "end_waypoint", + "id": "position" + }, + { + "value": 10, + "input_name": null, + "id": "retries" + }, + { + "value": 0.2, + "input_name": null, + "id": "distance_threshold" + } + ], + "action_type": "move" + }, + { + "priority": 10, + "parameters": [], + "action_type": "adjust_localization" + } + ], + "rmf_pickup_cart": [ + { + "priority": 1, + "parameters": [ + { + "value": "13", + "input_name": null, + "id": "register" + }, + { + "value": "set", + "input_name": null, + "id": "action" + }, + { + "value": 0.0, + "input_name": null, + "id": "value" + } + ], + "action_type": "set_plc_register" + }, + { + "priority": 2, + "parameters": [ + { + "value": "14", + "input_name": null, + "id": "register" + }, + { + "value": 1.0, + "input_name": null, + "id": "value" + }, + { + "value": 0.0, + "input_name": null, + "id": "reset_value" + }, + { + "value": "", + "input_name": null, + "id": "content" + } + ], + "action_type": "set_reset_plc" + }, + { + "priority": 3, + "parameters": [ + { + "value": "8", + "input_name": null, + "id": "register" + }, + { + "value": 1.0, + "input_name": null, + "id": "value" + }, + { + "value": "00:01:00.000000", + "input_name": null, + "id": "timeout" + } + ], + "action_type": "wait_for_plc_register" + }, + { + "priority": 4, + "parameters": [ + { + "value": "f65abbec-ea4e-11ed-af33-00012983ef2c", + "input_name": null, + "id": "footprint" + } + ], + "action_type": "set_footprint" + } + ], + "rmf_update_footprint": [ + { + "priority": 1, + "parameters": [ + { + "value": "plc_register", + "input_name": null, + "id": "compare" + }, + { + "value": "e2fc134a-56bb-11ee-a409-00012998f454", + "input_name": null, + "id": "module" + }, + { + "value": "0", + "input_name": null, + "id": "io_port" + }, + { + "value": "8", + "input_name": null, + "id": "register" + }, + { + "value": "==", + "input_name": null, + "id": "operator" + }, + { + "value": 1.0, + "input_name": null, + "id": "value" + }, + { + "value": "", + "input_name": null, + "id": "true" + }, + { + "value": "", + "input_name": null, + "id": "false" + } + ], + "action_type": "if" + }, + { + "priority": 2, + "parameters": [ + { + "value": "f65abbec-ea4e-11ed-af33-00012983ef2c", + "input_name": null, + "id": "footprint" + } + ], + "action_type": "set_footprint" + }, + { + "priority": 3, + "parameters": [ + { + "value": "mirconst-guid-0000-0001-footprint000", + "input_name": null, + "id": "footprint" + } + ], + "action_type": "set_footprint" + } + ] +} \ No newline at end of file diff --git a/fleet_adapter_mir/fleet_adapter_mir/rmf_missions.json b/fleet_adapter_mir/fleet_adapter_mir/rmf_missions.json new file mode 100644 index 0000000..9ba25b3 --- /dev/null +++ b/fleet_adapter_mir/fleet_adapter_mir/rmf_missions.json @@ -0,0 +1,215 @@ +{ + "rmf_dock_and_charge": [ + { + "priority": 1, + "parameters": [ + { + "value": "to be replaced with a value guid in the fleet adapter", + "input_name": "end_waypoint", + "id": "position" + }, + { + "value": 10, + "input_name": null, + "id": "retries" + }, + { + "value": 0.2, + "input_name": null, + "id": "distance_threshold" + } + ], + "action_type": "move" + }, + { + "priority": 2, + "parameters": [ + { + "value": null, + "input_name": "end_waypoint", + "id": "marker" + }, + { + "value": "mirconst-guid-0000-0001-marker000001", + "input_name": null, + "id": "marker_type" + }, + { + "value": "10", + "input_name": null, + "id": "retries" + }, + { + "value": 0.25, + "input_name": null, + "id": "max_linear_speed" + } + ], + "action_type": "docking" + }, + { + "priority": 3, + "parameters": [ + { + "value": "00:10:00.000000", + "input_name": null, + "id": "minimum_time" + }, + { + "value": 25.0, + "input_name": null, + "id": "minimum_percentage" + }, + { + "value": true, + "input_name": null, + "id": "charge_until_new_mission" + } + ], + "action_type": "charging" + } + ], + "rmf_follow_line": [ + { + "priority": 1, + "parameters": [], + "action_type": "adjust_localization" + }, + { + "priority": 2, + "parameters": [ + { + "value": "to be replaced with a value guid in the fleet adapter", + "input_name": "start_waypoint", + "id": "position" + }, + { + "value": 10, + "input_name": null, + "id": "retries" + }, + { + "value": 0.2, + "input_name": null, + "id": "distance_threshold" + } + ], + "action_type": "move" + }, + { + "priority": 3, + "parameters": [ + { + "value": "to be replaced with a value guid in the fleet adapter", + "input_name": "end_waypoint", + "id": "position" + }, + { + "value": 10, + "input_name": null, + "id": "retries" + }, + { + "value": 0.2, + "input_name": null, + "id": "distance_threshold" + } + ], + "action_type": "move" + }, + { + "priority": 4, + "parameters": [], + "action_type": "adjust_localization" + } + ], + "rmf_localize": [ + { + "priority": 1, + "parameters": [], + "action_type": "adjust_localization" + }, + { + "priority": 2, + "parameters": [ + { + "value": "to be replaced with a value guid in the fleet adapter", + "input_name": "position_estimate", + "id": "entry_position" + } + ], + "action_type": "switch_map" + }, + { + "priority": 3, + "parameters": [], + "action_type": "adjust_localization" + }, + { + "priority": 4, + "parameters": [], + "action_type": "adjust_localization" + }, + { + "priority": 5, + "parameters": [], + "action_type": "adjust_localization" + } + ], + "rmf_move": [ + { + "priority": 1, + "parameters": [ + { + "value": 0.0, + "input_name": "X", + "id": "x" + }, + { + "value": 0.0, + "input_name": "Y", + "id": "y" + }, + { + "value": 0.0, + "input_name": "Orientation", + "id": "orientation" + }, + { + "value": 10, + "input_name": null, + "id": "retries" + }, + { + "value": 0.2, + "input_name": null, + "id": "distance_threshold" + } + ], + "action_type": "move_to_position" + } + ], + "rmf_move_to_position": [ + { + "action_type": "move", + "priority": 1, + "parameters": [ + { + "value": "to be replaced with a value guid in the fleet adapter", + "input_name": "end_waypoint", + "id": "position" + }, + { + "value": 10, + "input_name": null, + "id": "retries" + }, + { + "value": 0.2, + "input_name": null, + "id": "distance_threshold" + } + ] + } + ] +} \ No newline at end of file diff --git a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py new file mode 100644 index 0000000..ea5ad7b --- /dev/null +++ b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py @@ -0,0 +1,470 @@ +import math +import time +from typing import Any +from dataclasses import dataclass +import json +from rmf_adapter.robot_update_handle import Tier +import rmf_adapter.easy_full_control as rmf_easy +import rclpy +import rclpy.node as Node +from rclpy.duration import Duration +from .mir_api import MirAPI, MirStatus, MiRStateCode +from threading import Lock + + +# Parallel processing solution derived from +# https://stackoverflow.com/a/59385935 +def parallel(f): + def run_in_parallel(*args, **kwargs): + + return args[0].event_loop.run_in_executor( + None, f, *args, **kwargs + ) + + return run_in_parallel + + +class MissionHandle: + def __init__(self, execution, docking=False, localize=False, charger=None): + self.execution = execution + self.docking = docking + self.localize = localize + self.charger = charger + self.done = False + # mission_queue_id gets set asynchronously + self.mission_queue_id = None + self.do_not_cancel = False + self.mutex = Lock() + # Block before beginning the request to guarantee that a call to stop() + # cannot possibly lock it first + self.mutex.acquire(blocking=True) + + def set_mission_queue_id(self, mission_queue_id): + self.mission_queue_id = mission_queue_id + self.mutex.release() + + @property + def activity(self): + # Move the execution reference into a separate variable just in case + # another thread modifies self.execution while we're still using it. + execution = self.execution + if execution is not None and not self.done: + return execution.identifier + return None + +class RobotAdapterMiR: + def __init__( + self, + name: str, + rmf_config: rmf_easy.RobotConfiguration, + mir_config: dict, + conversions: dict, + fleet_handle, + fleet_config, + node: Node, + event_loop, + debug=False + ): + self.name = name + self.node = node + self.mission: MissionHandle | None = None + self.event_loop = event_loop + self.debug = debug + + self.disconnect = False + + prefix = mir_config['base_url'] + headers = { + 'Content-Type': mir_config['user'], + 'Authorization': mir_config['password'], + } + self.api: MirAPI = MirAPI(prefix, headers, conversions) + + status = self.api.status_get() + while self.api.status_get() is None: + status = self.api.status_get() + time.sleep(0.1) + self.last_known_status: MirStatus = status + self.current_map = status.state.map + self.fleet_config = fleet_config + + self.api.update_known_positions() + self.api.positions_delete() + + # This must be done after the API is made + self.lift_positions: dict = conversions.get('lift_positions', {}) + for lift, levels in self.lift_positions.items(): + for level, position in levels.items(): + position_name = position.get('name') + assert position_name is not None, ( + f'Missing "name" field for level [{level}] in lift ' + f'[{lift}] for lift_positions in configuration file' + ) + known = self.api.known_positions.get(position_name) + assert known is not None, ( + f'MiR is missing the position [{position_name}] needed as ' + f'a lift position on level [{level}] for lift [{lift}]' + ) + self.nav_issue_ticket = None # We should only have one issue ticket at a time to manage unsuccessful missions + self.requested_replan = False + self.replan_counts = 0 + + self.fleet_handle = fleet_handle + self.update_handle = fleet_handle.add_robot( + self.name, + status.state, + rmf_config, + self._make_callbacks(), + ) + + @property + def activity(self): + # Move the mission reference into a separate variable just in case + # another thread modifies self.mission while we're still using it. + mission = self.mission + if mission is not None: + return self.mission.activity + return None + + async def update_loop(self, period): + while rclpy.ok(): + now = self.node.get_clock().now() + next_wakeup = now + Duration(nanoseconds = period * 1e9) + await self.request_update() + while self.node.get_clock().now() < next_wakeup: + time.sleep(0.01) + + @parallel + def request_update(self): + # Retrieve the latest MiR status from robot + status = self.api.status_get() + if status is None: + self.disconnect = True + self.node.get_logger().warn(f'Unable to retrieve status from robot [{self.name}]!') + return + if self.disconnect: + self.node.get_logger().info(f'Robot [{self.name}] connectivity resumed, received status from robot successfully.') + self.disconnect = False + more = self.update_handle.more() + if more is not None: + more.unstable_debug_positions(self.debug) + + # Update the stored mission status from MiR + mission = self.mission + self.update_mission_status(status, mission) + + # Update RMF with the latest RobotState + if mission is None or (mission.localize and mission.done) or not mission.localize: + self.update_handle.update(status.state, self.activity) + self.last_known_status = status + else: + self.node.get_logger().info( + f'Mission is None / Robot is localizing, ignore status update') + + # Update RMF to mark the ActionExecution as finished + if mission is not None and mission.done: + self.update_rmf_finished(mission) + + # Clear error on updates + if status is not None and 'errors' in status.response and len(status.response['errors']) > 0: + self.api.clear_error() + if status is not None and (status.response['state_id'] == MiRStateCode.PAUSE or status.response['state_id'] == MiRStateCode.ERROR): + self.api.status_put(MiRStateCode.READY) + + def is_charging(self, status: MirStatus): + # TODO(XY): check if we can verify that a robot is charging via mode_id instead + if status.response.get('mission_text') == "Charging... Waiting for new mission...": + return True + return False + + def update_rmf_finished(self, mission: MissionHandle): + if not mission.execution: + return + mission.execution.finished() + mission.execution = None + + def update_mission_status(self, status: MirStatus, mission: MissionHandle): + if mission is None or mission.mission_queue_id is None: + # Either we don't have a mission or we don't know the + # mission_queue_id yet so just continue as normal for now + return + + if mission.execution is None: + # This mission is already finished, so we return early + return + + mission_status = self.api.mission_queue_id_get(mission.mission_queue_id) + executing_mission = status.response.get('mission_queue_id') + if executing_mission == mission.mission_queue_id: + # The current mission is still being executed, so we don't + # need to change anything + if mission.charger is not None and self.is_charging(status): + self.node.get_logger().info(f'Robot [{self.name}] has begun charging...') + mission.docking = False + mission.done = True + return + + # The mission is not being executed according to the status, so either + # the mission has finished or it has not started yet. We need a second + # API call to figure out which it is. + if mission_status is None or mission_status.get('state') is None: + # It shouldn't come to here, but we'll prevent any potential crashes + # with a check here + return + if mission_status['state'] == 'Done': + # The mission has finished so let's trigger execution.finished() and + # then clear it out + self.node.get_logger().info(f'MiR [{self.name}] has completed mission {mission.mission_queue_id}, ' + f'marking ActionExecution object as finished.') + mission.docking = False + mission.done = True + # If the mission previously issued a ticket, let's resolve that ticket + if self.nav_issue_ticket is not None: + msg = {} + self.nav_issue_ticket.resolve(msg) + self.nav_issue_ticket = None + self.node.get_logger().info(f'Issue ticket is resolved!') + self.replan_counts = 0 + elif mission_status['state'] == 'Aborted': + # The robot is unable to perform the mission for some reason, so we + # raise an issue and re-attempt the mission. + tier = Tier.Error + category = mission_status['state'] + detail = { + 'mission_queue_id': mission.mission_queue_id, + 'message': 'Mission has been aborted.' + } + # Save the issue ticket somewhere so that we can resolve it later + self.nav_issue_ticket = self.update_handle.more().create_issue(tier, category, detail) + self.node.get_logger().info(f'Created [{category}] issue ticket for mission queue ID [{mission.mission_queue_id}]') + + # After issuing a ticket, let's request a replan + mission.done = True + self.update_handle.more().replan() + # We keep track of the number of times we are replanning for the same mission + self.replan_counts += 1 + self.node.get_logger().info(f'[{self.name}] Replan count: {self.replan_counts}') + + # Ensure that robot is charging + if mission.done and mission.charger is not None and not self.is_charging(status): + # Charging mission is marked as done but robot is not charging. Let's send + # the robot to the charger again. + mission.done = False + self.update_handle.more().replan() + self.replan_counts += 1 + self.node.get_logger().info(f'[{self.name}] Replan count: {self.replan_counts}') + + def _make_callbacks(self): + callbacks = rmf_easy.RobotCallbacks( + lambda destination, execution: self.navigate( + destination, execution + ), + lambda activity: self.stop(activity), + lambda category, description, execution: self.perform_action( + category, description, execution + ) + ) + + callbacks.localize = lambda estimate, execution: self.localize( + estimate, execution + ) + + return callbacks + + def navigate(self, destination, execution): + # If this is a cancellation behavior command, we check if we're meant to ignore it. + if self.ignore_action: + self.node.get_logger().info(f'Ignoring navigation command, ignore action flag is ' + f'raised after checking latch.') + execution.finished() + return + + # If the nav command coming in is to bring the robot to a charger, but the robot is + # already charging at the same charger, we ignore this nav command + status = self.last_known_status + if status and self.is_charging(status): + ignore_charging_cmd = False + mission = self.mission + # If the robot's previous mission was a charging mission to the same charger + if mission and mission.charger is not None and destination.name == mission.charger: + ignore_charging_cmd = True + # If the robot was already charging at the same charger before any missions were + # sent/stored + elif destination.map == self.current_map and \ + (self.dist(destination.position, status.state.position) < + self.update_handle.max_merge_waypoint_distance()): + ignore_charging_cmd = True + + if ignore_charging_cmd: + self.node.get_logger().info(f'[{self.name}] Received navigation command to dock to ' + f'charger {destination.name} when robot is already charging ' + f'at the same charger, ignoring command and marking it as ' + f'finished.') + execution.finished() + return + + # If the robot already has a mission, cancel it + self.node.get_logger().info(f'[{self.name}] Calling stop for new navigation command.') + self.request_stop(self.mission) + + # If this is a docking task, send the appropriate docking mission + if destination.dock is not None: + dock_json = json.loads(destination.dock) + if dock_json.get('mission_name') == self.api.dock_and_charge_mission: + self.mission = MissionHandle(execution, charger=destination.name) + else: + self.mission = MissionHandle(execution) + self.request_dock(dock_json, self.mission) + return + # TODO(XY): remove this hack and make sure dock missions are passed properly to + # the nav command + elif destination.name and 'Charger' in destination.name: + self.mission = MissionHandle(execution, charger=destination.name) + dock_json = {'description': {'end_waypoint': destination.name}, + 'mission_name': self.api.dock_and_charge_mission} + self.request_dock(dock_json, self.mission) + + if destination.inside_lift is not None: + positions_for_lift = self.lift_positions.get(destination.inside_lift.name) + if positions_for_lift is not None: + position_info = positions_for_lift.get(destination.map) + if position_info is not None: + position_name = position_info['name'] + mir_pos = self.api.known_positions.get(position_name) + if mir_pos is not None: + p_x = mir_pos['pos_x'] + p_y = mir_pos['pos_y'] + r = self.last_known_status.response['position'] + dx = p_x - r['x'] + dy = p_y - r['y'] + dist = math.sqrt(dx*dx + dy*dy) + tolerance = position_info.get('tolerance', 0.3) + if dist < tolerance: + # We are already close enough to the point, so we + # will just have the robot stop and tell RMF to go + # ahead. + self.node.get_logger().info(f'[{self.name}] Calling stop in the lift.') + self.request_stop(self.mission) + self.mission = None + execution.finished() + return + # We are inside the lift but not close enough to the + # desired center point, so we will ask the robot to + # simply move there + self.mission = MissionHandle(execution) + self.request_go_to_known_position(position_name, self.mission) + return + + # If this is a move to task, send rmf_move mission + self.mission = MissionHandle(execution) + self.request_navigate(destination, self.mission) + + @parallel + def request_navigate( + self, + destination, + mission_handle: MissionHandle + ): + mission_queue_id = None + if destination.name: + self.node.get_logger().info(f'[{self.name}] is going to MiR position {destination.name}') + mission_queue_id = self.api.go_to_known_position(destination.name) + if mission_queue_id is None: + self.node.get_logger().info(f'[{self.name}] is going to MiR coordinates [{destination.position}]') + mission_queue_id = self.api.navigate(destination.position) + mission_handle.set_mission_queue_id(mission_queue_id) + + @parallel + def request_go_to_known_position( + self, + position_name: str, + mission_handle: MissionHandle + ): + mission_queue_id = self.api.go_to_known_position(position_name) + mission_handle.set_mission_queue_id(mission_queue_id) + + + @parallel + def request_dock( + self, + docking_points, + mission_handle: MissionHandle + ): + if not ('description' in docking_points): + return + self.node.get_logger().info(f'Requested dock mission for [{self.name}]: {docking_points}') + end_waypoint = docking_points['description']['end_waypoint'] + if 'start_waypoint' in docking_points['description']: + start_waypoint = docking_points['description']['start_waypoint'] + else: + start_waypoint = None + mission_name = docking_points['mission_name'] + + mission_queue_id = self.api.dock(mission_name, start_waypoint, end_waypoint) + mission_handle.set_mission_queue_id(mission_queue_id) + + def stop(self, activity): + mission = self.mission + if mission is not None: + if mission.docking: + self.node.get_logger().info(f'Robot is performing docking mission, ignoring stop issued by RMF') + return + if mission.execution is not None and activity.is_same(mission.execution.identifier): + self.node.get_logger().info(f'[{self.name}] Stop requested from RMF!') + self.request_stop(mission) + self.mission = None + # Before replan, let's make sure the robot footprint is set correctly + self.api.update_footprint() + + @parallel + def request_stop(self, mission: MissionHandle): + if mission is not None: + with mission.mutex: + if mission.mission_queue_id is not None and not mission.do_not_cancel: + self.api.mission_queue_id_delete(mission.mission_queue_id) + + def localize(self, estimate, execution): + self.mission = MissionHandle(execution, localize=True) + self.mission.do_not_cancel = True + self.request_localize(estimate, self.mission) + + @parallel + def request_localize(self, estimate, mission: MissionHandle): + count = 0 + mission_queue_id = None + while count < self.retries and not mission_queue_id: + count += 1 + try: + mission_queue_id = self.api.localize( + estimate.map, estimate.position, estimate.graph_index + ) + if mission_queue_id is not None: + self.node.get_logger().info(f'Localize mission is successfully queued!') + break + except Exception as err: + self.node.get_logger().info( + f'Failed to localize on map {estimate.map}: {err}. Retrying...' + ) + time.sleep(1) + + if not mission_queue_id: + self.node.get_logger().info( + f'Failed to localize on map {estimate.map}. Maximum localize retries exceeded!' + ) + mission.execution.finished() + mission_queue_id = None + return + + mission.set_mission_queue_id(mission_queue_id) + + def perform_action(self, category, description, execution): + task_id = self.update_handle.more().current_task_id() + # ----------------------------------------------------- + # INSERT PERFORM ACTION LOGIC HERE + # ----------------------------------------------------- + raise NotImplementedError + + def dist(self, A, B): + assert(len(A) > 1) + assert(len(B) > 1) + return math.sqrt((A[0] - B[0])**2 + (A[1] - B[1])**2) From 118be994832f5abd964b8e2369d76fef6aeb2e11 Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Wed, 10 Jan 2024 10:45:01 +0800 Subject: [PATCH 02/46] Create standard RMF missions from fleet adapter Signed-off-by: Xiyu Oh --- .../fleet_adapter_mir/fleet_adapter_mir.py | 17 +- .../fleet_adapter_mir/mir_api.py | 148 +++++++++++++++--- .../fleet_adapter_mir/robot_adapter_mir.py | 5 +- 3 files changed, 145 insertions(+), 25 deletions(-) diff --git a/fleet_adapter_mir/fleet_adapter_mir/fleet_adapter_mir.py b/fleet_adapter_mir/fleet_adapter_mir/fleet_adapter_mir.py index f772154..92a96b4 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/fleet_adapter_mir.py +++ b/fleet_adapter_mir/fleet_adapter_mir/fleet_adapter_mir.py @@ -1,6 +1,7 @@ import asyncio import sys import yaml +import json import nudged import argparse import time @@ -117,7 +118,7 @@ def start(self): rclpy.shutdown() -def create_fleet(fleet_config, config_yaml, cmd_node) -> FleetAdapterMiR: +def create_fleet(fleet_config, config_yaml, cmd_node, rmf_missions) -> FleetAdapterMiR: """Create RMF Adapter and fleet handle""" for level, coords in config_yaml['conversions']['reference_coordinates'].items(): tf = compute_transforms(level, coords, cmd_node) @@ -152,6 +153,7 @@ def create_fleet(fleet_config, config_yaml, cmd_node) -> FleetAdapterMiR: rmf_config, mir_config, conversions, + rmf_missions, fleet_handle, fleet_config, cmd_node, @@ -173,7 +175,7 @@ def main(argv=sys.argv): args_without_ros = rclpy.utilities.remove_ros_args(argv) parser = argparse.ArgumentParser( - prog="fleet_adapter_mir", + prog="cgh_fleet_adapter_mir", description="Configure and spin up fleet adapters for MiR 100 robots " "that interface between the " "MiR REST API, ROS2, and rmf_core!") @@ -181,6 +183,8 @@ def main(argv=sys.argv): help="Input config.yaml file to process") parser.add_argument("-n", "--nav_graph", type=str, required=True, help="Path to the nav_graph for this fleet adapter") + parser.add_argument("-a", "--actions", type=str, required=False, default='', + help="Path to the RMF mission actions to be created") parser.add_argument("-m", "--mock", action='store_true', help="Init a mock adapter instead " "(does not require a schedule node, " @@ -193,6 +197,7 @@ def main(argv=sys.argv): config_path = args.config_file nav_graph_path = args.nav_graph + actions_path = args.actions fleet_config = rmf_easy.FleetConfiguration.from_config_files( config_path, nav_graph_path @@ -202,6 +207,12 @@ def main(argv=sys.argv): with open(config_path, 'r') as f: config_yaml = yaml.safe_load(f) + if actions_path == '': + rmf_missions = None + else: + with open(actions_path, 'r') as g: + rmf_missions = json.load(g) + dry_run = args.dry_run # For testing if dry_run: @@ -222,7 +233,7 @@ def main(argv=sys.argv): cmd_node = rclpy.node.Node(config_yaml['node_names']['robot_command_handle']) # Create the fleet, including the robots that are in the config file - fleet = create_fleet(fleet_config, config_yaml, cmd_node) + fleet = create_fleet(fleet_config, config_yaml, cmd_node, rmf_missions) # GO! fleet.start() diff --git a/fleet_adapter_mir/fleet_adapter_mir/mir_api.py b/fleet_adapter_mir/fleet_adapter_mir/mir_api.py index 7d330cc..da0e22f 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/mir_api.py +++ b/fleet_adapter_mir/fleet_adapter_mir/mir_api.py @@ -54,13 +54,14 @@ def __init__(self, response: dict, map_conversions: MapConversions, map_name: st class MirAPI: - def __init__(self, prefix, headers, conversions, timeout=10.0, debug=False): + def __init__(self, prefix, headers, conversions, rmf_missions, timeout=10.0, debug=False): #HTTP connection self.prefix = prefix self.debug = False self.headers = headers self.timeout = timeout self.connected = False + self.rmf_missions = rmf_missions self.map_conversions = MapConversions(conversions['maps']) self.known_missions = {} self.known_positions = {} @@ -68,6 +69,7 @@ def __init__(self, prefix, headers, conversions, timeout=10.0, debug=False): self.mission_keys: dict = conversions['missions'] self.mission_actions: dict = {} self.mission_action_types: dict = {} + self.footprint_keys: dict = conversions['footprints'] self.attempt_connection() def attempt_connection(self): @@ -84,6 +86,7 @@ def attempt_connection(self): self.load_missions() self.load_maps() + self.create_rmf_missions() move_key = 'move' assert move_key in self.mission_keys, ( @@ -158,6 +161,9 @@ def make_optional_mission(key): self.created_by_id = self.me_get()['guid'] + # Set footprints + self.footprint = self.footprints_guid_get(self.footprint_keys['robot']) + self.update_footprint() def update_known_positions(self): self.known_positions = {} @@ -176,18 +182,33 @@ def update_known_positions(self): self.positions_guid_get(pos['guid']) ) - def create_rmf_missions(self, rmf_missions: dict): - rmf_mission_group_id = 'some_id' #TODO create a group id - for mission_name, mission_json in rmf_missions.items(): + def create_rmf_missions(self): + if self.rmf_missions is None: + return + + # Retrieve the RMF group id if it already exists + mission_groups = self.mission_groups_get() + rmf_mission_group_id = None + mission_group_name = 'RMF' + for group in mission_groups: + if group['name'] == mission_group_name: + rmf_mission_group_id = group['guid'] + break + # If the RMF mission group doesn't exist, create one + if rmf_mission_group_id is None: + mission_group = self.mission_groups_post(mission_group_name) + rmf_mission_group_id = mission_group['guid'] + + # Create RMF missions if they don't exist on the robot + for mission_name, mission_json in self.rmf_missions.items(): if mission_name not in self.known_missions: # Create the relevant mission on MiR - mission_id = self.missions_post(mission_name, rmf_mission_group_id) + mission = self.missions_post(mission_name, rmf_mission_group_id) + self.known_missions[mission['name']] = mission # Fill in mission actions - self.create_rmf_mission_actions(mission_name, mission_id, mission_json) + self.create_rmf_mission_actions(mission_name, mission['guid'], mission_json) def create_rmf_mission_actions(self, mission_name: str, mission_id: str, mission_json: list[dict]): - mission_actions = [] - for action in mission_json: # Find schema for action type action_type = action.get('action_type') @@ -209,15 +230,18 @@ def create_rmf_mission_actions(self, mission_name: str, mission_id: str, mission # If the input type is a position, we would need a valid GUID for the value field # Let's find a placeholder position GUID from the list of known positions if param_body['id'] == 'position' or param_body['id'] == 'entry_position': - default_pos = list(self.known_positions.items())[0]['guid'] + default_pos = self.positions_get()[0]['guid'] param_body['value'] = default_pos + # Similarly, if the input type is a marker type, we'll need to find a placeholder + # marker type GUID from the list of known marker types + if param_body['id'] == 'marker_type': + default_marker = self.docking_offsets_get()[0]['guid'] + param_body['value'] = default_marker action_body_param.append(param_body) # Next, add the default parameters that come with this action for param in action_type_schema['parameters']: - # TODO: skip if this parameter has already been included in the json provided in rmf missions - # e.g. "position" in rmf_move_to_position if param['id'] in id_tracker: continue id_tracker.append(param['id']) @@ -236,10 +260,8 @@ def create_rmf_mission_actions(self, mission_name: str, mission_id: str, mission action_body['action_type'] = action_type action_body['priority'] = action.get('priority') action_body['parameters'] = action_body_param - - mission_actions.append(action_body) - - action_guid = self.missions_mission_id_actions_post(mission_id, mission_actions) + action_body['mission_id'] = mission_id + self.missions_mission_id_actions_post(mission_id, action_body) def navigate(self, position): pos_x = round(position[0], 3) @@ -497,6 +519,8 @@ def load_maps(self): self.known_maps[map['name']] = map['guid'] def me_get(self): + if not self.connected: + return try: response = requests.get(self.prefix + 'users/me', headers=self.headers, timeout=self.timeout) if self.debug: @@ -507,6 +531,17 @@ def me_get(self): except Exception as err: print(f'Other error: {err}') + def mission_groups_get(self): + if not self.connected: + return + try: + response = requests.get(self.prefix + f'mission_groups', headers = self.headers, timeout=self.timeout) + return response.json() + except HTTPError as http_err: + print(f"HTTP error: {http_err}") + except Exception as err: + print(f"Other here error: {err}") + def actions_get(self): if not self.connected: return @@ -602,7 +637,7 @@ def mission_queue_post(self, mission_id, full_mission_description=None): except Exception as err: print(f"Other here error: {err}") - def missions_mission_id_actions_post(self,mission_id,body): + def missions_mission_id_actions_post(self, mission_id, body): if not self.connected: return try: @@ -630,11 +665,35 @@ def missions_mission_id_actions_get(self, mission_id): except Exception as err: print(f"Other error: {err}") - def missions_post(self, mission): + def mission_groups_post(self, group_name): if not self.connected: return + data = { + 'name': group_name, + 'priority': 0, + 'feature': 'default', + 'icon': '' + } + try: + response = requests.post(self.prefix + 'mission_groups' , headers = self.headers, data=json.dumps(data), timeout = self.timeout) + if self.debug: + print(f"Response: {response.json()}") + return response.json() + except HTTPError as http_err: + print(f"HTTP error: {http_err}") + except Exception as err: + print(f"Other error: {err}") + + def missions_post(self, mission, mission_group_id): + if not self.connected: + return + data = { + 'name': mission, + 'hidden': False, + 'group_id': mission_group_id + } try: - response = requests.post(self.prefix + 'missions' , headers = self.headers, data=mission, timeout = self.timeout) + response = requests.post(self.prefix + 'missions' , headers = self.headers, data=json.dumps(data), timeout = self.timeout) if self.debug: print(f"Response: {response.json()}") return response.json() @@ -748,6 +807,52 @@ def maps_get(self): print(f"Other error: {err}") return [] + def docking_offsets_get(self): + if not self.connected: + return + try: + response = requests.get(self.prefix + 'docking_offsets', headers=self.headers, timeout=self.timeout) + if self.debug: + print(f"Response: {response.json()}") + return response.json() + except HTTPError as http_err: + print(f"HTTP error: {http_err}") + except Exception as err: + print(f"Other error: {err}") + + def docking_offsets_guid_get(self, guid: str): + if not self.connected: + return + try: + response = requests.get(self.prefix + f'docking_offsets/{guid}', headers=self.headers, timeout=self.timeout) + if self.debug: + print(f"Response: {response.json()}") + return response.json() + except HTTPError as http_err: + print(f"HTTP error: {http_err}") + except Exception as err: + print(f"Other error: {err}") + + def footprints_get(self): + if not self.connected: + return + try: + response = requests.get(self.prefix + 'footprints', headers=self.headers, timeout=self.timeout) + if self.debug: + print(f"Response: {response.json()}") + return response.json() + except HTTPError as http_err: + print(f"HTTP error: {http_err}") + except Exception as err: + print(f"Other error: {err}") + + def footprints_guid_get(self, footprint_name: str): + footprints = self.footprints_get() + for ft in footprints: + if ft['name'] == footprint_name: + return ft['guid'] + return None + def mission_completed(self, mission_queue_id): mission_status = self.mission_queue_id_get(mission_queue_id) if not mission_status: @@ -772,4 +877,9 @@ def get_mission_params_with_value(self, mission_name: str, action_type: str, par return mission_params def update_footprint(self): - return self.queue_mission_by_name(self.footprint_mission) + ft_guid = self.footprint + ft_params = self.get_mission_params_with_value(self.footprint_mission, + 'set_footprint', + 'footprint', + ft_guid) + return self.queue_mission_by_name(self.footprint_mission, ft_params) diff --git a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py index ea5ad7b..4e8462b 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py +++ b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py @@ -59,6 +59,7 @@ def __init__( rmf_config: rmf_easy.RobotConfiguration, mir_config: dict, conversions: dict, + rmf_missions: dict, fleet_handle, fleet_config, node: Node, @@ -78,7 +79,7 @@ def __init__( 'Content-Type': mir_config['user'], 'Authorization': mir_config['password'], } - self.api: MirAPI = MirAPI(prefix, headers, conversions) + self.api: MirAPI = MirAPI(prefix, headers, conversions, rmf_missions) status = self.api.status_get() while self.api.status_get() is None: @@ -413,8 +414,6 @@ def stop(self, activity): self.node.get_logger().info(f'[{self.name}] Stop requested from RMF!') self.request_stop(mission) self.mission = None - # Before replan, let's make sure the robot footprint is set correctly - self.api.update_footprint() @parallel def request_stop(self, mission: MissionHandle): From aceb40195873741770e180328366e03200d29a98 Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Wed, 10 Jan 2024 16:19:25 +0800 Subject: [PATCH 03/46] Set up plugin system for custom MiR perform actions Signed-off-by: Xiyu Oh --- configs/mir_config.yaml | 16 + .../fleet_adapter_mir/fleet_adapter_mir.py | 2 + .../fleet_adapter_mir/mir_action.py | 51 ++ .../fleet_adapter_mir/mir_api.py | 26 +- .../fleet_adapter_mir/rmf_cart_delivery.py | 428 +++++++++++++++ .../fleet_adapter_mir/rmf_cart_missions.json | 500 +++++++++++------- .../fleet_adapter_mir/robot_adapter_mir.py | 44 +- 7 files changed, 864 insertions(+), 203 deletions(-) create mode 100644 fleet_adapter_mir/fleet_adapter_mir/mir_action.py create mode 100644 fleet_adapter_mir/fleet_adapter_mir/rmf_cart_delivery.py diff --git a/configs/mir_config.yaml b/configs/mir_config.yaml index 6db6795..56f26e4 100644 --- a/configs/mir_config.yaml +++ b/configs/mir_config.yaml @@ -96,3 +96,19 @@ rmf_fleet: robot_state_update_frequency: 1 debug: False # whether to enable debug printouts from EasyFullControl + +plugins: + rmf_cart_delivery: + actions: ["delivery_pickup", "delivery_dropoff"] + missions: + dock_to_cart: "rmf_dock_to_cart" + pickup: "rmf_pickup_cart_top" + dropoff: "rmf_dropoff_cart_top" + exit_lot: "rmf_exit_lot" + update_footprint: "rmf_update_footprint" + footprints: + robot: "MiR100-200" + cart: "HostShelfCart800" + mission_json: "/path/to/mission/json" + search_timeout: 60 + pickup_dist_threshold: 3.0 # metres diff --git a/fleet_adapter_mir/fleet_adapter_mir/fleet_adapter_mir.py b/fleet_adapter_mir/fleet_adapter_mir/fleet_adapter_mir.py index 92a96b4..ebf082f 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/fleet_adapter_mir.py +++ b/fleet_adapter_mir/fleet_adapter_mir/fleet_adapter_mir.py @@ -142,6 +142,7 @@ def create_fleet(fleet_config, config_yaml, cmd_node, rmf_missions) -> FleetAdap conversions = config_yaml['conversions'] update_frequency = config_yaml['rmf_fleet']['robot_state_update_frequency'] debug = config_yaml['rmf_fleet']['debug'] + plugin_config = config_yaml.get('plugins') event_loop = asyncio.new_event_loop() @@ -156,6 +157,7 @@ def create_fleet(fleet_config, config_yaml, cmd_node, rmf_missions) -> FleetAdap rmf_missions, fleet_handle, fleet_config, + plugin_config, cmd_node, event_loop, debug, diff --git a/fleet_adapter_mir/fleet_adapter_mir/mir_action.py b/fleet_adapter_mir/fleet_adapter_mir/mir_action.py new file mode 100644 index 0000000..e6ec961 --- /dev/null +++ b/fleet_adapter_mir/fleet_adapter_mir/mir_action.py @@ -0,0 +1,51 @@ + +import json +from .mir_api import MirAPI, MirStatus, MiRStateCode + + +class MirAction: + def __init__( + self, + node, + name, + mir_api: MirAPI, + update_handle, + actions: list[str], + missions_json: str | None, + action_config: dict | None, + ): + self.node = node + self.name = name + self.api = mir_api + self.update_handle = update_handle + self.actions = actions + self.action_config = action_config + + if missions_json: + with open(missions_json, 'r') as g: + action_missions = json.load(g) + # Create these missions on the robot + self.api.create_missions(action_missions) + # Update mission actions stored in MirAPI + for mission, mission_data in self.api.known_missions.items(): + self.api.mission_actions[mission] = self.api.missions_mission_id_actions_get(mission_data['guid']) + + def update_action(self): + # To be populated in the plugins + pass + + def perform_action(self, category, description, execution): + # To be populated in the plugins + pass + + def cancel_current_task(self, cancel_success, cancel_fail, label): + current_task_id = self.update_handle.more().current_task_id() + self.node.get_logger().info(f'Cancel task requested for [{current_task_id}]') + def _on_cancel(result: bool): + if result: + self.node.get_logger().info(f'Found task [{current_task_id}], cancelling...') + cancel_success() + else: + self.node.get_logger().info(f'Failed to cancel task [{current_task_id}]') + cancel_fail() + self.update_handle.more().cancel_task(current_task_id, [label], lambda result: _on_cancel(result)) diff --git a/fleet_adapter_mir/fleet_adapter_mir/mir_api.py b/fleet_adapter_mir/fleet_adapter_mir/mir_api.py index da0e22f..5337662 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/mir_api.py +++ b/fleet_adapter_mir/fleet_adapter_mir/mir_api.py @@ -69,7 +69,6 @@ def __init__(self, prefix, headers, conversions, rmf_missions, timeout=10.0, deb self.mission_keys: dict = conversions['missions'] self.mission_actions: dict = {} self.mission_action_types: dict = {} - self.footprint_keys: dict = conversions['footprints'] self.attempt_connection() def attempt_connection(self): @@ -86,7 +85,7 @@ def attempt_connection(self): self.load_missions() self.load_maps() - self.create_rmf_missions() + self.create_missions(self.rmf_missions) move_key = 'move' assert move_key in self.mission_keys, ( @@ -122,11 +121,6 @@ def make_optional_mission(key): return target_mission self.localize_mission: str | None = make_optional_mission('localize') - self.dock_to_cart_mission: str | None = make_optional_mission('dock_to_cart') - self.pickup_mission: str | None = make_optional_mission('pickup') - self.dropoff_mission: str | None = make_optional_mission('dropoff') - self.exit_mission: str | None = make_optional_mission('exit_lot') - self.footprint_mission: str | None = make_optional_mission('check_footprint') self.go_to: str | None = make_optional_mission('go_to') if self.localize_mission is not None: @@ -161,10 +155,6 @@ def make_optional_mission(key): self.created_by_id = self.me_get()['guid'] - # Set footprints - self.footprint = self.footprints_guid_get(self.footprint_keys['robot']) - self.update_footprint() - def update_known_positions(self): self.known_positions = {} for pos in self.positions_get(): @@ -182,8 +172,8 @@ def update_known_positions(self): self.positions_guid_get(pos['guid']) ) - def create_rmf_missions(self): - if self.rmf_missions is None: + def create_missions(self, rmf_missions): + if rmf_missions is None: return # Retrieve the RMF group id if it already exists @@ -200,7 +190,7 @@ def create_rmf_missions(self): rmf_mission_group_id = mission_group['guid'] # Create RMF missions if they don't exist on the robot - for mission_name, mission_json in self.rmf_missions.items(): + for mission_name, mission_json in rmf_missions.items(): if mission_name not in self.known_missions: # Create the relevant mission on MiR mission = self.missions_post(mission_name, rmf_mission_group_id) @@ -875,11 +865,3 @@ def get_mission_params_with_value(self, mission_name: str, action_type: str, par mission_params = [p] return mission_params return mission_params - - def update_footprint(self): - ft_guid = self.footprint - ft_params = self.get_mission_params_with_value(self.footprint_mission, - 'set_footprint', - 'footprint', - ft_guid) - return self.queue_mission_by_name(self.footprint_mission, ft_params) diff --git a/fleet_adapter_mir/fleet_adapter_mir/rmf_cart_delivery.py b/fleet_adapter_mir/fleet_adapter_mir/rmf_cart_delivery.py new file mode 100644 index 0000000..520b12b --- /dev/null +++ b/fleet_adapter_mir/fleet_adapter_mir/rmf_cart_delivery.py @@ -0,0 +1,428 @@ +import math +from icecream import ic +import enum +from typing import Any +from dataclasses import dataclass +import requests +from urllib.error import HTTPError +from .mir_action import MirAction +from .mir_api import MirAPI, MirStatus, MiRStateCode + + +class PickupState(enum.IntEnum): + PICKUP_ALLOCATED = 0 + MOVE_REQUESTED = 1 + AT_PICKUP = 2 + DOCK_REQUESTED = 3 + DOCK_COMPLETED = 4 + PICKUP_REQUESTED = 5 + PICKUP_SUCCESS = 6 + WARNING_ALERT_PUBLISHED = 7 + TASK_CANCELLED = 8 + + +@dataclass +class Pickup: + state: PickupState + pickup_lots: list[str] # contains either a single pickup lot or list of pickup lots + execution: Any + mission_start_time: float + mission_queue_id: str + latching: bool + + +@dataclass +class Dropoff: + execution: Any + mission_queue_id: str + + +class CartDelivery(MirAction): + def __init__( + self, + retrieve_mir_coordinates, # callback + ): + self.known_positions = self.api.known_positions + + # Delivery related params + self.pickup: Pickup = None + self.dropoff: Dropoff = None + self.search_timeout = self.action_config.get('search_timeout', 60) # seconds + + # Useful robot adapter callbacks + self.retrieve_mir_coordinates = retrieve_mir_coordinates + + # Store the mission names to be used later + self.dock_to_cart_mission = self.action_config['missions']['dock_to_cart'] + self.pickup_mission = self.action_config['missions']['pickup'] + self.dropoff_mission = self.action_config['missions']['dropoff'] + self.exit_mission = self.action_config['missions']['exit_lot'] + self.footprint_mission = self.action_config['missions']['update_footprint'] + + # Initialize footprints + self.robot_footprint_guid = self.api.footprints_guid_get(self.action_config['footprints']['robot']) + self.cart_footprint_guid = self.api.footprints_guid_get(self.action_config['footprints']['cart']) + self.update_footprint(self.robot_footprint_guid) + + def update_action(self): + if self.pickup is not None: + if self.check_pickup(self.pickup): + self.pickup = None + if self.dropoff is not None: + if self.check_dropoff(self.dropoff): + self.dropoff = None + + def perform_action(self, category, description, execution): + if category == 'delivery_pickup': + pickup_lot = description.get('pickup_lot') + self.cart_pickup(execution, pickup_lot) + elif category == 'delivery_dropoff': + self.node.get_logger().info(f'Received dropoff request!') + self.dropoff = Dropoff(execution=execution, mission_queue_id=None) + + def cancel_task(self, label: str = None): + def _cancel_success(): + if self.pickup: + self.pickup.state = PickupState.TASK_CANCELLED + def _cancel_fail(): + pass + self.cancel_current_task(_cancel_success, _cancel_fail, label) + + def cart_pickup(self, execution, pickup_lot: str): + if self.pickup is not None: + # If there is an existing pickup, we'll replace it + if self.pickup.execution is not None and self.pickup.execution.okay(): + self.pickup.execution.finished() + self.pickup = None + + # Check if robot's latch is open + if self.is_latch_open(): + # Latch is open, unable to perform pickup + self.node.get_logger().info(f'Robot [{self.name}] latch is open, unable to perform pickup, cancelling task...') + self.cancel_task() + return + + self.node.get_logger().info(f'New pickup requested for robot [{self.name}]') + + # TODO(XY): Allow multiple pickups? + pickup_lots = [pickup_lot] + + self.pickup = Pickup( + state=PickupState.PICKUP_ALLOCATED, + pickup_lots=pickup_lots, + execution=execution, + mission_start_time=None, + mission_queue_id=None, + latching=False + ) + return + + def check_pickup(self, pickup: Pickup): + # If this is a PerformAction pickup, check that the action is underway and valid + if pickup.execution is not None and not pickup.execution.okay(): + self.node.get_logger().info(f'[{pickup.type}] action is killed/canceled.') + pickup.state = PickupState.TASK_CANCELLED + + # Start state machine check + self.node.get_logger().debug(f'PickupState: {pickup.state.name}') + match pickup.state: + case PickupState.PICKUP_ALLOCATED: + # Move to the first pickup place on the list + pickup_lot = pickup.pickup_lots[0] + self.node.get_logger().info(f'Requested to pickup cart at waypoint {pickup.state.name}') + if self.known_positions.get(pickup_lot) is None: + self.node.get_logger().info(f'Pickup Lot does not exist in MiR map, please resubmit.') + self.cancel_task() + pickup.state = PickupState.TASK_CANCELLED + return + + # Find the MiR coordinates of this pickup place + mir_pose = self.retrieve_mir_coordinates(pickup_lot) + pickup.mission_queue_id = self.api.navigate(mir_pose) + pickup.state = PickupState.MOVE_REQUESTED + + case PickupState.MOVE_REQUESTED: + # Make sure that there is an rmf_move mission issued + if pickup.mission_queue_id is None: + self.node.get_logger().info(f'Robot [{self.name}] is indicated to be at the MOVE_REQUESTED state but ' + f'no mission queue ID stored for this pickup mission! Returning to PICKUP_ALLOCATED state.') + pickup.state = PickupState.PICKUP_ALLOCATED + return + + # Robot has reached the pickup lot + pickup_lot = pickup.pickup_lots[0] + if self.api.mission_completed(pickup.mission_queue_id): + self.node.get_logger().info(f'Robot [{self.name}] has reached the pickup waypoint {pickup_lot}') + pickup.mission_queue_id = None + pickup.state = PickupState.AT_PICKUP + return + + # If the robot is relatively close to the pickup lot, we also consider it to be at pickup + # and allow the dock_to_cart mission to position the robot in front of the cart + pickup_pose = self.retrieve_mir_coordinates(pickup) + current_pose = self.api.status_get().state.position + if self.dist(pickup_pose, current_pose) < self.action_config['pickup_dist_threshold']: + # Delete the ongoing mission + self.api.mission_queue_id_delete(pickup.mission_queue_id) + self.node.get_logger().info(f'Robot [{self.name}] is sufficiently near to the pickup waypoint {pickup_lot} for docking') + pickup.mission_queue_id = None + pickup.state = PickupState.AT_PICKUP + + case PickupState.AT_PICKUP: + # Send rmf_dock_to_cart mission + assert self.dock_to_cart_mission is not None + current_wp_name = pickup.pickup_lots[0] + cart_marker_guid = self.api.known_positions[current_wp_name]['guid'] + mission_params = self.api.get_mission_params_with_value(self.dock_to_cart_mission, + 'docking', + 'cart_marker', + cart_marker_guid) + self.update_footprint(self.robot_footprint_guid) + mission_queue_id = self.api.queue_mission_by_name(self.dock_to_cart_mission, mission_params) + if not mission_queue_id: + error_str = f'Mission {self.dock_to_cart_mission} not supported, ignoring' + self.node.get_logger().error(error_str) + return + pickup.mission_queue_id = mission_queue_id + pickup.state = PickupState.DOCK_REQUESTED + self.node.get_logger().info(f'Dock to cart mission requested with mission queue id {mission_queue_id}') + + case PickupState.DOCK_REQUESTED: + # Make sure that there is an rmf_dock_to_cart mission issued + if pickup.mission_queue_id is None: + self.node.get_logger().info(f'Robot [{self.name}] is indicated to be at the DOCK_REQUESTED state but ' + f'no mission queue ID stored for this docking mission! Returning to AT_PICKUP state.') + pickup.state = PickupState.AT_PICKUP + return + # Mission completed, move onto the next state + if self.api.mission_completed(pickup.mission_queue_id): + self.node.get_logger().info(f'Robot [{self.name}] dock to cart mission {pickup.mission_queue_id} completed or timed out.') + pickup.mission_queue_id = None + pickup.mission_start_time = None + pickup.state = PickupState.DOCK_COMPLETED + return + # Mission not yet completed, we check the timeout status to decide if we need to publish any alert + if pickup.mission_start_time is None: + pickup.mission_start_time = self.node.get_clock().now().nanoseconds / 1e9 + now = self.node.get_clock().now().nanoseconds / 1e9 + seconds_passed = now - pickup.mission_start_time + # Publish update every 10 seconds just to monitor + if round(seconds_passed)%10 == 0: + self.node.get_logger().info(f'{round(seconds_passed)} seconds have passed since pickup mission requested.') + # Mission timeout, cart not found + if seconds_passed > self.search_timeout: + # Delete mission from mir first + self.api.mission_queue_id_delete(pickup.mission_queue_id) + # Regardless of whether the robot completed docking properly, we move to the next state to check + self.node.get_logger().info(f'Robot [{self.name}] dock to cart mission {pickup.mission_queue_id} timed out! ' + f'Configured search timeout is {self.search_timeout} seconds.') + pickup.state = PickupState.DOCK_COMPLETED + return + + case PickupState.DOCK_COMPLETED: + if pickup.mission_start_time is not None: + pickup.mission_start_time = None + # Check if robot docked under the correct cart + cart_check = self.is_correct_cart() + if cart_check: + # If cart is correct, send pickup mission + assert self.pickup_mission is not None + mission_queue_id = self.api.queue_mission_by_name(self.pickup_mission) + if not mission_queue_id: + error_str = f'Mission {self.pickup_mission} not supported, ignoring' + self.node.get_logger().error(error_str) + return + pickup.mission_queue_id = mission_queue_id + pickup.mission_start_time = self.node.get_clock().now().nanoseconds / 1e9 + pickup.latching = True + self.node.get_logger().info(f'Robot [{self.name}] found the correct cart, pickup mission requested with mission queue id {mission_queue_id}') + pickup.state = PickupState.PICKUP_REQUESTED + elif cart_check is None: + # If cart is missing, cancel this task + self.node.get_logger().info(f'Robot [{self.name}] was unable to dock under any carts, please check that cart is present. Cancelling task.') + pickup.state = PickupState.TASK_CANCELLED + else: + # If cart is wrong, cancel this task also but after we exit from the lot + self.node.get_logger().info(f'Robot [{self.name}] found the wrong cart, exiting lot and cancelling task.') + self.exit_lot() + pickup.state = PickupState.TASK_CANCELLED + + case PickupState.PICKUP_REQUESTED: + if self.is_latch_open(): + # Latch successfully opened, indicate pickup as success + pickup.state = PickupState.PICKUP_SUCCESS + pickup.latching = False + + case PickupState.PICKUP_SUCCESS: + # Correct ID, we can end the delivery now + self.node.get_logger().info(f'Robot [{self.name}] successfully received cart, exiting lot with cart and ending mission') + self.exit_lot() + if pickup.execution is not None: + pickup.execution.finished() + return True + + case PickupState.TASK_CANCELLED: + self.node.get_logger().info(f'Robot [{self.name}] is in pickup cancelled state.') + # If some MiR mission is in progress, we abort it unless it is latching + if pickup.mission_queue_id is not None and not self.api.mission_completed(pickup.mission_queue_id): + if pickup.latching: + self.node.get_logger().info(f'Robot [{self.name}] is performing latching, cancelling task after this action is complete.') + return False + self.api.mission_queue_id_delete(pickup.mission_queue_id) + # Clear any errors + self.api.clear_error() + self.api.status_put(state_id=MiRStateCode.READY) + self.release_cart() + # Mark pickup session as completed + return True + + return False + + def check_dropoff(self, dropoff: Dropoff): + # Check if action is underway or cancelled + if dropoff.execution is not None and not dropoff.execution.okay(): + self.node.get_logger().info(f'Dropoff action is killed/canceled') + + # If cart release is in progress, we let it finish first + if dropoff.mission_queue_id is not None and not self.api.mission_completed(dropoff.mission_queue_id): + return False + + # Task is cancelled and cart is done dropping off/mission is not yet queued anyway, + # we can mark it as completed at this point + self.api.clear_error() + self.api.status_put(state_id=MiRStateCode.READY) + # Mark dropoff session as completed + return True + + # No mission queued yet + if dropoff.mission_queue_id is None: + assert self.dropoff_mission is not None + mission_queue_id = self.api.queue_mission_by_name(self.dropoff_mission) + if not mission_queue_id: + error_str = f'Mission {self.dropoff_mission} not supported, ignoring' + self.node.get_logger().error(error_str) + return True + self.node.get_logger().info(f'Mission {self.dropoff_mission} added to queue.') + dropoff.mission_queue_id = mission_queue_id + self.node.get_logger().info(f'Dropoff mission requested with mission queue id {mission_queue_id}') + + # Mission queued, check completion + else: + if self.api.mission_completed(dropoff.mission_queue_id): + self.node.get_logger().info(f'Dropoff mission completed!') + if dropoff.execution is not None: + dropoff.execution.finished() + return True + else: + self.node.get_logger().info(f'Dropoff mission in progress...') + return + + def is_latch_open(self): + # Return True if latch is open, else False + # ------------------------ + # IMPLEMENT YOUR CODE HERE + # ------------------------ + return False + + def is_under_cart(self): + # Return True if robot is under any carts, else False + # ------------------------ + # IMPLEMENT YOUR CODE HERE + # ------------------------ + return False + + def is_correct_cart(self): + # Return True if cart is correct, False if cart is wrong, None if no cart + # ------------------------ + # IMPLEMENT YOUR CODE HERE + # ------------------------ + return None + + def exit_lot(self): + if not self.api.connected: + return None + # Set footprint to robot footprint before exiting lot + self.update_footprint(self.robot_footprint_guid) + return self.api.queue_mission_by_name(self.exit_mission) + + def release_cart(self): + # If robot latch is open, close it + if self.is_latch_open(): + self.node.get_logger().info(f'Robot [{self.name}] detected to have latch open, dropping off cart...') + self.dropoff = Dropoff( + execution=None, + mission_queue_id=None) + # Dropoff mission will take care of the lot exit, so we can return here + return + # If robot is under a cart, exit lot + if self.is_under_cart(): + self.node.get_logger().info(f'Cart detected above robot [{self.name}] during a release call, exiting lot...') + self.exit_lot() + + def update_footprint(self, ft_guid: str): + ft_params = self.api.get_mission_params_with_value(self.footprint_mission, + 'set_footprint', + 'footprint', + ft_guid) + return self.api.queue_mission_by_name(self.footprint_mission, ft_params) + + def dist(self, A, B): + assert(len(A) > 1) + assert(len(B) > 1) + return math.sqrt((A[0] - B[0])**2 + (A[1] - B[1])**2) + + + # ------------------------------------------------------------------------------------------------------------------ + # MIR API FOR CART RELATED MISSIONS + # ------------------------------------------------------------------------------------------------------------------ + + def register_get(self, register: int): + if not self.api.connected: + return None + try: + response = requests.get(self.api.prefix + f'registers/{register}', headers = self.api.headers, timeout = self.api.timeout) + if self.api.debug: + print(f"Response: {response.headers}") + # Response value is string, return integer of value + return int(response.json().get('value', 0)) + except HTTPError as http_err: + print(f"HTTP error: {http_err}") + return None + except Exception as err: + print(f"Other error: {err}") + return None + + def io_module_guid_status_get(self, io_guid: str): + if not self.api.connected: + return None + if io_guid is None: + return None + try: + response = requests.get(self.api.prefix + f'io_modules/{io_guid}/status', headers = self.api.headers, timeout = self.api.timeout) + if self.api.debug: + print(f"Response: {response.headers}") + if 'input_state' not in response.json(): + return None + return response.json()['input_state'] + except HTTPError as http_err: + print(f"HTTP error: {http_err}") + return None + except Exception as err: + print(f"Other error: {err}") + return None + + def io_modules_get(self): + if not self.api.connected: + return None + try: + response = requests.get(self.api.prefix + f'io_modules', headers = self.api.headers, timeout = self.api.timeout) + if self.api.debug: + print(f"Response: {response.headers}") + # Response value is string, return integer of value + return response.json() + except HTTPError as http_err: + print(f"HTTP error: {http_err}") + return None + except Exception as err: + print(f"Other error: {err}") + return None diff --git a/fleet_adapter_mir/fleet_adapter_mir/rmf_cart_missions.json b/fleet_adapter_mir/fleet_adapter_mir/rmf_cart_missions.json index b7d49ba..86ce67c 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/rmf_cart_missions.json +++ b/fleet_adapter_mir/fleet_adapter_mir/rmf_cart_missions.json @@ -4,28 +4,17 @@ "priority": 1, "parameters": [ { - "value": "mirconst-guid-0000-0001-footprint000", - "input_name": null, - "id": "footprint" - } - ], - "action_type": "set_footprint" - }, - { - "priority": 2, - "parameters": [ - { - "value": -1.0, + "value": -1, "input_name": null, "id": "x" }, { - "value": 0.0, + "value": 0, "input_name": null, "id": "y" }, { - "value": 0.0, + "value": 0, "input_name": null, "id": "orientation" }, @@ -46,90 +35,11 @@ } ], "action_type": "relative_move" - }, - { - "priority": 3, - "parameters": [ - { - "value": "plc_register", - "input_name": null, - "id": "compare" - }, - { - "value": "e2fc134a-56bb-11ee-a409-00012998f454", - "input_name": null, - "id": "module" - }, - { - "value": "0", - "input_name": null, - "id": "io_port" - }, - { - "value": "8", - "input_name": null, - "id": "register" - }, - { - "value": "==", - "input_name": null, - "id": "operator" - }, - { - "value": 1.0, - "input_name": null, - "id": "value" - }, - { - "value": "", - "input_name": null, - "id": "true" - }, - { - "value": "", - "input_name": null, - "id": "false" - } - ], - "action_type": "if" - }, - { - "priority": 4, - "parameters": [ - { - "value": "f65abbec-ea4e-11ed-af33-00012983ef2c", - "input_name": null, - "id": "footprint" - } - ], - "action_type": "set_footprint" - }, - { - "priority": 5, - "parameters": [ - { - "value": "mirconst-guid-0000-0001-footprint000", - "input_name": null, - "id": "footprint" - } - ], - "action_type": "set_footprint" } ], "rmf_dock_to_cart": [ { "priority": 1, - "parameters": [ - { - "value": "mirconst-guid-0000-0001-footprint000", - "input_name": null, - "id": "footprint" - } - ], - "action_type": "set_footprint" - }, - { - "priority": 2, "parameters": [ { "value": null, @@ -155,7 +65,7 @@ "action_type": "docking" } ], - "rmf_dropoff_cart": [ + "rmf_dropoff_cart_side": [ { "priority": 2, "parameters": [ @@ -215,32 +125,27 @@ "action_type": "load_mission" } ], - "rmf_follow_line": [ + "rmf_dropoff_cart_top": [ { "priority": 1, - "parameters": [], - "action_type": "adjust_localization" - }, - { - "priority": 2, "parameters": [ { - "value": "plc_register", + "value": "io_module", "input_name": null, "id": "compare" }, { - "value": "e2fc134a-56bb-11ee-a409-00012998f454", + "value": "mirconst-guid-0000-0001-internalIO00", "input_name": null, "id": "module" }, { - "value": "0", + "value": 3, "input_name": null, "id": "io_port" }, { - "value": "8", + "value": "1", "input_name": null, "id": "register" }, @@ -250,7 +155,7 @@ "id": "operator" }, { - "value": 1.0, + "value": 0, "input_name": null, "id": "value" }, @@ -267,22 +172,58 @@ ], "action_type": "if" }, + { + "priority": 2, + "parameters": [ + { + "value": "No shelf is lifted according to IO input 3", + "input_name": null, + "id": "message" + } + ], + "action_type": "throw_error" + }, { "priority": 3, "parameters": [ { - "value": "f65abbec-ea4e-11ed-af33-00012983ef2c", + "value": null, "input_name": null, - "id": "footprint" + "id": "sound" + }, + { + "value": null, + "input_name": null, + "id": "volume" + }, + { + "value": "muted", + "input_name": null, + "id": "front" + }, + { + "value": "muted", + "input_name": null, + "id": "rear" + }, + { + "value": "muted", + "input_name": null, + "id": "sides" + }, + { + "value": "", + "input_name": null, + "id": "content" } ], - "action_type": "set_footprint" + "action_type": "reduce_protective_fields" }, { - "priority": 4, + "priority": 8, "parameters": [ { - "value": "mirconst-guid-0000-0001-footprint000", + "value": "mirconst-guid-0000-0001-footprint007", "input_name": null, "id": "footprint" } @@ -290,122 +231,148 @@ "action_type": "set_footprint" }, { - "priority": 5, + "priority": 9, "parameters": [ { - "value": "to be replaced with a value guid in the fleet adapter", - "input_name": "start_waypoint", - "id": "position" + "value": -1, + "input_name": null, + "id": "x" }, { - "value": 10, + "value": 0, "input_name": null, - "id": "retries" + "id": "y" }, { - "value": 0.2, + "value": 0, "input_name": null, - "id": "distance_threshold" - } - ], - "action_type": "move" - }, - { - "priority": 6, - "parameters": [ + "id": "orientation" + }, { - "value": "plc_register", + "value": 0.25, "input_name": null, - "id": "compare" + "id": "max_linear_speed" }, { - "value": "e2fc134a-56bb-11ee-a409-00012998f454", + "value": 0.25, "input_name": null, - "id": "module" + "id": "max_angular_speed" }, { - "value": "0", + "value": true, "input_name": null, - "id": "io_port" - }, + "id": "collision_detection" + } + ], + "action_type": "relative_move" + }, + { + "priority": 10, + "parameters": [ { - "value": "8", + "value": "577eaace-be75-11ed-a404-0001297c2278", "input_name": null, - "id": "register" - }, + "id": "footprint" + } + ], + "action_type": "set_footprint" + }, + { + "priority": 4, + "parameters": [ { - "value": "==", + "value": "mirconst-guid-0000-0001-internalIO00", "input_name": null, - "id": "operator" + "id": "module" }, { - "value": 1.0, + "value": 3, "input_name": null, - "id": "value" + "id": "port" }, { - "value": "", + "value": "off", "input_name": null, - "id": "true" + "id": "operation" }, { - "value": "", + "value": null, "input_name": null, - "id": "false" + "id": "timeout" } ], - "action_type": "if" + "action_type": "set_io" }, { - "priority": 7, + "priority": 5, "parameters": [ { - "value": "454e65f9-06b9-11ee-acbc-00012983ef2c", + "value": "00:00:01.000000", "input_name": null, - "id": "footprint" + "id": "time" } ], - "action_type": "set_footprint" + "action_type": "wait" }, { - "priority": 8, + "priority": 6, "parameters": [ { - "value": "mirconst-guid-0000-0001-footprint000", + "value": "mirconst-guid-0000-0001-internalIO00", "input_name": null, - "id": "footprint" + "id": "module" + }, + { + "value": 2, + "input_name": null, + "id": "port" + }, + { + "value": "on", + "input_name": null, + "id": "operation" + }, + { + "value": "00:00:10.000000", + "input_name": null, + "id": "timeout" + }, + { + "value": "", + "input_name": null, + "id": "content" } ], - "action_type": "set_footprint" + "action_type": "set_reset_io" }, { - "priority": 9, + "priority": 7, "parameters": [ { - "value": "to be replaced with a value guid in the fleet adapter", - "input_name": "end_waypoint", - "id": "position" + "value": "mirconst-guid-0000-0001-internalIO00", + "input_name": null, + "id": "module" }, { - "value": 10, + "value": 2, "input_name": null, - "id": "retries" + "id": "port" + }, + { + "value": "on", + "input_name": null, + "id": "value" }, { - "value": 0.2, + "value": "00:00:10.000000", "input_name": null, - "id": "distance_threshold" + "id": "timeout" } ], - "action_type": "move" - }, - { - "priority": 10, - "parameters": [], - "action_type": "adjust_localization" + "action_type": "wait_for_io" } ], - "rmf_pickup_cart": [ + "rmf_pickup_cart_side": [ { "priority": 1, "parameters": [ @@ -486,27 +453,110 @@ "action_type": "set_footprint" } ], - "rmf_update_footprint": [ + "rmf_pickup_cart_top": [ + { + "priority": 7, + "parameters": [ + { + "value": "mirconst-guid-0000-0001-footprint007", + "input_name": null, + "id": "footprint" + } + ], + "action_type": "set_footprint" + }, + { + "priority": 8, + "parameters": [ + { + "value": null, + "input_name": null, + "id": "sound" + }, + { + "value": null, + "input_name": null, + "id": "volume" + }, + { + "value": "muted", + "input_name": null, + "id": "front" + }, + { + "value": "muted", + "input_name": null, + "id": "rear" + }, + { + "value": "muted", + "input_name": null, + "id": "sides" + }, + { + "value": "", + "input_name": null, + "id": "content" + } + ], + "action_type": "reduce_protective_fields" + }, + { + "priority": 9, + "parameters": [ + { + "value": 0, + "input_name": null, + "id": "x" + }, + { + "value": 0, + "input_name": null, + "id": "y" + }, + { + "value": 0, + "input_name": null, + "id": "orientation" + }, + { + "value": 0.25, + "input_name": null, + "id": "max_linear_speed" + }, + { + "value": 0.25, + "input_name": null, + "id": "max_angular_speed" + }, + { + "value": true, + "input_name": null, + "id": "collision_detection" + } + ], + "action_type": "relative_move" + }, { "priority": 1, "parameters": [ { - "value": "plc_register", + "value": "io_module", "input_name": null, "id": "compare" }, { - "value": "e2fc134a-56bb-11ee-a409-00012998f454", + "value": "mirconst-guid-0000-0001-internalIO00", "input_name": null, "id": "module" }, { - "value": "0", + "value": 2, "input_name": null, "id": "io_port" }, { - "value": "8", + "value": "1", "input_name": null, "id": "register" }, @@ -516,7 +566,7 @@ "id": "operator" }, { - "value": 1.0, + "value": 0, "input_name": null, "id": "value" }, @@ -537,19 +587,115 @@ "priority": 2, "parameters": [ { - "value": "f65abbec-ea4e-11ed-af33-00012983ef2c", + "value": "A shelf is already lifted according to IO input 2", "input_name": null, - "id": "footprint" + "id": "message" } ], - "action_type": "set_footprint" + "action_type": "throw_error" }, { "priority": 3, "parameters": [ { - "value": "mirconst-guid-0000-0001-footprint000", + "value": "mirconst-guid-0000-0001-internalIO00", + "input_name": null, + "id": "module" + }, + { + "value": 2, + "input_name": null, + "id": "port" + }, + { + "value": "off", + "input_name": null, + "id": "operation" + }, + { + "value": null, + "input_name": null, + "id": "timeout" + } + ], + "action_type": "set_io" + }, + { + "priority": 4, + "parameters": [ + { + "value": "00:00:01.000000", + "input_name": null, + "id": "time" + } + ], + "action_type": "wait" + }, + { + "priority": 5, + "parameters": [ + { + "value": "mirconst-guid-0000-0001-internalIO00", "input_name": null, + "id": "module" + }, + { + "value": 3, + "input_name": null, + "id": "port" + }, + { + "value": "on", + "input_name": null, + "id": "operation" + }, + { + "value": "00:00:10.000000", + "input_name": null, + "id": "timeout" + }, + { + "value": "", + "input_name": null, + "id": "content" + } + ], + "action_type": "set_reset_io" + }, + { + "priority": 6, + "parameters": [ + { + "value": "mirconst-guid-0000-0001-internalIO00", + "input_name": null, + "id": "module" + }, + { + "value": 3, + "input_name": null, + "id": "port" + }, + { + "value": "on", + "input_name": null, + "id": "value" + }, + { + "value": "00:00:10.000000", + "input_name": null, + "id": "timeout" + } + ], + "action_type": "wait_for_io" + } + ], + "rmf_update_footprint": [ + { + "priority": 1, + "parameters": [ + { + "value": "mirconst-guid-0000-0001-footprint000", + "input_name": "footprint", "id": "footprint" } ], diff --git a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py index 4e8462b..80ee1e2 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py +++ b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py @@ -1,8 +1,13 @@ import math +import numpy as np +from icecream import ic +import enum +import copy import time from typing import Any from dataclasses import dataclass import json +import datetime from rmf_adapter.robot_update_handle import Tier import rmf_adapter.easy_full_control as rmf_easy import rclpy @@ -11,6 +16,9 @@ from .mir_api import MirAPI, MirStatus, MiRStateCode from threading import Lock +# Import plugins +from .rmf_cart_delivery import CartDelivery + # Parallel processing solution derived from # https://stackoverflow.com/a/59385935 @@ -58,10 +66,12 @@ def __init__( name: str, rmf_config: rmf_easy.RobotConfiguration, mir_config: dict, + # pickup_config: dict, conversions: dict, rmf_missions: dict, fleet_handle, fleet_config, + plugin_config: dict | None, node: Node, event_loop, debug=False @@ -109,6 +119,19 @@ def __init__( self.nav_issue_ticket = None # We should only have one issue ticket at a time to manage unsuccessful missions self.requested_replan = False self.replan_counts = 0 + self.plugins = {} + # Available plugins: + if 'rmf_cart_delivery' in plugin_config: + self.plugins['rmf_cart_delivery'] = CartDelivery( + node=node, + name=name, + mir_api=self.api, + update_handle=self.update_handle, + actions=plugin_config['rmf_cart_delivery']['actions'], + missions_json=plugin_config['rmf_cart_delivery']['missions_json'], + action_config=plugin_config['rmf_cart_delivery'], + retrieve_mir_coordinates=self.retrieve_mir_coordinates) + # To be added on with other plugins self.fleet_handle = fleet_handle self.update_handle = fleet_handle.add_robot( @@ -166,6 +189,10 @@ def request_update(self): if mission is not None and mission.done: self.update_rmf_finished(mission) + # PerformAction related checks + for plugin in self.plugins.values(): + plugin.update_action() + # Clear error on updates if status is not None and 'errors' in status.response and len(status.response['errors']) > 0: self.api.clear_error() @@ -457,12 +484,21 @@ def request_localize(self, estimate, mission: MissionHandle): mission.set_mission_queue_id(mission_queue_id) def perform_action(self, category, description, execution): - task_id = self.update_handle.more().current_task_id() - # ----------------------------------------------------- - # INSERT PERFORM ACTION LOGIC HERE - # ----------------------------------------------------- + for plugin in self.plugins.values(): + if category in plugin.actions: + action = self.actions[category] + action.perform_action(category, description, execution) + return raise NotImplementedError + def retrieve_mir_coordinates(self, waypoint_name: str): + transform = self.fleet_config.transformations_to_robot_coordinates + transform_current_map = transform.get(self.current_map) + rmf_pose = self.fleet_config.graph.find_waypoint(waypoint_name).location + new_rmf_pose = np.array([rmf_pose[0], rmf_pose[1], 0.0]) + mir_pose = transform_current_map.apply(new_rmf_pose) + return mir_pose + def dist(self, A, B): assert(len(A) > 1) assert(len(B) > 1) From 6e2dd989cbdf775bff9a03b1ef25c772fff61d96 Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Thu, 11 Jan 2024 12:22:56 +0800 Subject: [PATCH 04/46] Cart delivery plugin fixes Signed-off-by: Xiyu Oh --- configs/mir_config.yaml | 11 +++----- .../fleet_adapter_mir/__init__.py | 2 -- .../fleet_adapter_mir/rmf_cart_delivery.py | 11 +++++++- .../fleet_adapter_mir/robot_adapter_mir.py | 27 +++++++------------ .../rmf_cart_missions.json | 0 .../rmf_missions.json | 0 6 files changed, 23 insertions(+), 28 deletions(-) rename {fleet_adapter_mir/fleet_adapter_mir => missions}/rmf_cart_missions.json (100%) rename {fleet_adapter_mir/fleet_adapter_mir => missions}/rmf_missions.json (100%) diff --git a/configs/mir_config.yaml b/configs/mir_config.yaml index 56f26e4..1af76aa 100644 --- a/configs/mir_config.yaml +++ b/configs/mir_config.yaml @@ -36,12 +36,7 @@ conversions: move: "rmf_move" # This mission must be predefined dock_and_charge: "rmf_dock_and_charge" # This mission must be predefined localize: "rmf_localize" - # dock_to_cart: "rmf_dock_to_cart" - # pickup: "rmf_pickup_cart" - # dropoff: "rmf_dropoff_cart" - # exit_lot: "rmf_exit_lot" go_to: "rmf_move_to_position" - # check_footprint: "rmf_update_footprint" lift_positions: lift_1: # Name of lift matching the navigation graph @@ -83,7 +78,7 @@ rmf_fleet: delivery: True clean: False finishing_request: "charge" # [park, charge, nothing] - actions: [] + actions: ["delivery_pickup", "delivery_dropoff", "dropoff_if_carrying_cart"] robots: mir_1: charger: "Charger_1" @@ -99,7 +94,7 @@ rmf_fleet: plugins: rmf_cart_delivery: - actions: ["delivery_pickup", "delivery_dropoff"] + actions: ["delivery_pickup", "delivery_dropoff", "dropoff_if_carrying_cart"] missions: dock_to_cart: "rmf_dock_to_cart" pickup: "rmf_pickup_cart_top" @@ -109,6 +104,6 @@ plugins: footprints: robot: "MiR100-200" cart: "HostShelfCart800" - mission_json: "/path/to/mission/json" + missions_json: "/home/some_user/mir_ws/src/fleet_adapter_mir/missions/rmf_cart_missions.json" search_timeout: 60 pickup_dist_threshold: 3.0 # metres diff --git a/fleet_adapter_mir/fleet_adapter_mir/__init__.py b/fleet_adapter_mir/fleet_adapter_mir/__init__.py index de62d2a..e69de29 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/__init__.py +++ b/fleet_adapter_mir/fleet_adapter_mir/__init__.py @@ -1,2 +0,0 @@ -from .fleet_adapter_mir import * -from .MiRClientAPI import * diff --git a/fleet_adapter_mir/fleet_adapter_mir/rmf_cart_delivery.py b/fleet_adapter_mir/fleet_adapter_mir/rmf_cart_delivery.py index 520b12b..4cbf4df 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/rmf_cart_delivery.py +++ b/fleet_adapter_mir/fleet_adapter_mir/rmf_cart_delivery.py @@ -40,8 +40,17 @@ class Dropoff: class CartDelivery(MirAction): def __init__( self, + node, + name, + mir_api, + update_handle, + actions, + missions_json, + action_config, retrieve_mir_coordinates, # callback ): + MirAction.__init__(self, node, name, mir_api, update_handle, actions, + missions_json, action_config) self.known_positions = self.api.known_positions # Delivery related params @@ -159,7 +168,7 @@ def check_pickup(self, pickup: Pickup): # If the robot is relatively close to the pickup lot, we also consider it to be at pickup # and allow the dock_to_cart mission to position the robot in front of the cart - pickup_pose = self.retrieve_mir_coordinates(pickup) + pickup_pose = self.retrieve_mir_coordinates(pickup_lot) current_pose = self.api.status_get().state.position if self.dist(pickup_pose, current_pose) < self.action_config['pickup_dist_threshold']: # Delete the ongoing mission diff --git a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py index 80ee1e2..db7948d 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py +++ b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py @@ -119,6 +119,15 @@ def __init__( self.nav_issue_ticket = None # We should only have one issue ticket at a time to manage unsuccessful missions self.requested_replan = False self.replan_counts = 0 + + self.fleet_handle = fleet_handle + self.update_handle = fleet_handle.add_robot( + self.name, + status.state, + rmf_config, + self._make_callbacks(), + ) + self.plugins = {} # Available plugins: if 'rmf_cart_delivery' in plugin_config: @@ -133,14 +142,6 @@ def __init__( retrieve_mir_coordinates=self.retrieve_mir_coordinates) # To be added on with other plugins - self.fleet_handle = fleet_handle - self.update_handle = fleet_handle.add_robot( - self.name, - status.state, - rmf_config, - self._make_callbacks(), - ) - @property def activity(self): # Move the mission reference into a separate variable just in case @@ -300,13 +301,6 @@ def _make_callbacks(self): return callbacks def navigate(self, destination, execution): - # If this is a cancellation behavior command, we check if we're meant to ignore it. - if self.ignore_action: - self.node.get_logger().info(f'Ignoring navigation command, ignore action flag is ' - f'raised after checking latch.') - execution.finished() - return - # If the nav command coming in is to bring the robot to a charger, but the robot is # already charging at the same charger, we ignore this nav command status = self.last_known_status @@ -486,8 +480,7 @@ def request_localize(self, estimate, mission: MissionHandle): def perform_action(self, category, description, execution): for plugin in self.plugins.values(): if category in plugin.actions: - action = self.actions[category] - action.perform_action(category, description, execution) + plugin.perform_action(category, description, execution) return raise NotImplementedError diff --git a/fleet_adapter_mir/fleet_adapter_mir/rmf_cart_missions.json b/missions/rmf_cart_missions.json similarity index 100% rename from fleet_adapter_mir/fleet_adapter_mir/rmf_cart_missions.json rename to missions/rmf_cart_missions.json diff --git a/fleet_adapter_mir/fleet_adapter_mir/rmf_missions.json b/missions/rmf_missions.json similarity index 100% rename from fleet_adapter_mir/fleet_adapter_mir/rmf_missions.json rename to missions/rmf_missions.json From 47db7f19a4aa3968eb04fadc7b1378571d749068 Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Fri, 12 Jan 2024 11:03:20 +0800 Subject: [PATCH 05/46] Add cart pickup task script Signed-off-by: Xiyu Oh --- .../fleet_adapter_mir/rmf_cart_delivery.py | 16 +- fleet_adapter_mir_tasks/LICENSE | 202 ++++++++++++++++++ .../fleet_adapter_mir_tasks/__init__.py | 0 .../dispatch_pickup.py | 201 +++++++++++++++++ fleet_adapter_mir_tasks/package.xml | 18 ++ .../resource/fleet_adapter_mir_tasks | 0 fleet_adapter_mir_tasks/setup.cfg | 4 + fleet_adapter_mir_tasks/setup.py | 25 +++ 8 files changed, 461 insertions(+), 5 deletions(-) create mode 100644 fleet_adapter_mir_tasks/LICENSE create mode 100644 fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/__init__.py create mode 100644 fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_pickup.py create mode 100644 fleet_adapter_mir_tasks/package.xml create mode 100644 fleet_adapter_mir_tasks/resource/fleet_adapter_mir_tasks create mode 100644 fleet_adapter_mir_tasks/setup.cfg create mode 100644 fleet_adapter_mir_tasks/setup.py diff --git a/fleet_adapter_mir/fleet_adapter_mir/rmf_cart_delivery.py b/fleet_adapter_mir/fleet_adapter_mir/rmf_cart_delivery.py index 4cbf4df..078d1a6 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/rmf_cart_delivery.py +++ b/fleet_adapter_mir/fleet_adapter_mir/rmf_cart_delivery.py @@ -25,6 +25,7 @@ class PickupState(enum.IntEnum): class Pickup: state: PickupState pickup_lots: list[str] # contains either a single pickup lot or list of pickup lots + cart_id: str execution: Any mission_start_time: float mission_queue_id: str @@ -84,7 +85,8 @@ def update_action(self): def perform_action(self, category, description, execution): if category == 'delivery_pickup': pickup_lot = description.get('pickup_lot') - self.cart_pickup(execution, pickup_lot) + cart_id = description.get('cart_id') + self.cart_pickup(execution, pickup_lot, cart_id) elif category == 'delivery_dropoff': self.node.get_logger().info(f'Received dropoff request!') self.dropoff = Dropoff(execution=execution, mission_queue_id=None) @@ -97,7 +99,7 @@ def _cancel_fail(): pass self.cancel_current_task(_cancel_success, _cancel_fail, label) - def cart_pickup(self, execution, pickup_lot: str): + def cart_pickup(self, execution, pickup_lot: str, cart_id: str): if self.pickup is not None: # If there is an existing pickup, we'll replace it if self.pickup.execution is not None and self.pickup.execution.okay(): @@ -119,6 +121,7 @@ def cart_pickup(self, execution, pickup_lot: str): self.pickup = Pickup( state=PickupState.PICKUP_ALLOCATED, pickup_lots=pickup_lots, + cart_id=cart_id, execution=execution, mission_start_time=None, mission_queue_id=None, @@ -232,7 +235,7 @@ def check_pickup(self, pickup: Pickup): if pickup.mission_start_time is not None: pickup.mission_start_time = None # Check if robot docked under the correct cart - cart_check = self.is_correct_cart() + cart_check = self.is_correct_cart(pickup.cart_id) if cart_check: # If cart is correct, send pickup mission assert self.pickup_mission is not None @@ -327,6 +330,7 @@ def check_dropoff(self, dropoff: Dropoff): return def is_latch_open(self): + # Checks if the robot's latch is open and carrying a cart # Return True if latch is open, else False # ------------------------ # IMPLEMENT YOUR CODE HERE @@ -334,14 +338,16 @@ def is_latch_open(self): return False def is_under_cart(self): + # Checks if the robot is docked under a cart # Return True if robot is under any carts, else False # ------------------------ # IMPLEMENT YOUR CODE HERE # ------------------------ return False - def is_correct_cart(self): - # Return True if cart is correct, False if cart is wrong, None if no cart + def is_correct_cart(self, cart_id: str): + # Checks if the detected cart identifier matches the target cart_id + # Return True if cart is correct, False if cart is wrong, None if no cart detected # ------------------------ # IMPLEMENT YOUR CODE HERE # ------------------------ diff --git a/fleet_adapter_mir_tasks/LICENSE b/fleet_adapter_mir_tasks/LICENSE new file mode 100644 index 0000000..d645695 --- /dev/null +++ b/fleet_adapter_mir_tasks/LICENSE @@ -0,0 +1,202 @@ + + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + APPENDIX: How to apply the Apache License to your work. + + To apply the Apache License to your work, attach the following + boilerplate notice, with the fields enclosed by brackets "[]" + replaced with your own identifying information. (Don't include + the brackets!) The text should be enclosed in the appropriate + comment syntax for the file format. We also recommend that a + file or class name and description of purpose be included on the + same "printed page" as the copyright notice for easier + identification within third-party archives. + + Copyright [yyyy] [name of copyright owner] + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. diff --git a/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/__init__.py b/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_pickup.py b/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_pickup.py new file mode 100644 index 0000000..8f561ea --- /dev/null +++ b/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_pickup.py @@ -0,0 +1,201 @@ +#!/usr/bin/env python3 + +# Copyright 2022 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import sys +import uuid +import argparse +import json +import asyncio + +import rclpy +from rclpy.node import Node +from rclpy.parameter import Parameter +from rclpy.qos import qos_profile_system_default +from rclpy.qos import QoSProfile +from rclpy.qos import QoSHistoryPolicy as History +from rclpy.qos import QoSDurabilityPolicy as Durability +from rclpy.qos import QoSReliabilityPolicy as Reliability + +from rmf_task_msgs.msg import ApiRequest, ApiResponse + + +############################################################################### + +class TaskRequester(Node): + + def __init__(self, argv=sys.argv): + super().__init__('task_requester') + parser = argparse.ArgumentParser() + parser.add_argument('-F', '--fleet', required=False, default='', + type=str, help='Fleet name') + parser.add_argument('-R', '--robot', required=False, default='', + type=str, help='Robot name') + parser.add_argument('-c', '--cart_id', required=True, + type=str, help='Cart identifier') + parser.add_argument('-p', '--pickup_lot', required=True, + type=str, help='Pick up place') + parser.add_argument('-d', '--dropoff_lot', required=True, + type=str, help='Dropoff lot waypoint name') + parser.add_argument('-e', '--emergency_lots', required=False, default='', + type=str, nargs='+', help='Emergency waypoints') + parser.add_argument('-st', '--start_time', + help='Start time from now in secs, default: 0', + type=int, default=0) + parser.add_argument('-pt', '--priority', + help='Priority value for this request', + type=int, default=0) + parser.add_argument("--use_sim_time", action="store_true", + help='Use sim time, default: false') + + self.args = parser.parse_args(argv[1:]) + self.response = asyncio.Future() + + transient_qos = QoSProfile( + history=History.KEEP_LAST, + depth=1, + reliability=Reliability.RELIABLE, + durability=Durability.TRANSIENT_LOCAL) + + self.pub = self.create_publisher( + ApiRequest, 'task_api_requests', transient_qos) + + # enable ros sim time + if self.args.use_sim_time: + self.get_logger().info("Using Sim Time") + param = Parameter("use_sim_time", Parameter.Type.BOOL, True) + self.set_parameters([param]) + + # Construct task + msg = ApiRequest() + msg.request_id = f"delivery_pickup_" + str(uuid.uuid4()) + payload = {} + if self.args.fleet and self.args.robot: + payload["type"] = "robot_task_request" + payload["robot"] = self.args.robot + payload["fleet"] = self.args.fleet + else: + payload["type"] = "dispatch_task_request" + request = {} + + # Set task request start time + now = self.get_clock().now().to_msg() + now.sec = now.sec + self.args.start_time + start_time = now.sec * 1000 + round(now.nanosec/10**6) + request["unix_millis_earliest_start_time"] = start_time + # todo(YV): Fill priority after schema is added + + # Define task request category + request["category"] = "compose" + + # Define task request description with phases + description = {} # task_description_Compose.json + description["category"] = "delivery_pickup" + description["phases"] = [] + activities = [] + + pickup_lot = self.args.pickup_lot + + # on_cancel = [] + # emergency_lots = [] + # if self.args.emergency_lots: + # for lot in self.args.emergency_lots: + # emergency_lots.append({"waypoint": lot}) + # cancellation_desc = { + # "one_of": emergency_lots, + # "constraints": [{ + # "category": "prefer_same_map", + # "description": "some description" + # }] + # } + # cancellation_activities = [] + # cancellation_activities.append({"category": "perform_action", + # "description": { + # "unix_millis_action_duration_estimate": 60000, + # "category": "dropoff_if_carrying_cart", + # "description": {} + # }}) + # cancellation_activities.append({"category": "go_to_place", + # "description": cancellation_desc}) + # cancellation_activities.append({"category": "perform_action", + # "description": { + # "unix_millis_action_duration_estimate": 60000, + # "category": "delivery_dropoff", + # "description": {} + # }}) + # on_cancel.append( + # {"category": "sequence", + # "description": cancellation_activities}) + + # Add activities + activities.append({"category": "go_to_place", + "description": pickup_lot}) + activities.append({"category": "perform_action", + "description": { + "unix_millis_action_duration_estimate": 60000, + "category": "delivery_pickup", + "description": { + "cart_id": self.args.cart_id, + "pickup_lot": pickup_lot + }}}) + activities.append({"category": "go_to_place", + "description": self.args.dropoff_lot}) + activities.append({"category": "perform_action", + "description": { + "unix_millis_action_duration_estimate": 60000, + "category": "delivery_dropoff", + "description": {} + }}) + # Add activities to phases + description["phases"].append( + {"activity": {"category": "sequence", + "description": {"activities": activities}}, + "on_cancel": on_cancel}) + request["description"] = description + payload["request"] = request + msg.json_msg = json.dumps(payload) + + def receive_response(response_msg: ApiResponse): + if response_msg.request_id == msg.request_id: + self.response.set_result(json.loads(response_msg.json_msg)) + + transient_qos.depth = 10 + self.sub = self.create_subscription( + ApiResponse, 'task_api_responses', receive_response, transient_qos + ) + + print(f"Json msg payload: \n{json.dumps(payload, indent=2)}") + self.pub.publish(msg) + + +############################################################################### + + +def main(argv=sys.argv): + rclpy.init(args=sys.argv) + args_without_ros = rclpy.utilities.remove_ros_args(sys.argv) + + task_requester = TaskRequester(args_without_ros) + rclpy.spin_until_future_complete( + task_requester, task_requester.response, timeout_sec=5.0) + if task_requester.response.done(): + print(f'Got response:\n{task_requester.response.result()}') + else: + print('Did not get a response') + rclpy.shutdown() + + +if __name__ == '__main__': + main(sys.argv) diff --git a/fleet_adapter_mir_tasks/package.xml b/fleet_adapter_mir_tasks/package.xml new file mode 100644 index 0000000..b492141 --- /dev/null +++ b/fleet_adapter_mir_tasks/package.xml @@ -0,0 +1,18 @@ + + + + fleet_adapter_mir_tasks + 0.1.0 + RMF fleet adapter custom tasks for MiR robots + Xiyu + Apache License 2.0 + + rmf_fleet_msgs + rmf_task_msgs + rmf_dispenser_msgs + rmf_lift_msgs + + + ament_python + + diff --git a/fleet_adapter_mir_tasks/resource/fleet_adapter_mir_tasks b/fleet_adapter_mir_tasks/resource/fleet_adapter_mir_tasks new file mode 100644 index 0000000..e69de29 diff --git a/fleet_adapter_mir_tasks/setup.cfg b/fleet_adapter_mir_tasks/setup.cfg new file mode 100644 index 0000000..3462068 --- /dev/null +++ b/fleet_adapter_mir_tasks/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script_dir=$base/lib/fleet_adapter_mir_tasks +[install] +install_scripts=$base/lib/fleet_adapter_mir_tasks diff --git a/fleet_adapter_mir_tasks/setup.py b/fleet_adapter_mir_tasks/setup.py new file mode 100644 index 0000000..302fba9 --- /dev/null +++ b/fleet_adapter_mir_tasks/setup.py @@ -0,0 +1,25 @@ +from setuptools import find_packages, setup + +package_name = 'fleet_adapter_mir_tasks' + +setup( + name=package_name, + version='0.1.0', + packages=[package_name], + data_files=[ + ('share/ament_index/resource_index/packages', + ['resource/' + package_name]), + ('share/' + package_name, ['package.xml']), + ], + install_requires=['setuptools'], + zip_safe=True, + maintainer='Xiyu', + maintainer_email='xiyu@openrobotics.org', + description='RMF fleet adapter custom tasks for MiR robots', + license='Apache License 2.0', + entry_points={ + 'console_scripts': [ + 'dispatch_pickup = fleet_adapter_mir_tasks.dispatch_pickup:main' + ], + }, +) From 9d928961367520977f2c94a81f657a752d2a42cb Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Fri, 12 Jan 2024 18:21:55 +0800 Subject: [PATCH 06/46] Footprint and marker type things and update readme Signed-off-by: Xiyu Oh --- README.md | 18 +- configs/mir_config.yaml | 18 +- fleet_adapter_mir/README.md | 66 +- .../fleet_adapter_mir/mir_api.py | 4 + .../fleet_adapter_mir/rmf_cart_delivery.py | 14 +- .../fleet_adapter_mir/robot_adapter_mir.py | 9 +- .../dispatch_pickup.py | 74 +- missions/rmf_cart_missions.json | 630 +----------------- 8 files changed, 133 insertions(+), 700 deletions(-) diff --git a/README.md b/README.md index f94095b..2155ba0 100644 --- a/README.md +++ b/README.md @@ -1,5 +1,5 @@ # fleet_adapter_mir -MiR100 and MirFM Fleet Adapter using the https://github.com/open-rmf/rmf_ros2/tree/main/rmf_fleet_adapter_python +MiR100, 200 and 250 using the https://github.com/open-rmf/rmf_ros2/tree/main/rmf_fleet_adapter_python @@ -30,24 +30,13 @@ colcon build ## Description -These packages implement a MiR robot/MiR Fleet command handle that is managed by a fleet adapter in Python. (Along with some helpers.) It can be used to command and manage a fleet of MiR robots using RMF! +These packages implement a MiR command handle that is managed by a fleet adapter in Python. (Along with some helpers.) It can be used to command and manage a fleet of MiR robots using RMF! It uses the `rmf_fleet_adapter_python` bindings, which allows for communication with `open-rmf` libraries and ROS2 nodes. In effect, it interfaces the MiR REST API with `open-rmf`, all without needing to directly use ROS 2 messages to communicate with `open-rmf`! - -### MiR vs. MiR Fleet - -Since the MiR robots and MiR Fleet work with different sets of endpoints that serve different functions, both `fleet_adapter_mir` and `fleet_adapter_mirfm` packages are availble to demonstrate RMF integration between MiR100 and MiR Fleet respectively. In addition, the `mir_fleet_client` package provides additional API needed for the MiR Fleet + RMF integration. - -For users who wish to take advantage of MiR Fleet's centralized control system/interface or do not have access to individual MiR robots, the `fleet_adapter_mirfm` package enables RMF integration with MiR Fleet by obtaining individual MiR robot positions and mission GUIDs via the MiR Fleet API and dispatching commands directly to the robots themselves. The current MiR Fleet API does not provide all the necessary endpoints for RMF to perform its task allocation and traffic deconfliction to the full extent, hence the implementation contains direct communication between RMF and MiR robots as well. - -As such, it is recommended to implement the fleet adapter directly with individual MiR robots using `fleet_adapter_mir`. - - - ## Additional Notes ### Different Units for Angles @@ -83,7 +72,8 @@ We have to deal with the `rmf_traffic` navgraph and the MiR map, with their own Luckily, we can leverage the `nudged` Python library to compute coordinate transforms between the two sets of coordinates. You just have to make sure to provide equivalent reference points within the two maps so transforms can be computed. -The transform objects are stored in the robot command handle's `self.transforms` member. +The transform objects are stored in the EasyFullControl fleet adapter handle. + diff --git a/configs/mir_config.yaml b/configs/mir_config.yaml index 1af76aa..9089a1c 100644 --- a/configs/mir_config.yaml +++ b/configs/mir_config.yaml @@ -96,14 +96,16 @@ plugins: rmf_cart_delivery: actions: ["delivery_pickup", "delivery_dropoff", "dropoff_if_carrying_cart"] missions: - dock_to_cart: "rmf_dock_to_cart" - pickup: "rmf_pickup_cart_top" - dropoff: "rmf_dropoff_cart_top" - exit_lot: "rmf_exit_lot" - update_footprint: "rmf_update_footprint" + dock_to_cart: "rmf_dock_to_cart" # Name of MiR mission for robot to dock under a cart - to be created by fleet adapter upon launch + pickup: "rmf_pickup_cart" # Name of MiR mission for robot to latch onto a cart - to be created and filled in by user + dropoff: "rmf_dropoff_cart" # Name of MiR mission for robot to unlatch and exit from under a cart - to be created and filled in by user + exit_lot: "rmf_exit_lot" # Name of MiR mission for robot to exit from under a cart - to be created by fleet adapter upon launch + update_footprint: "rmf_update_footprint" # Name of MiR mission for robot to update the footprint of a robot - to be created by fleet adapter upon launch footprints: - robot: "MiR100-200" - cart: "HostShelfCart800" - missions_json: "/home/some_user/mir_ws/src/fleet_adapter_mir/missions/rmf_cart_missions.json" + robot: "MiR100-200" # Name of robot footprint stored on MiR + cart: "ShelfCart" # Name of cart footprint stored on MiR + marker_types: + cart: "AsymmetricShelf" # Name of cart marker type + missions_json: "/home/some_user/mir_ws/src/fleet_adapter_mir/missions/rmf_cart_missions.json" # Filepath to RMF cart delivery missions search_timeout: 60 pickup_dist_threshold: 3.0 # metres diff --git a/fleet_adapter_mir/README.md b/fleet_adapter_mir/README.md index 3aa54b8..a70dc16 100644 --- a/fleet_adapter_mir/README.md +++ b/fleet_adapter_mir/README.md @@ -41,8 +41,72 @@ Alternatively, if you want to run everything with full capabilities, (though not ros2 run fleet_adapter_mir fleet_adapter_mir -c mir_config.yaml -n nav_graph.yaml ``` +If you have not configured the necessary RMF missions on the MiR, you may parse the relevant JSON filepaths when launching the fleet adapter node. On startup, the fleet adapter will create these missions via MiR REST API + +```bash +ros2 run fleet_adapter_mir fleet_adapter_mir -c mir_config.yaml -n nav_graph.yaml -a ../missions/rmf_missions.json +``` + ### Configuration -An example configuration file, `mir_config.yaml` has been provided. It has been generously commented, and in the cases where it has not, the parameter names are self-explanatory enough. \ No newline at end of file +An example configuration file, `mir_config.yaml` has been provided. It has been generously commented, and in the cases where it has not, the parameter names are self-explanatory enough. + + + +### Setting up building maps + +**Chargers** + +To use the `rmf_dock_and_charge` mission for charging, you may provide a description similar to the following when adding a `dock_name` to the charging point in your building map yaml/navigation graph: +```json +{"description": {"end_waypoint": "charger_name"}, "mission_name": "rmf_dock_and_charge"} +``` +Where you replace `end_waypoint` with the name of your MiR charger. + + +**MiR positions** + +For more accurate robot maneuver, you may wish to send the MiR to a Robot Position instead of using coordinates. For such waypoints, you can provide a `dock_name` with the `rmf_move_to_position` mission specified: +```json +{"description": {"end_waypoint": "waypoint_name"}, "mission_name": "rmf_move_to_position"} +``` + + + +### Plugins + +The MiR is capable of performing various types of custom missions and tasks. You can now easily set up plugins offered in this repo instead of writing your own perform action for common use cases. + +For cart deliveries from point A to B: + +**rmf_cart_delivery** + +The `rmf_cart_delivery` plugin allows users to submit pickup and dropoff tasks to MiR integrated with RMF. The workflow of the task is as follows: +1. RMF will send the robot to the pickup lot +2. The robot will attempt to dock under a cart in the pickup lot +3. If the robot successfully docks under the correct cart, it will proceed to deliver it to a dropoff point. If the cart is missing or is not the desired cart, RMF will cancel the task. + +Some relevant MiR missions (docking, exit, update footprint) will be automatically created on the MiR on startup. These missions are used to facilitate the pickup and dropoff activities and can be found in the plugin config under `missions`. They are: +- `rmf_dock_to_cart`: Docks robot under the cart +- `rmf_exit_lot`: Calls the robot to exit from under the cart +- `rmf_update_footprint`: Updates the robot footprint +They are defined and stored in the `rmf_cart_missions.json` file and do not require any further configuration. + +However, since there are various types of latching methods available for different MiR models, users will need to set up their custom pickup and dropoff missions on the MiR: +1. Create 2 missions on the MiR: + - `rmf_pickup_cart`: Triggers the robot's latching module to open + - `rmf_dropoff_cart`: Triggers the robot's latching module to close and release the cart, then exit from under the cart (relative move -1 metre in the X-direction) +2. Fill in the MiR mission names in the plugin config under `missions`. The default mission names are `rmf_pickup_cart` and `rmf_dropoff_cart`. +3. Fill in the footprints and marker types to be used for your specific robot and cart in the plugin config. +4. In `rmf_cart_delivery.py`, fill in the logic to check whether the robot's latching module is open in blanks marked `# IMPLEMENT YOUR CODE HERE`. Some API calls to check the MiR's PLC registers and IO modules are provided in case you may want to use them. + +To submit a cart delivery task, you may use the `dispatch_pickup` task script: +```bash +ros2 run fleet_adapter_mir_tasks dispatch_pickup -g go_to_waypoint -p pickup_lot -d dropoff_lot -c some_cart_id +``` +- `-g`: Takes in an existing waypoint name for the robot to travel to before performing the pickup +- `-p`: Name of the pickup lot. This name should be identical to the shelf position configured on the MiR. +- `-d`: Name of the dropoff lot. This name should be identical to the robot or shelf position configured on the MiR. +- `-c`: Optional cart identifier for the fleet adapter to assess whether the cart is correct for pickup. diff --git a/fleet_adapter_mir/fleet_adapter_mir/mir_api.py b/fleet_adapter_mir/fleet_adapter_mir/mir_api.py index 5337662..5201b22 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/mir_api.py +++ b/fleet_adapter_mir/fleet_adapter_mir/mir_api.py @@ -227,6 +227,10 @@ def create_rmf_mission_actions(self, mission_name: str, mission_id: str, mission if param_body['id'] == 'marker_type': default_marker = self.docking_offsets_get()[0]['guid'] param_body['value'] = default_marker + # If the input type is a footprint, we'll also use a placeholder footprint GUID + if param_body['id'] == 'footprint': + default_footprint = self.footprints_get()[0]['guid'] + param_body['value'] = default_footprint action_body_param.append(param_body) diff --git a/fleet_adapter_mir/fleet_adapter_mir/rmf_cart_delivery.py b/fleet_adapter_mir/fleet_adapter_mir/rmf_cart_delivery.py index 078d1a6..47f0c60 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/rmf_cart_delivery.py +++ b/fleet_adapter_mir/fleet_adapter_mir/rmf_cart_delivery.py @@ -69,9 +69,10 @@ def __init__( self.exit_mission = self.action_config['missions']['exit_lot'] self.footprint_mission = self.action_config['missions']['update_footprint'] - # Initialize footprints + # Initialize footprints and marker types self.robot_footprint_guid = self.api.footprints_guid_get(self.action_config['footprints']['robot']) self.cart_footprint_guid = self.api.footprints_guid_get(self.action_config['footprints']['cart']) + self.cart_marker_type_guid = self.api.docking_offsets_guid_get(self.action_config['marker_types']['cart']) self.update_footprint(self.robot_footprint_guid) def update_action(self): @@ -185,10 +186,9 @@ def check_pickup(self, pickup: Pickup): assert self.dock_to_cart_mission is not None current_wp_name = pickup.pickup_lots[0] cart_marker_guid = self.api.known_positions[current_wp_name]['guid'] - mission_params = self.api.get_mission_params_with_value(self.dock_to_cart_mission, - 'docking', - 'cart_marker', - cart_marker_guid) + cart_marker_param = self.api.get_mission_params_with_value(self.dock_to_cart_mission, 'docking', 'cart_marker', cart_marker_guid) + marker_type_param = self.api.get_mission_params_with_value(self.dock_to_cart_mission, 'docking', 'cart_marker_type', self.cart_marker_type_guid) + mission_params = cart_marker_param + marker_type_param self.update_footprint(self.robot_footprint_guid) mission_queue_id = self.api.queue_mission_by_name(self.dock_to_cart_mission, mission_params) if not mission_queue_id: @@ -264,6 +264,8 @@ def check_pickup(self, pickup: Pickup): # Latch successfully opened, indicate pickup as success pickup.state = PickupState.PICKUP_SUCCESS pickup.latching = False + # Update robot footprint to accommodate the cart size + self.update_footprint(self.cart_footprint_guid) case PickupState.PICKUP_SUCCESS: # Correct ID, we can end the delivery now @@ -322,6 +324,8 @@ def check_dropoff(self, dropoff: Dropoff): else: if self.api.mission_completed(dropoff.mission_queue_id): self.node.get_logger().info(f'Dropoff mission completed!') + # Update robot footprint + self.update_footprint(self.robot_footprint_guid) if dropoff.execution is not None: dropoff.execution.finished() return True diff --git a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py index db7948d..7a747f2 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py +++ b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py @@ -137,7 +137,7 @@ def __init__( mir_api=self.api, update_handle=self.update_handle, actions=plugin_config['rmf_cart_delivery']['actions'], - missions_json=plugin_config['rmf_cart_delivery']['missions_json'], + missions_json=plugin_config['rmf_cart_delivery'].get('missions_json'), action_config=plugin_config['rmf_cart_delivery'], retrieve_mir_coordinates=self.retrieve_mir_coordinates) # To be added on with other plugins @@ -338,13 +338,6 @@ def navigate(self, destination, execution): self.mission = MissionHandle(execution) self.request_dock(dock_json, self.mission) return - # TODO(XY): remove this hack and make sure dock missions are passed properly to - # the nav command - elif destination.name and 'Charger' in destination.name: - self.mission = MissionHandle(execution, charger=destination.name) - dock_json = {'description': {'end_waypoint': destination.name}, - 'mission_name': self.api.dock_and_charge_mission} - self.request_dock(dock_json, self.mission) if destination.inside_lift is not None: positions_for_lift = self.lift_positions.get(destination.inside_lift.name) diff --git a/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_pickup.py b/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_pickup.py index 8f561ea..d7ee46c 100644 --- a/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_pickup.py +++ b/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_pickup.py @@ -43,12 +43,14 @@ def __init__(self, argv=sys.argv): type=str, help='Fleet name') parser.add_argument('-R', '--robot', required=False, default='', type=str, help='Robot name') - parser.add_argument('-c', '--cart_id', required=True, + parser.add_argument('-c', '--cart_id', required=False, default='', type=str, help='Cart identifier') + parser.add_argument('-g', '--go_to', required=True, + type=str, help='Waypoint name to go to for pickup') parser.add_argument('-p', '--pickup_lot', required=True, - type=str, help='Pick up place') + type=str, help='Name of pickup lot') parser.add_argument('-d', '--dropoff_lot', required=True, - type=str, help='Dropoff lot waypoint name') + type=str, help='Name of dropoff lot') parser.add_argument('-e', '--emergency_lots', required=False, default='', type=str, nargs='+', help='Emergency waypoints') parser.add_argument('-st', '--start_time', @@ -106,49 +108,47 @@ def __init__(self, argv=sys.argv): description["phases"] = [] activities = [] - pickup_lot = self.args.pickup_lot - - # on_cancel = [] - # emergency_lots = [] - # if self.args.emergency_lots: - # for lot in self.args.emergency_lots: - # emergency_lots.append({"waypoint": lot}) - # cancellation_desc = { - # "one_of": emergency_lots, - # "constraints": [{ - # "category": "prefer_same_map", - # "description": "some description" - # }] - # } - # cancellation_activities = [] - # cancellation_activities.append({"category": "perform_action", - # "description": { - # "unix_millis_action_duration_estimate": 60000, - # "category": "dropoff_if_carrying_cart", - # "description": {} - # }}) - # cancellation_activities.append({"category": "go_to_place", - # "description": cancellation_desc}) - # cancellation_activities.append({"category": "perform_action", - # "description": { - # "unix_millis_action_duration_estimate": 60000, - # "category": "delivery_dropoff", - # "description": {} - # }}) - # on_cancel.append( - # {"category": "sequence", - # "description": cancellation_activities}) + on_cancel = [] + emergency_lots = [] + if self.args.emergency_lots: + for lot in self.args.emergency_lots: + emergency_lots.append({"waypoint": lot}) + cancellation_desc = { + "one_of": emergency_lots, + "constraints": [{ + "category": "prefer_same_map", + "description": "some description" + }] + } + cancellation_activities = [] + cancellation_activities.append({"category": "perform_action", + "description": { + "unix_millis_action_duration_estimate": 60000, + "category": "dropoff_if_carrying_cart", + "description": {} + }}) + cancellation_activities.append({"category": "go_to_place", + "description": cancellation_desc}) + cancellation_activities.append({"category": "perform_action", + "description": { + "unix_millis_action_duration_estimate": 60000, + "category": "delivery_dropoff", + "description": {} + }}) + on_cancel.append( + {"category": "sequence", + "description": cancellation_activities}) # Add activities activities.append({"category": "go_to_place", - "description": pickup_lot}) + "description": self.args.go_to}) activities.append({"category": "perform_action", "description": { "unix_millis_action_duration_estimate": 60000, "category": "delivery_pickup", "description": { "cart_id": self.args.cart_id, - "pickup_lot": pickup_lot + "pickup_lot": self.args.pickup_lot }}}) activities.append({"category": "go_to_place", "description": self.args.dropoff_lot}) diff --git a/missions/rmf_cart_missions.json b/missions/rmf_cart_missions.json index 86ce67c..d710062 100644 --- a/missions/rmf_cart_missions.json +++ b/missions/rmf_cart_missions.json @@ -47,8 +47,8 @@ "id": "marker" }, { - "value": "cbd0de8c-467c-11ee-899f-00012983ef2c", - "input_name": null, + "value": "some_placeholder_marker_type_guid", + "input_name": "cart_marker_type", "id": "marker_type" }, { @@ -65,636 +65,12 @@ "action_type": "docking" } ], - "rmf_dropoff_cart_side": [ - { - "priority": 2, - "parameters": [ - { - "value": "mirconst-guid-0000-0001-footprint000", - "input_name": null, - "id": "footprint" - } - ], - "action_type": "set_footprint" - }, - { - "priority": 3, - "parameters": [ - { - "value": -1.0, - "input_name": null, - "id": "x" - }, - { - "value": 0.0, - "input_name": null, - "id": "y" - }, - { - "value": 0.0, - "input_name": null, - "id": "orientation" - }, - { - "value": 0.25, - "input_name": null, - "id": "max_linear_speed" - }, - { - "value": 0.25, - "input_name": null, - "id": "max_angular_speed" - }, - { - "value": true, - "input_name": null, - "id": "collision_detection" - } - ], - "action_type": "relative_move" - }, - { - "priority": 1, - "parameters": [ - { - "value": "mirconst-guid-0000-0011-actionlist00", - "input_name": null, - "id": "mission_id" - } - ], - "action_type": "load_mission" - } - ], - "rmf_dropoff_cart_top": [ - { - "priority": 1, - "parameters": [ - { - "value": "io_module", - "input_name": null, - "id": "compare" - }, - { - "value": "mirconst-guid-0000-0001-internalIO00", - "input_name": null, - "id": "module" - }, - { - "value": 3, - "input_name": null, - "id": "io_port" - }, - { - "value": "1", - "input_name": null, - "id": "register" - }, - { - "value": "==", - "input_name": null, - "id": "operator" - }, - { - "value": 0, - "input_name": null, - "id": "value" - }, - { - "value": "", - "input_name": null, - "id": "true" - }, - { - "value": "", - "input_name": null, - "id": "false" - } - ], - "action_type": "if" - }, - { - "priority": 2, - "parameters": [ - { - "value": "No shelf is lifted according to IO input 3", - "input_name": null, - "id": "message" - } - ], - "action_type": "throw_error" - }, - { - "priority": 3, - "parameters": [ - { - "value": null, - "input_name": null, - "id": "sound" - }, - { - "value": null, - "input_name": null, - "id": "volume" - }, - { - "value": "muted", - "input_name": null, - "id": "front" - }, - { - "value": "muted", - "input_name": null, - "id": "rear" - }, - { - "value": "muted", - "input_name": null, - "id": "sides" - }, - { - "value": "", - "input_name": null, - "id": "content" - } - ], - "action_type": "reduce_protective_fields" - }, - { - "priority": 8, - "parameters": [ - { - "value": "mirconst-guid-0000-0001-footprint007", - "input_name": null, - "id": "footprint" - } - ], - "action_type": "set_footprint" - }, - { - "priority": 9, - "parameters": [ - { - "value": -1, - "input_name": null, - "id": "x" - }, - { - "value": 0, - "input_name": null, - "id": "y" - }, - { - "value": 0, - "input_name": null, - "id": "orientation" - }, - { - "value": 0.25, - "input_name": null, - "id": "max_linear_speed" - }, - { - "value": 0.25, - "input_name": null, - "id": "max_angular_speed" - }, - { - "value": true, - "input_name": null, - "id": "collision_detection" - } - ], - "action_type": "relative_move" - }, - { - "priority": 10, - "parameters": [ - { - "value": "577eaace-be75-11ed-a404-0001297c2278", - "input_name": null, - "id": "footprint" - } - ], - "action_type": "set_footprint" - }, - { - "priority": 4, - "parameters": [ - { - "value": "mirconst-guid-0000-0001-internalIO00", - "input_name": null, - "id": "module" - }, - { - "value": 3, - "input_name": null, - "id": "port" - }, - { - "value": "off", - "input_name": null, - "id": "operation" - }, - { - "value": null, - "input_name": null, - "id": "timeout" - } - ], - "action_type": "set_io" - }, - { - "priority": 5, - "parameters": [ - { - "value": "00:00:01.000000", - "input_name": null, - "id": "time" - } - ], - "action_type": "wait" - }, - { - "priority": 6, - "parameters": [ - { - "value": "mirconst-guid-0000-0001-internalIO00", - "input_name": null, - "id": "module" - }, - { - "value": 2, - "input_name": null, - "id": "port" - }, - { - "value": "on", - "input_name": null, - "id": "operation" - }, - { - "value": "00:00:10.000000", - "input_name": null, - "id": "timeout" - }, - { - "value": "", - "input_name": null, - "id": "content" - } - ], - "action_type": "set_reset_io" - }, - { - "priority": 7, - "parameters": [ - { - "value": "mirconst-guid-0000-0001-internalIO00", - "input_name": null, - "id": "module" - }, - { - "value": 2, - "input_name": null, - "id": "port" - }, - { - "value": "on", - "input_name": null, - "id": "value" - }, - { - "value": "00:00:10.000000", - "input_name": null, - "id": "timeout" - } - ], - "action_type": "wait_for_io" - } - ], - "rmf_pickup_cart_side": [ - { - "priority": 1, - "parameters": [ - { - "value": "13", - "input_name": null, - "id": "register" - }, - { - "value": "set", - "input_name": null, - "id": "action" - }, - { - "value": 0.0, - "input_name": null, - "id": "value" - } - ], - "action_type": "set_plc_register" - }, - { - "priority": 2, - "parameters": [ - { - "value": "14", - "input_name": null, - "id": "register" - }, - { - "value": 1.0, - "input_name": null, - "id": "value" - }, - { - "value": 0.0, - "input_name": null, - "id": "reset_value" - }, - { - "value": "", - "input_name": null, - "id": "content" - } - ], - "action_type": "set_reset_plc" - }, - { - "priority": 3, - "parameters": [ - { - "value": "8", - "input_name": null, - "id": "register" - }, - { - "value": 1.0, - "input_name": null, - "id": "value" - }, - { - "value": "00:01:00.000000", - "input_name": null, - "id": "timeout" - } - ], - "action_type": "wait_for_plc_register" - }, - { - "priority": 4, - "parameters": [ - { - "value": "f65abbec-ea4e-11ed-af33-00012983ef2c", - "input_name": null, - "id": "footprint" - } - ], - "action_type": "set_footprint" - } - ], - "rmf_pickup_cart_top": [ - { - "priority": 7, - "parameters": [ - { - "value": "mirconst-guid-0000-0001-footprint007", - "input_name": null, - "id": "footprint" - } - ], - "action_type": "set_footprint" - }, - { - "priority": 8, - "parameters": [ - { - "value": null, - "input_name": null, - "id": "sound" - }, - { - "value": null, - "input_name": null, - "id": "volume" - }, - { - "value": "muted", - "input_name": null, - "id": "front" - }, - { - "value": "muted", - "input_name": null, - "id": "rear" - }, - { - "value": "muted", - "input_name": null, - "id": "sides" - }, - { - "value": "", - "input_name": null, - "id": "content" - } - ], - "action_type": "reduce_protective_fields" - }, - { - "priority": 9, - "parameters": [ - { - "value": 0, - "input_name": null, - "id": "x" - }, - { - "value": 0, - "input_name": null, - "id": "y" - }, - { - "value": 0, - "input_name": null, - "id": "orientation" - }, - { - "value": 0.25, - "input_name": null, - "id": "max_linear_speed" - }, - { - "value": 0.25, - "input_name": null, - "id": "max_angular_speed" - }, - { - "value": true, - "input_name": null, - "id": "collision_detection" - } - ], - "action_type": "relative_move" - }, - { - "priority": 1, - "parameters": [ - { - "value": "io_module", - "input_name": null, - "id": "compare" - }, - { - "value": "mirconst-guid-0000-0001-internalIO00", - "input_name": null, - "id": "module" - }, - { - "value": 2, - "input_name": null, - "id": "io_port" - }, - { - "value": "1", - "input_name": null, - "id": "register" - }, - { - "value": "==", - "input_name": null, - "id": "operator" - }, - { - "value": 0, - "input_name": null, - "id": "value" - }, - { - "value": "", - "input_name": null, - "id": "true" - }, - { - "value": "", - "input_name": null, - "id": "false" - } - ], - "action_type": "if" - }, - { - "priority": 2, - "parameters": [ - { - "value": "A shelf is already lifted according to IO input 2", - "input_name": null, - "id": "message" - } - ], - "action_type": "throw_error" - }, - { - "priority": 3, - "parameters": [ - { - "value": "mirconst-guid-0000-0001-internalIO00", - "input_name": null, - "id": "module" - }, - { - "value": 2, - "input_name": null, - "id": "port" - }, - { - "value": "off", - "input_name": null, - "id": "operation" - }, - { - "value": null, - "input_name": null, - "id": "timeout" - } - ], - "action_type": "set_io" - }, - { - "priority": 4, - "parameters": [ - { - "value": "00:00:01.000000", - "input_name": null, - "id": "time" - } - ], - "action_type": "wait" - }, - { - "priority": 5, - "parameters": [ - { - "value": "mirconst-guid-0000-0001-internalIO00", - "input_name": null, - "id": "module" - }, - { - "value": 3, - "input_name": null, - "id": "port" - }, - { - "value": "on", - "input_name": null, - "id": "operation" - }, - { - "value": "00:00:10.000000", - "input_name": null, - "id": "timeout" - }, - { - "value": "", - "input_name": null, - "id": "content" - } - ], - "action_type": "set_reset_io" - }, - { - "priority": 6, - "parameters": [ - { - "value": "mirconst-guid-0000-0001-internalIO00", - "input_name": null, - "id": "module" - }, - { - "value": 3, - "input_name": null, - "id": "port" - }, - { - "value": "on", - "input_name": null, - "id": "value" - }, - { - "value": "00:00:10.000000", - "input_name": null, - "id": "timeout" - } - ], - "action_type": "wait_for_io" - } - ], "rmf_update_footprint": [ { "priority": 1, "parameters": [ { - "value": "mirconst-guid-0000-0001-footprint000", + "value": "some_placeholder_footprint_guid", "input_name": "footprint", "id": "footprint" } From 946d98cfc7ce0de76ec249c22546c8f9f0697528 Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Mon, 15 Jan 2024 17:09:56 +0800 Subject: [PATCH 07/46] Restore mir/mirfm comparison and add note that mirfm is not actively supported Signed-off-by: Xiyu Oh --- README.md | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/README.md b/README.md index 2155ba0..6508e15 100644 --- a/README.md +++ b/README.md @@ -37,6 +37,19 @@ It uses the `rmf_fleet_adapter_python` bindings, which allows for communication In effect, it interfaces the MiR REST API with `open-rmf`, all without needing to directly use ROS 2 messages to communicate with `open-rmf`! + +### MiR vs. MiR Fleet + +Since the MiR robots and MiR Fleet work with different sets of endpoints that serve different functions, both `fleet_adapter_mir` and `fleet_adapter_mirfm` packages are availble to demonstrate RMF integration between MiR100/200/250 and MiR Fleet respectively. In addition, the `mir_fleet_client` package provides additional API needed for the MiR Fleet + RMF integration. + +For users who wish to take advantage of MiR Fleet's centralized control system/interface or do not have access to individual MiR robots, the `fleet_adapter_mirfm` package enables RMF integration with MiR Fleet by obtaining individual MiR robot positions and mission GUIDs via the MiR Fleet API and dispatching commands directly to the robots themselves. The current MiR Fleet API does not provide all the necessary endpoints for RMF to perform its task allocation and traffic deconfliction to the full extent, hence the implementation contains direct communication between RMF and MiR robots as well. + +As such, it is recommended to implement the fleet adapter directly with individual MiR robots using `fleet_adapter_mir`. + +**NOTE**: `fleet_adapter_mirfm` is currently not being actively supported. + + + ## Additional Notes ### Different Units for Angles From 725fd0d9c287c1802c6ce374b314846c52118968 Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Thu, 18 Jan 2024 15:23:06 +0800 Subject: [PATCH 08/46] Make marker type a variable when posting missions Signed-off-by: Xiyu Oh --- configs/mir_config.yaml | 2 ++ .../fleet_adapter_mir/mir_api.py | 32 +++++++++---------- missions/rmf_missions.json | 4 +-- 3 files changed, 19 insertions(+), 19 deletions(-) diff --git a/configs/mir_config.yaml b/configs/mir_config.yaml index 9089a1c..e222b30 100644 --- a/configs/mir_config.yaml +++ b/configs/mir_config.yaml @@ -46,6 +46,8 @@ conversions: L2: name: "Level_2_Lift" + marker_types: + "charger": "Narrow asymmetric MiR500/1000 shelf" # RMF Fleet parameters rmf_fleet: diff --git a/fleet_adapter_mir/fleet_adapter_mir/mir_api.py b/fleet_adapter_mir/fleet_adapter_mir/mir_api.py index 5201b22..94fedb1 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/mir_api.py +++ b/fleet_adapter_mir/fleet_adapter_mir/mir_api.py @@ -69,6 +69,7 @@ def __init__(self, prefix, headers, conversions, rmf_missions, timeout=10.0, deb self.mission_keys: dict = conversions['missions'] self.mission_actions: dict = {} self.mission_action_types: dict = {} + self.marker_type_keys: dict = conversions['marker_types'] self.attempt_connection() def attempt_connection(self): @@ -160,7 +161,7 @@ def update_known_positions(self): for pos in self.positions_get(): if pos['name'] in self.known_positions and \ pos['type_id'] == self.known_positions[pos['name']]['type_id'] and \ - ('rmf_localize' in pos['name'] or 'cgh_localize' in pos['name']): + ('rmf_localize' in pos['name']): # Delete any duplicate positions self.positions_guid_delete(pos['guid']) elif pos['type_id'] == MiRPositionTypes.ROBOT or \ @@ -301,7 +302,10 @@ def dock(self, mission_name, start_waypoint, end_waypoint): # Check whether we should dock into this end waypoint or not (for charging) elif dock_param: - mission_params = end_param + dock_param + charger_marker_type = self.marker_type_keys['charger'] + charger_marker_type_guid = self.docking_offsets_guid_get(charger_marker_type) + marker_param = self.get_mission_params_with_value(mission_name, 'docking', 'charger_marker_type', charger_marker_type_guid) + mission_params = end_param + dock_param + marker_param else: mission_params = end_param return self.queue_mission_by_name(mission_name, mission_params) @@ -313,10 +317,10 @@ def localize(self, map, estimate, index): ) if index is not None: - position_name = f'cgh_1810_localize_{index}' + position_name = f'rmf_localize_{index}' else: p = estimate - position_name = f'cgh_1810_localize_{map}_{p[0]:.2f}_{p[1]:.2f}' + position_name = f'rmf_localize_{map}_{p[0]:.2f}_{p[1]:.2f}' mir_map = self.map_conversions.rmf_to_mir[map] map_id = self.known_maps[mir_map] position_guid = self.get_position_guid(position_name, map_id, estimate) @@ -450,7 +454,7 @@ def positions_put(self, guid, name, map_id, location): def positions_delete(self): new_known_positions = {} for position in self.known_positions: - if 'rmf_localize' in position or 'cgh_localize' in position: + if 'rmf_localize' in position: pos_guid = self.known_positions[position] try: response = requests.delete( @@ -814,18 +818,12 @@ def docking_offsets_get(self): except Exception as err: print(f"Other error: {err}") - def docking_offsets_guid_get(self, guid: str): - if not self.connected: - return - try: - response = requests.get(self.prefix + f'docking_offsets/{guid}', headers=self.headers, timeout=self.timeout) - if self.debug: - print(f"Response: {response.json()}") - return response.json() - except HTTPError as http_err: - print(f"HTTP error: {http_err}") - except Exception as err: - print(f"Other error: {err}") + def docking_offsets_guid_get(self, offset_name: str): + offsets = self.docking_offsets_get() + for offs in offsets: + if offs['name'] == offset_name: + return offs['guid'] + return None def footprints_get(self): if not self.connected: diff --git a/missions/rmf_missions.json b/missions/rmf_missions.json index 9ba25b3..a7df7d5 100644 --- a/missions/rmf_missions.json +++ b/missions/rmf_missions.json @@ -30,8 +30,8 @@ "id": "marker" }, { - "value": "mirconst-guid-0000-0001-marker000001", - "input_name": null, + "value": "some_placeholder_marker_type_guid", + "input_name": "charger_marker_type", "id": "marker_type" }, { From 8aeb014ec98e7d01ccb5ea11be683e734a42b69b Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Wed, 31 Jan 2024 11:58:53 +0800 Subject: [PATCH 09/46] Update dispatch pickup cancellation behavior and configs Signed-off-by: Xiyu Oh --- configs/mir_config.yaml | 4 +- .../fleet_adapter_mir/robot_adapter_mir.py | 2 +- .../dispatch_pickup.py | 51 +++++++++++-------- 3 files changed, 32 insertions(+), 25 deletions(-) diff --git a/configs/mir_config.yaml b/configs/mir_config.yaml index e222b30..1de4059 100644 --- a/configs/mir_config.yaml +++ b/configs/mir_config.yaml @@ -80,7 +80,7 @@ rmf_fleet: delivery: True clean: False finishing_request: "charge" # [park, charge, nothing] - actions: ["delivery_pickup", "delivery_dropoff", "dropoff_if_carrying_cart"] + actions: ["delivery_pickup", "delivery_dropoff"] robots: mir_1: charger: "Charger_1" @@ -96,7 +96,7 @@ rmf_fleet: plugins: rmf_cart_delivery: - actions: ["delivery_pickup", "delivery_dropoff", "dropoff_if_carrying_cart"] + actions: ["delivery_pickup", "delivery_dropoff"] missions: dock_to_cart: "rmf_dock_to_cart" # Name of MiR mission for robot to dock under a cart - to be created by fleet adapter upon launch pickup: "rmf_pickup_cart" # Name of MiR mission for robot to latch onto a cart - to be created and filled in by user diff --git a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py index 7a747f2..6edcd45 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py +++ b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py @@ -201,7 +201,7 @@ def request_update(self): self.api.status_put(MiRStateCode.READY) def is_charging(self, status: MirStatus): - # TODO(XY): check if we can verify that a robot is charging via mode_id instead + # Note: Not the best way to verify that robot is charging but there's currently no other option if status.response.get('mission_text') == "Charging... Waiting for new mission...": return True return False diff --git a/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_pickup.py b/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_pickup.py index d7ee46c..bd310dc 100644 --- a/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_pickup.py +++ b/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_pickup.py @@ -106,8 +106,8 @@ def __init__(self, argv=sys.argv): description = {} # task_description_Compose.json description["category"] = "delivery_pickup" description["phases"] = [] - activities = [] + # Set up cancellation behavior on_cancel = [] emergency_lots = [] if self.args.emergency_lots: @@ -121,12 +121,6 @@ def __init__(self, argv=sys.argv): }] } cancellation_activities = [] - cancellation_activities.append({"category": "perform_action", - "description": { - "unix_millis_action_duration_estimate": 60000, - "category": "dropoff_if_carrying_cart", - "description": {} - }}) cancellation_activities.append({"category": "go_to_place", "description": cancellation_desc}) cancellation_activities.append({"category": "perform_action", @@ -139,30 +133,43 @@ def __init__(self, argv=sys.argv): {"category": "sequence", "description": cancellation_activities}) - # Add activities - activities.append({"category": "go_to_place", - "description": self.args.go_to}) - activities.append({"category": "perform_action", + # Pickup activity + pickup_activity = [] + pickup_activity.append({"category": "go_to_place", + "description": self.args.pickup_lot}) + pickup_activity.append({"category": "perform_action", "description": { "unix_millis_action_duration_estimate": 60000, - "category": "delivery_pickup", + "category": self.args.pickup_type, "description": { "cart_id": self.args.cart_id, "pickup_lot": self.args.pickup_lot }}}) - activities.append({"category": "go_to_place", - "description": self.args.dropoff_lot}) - activities.append({"category": "perform_action", - "description": { - "unix_millis_action_duration_estimate": 60000, - "category": "delivery_dropoff", - "description": {} - }}) - # Add activities to phases description["phases"].append( {"activity": {"category": "sequence", - "description": {"activities": activities}}, + "description": {"activities": pickup_activity}}}) + # GoToPlace activity + go_to_place_activity = [{ + "category": "go_to_place", + "description": self.args.dropoff_lot + }] + description["phases"].append( + {"activity": {"category": "sequence", + "description": {"activities": go_to_place_activity}}, "on_cancel": on_cancel}) + # Dropoff activity + dropoff_activity = [{ + "category": "perform_action", + "description": { + "unix_millis_action_duration_estimate": 60000, + "category": "delivery_dropoff", + "description": {} + } + }] + description["phases"].append( + {"activity": {"category": "sequence", + "description": {"activities": dropoff_activity}}}) + # Consolidate request["description"] = description payload["request"] = request msg.json_msg = json.dumps(payload) From b7f377092d49b55cd15cc56cb3593e0053640315 Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Mon, 5 Feb 2024 14:31:54 +0800 Subject: [PATCH 10/46] Remove limits on charging mission Signed-off-by: Xiyu Oh --- missions/rmf_missions.json | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/missions/rmf_missions.json b/missions/rmf_missions.json index a7df7d5..1cd2652 100644 --- a/missions/rmf_missions.json +++ b/missions/rmf_missions.json @@ -51,12 +51,12 @@ "priority": 3, "parameters": [ { - "value": "00:10:00.000000", + "value": null, "input_name": null, "id": "minimum_time" }, { - "value": 25.0, + "value": null, "input_name": null, "id": "minimum_percentage" }, From 7b747f0a960677c877457ddd3ba6fef7d7448319 Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Thu, 22 Feb 2024 12:41:05 +0800 Subject: [PATCH 11/46] Fixes bugs for cancelled pickup states, refactor mission info stored in pickup/dropoff, and move action-related code into its own package Signed-off-by: Xiyu Oh --- .../fleet_adapter_mir/robot_adapter_mir.py | 2 +- .../fleet_adapter_mir_actions/__init__.py | 0 .../fleet_adapter_mir_actions}/mir_action.py | 24 +- .../rmf_cart_delivery.py | 214 +++++++++--------- fleet_adapter_mir_actions/package.xml | 15 ++ .../resource/fleet_adapter_mir_actions | 0 fleet_adapter_mir_actions/setup.cfg | 4 + fleet_adapter_mir_actions/setup.py | 24 ++ 8 files changed, 165 insertions(+), 118 deletions(-) create mode 100644 fleet_adapter_mir_actions/fleet_adapter_mir_actions/__init__.py rename {fleet_adapter_mir/fleet_adapter_mir => fleet_adapter_mir_actions/fleet_adapter_mir_actions}/mir_action.py (70%) rename {fleet_adapter_mir/fleet_adapter_mir => fleet_adapter_mir_actions/fleet_adapter_mir_actions}/rmf_cart_delivery.py (78%) create mode 100644 fleet_adapter_mir_actions/package.xml create mode 100644 fleet_adapter_mir_actions/resource/fleet_adapter_mir_actions create mode 100644 fleet_adapter_mir_actions/setup.cfg create mode 100644 fleet_adapter_mir_actions/setup.py diff --git a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py index 6edcd45..652779e 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py +++ b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py @@ -17,7 +17,7 @@ from threading import Lock # Import plugins -from .rmf_cart_delivery import CartDelivery +from ...fleet_adapter_mir_actions.fleet_adapter_mir_actions.rmf_cart_delivery import CartDelivery # Parallel processing solution derived from diff --git a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/__init__.py b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/fleet_adapter_mir/fleet_adapter_mir/mir_action.py b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/mir_action.py similarity index 70% rename from fleet_adapter_mir/fleet_adapter_mir/mir_action.py rename to fleet_adapter_mir_actions/fleet_adapter_mir_actions/mir_action.py index e6ec961..62505bb 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/mir_action.py +++ b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/mir_action.py @@ -1,6 +1,6 @@ import json -from .mir_api import MirAPI, MirStatus, MiRStateCode +from ...fleet_adapter_mir.fleet_adapter_mir.mir_api import MirAPI, MirStatus, MiRStateCode class MirAction: @@ -10,31 +10,41 @@ def __init__( name, mir_api: MirAPI, update_handle, - actions: list[str], - missions_json: str | None, action_config: dict | None, ): self.node = node self.name = name self.api = mir_api self.update_handle = update_handle - self.actions = actions self.action_config = action_config + missions_json = self.action_config.get('missions_json') if missions_json: with open(missions_json, 'r') as g: - action_missions = json.load(g) + action_missions = json.load(g) + + # Check if these missions are already created on the robot + missions_created = True + for mission_name in action_missions.keys(): + if not mission_name in self.api.known_missions: + missions_created = False + break + if missions_created: + return + # Create these missions on the robot self.api.create_missions(action_missions) # Update mission actions stored in MirAPI for mission, mission_data in self.api.known_missions.items(): self.api.mission_actions[mission] = self.api.missions_mission_id_actions_get(mission_data['guid']) - def update_action(self): + # This will be called whenever an action has begun + def perform_action(self, category, description, execution): # To be populated in the plugins pass - def perform_action(self, category, description, execution): + # This will be called on every update to check on the action's current state + def update_action(self): # To be populated in the plugins pass diff --git a/fleet_adapter_mir/fleet_adapter_mir/rmf_cart_delivery.py b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py similarity index 78% rename from fleet_adapter_mir/fleet_adapter_mir/rmf_cart_delivery.py rename to fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py index 47f0c60..070f00e 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/rmf_cart_delivery.py +++ b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py @@ -6,36 +6,41 @@ import requests from urllib.error import HTTPError from .mir_action import MirAction -from .mir_api import MirAPI, MirStatus, MiRStateCode +from ...fleet_adapter_mir.fleet_adapter_mir.mir_api import MirAPI, MirStatus, MiRStateCode class PickupState(enum.IntEnum): - PICKUP_ALLOCATED = 0 - MOVE_REQUESTED = 1 - AT_PICKUP = 2 - DOCK_REQUESTED = 3 - DOCK_COMPLETED = 4 - PICKUP_REQUESTED = 5 - PICKUP_SUCCESS = 6 - WARNING_ALERT_PUBLISHED = 7 + PICKUP_INITIALIZED = 0 + PICKUP_ALLOCATED = 1 + MOVE_REQUESTED = 2 + AT_PICKUP = 3 + DOCK_REQUESTED = 4 + DOCK_COMPLETED = 5 + PICKUP_REQUESTED = 6 + PICKUP_SUCCESS = 7 TASK_CANCELLED = 8 +class Mission: + def __init__(self, queue_id: str, start_time: float): + self.queue_id = queue_id + self.start_time = start_time + + @dataclass class Pickup: state: PickupState pickup_lots: list[str] # contains either a single pickup lot or list of pickup lots cart_id: str execution: Any - mission_start_time: float - mission_queue_id: str + mission: Mission latching: bool @dataclass class Dropoff: execution: Any - mission_queue_id: str + mission: Mission class CartDelivery(MirAction): @@ -45,24 +50,18 @@ def __init__( name, mir_api, update_handle, - actions, - missions_json, action_config, - retrieve_mir_coordinates, # callback + retrieve_mir_coordinates # Function for plugin to retrieve information about how to convert between rmf and mir coordinates ): - MirAction.__init__(self, node, name, mir_api, update_handle, actions, - missions_json, action_config) - self.known_positions = self.api.known_positions + MirAction.__init__(self, node, name, mir_api, update_handle, action_config) - # Delivery related params - self.pickup: Pickup = None - self.dropoff: Dropoff = None + self.action: Pickup | Dropoff = None self.search_timeout = self.action_config.get('search_timeout', 60) # seconds # Useful robot adapter callbacks self.retrieve_mir_coordinates = retrieve_mir_coordinates - # Store the mission names to be used later + # Store the mission names to be used during the action self.dock_to_cart_mission = self.action_config['missions']['dock_to_cart'] self.pickup_mission = self.action_config['missions']['pickup'] self.dropoff_mission = self.action_config['missions']['dropoff'] @@ -75,75 +74,61 @@ def __init__( self.cart_marker_type_guid = self.api.docking_offsets_guid_get(self.action_config['marker_types']['cart']) self.update_footprint(self.robot_footprint_guid) - def update_action(self): - if self.pickup is not None: - if self.check_pickup(self.pickup): - self.pickup = None - if self.dropoff is not None: - if self.check_dropoff(self.dropoff): - self.dropoff = None - def perform_action(self, category, description, execution): - if category == 'delivery_pickup': - pickup_lot = description.get('pickup_lot') - cart_id = description.get('cart_id') - self.cart_pickup(execution, pickup_lot, cart_id) - elif category == 'delivery_dropoff': - self.node.get_logger().info(f'Received dropoff request!') - self.dropoff = Dropoff(execution=execution, mission_queue_id=None) - - def cancel_task(self, label: str = None): - def _cancel_success(): - if self.pickup: - self.pickup.state = PickupState.TASK_CANCELLED - def _cancel_fail(): - pass - self.cancel_current_task(_cancel_success, _cancel_fail, label) - - def cart_pickup(self, execution, pickup_lot: str, cart_id: str): - if self.pickup is not None: - # If there is an existing pickup, we'll replace it - if self.pickup.execution is not None and self.pickup.execution.okay(): - self.pickup.execution.finished() - self.pickup = None - - # Check if robot's latch is open - if self.is_latch_open(): - # Latch is open, unable to perform pickup - self.node.get_logger().info(f'Robot [{self.name}] latch is open, unable to perform pickup, cancelling task...') - self.cancel_task() - return + # Check that the perform action category matches + match category: + case 'delivery_pickup': + # Check if the robot's latch is currently open + if self.is_latch_open(): + # Latch is open, unable to perform pickup + self.node.get_logger().info(f'Robot [{self.name}] latch is open, unable to perform pickup, cancelling task...') + self.cancel_task() + return - self.node.get_logger().info(f'New pickup requested for robot [{self.name}]') + self.node.get_logger().info(f'New pickup requested for robot [{self.name}]') + self.pickup = Pickup( + state=PickupState.PICKUP_ALLOCATED, + pickup_lots=[description.get('pickup_lot')], # TODO(XY): Allow multiple pickups? + cart_id=description.get('cart_id'), + execution=execution, + mission=None, + latching=False + ) + case 'delivery_dropoff': + self.node.get_logger().info(f'Received dropoff request!') + self.dropoff = Dropoff( + execution=execution, + mission=None + ) + case _: + self.node.get_logger().info(f'Invalid perform action [{category}] passed to CartDelivery, ending action.') + execution.finished() - # TODO(XY): Allow multiple pickups? - pickup_lots = [pickup_lot] + def update_action(self): + # There should not be a pickup and dropoff being performed simultaneously at any given time, since actions are + # dispatched sequentially + if self.pickup: + return self.update_pickup(self.pickup) + elif self.dropoff: + return self.update_dropoff(self.dropoff) - self.pickup = Pickup( - state=PickupState.PICKUP_ALLOCATED, - pickup_lots=pickup_lots, - cart_id=cart_id, - execution=execution, - mission_start_time=None, - mission_queue_id=None, - latching=False - ) - return + return False - def check_pickup(self, pickup: Pickup): + def update_pickup(self, pickup: Pickup): # If this is a PerformAction pickup, check that the action is underway and valid if pickup.execution is not None and not pickup.execution.okay(): - self.node.get_logger().info(f'[{pickup.type}] action is killed/canceled.') + self.node.get_logger().info(f'[delivery_pickup] action is killed/canceled.') pickup.state = PickupState.TASK_CANCELLED # Start state machine check + now = self.node.get_clock().now().nanoseconds / 1e9 self.node.get_logger().debug(f'PickupState: {pickup.state.name}') match pickup.state: case PickupState.PICKUP_ALLOCATED: # Move to the first pickup place on the list pickup_lot = pickup.pickup_lots[0] self.node.get_logger().info(f'Requested to pickup cart at waypoint {pickup.state.name}') - if self.known_positions.get(pickup_lot) is None: + if self.api.known_positions.get(pickup_lot) is None: self.node.get_logger().info(f'Pickup Lot does not exist in MiR map, please resubmit.') self.cancel_task() pickup.state = PickupState.TASK_CANCELLED @@ -151,12 +136,12 @@ def check_pickup(self, pickup: Pickup): # Find the MiR coordinates of this pickup place mir_pose = self.retrieve_mir_coordinates(pickup_lot) - pickup.mission_queue_id = self.api.navigate(mir_pose) + pickup.mission = Mission(self.api.navigate(mir_pose), now) pickup.state = PickupState.MOVE_REQUESTED case PickupState.MOVE_REQUESTED: # Make sure that there is an rmf_move mission issued - if pickup.mission_queue_id is None: + if not pickup.mission: self.node.get_logger().info(f'Robot [{self.name}] is indicated to be at the MOVE_REQUESTED state but ' f'no mission queue ID stored for this pickup mission! Returning to PICKUP_ALLOCATED state.') pickup.state = PickupState.PICKUP_ALLOCATED @@ -164,9 +149,9 @@ def check_pickup(self, pickup: Pickup): # Robot has reached the pickup lot pickup_lot = pickup.pickup_lots[0] - if self.api.mission_completed(pickup.mission_queue_id): + if self.api.mission_completed(pickup.mission.queue_id): self.node.get_logger().info(f'Robot [{self.name}] has reached the pickup waypoint {pickup_lot}') - pickup.mission_queue_id = None + pickup.mission = None pickup.state = PickupState.AT_PICKUP return @@ -176,9 +161,9 @@ def check_pickup(self, pickup: Pickup): current_pose = self.api.status_get().state.position if self.dist(pickup_pose, current_pose) < self.action_config['pickup_dist_threshold']: # Delete the ongoing mission - self.api.mission_queue_id_delete(pickup.mission_queue_id) + self.api.mission_queue_id_delete(pickup.mission.queue_id) self.node.get_logger().info(f'Robot [{self.name}] is sufficiently near to the pickup waypoint {pickup_lot} for docking') - pickup.mission_queue_id = None + pickup.mission = None pickup.state = PickupState.AT_PICKUP case PickupState.AT_PICKUP: @@ -195,45 +180,40 @@ def check_pickup(self, pickup: Pickup): error_str = f'Mission {self.dock_to_cart_mission} not supported, ignoring' self.node.get_logger().error(error_str) return - pickup.mission_queue_id = mission_queue_id + pickup.mission = Mission(mission_queue_id, now) pickup.state = PickupState.DOCK_REQUESTED self.node.get_logger().info(f'Dock to cart mission requested with mission queue id {mission_queue_id}') case PickupState.DOCK_REQUESTED: # Make sure that there is an rmf_dock_to_cart mission issued - if pickup.mission_queue_id is None: + if not pickup.mission: self.node.get_logger().info(f'Robot [{self.name}] is indicated to be at the DOCK_REQUESTED state but ' f'no mission queue ID stored for this docking mission! Returning to AT_PICKUP state.') pickup.state = PickupState.AT_PICKUP return # Mission completed, move onto the next state - if self.api.mission_completed(pickup.mission_queue_id): - self.node.get_logger().info(f'Robot [{self.name}] dock to cart mission {pickup.mission_queue_id} completed or timed out.') - pickup.mission_queue_id = None - pickup.mission_start_time = None + if self.api.mission_completed(pickup.mission.queue_id): + self.node.get_logger().info(f'Robot [{self.name}] dock to cart mission {pickup.mission.queue_id} completed or timed out.') + pickup.mission = None pickup.state = PickupState.DOCK_COMPLETED return # Mission not yet completed, we check the timeout status to decide if we need to publish any alert - if pickup.mission_start_time is None: - pickup.mission_start_time = self.node.get_clock().now().nanoseconds / 1e9 - now = self.node.get_clock().now().nanoseconds / 1e9 - seconds_passed = now - pickup.mission_start_time + seconds_passed = now - pickup.mission.start_time # Publish update every 10 seconds just to monitor if round(seconds_passed)%10 == 0: self.node.get_logger().info(f'{round(seconds_passed)} seconds have passed since pickup mission requested.') # Mission timeout, cart not found if seconds_passed > self.search_timeout: # Delete mission from mir first - self.api.mission_queue_id_delete(pickup.mission_queue_id) + self.api.mission_queue_id_delete(pickup.mission.queue_id) # Regardless of whether the robot completed docking properly, we move to the next state to check - self.node.get_logger().info(f'Robot [{self.name}] dock to cart mission {pickup.mission_queue_id} timed out! ' + self.node.get_logger().info(f'Robot [{self.name}] dock to cart mission {pickup.mission.queue_id} timed out! ' f'Configured search timeout is {self.search_timeout} seconds.') + pickup.mission = None pickup.state = PickupState.DOCK_COMPLETED return case PickupState.DOCK_COMPLETED: - if pickup.mission_start_time is not None: - pickup.mission_start_time = None # Check if robot docked under the correct cart cart_check = self.is_correct_cart(pickup.cart_id) if cart_check: @@ -244,28 +224,31 @@ def check_pickup(self, pickup: Pickup): error_str = f'Mission {self.pickup_mission} not supported, ignoring' self.node.get_logger().error(error_str) return - pickup.mission_queue_id = mission_queue_id - pickup.mission_start_time = self.node.get_clock().now().nanoseconds / 1e9 + pickup.mission = Mission(mission_queue_id, now) pickup.latching = True self.node.get_logger().info(f'Robot [{self.name}] found the correct cart, pickup mission requested with mission queue id {mission_queue_id}') pickup.state = PickupState.PICKUP_REQUESTED elif cart_check is None: # If cart is missing, cancel this task self.node.get_logger().info(f'Robot [{self.name}] was unable to dock under any carts, please check that cart is present. Cancelling task.') + self.cancel_task() pickup.state = PickupState.TASK_CANCELLED else: # If cart is wrong, cancel this task also but after we exit from the lot self.node.get_logger().info(f'Robot [{self.name}] found the wrong cart, exiting lot and cancelling task.') self.exit_lot() + self.cancel_task() pickup.state = PickupState.TASK_CANCELLED case PickupState.PICKUP_REQUESTED: - if self.is_latch_open(): - # Latch successfully opened, indicate pickup as success + # Pickup mission completed + if self.api.mission_completed(pickup.mission.queue_id): pickup.state = PickupState.PICKUP_SUCCESS + pickup.mission = None pickup.latching = False # Update robot footprint to accommodate the cart size self.update_footprint(self.cart_footprint_guid) + # TODO(XY) consider doing a check for whether the latching time exceeds a configurable timeout case PickupState.PICKUP_SUCCESS: # Correct ID, we can end the delivery now @@ -278,11 +261,12 @@ def check_pickup(self, pickup: Pickup): case PickupState.TASK_CANCELLED: self.node.get_logger().info(f'Robot [{self.name}] is in pickup cancelled state.') # If some MiR mission is in progress, we abort it unless it is latching - if pickup.mission_queue_id is not None and not self.api.mission_completed(pickup.mission_queue_id): + if pickup.mission and not self.api.mission_completed(pickup.mission.queue_id): if pickup.latching: self.node.get_logger().info(f'Robot [{self.name}] is performing latching, cancelling task after this action is complete.') return False - self.api.mission_queue_id_delete(pickup.mission_queue_id) + self.api.mission_queue_id_delete(pickup.mission.queue_id) + pickup.mission = None # Clear any errors self.api.clear_error() self.api.status_put(state_id=MiRStateCode.READY) @@ -292,13 +276,13 @@ def check_pickup(self, pickup: Pickup): return False - def check_dropoff(self, dropoff: Dropoff): + def update_dropoff(self, dropoff: Dropoff): # Check if action is underway or cancelled if dropoff.execution is not None and not dropoff.execution.okay(): self.node.get_logger().info(f'Dropoff action is killed/canceled') # If cart release is in progress, we let it finish first - if dropoff.mission_queue_id is not None and not self.api.mission_completed(dropoff.mission_queue_id): + if dropoff.mission and not self.api.mission_completed(dropoff.mission.queue_id): return False # Task is cancelled and cart is done dropping off/mission is not yet queued anyway, @@ -309,30 +293,40 @@ def check_dropoff(self, dropoff: Dropoff): return True # No mission queued yet - if dropoff.mission_queue_id is None: + if dropoff.mission is None: assert self.dropoff_mission is not None mission_queue_id = self.api.queue_mission_by_name(self.dropoff_mission) if not mission_queue_id: error_str = f'Mission {self.dropoff_mission} not supported, ignoring' self.node.get_logger().error(error_str) return True - self.node.get_logger().info(f'Mission {self.dropoff_mission} added to queue.') - dropoff.mission_queue_id = mission_queue_id - self.node.get_logger().info(f'Dropoff mission requested with mission queue id {mission_queue_id}') + self.node.get_logger().info(f'Mission {self.dropoff_mission} added to queue for robot [{self.name}].') + now = self.node.get_clock().now().nanoseconds / 1e9 + dropoff.mission = Mission(mission_queue_id, + now) + self.node.get_logger().info(f'[{self.name}] Dropoff mission requested with mission queue id {mission_queue_id}') # Mission queued, check completion else: - if self.api.mission_completed(dropoff.mission_queue_id): - self.node.get_logger().info(f'Dropoff mission completed!') + if self.api.mission_completed(dropoff.mission.queue_id): + self.node.get_logger().info(f'[{self.name}] Dropoff mission completed!') # Update robot footprint self.update_footprint(self.robot_footprint_guid) if dropoff.execution is not None: dropoff.execution.finished() return True else: - self.node.get_logger().info(f'Dropoff mission in progress...') + self.node.get_logger().info(f'[{self.name}] Dropoff mission in progress...') return + def cancel_task(self, label: str = None): + def _cancel_success(): + if self.pickup: + self.pickup.state = PickupState.TASK_CANCELLED + def _cancel_fail(): + pass + self.cancel_current_task(_cancel_success, _cancel_fail, label) + def is_latch_open(self): # Checks if the robot's latch is open and carrying a cart # Return True if latch is open, else False diff --git a/fleet_adapter_mir_actions/package.xml b/fleet_adapter_mir_actions/package.xml new file mode 100644 index 0000000..b1cbb03 --- /dev/null +++ b/fleet_adapter_mir_actions/package.xml @@ -0,0 +1,15 @@ + + + + fleet_adapter_mir_actions + 0.1.0 + RMF fleet adapter actions for MiR robots + Xiyu + Apache License 2.0 + + rmf_fleet_adapter_python + + + ament_python + + diff --git a/fleet_adapter_mir_actions/resource/fleet_adapter_mir_actions b/fleet_adapter_mir_actions/resource/fleet_adapter_mir_actions new file mode 100644 index 0000000..e69de29 diff --git a/fleet_adapter_mir_actions/setup.cfg b/fleet_adapter_mir_actions/setup.cfg new file mode 100644 index 0000000..c18a730 --- /dev/null +++ b/fleet_adapter_mir_actions/setup.cfg @@ -0,0 +1,4 @@ +[develop] +script_dir=$base/lib/fleet_adapter_mir_actions +[install] +install_scripts=$base/lib/fleet_adapter_mir_actions diff --git a/fleet_adapter_mir_actions/setup.py b/fleet_adapter_mir_actions/setup.py new file mode 100644 index 0000000..e7e69bf --- /dev/null +++ b/fleet_adapter_mir_actions/setup.py @@ -0,0 +1,24 @@ +from setuptools import setup + +package_name = 'fleet_adapter_mir_actions' + +setup( + name=package_name, + version='0.1.0', + packages=[package_name], + data_files=[ + ('share/ament_index/resource_index/packages', + ['resource/' + package_name]), + ('share/' + package_name, ['package.xml']), + ], + install_requires=['setuptools'], + zip_safe=True, + maintainer='Xiyu', + maintainer_email='xiyu@openrobotics.org', + description='RMF fleet adapter actions for MiR robots', + license='Apache License 2.0', + entry_points={ + 'console_scripts': [ + ], + }, +) From 6b256dff5797be6eb689501587035c27cbf2f569 Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Mon, 26 Feb 2024 10:58:05 +0800 Subject: [PATCH 12/46] Use ActionFactory to create MirAction objects Signed-off-by: Xiyu Oh --- .../fleet_adapter_mir/robot_adapter_mir.py | 62 ++++++++++--------- fleet_adapter_mir/package.xml | 1 + .../fleet_adapter_mir_actions/mir_action.py | 44 +++++++++++-- .../rmf_cart_delivery.py | 38 +++++++++--- fleet_adapter_mir_actions/package.xml | 1 + 5 files changed, 102 insertions(+), 44 deletions(-) diff --git a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py index 652779e..9111271 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py +++ b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py @@ -15,9 +15,9 @@ from rclpy.duration import Duration from .mir_api import MirAPI, MirStatus, MiRStateCode from threading import Lock +import importlib -# Import plugins -from ...fleet_adapter_mir_actions.fleet_adapter_mir_actions.rmf_cart_delivery import CartDelivery +from fleet_adapter_mir_actions.fleet_adapter_mir_actions.mir_action import MirAction # Parallel processing solution derived from @@ -128,19 +128,8 @@ def __init__( self._make_callbacks(), ) - self.plugins = {} - # Available plugins: - if 'rmf_cart_delivery' in plugin_config: - self.plugins['rmf_cart_delivery'] = CartDelivery( - node=node, - name=name, - mir_api=self.api, - update_handle=self.update_handle, - actions=plugin_config['rmf_cart_delivery']['actions'], - missions_json=plugin_config['rmf_cart_delivery'].get('missions_json'), - action_config=plugin_config['rmf_cart_delivery'], - retrieve_mir_coordinates=self.retrieve_mir_coordinates) - # To be added on with other plugins + self.current_action: MirAction = None # Tracks the current ongoing action + self.plugin_config = plugin_config # Stores all the configured plugin action configs @property def activity(self): @@ -191,8 +180,11 @@ def request_update(self): self.update_rmf_finished(mission) # PerformAction related checks - for plugin in self.plugins.values(): - plugin.update_action() + if self.current_action: + if self.current_action.update_action(): + # This means that the action has ended, we can clear the current action object + self.node.get_logger().info(f'Robot [{self.name}] has completed its current action.') + self.current_action = None # Clear error on updates if status is not None and 'errors' in status.response and len(status.response['errors']) > 0: @@ -471,19 +463,33 @@ def request_localize(self, estimate, mission: MissionHandle): mission.set_mission_queue_id(mission_queue_id) def perform_action(self, category, description, execution): - for plugin in self.plugins.values(): - if category in plugin.actions: - plugin.perform_action(category, description, execution) + if self.current_action: + # Should not reach here, but we log an error anyway + self.node.get_logger().info(f'Robot is busy with another perform action! Ignoring new action [{category}]') + execution.finished() + return + + for plugin_name, config in self.plugin_config.items(): + actions = config['actions'] + if category in actions: + # Import relevant plugin + plugin = importlib.import_module(plugin_name, 'fleet_adapter_mir_actions') + # Create the relevant MirAction + action_obj = plugin.ActionFactory().make_action(self.node, + self.name, + self.api, + self.update_handle, + self.fleet_config, + config) + # Begin performing the plugin action + action_obj.perform_action(category, description, execution) + # Keep track of the current action + self.current_action = action_obj return - raise NotImplementedError - def retrieve_mir_coordinates(self, waypoint_name: str): - transform = self.fleet_config.transformations_to_robot_coordinates - transform_current_map = transform.get(self.current_map) - rmf_pose = self.fleet_config.graph.find_waypoint(waypoint_name).location - new_rmf_pose = np.array([rmf_pose[0], rmf_pose[1], 0.0]) - mir_pose = transform_current_map.apply(new_rmf_pose) - return mir_pose + # No relevant perform action found + self.node.get_logger().info(f'Perform action [{category}] was not configured for this fleet') + raise NotImplementedError def dist(self, A, B): assert(len(A) > 1) diff --git a/fleet_adapter_mir/package.xml b/fleet_adapter_mir/package.xml index 05774a9..f0866d4 100644 --- a/fleet_adapter_mir/package.xml +++ b/fleet_adapter_mir/package.xml @@ -9,6 +9,7 @@ Apache License 2.0 rmf_fleet_adapter_python + fleet_adapter_mir_actions ament_python diff --git a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/mir_action.py b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/mir_action.py index 62505bb..0ae6508 100644 --- a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/mir_action.py +++ b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/mir_action.py @@ -1,22 +1,30 @@ import json -from ...fleet_adapter_mir.fleet_adapter_mir.mir_api import MirAPI, MirStatus, MiRStateCode +from abc import ABC, abstractmethod +from typing import Callable +import rclpy +import rclpy.node as Node +import rmf_adapter.easy_full_control as rmf_easy +from fleet_adapter_mir.fleet_adapter_mir.mir_api import MirAPI -class MirAction: +class MirAction(ABC): def __init__( self, node, name, mir_api: MirAPI, update_handle, + fleet_config, action_config: dict | None, ): self.node = node self.name = name self.api = mir_api self.update_handle = update_handle + self.fleet_config = fleet_config self.action_config = action_config + self.actions = self.action_config.get('actions') missions_json = self.action_config.get('missions_json') if missions_json: @@ -39,16 +47,25 @@ def __init__( self.api.mission_actions[mission] = self.api.missions_mission_id_actions_get(mission_data['guid']) # This will be called whenever an action has begun - def perform_action(self, category, description, execution): + @abstractmethod + def perform_action(self, + category: str, + description: dict, + execution # rmf_fleet_adapter.ActionExecution + ): # To be populated in the plugins - pass + ... # This will be called on every update to check on the action's current state + @abstractmethod def update_action(self): # To be populated in the plugins - pass + ... - def cancel_current_task(self, cancel_success, cancel_fail, label): + def cancel_current_task(self, + cancel_success: Callable((), None), + cancel_fail: Callable((), None), + label: str = None): current_task_id = self.update_handle.more().current_task_id() self.node.get_logger().info(f'Cancel task requested for [{current_task_id}]') def _on_cancel(result: bool): @@ -59,3 +76,18 @@ def _on_cancel(result: bool): self.node.get_logger().info(f'Failed to cancel task [{current_task_id}]') cancel_fail() self.update_handle.more().cancel_task(current_task_id, [label], lambda result: _on_cancel(result)) + + +class MirActionFactory(ABC): + def __init__(self): + pass + + def make_action(self, + node: Node, + name: str, + mir_api: MirAPI, + update_handle, # rmf_fleet_adapter.RobotUpdateHandle + fleet_config: rmf_easy.FleetConfiguration, + action_config) -> MirAction: + # To be populated in the plugins + pass diff --git a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py index 070f00e..e1be006 100644 --- a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py +++ b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py @@ -1,12 +1,13 @@ import math from icecream import ic import enum +import numpy as np from typing import Any from dataclasses import dataclass import requests from urllib.error import HTTPError -from .mir_action import MirAction -from ...fleet_adapter_mir.fleet_adapter_mir.mir_api import MirAPI, MirStatus, MiRStateCode +from .mir_action import MirAction, MirActionFactory +from fleet_adapter_mir.fleet_adapter_mir.mir_api import MirAPI, MirStatus, MiRStateCode class PickupState(enum.IntEnum): @@ -43,6 +44,17 @@ class Dropoff: mission: Mission +class ActionFactory(MirActionFactory): + def make_action(self, + node, + name, + mir_api, + update_handle, + fleet_config, + action_config) -> MirAction: + return CartDelivery(node, name, mir_api, update_handle, fleet_config, action_config) + + class CartDelivery(MirAction): def __init__( self, @@ -50,17 +62,15 @@ def __init__( name, mir_api, update_handle, - action_config, - retrieve_mir_coordinates # Function for plugin to retrieve information about how to convert between rmf and mir coordinates - ): - MirAction.__init__(self, node, name, mir_api, update_handle, action_config) + fleet_config, + action_config + ): + MirAction.__init__(self, node, name, mir_api, update_handle, fleet_config, action_config) - self.action: Pickup | Dropoff = None + self.pickup: Pickup = None + self.dropoff: Dropoff = None self.search_timeout = self.action_config.get('search_timeout', 60) # seconds - # Useful robot adapter callbacks - self.retrieve_mir_coordinates = retrieve_mir_coordinates - # Store the mission names to be used during the action self.dock_to_cart_mission = self.action_config['missions']['dock_to_cart'] self.pickup_mission = self.action_config['missions']['pickup'] @@ -379,6 +389,14 @@ def update_footprint(self, ft_guid: str): ft_guid) return self.api.queue_mission_by_name(self.footprint_mission, ft_params) + def retrieve_mir_coordinates(self, waypoint_name: str): + transform = self.fleet_config.transformations_to_robot_coordinates + transform_current_map = transform.get(self.current_map) + rmf_pose = self.fleet_config.graph.find_waypoint(waypoint_name).location + new_rmf_pose = np.array([rmf_pose[0], rmf_pose[1], 0.0]) + mir_pose = transform_current_map.apply(new_rmf_pose) + return mir_pose + def dist(self, A, B): assert(len(A) > 1) assert(len(B) > 1) diff --git a/fleet_adapter_mir_actions/package.xml b/fleet_adapter_mir_actions/package.xml index b1cbb03..340b62f 100644 --- a/fleet_adapter_mir_actions/package.xml +++ b/fleet_adapter_mir_actions/package.xml @@ -8,6 +8,7 @@ Apache License 2.0 rmf_fleet_adapter_python + fleet_adapter_mir ament_python From a68026a19c4bd3a8e6e4c679a11071491aeef2ca Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Mon, 4 Mar 2024 11:03:53 +0800 Subject: [PATCH 13/46] Remove fleet_adapter_mir_actions as dependency in fleet_adapter_mir Signed-off-by: Xiyu Oh --- fleet_adapter_mir/fleet_adapter_mir/mir_api.py | 4 ++-- fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py | 7 ++++--- fleet_adapter_mir/package.xml | 2 +- 3 files changed, 7 insertions(+), 6 deletions(-) diff --git a/fleet_adapter_mir/fleet_adapter_mir/mir_api.py b/fleet_adapter_mir/fleet_adapter_mir/mir_api.py index 94fedb1..f2b53ae 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/mir_api.py +++ b/fleet_adapter_mir/fleet_adapter_mir/mir_api.py @@ -27,8 +27,8 @@ class MiRStateCode(enum.IntEnum): class MiRPositionTypes(enum.IntEnum): ROBOT = 0 SHELF = 5 - CHARGING_STATION = 7 - CHARGING_STATION_ENTRY = 8 + CHARGING_STATION = 20 + CHARGING_STATION_ENTRY = 21 CART = 22 LIFT = 25 LIFT_ENTRY = 26 diff --git a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py index 9111271..46f69ce 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py +++ b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py @@ -17,7 +17,7 @@ from threading import Lock import importlib -from fleet_adapter_mir_actions.fleet_adapter_mir_actions.mir_action import MirAction +# from fleet_adapter_mir_actions.fleet_adapter_mir_actions.mir_action import MirAction # Parallel processing solution derived from @@ -127,8 +127,9 @@ def __init__( rmf_config, self._make_callbacks(), ) - - self.current_action: MirAction = None # Tracks the current ongoing action + + # TODO(XY): move MirAction into this package + self.current_action = None # Tracks the current ongoing action self.plugin_config = plugin_config # Stores all the configured plugin action configs @property diff --git a/fleet_adapter_mir/package.xml b/fleet_adapter_mir/package.xml index f0866d4..d7298a7 100644 --- a/fleet_adapter_mir/package.xml +++ b/fleet_adapter_mir/package.xml @@ -9,7 +9,7 @@ Apache License 2.0 rmf_fleet_adapter_python - fleet_adapter_mir_actions + ament_python From ee6fbddf3c0fe52fb7c3e0f024a7f5fb5084a590 Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Mon, 4 Mar 2024 13:25:17 +0800 Subject: [PATCH 14/46] Move MirAction to fleet_adapter_mir pkg Signed-off-by: Xiyu Oh --- .../fleet_adapter_mir}/mir_action.py | 6 +++--- fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py | 7 +++---- fleet_adapter_mir/package.xml | 1 - .../fleet_adapter_mir_actions/rmf_cart_delivery.py | 2 +- 4 files changed, 7 insertions(+), 9 deletions(-) rename {fleet_adapter_mir_actions/fleet_adapter_mir_actions => fleet_adapter_mir/fleet_adapter_mir}/mir_action.py (94%) diff --git a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/mir_action.py b/fleet_adapter_mir/fleet_adapter_mir/mir_action.py similarity index 94% rename from fleet_adapter_mir_actions/fleet_adapter_mir_actions/mir_action.py rename to fleet_adapter_mir/fleet_adapter_mir/mir_action.py index 0ae6508..62d19a1 100644 --- a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/mir_action.py +++ b/fleet_adapter_mir/fleet_adapter_mir/mir_action.py @@ -5,7 +5,7 @@ import rclpy import rclpy.node as Node import rmf_adapter.easy_full_control as rmf_easy -from fleet_adapter_mir.fleet_adapter_mir.mir_api import MirAPI +from .mir_api import MirAPI class MirAction(ABC): @@ -63,8 +63,8 @@ def update_action(self): ... def cancel_current_task(self, - cancel_success: Callable((), None), - cancel_fail: Callable((), None), + cancel_success: Callable[[], None], + cancel_fail: Callable[[], None], label: str = None): current_task_id = self.update_handle.more().current_task_id() self.node.get_logger().info(f'Cancel task requested for [{current_task_id}]') diff --git a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py index 46f69ce..914b34b 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py +++ b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py @@ -17,7 +17,7 @@ from threading import Lock import importlib -# from fleet_adapter_mir_actions.fleet_adapter_mir_actions.mir_action import MirAction +from .mir_action import MirAction # Parallel processing solution derived from @@ -127,9 +127,8 @@ def __init__( rmf_config, self._make_callbacks(), ) - - # TODO(XY): move MirAction into this package - self.current_action = None # Tracks the current ongoing action + + self.current_action: MirAction = None # Tracks the current ongoing action self.plugin_config = plugin_config # Stores all the configured plugin action configs @property diff --git a/fleet_adapter_mir/package.xml b/fleet_adapter_mir/package.xml index d7298a7..05774a9 100644 --- a/fleet_adapter_mir/package.xml +++ b/fleet_adapter_mir/package.xml @@ -9,7 +9,6 @@ Apache License 2.0 rmf_fleet_adapter_python - ament_python diff --git a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py index e1be006..9951e1a 100644 --- a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py +++ b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py @@ -6,7 +6,7 @@ from dataclasses import dataclass import requests from urllib.error import HTTPError -from .mir_action import MirAction, MirActionFactory +from fleet_adapter_mir.fleet_adapter_mir.mir_action import MirAction, MirActionFactory from fleet_adapter_mir.fleet_adapter_mir.mir_api import MirAPI, MirStatus, MiRStateCode From bdc0218a48f331e20c92eee7906c207fad9b7b97 Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Thu, 28 Mar 2024 10:30:22 +0800 Subject: [PATCH 15/46] Working plugin module via importlib and modified dispatch_delivery task Signed-off-by: Xiyu Oh --- .../fleet_adapter_mir/robot_adapter_mir.py | 11 ++-- fleet_adapter_mir/setup.py | 1 + .../fleet_adapter_mir_actions}/mir_action.py | 2 +- .../rmf_cart_delivery.py | 48 +--------------- ...ispatch_pickup.py => dispatch_delivery.py} | 55 ++++++------------- fleet_adapter_mir_tasks/setup.py | 2 +- 6 files changed, 29 insertions(+), 90 deletions(-) rename {fleet_adapter_mir/fleet_adapter_mir => fleet_adapter_mir_actions/fleet_adapter_mir_actions}/mir_action.py (98%) rename fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/{dispatch_pickup.py => dispatch_delivery.py} (78%) diff --git a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py index 914b34b..1d0b96c 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py +++ b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py @@ -17,8 +17,6 @@ from threading import Lock import importlib -from .mir_action import MirAction - # Parallel processing solution derived from # https://stackoverflow.com/a/59385935 @@ -128,7 +126,7 @@ def __init__( self._make_callbacks(), ) - self.current_action: MirAction = None # Tracks the current ongoing action + self.current_action = None # Tracks the current ongoing action self.plugin_config = plugin_config # Stores all the configured plugin action configs @property @@ -326,8 +324,13 @@ def navigate(self, destination, execution): dock_json = json.loads(destination.dock) if dock_json.get('mission_name') == self.api.dock_and_charge_mission: self.mission = MissionHandle(execution, charger=destination.name) + # Clear the mission queue before requesting dock and charge + self.node.get_logger().info(f'Clearing mission queue for [{self.name}] before submitting a dock_and_charge mission.') + self.api.mission_queue_delete() else: self.mission = MissionHandle(execution) + mission_name = dock_json.get('mission_name') + self.node.get_logger().info(f'Requesting [{mission_name}] mission for [{self.name}].') self.request_dock(dock_json, self.mission) return @@ -473,7 +476,7 @@ def perform_action(self, category, description, execution): actions = config['actions'] if category in actions: # Import relevant plugin - plugin = importlib.import_module(plugin_name, 'fleet_adapter_mir_actions') + plugin = importlib.import_module(f'fleet_adapter_mir_actions.{plugin_name}') # Create the relevant MirAction action_obj = plugin.ActionFactory().make_action(self.node, self.name, diff --git a/fleet_adapter_mir/setup.py b/fleet_adapter_mir/setup.py index c8a5b73..8ccc66f 100644 --- a/fleet_adapter_mir/setup.py +++ b/fleet_adapter_mir/setup.py @@ -20,6 +20,7 @@ entry_points={ 'console_scripts': [ 'fleet_adapter_mir=fleet_adapter_mir.fleet_adapter_mir:main', + 'rmf_cart_delivery=fleet_adapter_mir.rmf_cart_delivery:CartDelivery', ], }, ) diff --git a/fleet_adapter_mir/fleet_adapter_mir/mir_action.py b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/mir_action.py similarity index 98% rename from fleet_adapter_mir/fleet_adapter_mir/mir_action.py rename to fleet_adapter_mir_actions/fleet_adapter_mir_actions/mir_action.py index 62d19a1..0576a7a 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/mir_action.py +++ b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/mir_action.py @@ -5,7 +5,7 @@ import rclpy import rclpy.node as Node import rmf_adapter.easy_full_control as rmf_easy -from .mir_api import MirAPI +from fleet_adapter_mir.mir_api import MirAPI class MirAction(ABC): diff --git a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py index 9951e1a..abf23d4 100644 --- a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py +++ b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py @@ -6,8 +6,8 @@ from dataclasses import dataclass import requests from urllib.error import HTTPError -from fleet_adapter_mir.fleet_adapter_mir.mir_action import MirAction, MirActionFactory -from fleet_adapter_mir.fleet_adapter_mir.mir_api import MirAPI, MirStatus, MiRStateCode +from fleet_adapter_mir_actions.mir_action import MirAction, MirActionFactory +from fleet_adapter_mir.mir_api import MirAPI, MirStatus, MiRStateCode class PickupState(enum.IntEnum): @@ -97,7 +97,7 @@ def perform_action(self, category, description, execution): self.node.get_logger().info(f'New pickup requested for robot [{self.name}]') self.pickup = Pickup( - state=PickupState.PICKUP_ALLOCATED, + state=PickupState.AT_PICKUP, pickup_lots=[description.get('pickup_lot')], # TODO(XY): Allow multiple pickups? cart_id=description.get('cart_id'), execution=execution, @@ -134,48 +134,6 @@ def update_pickup(self, pickup: Pickup): now = self.node.get_clock().now().nanoseconds / 1e9 self.node.get_logger().debug(f'PickupState: {pickup.state.name}') match pickup.state: - case PickupState.PICKUP_ALLOCATED: - # Move to the first pickup place on the list - pickup_lot = pickup.pickup_lots[0] - self.node.get_logger().info(f'Requested to pickup cart at waypoint {pickup.state.name}') - if self.api.known_positions.get(pickup_lot) is None: - self.node.get_logger().info(f'Pickup Lot does not exist in MiR map, please resubmit.') - self.cancel_task() - pickup.state = PickupState.TASK_CANCELLED - return - - # Find the MiR coordinates of this pickup place - mir_pose = self.retrieve_mir_coordinates(pickup_lot) - pickup.mission = Mission(self.api.navigate(mir_pose), now) - pickup.state = PickupState.MOVE_REQUESTED - - case PickupState.MOVE_REQUESTED: - # Make sure that there is an rmf_move mission issued - if not pickup.mission: - self.node.get_logger().info(f'Robot [{self.name}] is indicated to be at the MOVE_REQUESTED state but ' - f'no mission queue ID stored for this pickup mission! Returning to PICKUP_ALLOCATED state.') - pickup.state = PickupState.PICKUP_ALLOCATED - return - - # Robot has reached the pickup lot - pickup_lot = pickup.pickup_lots[0] - if self.api.mission_completed(pickup.mission.queue_id): - self.node.get_logger().info(f'Robot [{self.name}] has reached the pickup waypoint {pickup_lot}') - pickup.mission = None - pickup.state = PickupState.AT_PICKUP - return - - # If the robot is relatively close to the pickup lot, we also consider it to be at pickup - # and allow the dock_to_cart mission to position the robot in front of the cart - pickup_pose = self.retrieve_mir_coordinates(pickup_lot) - current_pose = self.api.status_get().state.position - if self.dist(pickup_pose, current_pose) < self.action_config['pickup_dist_threshold']: - # Delete the ongoing mission - self.api.mission_queue_id_delete(pickup.mission.queue_id) - self.node.get_logger().info(f'Robot [{self.name}] is sufficiently near to the pickup waypoint {pickup_lot} for docking') - pickup.mission = None - pickup.state = PickupState.AT_PICKUP - case PickupState.AT_PICKUP: # Send rmf_dock_to_cart mission assert self.dock_to_cart_mission is not None diff --git a/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_pickup.py b/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_delivery.py similarity index 78% rename from fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_pickup.py rename to fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_delivery.py index bd310dc..3fd951c 100644 --- a/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_pickup.py +++ b/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_delivery.py @@ -104,61 +104,38 @@ def __init__(self, argv=sys.argv): # Define task request description with phases description = {} # task_description_Compose.json - description["category"] = "delivery_pickup" + description["category"] = "rmf_cart_delivery" description["phases"] = [] - # Set up cancellation behavior - on_cancel = [] - emergency_lots = [] - if self.args.emergency_lots: - for lot in self.args.emergency_lots: - emergency_lots.append({"waypoint": lot}) - cancellation_desc = { - "one_of": emergency_lots, - "constraints": [{ - "category": "prefer_same_map", - "description": "some description" - }] - } - cancellation_activities = [] - cancellation_activities.append({"category": "go_to_place", - "description": cancellation_desc}) - cancellation_activities.append({"category": "perform_action", - "description": { - "unix_millis_action_duration_estimate": 60000, - "category": "delivery_dropoff", - "description": {} - }}) - on_cancel.append( - {"category": "sequence", - "description": cancellation_activities}) - # Pickup activity - pickup_activity = [] - pickup_activity.append({"category": "go_to_place", - "description": self.args.pickup_lot}) - pickup_activity.append({"category": "perform_action", + go_to_pickup_activity = [{ + "category": "go_to_place", + "description": self.args.go_to + }] + description["phases"].append( + {"activity": {"category": "sequence", + "description": {"activities": go_to_pickup_activity}}}) + pickup_action_activity = [{"category": "perform_action", "description": { "unix_millis_action_duration_estimate": 60000, - "category": self.args.pickup_type, + "category": 'delivery_pickup', "description": { "cart_id": self.args.cart_id, "pickup_lot": self.args.pickup_lot - }}}) + }}}] description["phases"].append( {"activity": {"category": "sequence", - "description": {"activities": pickup_activity}}}) + "description": {"activities": pickup_action_activity}}}) # GoToPlace activity - go_to_place_activity = [{ + go_to_dropoff_activity = [{ "category": "go_to_place", "description": self.args.dropoff_lot }] description["phases"].append( {"activity": {"category": "sequence", - "description": {"activities": go_to_place_activity}}, - "on_cancel": on_cancel}) + "description": {"activities": go_to_dropoff_activity}}}) # Dropoff activity - dropoff_activity = [{ + dropoff_action_activity = [{ "category": "perform_action", "description": { "unix_millis_action_duration_estimate": 60000, @@ -168,7 +145,7 @@ def __init__(self, argv=sys.argv): }] description["phases"].append( {"activity": {"category": "sequence", - "description": {"activities": dropoff_activity}}}) + "description": {"activities": dropoff_action_activity}}}) # Consolidate request["description"] = description payload["request"] = request diff --git a/fleet_adapter_mir_tasks/setup.py b/fleet_adapter_mir_tasks/setup.py index 302fba9..2502dbf 100644 --- a/fleet_adapter_mir_tasks/setup.py +++ b/fleet_adapter_mir_tasks/setup.py @@ -19,7 +19,7 @@ license='Apache License 2.0', entry_points={ 'console_scripts': [ - 'dispatch_pickup = fleet_adapter_mir_tasks.dispatch_pickup:main' + 'dispatch_delivery = fleet_adapter_mir_tasks.dispatch_delivery:main' ], }, ) From bc241bb06e808a5c1d9e87005bda4950d6f081b3 Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Thu, 28 Mar 2024 11:02:37 +0800 Subject: [PATCH 16/46] Rename actions arg parsed to fleet_adapter_mir to rmf_missions Signed-off-by: Xiyu Oh --- configs/mir_config.yaml | 6 +++--- fleet_adapter_mir/README.md | 9 +++------ .../fleet_adapter_mir/fleet_adapter_mir.py | 13 +++++++------ .../fleet_adapter_mir_tasks/dispatch_delivery.py | 2 -- 4 files changed, 13 insertions(+), 17 deletions(-) diff --git a/configs/mir_config.yaml b/configs/mir_config.yaml index 1de4059..3460bbf 100644 --- a/configs/mir_config.yaml +++ b/configs/mir_config.yaml @@ -27,9 +27,9 @@ conversions: [1.0, 1.0], [1.0, 0.0]] - # RMF to MIR map names maps: - L1: "Level 1" # Map name stored on MiR + # "RMF map name": "Map name stored on MiR" + L1: "Level 1" L2: "Level 2" missions: @@ -80,7 +80,7 @@ rmf_fleet: delivery: True clean: False finishing_request: "charge" # [park, charge, nothing] - actions: ["delivery_pickup", "delivery_dropoff"] + actions: ["rmf_cart_delivery", "delivery_pickup", "delivery_dropoff"] robots: mir_1: charger: "Charger_1" diff --git a/fleet_adapter_mir/README.md b/fleet_adapter_mir/README.md index a70dc16..6ae44e6 100644 --- a/fleet_adapter_mir/README.md +++ b/fleet_adapter_mir/README.md @@ -59,7 +59,7 @@ An example configuration file, `mir_config.yaml` has been provided. It has been **Chargers** -To use the `rmf_dock_and_charge` mission for charging, you may provide a description similar to the following when adding a `dock_name` to the charging point in your building map yaml/navigation graph: +To use the `rmf_dock_and_charge` mission for charging, use the traffic-editor to set the `dock_name` property of your charging point to a json description like the following: ```json {"description": {"end_waypoint": "charger_name"}, "mission_name": "rmf_dock_and_charge"} ``` @@ -68,11 +68,7 @@ Where you replace `end_waypoint` with the name of your MiR charger. **MiR positions** -For more accurate robot maneuver, you may wish to send the MiR to a Robot Position instead of using coordinates. For such waypoints, you can provide a `dock_name` with the `rmf_move_to_position` mission specified: -```json -{"description": {"end_waypoint": "waypoint_name"}, "mission_name": "rmf_move_to_position"} -``` - +Upon launch, the MiR fleet adapter recognizes MiR positions with identical names to RMF waypoints to be the same location. Hence, when a navigation command is submitted for the robot to a specific waypoint, if this waypoint name also exists as a robot position on the MiR, the fleet adapter would send it directly to the MiR position even if the coordinates are different. ### Plugins @@ -92,6 +88,7 @@ Some relevant MiR missions (docking, exit, update footprint) will be automatical - `rmf_dock_to_cart`: Docks robot under the cart - `rmf_exit_lot`: Calls the robot to exit from under the cart - `rmf_update_footprint`: Updates the robot footprint + They are defined and stored in the `rmf_cart_missions.json` file and do not require any further configuration. However, since there are various types of latching methods available for different MiR models, users will need to set up their custom pickup and dropoff missions on the MiR: diff --git a/fleet_adapter_mir/fleet_adapter_mir/fleet_adapter_mir.py b/fleet_adapter_mir/fleet_adapter_mir/fleet_adapter_mir.py index ebf082f..d4cd279 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/fleet_adapter_mir.py +++ b/fleet_adapter_mir/fleet_adapter_mir/fleet_adapter_mir.py @@ -184,9 +184,10 @@ def main(argv=sys.argv): parser.add_argument("-c", "--config_file", type=str, required=True, help="Input config.yaml file to process") parser.add_argument("-n", "--nav_graph", type=str, required=True, - help="Path to the nav_graph for this fleet adapter") - parser.add_argument("-a", "--actions", type=str, required=False, default='', - help="Path to the RMF mission actions to be created") + help="Path to the nav_graph for this fleet adapter") + parser.add_argument("-m", "--rmf_missions", type=str, + required=False, default='', + help="Path to the RMF missions to be created on robot") parser.add_argument("-m", "--mock", action='store_true', help="Init a mock adapter instead " "(does not require a schedule node, " @@ -199,7 +200,7 @@ def main(argv=sys.argv): config_path = args.config_file nav_graph_path = args.nav_graph - actions_path = args.actions + missions_path = args.rmf_missions fleet_config = rmf_easy.FleetConfiguration.from_config_files( config_path, nav_graph_path @@ -209,10 +210,10 @@ def main(argv=sys.argv): with open(config_path, 'r') as f: config_yaml = yaml.safe_load(f) - if actions_path == '': + if missions_path == '': rmf_missions = None else: - with open(actions_path, 'r') as g: + with open(missions_path, 'r') as g: rmf_missions = json.load(g) dry_run = args.dry_run # For testing diff --git a/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_delivery.py b/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_delivery.py index 3fd951c..b21c35c 100644 --- a/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_delivery.py +++ b/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_delivery.py @@ -51,8 +51,6 @@ def __init__(self, argv=sys.argv): type=str, help='Name of pickup lot') parser.add_argument('-d', '--dropoff_lot', required=True, type=str, help='Name of dropoff lot') - parser.add_argument('-e', '--emergency_lots', required=False, default='', - type=str, nargs='+', help='Emergency waypoints') parser.add_argument('-st', '--start_time', help='Start time from now in secs, default: 0', type=int, default=0) From 3d855a369908d12fccec8cf0783fe00946d06039 Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Thu, 28 Mar 2024 11:09:37 +0800 Subject: [PATCH 17/46] Add module key to config Signed-off-by: Xiyu Oh --- configs/mir_config.yaml | 4 +++- fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py | 3 ++- 2 files changed, 5 insertions(+), 2 deletions(-) diff --git a/configs/mir_config.yaml b/configs/mir_config.yaml index 3460bbf..426f01a 100644 --- a/configs/mir_config.yaml +++ b/configs/mir_config.yaml @@ -96,7 +96,9 @@ rmf_fleet: plugins: rmf_cart_delivery: - actions: ["delivery_pickup", "delivery_dropoff"] + module: "fleet_adapter_mir_actions.rmf_cart_delivery" + class: "CartDelivery" + actions: ["rmf_cart_delivery", "delivery_pickup", "delivery_dropoff"] missions: dock_to_cart: "rmf_dock_to_cart" # Name of MiR mission for robot to dock under a cart - to be created by fleet adapter upon launch pickup: "rmf_pickup_cart" # Name of MiR mission for robot to latch onto a cart - to be created and filled in by user diff --git a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py index 1d0b96c..611f894 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py +++ b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py @@ -476,7 +476,8 @@ def perform_action(self, category, description, execution): actions = config['actions'] if category in actions: # Import relevant plugin - plugin = importlib.import_module(f'fleet_adapter_mir_actions.{plugin_name}') + module = config['module'] + plugin = importlib.import_module(module) # Create the relevant MirAction action_obj = plugin.ActionFactory().make_action(self.node, self.name, From 598a2ee4d6d050b9d78bf8aa9b8351943244fa07 Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Tue, 16 Apr 2024 20:38:44 +0800 Subject: [PATCH 18/46] Remove footprint update from cart delivery plugin and cancel task if pickup pos is not found Signed-off-by: Xiyu Oh --- .../rmf_cart_delivery.py | 27 ++++++++++--------- 1 file changed, 14 insertions(+), 13 deletions(-) diff --git a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py index abf23d4..fafa836 100644 --- a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py +++ b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py @@ -76,13 +76,10 @@ def __init__( self.pickup_mission = self.action_config['missions']['pickup'] self.dropoff_mission = self.action_config['missions']['dropoff'] self.exit_mission = self.action_config['missions']['exit_lot'] - self.footprint_mission = self.action_config['missions']['update_footprint'] + self.footprint_mission = self.action_config['missions'].get('update_footprint') # Optional - # Initialize footprints and marker types - self.robot_footprint_guid = self.api.footprints_guid_get(self.action_config['footprints']['robot']) - self.cart_footprint_guid = self.api.footprints_guid_get(self.action_config['footprints']['cart']) + # Initialize cart marker type self.cart_marker_type_guid = self.api.docking_offsets_guid_get(self.action_config['marker_types']['cart']) - self.update_footprint(self.robot_footprint_guid) def perform_action(self, category, description, execution): # Check that the perform action category matches @@ -138,11 +135,16 @@ def update_pickup(self, pickup: Pickup): # Send rmf_dock_to_cart mission assert self.dock_to_cart_mission is not None current_wp_name = pickup.pickup_lots[0] - cart_marker_guid = self.api.known_positions[current_wp_name]['guid'] + mir_pos = self.api.known_positions.get(current_wp_name) + if not mir_pos: + self.node.get_logger().info(f'No shelf position [{mir_pos}] found on robot [{self.name}], cancelling task') + self.cancel_task() + pickup.state = PickupState.TASK_CANCELLED + return + cart_marker_guid = mir_pos['guid'] cart_marker_param = self.api.get_mission_params_with_value(self.dock_to_cart_mission, 'docking', 'cart_marker', cart_marker_guid) marker_type_param = self.api.get_mission_params_with_value(self.dock_to_cart_mission, 'docking', 'cart_marker_type', self.cart_marker_type_guid) mission_params = cart_marker_param + marker_type_param - self.update_footprint(self.robot_footprint_guid) mission_queue_id = self.api.queue_mission_by_name(self.dock_to_cart_mission, mission_params) if not mission_queue_id: error_str = f'Mission {self.dock_to_cart_mission} not supported, ignoring' @@ -214,9 +216,6 @@ def update_pickup(self, pickup: Pickup): pickup.state = PickupState.PICKUP_SUCCESS pickup.mission = None pickup.latching = False - # Update robot footprint to accommodate the cart size - self.update_footprint(self.cart_footprint_guid) - # TODO(XY) consider doing a check for whether the latching time exceeds a configurable timeout case PickupState.PICKUP_SUCCESS: # Correct ID, we can end the delivery now @@ -279,7 +278,6 @@ def update_dropoff(self, dropoff: Dropoff): if self.api.mission_completed(dropoff.mission.queue_id): self.node.get_logger().info(f'[{self.name}] Dropoff mission completed!') # Update robot footprint - self.update_footprint(self.robot_footprint_guid) if dropoff.execution is not None: dropoff.execution.finished() return True @@ -317,13 +315,13 @@ def is_correct_cart(self, cart_id: str): # ------------------------ # IMPLEMENT YOUR CODE HERE # ------------------------ - return None + return True + # return None def exit_lot(self): if not self.api.connected: return None # Set footprint to robot footprint before exiting lot - self.update_footprint(self.robot_footprint_guid) return self.api.queue_mission_by_name(self.exit_mission) def release_cart(self): @@ -340,7 +338,10 @@ def release_cart(self): self.node.get_logger().info(f'Cart detected above robot [{self.name}] during a release call, exiting lot...') self.exit_lot() + # Optional function for updating robot footprint by providing footprint guid def update_footprint(self, ft_guid: str): + if not self.footprint_mission: + return ft_params = self.api.get_mission_params_with_value(self.footprint_mission, 'set_footprint', 'footprint', From 51585960373b4f49149bde01241291063f7b55eb Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Thu, 18 Apr 2024 10:37:35 +0800 Subject: [PATCH 19/46] Configurable transformation params Signed-off-by: Xiyu Oh --- .../fleet_adapter_mir/fleet_adapter_mir.py | 37 +++++++++++++------ .../fleet_adapter_mir/robot_adapter_mir.py | 3 +- 2 files changed, 27 insertions(+), 13 deletions(-) diff --git a/fleet_adapter_mir/fleet_adapter_mir/fleet_adapter_mir.py b/fleet_adapter_mir/fleet_adapter_mir/fleet_adapter_mir.py index d4cd279..5713135 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/fleet_adapter_mir.py +++ b/fleet_adapter_mir/fleet_adapter_mir/fleet_adapter_mir.py @@ -55,19 +55,32 @@ def sanitise_dict(dictionary, inplace=False, recursive=False): def compute_transforms(level, coords, node=None): """Get transforms between RMF and MIR coordinates.""" - rmf_coords = coords['rmf'] - mir_coords = coords['mir'] - tf = nudged.estimate(rmf_coords, mir_coords) - if node: - mse = nudged.estimate_error(tf, rmf_coords, mir_coords) - node.get_logger().info( - f"Transformation error estimate for {level}: {mse}" - ) + rotation = None + scale = None + translation = None + if 'rmf' in coords: + rmf_coords = coords['rmf'] + mir_coords = coords['mir'] + tf = nudged.estimate(rmf_coords, mir_coords) + if node: + mse = nudged.estimate_error(tf, rmf_coords, mir_coords) + node.get_logger().info( + f"Transformation error estimate for {level}: {mse}" + ) + rotation = tf.get_rotation() + scale = tf.get_scale() + translation = tf.get_translation() + elif 'rotation' in coords: + rotation = coords['rotation'] + scale = coords['scale'] + translation = coords['translation'] + else: + return None return Transformation( - tf.get_rotation(), - tf.get_scale(), - tf.get_translation() + rotation, + scale, + translation ) @@ -185,7 +198,7 @@ def main(argv=sys.argv): help="Input config.yaml file to process") parser.add_argument("-n", "--nav_graph", type=str, required=True, help="Path to the nav_graph for this fleet adapter") - parser.add_argument("-m", "--rmf_missions", type=str, + parser.add_argument("-r", "--rmf_missions", type=str, required=False, default='', help="Path to the RMF missions to be created on robot") parser.add_argument("-m", "--mock", action='store_true', diff --git a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py index 611f894..a9c62f3 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py +++ b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py @@ -438,9 +438,10 @@ def localize(self, estimate, execution): @parallel def request_localize(self, estimate, mission: MissionHandle): + retry_count = 10 count = 0 mission_queue_id = None - while count < self.retries and not mission_queue_id: + while count < retry_count and not mission_queue_id: count += 1 try: mission_queue_id = self.api.localize( From 6063200566e90ca3afda5cd637bf99e25d7898b9 Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Fri, 10 May 2024 15:59:47 +0800 Subject: [PATCH 20/46] Add in retry mechanism for navigate cmds Signed-off-by: Xiyu Oh --- .../fleet_adapter_mir/robot_adapter_mir.py | 34 ++++++++++++++++--- 1 file changed, 29 insertions(+), 5 deletions(-) diff --git a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py index a9c62f3..e1c67d4 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py +++ b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py @@ -376,12 +376,36 @@ def request_navigate( mission_handle: MissionHandle ): mission_queue_id = None - if destination.name: - self.node.get_logger().info(f'[{self.name}] is going to MiR position {destination.name}') - mission_queue_id = self.api.go_to_known_position(destination.name) + retry_count = 10 + count = 0 + while count < retry_count and not mission_queue_id: + try: + if destination.name: + self.node.get_logger().info(f'[{self.name}] is going to MiR position {destination.name}') + mission_queue_id = self.api.go_to_known_position(destination.name) + if mission_queue_id is None: + self.node.get_logger().info(f'[{self.name}] is going to MiR coordinates [{destination.position}]') + mission_queue_id = self.api.navigate(destination.position) + else: + self.node.get_logger().info( + f'[{self.name}] Move mission cannot be queued' + f'(no mission queue id provided), retrying...' + ) + except Exception as err: + self.node.get_logger().info( + f'[{self.name}] Failed to request robot to move to ' + f'destination: {err}. Retrying... ({count})' + ) + count += 1 + time.sleep(1) + if mission_queue_id is None: - self.node.get_logger().info(f'[{self.name}] is going to MiR coordinates [{destination.position}]') - mission_queue_id = self.api.navigate(destination.position) + self.node.get_logger().info( + f'[{self.name}] Failed to request robot to move to destination.' + f' Maximum request navigate retries exceeded!') + mission_handle.execution.finished() + return + mission_handle.set_mission_queue_id(mission_queue_id) @parallel From 51d7fba94290bebd1b6c1e8891ae4ffa0d40a840 Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Wed, 15 May 2024 14:14:20 +0800 Subject: [PATCH 21/46] Add retry mechanism for dock and go to known position Signed-off-by: Xiyu Oh --- .../fleet_adapter_mir/robot_adapter_mir.py | 160 ++++++++++++++++-- 1 file changed, 144 insertions(+), 16 deletions(-) diff --git a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py index e1c67d4..584f269 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py +++ b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py @@ -375,22 +375,39 @@ def request_navigate( destination, mission_handle: MissionHandle ): + # Used for exiting while loop early in the event that for whatever + # reason the robot starts performing a different mission, while the + # original navigation mission is ongoing + navigation_mission_identifier = mission_handle.execution.identifier mission_queue_id = None - retry_count = 10 count = 0 + retry_count = 10 while count < retry_count and not mission_queue_id: + if (navigation_mission_identifier != + mission_handle.execution.identifier): + self.node.get_logger().info( + f'[{self.name}] MissionHandle has changed to ' + f'{mission_handle.execution.identifier}, interrupting ' + f'navigation mission {navigation_mission_identifier}. ' + f'Stopping original navigation mission loop.') + break + try: if destination.name: - self.node.get_logger().info(f'[{self.name}] is going to MiR position {destination.name}') - mission_queue_id = self.api.go_to_known_position(destination.name) + self.node.get_logger().info( + f'[{self.name}] is going to MiR position ' + f'{destination.name}') + mission_queue_id = self.api.go_to_known_position( + destination.name) if mission_queue_id is None: - self.node.get_logger().info(f'[{self.name}] is going to MiR coordinates [{destination.position}]') + self.node.get_logger().info( + f'[{self.name}] is going to MiR coordinates ' + f'[{destination.position}]') mission_queue_id = self.api.navigate(destination.position) else: self.node.get_logger().info( - f'[{self.name}] Move mission cannot be queued' - f'(no mission queue id provided), retrying...' - ) + f'[{self.name}] Move mission cannot be queued ' + f'(no mission queue id provided), retrying...') except Exception as err: self.node.get_logger().info( f'[{self.name}] Failed to request robot to move to ' @@ -399,6 +416,16 @@ def request_navigate( count += 1 time.sleep(1) + if (mission_queue_id is None and + navigation_mission_identifier != + mission_handle.execution.identifier): + self.node.get_logger().info( + f'[{self.name}] Failed to request robot to move to destination.' + f' Navigation step {navigation_mission_identifier} interrupted ' + f'by new mission {mission_handle.execution.identifier}.' + ) + return + if mission_queue_id is None: self.node.get_logger().info( f'[{self.name}] Failed to request robot to move to destination.' @@ -414,7 +441,56 @@ def request_go_to_known_position( position_name: str, mission_handle: MissionHandle ): - mission_queue_id = self.api.go_to_known_position(position_name) + # Used for exiting while loop early in the event that for whatever + # reason the robot starts performing a different mission, while the + # original navigation mission is ongoing + navigation_mission_identifier = mission_handle.execution.identifier + mission_queue_id = None + count = 0 + retry_count = 10 + while count < retry_count and not mission_queue_id: + if (navigation_mission_identifier != + mission_handle.execution.identifier): + self.node.get_logger().info( + f'[{self.name}] MissionHandle has changed to ' + f'{mission_handle.execution.identifier}, interrupting ' + f'navigation mission {navigation_mission_identifier}.' + f' Stopping original navigation mission loop.') + break + + try: + mission_queue_id = self.api.go_to_known_position(position_name) + if mission_queue_id is None: + self.node.get_logger().info( + f'[{self.name}] Move to known positions mission cannot ' + f'be queued (no mission queue id provided), retrying...' + ) + except Exception as err: + self.node.get_logger().info( + f'[{self.name}] Failed to request robot to move to known' + f'position: {err}. Retrying... ({count})' + ) + count += 1 + time.sleep(1) + + if (mission_queue_id is None and + navigation_mission_identifier != + mission_handle.execution.identifier): + self.node.get_logger().info( + f'[{self.name}] Failed to request robot to move to known ' + f'position. Navigation step {navigation_mission_identifier} ' + f'interrupted by new mission ' + f'{mission_handle.execution.identifier}.' + ) + return + + if mission_queue_id is None: + self.node.get_logger().info( + f'[{self.name}] Failed to request robot to move to known ' + f'position. Maximum request navigate retries exceeded!') + mission_handle.execution.finished() + return + mission_handle.set_mission_queue_id(mission_queue_id) @@ -426,15 +502,67 @@ def request_dock( ): if not ('description' in docking_points): return - self.node.get_logger().info(f'Requested dock mission for [{self.name}]: {docking_points}') - end_waypoint = docking_points['description']['end_waypoint'] - if 'start_waypoint' in docking_points['description']: - start_waypoint = docking_points['description']['start_waypoint'] - else: - start_waypoint = None - mission_name = docking_points['mission_name'] + # Used for exiting while loop early in the event that for whatever + # reason the robot starts performing a different mission, while the + # original navigation mission is ongoing + docking_mission_identifier = mission_handle.execution.identifier + mission_queue_id = None + count = 0 + retry_count = 10 + while count < retry_count and not mission_queue_id: + if (docking_mission_identifier != + mission_handle.execution.identifier): + self.node.get_logger().info( + f'[{self.name}] MissionHandle has changed to ' + f'{mission_handle.execution.identifier}, interrupting ' + f'navigation mission {docking_mission_identifier}. ' + f'Stopping original docking mission loop.') + break + + try: + self.node.get_logger().info( + f'Requested dock mission for [{self.name}]: ' + f'{docking_points}') + end_waypoint = docking_points['description']['end_waypoint'] + if 'start_waypoint' in docking_points['description']: + start_waypoint = \ + docking_points['description']['start_waypoint'] + else: + start_waypoint = None + mission_name = docking_points['mission_name'] + + mission_queue_id = self.api.dock(mission_name, + start_waypoint, + end_waypoint) + if mission_queue_id is None: + self.node.get_logger().info( + f'[{self.name}] Dock mission cannot be queued ' + f'(no mission queue id provided), retrying...') + except Exception as err: + self.node.get_logger().info( + f'[{self.name}] Failed to request robot to dock to ' + f'destination: {err}. Retrying... ({count})' + ) + count += 1 + time.sleep(1) + + if (mission_queue_id is None and + docking_mission_identifier != + mission_handle.execution.identifier): + self.node.get_logger().info( + f'[{self.name}] Failed to request robot to dock to destination.' + f' Docking step {docking_mission_identifier} interrupted ' + f'by new mission {mission_handle.execution.identifier}.' + ) + return + + if mission_queue_id is None: + self.node.get_logger().info( + f'[{self.name}] Failed to request robot to dock to destination.' + f' Maximum request navigate retries exceeded!') + mission_handle.execution.finished() + return - mission_queue_id = self.api.dock(mission_name, start_waypoint, end_waypoint) mission_handle.set_mission_queue_id(mission_queue_id) def stop(self, activity): From 27baec2c991f79330f236b22bd3caf1ebd193338 Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Tue, 21 May 2024 12:58:16 +0800 Subject: [PATCH 22/46] Fix wrong input argument for task cancellation Signed-off-by: Xiyu Oh --- .../fleet_adapter_mir_actions/mir_action.py | 2 +- .../fleet_adapter_mir_actions/rmf_cart_delivery.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/mir_action.py b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/mir_action.py index 0576a7a..a88694d 100644 --- a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/mir_action.py +++ b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/mir_action.py @@ -65,7 +65,7 @@ def update_action(self): def cancel_current_task(self, cancel_success: Callable[[], None], cancel_fail: Callable[[], None], - label: str = None): + label: str = ''): current_task_id = self.update_handle.more().current_task_id() self.node.get_logger().info(f'Cancel task requested for [{current_task_id}]') def _on_cancel(result: bool): diff --git a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py index fafa836..d3976ad 100644 --- a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py +++ b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py @@ -285,7 +285,7 @@ def update_dropoff(self, dropoff: Dropoff): self.node.get_logger().info(f'[{self.name}] Dropoff mission in progress...') return - def cancel_task(self, label: str = None): + def cancel_task(self, label: str = ''): def _cancel_success(): if self.pickup: self.pickup.state = PickupState.TASK_CANCELLED From 01ad9ccf66f99553fa9b273d7a82f7ea9964bc32 Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Wed, 26 Jun 2024 13:43:44 +0100 Subject: [PATCH 23/46] Separate cart detection related functions into another plugin Signed-off-by: Xiyu Oh --- configs/mir_config.yaml | 1 + fleet_adapter_mir/setup.py | 1 + .../rmf_cart_delivery.py | 32 ++---- .../rmf_cart_detection.py | 104 ++++++++++++++++++ 4 files changed, 118 insertions(+), 20 deletions(-) create mode 100644 fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_detection.py diff --git a/configs/mir_config.yaml b/configs/mir_config.yaml index 426f01a..8eeb723 100644 --- a/configs/mir_config.yaml +++ b/configs/mir_config.yaml @@ -99,6 +99,7 @@ plugins: module: "fleet_adapter_mir_actions.rmf_cart_delivery" class: "CartDelivery" actions: ["rmf_cart_delivery", "delivery_pickup", "delivery_dropoff"] + cart_detection_module: "fleet_adapter_mir_actions.rmf_cart_detection" missions: dock_to_cart: "rmf_dock_to_cart" # Name of MiR mission for robot to dock under a cart - to be created by fleet adapter upon launch pickup: "rmf_pickup_cart" # Name of MiR mission for robot to latch onto a cart - to be created and filled in by user diff --git a/fleet_adapter_mir/setup.py b/fleet_adapter_mir/setup.py index 8ccc66f..1ce52ce 100644 --- a/fleet_adapter_mir/setup.py +++ b/fleet_adapter_mir/setup.py @@ -21,6 +21,7 @@ 'console_scripts': [ 'fleet_adapter_mir=fleet_adapter_mir.fleet_adapter_mir:main', 'rmf_cart_delivery=fleet_adapter_mir.rmf_cart_delivery:CartDelivery', + 'rmf_cart_detection=fleet_adapter_mir.rmf_cart_detection:CartDetection', ], }, ) diff --git a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py index d3976ad..d1b5886 100644 --- a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py +++ b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py @@ -1,9 +1,9 @@ import math -from icecream import ic import enum import numpy as np from typing import Any from dataclasses import dataclass +import importlib import requests from urllib.error import HTTPError from fleet_adapter_mir_actions.mir_action import MirAction, MirActionFactory @@ -81,6 +81,14 @@ def __init__( # Initialize cart marker type self.cart_marker_type_guid = self.api.docking_offsets_guid_get(self.action_config['marker_types']['cart']) + # Import CartDetection module if provided + detection_module = self.action_config.get('cart_detection_module') + assert (detection_module is not None, + 'CartDetection module is required for CartDelivery plugin, ' + \ + 'but it is not found!') + detection_plugin = importlib.import_module(detection_module) + self.cart_detection = detection_plugin.CartDetection(mir_api, action_config) + def perform_action(self, category, description, execution): # Check that the perform action category matches match category: @@ -294,29 +302,13 @@ def _cancel_fail(): self.cancel_current_task(_cancel_success, _cancel_fail, label) def is_latch_open(self): - # Checks if the robot's latch is open and carrying a cart - # Return True if latch is open, else False - # ------------------------ - # IMPLEMENT YOUR CODE HERE - # ------------------------ - return False + return self.cart_detection.is_latch_open() def is_under_cart(self): - # Checks if the robot is docked under a cart - # Return True if robot is under any carts, else False - # ------------------------ - # IMPLEMENT YOUR CODE HERE - # ------------------------ - return False + return self.cart_detection.is_under_cart() def is_correct_cart(self, cart_id: str): - # Checks if the detected cart identifier matches the target cart_id - # Return True if cart is correct, False if cart is wrong, None if no cart detected - # ------------------------ - # IMPLEMENT YOUR CODE HERE - # ------------------------ - return True - # return None + return self.cart_detection.is_correct_cart(cart_id) def exit_lot(self): if not self.api.connected: diff --git a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_detection.py b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_detection.py new file mode 100644 index 0000000..c209270 --- /dev/null +++ b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_detection.py @@ -0,0 +1,104 @@ +import requests +from urllib.error import HTTPError + +class CartDetection: + def __init__( + self, + mir_api, + action_config + ): + self.api = mir_api + self.action_config = action_config + + def is_latch_open(self): + ''' + Checks if the robot's latch is open and carrying a cart + Return True if latch is open, else False + ''' + # ------------------------ + # IMPLEMENT YOUR CODE HERE + # ------------------------ + return False + + def is_under_cart(self): + ''' + Checks if the robot is docked under a cart + Return True if robot is under any carts, else False + ''' + # ------------------------ + # IMPLEMENT YOUR CODE HERE + # ------------------------ + return False + + def is_correct_cart(self, cart_id: str): + ''' + Checks if the detected cart identifier matches the target cart_id + Return True if cart is correct, False if cart is wrong, None if no + cart detected + ''' + # ------------------------ + # IMPLEMENT YOUR CODE HERE + # ------------------------ + return None + + # -------------------------------------------------------------------------- + # HELPFUL FUNCTIONS FOR INTERACTING WITH MIR REST API + # -------------------------------------------------------------------------- + + def register_get(self, register: int): + if not self.api.connected: + return None + try: + response = requests.get(self.api.prefix + f'registers/{register}', + headers=self.api.headers, + timeout=self.api.timeout) + if self.api.debug: + print(f"Response: {response.headers}") + # Response value is string, return integer of value + return int(response.json().get('value', 0)) + except HTTPError as http_err: + print(f"HTTP error: {http_err}") + return None + except Exception as err: + print(f"Other error: {err}") + return None + + def io_module_guid_status_get(self, io_guid: str): + if not self.api.connected: + return None + if io_guid is None: + return None + try: + response = requests.get(self.api.prefix + + f'io_modules/{io_guid}/status', + headers=self.api.headers, + timeout=self.api.timeout) + if self.api.debug: + print(f"Response: {response.headers}") + if 'input_state' not in response.json(): + return None + return response.json()['input_state'] + except HTTPError as http_err: + print(f"HTTP error: {http_err}") + return None + except Exception as err: + print(f"Other error: {err}") + return None + + def io_modules_get(self): + if not self.api.connected: + return None + try: + response = requests.get(self.api.prefix + f'io_modules', + headers=self.api.headers, + timeout=self.api.timeout) + if self.api.debug: + print(f"Response: {response.headers}") + # Response value is string, return integer of value + return response.json() + except HTTPError as http_err: + print(f"HTTP error: {http_err}") + return None + except Exception as err: + print(f"Other error: {err}") + return None \ No newline at end of file From c48e0af96e0d8aa662581c8f3966768b88024c61 Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Wed, 17 Jul 2024 16:49:30 +0800 Subject: [PATCH 24/46] Add example for module config and minor cleanup Signed-off-by: Xiyu Oh --- configs/mir_config.yaml | 3 +++ .../fleet_adapter_mir_actions/rmf_cart_delivery.py | 2 +- 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/configs/mir_config.yaml b/configs/mir_config.yaml index 8eeb723..b0177c9 100644 --- a/configs/mir_config.yaml +++ b/configs/mir_config.yaml @@ -114,3 +114,6 @@ plugins: missions_json: "/home/some_user/mir_ws/src/fleet_adapter_mir/missions/rmf_cart_missions.json" # Filepath to RMF cart delivery missions search_timeout: 60 pickup_dist_threshold: 3.0 # metres + # Examples of additional fields for cart detection module + io_name: "MiR internal IOs" + latch_io: 2 diff --git a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py index d1b5886..7188c87 100644 --- a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py +++ b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py @@ -84,7 +84,7 @@ def __init__( # Import CartDetection module if provided detection_module = self.action_config.get('cart_detection_module') assert (detection_module is not None, - 'CartDetection module is required for CartDelivery plugin, ' + \ + 'CartDetection module is required for CartDelivery plugin, ' + 'but it is not found!') detection_plugin = importlib.import_module(detection_module) self.cart_detection = detection_plugin.CartDetection(mir_api, action_config) From 9c25969613ed44fe875e2e1aa7597c7fdd35a81d Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Tue, 30 Jul 2024 18:01:38 +0800 Subject: [PATCH 25/46] Codestyle cleanup Signed-off-by: Xiyu Oh --- .../fleet_adapter_mir/fleet_adapter_mir.py | 25 +- .../fleet_adapter_mir/mir_api.py | 253 +++++++++++++----- .../fleet_adapter_mir/robot_adapter_mir.py | 218 +++++++++------ .../fleet_adapter_mir_actions/mir_action.py | 26 +- .../rmf_cart_delivery.py | 240 +++++++++++------ .../rmf_cart_detection.py | 25 +- .../dispatch_delivery.py | 28 +- 7 files changed, 542 insertions(+), 273 deletions(-) diff --git a/fleet_adapter_mir/fleet_adapter_mir/fleet_adapter_mir.py b/fleet_adapter_mir/fleet_adapter_mir/fleet_adapter_mir.py index 5713135..3c0cc7c 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/fleet_adapter_mir.py +++ b/fleet_adapter_mir/fleet_adapter_mir/fleet_adapter_mir.py @@ -18,6 +18,7 @@ from rmf_adapter import Transformation from .robot_adapter_mir import RobotAdapterMiR + ############################################################################### # HELPER FUNCTIONS AND CLASSES ############################################################################### @@ -110,7 +111,7 @@ async def state_updates(self): for robot in self.robot_handles: robot_updaters.append(robot.update_loop(self.period)) await asyncio.gather(*robot_updaters) - + def update_loop(self): asyncio.set_event_loop(self.event_loop) self.event_loop.run_until_complete(self.state_updates()) @@ -131,14 +132,17 @@ def start(self): rclpy.shutdown() -def create_fleet(fleet_config, config_yaml, cmd_node, rmf_missions) -> FleetAdapterMiR: +def create_fleet( + fleet_config, config_yaml, cmd_node, rmf_missions) -> FleetAdapterMiR: """Create RMF Adapter and fleet handle""" - for level, coords in config_yaml['conversions']['reference_coordinates'].items(): + for level, coords in \ + config_yaml['conversions']['reference_coordinates'].items(): tf = compute_transforms(level, coords, cmd_node) fleet_config.add_robot_coordinates_transformation(level, tf) # RMF_CORE Fleet Adapter: Manages delivery or loop requests - adapter = rmf_adapter.Adapter.make(config_yaml['node_names']['rmf_fleet_adapter']) + adapter = rmf_adapter.Adapter.make( + config_yaml['node_names']['rmf_fleet_adapter']) assert adapter, ("Adapter could not be init! " "Ensure a ROS2 scheduler node is running") @@ -160,8 +164,10 @@ def create_fleet(fleet_config, config_yaml, cmd_node, rmf_missions) -> FleetAdap event_loop = asyncio.new_event_loop() robots_handles = [] - for robot_name, rmf_config in fleet_config.known_robot_configurations.items(): - mir_config = config_yaml['rmf_fleet']['robots'][robot_name]['mir_config'] + for robot_name, rmf_config in \ + fleet_config.known_robot_configurations.items(): + mir_config = \ + config_yaml['rmf_fleet']['robots'][robot_name]['mir_config'] robots_handles.append(RobotAdapterMiR( robot_name, rmf_config, @@ -176,7 +182,9 @@ def create_fleet(fleet_config, config_yaml, cmd_node, rmf_missions) -> FleetAdap debug, )) - return FleetAdapterMiR(cmd_node, adapter, fleet_handle, robots_handles, update_frequency, event_loop) + return FleetAdapterMiR( + cmd_node, adapter, fleet_handle, robots_handles, update_frequency, + event_loop) ############################################################################### @@ -246,7 +254,8 @@ def main(argv=sys.argv): print() # Create a node to use inside of the Python code for logging - cmd_node = rclpy.node.Node(config_yaml['node_names']['robot_command_handle']) + cmd_node = rclpy.node.Node( + config_yaml['node_names']['robot_command_handle']) # Create the fleet, including the robots that are in the config file fleet = create_fleet(fleet_config, config_yaml, cmd_node, rmf_missions) diff --git a/fleet_adapter_mir/fleet_adapter_mir/mir_api.py b/fleet_adapter_mir/fleet_adapter_mir/mir_api.py index f2b53ae..6f34769 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/mir_api.py +++ b/fleet_adapter_mir/fleet_adapter_mir/mir_api.py @@ -36,6 +36,7 @@ class MiRPositionTypes(enum.IntEnum): LocalizationParamPosition = 'position_estimate' + class MapConversions: def __init__(self, rmf_to_mir: dict): self.rmf_to_mir = rmf_to_mir @@ -43,7 +44,10 @@ def __init__(self, rmf_to_mir: dict): class MirStatus: - def __init__(self, response: dict, map_conversions: MapConversions, map_name: str): + def __init__(self, + response: dict, + map_conversions: MapConversions, + map_name: str): self.response = response p = response['position'] self.state = RobotState( @@ -54,9 +58,14 @@ def __init__(self, response: dict, map_conversions: MapConversions, map_name: st class MirAPI: - def __init__(self, prefix, headers, conversions, rmf_missions, timeout=10.0, debug=False): - #HTTP connection - self.prefix = prefix + def __init__(self, + prefix, + headers, + conversions, + rmf_missions, + timeout=10.0, + debug=False): + self.prefix = prefix self.debug = False self.headers = headers self.timeout = timeout @@ -74,7 +83,10 @@ def __init__(self, prefix, headers, conversions, rmf_missions, timeout=10.0, deb def attempt_connection(self): try: - requests.get(self.prefix + 'wifi/connections', headers=self.headers, timeout=self.timeout) + requests.get( + self.prefix + 'wifi/connections', + headers=self.headers, + timeout=self.timeout) except HTTPError as http_err: print(f"HTTP error: {http_err}") return @@ -104,7 +116,8 @@ def attempt_connection(self): f'{dock_and_charge_key} mission must be specified in fleet config ' f'file under conversions -> missions' ) - self.dock_and_charge_mission: str = self.mission_keys[dock_and_charge_key] + self.dock_and_charge_mission: str = \ + self.mission_keys[dock_and_charge_key] assert self.dock_and_charge_mission in self.known_missions, ( f'RMF dock and charge mission [{self.dock_and_charge_mission}] ' f'has not yet been defined as a mission in the MiR robot ' @@ -137,8 +150,8 @@ def make_optional_mission(key): self.localize_params = action['parameters'] break assert self.localize_params is not None, ( - f'No switch_map action in the mission {self.localize_mission}:\n' - f'{localize_actions}' + f'No switch_map action in the mission {self.localize_mission}:' + f'\n{localize_actions}' ) found_position_estimate_param = False for param in self.localize_params: @@ -151,17 +164,18 @@ def make_optional_mission(key): # Retrieve mission parameters for mission, mission_data in self.known_missions.items(): - self.mission_actions[mission] = self.missions_mission_id_actions_get( - mission_data['guid']) + self.mission_actions[mission] = \ + self.missions_mission_id_actions_get(mission_data['guid']) self.created_by_id = self.me_get()['guid'] def update_known_positions(self): self.known_positions = {} for pos in self.positions_get(): - if pos['name'] in self.known_positions and \ - pos['type_id'] == self.known_positions[pos['name']]['type_id'] and \ - ('rmf_localize' in pos['name']): + if (pos['name'] in self.known_positions and + (pos['type_id'] == + self.known_positions[pos['name']]['type_id']) and + ('rmf_localize' in pos['name'])): # Delete any duplicate positions self.positions_guid_delete(pos['guid']) elif pos['type_id'] == MiRPositionTypes.ROBOT or \ @@ -194,12 +208,18 @@ def create_missions(self, rmf_missions): for mission_name, mission_json in rmf_missions.items(): if mission_name not in self.known_missions: # Create the relevant mission on MiR - mission = self.missions_post(mission_name, rmf_mission_group_id) + mission = self.missions_post( + mission_name, rmf_mission_group_id) self.known_missions[mission['name']] = mission # Fill in mission actions - self.create_rmf_mission_actions(mission_name, mission['guid'], mission_json) - - def create_rmf_mission_actions(self, mission_name: str, mission_id: str, mission_json: list[dict]): + self.create_rmf_mission_actions( + mission_name, mission['guid'], mission_json) + + def create_rmf_mission_actions( + self, + mission_name: str, + mission_id: str, + mission_json: list[dict]): for action in mission_json: # Find schema for action type action_type = action.get('action_type') @@ -218,17 +238,21 @@ def create_rmf_mission_actions(self, mission_name: str, mission_id: str, mission param_body['input_name'] = param['input_name'] param_body['value'] = param['value'] - # If the input type is a position, we would need a valid GUID for the value field - # Let's find a placeholder position GUID from the list of known positions - if param_body['id'] == 'position' or param_body['id'] == 'entry_position': + # If the input type is a position, we would need a valid GUID + # for the value field. Let's find a placeholder position GUID + # from the list of known positions + if (param_body['id'] == 'position' or + param_body['id'] == 'entry_position'): default_pos = self.positions_get()[0]['guid'] param_body['value'] = default_pos - # Similarly, if the input type is a marker type, we'll need to find a placeholder - # marker type GUID from the list of known marker types + # Similarly, if the input type is a marker type, we'll need to + # find a placeholder marker type GUID from the list of known + # marker types if param_body['id'] == 'marker_type': default_marker = self.docking_offsets_get()[0]['guid'] param_body['value'] = default_marker - # If the input type is a footprint, we'll also use a placeholder footprint GUID + # If the input type is a footprint, we'll also use a + # placeholder footprint GUID if param_body['id'] == 'footprint': default_footprint = self.footprints_get()[0]['guid'] param_body['value'] = default_footprint @@ -246,7 +270,8 @@ def create_rmf_mission_actions(self, mission_name: str, mission_id: str, mission param_body['input_name'] = param.get('input_name') default_value = None - if 'constraints' in param and 'default' in param['constraints']: + if ('constraints' in param and + 'default' in param['constraints']): default_value = param['constraints']['default'] param_body['value'] = default_value action_body_param.append(param_body) @@ -270,7 +295,7 @@ def navigate(self, position): return self.queue_mission_by_name(self.move_mission, mission_params) def go_to_known_position(self, position_name): - if not position_name in self.known_positions: + if position_name not in self.known_positions: return None return self.dock(self.go_to, None, position_name) @@ -285,8 +310,10 @@ def dock(self, mission_name, start_waypoint, end_waypoint): assert end_wp is not None end_wp_guid = end_wp.get('guid') assert end_wp_guid is not None - end_param = self.get_mission_params_with_value(mission_name, 'move', 'end_waypoint', end_wp_guid) - dock_param = self.get_mission_params_with_value(mission_name, 'docking', 'end_waypoint', end_wp_guid) + end_param = self.get_mission_params_with_value( + mission_name, 'move', 'end_waypoint', end_wp_guid) + dock_param = self.get_mission_params_with_value( + mission_name, 'docking', 'end_waypoint', end_wp_guid) # Start waypoint is optional if start_waypoint is not None: @@ -297,14 +324,18 @@ def dock(self, mission_name, start_waypoint, end_waypoint): assert start_wp is not None start_wp_guid = start_wp.get('guid') assert start_wp_guid is not None - start_param = self.get_mission_params_with_value(mission_name, 'move', 'start_waypoint', start_wp_guid) + start_param = self.get_mission_params_with_value( + mission_name, 'move', 'start_waypoint', start_wp_guid) mission_params = start_param + end_param - # Check whether we should dock into this end waypoint or not (for charging) + # Check whether we should dock into this end waypoint (for charging) elif dock_param: charger_marker_type = self.marker_type_keys['charger'] - charger_marker_type_guid = self.docking_offsets_guid_get(charger_marker_type) - marker_param = self.get_mission_params_with_value(mission_name, 'docking', 'charger_marker_type', charger_marker_type_guid) + charger_marker_type_guid = self.docking_offsets_guid_get( + charger_marker_type) + marker_param = self.get_mission_params_with_value( + mission_name, 'docking', 'charger_marker_type', + charger_marker_type_guid) mission_params = end_param + dock_param + marker_param else: mission_params = end_param @@ -336,16 +367,15 @@ def localize(self, map, estimate, index): mission_params=mission_params ) - def get_position_guid(self, name, map_id, location): attempts = 0 max_attempts = 10 while True: - attempts +=1 + attempts += 1 if attempts >= max_attempts: print( - f'Too many attempts [{max_attempts}] to set a localization ' - 'position.' + f'Too many attempts [{max_attempts}] to set a ' + f'localization position.' ) return None @@ -373,12 +403,12 @@ def position_matches(pos): # positions and retry this loop. self.update_known_positions() elif not position_matches(position): - if self.positions_put(position['guid'], name, map_id, location): + if self.positions_put( + position['guid'], name, map_id, location): return position['guid'] else: return position['guid'] - def queue_mission_by_name(self, mission_name, mission_params=None): mir_mission = self.known_missions.get(mission_name) if mir_mission is None: @@ -448,7 +478,7 @@ def positions_put(self, guid, name, map_id, location): print(f'Response: {response}') self.known_positions[response['name']] = response return response['guid'] - except: + except Exception as err: pass def positions_delete(self): @@ -463,17 +493,18 @@ def positions_delete(self): timeout=self.timeout ).json() return response['guid'] - except: + except Exception as err: pass else: - new_known_positions[position] = copy.deepcopy(self.known_positions[position]) + new_known_positions[position] = \ + copy.deepcopy(self.known_positions[position]) self.known_positions = {} self.known_positions = new_known_positions def positions_guid_delete(self, guid): try: response = requests.delete( - self.prefix + f'positions/{guid}', + self.prefix + f'positions/{guid}', headers=self.headers, timeout=self.timeout ).json() @@ -486,7 +517,10 @@ def status_get(self) -> MirStatus: if not self.connected: return try: - response = requests.get(self.prefix + f'status', headers=self.headers, timeout=self.timeout) + response = requests.get( + self.prefix + f'status', + headers=self.headers, + timeout=self.timeout) # To prevent adapter crashing in case of error if response.json() is None or 'position' not in response.json(): return None @@ -520,7 +554,10 @@ def me_get(self): if not self.connected: return try: - response = requests.get(self.prefix + 'users/me', headers=self.headers, timeout=self.timeout) + response = requests.get( + self.prefix + 'users/me', + headers=self.headers, + timeout=self.timeout) if self.debug: print(f'Response: {response.json()}') return response.json() @@ -533,7 +570,10 @@ def mission_groups_get(self): if not self.connected: return try: - response = requests.get(self.prefix + f'mission_groups', headers = self.headers, timeout=self.timeout) + response = requests.get( + self.prefix + f'mission_groups', + headers=self.headers, + timeout=self.timeout) return response.json() except HTTPError as http_err: print(f"HTTP error: {http_err}") @@ -544,7 +584,10 @@ def actions_get(self): if not self.connected: return try: - response = requests.get(self.prefix + 'actions', headers=self.headers, timeout=self.timeout) + response = requests.get( + self.prefix + 'actions', + headers=self.headers, + timeout=self.timeout) if self.debug: print(f"Response: {response.json()}") return response.json() @@ -557,7 +600,10 @@ def action_type_get(self, action_type: str): if not self.connected: return try: - response = requests.get(self.prefix + f'actions/{action_type}', headers=self.headers, timeout=self.timeout) + response = requests.get( + self.prefix + f'actions/{action_type}', + headers=self.headers, + timeout=self.timeout) if self.debug: print(f"Response: {response.json()}") return response.json() @@ -570,7 +616,10 @@ def missions_get(self): if not self.connected: return try: - response = requests.get(self.prefix + 'missions', headers=self.headers, timeout=self.timeout) + response = requests.get( + self.prefix + 'missions', + headers=self.headers, + timeout=self.timeout) if self.debug: print(f"Response: {response.json()}") return response.json() @@ -583,7 +632,10 @@ def positions_get(self): if not self.connected: return try: - response = requests.get(self.prefix + 'positions' , headers=self.headers, timeout=self.timeout) + response = requests.get( + self.prefix + 'positions', + headers=self.headers, + timeout=self.timeout) if self.debug: print(f"Response: {response.json()}") return response.json() @@ -596,7 +648,10 @@ def mission_queue_get(self): if not self.connected: return try: - response = requests.get(self.prefix + f'mission_queue', headers = self.headers, timeout=self.timeout) + response = requests.get( + self.prefix + f'mission_queue', + headers=self.headers, + timeout=self.timeout) return response.json() except HTTPError as http_err: print(f"HTTP error: {http_err}") @@ -607,7 +662,10 @@ def mission_queue_id_get(self, mission_queue_id): if not self.connected: return try: - response = requests.get(self.prefix + f'mission_queue/{mission_queue_id}', headers = self.headers, timeout=self.timeout) + response = requests.get( + self.prefix + f'mission_queue/{mission_queue_id}', + headers=self.headers, + timeout=self.timeout) return response.json() except HTTPError as http_err: print(f"HTTP error: {http_err}") @@ -619,14 +677,19 @@ def mission_queue_post(self, mission_id, full_mission_description=None): return data = {'mission_id': mission_id} if full_mission_description is not None: - # print(f'---------->>> {full_mission_description}') data = full_mission_description if mission_id != full_mission_description['mission_id']: - print(f'Inconsistent mission id, provided [{mission_id}], full_mission_description: [{full_mission_description}]') + print(f'Inconsistent mission id, provided [{mission_id}], ' + f'full_mission_description: ' + f'[{full_mission_description}]') return try: - response = requests.post(self.prefix + 'mission_queue' , headers = self.headers, data=json.dumps(data), timeout = self.timeout) + response = requests.post( + self.prefix + 'mission_queue', + headers=self.headers, + data=json.dumps(data), + timeout=self.timeout) if self.debug: print(f"Response: {response.json()}") return response.json() @@ -639,7 +702,11 @@ def missions_mission_id_actions_post(self, mission_id, body): if not self.connected: return try: - response = requests.post(self.prefix + 'missions/' + mission_id +'/actions' , headers = self.headers, data=json.dumps(body), timeout = self.timeout) + response = requests.post( + self.prefix + 'missions/' + mission_id + '/actions', + headers=self.headers, + data=json.dumps(body), + timeout=self.timeout) if self.debug: print(f"Response: {response.json()}") print(response.status_code) @@ -653,7 +720,10 @@ def missions_mission_id_actions_get(self, mission_id): if not self.connected: return try: - response = requests.get(self.prefix + 'missions/' + str(mission_id) +'/actions' , headers = self.headers, timeout = self.timeout) + response = requests.get( + self.prefix + 'missions/' + str(mission_id) + '/actions', + headers=self.headers, + timeout=self.timeout) if self.debug: print(f"Response: {response.json()}") print(response.status_code) @@ -673,7 +743,11 @@ def mission_groups_post(self, group_name): 'icon': '' } try: - response = requests.post(self.prefix + 'mission_groups' , headers = self.headers, data=json.dumps(data), timeout = self.timeout) + response = requests.post( + self.prefix + 'mission_groups', + headers=self.headers, + data=json.dumps(data), + timeout=self.timeout) if self.debug: print(f"Response: {response.json()}") return response.json() @@ -691,7 +765,11 @@ def missions_post(self, mission, mission_group_id): 'group_id': mission_group_id } try: - response = requests.post(self.prefix + 'missions' , headers = self.headers, data=json.dumps(data), timeout = self.timeout) + response = requests.post( + self.prefix + 'missions', + headers=self.headers, + data=json.dumps(data), + timeout=self.timeout) if self.debug: print(f"Response: {response.json()}") return response.json() @@ -704,7 +782,10 @@ def positions_guid_get(self, guid): if not self.connected: return try: - response = requests.get(self.prefix + 'positions/'+ guid, headers=self.headers, timeout=self.timeout) + response = requests.get( + self.prefix + 'positions/' + guid, + headers=self.headers, + timeout=self.timeout) if self.debug: print(f"Response: {response.json()}") return response.json() @@ -718,9 +799,13 @@ def status_put(self, state_id): return data = {"state_id": state_id} try: - response = requests.put(self.prefix + 'status', headers = self.headers, data=json.dumps(data), timeout=self.timeout) + response = requests.put( + self.prefix + 'status', + headers=self.headers, + data=json.dumps(data), + timeout=self.timeout) if self.debug: - print(f"Response: {response.json()}") + print(f"Response: {response.json()}") return response.json() except HTTPError as http_err: print(f"HTTP error: {http_err}") @@ -732,9 +817,13 @@ def clear_error(self): return data = {"clear_error": True} try: - response = requests.put(self.prefix + 'status', headers = self.headers, data=json.dumps(data), timeout=self.timeout) + response = requests.put( + self.prefix + 'status', + headers=self.headers, + data=json.dumps(data), + timeout=self.timeout) if self.debug: - print(f"Response: {response.json()}") + print(f"Response: {response.json()}") return response.json() except HTTPError as http_err: print(f"HTTP error: {http_err}") @@ -745,7 +834,10 @@ def mission_queue_delete(self): if not self.connected: return try: - response = requests.delete(self.prefix + 'mission_queue' , headers = self.headers, timeout = self.timeout) + response = requests.delete( + self.prefix + 'mission_queue', + headers=self.headers, + timeout=self.timeout) if self.debug: print(f"Response: {response.headers}") return True @@ -762,8 +854,8 @@ def mission_queue_id_delete(self, mission_queue_id): try: response = requests.delete( self.prefix + 'mission_queue/' + str(mission_queue_id), - headers = self.headers, - timeout = self.timeout + headers=self.headers, + timeout=self.timeout ) if self.debug: print(f"Response: {response.headers}") @@ -779,7 +871,10 @@ def missions_guid_delete(self, guid): if not self.connected: return try: - response = requests.delete(self.prefix + 'missions/' +guid , headers = self.headers, timeout = self.timeout) + response = requests.delete( + self.prefix + 'missions/' + guid, + headers=self.headers, + timeout=self.timeout) if self.debug: print(f"Response: {response.headers}") return True @@ -794,7 +889,10 @@ def maps_get(self): if not self.connected: return [] try: - response = requests.get(self.prefix + 'maps', headers = self.headers, timeout = self.timeout) + response = requests.get( + self.prefix + 'maps', + headers=self.headers, + timeout=self.timeout) if self.debug: print(f"Response: {response.headers}") return response.json() @@ -809,7 +907,10 @@ def docking_offsets_get(self): if not self.connected: return try: - response = requests.get(self.prefix + 'docking_offsets', headers=self.headers, timeout=self.timeout) + response = requests.get( + self.prefix + 'docking_offsets', + headers=self.headers, + timeout=self.timeout) if self.debug: print(f"Response: {response.json()}") return response.json() @@ -829,7 +930,10 @@ def footprints_get(self): if not self.connected: return try: - response = requests.get(self.prefix + 'footprints', headers=self.headers, timeout=self.timeout) + response = requests.get( + self.prefix + 'footprints', + headers=self.headers, + timeout=self.timeout) if self.debug: print(f"Response: {response.json()}") return response.json() @@ -849,12 +953,17 @@ def mission_completed(self, mission_queue_id): mission_status = self.mission_queue_id_get(mission_queue_id) if not mission_status: return False - if 'finished' in mission_status and mission_status['finished'] is not None: - # if 'state' in mission_status and mission_status['state'] == 'Done': + if ('finished' in mission_status and + mission_status['finished'] is not None): return True return False - def get_mission_params_with_value(self, mission_name: str, action_type: str, param_name: str, value: str): + def get_mission_params_with_value( + self, + mission_name: str, + action_type: str, + param_name: str, + value: str): mission_actions = self.mission_actions.get(mission_name) mission_params = None for d in mission_actions: diff --git a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py index 584f269..3b3d296 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py +++ b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py @@ -58,6 +58,7 @@ def activity(self): return execution.identifier return None + class RobotAdapterMiR: def __init__( self, @@ -114,7 +115,9 @@ def __init__( f'MiR is missing the position [{position_name}] needed as ' f'a lift position on level [{level}] for lift [{lift}]' ) - self.nav_issue_ticket = None # We should only have one issue ticket at a time to manage unsuccessful missions + # We should only have one issue ticket at a time to manage unsuccessful + # navigation missions + self.nav_issue_ticket = None self.requested_replan = False self.replan_counts = 0 @@ -126,8 +129,11 @@ def __init__( self._make_callbacks(), ) - self.current_action = None # Tracks the current ongoing action - self.plugin_config = plugin_config # Stores all the configured plugin action configs + # Track the current ongoing action + self.current_action = None + + # Store all the configured plugin action configs + self.plugin_config = plugin_config @property def activity(self): @@ -141,7 +147,7 @@ def activity(self): async def update_loop(self, period): while rclpy.ok(): now = self.node.get_clock().now() - next_wakeup = now + Duration(nanoseconds = period * 1e9) + next_wakeup = now + Duration(nanoseconds=period * 1e9) await self.request_update() while self.node.get_clock().now() < next_wakeup: time.sleep(0.01) @@ -152,10 +158,13 @@ def request_update(self): status = self.api.status_get() if status is None: self.disconnect = True - self.node.get_logger().warn(f'Unable to retrieve status from robot [{self.name}]!') + self.node.get_logger().warn( + f'Unable to retrieve status from robot [{self.name}]!') return if self.disconnect: - self.node.get_logger().info(f'Robot [{self.name}] connectivity resumed, received status from robot successfully.') + self.node.get_logger().info( + f'Robot [{self.name}] connectivity resumed, received status ' + f'from robot successfully.') self.disconnect = False more = self.update_handle.more() if more is not None: @@ -166,7 +175,8 @@ def request_update(self): self.update_mission_status(status, mission) # Update RMF with the latest RobotState - if mission is None or (mission.localize and mission.done) or not mission.localize: + if (mission is None or (mission.localize and mission.done) or + not mission.localize): self.update_handle.update(status.state, self.activity) self.last_known_status = status else: @@ -180,19 +190,26 @@ def request_update(self): # PerformAction related checks if self.current_action: if self.current_action.update_action(): - # This means that the action has ended, we can clear the current action object - self.node.get_logger().info(f'Robot [{self.name}] has completed its current action.') + # This means that the action has ended, we can clear the + # current action object + self.node.get_logger().info( + f'Robot [{self.name}] has completed its current action.') self.current_action = None # Clear error on updates - if status is not None and 'errors' in status.response and len(status.response['errors']) > 0: + if (status is not None and 'errors' in status.response and + len(status.response['errors']) > 0): self.api.clear_error() - if status is not None and (status.response['state_id'] == MiRStateCode.PAUSE or status.response['state_id'] == MiRStateCode.ERROR): + if (status is not None and + (status.response['state_id'] == MiRStateCode.PAUSE or + status.response['state_id'] == MiRStateCode.ERROR)): self.api.status_put(MiRStateCode.READY) def is_charging(self, status: MirStatus): - # Note: Not the best way to verify that robot is charging but there's currently no other option - if status.response.get('mission_text') == "Charging... Waiting for new mission...": + # Note: Not the best way to verify that robot is charging but there's + # currently no other option + if (status.response.get('mission_text') == + "Charging... Waiting for new mission..."): return True return False @@ -202,7 +219,8 @@ def update_rmf_finished(self, mission: MissionHandle): mission.execution.finished() mission.execution = None - def update_mission_status(self, status: MirStatus, mission: MissionHandle): + def update_mission_status( + self, status: MirStatus, mission: MissionHandle): if mission is None or mission.mission_queue_id is None: # Either we don't have a mission or we don't know the # mission_queue_id yet so just continue as normal for now @@ -212,13 +230,15 @@ def update_mission_status(self, status: MirStatus, mission: MissionHandle): # This mission is already finished, so we return early return - mission_status = self.api.mission_queue_id_get(mission.mission_queue_id) + mission_status = self.api.mission_queue_id_get( + mission.mission_queue_id) executing_mission = status.response.get('mission_queue_id') if executing_mission == mission.mission_queue_id: # The current mission is still being executed, so we don't # need to change anything if mission.charger is not None and self.is_charging(status): - self.node.get_logger().info(f'Robot [{self.name}] has begun charging...') + self.node.get_logger().info( + f'Robot [{self.name}] has begun charging...') mission.docking = False mission.done = True return @@ -227,17 +247,21 @@ def update_mission_status(self, status: MirStatus, mission: MissionHandle): # the mission has finished or it has not started yet. We need a second # API call to figure out which it is. if mission_status is None or mission_status.get('state') is None: - # It shouldn't come to here, but we'll prevent any potential crashes + # It shouldn't come to here, but we'll prevent any potential + # crashes # with a check here return if mission_status['state'] == 'Done': - # The mission has finished so let's trigger execution.finished() and - # then clear it out - self.node.get_logger().info(f'MiR [{self.name}] has completed mission {mission.mission_queue_id}, ' - f'marking ActionExecution object as finished.') + # The mission has finished so let's trigger execution.finished() + # and then clear it out + self.node.get_logger().info( + f'MiR [{self.name}] has completed mission ' + f'{mission.mission_queue_id}, marking ActionExecution object ' + f'as finished.') mission.docking = False mission.done = True - # If the mission previously issued a ticket, let's resolve that ticket + # If the mission previously issued a ticket, + # let's resolve that ticket if self.nav_issue_ticket is not None: msg = {} self.nav_issue_ticket.resolve(msg) @@ -254,24 +278,31 @@ def update_mission_status(self, status: MirStatus, mission: MissionHandle): 'message': 'Mission has been aborted.' } # Save the issue ticket somewhere so that we can resolve it later - self.nav_issue_ticket = self.update_handle.more().create_issue(tier, category, detail) - self.node.get_logger().info(f'Created [{category}] issue ticket for mission queue ID [{mission.mission_queue_id}]') + self.nav_issue_ticket = \ + self.update_handle.more().create_issue(tier, category, detail) + self.node.get_logger().info( + f'Created [{category}] issue ticket for mission queue ID ' + f'[{mission.mission_queue_id}]') # After issuing a ticket, let's request a replan mission.done = True self.update_handle.more().replan() - # We keep track of the number of times we are replanning for the same mission + # We keep track of the number of times we are replanning for the + # same mission self.replan_counts += 1 - self.node.get_logger().info(f'[{self.name}] Replan count: {self.replan_counts}') + self.node.get_logger().info( + f'[{self.name}] Replan count: {self.replan_counts}') # Ensure that robot is charging - if mission.done and mission.charger is not None and not self.is_charging(status): - # Charging mission is marked as done but robot is not charging. Let's send - # the robot to the charger again. + if (mission.done and mission.charger is not None and + not self.is_charging(status)): + # Charging mission is marked as done but robot is not charging. + # Let's send the robot to the charger again. mission.done = False self.update_handle.more().replan() self.replan_counts += 1 - self.node.get_logger().info(f'[{self.name}] Replan count: {self.replan_counts}') + self.node.get_logger().info( + f'[{self.name}] Replan count: {self.replan_counts}') def _make_callbacks(self): callbacks = rmf_easy.RobotCallbacks( @@ -291,51 +322,56 @@ def _make_callbacks(self): return callbacks def navigate(self, destination, execution): - # If the nav command coming in is to bring the robot to a charger, but the robot is - # already charging at the same charger, we ignore this nav command + # If the nav command coming in is to bring the robot to a charger, but + # the robot is already charging at the same charger, we ignore this + # nav command status = self.last_known_status if status and self.is_charging(status): ignore_charging_cmd = False mission = self.mission - # If the robot's previous mission was a charging mission to the same charger - if mission and mission.charger is not None and destination.name == mission.charger: - ignore_charging_cmd = True - # If the robot was already charging at the same charger before any missions were - # sent/stored - elif destination.map == self.current_map and \ - (self.dist(destination.position, status.state.position) < - self.update_handle.max_merge_waypoint_distance()): + # If the robot's previous mission was a charging mission to the + # same charger + if (mission and mission.charger is not None and + destination.name == mission.charger): ignore_charging_cmd = True if ignore_charging_cmd: - self.node.get_logger().info(f'[{self.name}] Received navigation command to dock to ' - f'charger {destination.name} when robot is already charging ' - f'at the same charger, ignoring command and marking it as ' - f'finished.') + self.node.get_logger().info( + f'[{self.name}] Received navigation command to dock to ' + f'charger {destination.name} when robot is already ' + f'charging at the same charger, ignoring command and ' + f'marking it as finished.') execution.finished() return # If the robot already has a mission, cancel it - self.node.get_logger().info(f'[{self.name}] Calling stop for new navigation command.') + self.node.get_logger().info( + f'[{self.name}] Calling stop for new navigation command.') self.request_stop(self.mission) # If this is a docking task, send the appropriate docking mission if destination.dock is not None: dock_json = json.loads(destination.dock) - if dock_json.get('mission_name') == self.api.dock_and_charge_mission: - self.mission = MissionHandle(execution, charger=destination.name) + if (dock_json.get('mission_name') == + self.api.dock_and_charge_mission): + self.mission = MissionHandle( + execution, charger=destination.name) # Clear the mission queue before requesting dock and charge - self.node.get_logger().info(f'Clearing mission queue for [{self.name}] before submitting a dock_and_charge mission.') + self.node.get_logger().info( + f'Clearing mission queue for [{self.name}] before ' + f'submitting a dock_and_charge mission.') self.api.mission_queue_delete() else: self.mission = MissionHandle(execution) mission_name = dock_json.get('mission_name') - self.node.get_logger().info(f'Requesting [{mission_name}] mission for [{self.name}].') + self.node.get_logger().info( + f'Requesting [{mission_name}] mission for [{self.name}].') self.request_dock(dock_json, self.mission) return if destination.inside_lift is not None: - positions_for_lift = self.lift_positions.get(destination.inside_lift.name) + positions_for_lift = self.lift_positions.get( + destination.inside_lift.name) if positions_for_lift is not None: position_info = positions_for_lift.get(destination.map) if position_info is not None: @@ -353,7 +389,8 @@ def navigate(self, destination, execution): # We are already close enough to the point, so we # will just have the robot stop and tell RMF to go # ahead. - self.node.get_logger().info(f'[{self.name}] Calling stop in the lift.') + self.node.get_logger().info( + f'[{self.name}] Calling stop in the lift.') self.request_stop(self.mission) self.mission = None execution.finished() @@ -362,7 +399,8 @@ def navigate(self, destination, execution): # desired center point, so we will ask the robot to # simply move there self.mission = MissionHandle(execution) - self.request_go_to_known_position(position_name, self.mission) + self.request_go_to_known_position( + position_name, self.mission) return # If this is a move to task, send rmf_move mission @@ -420,16 +458,17 @@ def request_navigate( navigation_mission_identifier != mission_handle.execution.identifier): self.node.get_logger().info( - f'[{self.name}] Failed to request robot to move to destination.' - f' Navigation step {navigation_mission_identifier} interrupted ' - f'by new mission {mission_handle.execution.identifier}.' + f'[{self.name}] Failed to request robot to move to ' + f'destination. Navigation step ' + f'{navigation_mission_identifier} interrupted by new mission ' + f'{mission_handle.execution.identifier}.' ) return if mission_queue_id is None: self.node.get_logger().info( - f'[{self.name}] Failed to request robot to move to destination.' - f' Maximum request navigate retries exceeded!') + f'[{self.name}] Failed to request robot to move to ' + f'destination. Maximum request navigate retries exceeded!') mission_handle.execution.finished() return @@ -462,8 +501,9 @@ def request_go_to_known_position( mission_queue_id = self.api.go_to_known_position(position_name) if mission_queue_id is None: self.node.get_logger().info( - f'[{self.name}] Move to known positions mission cannot ' - f'be queued (no mission queue id provided), retrying...' + f'[{self.name}] Move to known positions mission ' + f'cannot be queued (no mission queue id provided), ' + f'retrying...' ) except Exception as err: self.node.get_logger().info( @@ -493,7 +533,6 @@ def request_go_to_known_position( mission_handle.set_mission_queue_id(mission_queue_id) - @parallel def request_dock( self, @@ -531,9 +570,8 @@ def request_dock( start_waypoint = None mission_name = docking_points['mission_name'] - mission_queue_id = self.api.dock(mission_name, - start_waypoint, - end_waypoint) + mission_queue_id = self.api.dock( + mission_name, start_waypoint, end_waypoint) if mission_queue_id is None: self.node.get_logger().info( f'[{self.name}] Dock mission cannot be queued ' @@ -550,16 +588,17 @@ def request_dock( docking_mission_identifier != mission_handle.execution.identifier): self.node.get_logger().info( - f'[{self.name}] Failed to request robot to dock to destination.' - f' Docking step {docking_mission_identifier} interrupted ' - f'by new mission {mission_handle.execution.identifier}.' + f'[{self.name}] Failed to request robot to dock to ' + f'destination. Docking step {docking_mission_identifier} ' + f'interrupted by new mission ' + f'{mission_handle.execution.identifier}.' ) return if mission_queue_id is None: self.node.get_logger().info( - f'[{self.name}] Failed to request robot to dock to destination.' - f' Maximum request navigate retries exceeded!') + f'[{self.name}] Failed to request robot to dock to ' + f'destination. Maximum request navigate retries exceeded!') mission_handle.execution.finished() return @@ -569,10 +608,14 @@ def stop(self, activity): mission = self.mission if mission is not None: if mission.docking: - self.node.get_logger().info(f'Robot is performing docking mission, ignoring stop issued by RMF') + self.node.get_logger().info( + f'Robot [{self.name}] is performing docking mission, ' + f'ignoring stop issued by RMF') return - if mission.execution is not None and activity.is_same(mission.execution.identifier): - self.node.get_logger().info(f'[{self.name}] Stop requested from RMF!') + if (mission.execution is not None and + activity.is_same(mission.execution.identifier)): + self.node.get_logger().info( + f'[{self.name}] Stop requested from RMF!') self.request_stop(mission) self.mission = None @@ -580,7 +623,8 @@ def stop(self, activity): def request_stop(self, mission: MissionHandle): if mission is not None: with mission.mutex: - if mission.mission_queue_id is not None and not mission.do_not_cancel: + if (mission.mission_queue_id is not None and + not mission.do_not_cancel): self.api.mission_queue_id_delete(mission.mission_queue_id) def localize(self, estimate, execution): @@ -600,17 +644,21 @@ def request_localize(self, estimate, mission: MissionHandle): estimate.map, estimate.position, estimate.graph_index ) if mission_queue_id is not None: - self.node.get_logger().info(f'Localize mission is successfully queued!') + self.node.get_logger().info( + f'[{self.name}] Localize mission is successfully ' + f'queued!') break except Exception as err: self.node.get_logger().info( - f'Failed to localize on map {estimate.map}: {err}. Retrying...' + f'Failed to localize on map {estimate.map}: {err}. ' + f'Retrying...' ) time.sleep(1) if not mission_queue_id: self.node.get_logger().info( - f'Failed to localize on map {estimate.map}. Maximum localize retries exceeded!' + f'[{self.name}] Failed to localize on map {estimate.map}. ' + f'Maximum localize retries exceeded!' ) mission.execution.finished() mission_queue_id = None @@ -621,7 +669,9 @@ def request_localize(self, estimate, mission: MissionHandle): def perform_action(self, category, description, execution): if self.current_action: # Should not reach here, but we log an error anyway - self.node.get_logger().info(f'Robot is busy with another perform action! Ignoring new action [{category}]') + self.node.get_logger().info( + f'Robot [{self.name}] is busy with another perform action! ' + f'Ignoring new action [{category}]') execution.finished() return @@ -632,12 +682,9 @@ def perform_action(self, category, description, execution): module = config['module'] plugin = importlib.import_module(module) # Create the relevant MirAction - action_obj = plugin.ActionFactory().make_action(self.node, - self.name, - self.api, - self.update_handle, - self.fleet_config, - config) + action_obj = plugin.ActionFactory().make_action( + self.node, self.name, self.api, self.update_handle, + self.fleet_config, config) # Begin performing the plugin action action_obj.perform_action(category, description, execution) # Keep track of the current action @@ -645,10 +692,11 @@ def perform_action(self, category, description, execution): return # No relevant perform action found - self.node.get_logger().info(f'Perform action [{category}] was not configured for this fleet') + self.node.get_logger().info( + f'Perform action [{category}] was not configured for this fleet') raise NotImplementedError def dist(self, A, B): - assert(len(A) > 1) - assert(len(B) > 1) + assert (len(A) > 1) + assert (len(B) > 1) return math.sqrt((A[0] - B[0])**2 + (A[1] - B[1])**2) diff --git a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/mir_action.py b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/mir_action.py index a88694d..658c4bd 100644 --- a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/mir_action.py +++ b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/mir_action.py @@ -34,7 +34,7 @@ def __init__( # Check if these missions are already created on the robot missions_created = True for mission_name in action_missions.keys(): - if not mission_name in self.api.known_missions: + if mission_name not in self.api.known_missions: missions_created = False break if missions_created: @@ -44,19 +44,21 @@ def __init__( self.api.create_missions(action_missions) # Update mission actions stored in MirAPI for mission, mission_data in self.api.known_missions.items(): - self.api.mission_actions[mission] = self.api.missions_mission_id_actions_get(mission_data['guid']) + self.api.mission_actions[mission] = \ + self.api.missions_mission_id_actions_get( + mission_data['guid']) # This will be called whenever an action has begun @abstractmethod def perform_action(self, category: str, description: dict, - execution # rmf_fleet_adapter.ActionExecution - ): + execution): # rmf_fleet_adapter.ActionExecution # To be populated in the plugins ... - # This will be called on every update to check on the action's current state + # This will be called on every update to check on the action's + # current state @abstractmethod def update_action(self): # To be populated in the plugins @@ -67,15 +69,21 @@ def cancel_current_task(self, cancel_fail: Callable[[], None], label: str = ''): current_task_id = self.update_handle.more().current_task_id() - self.node.get_logger().info(f'Cancel task requested for [{current_task_id}]') + self.node.get_logger().info( + f'[{self.name}] Cancel task requested for [{current_task_id}]') + def _on_cancel(result: bool): if result: - self.node.get_logger().info(f'Found task [{current_task_id}], cancelling...') + self.node.get_logger().info( + f'[{self.name}] Found task [{current_task_id}], ' + f'cancelling...') cancel_success() else: - self.node.get_logger().info(f'Failed to cancel task [{current_task_id}]') + self.node.get_logger().info( + f'[{self.name}] Failed to cancel task [{current_task_id}]') cancel_fail() - self.update_handle.more().cancel_task(current_task_id, [label], lambda result: _on_cancel(result)) + self.update_handle.more().cancel_task( + current_task_id, [label], lambda result: _on_cancel(result)) class MirActionFactory(ABC): diff --git a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py index 7188c87..194f3a0 100644 --- a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py +++ b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py @@ -31,7 +31,7 @@ def __init__(self, queue_id: str, start_time: float): @dataclass class Pickup: state: PickupState - pickup_lots: list[str] # contains either a single pickup lot or list of pickup lots + pickup_lots: list[str] # contains list of pickup lots cart_id: str execution: Any mission: Mission @@ -52,7 +52,8 @@ def make_action(self, update_handle, fleet_config, action_config) -> MirAction: - return CartDelivery(node, name, mir_api, update_handle, fleet_config, action_config) + return CartDelivery( + node, name, mir_api, update_handle, fleet_config, action_config) class CartDelivery(MirAction): @@ -63,23 +64,32 @@ def __init__( mir_api, update_handle, fleet_config, - action_config - ): - MirAction.__init__(self, node, name, mir_api, update_handle, fleet_config, action_config) + action_config): + MirAction.__init__( + self, node, name, mir_api, update_handle, fleet_config, + action_config) self.pickup: Pickup = None self.dropoff: Dropoff = None - self.search_timeout = self.action_config.get('search_timeout', 60) # seconds + self.search_timeout = \ + self.action_config.get('search_timeout', 60) # seconds # Store the mission names to be used during the action - self.dock_to_cart_mission = self.action_config['missions']['dock_to_cart'] - self.pickup_mission = self.action_config['missions']['pickup'] - self.dropoff_mission = self.action_config['missions']['dropoff'] - self.exit_mission = self.action_config['missions']['exit_lot'] - self.footprint_mission = self.action_config['missions'].get('update_footprint') # Optional + self.dock_to_cart_mission = \ + self.action_config['missions']['dock_to_cart'] + self.pickup_mission = \ + self.action_config['missions']['pickup'] + self.dropoff_mission = \ + self.action_config['missions']['dropoff'] + self.exit_mission = \ + self.action_config['missions']['exit_lot'] + self.footprint_mission = \ + self.action_config['missions'].get('update_footprint') # Optional # Initialize cart marker type - self.cart_marker_type_guid = self.api.docking_offsets_guid_get(self.action_config['marker_types']['cart']) + self.cart_marker_type_guid = \ + self.api.docking_offsets_guid_get( + self.action_config['marker_types']['cart']) # Import CartDetection module if provided detection_module = self.action_config.get('cart_detection_module') @@ -87,7 +97,8 @@ def __init__( 'CartDetection module is required for CartDelivery plugin, ' + 'but it is not found!') detection_plugin = importlib.import_module(detection_module) - self.cart_detection = detection_plugin.CartDetection(mir_api, action_config) + self.cart_detection = \ + detection_plugin.CartDetection(mir_api, action_config) def perform_action(self, category, description, execution): # Check that the perform action category matches @@ -96,32 +107,39 @@ def perform_action(self, category, description, execution): # Check if the robot's latch is currently open if self.is_latch_open(): # Latch is open, unable to perform pickup - self.node.get_logger().info(f'Robot [{self.name}] latch is open, unable to perform pickup, cancelling task...') + self.node.get_logger().info( + f'Robot [{self.name}] latch is open, unable to ' + f'perform pickup, cancelling task...') self.cancel_task() return - self.node.get_logger().info(f'New pickup requested for robot [{self.name}]') + self.node.get_logger().info( + f'New pickup requested for robot [{self.name}]') self.pickup = Pickup( state=PickupState.AT_PICKUP, - pickup_lots=[description.get('pickup_lot')], # TODO(XY): Allow multiple pickups? + pickup_lots=[description.get('pickup_lot')], cart_id=description.get('cart_id'), execution=execution, mission=None, latching=False ) case 'delivery_dropoff': - self.node.get_logger().info(f'Received dropoff request!') + self.node.get_logger().info( + f'[{self.name}] Received dropoff request!') self.dropoff = Dropoff( execution=execution, mission=None ) case _: - self.node.get_logger().info(f'Invalid perform action [{category}] passed to CartDelivery, ending action.') + self.node.get_logger().info( + f'Invalid perform action [{category}] passed to ' + f'CartDelivery, ending action.') execution.finished() def update_action(self): - # There should not be a pickup and dropoff being performed simultaneously at any given time, since actions are - # dispatched sequentially + # There should not be a pickup and dropoff being performed + # simultaneously at any given time, since actions are dispatched + # sequentially if self.pickup: return self.update_pickup(self.pickup) elif self.dropoff: @@ -130,9 +148,11 @@ def update_action(self): return False def update_pickup(self, pickup: Pickup): - # If this is a PerformAction pickup, check that the action is underway and valid + # If this is a PerformAction pickup, check that the action is underway + # and valid if pickup.execution is not None and not pickup.execution.okay(): - self.node.get_logger().info(f'[delivery_pickup] action is killed/canceled.') + self.node.get_logger().info( + f'[delivery_pickup] action is killed/canceled.') pickup.state = PickupState.TASK_CANCELLED # Start state machine check @@ -145,48 +165,74 @@ def update_pickup(self, pickup: Pickup): current_wp_name = pickup.pickup_lots[0] mir_pos = self.api.known_positions.get(current_wp_name) if not mir_pos: - self.node.get_logger().info(f'No shelf position [{mir_pos}] found on robot [{self.name}], cancelling task') + self.node.get_logger().info( + f'No shelf position [{mir_pos}] found on robot ' + f'[{self.name}], cancelling task') self.cancel_task() pickup.state = PickupState.TASK_CANCELLED return cart_marker_guid = mir_pos['guid'] - cart_marker_param = self.api.get_mission_params_with_value(self.dock_to_cart_mission, 'docking', 'cart_marker', cart_marker_guid) - marker_type_param = self.api.get_mission_params_with_value(self.dock_to_cart_mission, 'docking', 'cart_marker_type', self.cart_marker_type_guid) + cart_marker_param = self.api.get_mission_params_with_value( + self.dock_to_cart_mission, + 'docking', + 'cart_marker', + cart_marker_guid) + marker_type_param = self.api.get_mission_params_with_value( + self.dock_to_cart_mission, + 'docking', + 'cart_marker_type', + self.cart_marker_type_guid) mission_params = cart_marker_param + marker_type_param - mission_queue_id = self.api.queue_mission_by_name(self.dock_to_cart_mission, mission_params) + mission_queue_id = self.api.queue_mission_by_name( + self.dock_to_cart_mission, mission_params) if not mission_queue_id: - error_str = f'Mission {self.dock_to_cart_mission} not supported, ignoring' + error_str = \ + f'Mission {self.dock_to_cart_mission} not ' + \ + f'supported, ignoring' self.node.get_logger().error(error_str) return pickup.mission = Mission(mission_queue_id, now) pickup.state = PickupState.DOCK_REQUESTED - self.node.get_logger().info(f'Dock to cart mission requested with mission queue id {mission_queue_id}') + self.node.get_logger().info( + f'[{self.name}] Dock to cart mission requested with ' + f'mission queue id {mission_queue_id}') case PickupState.DOCK_REQUESTED: # Make sure that there is an rmf_dock_to_cart mission issued if not pickup.mission: - self.node.get_logger().info(f'Robot [{self.name}] is indicated to be at the DOCK_REQUESTED state but ' - f'no mission queue ID stored for this docking mission! Returning to AT_PICKUP state.') + self.node.get_logger().info( + f'Robot [{self.name}] is indicated to be at the ' + f'DOCK_REQUESTED state but no mission queue ID stored ' + f'for this docking mission! Returning to AT_PICKUP ' + f'state.') pickup.state = PickupState.AT_PICKUP return # Mission completed, move onto the next state if self.api.mission_completed(pickup.mission.queue_id): - self.node.get_logger().info(f'Robot [{self.name}] dock to cart mission {pickup.mission.queue_id} completed or timed out.') + self.node.get_logger().info( + f'Robot [{self.name}] dock to cart mission ' + f'{pickup.mission.queue_id} completed or timed out.') pickup.mission = None pickup.state = PickupState.DOCK_COMPLETED return - # Mission not yet completed, we check the timeout status to decide if we need to publish any alert + # Mission not yet completed, we check the timeout status to + # decide if we need to publish any alert seconds_passed = now - pickup.mission.start_time # Publish update every 10 seconds just to monitor - if round(seconds_passed)%10 == 0: - self.node.get_logger().info(f'{round(seconds_passed)} seconds have passed since pickup mission requested.') + if round(seconds_passed) % 10 == 0: + self.node.get_logger().info( + f'{round(seconds_passed)} seconds have passed since ' + f'pickup mission requested.') # Mission timeout, cart not found if seconds_passed > self.search_timeout: # Delete mission from mir first self.api.mission_queue_id_delete(pickup.mission.queue_id) - # Regardless of whether the robot completed docking properly, we move to the next state to check - self.node.get_logger().info(f'Robot [{self.name}] dock to cart mission {pickup.mission.queue_id} timed out! ' - f'Configured search timeout is {self.search_timeout} seconds.') + # Regardless of whether the robot completed docking + # properly, we move to the next state to check + self.node.get_logger().info( + f'Robot [{self.name}] dock to cart mission ' + f'{pickup.mission.queue_id} timed out! Configured ' + f'search timeout is {self.search_timeout} seconds.') pickup.mission = None pickup.state = PickupState.DOCK_COMPLETED return @@ -197,23 +243,35 @@ def update_pickup(self, pickup: Pickup): if cart_check: # If cart is correct, send pickup mission assert self.pickup_mission is not None - mission_queue_id = self.api.queue_mission_by_name(self.pickup_mission) + mission_queue_id = self.api.queue_mission_by_name( + self.pickup_mission) if not mission_queue_id: - error_str = f'Mission {self.pickup_mission} not supported, ignoring' + error_str = \ + f'Mission {self.pickup_mission} not supported,' + \ + f' ignoring' self.node.get_logger().error(error_str) return pickup.mission = Mission(mission_queue_id, now) pickup.latching = True - self.node.get_logger().info(f'Robot [{self.name}] found the correct cart, pickup mission requested with mission queue id {mission_queue_id}') + self.node.get_logger().info( + f'Robot [{self.name}] found the correct cart, pickup ' + f'mission requested with mission queue id ' + f'{mission_queue_id}') pickup.state = PickupState.PICKUP_REQUESTED elif cart_check is None: # If cart is missing, cancel this task - self.node.get_logger().info(f'Robot [{self.name}] was unable to dock under any carts, please check that cart is present. Cancelling task.') + self.node.get_logger().info( + f'Robot [{self.name}] was unable to dock under any ' + f'carts, please check that cart is present. ' + f'Cancelling task.') self.cancel_task() pickup.state = PickupState.TASK_CANCELLED else: - # If cart is wrong, cancel this task also but after we exit from the lot - self.node.get_logger().info(f'Robot [{self.name}] found the wrong cart, exiting lot and cancelling task.') + # If cart is wrong, cancel this task also but after we + # exit from the lot + self.node.get_logger().info( + f'Robot [{self.name}] found the wrong cart, exiting ' + f'lot and cancelling task.') self.exit_lot() self.cancel_task() pickup.state = PickupState.TASK_CANCELLED @@ -227,18 +285,25 @@ def update_pickup(self, pickup: Pickup): case PickupState.PICKUP_SUCCESS: # Correct ID, we can end the delivery now - self.node.get_logger().info(f'Robot [{self.name}] successfully received cart, exiting lot with cart and ending mission') + self.node.get_logger().info( + f'Robot [{self.name}] successfully received cart, ' + f'exiting lot with cart and ending mission') self.exit_lot() if pickup.execution is not None: pickup.execution.finished() return True case PickupState.TASK_CANCELLED: - self.node.get_logger().info(f'Robot [{self.name}] is in pickup cancelled state.') - # If some MiR mission is in progress, we abort it unless it is latching - if pickup.mission and not self.api.mission_completed(pickup.mission.queue_id): + self.node.get_logger().info( + f'Robot [{self.name}] is in pickup cancelled state.') + # If some MiR mission is in progress, we abort it unless + # it is latching + if pickup.mission and not self.api.mission_completed( + pickup.mission.queue_id): if pickup.latching: - self.node.get_logger().info(f'Robot [{self.name}] is performing latching, cancelling task after this action is complete.') + self.node.get_logger().info( + f'Robot [{self.name}] is performing latching, ' + f'cancelling task after this action is complete.') return False self.api.mission_queue_id_delete(pickup.mission.queue_id) pickup.mission = None @@ -257,11 +322,12 @@ def update_dropoff(self, dropoff: Dropoff): self.node.get_logger().info(f'Dropoff action is killed/canceled') # If cart release is in progress, we let it finish first - if dropoff.mission and not self.api.mission_completed(dropoff.mission.queue_id): + if dropoff.mission and not self.api.mission_completed( + dropoff.mission.queue_id): return False - # Task is cancelled and cart is done dropping off/mission is not yet queued anyway, - # we can mark it as completed at this point + # Task is cancelled and cart is done dropping off/mission is not + # yet queued anyway, we can mark it as completed at this point self.api.clear_error() self.api.status_put(state_id=MiRStateCode.READY) # Mark dropoff session as completed @@ -270,33 +336,42 @@ def update_dropoff(self, dropoff: Dropoff): # No mission queued yet if dropoff.mission is None: assert self.dropoff_mission is not None - mission_queue_id = self.api.queue_mission_by_name(self.dropoff_mission) + mission_queue_id = self.api.queue_mission_by_name( + self.dropoff_mission) if not mission_queue_id: - error_str = f'Mission {self.dropoff_mission} not supported, ignoring' + error_str = \ + f'Mission {self.dropoff_mission} not supported, ignoring' self.node.get_logger().error(error_str) return True - self.node.get_logger().info(f'Mission {self.dropoff_mission} added to queue for robot [{self.name}].') + self.node.get_logger().info( + f'Mission {self.dropoff_mission} added to queue for robot ' + f'[{self.name}].') now = self.node.get_clock().now().nanoseconds / 1e9 dropoff.mission = Mission(mission_queue_id, now) - self.node.get_logger().info(f'[{self.name}] Dropoff mission requested with mission queue id {mission_queue_id}') + self.node.get_logger().info( + f'[{self.name}] Dropoff mission requested with mission queue ' + f'id {mission_queue_id}') # Mission queued, check completion else: if self.api.mission_completed(dropoff.mission.queue_id): - self.node.get_logger().info(f'[{self.name}] Dropoff mission completed!') + self.node.get_logger().info( + f'[{self.name}] Dropoff mission completed!') # Update robot footprint if dropoff.execution is not None: dropoff.execution.finished() return True else: - self.node.get_logger().info(f'[{self.name}] Dropoff mission in progress...') + self.node.get_logger().info( + f'[{self.name}] Dropoff mission in progress...') return def cancel_task(self, label: str = ''): def _cancel_success(): if self.pickup: self.pickup.state = PickupState.TASK_CANCELLED + def _cancel_fail(): pass self.cancel_current_task(_cancel_success, _cancel_fail, label) @@ -319,50 +394,57 @@ def exit_lot(self): def release_cart(self): # If robot latch is open, close it if self.is_latch_open(): - self.node.get_logger().info(f'Robot [{self.name}] detected to have latch open, dropping off cart...') + self.node.get_logger().info( + f'Robot [{self.name}] detected to have latch open, dropping ' + f'off cart...') self.dropoff = Dropoff( execution=None, mission_queue_id=None) - # Dropoff mission will take care of the lot exit, so we can return here + # Dropoff mission will take care of the lot exit, + # so we can return here return # If robot is under a cart, exit lot if self.is_under_cart(): - self.node.get_logger().info(f'Cart detected above robot [{self.name}] during a release call, exiting lot...') + self.node.get_logger().info( + f'Cart detected above robot [{self.name}] during a release ' + f'call, exiting lot...') self.exit_lot() - # Optional function for updating robot footprint by providing footprint guid + # Optional function for updating robot footprint by providing + # footprint guid def update_footprint(self, ft_guid: str): if not self.footprint_mission: return - ft_params = self.api.get_mission_params_with_value(self.footprint_mission, - 'set_footprint', - 'footprint', - ft_guid) - return self.api.queue_mission_by_name(self.footprint_mission, ft_params) + ft_params = self.api.get_mission_params_with_value( + self.footprint_mission, 'set_footprint', 'footprint', ft_guid) + return self.api.queue_mission_by_name( + self.footprint_mission, ft_params) def retrieve_mir_coordinates(self, waypoint_name: str): transform = self.fleet_config.transformations_to_robot_coordinates transform_current_map = transform.get(self.current_map) - rmf_pose = self.fleet_config.graph.find_waypoint(waypoint_name).location + rmf_pose = \ + self.fleet_config.graph.find_waypoint(waypoint_name).location new_rmf_pose = np.array([rmf_pose[0], rmf_pose[1], 0.0]) mir_pose = transform_current_map.apply(new_rmf_pose) return mir_pose def dist(self, A, B): - assert(len(A) > 1) - assert(len(B) > 1) + assert (len(A) > 1) + assert (len(B) > 1) return math.sqrt((A[0] - B[0])**2 + (A[1] - B[1])**2) - - # ------------------------------------------------------------------------------------------------------------------ + # -------------------------------------------------------------------------- # MIR API FOR CART RELATED MISSIONS - # ------------------------------------------------------------------------------------------------------------------ - + # -------------------------------------------------------------------------- def register_get(self, register: int): if not self.api.connected: return None try: - response = requests.get(self.api.prefix + f'registers/{register}', headers = self.api.headers, timeout = self.api.timeout) + response = requests.get( + self.api.prefix + f'registers/{register}', + headers=self.api.headers, + timeout=self.api.timeout) if self.api.debug: print(f"Response: {response.headers}") # Response value is string, return integer of value @@ -380,7 +462,10 @@ def io_module_guid_status_get(self, io_guid: str): if io_guid is None: return None try: - response = requests.get(self.api.prefix + f'io_modules/{io_guid}/status', headers = self.api.headers, timeout = self.api.timeout) + response = requests.get( + self.api.prefix + f'io_modules/{io_guid}/status', + headers=self.api.headers, + timeout=self.api.timeout) if self.api.debug: print(f"Response: {response.headers}") if 'input_state' not in response.json(): @@ -397,7 +482,10 @@ def io_modules_get(self): if not self.api.connected: return None try: - response = requests.get(self.api.prefix + f'io_modules', headers = self.api.headers, timeout = self.api.timeout) + response = requests.get( + self.api.prefix + f'io_modules', + headers=self.api.headers, + timeout=self.api.timeout) if self.api.debug: print(f"Response: {response.headers}") # Response value is string, return integer of value diff --git a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_detection.py b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_detection.py index c209270..f563155 100644 --- a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_detection.py +++ b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_detection.py @@ -1,6 +1,7 @@ import requests from urllib.error import HTTPError + class CartDetection: def __init__( self, @@ -49,9 +50,10 @@ def register_get(self, register: int): if not self.api.connected: return None try: - response = requests.get(self.api.prefix + f'registers/{register}', - headers=self.api.headers, - timeout=self.api.timeout) + response = requests.get( + self.api.prefix + f'registers/{register}', + headers=self.api.headers, + timeout=self.api.timeout) if self.api.debug: print(f"Response: {response.headers}") # Response value is string, return integer of value @@ -69,10 +71,10 @@ def io_module_guid_status_get(self, io_guid: str): if io_guid is None: return None try: - response = requests.get(self.api.prefix + - f'io_modules/{io_guid}/status', - headers=self.api.headers, - timeout=self.api.timeout) + response = requests.get( + self.api.prefix + f'io_modules/{io_guid}/status', + headers=self.api.headers, + timeout=self.api.timeout) if self.api.debug: print(f"Response: {response.headers}") if 'input_state' not in response.json(): @@ -89,9 +91,10 @@ def io_modules_get(self): if not self.api.connected: return None try: - response = requests.get(self.api.prefix + f'io_modules', - headers=self.api.headers, - timeout=self.api.timeout) + response = requests.get( + self.api.prefix + f'io_modules', + headers=self.api.headers, + timeout=self.api.timeout) if self.api.debug: print(f"Response: {response.headers}") # Response value is string, return integer of value @@ -101,4 +104,4 @@ def io_modules_get(self): return None except Exception as err: print(f"Other error: {err}") - return None \ No newline at end of file + return None diff --git a/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_delivery.py b/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_delivery.py index b21c35c..15b3246 100644 --- a/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_delivery.py +++ b/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_delivery.py @@ -112,18 +112,20 @@ def __init__(self, argv=sys.argv): }] description["phases"].append( {"activity": {"category": "sequence", - "description": {"activities": go_to_pickup_activity}}}) - pickup_action_activity = [{"category": "perform_action", - "description": { - "unix_millis_action_duration_estimate": 60000, - "category": 'delivery_pickup', - "description": { - "cart_id": self.args.cart_id, - "pickup_lot": self.args.pickup_lot - }}}] + "description": { + "activities": go_to_pickup_activity}}}) + pickup_action_activity = [{ + "category": "perform_action", + "description": { + "unix_millis_action_duration_estimate": 60000, + "category": 'delivery_pickup', + "description": { + "cart_id": self.args.cart_id, + "pickup_lot": self.args.pickup_lot}}}] description["phases"].append( {"activity": {"category": "sequence", - "description": {"activities": pickup_action_activity}}}) + "description": { + "activities": pickup_action_activity}}}) # GoToPlace activity go_to_dropoff_activity = [{ "category": "go_to_place", @@ -131,7 +133,8 @@ def __init__(self, argv=sys.argv): }] description["phases"].append( {"activity": {"category": "sequence", - "description": {"activities": go_to_dropoff_activity}}}) + "description": { + "activities": go_to_dropoff_activity}}}) # Dropoff activity dropoff_action_activity = [{ "category": "perform_action", @@ -143,7 +146,8 @@ def __init__(self, argv=sys.argv): }] description["phases"].append( {"activity": {"category": "sequence", - "description": {"activities": dropoff_action_activity}}}) + "description": { + "activities": dropoff_action_activity}}}) # Consolidate request["description"] = description payload["request"] = request From 933358f8a73b2050d60473ee1b5c28926f0e9020 Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Tue, 30 Jul 2024 18:11:22 +0800 Subject: [PATCH 26/46] Update README with instruction to write own CartDetection module Signed-off-by: Xiyu Oh --- fleet_adapter_mir/README.md | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/fleet_adapter_mir/README.md b/fleet_adapter_mir/README.md index 6ae44e6..e9b13c2 100644 --- a/fleet_adapter_mir/README.md +++ b/fleet_adapter_mir/README.md @@ -73,7 +73,7 @@ Upon launch, the MiR fleet adapter recognizes MiR positions with identical names ### Plugins -The MiR is capable of performing various types of custom missions and tasks. You can now easily set up plugins offered in this repo instead of writing your own perform action for common use cases. +The MiR is capable of performing various types of custom missions and tasks. You can now easily set up plugins offered in this repo instead of writing your own perform action for common use cases. These plugins offered are available under the `fleet_adapter_mir_actions` package. For cart deliveries from point A to B: @@ -91,17 +91,18 @@ Some relevant MiR missions (docking, exit, update footprint) will be automatical They are defined and stored in the `rmf_cart_missions.json` file and do not require any further configuration. -However, since there are various types of latching methods available for different MiR models, users will need to set up their custom pickup and dropoff missions on the MiR: +However, since there are various types of latching methods available for different MiR models, users will need to set up their custom pickup and dropoff missions on the MiR, as well as implement their own `CartDetection` plugin module with the appropriate APIs to detect latching states. 1. Create 2 missions on the MiR: - `rmf_pickup_cart`: Triggers the robot's latching module to open - `rmf_dropoff_cart`: Triggers the robot's latching module to close and release the cart, then exit from under the cart (relative move -1 metre in the X-direction) 2. Fill in the MiR mission names in the plugin config under `missions`. The default mission names are `rmf_pickup_cart` and `rmf_dropoff_cart`. 3. Fill in the footprints and marker types to be used for your specific robot and cart in the plugin config. -4. In `rmf_cart_delivery.py`, fill in the logic to check whether the robot's latching module is open in blanks marked `# IMPLEMENT YOUR CODE HERE`. Some API calls to check the MiR's PLC registers and IO modules are provided in case you may want to use them. +4. Create your own `CartDetection` plugin. You may use `rmf_cart_detection.py` as a reference for how your plugin module should be implemented. Fill in the logic to check whether the robot's latching module is open in blanks marked `# IMPLEMENT YOUR CODE HERE`. Some API calls to check the MiR's PLC registers and IO modules are provided in case you may want to use them. +5. In the plugin config, update the `cart_detection_module` field to point to your own written module. -To submit a cart delivery task, you may use the `dispatch_pickup` task script: +To submit a cart delivery task, you may use the `dispatch_delivery` task script found in the `fleet_adapter_mir_tasks` package: ```bash -ros2 run fleet_adapter_mir_tasks dispatch_pickup -g go_to_waypoint -p pickup_lot -d dropoff_lot -c some_cart_id +ros2 run fleet_adapter_mir_tasks dispatch_delivery -g go_to_waypoint -p pickup_lot -d dropoff_lot -c some_cart_id ``` - `-g`: Takes in an existing waypoint name for the robot to travel to before performing the pickup - `-p`: Name of the pickup lot. This name should be identical to the shelf position configured on the MiR. From 52c4fbdce74e86deaaa96792baececbb491ee0ce Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Fri, 2 Aug 2024 11:29:00 +0800 Subject: [PATCH 27/46] Remove position_put logic when localizing to prevent overwriting existing MiR coords Signed-off-by: Xiyu Oh --- fleet_adapter_mir/fleet_adapter_mir/mir_api.py | 15 +++++++-------- 1 file changed, 7 insertions(+), 8 deletions(-) diff --git a/fleet_adapter_mir/fleet_adapter_mir/mir_api.py b/fleet_adapter_mir/fleet_adapter_mir/mir_api.py index 6f34769..385c5e3 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/mir_api.py +++ b/fleet_adapter_mir/fleet_adapter_mir/mir_api.py @@ -397,15 +397,14 @@ def position_matches(pos): # The position does not exist so we need to create a new one position_guid = self.positions_post(name, map_id, location) if position_guid is not None: + print( + f'Successfully posted position {name} on MiR with ' + f'location {location}' + ) return position_guid - # For some reason posting the new position failed. Maybe there - # was a timeout or an argument error. We will update the known - # positions and retry this loop. - self.update_known_positions() - elif not position_matches(position): - if self.positions_put( - position['guid'], name, map_id, location): - return position['guid'] + print( + f'Unable to post position {name} on MiR!' + ) else: return position['guid'] From 47d5488f62f8866bbb2c35b8f73aecdd69643b87 Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Fri, 2 Aug 2024 14:06:16 +0800 Subject: [PATCH 28/46] Add disconnect mutex Signed-off-by: Xiyu Oh --- .../fleet_adapter_mir/robot_adapter_mir.py | 137 ++++++++++++------ 1 file changed, 89 insertions(+), 48 deletions(-) diff --git a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py index 3b3d296..7f648bd 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py +++ b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py @@ -82,6 +82,8 @@ def __init__( self.debug = debug self.disconnect = False + self.disconnect_mutex = Lock() + self.replan_after_disconnect = False prefix = mir_config['base_url'] headers = { @@ -154,56 +156,67 @@ async def update_loop(self, period): @parallel def request_update(self): - # Retrieve the latest MiR status from robot - status = self.api.status_get() - if status is None: - self.disconnect = True - self.node.get_logger().warn( - f'Unable to retrieve status from robot [{self.name}]!') - return - if self.disconnect: - self.node.get_logger().info( - f'Robot [{self.name}] connectivity resumed, received status ' - f'from robot successfully.') - self.disconnect = False - more = self.update_handle.more() - if more is not None: - more.unstable_debug_positions(self.debug) - - # Update the stored mission status from MiR - mission = self.mission - self.update_mission_status(status, mission) - - # Update RMF with the latest RobotState - if (mission is None or (mission.localize and mission.done) or - not mission.localize): - self.update_handle.update(status.state, self.activity) - self.last_known_status = status - else: - self.node.get_logger().info( - f'Mission is None / Robot is localizing, ignore status update') - - # Update RMF to mark the ActionExecution as finished - if mission is not None and mission.done: - self.update_rmf_finished(mission) + with self.disconnect_mutex: + # Retrieve the latest MiR status from robot + status = self.api.status_get() + if status is None: + self.disconnect = True + self.node.get_logger().warn( + f'Unable to retrieve status from robot [{self.name}]!') + return + if self.disconnect: + self.node.get_logger().info( + f'Robot [{self.name}] connectivity resumed, received status ' + f'from robot successfully.') + self.disconnect = False + more = self.update_handle.more() + if more is not None: + more.unstable_debug_positions(self.debug) + + # Update the stored mission status from MiR + mission = self.mission + self.update_mission_status(status, mission) - # PerformAction related checks - if self.current_action: - if self.current_action.update_action(): - # This means that the action has ended, we can clear the - # current action object + # Update RMF with the latest RobotState + if (mission is None or (mission.localize and mission.done) or + not mission.localize): + self.update_handle.update(status.state, self.activity) + self.last_known_status = status + else: self.node.get_logger().info( - f'Robot [{self.name}] has completed its current action.') - self.current_action = None - - # Clear error on updates - if (status is not None and 'errors' in status.response and - len(status.response['errors']) > 0): - self.api.clear_error() - if (status is not None and - (status.response['state_id'] == MiRStateCode.PAUSE or - status.response['state_id'] == MiRStateCode.ERROR)): - self.api.status_put(MiRStateCode.READY) + f'Mission is None / Robot is localizing, ignore status update') + + # Update RMF to mark the ActionExecution as finished + if mission is not None and mission.done: + self.update_rmf_finished(mission) + + # Check if we need to replan after a disconnect, making sure that + # we have completed any ongoing mission and have updated the EFC + # handle with our latest robot status + if self.replan_after_disconnect and ( + mission is None or (mission and mission.done) + ): + if more is not None: + more.replan() + self.replan_after_disconnect = False + + # PerformAction related checks + if self.current_action: + if self.current_action.update_action(): + # This means that the action has ended, we can clear the + # current action object + self.node.get_logger().info( + f'Robot [{self.name}] has completed its current action.') + self.current_action = None + + # Clear error on updates + if (status is not None and 'errors' in status.response and + len(status.response['errors']) > 0): + self.api.clear_error() + if (status is not None and + (status.response['state_id'] == MiRStateCode.PAUSE or + status.response['state_id'] == MiRStateCode.ERROR)): + self.api.status_put(MiRStateCode.READY) def is_charging(self, status: MirStatus): # Note: Not the best way to verify that robot is charging but there's @@ -322,6 +335,22 @@ def _make_callbacks(self): return callbacks def navigate(self, destination, execution): + # If robot is disconnected and we are unable to retrieve any robot + # status, we'll ignore all commands from RMF until robot is re-connected + with self.disconnect_mutex: + if self.disconnect: + self.node.get_logger().info( + f'Robot [{self.name}] received new navigation command while' + f' disconnected, ignoring command and requesting replan ' + f'after robot is re-connected.' + ) + self.replan_after_disconnect = True + return + + self.node.get_logger().info( + f'New navigation command received for [{self.name}]' + ) + # If the nav command coming in is to bring the robot to a charger, but # the robot is already charging at the same charger, we ignore this # nav command @@ -605,6 +634,18 @@ def request_dock( mission_handle.set_mission_queue_id(mission_queue_id) def stop(self, activity): + # If robot is disconnected and we are unable to retrieve any robot + # status, we'll ignore all commands from RMF until robot is re-connected + with self.disconnect_mutex: + if self.disconnect: + self.node.get_logger().info( + f'Robot [{self.name}] received new stop command while' + f' disconnected, ignoring command and requesting replan ' + f'after robot is re-connected.' + ) + self.replan_after_disconnect = True + return + mission = self.mission if mission is not None: if mission.docking: From d3bf9fe2148167faa702fb39f7fcb30f6b633673 Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Fri, 2 Aug 2024 16:11:06 +0800 Subject: [PATCH 29/46] Check config for lift or localize positions before requesting for localize missions Signed-off-by: Xiyu Oh --- fleet_adapter_mir/fleet_adapter_mir/mir_api.py | 14 ++++++++------ .../fleet_adapter_mir/robot_adapter_mir.py | 14 +++++++++++++- 2 files changed, 21 insertions(+), 7 deletions(-) diff --git a/fleet_adapter_mir/fleet_adapter_mir/mir_api.py b/fleet_adapter_mir/fleet_adapter_mir/mir_api.py index 385c5e3..40dd5a9 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/mir_api.py +++ b/fleet_adapter_mir/fleet_adapter_mir/mir_api.py @@ -341,17 +341,19 @@ def dock(self, mission_name, start_waypoint, end_waypoint): mission_params = end_param return self.queue_mission_by_name(mission_name, mission_params) - def localize(self, map, estimate, index): + def localize(self, map, estimate, index, position_name=None): if self.localize_mission is None: raise Exception( 'The fleet was not configured with a localize mission' ) - if index is not None: - position_name = f'rmf_localize_{index}' - else: - p = estimate - position_name = f'rmf_localize_{map}_{p[0]:.2f}_{p[1]:.2f}' + # If a MiR position is provided, we'll use that position directly + if position_name is None: + if index is not None: + position_name = f'rmf_localize_{index}' + else: + p = estimate + position_name = f'rmf_localize_{map}_{p[0]:.2f}_{p[1]:.2f}' mir_map = self.map_conversions.rmf_to_mir[map] map_id = self.known_maps[mir_map] position_guid = self.get_position_guid(position_name, map_id, estimate) diff --git a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py index 7f648bd..2f91715 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py +++ b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py @@ -680,9 +680,21 @@ def request_localize(self, estimate, mission: MissionHandle): mission_queue_id = None while count < retry_count and not mission_queue_id: count += 1 + + # If this localize request is being made for a map switch, and a + # MiR position is provided in the fleet config for this RMF lift + # waypoint, we can localize to that position directly + mir_position = None + if estimate.inside_lift: + lift_name = estimate.inside_lift.name + this_lift = self.lift_positions.get(lift_name) + if this_lift and this_lift.get(estimate.map): + mir_position = this_lift[estimate.map].get('name') + try: mission_queue_id = self.api.localize( - estimate.map, estimate.position, estimate.graph_index + estimate.map, estimate.position, estimate.graph_index, + mir_position ) if mission_queue_id is not None: self.node.get_logger().info( From c2ecf17c9e8b0c51dd2e81c519c3d076f6ab63e5 Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Fri, 2 Aug 2024 16:55:05 +0800 Subject: [PATCH 30/46] Style Signed-off-by: Xiyu Oh --- .../fleet_adapter_mir/robot_adapter_mir.py | 24 +++++++++++-------- 1 file changed, 14 insertions(+), 10 deletions(-) diff --git a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py index 2f91715..ac65831 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py +++ b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py @@ -166,8 +166,8 @@ def request_update(self): return if self.disconnect: self.node.get_logger().info( - f'Robot [{self.name}] connectivity resumed, received status ' - f'from robot successfully.') + f'Robot [{self.name}] connectivity resumed, received ' + f'status from robot successfully.') self.disconnect = False more = self.update_handle.more() if more is not None: @@ -184,7 +184,8 @@ def request_update(self): self.last_known_status = status else: self.node.get_logger().info( - f'Mission is None / Robot is localizing, ignore status update') + f'Mission is None / Robot is localizing, ignore status ' + f'update') # Update RMF to mark the ActionExecution as finished if mission is not None and mission.done: @@ -206,7 +207,8 @@ def request_update(self): # This means that the action has ended, we can clear the # current action object self.node.get_logger().info( - f'Robot [{self.name}] has completed its current action.') + f'Robot [{self.name}] has completed its current ' + f'action.') self.current_action = None # Clear error on updates @@ -215,7 +217,7 @@ def request_update(self): self.api.clear_error() if (status is not None and (status.response['state_id'] == MiRStateCode.PAUSE or - status.response['state_id'] == MiRStateCode.ERROR)): + status.response['state_id'] == MiRStateCode.ERROR)): self.api.status_put(MiRStateCode.READY) def is_charging(self, status: MirStatus): @@ -336,13 +338,14 @@ def _make_callbacks(self): def navigate(self, destination, execution): # If robot is disconnected and we are unable to retrieve any robot - # status, we'll ignore all commands from RMF until robot is re-connected + # status, we'll ignore all commands from RMF until robot is + # re-connected with self.disconnect_mutex: if self.disconnect: self.node.get_logger().info( - f'Robot [{self.name}] received new navigation command while' - f' disconnected, ignoring command and requesting replan ' - f'after robot is re-connected.' + f'Robot [{self.name}] received new navigation command ' + f'while disconnected, ignoring command and requesting ' + f'replan after robot is re-connected.' ) self.replan_after_disconnect = True return @@ -635,7 +638,8 @@ def request_dock( def stop(self, activity): # If robot is disconnected and we are unable to retrieve any robot - # status, we'll ignore all commands from RMF until robot is re-connected + # status, we'll ignore all commands from RMF until robot is + # re-connected with self.disconnect_mutex: if self.disconnect: self.node.get_logger().info( From 561044d22f4802b8ad9a280b1342ffbdb32e4bd5 Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Fri, 2 Aug 2024 18:26:14 +0800 Subject: [PATCH 31/46] Cleanup and add license declaration Signed-off-by: Xiyu Oh --- .../fleet_adapter_mir/fleet_adapter_mir.py | 14 ++++++++++ .../fleet_adapter_mir/mir_api.py | 27 ++++++++++--------- .../fleet_adapter_mir/robot_adapter_mir.py | 20 +++++++++----- .../fleet_adapter_mir_actions/mir_action.py | 13 +++++++++ .../rmf_cart_delivery.py | 14 ++++++++++ .../rmf_cart_detection.py | 14 ++++++++++ .../dispatch_delivery.py | 2 +- 7 files changed, 85 insertions(+), 19 deletions(-) diff --git a/fleet_adapter_mir/fleet_adapter_mir/fleet_adapter_mir.py b/fleet_adapter_mir/fleet_adapter_mir/fleet_adapter_mir.py index 3c0cc7c..0c36e34 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/fleet_adapter_mir.py +++ b/fleet_adapter_mir/fleet_adapter_mir/fleet_adapter_mir.py @@ -1,3 +1,17 @@ +# Copyright 2024 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import asyncio import sys import yaml diff --git a/fleet_adapter_mir/fleet_adapter_mir/mir_api.py b/fleet_adapter_mir/fleet_adapter_mir/mir_api.py index 40dd5a9..a6544a9 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/mir_api.py +++ b/fleet_adapter_mir/fleet_adapter_mir/mir_api.py @@ -1,10 +1,23 @@ +# Copyright 2024 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + from collections import namedtuple import copy import enum import math import requests import json -from icecream import ic from urllib.error import HTTPError from rmf_adapter.easy_full_control import RobotState @@ -66,7 +79,7 @@ def __init__(self, timeout=10.0, debug=False): self.prefix = prefix - self.debug = False + self.debug = debug self.headers = headers self.timeout = timeout self.connected = False @@ -385,16 +398,6 @@ def get_position_guid(self, name, map_id, location): # the MiR server has an acceptable position for us to use for # localization position = self.known_positions.get(name) - - def position_matches(pos): - if abs(pos['pos_x'] - location[0]) > 0.01: - return False - if abs(pos['pos_y'] - location[1]) > 0.01: - return False - if pos['map_id'] != map_id: - return False - return True - if position is None: # The position does not exist so we need to create a new one position_guid = self.positions_post(name, map_id, location) diff --git a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py index ac65831..3bc578e 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py +++ b/fleet_adapter_mir/fleet_adapter_mir/robot_adapter_mir.py @@ -1,13 +1,22 @@ +# Copyright 2024 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import math -import numpy as np -from icecream import ic -import enum -import copy import time from typing import Any from dataclasses import dataclass import json -import datetime from rmf_adapter.robot_update_handle import Tier import rmf_adapter.easy_full_control as rmf_easy import rclpy @@ -65,7 +74,6 @@ def __init__( name: str, rmf_config: rmf_easy.RobotConfiguration, mir_config: dict, - # pickup_config: dict, conversions: dict, rmf_missions: dict, fleet_handle, diff --git a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/mir_action.py b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/mir_action.py index 658c4bd..179b236 100644 --- a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/mir_action.py +++ b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/mir_action.py @@ -1,3 +1,16 @@ +# Copyright 2024 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. import json from abc import ABC, abstractmethod diff --git a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py index 194f3a0..7c50d20 100644 --- a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py +++ b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_delivery.py @@ -1,3 +1,17 @@ +# Copyright 2024 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import math import enum import numpy as np diff --git a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_detection.py b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_detection.py index f563155..fe25fb1 100644 --- a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_detection.py +++ b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_cart_detection.py @@ -1,3 +1,17 @@ +# Copyright 2024 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + import requests from urllib.error import HTTPError diff --git a/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_delivery.py b/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_delivery.py index 15b3246..b1d453e 100644 --- a/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_delivery.py +++ b/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_delivery.py @@ -1,6 +1,6 @@ #!/usr/bin/env python3 -# Copyright 2022 Open Source Robotics Foundation, Inc. +# Copyright 2024 Open Source Robotics Foundation, Inc. # # Licensed under the Apache License, Version 2.0 (the "License"); # you may not use this file except in compliance with the License. From f67cd203ee07b937a461dd9e7a48e94934315efe Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Tue, 6 Aug 2024 13:41:43 +0800 Subject: [PATCH 32/46] Add WaitUntil perform action with mission and PLC move off behavior Signed-off-by: Xiyu Oh --- configs/mir_config.yaml | 13 +- fleet_adapter_mir/setup.py | 1 + .../rmf_wait_until.py | 322 ++++++++++++++++++ 3 files changed, 335 insertions(+), 1 deletion(-) create mode 100644 fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_wait_until.py diff --git a/configs/mir_config.yaml b/configs/mir_config.yaml index b0177c9..08bf5b2 100644 --- a/configs/mir_config.yaml +++ b/configs/mir_config.yaml @@ -80,7 +80,7 @@ rmf_fleet: delivery: True clean: False finishing_request: "charge" # [park, charge, nothing] - actions: ["rmf_cart_delivery", "delivery_pickup", "delivery_dropoff"] + actions: ["rmf_cart_delivery", "delivery_pickup", "delivery_dropoff", "wait_until"] robots: mir_1: charger: "Charger_1" @@ -117,3 +117,14 @@ plugins: # Examples of additional fields for cart detection module io_name: "MiR internal IOs" latch_io: 2 + rmf_wait_until: + module: "fleet_adapter_mir_actions.rmf_wait_until" + class: "WaitUntil" + actions: ["wait_until"] + timeout: 1800 # seconds, default timeout if there is no move-off signal received + # Optional fields to configure default move-off signal + signal_type: "mission" # [mission, plc, or custom], if not provided the robot will wait the full duration of the default timeout + mission_name: "some_mission_name" # Required field if signal type is "mission". The mission will be queued when the action starts, and the robot will move off when the mission is completed. + resubmit_on_abort: False # Optional field for signal type "mission". Set to True to resubmit mission if the mission gets aborted by the robot. Default to False. + plc_register: 20 # Required field if signal type is "plc". Robot moves off when PLC register returns True + move_off_module: "fleet_adapter_mir_actions.rmf_move_off_alert" # Required field if signal type is "custom". Fill in with path to custom module written. diff --git a/fleet_adapter_mir/setup.py b/fleet_adapter_mir/setup.py index 1ce52ce..b9a7cf2 100644 --- a/fleet_adapter_mir/setup.py +++ b/fleet_adapter_mir/setup.py @@ -22,6 +22,7 @@ 'fleet_adapter_mir=fleet_adapter_mir.fleet_adapter_mir:main', 'rmf_cart_delivery=fleet_adapter_mir.rmf_cart_delivery:CartDelivery', 'rmf_cart_detection=fleet_adapter_mir.rmf_cart_detection:CartDetection', + 'rmf_wait_until=fleet_adapter_mir.rmf_wait_until:WaitUntil', ], }, ) diff --git a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_wait_until.py b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_wait_until.py new file mode 100644 index 0000000..91a1603 --- /dev/null +++ b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_wait_until.py @@ -0,0 +1,322 @@ +# Copyright 2024 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import time +from threading import Lock +import requests +from urllib.error import HTTPError + +from fleet_adapter_mir_actions.mir_action import MirAction, MirActionFactory +from fleet_adapter_mir.mir_api import MirAPI, MirStatus, MiRStateCode + + +class ActionFactory(MirActionFactory): + def make_action(self, + node, + name, + mir_api, + update_handle, + fleet_config, + action_config) -> MirAction: + return WaitUntil( + node, name, mir_api, update_handle, fleet_config, action_config) + + +class WaitUntil(MirAction): + def __init__( + self, + node, + name, + mir_api, + update_handle, + fleet_config, + action_config + ): + MirAction.__init__(self, node, name, mir_api, update_handle, + fleet_config, action_config) + + self.execution = None + self.mutex = Lock() + self.start_time = None + self.wait_timeout = action_config.get('timeout', 1800) # seconds + self.move_off_cb = None + + def perform_action(self, category, description, execution): + self.start_time = self.node.get_clock().now().nanoseconds / 1e9 + # Retrieve task description + if description.get('timeout') is not None: + self.wait_timeout = description['timeout'] + + # The only accepted action name is "wait_until" + if category != 'wait_until': + self.node.get_logger().info( + f'[{self.name}] Invalid perform action [{category}] passed ' + f'to WaitUntil, ending action.') + execution.finished() + return + + self.move_off_cb = self.create_move_off_cb(description) + + if self.move_off_cb is None: + # Insufficient information provided to configure the check move-off + # callback, mark action as completed and continue task + self.node.get_logger().info( + f'Insufficient information provided to configure the move-' + f'off behavior, ignoring WaitUntil action and marking action ' + f'as completed.' + ) + execution.finished() + return + + self.node.get_logger().info( + f'Robot [{self.name}] will start to perform wait_until ' + f'action with a timeout of {self.wait_timeout} seconds.' + ) + # Store this execution object + self.execution = execution + + def update_action(self): + if self.execution is None: + return + # Check if action has been cancelled or killed + if not self.execution.okay(): + self.node.get_logger().info( + f'[{self.name}] wait_until action has been killed/canceled' + ) + return True + + # Check if we've received a move-off signal + if self.move_off_cb(): + self.node.get_logger().info( + f'[{self.name}] has received move-off signal, marking ' + f'action as completed.' + ) + self.execution.finished() + return True + + # Check if the default timeout has passed + now = self.node.get_clock().now().nanoseconds / 1e9 + if now > self.start_time + self.wait_timeout: + self.node.get_logger().info( + f'Robot [{self.name}] has completed waiting for ' + f'{self.wait_timeout} seconds without move-off signal, ' + f'action as complete.' + ) + return True + + # Log the robot waiting every 30 seconds + seconds_passed = round(now - self.start_time) + if seconds_passed%30 == 0: + self.node.get_logger().info( + f'{seconds_passed} seconds have passed since robot ' + f'[{self.name}] started its waiting action.' + ) + + return False + + def create_move_off_cb(self, description: dict): + signal_cb = None + + # Determine which move-off behavior config to use. Any config populated + # in the task description overrides the default config provided in + # fleet config. + if 'signal_type' in description: + signal_config = description + elif 'signal_type' in self.action_config: + signal_config = self.action_config + else: + # We have no move-off behavior configured at all, we will just wait + # until we reach the default timeout + self.node.get_logger().info( + f'No move-off behavior was configured for [{self.name}], the ' + f'robot will begin waiting until the default timeout.' + ) + signal_cb = lambda: False + return signal_cb + + # Configure type of move off signal + signal_type = signal_config['signal_type'] + match signal_type: + case "mission": + mission_name = signal_config.get('mission_name', None) + resubmit_on_abort = signal_config.get('resubmit_on_abort', + False) + if mission_name is None: + self.node.get_logger().info( + f'No mission name provided!' + ) + return None + elif mission_name not in self.api.known_missions: + self.node.get_logger().info( + f'Mission {mission_name} not found on robot ' + f'{self.name}!' + ) + return None + mission_actions = self.api.missions_mission_id_actions_get( + self.api.known_missions[mission_name]['guid'] + ) + if not mission_actions: + self.node.get_logger().info( + f'Mission {mission_name} actions not found on robot ' + f'{self.name}!' + ) + return None + # Queue the waiting mission for this robot + retry_count = 10 + count = 0 + mission_queue_id = None + while count < retry_count and not mission_queue_id: + count += 1 + self.node.get_logger().info( + f'Queueing mission {mission_name} for robot ' + f'[{self.name}]...' + ) + try: + mission_queue_id = self.api.queue_mission_by_name( + mission_name) + if mission_queue_id is not None: + break + except Exception as err: + self.node.get_logger().info( + f'Failed to queue mission {mission_name}: {err}. ' + f'Retrying...' + ) + time.sleep(1) + if not mission_queue_id: + self.node.get_logger().info( + f'Unable to queue mission {mission_name} for robot ' + f'[{self.name}]!' + ) + return None + self.node.get_logger().info( + f'Mission {self.mission_name} queued for [{self.name}] ' + f'with mission queue id {mission_queue_id}.' + ) + signal_cb = lambda: self.check_mission_complete( + mission_queue_id, resubmit_on_abort) + self.node.get_logger().info( + f'Configuring robot [{self.name}] move-off behavior: ' + f'robot will wait until mission {mission_name} with ' + f'mission queue id {mission_queue_id} is completed.' + ) + case "plc": + register = signal_config.get('plc_register', None) + if register is None: + self.node.get_logger().info( + f'No PLC register provided!' + ) + return None + signal_cb = lambda: self.check_plc_register(register) + self.node.get_logger().info( + f'Configuring robot [{self.name}] move-off behavior: ' + f'robot will wait until the PLC register {register} ' + f'returns True.' + ) + case "custom": + # TODO(XY): import the module, create the object, then assign + # check custom signal + signal_cb = lambda: self.check_custom_signal( + signal_config, description) + self.node.get_logger().info( + f'Configuring robot [{self.name}] move-off behavior: ' + f'robot will wait until the custom move-off behavior ' + f'signals that the robot is ready to move off.' + ) + case _: + self.node.get_logger().info( + f'Invalid move off signal type provided, unable to ' + f'initialize a WaitUntil action for {self.name}.' + ) + return signal_cb + + def check_mission_complete(self, + mission_queue_id, + resubmit_on_abort=False): + mission_status = self.api.mission_queue_id_get(mission_queue_id) + if (mission_status is not None and + mission_status['state'] == 'Done'): + # Mission has completed, we can set move_off to True + self.node.get_logger().info( + f'Robot [{self.name}] has completed its mission ' + f'with mission queue id {mission_queue_id}' + ) + return True + + if (mission_status is not None and + mission_status['state'] == 'Aborted'): + if resubmit_on_abort: + # Mission aborted for some reason, let's submit the mission + # again + new_mission_queue_id = self.api.queue_mission_by_name( + self.mission_name) + if not new_mission_queue_id: + # If we didn't successfully post a new mission, we'll + # try again in the next loop + return + # Update the check move off callback with the updated mission + # queue id + self.move_off_cb = lambda: self.check_mission_complete( + new_mission_queue_id, resubmit_on_abort) + self.node.get_logger().info( + f'Robot [{self.name}] aborted mission with queue id ' + f'{mission_queue_id}, re-submitting mission with new ' + f'queue id {new_mission_queue_id}' + ) + else: + # If mission is aborted without option to resubmit on abort, + # mark mission as finished + self.node.get_logger().info( + f'Robot [{self.name}] has aborted its mission with ' + f'mission queue id {mission_queue_id}, marking action as ' + f'completed' + ) + return True + return False + + def check_plc_register(self, register: int): + # Update register to check if PLC register returns True + value = self.register_get(register) + if value: + self.node.get_logger().info( + f'[{self.name}] PLC register {register} detected ' + f'value {value}, robot is ready to move off.' + ) + return True + return False + + def check_custom_signal(self, signal_config, description): + # TODO(XY): Return a lambda function + pass + + # ------------------------------------------------------------------------------------------------------------------ + # MIR API FOR WAIT RELATED MISSIONS + # ------------------------------------------------------------------------------------------------------------------ + + def register_get(self, register: int): + if not self.api.connected: + return None + try: + response = requests.get(self.api.prefix + f'registers/{register}', + headers=self.api.headers, + timeout=self.api.timeout) + if self.api.debug: + print(f"Response: {response.headers}") + # Response value is string, return integer of value + return int(response.json().get('value', 0)) + except HTTPError as http_err: + print(f"HTTP error: {http_err}") + return None + except Exception as err: + print(f"Other error: {err}") + return None \ No newline at end of file From fc2e76993df4cffb2bc4b7e3555fc2aa2380750c Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Wed, 7 Aug 2024 11:13:15 +0800 Subject: [PATCH 33/46] Cleanup Signed-off-by: Xiyu Oh --- fleet_adapter_mir/fleet_adapter_mir/fleet_adapter_mir.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/fleet_adapter_mir/fleet_adapter_mir/fleet_adapter_mir.py b/fleet_adapter_mir/fleet_adapter_mir/fleet_adapter_mir.py index 0c36e34..58e4cfb 100644 --- a/fleet_adapter_mir/fleet_adapter_mir/fleet_adapter_mir.py +++ b/fleet_adapter_mir/fleet_adapter_mir/fleet_adapter_mir.py @@ -212,7 +212,7 @@ def main(argv=sys.argv): args_without_ros = rclpy.utilities.remove_ros_args(argv) parser = argparse.ArgumentParser( - prog="cgh_fleet_adapter_mir", + prog="fleet_adapter_mir", description="Configure and spin up fleet adapters for MiR 100 robots " "that interface between the " "MiR REST API, ROS2, and rmf_core!") From 15e5517f471b428330ca579f3be0a2536f2e9f3e Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Wed, 7 Aug 2024 11:19:06 +0800 Subject: [PATCH 34/46] Custom move off behavior with examples Signed-off-by: Xiyu Oh --- fleet_adapter_mir/setup.py | 2 + .../fleet_adapter_mir_actions/rmf_move_off.py | 46 ++++++++ .../rmf_move_off_on_alert.py | 109 ++++++++++++++++++ .../rmf_wait_until.py | 28 +++-- 4 files changed, 177 insertions(+), 8 deletions(-) create mode 100644 fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_move_off.py create mode 100644 fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_move_off_on_alert.py diff --git a/fleet_adapter_mir/setup.py b/fleet_adapter_mir/setup.py index b9a7cf2..4826b2a 100644 --- a/fleet_adapter_mir/setup.py +++ b/fleet_adapter_mir/setup.py @@ -23,6 +23,8 @@ 'rmf_cart_delivery=fleet_adapter_mir.rmf_cart_delivery:CartDelivery', 'rmf_cart_detection=fleet_adapter_mir.rmf_cart_detection:CartDetection', 'rmf_wait_until=fleet_adapter_mir.rmf_wait_until:WaitUntil', + 'rmf_move_off=fleet_adapter_mir.rmf_move_off:MoveOff', + 'rmf_move_off_on_alert=fleet_adapter_mir.rmf_move_off_on_alert:MoveOff', ], }, ) diff --git a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_move_off.py b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_move_off.py new file mode 100644 index 0000000..59fbe30 --- /dev/null +++ b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_move_off.py @@ -0,0 +1,46 @@ +# Copyright 2024 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + + +class MoveOff: + def __init__( + self, + action_handle, + signal_config, + task_description + ): + self.action = action_handle + self.config = signal_config + self.task_desc = task_description + + def begin_waiting(self, description): + ''' + This will be called when the robot has reached the waiting waypoint and + begins waiting. Use this callback to trigger any process during the + waiting period. + ''' + # ------------------------ + # IMPLEMENT YOUR CODE HERE + # ------------------------ + pass + + def is_move_off_ready(self): + ''' + Checks if the robot is ready to move off. + Returns True if ready, else False. + ''' + # ------------------------ + # IMPLEMENT YOUR CODE HERE + # ------------------------ + return False diff --git a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_move_off_on_alert.py b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_move_off_on_alert.py new file mode 100644 index 0000000..4a49739 --- /dev/null +++ b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_move_off_on_alert.py @@ -0,0 +1,109 @@ +# Copyright 2024 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import datetime +from threading import Lock + +from rclpy.qos import qos_profile_system_default +from rclpy.qos import QoSDurabilityPolicy as Durability +from rclpy.qos import QoSHistoryPolicy as History +from rclpy.qos import QoSProfile +from rclpy.qos import QoSReliabilityPolicy as Reliability +from rmf_task_msgs.msg import Alert +from rmf_task_msgs.msg import AlertResponse +from rmf_task_msgs.msg import AlertParameter + + +class MoveOff: + def __init__( + self, + action_handle, + signal_config, + task_description + ): + self.action = action_handle + self.config = signal_config + self.task_desc = task_description + + ''' + This example demonstrates how we can notify the robot to move off when + it receives an Alert via ROS 2. + ''' + self.mutex = Lock() + self.alert = None + self.move_off = False + + # Create alert related publisher and subscribers + transient_qos = QoSProfile( + history=History.KEEP_LAST, + depth=1, + reliability=Reliability.RELIABLE, + durability=Durability.TRANSIENT_LOCAL, + ) + self.alert_response_sub = self.action.node.create_subscription( + AlertResponse, + 'alert_response', + self.alert_response_cb, + qos_profile=transient_qos + ) + self.alert_pub = self.action.node.create_publisher( + Alert, + 'alert', + qos_profile=transient_qos + ) + + def begin_waiting(self, description): + # Publish an alert to signal that the robot has begun waiting + msg = Alert() + msg.id = datetime.datetime.now().strftime( + "alert-%Y-%m-%d-%H-%M-%S") + msg.title = f'Robot [{self.action.name}] has begun waiting.' + msg.tier = Alert.TIER_INFO + msg.responses_available = ['ready'] + msg.task_id = self.action.update_handle.more().current_task_id() + self.alert_pub.publish(msg) + self.action.node.get_logger().info( + f'Robot [{self.action.name}] published alert [{msg.id}] to signal ' + f'that it has started waiting.' + ) + self.alert = msg + + def is_move_off_ready(self): + with self.mutex: + if self.move_off: + # This move-off object is created everytime the robot begins a + # wait_until action, so there is no need to toggle it back to + # False + return True + return False + + def alert_response_cb(self, msg): + if not self.alert: + return + if msg.id != self.alert.id: + return + + if msg.response != 'ready': + self.node.get_logger().info( + f'Robot [{self.name}] received invalid response inside alert ' + f'response: [{msg.response}], ignoring...' + ) + return + + self.node.get_logger().info( + f'Robot [{self.name}] received move-off signal, delivery is ' + f'complete, marking action as completed.' + ) + with self.mutex: + self.move_off = True diff --git a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_wait_until.py b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_wait_until.py index 91a1603..fc1ffa1 100644 --- a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_wait_until.py +++ b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_wait_until.py @@ -13,7 +13,7 @@ # limitations under the License. import time -from threading import Lock +import importlib import requests from urllib.error import HTTPError @@ -47,7 +47,6 @@ def __init__( fleet_config, action_config) self.execution = None - self.mutex = Lock() self.start_time = None self.wait_timeout = action_config.get('timeout', 1800) # seconds self.move_off_cb = None @@ -224,9 +223,7 @@ def create_move_off_cb(self, description: dict): f'returns True.' ) case "custom": - # TODO(XY): import the module, create the object, then assign - # check custom signal - signal_cb = lambda: self.check_custom_signal( + signal_cb = lambda: self.create_custom_signal( signal_config, description) self.node.get_logger().info( f'Configuring robot [{self.name}] move-off behavior: ' @@ -295,9 +292,24 @@ def check_plc_register(self, register: int): return True return False - def check_custom_signal(self, signal_config, description): - # TODO(XY): Return a lambda function - pass + def create_custom_signal(self, signal_config, description): + # Import the move-off behavior module + if 'move_off_module' not in signal_config: + self.node.get_logger().info( + f'Move-off behavior is set to custom but no move-off module ' + f'was provided!' + ) + return None + move_off_module = signal_config['move_off_module'] + move_off_plugin = importlib.import_module(move_off_module) + move_off_signal = move_off_plugin.MoveOff( + self, signal_config, description) + + # Trigger the begin waiting callback + move_off_signal.begin_waiting(description) + # Define the move-off callback to be called on every update + move_off_cb = lambda: move_off_signal.is_move_off_ready() + return move_off_cb # ------------------------------------------------------------------------------------------------------------------ # MIR API FOR WAIT RELATED MISSIONS From 2be1c555bff2a82f0e8d569207511155505b8712 Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Wed, 7 Aug 2024 11:23:10 +0800 Subject: [PATCH 35/46] Add wait_until task Signed-off-by: Xiyu Oh --- .../dispatch_wait_until.py | 170 ++++++++++++++++++ 1 file changed, 170 insertions(+) create mode 100644 fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_wait_until.py diff --git a/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_wait_until.py b/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_wait_until.py new file mode 100644 index 0000000..f4d13ed --- /dev/null +++ b/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_wait_until.py @@ -0,0 +1,170 @@ +#!/usr/bin/env python3 + +# Copyright 2024 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import sys +import uuid +import argparse +import json +import asyncio + +import rclpy +from rclpy.node import Node +from rclpy.parameter import Parameter +from rclpy.qos import qos_profile_system_default +from rclpy.qos import QoSProfile +from rclpy.qos import QoSHistoryPolicy as History +from rclpy.qos import QoSDurabilityPolicy as Durability +from rclpy.qos import QoSReliabilityPolicy as Reliability + +from rmf_task_msgs.msg import ApiRequest, ApiResponse + + +############################################################################### + +class TaskRequester(Node): + + def __init__(self, argv=sys.argv): + super().__init__('task_requester') + parser = argparse.ArgumentParser() + parser.add_argument('-F', '--fleet', required=False, default='', + type=str, help='Fleet name') + parser.add_argument('-R', '--robot', required=False, default='', + type=str, help='Robot name') + parser.add_argument('-g', '--go_to', required=True, nargs='+', + type=str, + help='Places to go to for multistop task') + parser.add_argument('-t', '--timeout', required=False, default=30, + type=int, help='Number of seconds to timeout') + parser.add_argument('-st', '--start_time', + help='Start time from now in secs, default: 0', + type=int, default=0) + parser.add_argument('-pt', '--priority', + help='Priority value for this request', + type=int, default=0) + parser.add_argument("--use_sim_time", action="store_true", + help='Use sim time, default: false') + + self.args = parser.parse_args(argv[1:]) + self.response = asyncio.Future() + + transient_qos = QoSProfile( + history=History.KEEP_LAST, + depth=1, + reliability=Reliability.RELIABLE, + durability=Durability.TRANSIENT_LOCAL) + + self.pub = self.create_publisher( + ApiRequest, 'task_api_requests', transient_qos) + + # enable ros sim time + if self.args.use_sim_time: + self.get_logger().info("Using Sim Time") + param = Parameter("use_sim_time", Parameter.Type.BOOL, True) + self.set_parameters([param]) + + # Construct task + msg = ApiRequest() + msg.request_id = f"wait_until_" + str(uuid.uuid4()) + payload = {} + if self.args.fleet and self.args.robot: + payload["type"] = "robot_task_request" + payload["robot"] = self.args.robot + payload["fleet"] = self.args.fleet + else: + payload["type"] = "dispatch_task_request" + request = {} + + # Set task request start time + now = self.get_clock().now().to_msg() + now.sec = now.sec + self.args.start_time + start_time = now.sec * 1000 + round(now.nanosec/10**6) + request["unix_millis_earliest_start_time"] = start_time + # todo(YV): Fill priority after schema is added + + # Define task request category + request["category"] = "compose" + + # Define task request description with phases + description = {} # task_description_Compose.json + description["category"] = "wait_until" + description["phases"] = [] + + # GoToPlace + wait + for i in range(len(self.args.go_to)): + place = self.args.go_to[i] + # Add GoToPlace activity + go_to_place_activity = [{ + "category": "go_to_place", + "description": place + }] + description["phases"].append({ + "activity": { + "category": "sequence", + "description": {"activities": go_to_place_activity + }}}) + # Add wait activity + wait_activity = [{ + "category": "perform_action", + "description": { + "unix_millis_action_duration_estimate": 60000, + "category": 'wait_until', + "description": { + "timeout": self.args.timeout + }}}] + description["phases"].append({ + "activity": { + "category": "sequence", + "description": { + "activities": wait_activity + }}}) + + # Consolidate + request["description"] = description + payload["request"] = request + msg.json_msg = json.dumps(payload) + + def receive_response(response_msg: ApiResponse): + if response_msg.request_id == msg.request_id: + self.response.set_result(json.loads(response_msg.json_msg)) + + transient_qos.depth = 10 + self.sub = self.create_subscription( + ApiResponse, 'task_api_responses', receive_response, transient_qos + ) + + print(f"Json msg payload: \n{json.dumps(payload, indent=2)}") + self.pub.publish(msg) + + +############################################################################### + + +def main(argv=sys.argv): + rclpy.init(args=sys.argv) + args_without_ros = rclpy.utilities.remove_ros_args(sys.argv) + + task_requester = TaskRequester(args_without_ros) + rclpy.spin_until_future_complete( + task_requester, task_requester.response, timeout_sec=5.0) + if task_requester.response.done(): + print(f'Got response:\n{task_requester.response.result()}') + else: + print('Did not get a response') + rclpy.shutdown() + + +if __name__ == '__main__': + main(sys.argv) From acb649101d129661727ad4d801b753521930e8d3 Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Wed, 7 Aug 2024 12:07:09 +0800 Subject: [PATCH 36/46] Add readme and rename task to multistop Signed-off-by: Xiyu Oh --- configs/mir_config.yaml | 4 +- fleet_adapter_mir/README.md | 45 +++++++++++++++++++ ...ch_wait_until.py => dispatch_multistop.py} | 4 +- fleet_adapter_mir_tasks/setup.py | 1 + 4 files changed, 50 insertions(+), 4 deletions(-) rename fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/{dispatch_wait_until.py => dispatch_multistop.py} (98%) diff --git a/configs/mir_config.yaml b/configs/mir_config.yaml index 08bf5b2..a6e6291 100644 --- a/configs/mir_config.yaml +++ b/configs/mir_config.yaml @@ -80,7 +80,7 @@ rmf_fleet: delivery: True clean: False finishing_request: "charge" # [park, charge, nothing] - actions: ["rmf_cart_delivery", "delivery_pickup", "delivery_dropoff", "wait_until"] + actions: ["rmf_cart_delivery", "delivery_pickup", "delivery_dropoff", "rmf_multistop", "wait_until"] robots: mir_1: charger: "Charger_1" @@ -120,7 +120,7 @@ plugins: rmf_wait_until: module: "fleet_adapter_mir_actions.rmf_wait_until" class: "WaitUntil" - actions: ["wait_until"] + actions: ["rmf_multistop", "wait_until"] timeout: 1800 # seconds, default timeout if there is no move-off signal received # Optional fields to configure default move-off signal signal_type: "mission" # [mission, plc, or custom], if not provided the robot will wait the full duration of the default timeout diff --git a/fleet_adapter_mir/README.md b/fleet_adapter_mir/README.md index e9b13c2..ce9e5b5 100644 --- a/fleet_adapter_mir/README.md +++ b/fleet_adapter_mir/README.md @@ -108,3 +108,48 @@ ros2 run fleet_adapter_mir_tasks dispatch_delivery -g go_to_waypoint -p pickup_l - `-p`: Name of the pickup lot. This name should be identical to the shelf position configured on the MiR. - `-d`: Name of the dropoff lot. This name should be identical to the robot or shelf position configured on the MiR. - `-c`: Optional cart identifier for the fleet adapter to assess whether the cart is correct for pickup. + + +For multistop deliveries: + +**rmf_wait_until** + +The `rmf_wait_until` plugin allows users to create a multistop task for their MiR integrated with RMF. The action would consist of the robot travelling to multiple waypoints, stop and wait there for a configured period of time, then complete the task by performing its finishing request. Users may wish to use the move-off behavior provided in the plugin or customize their own to end the waiting process earlier. + +This action can come in handy for various use cases, for example: +- The robot has to perform a multistop delivery, i.e. travel to several waypoints to pickup or dropoff some items that it is carrying +- The robot is performing the same custom MiR mission at different locations, and is ready to move off to the next stop when the mission is completed. + +The workflow of the task is as follows: +1. After users submit a task with a list of waypoints for the robot to travel to, RMF will send the robot to the first waypoint +2. The robot will stop at the waypoint and do nothing until it receives a move-off signal or timeout (both are configurable) +3. Steps 1. and 2. repeat until the robots has travelled to all the waypoints in the task. + + +There are 2 move-off behavior provided in the plugin. +1. Move-off when a MiR mission completes. + - Users may create/pick a MiR mission on the robot and provide the mission name in the fleet config or task description. This mission will be submitted to the robot when the waiting action begins. The waiting action will end when the robot receives the move-off signal, which in this case happens when the robot completes the mission. + - Users may wish to configure the action behavior in cases where the mission is aborted by the robot. By setting the `resubmit_on_abort` parameter to `True`, the fleet adapter will submit the same MiR mission to the robot if the previous attempt has been aborted. The move-off signal will come only when the mission has been successfully completed. If `resubmit_on_abort` is set to `False`, the fleet adapter will accept abort missions as a move-off signal and end the waiting action. +2. Move-off when a PLC register returns `True`. + - When the waiting action begins, the fleet adapter will monitor the state of the PLC register specified in the fleet config or task description. When the register returns a value of `1` or `True`, the waiting action will end and the robot will move on to its next waypoint or task. + + +It is important to fill in the configuration relevant to the `wait_until` action following the example provided in `mir_config.yaml`. It allows users to customize the behavior of their robots during the waiting action: +- `timeout`: The default timeout of the waiting action. At timeout, the robot will move off even if it did not receive the move off signal. +- `signal_type`: The type of move off signal for the robot. We currently support `mission`, `plc` and `custom`. + - If `mission` signal is chosen, users will need to provide the `mission_name` for the robot to trigger the MiR mission when the waiting action starts. + + An optional field `resubmit_on_abort` can be used to configure the action behavior in cases where the MiR mission cannot be successfully completed and gets aborted by the robot. When set to `True`, the fleet adapter will submit the same MiR mission to the robot if the previous attempt has been aborted. The move-off signal will come only when the mission has been successfully completed. If `resubmit_on_abort` is set to `False`, the fleet adapter will accept abort missions as a move-off signal and end the waiting action. + - If `plc` signal is chosen, users will need to provide the relevant `plc_register`. + - If `custom` is chosen, users will need to provide a path their custom `MoveOff` module. This will require your own `MoveOff` plugin. A skeleton of the plugin is provided in `rmf_move_off.py`, with `# IMPLEMENT YOUR CODE HERE` indicating where users should fill in their code logic. An example demonstrating how a move-off signal can be called with ROS 2 `Alert` msg is provided in `rmf_move_off_on_alert.py`. + - If the `signal_type` is not provided, the robot will carry out the waiting action for the full duration of the default timeout. + +For task-specific waiting behavior, users could provide the same signal config in their task description instead. The signal behavior provided in the task description will override the default behavior in the fleet config. + + +To submit a multistop waiting task, you may use the `dispatch_multistop` task script found in the `fleet_adapter_mir_tasks` package: +```bash +ros2 run fleet_adapter_mir_tasks dispatch_multistop -g waypoint_1 waypoint_2 waypoint_3 -t 1800 +``` +- `-g`: Takes in the waypoints the robots should travel to for each waiting action. +- `-t`: Default timeout of the action in seconds. diff --git a/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_wait_until.py b/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_multistop.py similarity index 98% rename from fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_wait_until.py rename to fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_multistop.py index f4d13ed..3acaa6d 100644 --- a/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_wait_until.py +++ b/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_multistop.py @@ -77,7 +77,7 @@ def __init__(self, argv=sys.argv): # Construct task msg = ApiRequest() - msg.request_id = f"wait_until_" + str(uuid.uuid4()) + msg.request_id = f"multistop_" + str(uuid.uuid4()) payload = {} if self.args.fleet and self.args.robot: payload["type"] = "robot_task_request" @@ -99,7 +99,7 @@ def __init__(self, argv=sys.argv): # Define task request description with phases description = {} # task_description_Compose.json - description["category"] = "wait_until" + description["category"] = "rmf_multistop" description["phases"] = [] # GoToPlace + wait diff --git a/fleet_adapter_mir_tasks/setup.py b/fleet_adapter_mir_tasks/setup.py index 2502dbf..3edd5ce 100644 --- a/fleet_adapter_mir_tasks/setup.py +++ b/fleet_adapter_mir_tasks/setup.py @@ -20,6 +20,7 @@ entry_points={ 'console_scripts': [ 'dispatch_delivery = fleet_adapter_mir_tasks.dispatch_delivery:main' + 'dispatch_multistop = fleet_adapter_mir_tasks.dispatch_multistop:main' ], }, ) From ebf7d7053ca6d86faf4053c162e542aef9639ac8 Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Wed, 7 Aug 2024 12:10:53 +0800 Subject: [PATCH 37/46] Remove duplicate instructions Signed-off-by: Xiyu Oh --- fleet_adapter_mir/README.md | 1 - 1 file changed, 1 deletion(-) diff --git a/fleet_adapter_mir/README.md b/fleet_adapter_mir/README.md index ce9e5b5..c9fd612 100644 --- a/fleet_adapter_mir/README.md +++ b/fleet_adapter_mir/README.md @@ -129,7 +129,6 @@ The workflow of the task is as follows: There are 2 move-off behavior provided in the plugin. 1. Move-off when a MiR mission completes. - Users may create/pick a MiR mission on the robot and provide the mission name in the fleet config or task description. This mission will be submitted to the robot when the waiting action begins. The waiting action will end when the robot receives the move-off signal, which in this case happens when the robot completes the mission. - - Users may wish to configure the action behavior in cases where the mission is aborted by the robot. By setting the `resubmit_on_abort` parameter to `True`, the fleet adapter will submit the same MiR mission to the robot if the previous attempt has been aborted. The move-off signal will come only when the mission has been successfully completed. If `resubmit_on_abort` is set to `False`, the fleet adapter will accept abort missions as a move-off signal and end the waiting action. 2. Move-off when a PLC register returns `True`. - When the waiting action begins, the fleet adapter will monitor the state of the PLC register specified in the fleet config or task description. When the register returns a value of `1` or `True`, the waiting action will end and the robot will move on to its next waypoint or task. From 1b70ee126f0f78da967109f197c99caf5c0227e3 Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Wed, 4 Dec 2024 17:49:38 +0800 Subject: [PATCH 38/46] Update wait until action Signed-off-by: Xiyu Oh --- configs/mir_config.yaml | 20 +- fleet_adapter_mir/setup.py | 2 +- .../fleet_adapter_mir_actions/rmf_move_off.py | 77 ++-- .../rmf_move_off_on_alert.py | 47 +- .../rmf_wait_until.py | 406 ++++++++++-------- 5 files changed, 319 insertions(+), 233 deletions(-) diff --git a/configs/mir_config.yaml b/configs/mir_config.yaml index 7e01494..aa784c8 100644 --- a/configs/mir_config.yaml +++ b/configs/mir_config.yaml @@ -113,12 +113,14 @@ plugins: latch_io: 2 rmf_wait_until: module: "fleet_adapter_mir_actions.rmf_wait_until" - actions: ["rmf_multistop", "wait_until"] - timeout: 1800 # seconds, default timeout if there is no move-off signal received - # Optional fields to configure default move-off signal - signal_type: "mission" # [mission, plc, or custom], if not provided the robot will wait the full duration of the default timeout - mission_name: "some_mission_name" # Required field if signal type is "mission". The mission will be queued when the action starts, and the robot will move off when the mission is completed. - resubmit_on_abort: False # Optional field for signal type "mission". Set to True to resubmit mission if the mission gets aborted by the robot. Default to False. - plc_register: 20 # Required field if signal type is "plc". Robot moves off when PLC register returns True - move_off_module: "fleet_adapter_mir_actions.rmf_move_off_alert" # Required field if signal type is "custom". Fill in with path to custom module written. - action_categories: ["custom_mission_1"] + actions: ["wait_until"] + timeout: 1800 # Optional, in seconds. Timeout if there is no move-off signal received, after which robot will move off regardless. Default to 60 seconds. + signal_type: # Defines the default configs for various move off signal types. If this field is not provided, the robot will wait the full duration of the default timeout. Signal configs can be overridden by task description. + # Currently three signal types are supported: [mission, plc, custom]. + mission: + mission_name: "some_mission_name" # If this mission is found on the robot, it will be queued when the action starts, and the robot will move off when the mission is completed. + resubmit_on_abort: False # Optional field for signal type "mission". Set to True to resubmit mission if the mission gets aborted by the robot. Default to False. + retry_count: 10 # Optional field for signal type "mission". The fleet adapter will re-attempt queueing the mission for this number of tries. + plc: 20 # Fill in with PLC register number. Robot moves off when this PLC register returns True + custom: + module: "fleet_adapter_mir_actions.rmf_move_off_on_alert" # Fill in with path to custom module written. Robot moves off when module provides the user-defined move off signal. \ No newline at end of file diff --git a/fleet_adapter_mir/setup.py b/fleet_adapter_mir/setup.py index 4826b2a..3d06919 100644 --- a/fleet_adapter_mir/setup.py +++ b/fleet_adapter_mir/setup.py @@ -23,7 +23,7 @@ 'rmf_cart_delivery=fleet_adapter_mir.rmf_cart_delivery:CartDelivery', 'rmf_cart_detection=fleet_adapter_mir.rmf_cart_detection:CartDetection', 'rmf_wait_until=fleet_adapter_mir.rmf_wait_until:WaitUntil', - 'rmf_move_off=fleet_adapter_mir.rmf_move_off:MoveOff', + 'rmf_move_off=fleet_adapter_mir.rmf_move_off:BaseMoveOff', 'rmf_move_off_on_alert=fleet_adapter_mir.rmf_move_off_on_alert:MoveOff', ], }, diff --git a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_move_off.py b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_move_off.py index 59fbe30..437d33c 100644 --- a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_move_off.py +++ b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_move_off.py @@ -12,35 +12,54 @@ # See the License for the specific language governing permissions and # limitations under the License. +from abc import ABC, abstractmethod +import requests +from urllib.error import HTTPError +from fleet_adapter_mir.robot_adapter_mir import ActionContext -class MoveOff: - def __init__( - self, - action_handle, - signal_config, - task_description - ): - self.action = action_handle - self.config = signal_config - self.task_desc = task_description - def begin_waiting(self, description): - ''' - This will be called when the robot has reached the waiting waypoint and - begins waiting. Use this callback to trigger any process during the - waiting period. - ''' - # ------------------------ - # IMPLEMENT YOUR CODE HERE - # ------------------------ - pass +class BaseMoveOff(ABC): + def __init__(self, context: ActionContext): + self.context = context - def is_move_off_ready(self): - ''' - Checks if the robot is ready to move off. - Returns True if ready, else False. - ''' - # ------------------------ - # IMPLEMENT YOUR CODE HERE - # ------------------------ - return False + ''' + This method is called when the robot reaches the waiting waypoint and + begins waiting. Use this callback to trigger any process during the + waiting period. + ''' + @abstractmethod + def begin_waiting(self, description: dict): + # To be implemented + ... + + ''' + This method checks if the robot is ready to move off. + Returns True if ready, else False. + ''' + @abstractmethod + def is_move_off_ready(self) -> bool: + # To be implemented + ... + + # -------------------------------------------------------------------------- + # HELPFUL FUNCTIONS FOR INTERACTING WITH MIR REST API + # -------------------------------------------------------------------------- + + def register_get(self, register: int): + if not self.context.api.connected: + return None + try: + response = requests.get( + self.context.api.prefix + f'registers/{register}', + headers=self.context.api.headers, + timeout=self.context.api.timeout) + if self.context.api.debug: + print(f"Response: {response.headers}") + # Response value is string, return integer of value + return int(response.json().get('value', 0)) + except HTTPError as http_err: + print(f"HTTP error: {http_err}") + return None + except Exception as err: + print(f"Other error: {err}") + return None diff --git a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_move_off_on_alert.py b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_move_off_on_alert.py index 4a49739..00df7c6 100644 --- a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_move_off_on_alert.py +++ b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_move_off_on_alert.py @@ -24,17 +24,12 @@ from rmf_task_msgs.msg import AlertResponse from rmf_task_msgs.msg import AlertParameter +from fleet_adapter_mir.robot_adapter_mir import ActionContext -class MoveOff: - def __init__( - self, - action_handle, - signal_config, - task_description - ): - self.action = action_handle - self.config = signal_config - self.task_desc = task_description + +class MoveOff(BaseMoveOff): + def __init__(self, context: ActionContext): + MoveOff.__init__(self, context) ''' This example demonstrates how we can notify the robot to move off when @@ -42,7 +37,7 @@ def __init__( ''' self.mutex = Lock() self.alert = None - self.move_off = False + self.ready = False # Create alert related publisher and subscribers transient_qos = QoSProfile( @@ -51,13 +46,13 @@ def __init__( reliability=Reliability.RELIABLE, durability=Durability.TRANSIENT_LOCAL, ) - self.alert_response_sub = self.action.node.create_subscription( + self.alert_response_sub = self.context.node.create_subscription( AlertResponse, 'alert_response', self.alert_response_cb, qos_profile=transient_qos ) - self.alert_pub = self.action.node.create_publisher( + self.alert_pub = self.context.node.create_publisher( Alert, 'alert', qos_profile=transient_qos @@ -68,21 +63,21 @@ def begin_waiting(self, description): msg = Alert() msg.id = datetime.datetime.now().strftime( "alert-%Y-%m-%d-%H-%M-%S") - msg.title = f'Robot [{self.action.name}] has begun waiting.' + msg.title = f'Robot [{self.context.name}] has begun waiting.' msg.tier = Alert.TIER_INFO msg.responses_available = ['ready'] - msg.task_id = self.action.update_handle.more().current_task_id() + msg.task_id = self.context.update_handle.more().current_task_id() self.alert_pub.publish(msg) - self.action.node.get_logger().info( - f'Robot [{self.action.name}] published alert [{msg.id}] to signal ' + self.context.node.get_logger().info( + f'Robot [{self.context.name}] published alert [{msg.id}] to signal ' f'that it has started waiting.' ) self.alert = msg def is_move_off_ready(self): with self.mutex: - if self.move_off: - # This move-off object is created everytime the robot begins a + if self.ready: + # This `ready` variable is created everytime the robot begins a # wait_until action, so there is no need to toggle it back to # False return True @@ -95,15 +90,15 @@ def alert_response_cb(self, msg): return if msg.response != 'ready': - self.node.get_logger().info( - f'Robot [{self.name}] received invalid response inside alert ' - f'response: [{msg.response}], ignoring...' + self.context.node.get_logger().info( + f'Robot [{self.context.name}] received invalid response ' + f'inside alert response: [{msg.response}], ignoring...' ) return - self.node.get_logger().info( - f'Robot [{self.name}] received move-off signal, delivery is ' - f'complete, marking action as completed.' + self.context.node.get_logger().info( + f'Received move off signal, robot [{self.context.name}] is done ' + f'waiting, marking action as completed.' ) with self.mutex: - self.move_off = True + self.ready = True diff --git a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_wait_until.py b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_wait_until.py index fc1ffa1..e945ba1 100644 --- a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_wait_until.py +++ b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_wait_until.py @@ -18,234 +18,321 @@ from urllib.error import HTTPError from fleet_adapter_mir_actions.mir_action import MirAction, MirActionFactory +from fleet_adapter_mir.robot_adapter_mir import ActionContext from fleet_adapter_mir.mir_api import MirAPI, MirStatus, MiRStateCode class ActionFactory(MirActionFactory): - def make_action(self, - node, - name, - mir_api, - update_handle, - fleet_config, - action_config) -> MirAction: - return WaitUntil( - node, name, mir_api, update_handle, fleet_config, action_config) - - -class WaitUntil(MirAction): - def __init__( - self, - node, - name, - mir_api, - update_handle, - fleet_config, - action_config - ): - MirAction.__init__(self, node, name, mir_api, update_handle, - fleet_config, action_config) + def __init__(self, context: ActionContext): + MirActionFactory.__init__(context) + self.move_off = None + # Raise error if config file is invalid + if 'signal_type' in context.action_config: + signal_type = context.action_config['signal_type'] + if 'mission' in signal_type: + if 'mission_name' not in signal_type['mission']: + raise KeyError( + f'WaitUntil MirAction requires a default mission name ' + f'for signal type [mission], but mission name is not ' + f'provided in the action config! Unable to ' + f'instantiate an ActionFactory.') + if 'plc' in signal_type: + if not isinstance(signal_type['plc'], int): + raise TypeError( + f'WaitUntil MirAction requires a default PLC register ' + f'number for signal type [plc], but the value ' + f'provided is not an integer! Unable to instantiate ' + f'an ActionFactory.') + # If user provides a custom MoveOff module, import it + if 'custom' in signal_type: + if 'module' not in signal_type['custom']: + raise KeyError( + f'WaitUntil MirAction requires a custom module for ' + f'signal type [custom], but path to module is not ' + f'provided in the action config! Unable to ' + f'instantiate an ActionFactory.') + try: + move_off_module = context.action_config['module'] + move_off_plugin = importlib.import_module(move_off_module) + self.move_off = move_off_plugin.MoveOff(self.context) + except ImportError: + self.context.node.get_logger().warn( + f'Unable to import module {move_off_module}! The ' + f'WaitUntil ActionFactory will be instantiated ' + f'without supporting any user-defined signal module.' + ) + else: + # If the user did not provide any default signal config, log a + # warning to remind users to provide signal type config in any task + # description they submit + self.context.node.get_logger().warn( + f'WaitUntil ActionFactory is instantiated for robot ' + f'[{self.context.name}], but no signal_type config has been ' + f'provided in the action config! Any move off signal config ' + f'will have to be provided in the task description submitted ' + f'to RMF.' + ) - self.execution = None - self.start_time = None - self.wait_timeout = action_config.get('timeout', 1800) # seconds - self.move_off_cb = None + def supports_action(self, category: str) -> bool: + match category: + case 'wait_until': + return True + case _: + return False - def perform_action(self, category, description, execution): - self.start_time = self.node.get_clock().now().nanoseconds / 1e9 - # Retrieve task description - if description.get('timeout') is not None: - self.wait_timeout = description['timeout'] + def perform_action( + self, + category: str, + description: dict, + execution + ) -> MirAction: + match category: + case 'wait_until': + return WaitUntil( + description, execution, self.context, self.move_off) - # The only accepted action name is "wait_until" - if category != 'wait_until': - self.node.get_logger().info( - f'[{self.name}] Invalid perform action [{category}] passed ' - f'to WaitUntil, ending action.') - execution.finished() - return - self.move_off_cb = self.create_move_off_cb(description) +class WaitUntil(MirAction): + def __init__( + self, + description: dict, + execution, + context: ActionContext, + move_off + ): + MirAction.__init__(self, context, execution) + self.move_off_cb = self.create_move_off_cb(description, move_off) if self.move_off_cb is None: - # Insufficient information provided to configure the check move-off + # Insufficient information provided to configure the check move off # callback, mark action as completed and continue task - self.node.get_logger().info( + self.context.node.get_logger().info( f'Insufficient information provided to configure the move-' - f'off behavior, ignoring WaitUntil action and marking action ' - f'as completed.' + f'off behavior for robot [{self.context.name}], cancelling ' + f'task...' + ) + self.cancel_task( + label='Move off behavior cannot be configured, unable to ' + \ + 'perform wait until action.' ) - execution.finished() return - self.node.get_logger().info( - f'Robot [{self.name}] will start to perform wait_until ' - f'action with a timeout of {self.wait_timeout} seconds.' - ) - # Store this execution object - self.execution = execution + self.logging_gap = \ + context.action_config.get('logging_gap', 60) # seconds + if description.get('logging_gap') is not None: + self.logging_gap = description['logging_gap'] + self.wait_timeout = context.action_config.get('timeout', 60) # seconds + if description.get('timeout') is not None: + self.wait_timeout = description['timeout'] + + self.start_time = self.context.node.get_clock().now().nanoseconds / 1e9 + self.context.node.get_logger().info( + f'New wait until action with a timeout of {self.wait_timeout} ' + f'seconds requested for robot [{self.context.name}]') + + def cancel_task(self, label: str = ''): + def _cancel_success(): + pass + def _cancel_fail(): + pass + self.cancel_task_of_action(_cancel_success, _cancel_fail, label) def update_action(self): - if self.execution is None: - return - # Check if action has been cancelled or killed - if not self.execution.okay(): - self.node.get_logger().info( - f'[{self.name}] wait_until action has been killed/canceled' - ) + # If the action is no longer active, mark action as complete + if self.execution is not None and not self.execution.okay(): + self.context.node.get_logger().info( + f'[wait_until] action is no longer underway and valid, ' + f'marking action as complete.') return True - # Check if we've received a move-off signal + # Check if we've received a move off signal if self.move_off_cb(): - self.node.get_logger().info( - f'[{self.name}] has received move-off signal, marking ' + self.context.node.get_logger().info( + f'[{self.context.name}] has received move off signal, marking ' f'action as completed.' ) self.execution.finished() return True # Check if the default timeout has passed - now = self.node.get_clock().now().nanoseconds / 1e9 + now = self.context.node.get_clock().now().nanoseconds / 1e9 if now > self.start_time + self.wait_timeout: - self.node.get_logger().info( - f'Robot [{self.name}] has completed waiting for ' - f'{self.wait_timeout} seconds without move-off signal, ' + self.context.node.get_logger().info( + f'Robot [{self.context.name}] has completed waiting for ' + f'{self.wait_timeout} seconds without move off signal, ' f'action as complete.' ) return True - # Log the robot waiting every 30 seconds + # Log the robot waiting every X seconds seconds_passed = round(now - self.start_time) - if seconds_passed%30 == 0: - self.node.get_logger().info( + if seconds_passed%self.logging_gap == 0: + self.context.node.get_logger().info( f'{seconds_passed} seconds have passed since robot ' - f'[{self.name}] started its waiting action.' + f'[{self.context.name}] started its waiting action.' ) return False - def create_move_off_cb(self, description: dict): + def create_move_off_cb(self, description: dict, move_off): signal_cb = None - # Determine which move-off behavior config to use. Any config populated + # Determine which move off signal config to use. Any config populated # in the task description overrides the default config provided in - # fleet config. + # action config. if 'signal_type' in description: - signal_config = description - elif 'signal_type' in self.action_config: - signal_config = self.action_config + signal_type = description['signal_type'] + elif 'signal_type' in self.context.action_config: + signal_type = self.context.action_config['signal_type'] else: - # We have no move-off behavior configured at all, we will just wait - # until we reach the default timeout - self.node.get_logger().info( - f'No move-off behavior was configured for [{self.name}], the ' - f'robot will begin waiting until the default timeout.' + # There is no move off signal provided, we will just wait for the + # duration of the configured timeout + timeout = description.get('timeout', self.wait_timeout) + self.context.node.get_logger().info( + f'No move off signal was configured for [{self.context.name}]' + f', the robot will begin waiting until the configured timeout ' + f'of [{timeout}] seconds.' ) signal_cb = lambda: False return signal_cb - # Configure type of move off signal - signal_type = signal_config['signal_type'] + # Configure the specified move off signal match signal_type: case "mission": - mission_name = signal_config.get('mission_name', None) - resubmit_on_abort = signal_config.get('resubmit_on_abort', - False) + mission_config = self.context.action_config.get('mission') + mission_name = description.get('mission_name', None) + resubmit_on_abort = description.get('resubmit_on_abort', None) + retry_count = description.get('retry_count', None) + + # Check for default mission config values if they are not + # provided in the task description + if mission_config is not None: + if mission_name is None: + mission_name = mission_config['mission_name'] + if resubmit_on_abort is None: + resubmit_on_abort = \ + mission_config.get('resubmit_on_abort', False) + if retry_count is None: + retry_count = \ + mission_config.get('retry_count', 10) + + # Check if mission config values are valid if mission_name is None: - self.node.get_logger().info( - f'No mission name provided!' + self.context.node.get_logger().info( + f'MoveOff signal type [mission] was selected for ' + f'robot [{self.context.name}], but no mission name ' + f'was provided! Please ensure that the required ' + f'fields are provided in the fleet config.' ) return None - elif mission_name not in self.api.known_missions: - self.node.get_logger().info( + if mission_name not in self.context.api.known_missions: + self.context.node.get_logger().info( f'Mission {mission_name} not found on robot ' - f'{self.name}!' + f'{self.context.name}!' ) return None - mission_actions = self.api.missions_mission_id_actions_get( - self.api.known_missions[mission_name]['guid'] + mission_actions = \ + self.context.api.missions_mission_id_actions_get( + self.context.api.known_missions[mission_name]['guid'] ) if not mission_actions: - self.node.get_logger().info( + self.context.node.get_logger().info( f'Mission {mission_name} actions not found on robot ' - f'{self.name}!' + f'{self.context.name}!' ) return None # Queue the waiting mission for this robot - retry_count = 10 count = 0 mission_queue_id = None while count < retry_count and not mission_queue_id: count += 1 - self.node.get_logger().info( + self.context.node.get_logger().info( f'Queueing mission {mission_name} for robot ' - f'[{self.name}]...' + f'[{self.context.name}]...' ) try: - mission_queue_id = self.api.queue_mission_by_name( + mission_queue_id = self.context.api.queue_mission_by_name( mission_name) if mission_queue_id is not None: break except Exception as err: - self.node.get_logger().info( + self.context.node.get_logger().info( f'Failed to queue mission {mission_name}: {err}. ' f'Retrying...' ) time.sleep(1) if not mission_queue_id: - self.node.get_logger().info( + self.context.node.get_logger().info( f'Unable to queue mission {mission_name} for robot ' - f'[{self.name}]!' + f'[{self.context.name}]!' ) return None - self.node.get_logger().info( - f'Mission {self.mission_name} queued for [{self.name}] ' + self.context.node.get_logger().info( + f'Mission {mission_name} queued for [{self.context.name}] ' f'with mission queue id {mission_queue_id}.' ) signal_cb = lambda: self.check_mission_complete( - mission_queue_id, resubmit_on_abort) - self.node.get_logger().info( - f'Configuring robot [{self.name}] move-off behavior: ' + mission_name, mission_queue_id, resubmit_on_abort) + self.context.node.get_logger().info( + f'Configuring robot [{self.context.name}] move off signal: ' f'robot will wait until mission {mission_name} with ' f'mission queue id {mission_queue_id} is completed.' ) case "plc": - register = signal_config.get('plc_register', None) + register = description.get( + 'plc', self.context.action_config.get('plc', None)) if register is None: - self.node.get_logger().info( - f'No PLC register provided!' + self.context.node.get_logger().info( + f'MoveOff signal type [plc] was selected for ' + f'robot [{self.context.name}], but no plc register ' + f'was provided! Please ensure that the required ' + f'fields are provided in the fleet config.' ) return None signal_cb = lambda: self.check_plc_register(register) - self.node.get_logger().info( - f'Configuring robot [{self.name}] move-off behavior: ' - f'robot will wait until the PLC register {register} ' - f'returns True.' + self.context.node.get_logger().info( + f'Configuring robot [{self.context.name}] move off ' + f'signal: robot will wait until the PLC register ' + f'{register} returns True.' ) case "custom": - signal_cb = lambda: self.create_custom_signal( - signal_config, description) - self.node.get_logger().info( - f'Configuring robot [{self.name}] move-off behavior: ' - f'robot will wait until the custom move-off behavior ' - f'signals that the robot is ready to move off.' + if move_off is None: + self.context.node.get_logger().info( + f'MoveOff signal type [custom] was selected for ' + f'robot [{self.context.name}], but no valid move off ' + f'signal module was provided! Please ensure that the ' + f'required fields are provided in the fleet config.' + ) + return None + # Trigger the begin waiting callback + move_off.begin_waiting(description) + # Define the move off callback to be called on every update + signal_cb = lambda: move_off.is_move_off_ready() + self.context.node.get_logger().info( + f'Configuring robot [{self.context.name}] move off ' + f'behavior: robot will wait until the custom move off ' + f'behavior signals that the robot is ready to move off.' ) case _: - self.node.get_logger().info( - f'Invalid move off signal type provided, unable to ' - f'initialize a WaitUntil action for {self.name}.' + self.context.node.get_logger().info( + f'Invalid move off signal type [{signal_type}] provided, ' + f'unable to initialize a WaitUntil action for ' + f'{self.context.name}.' ) return signal_cb - def check_mission_complete(self, - mission_queue_id, - resubmit_on_abort=False): - mission_status = self.api.mission_queue_id_get(mission_queue_id) + def check_mission_complete( + self, + mission_name, + mission_queue_id, + resubmit_on_abort + ): + mission_status = self.context.api.mission_queue_id_get(mission_queue_id) if (mission_status is not None and mission_status['state'] == 'Done'): # Mission has completed, we can set move_off to True - self.node.get_logger().info( - f'Robot [{self.name}] has completed its mission ' + self.context.node.get_logger().info( + f'Robot [{self.context.name}] has completed its mission ' f'with mission queue id {mission_queue_id}' ) return True @@ -255,28 +342,29 @@ def check_mission_complete(self, if resubmit_on_abort: # Mission aborted for some reason, let's submit the mission # again - new_mission_queue_id = self.api.queue_mission_by_name( - self.mission_name) + new_mission_queue_id = self.context.api.queue_mission_by_name( + mission_name) if not new_mission_queue_id: # If we didn't successfully post a new mission, we'll - # try again in the next loop + # try again in the next update_action loop return # Update the check move off callback with the updated mission # queue id self.move_off_cb = lambda: self.check_mission_complete( - new_mission_queue_id, resubmit_on_abort) - self.node.get_logger().info( - f'Robot [{self.name}] aborted mission with queue id ' - f'{mission_queue_id}, re-submitting mission with new ' + mission_name, + new_mission_queue_id) + self.context.node.get_logger().info( + f'Robot [{self.context.name}] aborted mission with queue ' + f'id {mission_queue_id}, re-submitting mission with new ' f'queue id {new_mission_queue_id}' ) else: # If mission is aborted without option to resubmit on abort, # mark mission as finished - self.node.get_logger().info( - f'Robot [{self.name}] has aborted its mission with ' - f'mission queue id {mission_queue_id}, marking action as ' - f'completed' + self.context.node.get_logger().info( + f'Robot [{self.context.name}] has aborted its mission ' + f'with mission queue id {mission_queue_id}, marking ' + f'action as completed.' ) return True return False @@ -285,44 +373,26 @@ def check_plc_register(self, register: int): # Update register to check if PLC register returns True value = self.register_get(register) if value: - self.node.get_logger().info( - f'[{self.name}] PLC register {register} detected ' + self.context.node.get_logger().info( + f'[{self.context.name}] PLC register {register} detected ' f'value {value}, robot is ready to move off.' ) return True return False - def create_custom_signal(self, signal_config, description): - # Import the move-off behavior module - if 'move_off_module' not in signal_config: - self.node.get_logger().info( - f'Move-off behavior is set to custom but no move-off module ' - f'was provided!' - ) - return None - move_off_module = signal_config['move_off_module'] - move_off_plugin = importlib.import_module(move_off_module) - move_off_signal = move_off_plugin.MoveOff( - self, signal_config, description) - - # Trigger the begin waiting callback - move_off_signal.begin_waiting(description) - # Define the move-off callback to be called on every update - move_off_cb = lambda: move_off_signal.is_move_off_ready() - return move_off_cb - - # ------------------------------------------------------------------------------------------------------------------ - # MIR API FOR WAIT RELATED MISSIONS - # ------------------------------------------------------------------------------------------------------------------ + # -------------------------------------------------------------------------- + # HELPFUL FUNCTIONS FOR INTERACTING WITH MIR REST API + # -------------------------------------------------------------------------- def register_get(self, register: int): - if not self.api.connected: + if not self.context.api.connected: return None try: - response = requests.get(self.api.prefix + f'registers/{register}', - headers=self.api.headers, - timeout=self.api.timeout) - if self.api.debug: + response = requests.get( + self.context.api.prefix + f'registers/{register}', + headers=self.context.api.headers, + timeout=self.context.api.timeout) + if self.context.api.debug: print(f"Response: {response.headers}") # Response value is string, return integer of value return int(response.json().get('value', 0)) From f7cb1af07ff954cc71189bf7191680d28b8d01f0 Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Fri, 6 Dec 2024 10:54:46 +0800 Subject: [PATCH 39/46] Refactor signal type configuration Signed-off-by: Xiyu Oh --- configs/mir_config.yaml | 9 +- docs/mir_actions.md | 86 +++++++---- fleet_adapter_mir/setup.py | 3 - .../rmf_wait_until.py | 136 +++++++++++++----- .../dispatch_multistop.py | 45 +++++- 5 files changed, 210 insertions(+), 69 deletions(-) diff --git a/configs/mir_config.yaml b/configs/mir_config.yaml index 474d2eb..e8d7a27 100644 --- a/configs/mir_config.yaml +++ b/configs/mir_config.yaml @@ -115,12 +115,15 @@ plugins: module: "fleet_adapter_mir_actions.rmf_wait_until" actions: ["wait_until"] timeout: 1800 # Optional, in seconds. Timeout if there is no move-off signal received, after which robot will move off regardless. Default to 60 seconds. + update_gap: 30 # Optional, in seconds. The fleet adapter will log an update using this interval. Default to 30 seconds. signal_type: # Defines the default configs for various move off signal types. If this field is not provided, the robot will wait the full duration of the default timeout. Signal configs can be overridden by task description. # Currently three signal types are supported: [mission, plc, custom]. mission: mission_name: "some_mission_name" # If this mission is found on the robot, it will be queued when the action starts, and the robot will move off when the mission is completed. - resubmit_on_abort: False # Optional field for signal type "mission". Set to True to resubmit mission if the mission gets aborted by the robot. Default to False. retry_count: 10 # Optional field for signal type "mission". The fleet adapter will re-attempt queueing the mission for this number of tries. - plc: 20 # Fill in with PLC register number. Robot moves off when this PLC register returns True + resubmit_on_abort: False # Optional field for signal type "mission". Set to True to resubmit mission if the mission gets aborted by the robot. Default to False. + plc: + register: 20 # Fill in with PLC register number. Robot moves off when this PLC register returns True custom: - module: "fleet_adapter_mir_actions.rmf_move_off_on_alert" # Fill in with path to custom module written. Robot moves off when module provides the user-defined move off signal. \ No newline at end of file + module: "fleet_adapter_mir_actions.rmf_move_off_on_alert" # Fill in with path to custom module written. Robot moves off when module provides the user-defined move off signal. + default: "custom" # Specifies a default signal type out of those listed above. If the task description does not provide any signal config, the fleet adapter will use this default signal type. diff --git a/docs/mir_actions.md b/docs/mir_actions.md index 328a9ee..669c78d 100644 --- a/docs/mir_actions.md +++ b/docs/mir_actions.md @@ -59,41 +59,79 @@ ros2 run fleet_adapter_mir_tasks dispatch_delivery -g go_to_waypoint -p pickup_l ## rmf_wait_until -The `rmf_wait_until` plugin allows users to create a multistop task for their MiR integrated with RMF. The action would consist of the robot travelling to multiple waypoints, stop and wait there for a configured period of time, then complete the task by performing its finishing request. Users may wish to use the move-off behavior provided in the plugin or customize their own to end the waiting process earlier. +### Overview + +The `rmf_wait_until` plugin introduces the `wait_until` action. It allows users to command robots to wait at a specified location until it receives a move off signal or until a configured timeout. The robot would then be free to move on to carry out the remainder of its task, or complete the task and proceed to its idle behavior. During this waiting period, the user may command the robot to perform missions or any customized behavior with user-defined move off signals to trigger completion. This action can come in handy for various use cases, for example: -- The robot has to perform a multistop delivery, i.e. travel to several waypoints to pickup or dropoff some items that it is carrying -- The robot is performing the same custom MiR mission at different locations, and is ready to move off to the next stop when the mission is completed. +- The robot has to perform a delivery where it travels between pick up and drop off locations, and wait at each location for an external device to load or unload items on itself. +- The robot is performing a MiR mission at a specific location, and is only ready to move off when the mission is completed. + +Here is the workflow of a multi-stop task, demonstrating how the `wait_until` action can be used: +1. Users submit a task with a list of waypoints, RMF will send the robot to the first waypoint +2. The robot will stop at the waypoint and do nothing until it receives a move off signal or until a configured timeout. +3. Repeat Steps 1. and 2. until the robot has travelled to all the waypoints in the task. -The workflow of the task is as follows: -1. After users submit a task with a list of waypoints for the robot to travel to, RMF will send the robot to the first waypoint -2. The robot will stop at the waypoint and do nothing until it receives a move-off signal or timeout (both are configurable) -3. Steps 1. and 2. repeat until the robots has travelled to all the waypoints in the task. +This plugin currently supports three move off signal types: +1. Move off when a MiR mission completes. + - Users may create/select a MiR mission on the robot and provide the mission name in the fleet config or task description. This mission will be submitted to the robot when the waiting action begins. The waiting action will end when the robot receives the move off signal, which in this case happens when the robot completes the mission. +2. Move off when a PLC register returns `True`. + - When the waiting action begins, the fleet adapter will monitor the state of the PLC register specified in the fleet config or task description. When the register returns a non-zero integer or `True`, the waiting action will end and the robot will move on to its next waypoint or task. Numeric strings convertible to integers are also accepted, e.g. "1", "5". +3. Move off on a user-defined signal. + - Users can customize their own signal type by implementing a `MoveOff` module. +The plugin also supports task-specific move off signals, such that different signal types can be used for different tasks or task phases. Users can specify signal types in the task description, which will override the default signal type provided in the plugin config. If additional config is missing in the task description, the fleet adapter will refer to default values from the plugin config (if provided). -There are 2 move-off behavior provided in the plugin. -1. Move-off when a MiR mission completes. - - Users may create/pick a MiR mission on the robot and provide the mission name in the fleet config or task description. This mission will be submitted to the robot when the waiting action begins. The waiting action will end when the robot receives the move-off signal, which in this case happens when the robot completes the mission. -2. Move-off when a PLC register returns `True`. - - When the waiting action begins, the fleet adapter will monitor the state of the PLC register specified in the fleet config or task description. When the register returns a value of `1` or `True`, the waiting action will end and the robot will move on to its next waypoint or task. +It is possible to submit tasks with move off signals that have not been configured in the plugin config. However, it is up to the user to ensure that these signal types are valid and compatible with the MiR. +### Setup -It is important to fill in the configuration relevant to the `wait_until` action following the example provided in `mir_config.yaml`. It allows users to customize the behavior of their robots during the waiting action: -- `timeout`: The default timeout of the waiting action. At timeout, the robot will move off even if it did not receive the move off signal. -- `signal_type`: The type of move off signal for the robot. We currently support `mission`, `plc` and `custom`. - - If `mission` signal is chosen, users will need to provide the `mission_name` for the robot to trigger the MiR mission when the waiting action starts. +Users can configure multiple move off signals for their robot fleet in the fleet's plugin config, up to one of each supported signal type. If the task description does not provide sufficient information to configure a signal type, the fleet adapter will refer to the plugin config. This is suitable for users who only require a single signal type for their tasks. If signal types are not configured in the plugin config nor the task description, the robot will not have a move off signal set up, and simply wait for the full duration of the timeout during the action. - An optional field `resubmit_on_abort` can be used to configure the action behavior in cases where the MiR mission cannot be successfully completed and gets aborted by the robot. When set to `True`, the fleet adapter will submit the same MiR mission to the robot if the previous attempt has been aborted. The move-off signal will come only when the mission has been successfully completed. If `resubmit_on_abort` is set to `False`, the fleet adapter will accept abort missions as a move-off signal and end the waiting action. - - If `plc` signal is chosen, users will need to provide the relevant `plc_register`. - - If `custom` is chosen, users will need to provide a path their custom `MoveOff` module. This will require your own `MoveOff` plugin. A skeleton of the plugin is provided in `rmf_move_off.py`, with `# IMPLEMENT YOUR CODE HERE` indicating where users should fill in their code logic. An example demonstrating how a move-off signal can be called with ROS 2 `Alert` msg is provided in `rmf_move_off_on_alert.py`. - - If the `signal_type` is not provided, the robot will carry out the waiting action for the full duration of the default timeout. +Steps for setup: -For task-specific waiting behavior, users could provide the same signal config in their task description instead. The signal behavior provided in the task description will override the default behavior in the fleet config. +1. Fill in the appropriate fields under the `rmf_wait_until` plugin in the fleet config, with reference to the example provided in `mir_config.yaml`. It allows users to customize the behavior of their robots during the waiting action and the type of signal to trigger move off. + - `timeout`: Optional, the default timeout of the waiting action. At timeout, the robot will move off even if it did not receive the move off signal. If not specified, the timeout will default to 60 seconds. This value can be overridden by the task description. + - `update_gap`: Optional, the update interval for logging purposes. If not specified, the update gap will default to 30 seconds. This value can be overridden by the task description. + - `signal_type`: The type of move off signal for the robot. We currently support `mission`, `plc` and `custom`. You may configure default values for each supported signal type. These values act as default configuration to be used for the action. They may be overridden by the task description, with the exception of `custom` signals. This enables users to trigger different types of move off signals at runtime for the same robot fleet by submitting different task descriptions. + - For the `mission` signal type, users will have to provide the following fields: + - `mission_name` is required for the robot to trigger the relevant MiR mission when the waiting action starts. This is a compulsory field and may be overridden by the task description. + - `retry_count` is an integer and an optional field, used to configure the number of times the fleet adapter should re-attempt posting a mission at the start of the waiting action. If the mission cannot be successfully queued on the robot beyond the number of retries, the task will be cancelled. This value can be overridden by the task description. + - `resubmit_on_abort` is a boolean and an optional field, used to configure the action behavior in cases where the MiR mission cannot be successfully completed and gets aborted by the robot. When set to `True`, the fleet adapter will submit the same MiR mission to the robot if the previous attempt has been aborted. The move off signal will come only when the mission has been successfully completed. If set to `False`, the fleet adapter will treat aborted missions as completed and end the waiting action. This value can be overridden by the task description. + - For the `plc` signal type, users will need to provide the relevant PLC register number. This register number should be an integer and available on the MiR. This value can be overridden by the task description. + - For the `custom` signal type, users will need to fill in the path to their custom `MoveOff` module that is implemented from the `BaseMoveOff` abstract class provided. + - The `default` field is optional but encouraged to be added. It should point to any one of the configured signal types. If no signal type is provided in the task description, the fleet adapter will select the `default` signal type from the plugin config as the move off trigger. If neither is provided, the robot will simply wait for the full duration of the timeout since it does not have a move off signal configured. +2. [Optional] Create your own `MoveOff` plugin. + - You are encouraged to use the `BaseMoveOff` class in `rmf_move_off.py` as a base for your own module implementation. The class methods will be used by the `WaitUntil` Mir Action. + - In the plugin config, update the `custom` field to point to your own written module. -To submit a multistop waiting task, you may use the `dispatch_multistop` task script found in the `fleet_adapter_mir_tasks` package: +### Usage + +To submit a multi-stop waiting task, you may use the `dispatch_multistop` task script found in the `fleet_adapter_mir_tasks` package: ```bash -ros2 run fleet_adapter_mir_tasks dispatch_multistop -g waypoint_1 waypoint_2 waypoint_3 -t 1800 +# Trigger a task using the default mission signal type +ros2 run fleet_adapter_mir_tasks dispatch_multistop -g waypoint_1 waypoint_2 waypoint_3 -t 1800 -s mission + +# Trigger a task using the mission signal type with a specific mission +ros2 run fleet_adapter_mir_tasks dispatch_multistop -g waypoint_1 waypoint_2 waypoint_3 -t 1800 -s mission -m some_mission_name + +# Trigger a task using the default PLC signal type +ros2 run fleet_adapter_mir_tasks dispatch_multistop -g waypoint_1 waypoint_2 waypoint_3 -t 1800 -s plc + +# Trigger a task using the PLC signal type with a specific PLC register +ros2 run fleet_adapter_mir_tasks dispatch_multistop -g waypoint_1 waypoint_2 waypoint_3 -t 1800 -s plc -p 30 + +# Trigger a task using the custom signal type +ros2 run fleet_adapter_mir_tasks dispatch_multistop -g waypoint_1 waypoint_2 waypoint_3 -t 1800 -s custom ``` - `-g`: Takes in the waypoints the robots should travel to for each waiting action. -- `-t`: Default timeout of the action in seconds. +- `-t`: Optional timeout of the action in seconds. Default to 60 seconds. +- `-u`: Optional update gap of the action in seconds. Default to 30 seconds. +- `-s`: Signal type for this `wait_until` action, currently support options are `mission`, `plc` and `custom`. +- `-m`: Further specifies the mission name for signal type `mission`. +- `-r`: A boolean determining whether to resubmit missions if they are aborted by the robot. Used for signal type `mission`. +- `-rc`: An integer indicating the number of times to reattempt queueing a mission. Used for signal type `mission`. +- `-p`: Further specifies the PLC register number for signal type `plc`. + +Do note that this task involves using the same move off signal for every waypoint the robot travels to. diff --git a/fleet_adapter_mir/setup.py b/fleet_adapter_mir/setup.py index 3d06919..592ecaf 100644 --- a/fleet_adapter_mir/setup.py +++ b/fleet_adapter_mir/setup.py @@ -21,10 +21,7 @@ 'console_scripts': [ 'fleet_adapter_mir=fleet_adapter_mir.fleet_adapter_mir:main', 'rmf_cart_delivery=fleet_adapter_mir.rmf_cart_delivery:CartDelivery', - 'rmf_cart_detection=fleet_adapter_mir.rmf_cart_detection:CartDetection', 'rmf_wait_until=fleet_adapter_mir.rmf_wait_until:WaitUntil', - 'rmf_move_off=fleet_adapter_mir.rmf_move_off:BaseMoveOff', - 'rmf_move_off_on_alert=fleet_adapter_mir.rmf_move_off_on_alert:MoveOff', ], }, ) diff --git a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_wait_until.py b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_wait_until.py index e945ba1..08240f6 100644 --- a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_wait_until.py +++ b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_wait_until.py @@ -24,7 +24,7 @@ class ActionFactory(MirActionFactory): def __init__(self, context: ActionContext): - MirActionFactory.__init__(context) + MirActionFactory.__init__(self, context) self.move_off = None # Raise error if config file is invalid if 'signal_type' in context.action_config: @@ -36,8 +36,21 @@ def __init__(self, context: ActionContext): f'for signal type [mission], but mission name is not ' f'provided in the action config! Unable to ' f'instantiate an ActionFactory.') + if 'retry_count' in signal_type['mission']: + if signal_type['mission']['retry_count'] < 0: + raise ValueError( + f'WaitUntil MirAction takes in a retry count for ' + f'signal type [mission], but retry count provided ' + f'is invalid! Unable to instantiate an ' + f'ActionFactory.') if 'plc' in signal_type: - if not isinstance(signal_type['plc'], int): + if 'register' not in signal_type['plc']: + raise KeyError( + f'WaitUntil MirAction requires a default PLC register ' + f'for signal type [plc], but no PLC register was ' + f'provided in the action config! Unable to ' + f'instantiate an ActionFactory.') + elif not isinstance(signal_type['plc']['register'], int): raise TypeError( f'WaitUntil MirAction requires a default PLC register ' f'number for signal type [plc], but the value ' @@ -61,6 +74,27 @@ def __init__(self, context: ActionContext): f'WaitUntil ActionFactory will be instantiated ' f'without supporting any user-defined signal module.' ) + supported_signal_types = {'mission', 'plc', 'custom'} + if 'default' not in signal_type: + self.context.node.get_logger().warn( + f'WaitUntil ActionFactory instantiated for robot ' + f'[{self.context.name}], but no default signal type has ' + f'been provided in the action config! If no signal type ' + f'is populated in the task description, there will be no ' + f'move off signal available and the robot will wait for ' + f'the full duration of the timeout when this action is ' + f'triggered.' + ) + elif signal_type['default'] not in supported_signal_types: + raise ValueError( + f'User provided a default signal type in the action ' + f'config for WaitUntil MirAction, but the default signal ' + f'type is not supported!') + elif signal_type['default'] not in signal_type: + raise ValueError( + f'User provided a default signal type in the action ' + f'config for WaitUntil MirAction, but the default signal ' + f'type is not configured!') else: # If the user did not provide any default signal config, log a # warning to remind users to provide signal type config in any task @@ -117,13 +151,11 @@ def __init__( ) return - self.logging_gap = \ - context.action_config.get('logging_gap', 60) # seconds - if description.get('logging_gap') is not None: - self.logging_gap = description['logging_gap'] - self.wait_timeout = context.action_config.get('timeout', 60) # seconds - if description.get('timeout') is not None: - self.wait_timeout = description['timeout'] + self.update_gap = description.get( + 'update_gap', context.action_config.get('update_gap', 60)) # seconds + self.wait_timeout = description.get( + 'timeout', context.action_config.get('timeout', 60)) # seconds + self.signal_config = context.action_config.get('signal_type') self.start_time = self.context.node.get_clock().now().nanoseconds / 1e9 self.context.node.get_logger().info( @@ -166,7 +198,7 @@ def update_action(self): # Log the robot waiting every X seconds seconds_passed = round(now - self.start_time) - if seconds_passed%self.logging_gap == 0: + if seconds_passed%self.update_gap == 0: self.context.node.get_logger().info( f'{seconds_passed} seconds have passed since robot ' f'[{self.context.name}] started its waiting action.' @@ -176,14 +208,15 @@ def update_action(self): def create_move_off_cb(self, description: dict, move_off): signal_cb = None + signal_type = None # Determine which move off signal config to use. Any config populated # in the task description overrides the default config provided in # action config. if 'signal_type' in description: signal_type = description['signal_type'] - elif 'signal_type' in self.context.action_config: - signal_type = self.context.action_config['signal_type'] + elif self.signal_config is not None and 'default' in self.signal_config: + signal_type = self.signal_config['default'] else: # There is no move off signal provided, we will just wait for the # duration of the configured timeout @@ -196,25 +229,31 @@ def create_move_off_cb(self, description: dict, move_off): signal_cb = lambda: False return signal_cb + default_config = self.signal_config.get(signal_type) + task_config = description.get('signal_config') # Configure the specified move off signal match signal_type: case "mission": - mission_config = self.context.action_config.get('mission') - mission_name = description.get('mission_name', None) - resubmit_on_abort = description.get('resubmit_on_abort', None) - retry_count = description.get('retry_count', None) + mission_name = None + resubmit_on_abort = False + retry_count = 10 + + # Check for default mission config values + if default_config is not None: + mission_name = default_config['mission_name'] + if 'resubmit_on_abort' in default_config: + resubmit_on_abort = default_config['resubmit_on_abort'] + if 'retry_count' in default_config: + retry_count = default_config['retry_count'] - # Check for default mission config values if they are not - # provided in the task description - if mission_config is not None: - if mission_name is None: - mission_name = mission_config['mission_name'] - if resubmit_on_abort is None: - resubmit_on_abort = \ - mission_config.get('resubmit_on_abort', False) - if retry_count is None: - retry_count = \ - mission_config.get('retry_count', 10) + # Override default values with task config only if provided + if task_config is not None: + if 'mission_name' in task_config: + mission_name = task_config['mission_name'] + if 'resubmit_on_abort' in task_config: + resubmit_on_abort = task_config['resubmit_on_abort'] + if 'retry_count' in task_config: + retry_count = task_config['retry_count'] # Check if mission config values are valid if mission_name is None: @@ -242,9 +281,9 @@ def create_move_off_cb(self, description: dict, move_off): ) return None # Queue the waiting mission for this robot - count = 0 + count = 0 # we should attempt (retry_count + 1) times in total mission_queue_id = None - while count < retry_count and not mission_queue_id: + while count <= retry_count and not mission_queue_id: count += 1 self.context.node.get_logger().info( f'Queueing mission {mission_name} for robot ' @@ -279,16 +318,32 @@ def create_move_off_cb(self, description: dict, move_off): f'mission queue id {mission_queue_id} is completed.' ) case "plc": - register = description.get( - 'plc', self.context.action_config.get('plc', None)) + register = None + # Check for default plc config values + if default_config is not None: + register = default_config['register'] + # Override default values with task config only if provided + if task_config is not None: + if 'register' in task_config: + register = task_config['register'] + if register is None: self.context.node.get_logger().info( f'MoveOff signal type [plc] was selected for ' - f'robot [{self.context.name}], but no plc register ' + f'robot [{self.context.name}], but no PLC register ' f'was provided! Please ensure that the required ' f'fields are provided in the fleet config.' ) return None + elif not isinstance(register, int): + self.context.node.get_logger().info( + f'MoveOff signal type [plc] was selected for ' + f'robot [{self.context.name}], but a non-integer PLC ' + f'register number was provided! Please ensure that ' + f'the correct data type is provided in the fleet ' + f'config/task description.' + ) + return None signal_cb = lambda: self.check_plc_register(register) self.context.node.get_logger().info( f'Configuring robot [{self.context.name}] move off ' @@ -370,7 +425,7 @@ def check_mission_complete( return False def check_plc_register(self, register: int): - # Update register to check if PLC register returns True + # Update register to check if PLC register returns a non-zero value value = self.register_get(register) if value: self.context.node.get_logger().info( @@ -384,7 +439,7 @@ def check_plc_register(self, register: int): # HELPFUL FUNCTIONS FOR INTERACTING WITH MIR REST API # -------------------------------------------------------------------------- - def register_get(self, register: int): + def register_get(self, register: int) -> int: if not self.context.api.connected: return None try: @@ -394,8 +449,17 @@ def register_get(self, register: int): timeout=self.context.api.timeout) if self.context.api.debug: print(f"Response: {response.headers}") - # Response value is string, return integer of value - return int(response.json().get('value', 0)) + value = response.json().get('value', 0) + # Convert value into int if required + if isinstance(value, str): + try: + return int(value) + except ValueError as value_err: + print(f"Value error: {value_err}") + return None + elif isinstance(value, int): + return value + return None except HTTPError as http_err: print(f"HTTP error: {http_err}") return None diff --git a/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_multistop.py b/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_multistop.py index 3acaa6d..8e94572 100644 --- a/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_multistop.py +++ b/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_multistop.py @@ -46,8 +46,20 @@ def __init__(self, argv=sys.argv): parser.add_argument('-g', '--go_to', required=True, nargs='+', type=str, help='Places to go to for multistop task') - parser.add_argument('-t', '--timeout', required=False, default=30, - type=int, help='Number of seconds to timeout') + parser.add_argument('-t', '--timeout', type=int, + help='Number of seconds to timeout') + parser.add_argument('-u', '--update_gap', type=int, + help='Number of seconds between logging updates') + parser.add_argument('-s', '--signal_type', required=True, + type=str, help='Move off signal type') + parser.add_argument('-m', '--mission_name', required=False, default='', + type=str, help='Mission name') + parser.add_argument('-r', '--resubmit_on_abort', type=bool, + help='Resubmit mission if aborted by robot') + parser.add_argument('-rc', '--retry_count', required=False, default=-1, + type=int, help='Number of retries to queue mission') + parser.add_argument('-p', '--plc_register', type=int, + help='PLC register number') parser.add_argument('-st', '--start_time', help='Start time from now in secs, default: 0', type=int, default=0) @@ -115,6 +127,26 @@ def __init__(self, argv=sys.argv): "category": "sequence", "description": {"activities": go_to_place_activity }}}) + # Configure wait_until description + signal_type = self.args.signal_type + signal_config = {} + match signal_type: + case "mission": + if self.args.mission != '': + signal_config['mission_name'] = self.args.mission_name + if self.args.resubmit_on_abort is not None: + signal_config['resubmit_on_abort'] = self.args.resubmit_on_abort + if self.args.retry_count > -1: + signal_config['retry_count'] = self.args.retry_count + case "plc": + if self.args.plc_register is not None: + signal_config['register'] = self.args.plc_register + case "custom": + pass + case _: + raise ValueError( + f'Invalid move off signal type provided!' + ) # Add wait activity wait_activity = [{ "category": "perform_action", @@ -122,8 +154,15 @@ def __init__(self, argv=sys.argv): "unix_millis_action_duration_estimate": 60000, "category": 'wait_until', "description": { - "timeout": self.args.timeout + "timeout": self.args.timeout, # seconds + "update_gap": self.args.update_gap, # seconds, + "signal_type": signal_type, + "signal_config": signal_config }}}] + if self.args.timeout is not None: + wait_activity[0]['description']['description']['timeout'] = self.args.timeout + if self.args.update_gap is not None: + wait_activity[0]['description']['description']['update_gap'] = self.args.update_gap description["phases"].append({ "activity": { "category": "sequence", From 19cf114075eac7229e85483fb2144a88dc5a888f Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Fri, 6 Dec 2024 11:05:38 +0800 Subject: [PATCH 40/46] Codestyle - break lines that are too long Signed-off-by: Xiyu Oh --- .../rmf_move_off_on_alert.py | 4 +-- .../rmf_wait_until.py | 31 +++++++++++-------- .../dispatch_multistop.py | 23 +++++++++----- 3 files changed, 35 insertions(+), 23 deletions(-) diff --git a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_move_off_on_alert.py b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_move_off_on_alert.py index 00df7c6..4dc75bc 100644 --- a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_move_off_on_alert.py +++ b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_move_off_on_alert.py @@ -69,8 +69,8 @@ def begin_waiting(self, description): msg.task_id = self.context.update_handle.more().current_task_id() self.alert_pub.publish(msg) self.context.node.get_logger().info( - f'Robot [{self.context.name}] published alert [{msg.id}] to signal ' - f'that it has started waiting.' + f'Robot [{self.context.name}] published alert [{msg.id}] to ' + f'signal that it has started waiting.' ) self.alert = msg diff --git a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_wait_until.py b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_wait_until.py index 08240f6..b049fdd 100644 --- a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_wait_until.py +++ b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_wait_until.py @@ -146,13 +146,14 @@ def __init__( f'task...' ) self.cancel_task( - label='Move off behavior cannot be configured, unable to ' + \ - 'perform wait until action.' + label='Move off behavior cannot be configured, unable to ' + 'perform wait until action.' ) return self.update_gap = description.get( - 'update_gap', context.action_config.get('update_gap', 60)) # seconds + 'update_gap', + context.action_config.get('update_gap', 60)) # seconds self.wait_timeout = description.get( 'timeout', context.action_config.get('timeout', 60)) # seconds self.signal_config = context.action_config.get('signal_type') @@ -165,6 +166,7 @@ def __init__( def cancel_task(self, label: str = ''): def _cancel_success(): pass + def _cancel_fail(): pass self.cancel_task_of_action(_cancel_success, _cancel_fail, label) @@ -198,7 +200,7 @@ def update_action(self): # Log the robot waiting every X seconds seconds_passed = round(now - self.start_time) - if seconds_passed%self.update_gap == 0: + if seconds_passed % self.update_gap == 0: self.context.node.get_logger().info( f'{seconds_passed} seconds have passed since robot ' f'[{self.context.name}] started its waiting action.' @@ -215,7 +217,8 @@ def create_move_off_cb(self, description: dict, move_off): # action config. if 'signal_type' in description: signal_type = description['signal_type'] - elif self.signal_config is not None and 'default' in self.signal_config: + elif self.signal_config is not None and \ + 'default' in self.signal_config: signal_type = self.signal_config['default'] else: # There is no move off signal provided, we will just wait for the @@ -272,8 +275,8 @@ def create_move_off_cb(self, description: dict, move_off): return None mission_actions = \ self.context.api.missions_mission_id_actions_get( - self.context.api.known_missions[mission_name]['guid'] - ) + self.context.api.known_missions[mission_name]['guid'] + ) if not mission_actions: self.context.node.get_logger().info( f'Mission {mission_name} actions not found on robot ' @@ -290,8 +293,9 @@ def create_move_off_cb(self, description: dict, move_off): f'[{self.context.name}]...' ) try: - mission_queue_id = self.context.api.queue_mission_by_name( - mission_name) + mission_queue_id = \ + self.context.api.queue_mission_by_name( + mission_name) if mission_queue_id is not None: break except Exception as err: @@ -313,8 +317,8 @@ def create_move_off_cb(self, description: dict, move_off): signal_cb = lambda: self.check_mission_complete( mission_name, mission_queue_id, resubmit_on_abort) self.context.node.get_logger().info( - f'Configuring robot [{self.context.name}] move off signal: ' - f'robot will wait until mission {mission_name} with ' + f'Configuring robot [{self.context.name}] move off signal' + f': robot will wait until mission {mission_name} with ' f'mission queue id {mission_queue_id} is completed.' ) case "plc": @@ -382,7 +386,8 @@ def check_mission_complete( mission_queue_id, resubmit_on_abort ): - mission_status = self.context.api.mission_queue_id_get(mission_queue_id) + mission_status = \ + self.context.api.mission_queue_id_get(mission_queue_id) if (mission_status is not None and mission_status['state'] == 'Done'): # Mission has completed, we can set move_off to True @@ -465,4 +470,4 @@ def register_get(self, register: int) -> int: return None except Exception as err: print(f"Other error: {err}") - return None \ No newline at end of file + return None diff --git a/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_multistop.py b/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_multistop.py index 8e94572..9baf6ab 100644 --- a/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_multistop.py +++ b/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_multistop.py @@ -57,7 +57,8 @@ def __init__(self, argv=sys.argv): parser.add_argument('-r', '--resubmit_on_abort', type=bool, help='Resubmit mission if aborted by robot') parser.add_argument('-rc', '--retry_count', required=False, default=-1, - type=int, help='Number of retries to queue mission') + type=int, + help='Number of retries to queue mission') parser.add_argument('-p', '--plc_register', type=int, help='PLC register number') parser.add_argument('-st', '--start_time', @@ -125,8 +126,9 @@ def __init__(self, argv=sys.argv): description["phases"].append({ "activity": { "category": "sequence", - "description": {"activities": go_to_place_activity - }}}) + "description": {"activities": go_to_place_activity} + } + }) # Configure wait_until description signal_type = self.args.signal_type signal_config = {} @@ -135,7 +137,8 @@ def __init__(self, argv=sys.argv): if self.args.mission != '': signal_config['mission_name'] = self.args.mission_name if self.args.resubmit_on_abort is not None: - signal_config['resubmit_on_abort'] = self.args.resubmit_on_abort + signal_config['resubmit_on_abort'] = \ + self.args.resubmit_on_abort if self.args.retry_count > -1: signal_config['retry_count'] = self.args.retry_count case "plc": @@ -155,14 +158,18 @@ def __init__(self, argv=sys.argv): "category": 'wait_until', "description": { "timeout": self.args.timeout, # seconds - "update_gap": self.args.update_gap, # seconds, + "update_gap": self.args.update_gap, # seconds, "signal_type": signal_type, "signal_config": signal_config - }}}] + } + } + }] if self.args.timeout is not None: - wait_activity[0]['description']['description']['timeout'] = self.args.timeout + wait_activity[0]['description']['description']['timeout'] = \ + self.args.timeout if self.args.update_gap is not None: - wait_activity[0]['description']['description']['update_gap'] = self.args.update_gap + wait_activity[0]['description']['description']['update_gap'] = \ + self.args.update_gap description["phases"].append({ "activity": { "category": "sequence", From f375f4294be13b8169fb3ee0589fbe4ba0515432 Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Fri, 6 Dec 2024 14:12:05 +0800 Subject: [PATCH 41/46] Add examples Signed-off-by: Xiyu Oh --- _images/docs/wait_until_task_A.png | Bin 0 -> 87288 bytes _images/docs/wait_until_task_B.png | Bin 0 -> 77478 bytes _images/docs/wait_until_task_C.png | Bin 0 -> 75676 bytes _images/docs/wait_until_task_D.png | Bin 0 -> 73845 bytes docs/mir_actions.md | 12 ++++++++++++ 5 files changed, 12 insertions(+) create mode 100644 _images/docs/wait_until_task_A.png create mode 100644 _images/docs/wait_until_task_B.png create mode 100644 _images/docs/wait_until_task_C.png create mode 100644 _images/docs/wait_until_task_D.png diff --git a/_images/docs/wait_until_task_A.png b/_images/docs/wait_until_task_A.png new file mode 100644 index 0000000000000000000000000000000000000000..1418ab070fd89d6babe61fa630de885d798d10c7 GIT binary patch literal 87288 zcmeFZXH-Z;wr($Y=ge=wQdK8$X5M88%%2!LwjYIDQ5W_~Xz2+G)D}`QWJ(qto99u?KEI z5qHriW79z}AiOO9IvbbZ|63~rOJ?$duHEV$`Stsoq_YPtnvEbH`goF!K$3rordeH^Y|;@%T2?_ zJ+od1%DOu_LDU|sX5O3^S0~NYi#Dv17xVbjU#0ysLN^2R^4Q$2P^-E#7iXi*RkK_T zd(WK9$!m`%tfn#W#R&BER`q;P%kd-oi*PxupMHabuiQ@OgLKISXT6+GTCixwcCRm1 zB?pvEp1Zr(emgiEQjIKn@JwCCJ9czE3JhvUSZ-vi@!8?}&e>+M;P+7EPZGnipc%<) zRR3CDcgPZt5a=vrcqy7TG})}3AK@5Jmog)O#<#y>})M_r(#H@+!+oXHSp|39(<;-wNDjw zb8Y*KTYfn5(B}YR{3V)%5CRFNnl`JJBPT zn-Z+hMBnT4S!VwEyx3qo_}=UOG;x2IJ@6p)6m|^*5{Evh9z)E@-V|Xzvw9_3PU~ii z0s3UQhl$tV6q_cqp7@>R1jDNLKC0qJv3Dufk1oK2@+mA{_KO?H?Y#<{bFfg#?`11Uudb?KZ ziB?g?tf3F;TWY8|Q}Sx`Wu5Exd-tE>Z%T}$yFD_jmbl#cjDCEKb!pJu>bYds`0~R^v80tl^#=<*0>Fu8A{^d`+DsA>Vw>LchF9HQ1uJ*>$bcDzhqk zfV^VWvP%7Km)+ZqCo@%EtEp~yeUTq-+#*)F_Q#h< z6mtl$HjRi}*{+)GqjFz@?#u_#xcZ(ArL)hT8htK7qCN(87`N<@WMdq?<5LZt*_DEG_&?eMxm4#|BH7>{NPVLn1 z+FHs^onlKKkC_zaF%0(F8FIv(Uk#;S{nmFLc)kN3IC;|Nd|Q99BV3uS!OQ;2t_j8b zEr}_*bTLA-&i7)GW~ci}amD6dzecP*e-92>Mgxy)0y>S@;=?cTj4tD@3_a`Dj) zyDG`WFh2J5#MyVrHd~Rz1V!&cZXcY(C9g^+--dE*xt-$QT$f5y5!-K%HUI3n%v2&1 zgy-6{ch-Ed%=IbEk#hzM*^-kW_H2v>JX`E#r`=NG?9~}m#8-a`D~&(REv=9>-TN43 z<2Ix$c&DcZpPfR)IhR7zwV;tmeRWC42z3*S(#Wsl8Ux|v)z?~a`Q$2Vb zS0r)5V^Qzp$2%zxB=ThVMOH#2+{?bdTmNP&V-{i4surDJ+%#c|Sr%7&zS}%|Igjs) zJu<+9^DI?iC5hkak#%Un=|Q0M*eNXwm)KN(wsP{DfFMtmNm<&w=MRT^hb07kkwuMh|)TT`f~q zU^laG-85o-+HF?9_=}B5jce73g>iSDI5#X%?UuAcfz)Z-OshrP#O7iB+|W7TF+{lq1mhr(G+`p2#P8KS?iXj+() z*39sDz7f&3Q(KynLEl8c8%@(#P1IKc2*#l{?x}WvCohhVDNlbfylR7^qt&*7`!aE; zvpBMop(+jkt;ADQs07X4`A&VYcg1tjxm-Kg!Eod0FH`F82i8h3240e)2l5(E+i}a{ zgp2OB;K`^zi9x8v4J>Bbss%^c8$t_MEBf#CkiWd#b!$FPyuE6ho8{BqgH z=mas)QCa1qZfDemWqN!Il3z^o+#y2*?ehxS&q*bpAU}V-#Y^Tx4Ia`xnFCTd4wrLn zJ9P?7cgnLb+xqgPsKnhAk0&ROIZ9>ZH8F9G?aKP;?F?S{dH3bX%W&w?x+&fV1D*Z@ zWnxty&(b@2FOfl!`9*cz^hpJ~!}(gYPH-AuuM&>8HN%>^clrgPCRKk;d^1%Eo`5R4 zr~WIqLpP7nDn?v$-2qe%5*%5EFM086WY%@kM!je2{;jNN3-fq2`Znkamp)SgSM-V&B42VCbbgm>i!`|JG~G=sQ>LtW>8gFK|iBY zCpl7HLv@F5Si!r}u&?*xE=!7$Z^OQOn{XpSZFxk-`6+w!)%87)o>sCXAVt#UL0_Sl zU3w)%0Hu5DueaCIZ+Bga(< zJ4^F9v$WDB#Z)-kG`xP_Y{lTDzL_PiS@VXawWQQEqECdD0=8&iisSp+C>^BPV`8I0 zDf?4VB*8;!a#X}&gm4<}u^G9xDB&yng)WVi;0V6md>tg#y_H79Km_yx3AL7zswEK< zoZqOwn%+;niDJu(7N!%Ru8kc<{i$qt=o4C7v9QU&;(ze?YRYr)SC(yy&IzuW$7 zhqE0tc@w^p=C8D1VVN)bjVhV-y}q;&e=D_0KF{`fcs{>~aG(C|vM68I^OYLT=2-_g zmAT~}O`9Ipdbn%!LgqWjNMeqDtSZ*QeBOI%E&+MiE(*GcIu1039cbu6@oop0c)&6z zy_W8@NQcRDMK{v%VpY%j)ay%%zZmR`sBloq5Ix^2k5phuUHG+rZ`0z*ol2;%l;*m& ze_mw8;-Z^Og0RTQUwI5~y#^In#_RnMs0fJ~l?a7;;jD;R=e~vXe%v_WJexDgnmsN; zT^~>JCo&=jYncP5a~HhViSFpx*3 zu8CyZ!>K_NiF+KDU^DwsKH`A1;gF%agG3je`S_l1SC3@o24Um0${&UmT|uABa&AS4 z?vx1V9es-`A?75p(BX+VmQN3g&^cwePv1c!AlAuFXe^@f*NMh8 z=dbzull!7muKOSzs50-Dsee%=eNiLp<9T=W(kv~vjDVi+-})_Qpp1Z?eaju`-?U<= z$nnpRr!O>gPvuulre)6g=(BNc5S*W}zV;?!g%lO#<>!(yrbK)R_IR*;pjPc%rnvgt zhf=;ux+s8PpPqBM^6yuzcP~ge91P(ONahRr3`Kq|53;O6BN=~r&S8diFaI@slO0rE zvcpfe>U3NB2U@cP<7OW|+1ITZ3+V4AHRUKW@5t2I1P~l4{(HTfOs<}qwUI&d(p%>1 z2DyIMkk5BIEse~i$HT{@o?K!|(t5@S{vG4G$6~i3-hNqXR52THbxYh6Qu4rU(jx!T zIdF>%|8|R5Xl25b`TyM`M<*&PE4|69Y3?gz==#J8CO8C5w&TQ_X9y~7W^oip9w&^Btr4z8JHY!W*=v4>>iT?IS2qjy9qzh$nda}p%4Gg69Kr8aiq)o?-!%$TCh{{WMt3v> zuP!@|lY`Y=Xnpdv*xh#%y7QhD~3m zB5dGXqz@>qmNV|@3SLeWn0{w?vGiND)Ky zq%E9z!tT5DMkvf@Q-KKf)9khKm{Dtxvc8!DQ~{@z&u+`@cv3^7mKbNXe(-8qfBc8R zvFC6Z6O{Y|x&d-S4(s#iR1CVq zg4}`{jGPtCvp1zpvOS1+*7$gQW~5x;2AIJ$Uzw;Ohb4;E7`N! zuYf(d`iP9-jQ^Y5xsiB}IsUash1@#==`3p`%kG;a`3&3F9d=6jU73P4+25NgYtRwBjt($ zF?i(|*_HIWDI4|aU;d;$0FDKJv7SZ=Cw@AoI-mv<^%2TahNHQx)%+3c7?ks0w-Wlc=hnYrn z&Rpy>WP}ctIXZl+EY1AFO0<1Y2Ca=#WGgi9&dcL(DdVo~rW7}ta90Qds;zRGUeBf% zS|<53_MukuQNA#z5uLj>$h?t)(t`n6yr?w4>h#h+_1w?GMVD4pUR?zbD9((W4|1kD znIk85k$!gmivyVW(#d0`u;+*G{ZupwszXv|%8p$@xdggdR~2ken#k$^b8*&pXprxs z5^HOAA#!5E5$TVDD$|rZA0(?7iY?6tci=NEIU1KJVbir|D;9y;9W5+5%I@l1T`M!RXt%YBmX}9_Aw)XAOKGpD6$Qm2nMp#Yk=zql|hsTt>&~Su1Z#bWp zxw=NJnw|JM+ZTA<_jF$ZeXF+nrf1x}Py6(Ww0*+JK!}t69f;Vc>*2;b>Ka6rd4z_k zpKQ_Hf>=@96KfM&y^kAh$HpA#BCns=J(v+dS*f5Ck1r(0tftTF`MHrqExs=mCcBci zg|846)V0U*Y$^2LZw19pdHREk;&+b(vIp~|O1h~B^T?pSs=N1U=gGO1pl_<70gv0X zPYC{OhHarWd+kExBqpz*m4$Eh+j+0^-k?Wq6afk+(#l6U(O1)3VtOV|lQhqk;YGQg zo3UmvBf~+ZtZ#3THAcdVzZ_-=?ZgsKt232-QiS`@c(s;S!bpuwHVC(I6g#8Gzu7uQ zx>iM4-O6)u)T4m!v}GTAwq*Gkr7LmodF;b?8F!>{LiOB*3@opA;<=_WOArp?Dal?s zLN3orQW_ShOZpFsB^)&JwI&@q5Q{Usn6&FjS4TN557G=Lc50+f4RIe9%AGP&%uVB=2_GWaj4_ZGa5l#}j|T z_GIggP+viNZR1uHXFPG0`@rDbP^AZ|j8@+V7PRVrb8$SkTDJTex?7yZWq2AQh$s=6Za zh%{=kpoT@U(S{S897cw$FkF~d{HvcK*I0gwL3!-``EdqhD-T%FpFC^5}@eQmt8pj zdp;?*PZV@b^v>eT6{M-FXe66%fGXUe_b=F|tFZ4D(i%H{elGN_P^V>5byDI%_T9UNf=aoyAl&}wB z-v5MX+*`a3e}7!F%mbxhOpdfrt?Q(ObAn0dE-|w85~t@O>SxgLps*Qp=dhXq_gFxH z30*~2WXniMyrWH4WtQRS5oRDuG3f`Nt5ZS&*7H23&{rdJ^CAS6gMECOzZTXj2i2E5 zDm^*eFGF00JlrbsKBPJKQ}^FqUqG!0-WmctMYw_3eUCR@j z5oWKk_B4&Y{&GI^-#_-~hIkJqo9JL7? zqUn5B>X}ai9OUEf;_LKISG74wmhLUpk2h&k5qC>VJI&owasDf^fZ-ffyKZ<=63M`2 z5NKl{|K<6De_Zp1r?rpf_e%GL#a~24?_l|eaV)(B|MccQzJ0ALJ&6ZSbXu^?UaEn+ z=>iiIvjoeD7xw#kXp)S?ra<;59KeyHTZmRm&<6BMVfg-`7l za$Kqc%;>mZx^xOezf06<5qTvNJ%1+er6B;xVtdF>-x{Z~(!gql z^Q^~v?o5u~d#X^SvmnHUHB!67HEpe&BV+EJ>oBcaEhKekYV z>5B1r!WP>iB42S4DWNuK8MI(el!9;4?95l}f08(_=i*2rH0X2r0PbRm`|<0xf^O32 zEwhNV^y?4!J(LTdrPLpiOh`alfY#;rz?LQ!lo+a%W+$v(9P^QurkuJ0kd@Y3Iz(dr zUIhm!_LuVUA(MWNf<>2`1HBj-{RWA-2tq3QYjHgccN{fX`3a*#FEu1$bKWQLfR~6e zG_S>YLvtlX1J1EN+M9RyfakFPW1kUEQ#7dzAB7^9hAq)46#;Z3rkGt^frUyqOjUU(3_8uOfg1v4zO5TEA4O9^A( z7R~s<%fM1jk(^GAmF%PSt!~WYH=@>-Xr{!(M=mg%?ug_4~De4 zl9#m1N_vcfqZ+~x9F*@Dw&{4EUu83}IsNe7zx9mYXd+gc8McUemUQ9N;_`Wt`IayC zzWeq#DKFeJ>=0u>`1*oY214|yDnHmkfEP|<9js@LV{?(4cfX6RXS^$AThIr>O(V<8 zvLG+fv#IxAnN6qpyc8UJ#8Tneja-jAkkMdLI_C?s6nriT);62(7OHSKBaO22=Q+`v z^O=dwJLUM>nHM~lziwOim!57*?hp`9^!}O&K9VR~ozD~)lKY^-7|`YW>+`-05pC{; zVm;R!Mm$@r7lf!0+t;2!r-ElmWSn^l_TtqqgNmvEK1?6mo+#V^VKF)yd3u|{PQ?tH z3bn&qaB*WYcNy|^YYcgkvUXIh)_k62C*>qPsh4$5m1KU|B17Pk3-Ut2K}t`%qtt6y zWsjb)qgv;lDuf-imfgrOd}uL*xr9Ib)V)tgU{q$}w9#4R)m-71^$9$lR{P6&rw?}* z@Nqyz@XnI?S+{V*#|Qcg22jbVggtFPc_!3zA0*<|Nni!7BeqEMrMK*$Fh2Y(l4|ak zg0i-}yPVfBBrDQt>BAOLpCU4y?Wg=Z(g@3W8TO{beV zRLr{!d!U3MwZB}V>3>4i&6uyia%aTtY9XD^S2eu7zTM?O0#;K@HR{lKfaSZFNZr8I zU?>*!gOBKu2_v6gW%6p0q~;#`d7t|SgXsRj{NsrIWXX4@f8A|8iSBz7FqXJf-q3fa zOAk+7U46`9wNLp{@e$epbYhUrx(`#H)Gjglw7l3IH(tq;dlz{Xt;p%X z@utGQU-G&kS)_6$kCVUD3*{*2>r*CJgd6x&Iaz?CPRLxdKzn|r7sr?VHx0_GU%&-u z0>KmhOM4DvX{Td_R;|PA2Z7g#c&d;mo8%IwZL9KvzXPA}b%CWfdIEg~QI&spbdU`6suqgliYh52;Sk+x!p39Mp-Wxm| z*7`pD{(alyoRkHLYcW*9^%-;e?s&F}-aRZrUxCl)DoI`yt>Nh5EwMQ%CKTl(3BQQ| zJy=5{PQ=1IaU-Js{V-eTTmTtxC(*9at9WS_cvqZR&#TQbx!R)<-Jx#EQJAIS$Z%{& z1eIuA`o$7UiKPL0 z=(hipq@K!cY9PWB81VJLS4!^Os^4w0E$#B(FY9p2$g_sYOxey_B__sQ7*k{G~P52}>5VjedtWXsVQ^nX7IsW6q;C z8|}EeaxAs&`kaV{a>@c=Aav5IxRIR~UKvIq$oYJQStVsnMf^xzl&hz>`RYsxZ?r&X z5eS14qF5-W!vVQ^Y5!=9)2sbR->0bMx*2ztaZFYOz*MFzb5h?~uGZC@c%Kz`Leo7q z9#^;FiH`m8?`+ZTrs+;7S5t}DlvBU>G_YA0RfOhmE3!14E`;u^B->RTQO0!jOb%-q zZdXk?DpsG&cm`mh|QwN)1-R<%9TSkEE1)`edb*?=qQ>+)P;wp=;&Kd=@(Jn(*k zXnblsuP;q^)tH!=j&DkMo!W=C)4EI8pdIyQRIl9>L!{W-1HozMm=H=0tf9*0MgJ>c z1(nVME1Rd(YO<=ZmqA}k&mr*cz{YU?G)MK+0x+V*bV_^1?-fREG|- z9kf`D0^mpI?fy{19FhAgx~xr>6n$*Nz{lMuN5Gz&(LM`>P|2 znt<%;Ytd4G@txK-;v0=3XGO~gcahKSvev(n$jlz(Vm)RsTm|kI^R%>H_9zWo|sF zI3^KqU;!a+SkVErZv)tIan7=3fQ?9gnC3E~BV8})A+!)IwLM{rma%9S_e zxcw3FeD@j{%qD6O>>kS1)i;^zIbU)TglVV{SpUpf5Mwcs4E=SfFy6b*y`c&#q@xi# zvt%?8wyT@BFe8rjuRTe*`Xh_uR0+5xw`3l6$S976GB3bXR+zo^vX@nzy+r;%Mr=R{ zXL1t$czcgfg}9nKnB4KGS8!HaLnKcg$u-IF$O|C}5RIM8NC{qrukX{$`%;8I5zslQ z;~;L+tTxqq-HyQb&L-n~H^$GPK%KWoh@!(ahAqmZv!!Q!dP>h8MClmpiR@zW_ZEl1 zgKv9`kx1X`p&Z@%OI$nKfUi7Gcu<)_Xx0b!fk;MaGhL~;+l8#w6qy&BSYUyeJbfSFu# zL)0d#Rb}y8dEHv>kQ9uLKn48eYZGdnp@=&AKSQ+%2TNklrl2yS*ZSpZNdPzIBNHW_ zUnMjo1!WbT8Nv*+UW~$NnhS!9oi|OiQMO%|y!ih5eyWfcT_Ooem8M91Jdt+CHC|-SBgjr<_PAMnb1umDXWfO3l|2*=%QiK zk>{AgB-fpkal+8|gT2KLm5EvS`?Il$ytK{g#_(1l6Q3I{88$v&%^@%^<0)=rM`UOR z&;eMJ!mo)p$kT3?=WlXKq#_7Q3lhafIy_Afm8_t243KAhN3vE1U;MX31{5oxRjbxC&D9~CoWCqWeC>1rW}bF;WS}U#lj=94Q}gxZE(h5_zQbhu_M0-Z`nJpHwliP~L z)qGL5Yy&{59k>fo_<0-6)!a_QLEkUJk^SoC%ibcQPX#I~AM-u~%*OUtEzT+vl5Cp* zledc!B{e*XMg8Fi^5auSyxE97kZqJ-5*UBI$NoTpSey1tftoJbIEo25sKsTL#!9Bf zBlVj=8c7N4nzy505Oj$tCL;wpRd^ved=wp>7$7xSoNOUne;(2JgJHVj38ONEpo=IE zddo4g;Z>t1?`TPv+x(9oJz+#0a8zs>m7jDzYAyZuvQ20So#1h4^YJygJPAyOwLo0s z*?lM;en$I^=KF6EAGGB^cBw3UU@-9g6@cxYI8q;zjIu$Be4o+!-59Q+YD#O2If5rs zw-QeEZnK;&2Jy|`nf^sq$fq>2F!EXk)hNjBn9SL?0)J;-Eu#N;!?(#Y?lDnm z*i$p-^`Ii%Xm169>E*5(nZ$@UoV;Q=;{`P+^>T+k1>0R~0^;LawD)&vc{%cm-puz5 zzXt9#O3-5zn22)S!KNS-7<^F?!WNtr`W|+n2!A|Z}IC2HQmTd$J6TMJ1$mO$?bcw6oMxnEDKff?PGufz|yC#_2Pw@;Yj3h!a6^|vb#Z!h# z-acJ)RK*wFD)}1pVhJJhF!JfZ=Hp+rUsNSeQfIiO|9*v1zeD7S;Bsj|v^MS`tpBpG zM1%ElO-Vatuq!3#eW)=kd8FFu1td4iPD`-bJ{M3N{P={trnjRc=#?OC@m#Fbhy4f2RT( zw~$<_Z|Hl}rN==xA=A#Lugll}`}=GE+!qh&J?2%E9Bn505vRi}MP7$rkIXpf;;c8NdAsHCs}@o3KUXqo!DJG1yXDm*sJRs|G$f% zeu=o#-GfQO6sw#HRaT-08;eei(fIRkd=zJKIe=*2hbIWD34VZCVWWLGpiJe;3YD#! zSk*5TI}V*WI}SCgbW_@t2It<~B>c6GJ@8h}6e@g+|MMqSkHCD;@S@xF>Z3+oMdn@qr%8g#q z0l{T8Qd6TaVvwsY*%X5+4@ z_KEykidHB5$BkM_4}z0!KJeEb$ecetp~%6;pf%{kJJ(QB(R^}3_4TEAH0#4=oBP!P zKWNDoMH_50`~#T2m)VF@2D$2&u+hDc9}2)vP89Me-T$qD#R~h{MgqCpjf0u2cWe07 z_lOs114Tu-y7{zz>!MQ9njvFMneLm3BRS>EWGJboD7a6Gpd?+e5#bNl;x|5VKB!VE zlHd{LYe)SYh5Hzvw%nsk`}&_+71p5eUXuEK3YiV<$(|6|BxQnXnnGv!FquU)^3X=@ zv#jV{q=@c+Nk5=)ed-(~+&-kJL@70s`-m*fLXgxg_={%z!#`aW^0&4Bx4#S0eq1V# zTt@s5$QN9b;lbze39vk;dmw9){~xFQHwLeV@yT`_2Peixdu`y?No=Q(NkI=*MNs{I z2ZfDNc}?rr<@<#{2yOsSxJm^=`iyR;0hE*R)x$@@Wadr9yE>HrX&vzskji_Gl^7o< zQ{#i=9{0R=ZaC~o0{+_f=mx}7f)A8Nh(?a8u~z*L^MTAxVY5}Jm1H@=P%2Otq%L!q z%=1J3cNdjXk-R*t;DwKw!!Wm1@MzQ%WZHu#g=O@^dJk39-0Zkfz#B=p~(pz7o6qiJ;QO6hFxV5J21r*-4g zZ2$eaR+DxcC3zyt{3mRRq0#X(p^P&YBDdIKp8s?5OwpDAoqwxEUg4Yh>~?!>!+KwWRe_I!0@S$ z3mwGAOZ#Jtz4oYx+st86{4AV!vF`bJ^NXZATm<1}6z6?CBTv4e{n_My-Ur=-K+5~1+&@-!YZmdU0X19) z`n#(yeybP#t(Mg<^K`9C_{K*f!f$Sha)6p|EqHDKp;C-ZVvX&W%`PLDr z7IkRgZ5LgTRsoJr-3GEYQC)nMiE~#R;Dl44ayN-S07ZOlVbw%8QEK$TgUW4XkUIUpbI^Wrx zsI)R4mV&X&O7pVtLi<}kSr9>UfF%Lj+M9F>H&hc75XRK8AfuIFx~!Y{U>2qzaCIrD z>}u4zp&_t#dWvT^mgoX$M3WE->~>qsE|&9;;vQl3w3(FB*#TR>V%9a{#K0vpS+MMB z?BVtUYpna)5*hn#%o_aCs_~uVY8APN@f))TF;K^jvIGBYzRy#@FFf{KUI-M(*4J1# zTM4H~lUE$A^wb(RT3Eg_Ta-%j47>Du^xt~-5dv3m%IMXdVEkyvAvRiWp^zsBT0ba? zC72$_9fk(0KjdtNqRJKYX9N_UKWiN0F%q+zd>-d<)91KB5wdk~sT${kqT|e|+T|bTPi_B5|!opj(PP(8m_~q64 zuANO0nr*JOP(yM}4|nNRV8q6#N{rL1sWl+b` z94W$qdSo#P23KXE5`&XEp z=!qyY?d4gV(#oV8M`MJmnBD}f@vMxExm}xY$~GTmB?Ff@egu3tmD?`%QlHTBUc>+w zU4Tin&FK3lPL*`22({F*)5R*=zTlh8HlgOs*NFjHgt(^X!0Cs59Q475Wj0byawhTo zEYd&|NN@jUnexqZn}R9`#WRu&fuLGB>9GWr^UKBm{S84!J!i%_^+{fUSMbB$oYDEl z9<){xXnZZadAjt^E7T64!n4L*Ux=R+yrI|NA>`+B>P_OuIhM-?Fm`iuf&wz$)fP0f z&_YKujrSpxgJl<%!=g5EIFQz7hXv#8ZYckQMap z&iK@|kx`7LAs;eG_W{iD0ycjmR<)#3&Os3>YepDFO=s`(MNl9fVNC{@MdbNajOXR% z23H~mpq*ePg{=%0T8G>TVM!~Qm80>l2+zk76DXbo z`90iyaVu8z93Zd5Ob0;SFLl+W*d(+P#6P?6K1GRS7#==Uh|MqA4z(R`7_aIRA<~K3 z!mZBot$qj~UCJS8{+D^OgAp9M8N5M|K?8e~pJ~15?U*VbsQ_p$)vr(YY;JG6(N8Z< zG`_nPd_P)ZVi(BgV-@41%Ps=)D{pUT>=O{odW#>(!?(t}z*y{|q;mY_x;3cC6<&#G z0Ude@=apLnc(WdTy*i){JD#@PhFiy|>z2XuG#$RR5APjk3@u zT}rZP^)DSV*adTc^>Qb*yL6mV-k0bZ+_+jr&f4}2AKbvtr)m5T1!U*vJUz3_I{-2_ z$vcr5Zh7g|9iTU`-qre@sKEc>AVidRHsmf<-Yf#8v0CJ@~mBgKys zD-{n@e6LW)UiMASQJC}}tockkqt@PA^~e(sC{s0>qZl{?(cl;zFHr*W4JajW#a};w zc0c8*arJJ!u@HumJq)k1X>ua=_^yQ2k3a+2leEtCe@HK2Z~PlO`a7wnhY~Cq*gsbh z-F|8{+rf<$CYOMhmrd_gv5TYSK)i_t>VUL}{x!(Eg;xfO|4?@ScLzJ$H_Q~LlH$5l zzM$bI<+y+6Y0zj-%ie7#oS^3<#i|-{y0y9VbrmgTrkWwi!dZshyqLu4fHX`VtF1kn zf%TN!1wTtJ@JC7e7aj+4b5nXJ^2nF~IU{KKOCp&*ZK) z3da5Z5fO*G5m#ma5UrDhf4>P7CnYJuvv&gf6~F?M`Pqe~PE(*5Xk0`wxQC+aQ>l63 z<`0YcSO==)%fX`TlrV=(j!29I4 zhFUtTO@8cIXXxNCM^rh?3kja9$3Gf(>`0NxB`uG@CRSOY29I&6LkI|ZCkrd6_?^L zdZ$l%OpLi%zJh{JUb*nxd!Vs*%xCNVQ!Iu%E7}yk68A<# z1t&~@10C!Jso!0-tGPBn=kz8Bbvn-w!u`f4X5Ew1aPwkY81g95h7yF~R_T^`1I z(g+Jo)`*77sdJ*Cv~5cpf*JDQ7O$2-jax~77AMElLfQ8gFB@&ul?U$frV*@*2)lE} zQFQlw8$1(5{o+vp$g1`)ng8c+e@)7?!xy~FSA7K*?f5g5n=@u@!b~G$71@-#Pf0%At%hY% zQ8bFRBIvwdXIQJtP!4bH$8Ll}kV5e!Pi|YPSvr(RP+7~wsZJEC-HF`@Gg#4%=v1R} z23d&oZ9-V`84Anlq?r5D(e`>+y9=63tIr0nhf-Q1hPhrVCUxPU0R+wFE=b62JwdZM{1rxoDD=q283GpV^eHw-* zyQTfQW4zP?{<#y9uQW)FH@~07DXZxZ_HB8?Z)#f~cVrYhhlv@LEZrb3cXPRJ^Aq%Wb0X1?;fcvIdd0t-!<2e^Jq` z(&GN4spOe|2(nbmsQ>8v8~OIZn&net+D{9$;IUmNb?ceFkl)eJpOpt>-~;dtx{ahW zw&Kh`^j6HKXO-6#WoXK&?cVcu;JaWUSI=z?Q9@CA8}-dYaZSx2H1rQ?`d*9_`SOQ` z9d9xZ!_vG^n{4-W#cyAbZ1^k%Rs_^Yd)8ZHojn4VM=JkQ*5`TlpRQ#mJi~Nck*wWQ zpS_;vzy0qVJQEt}RX9l-Kw(fBJgl&&NNZPEDPsX^7Mi{?KwYR(&^SA8%s-(iV3u#9 zO?h+ZXSl`1FAwCSRA!g=w%6;H-C|I=BOM_G8PAW7upW~8WZb1rPJ#>JSfiS$2)xgv zFZmV0bsRo9)=BhOMgDn+218w&(!kA&TelLd@pHc0=75FYQQ3e?2G+N5W|BmF3?kfi zhSdyF=hdR^s$o^8nt%?~L|uAmz`KC@w(gDtOU?FdG<~8*UyUwAf=x0en>Nur zOJeuwCFcDFZQP$b7?(`N6e1irLznn{Iy;;fPmp(ec(kwHW>>YJnI#5puuwSy4StpN5|276D%oZpA;~c=I>tbk>5f`b#2e9 z08{?%aR$r+H*`Kby|p`nOIP~7i(c#3f+bNdfc2AJ_HvNE-6Xy5HB!R0bpin7sVvSe z>B0+M`NuvG`B(wFZnZnZ}&G9+fs zdJJOTlRG7yOJ0p-O9pIQnHY9?h1Wa!OTJgYH46Z7M&H0Z)ReQ|d3R=d8knw|%5F36 zIfcH!fVR%V0p>QTzWS4e#B5Iex*AaDLP%B-0e6WqLf`)c+3nQt?_H6dJSH7AzF<); zlw+_Q;0A*3$fdOfOgVvF9g+Wj?v*fd3qpYa_HjIpxLgEB3hxa42WmzRcBf7-FX_$Q zn{^i+v)xBnN>>oV-qhCcYGb+3IbkmWp?=Fvty;4P|-PtiFl6IGcISA zsJH#L(KER9-$A2R?BMrn)mjWZp&x@pX=&caI=a{B%rqN!8NC|VZOTE;*`Y8u|Ea?^ zFtlHTzb(egzIiT$uw;ZfEhO7DIbcyagY^!DHFJJAQ@VDIX3ask6f2y~7s$>>>$N*| zo9HB%M1N|o^GN*Qt(L)_jdNUZ3C}&O3~MJ@pT&+!-|1ee7?GDB-oS7)%nLMECYnr} zp=|UYI*A%JBS2PXU>YH>Yn)87jUpf2sWfs|Um<9GKE#szORdonL{V_~(7; z%{~cpkR)w*^ZKB=fr0HN375(&Piq(%pLH@fdZnueFPz_jvWSPuX|>OVn0QkTXRwrc zpDuxu>*HbxXG##7)|do!tBfuaOv1a)M)5a0)wgfoTpPI2D8Mb4A{^{3u$4G)$=R^i zdSu$S>TPDW0q11btwM}AGzbw^pKP5&fWemc?5xVBf+JKmI|Fc_=rpKuBf4`atB>P- ztT4pkO}fglCy2zhrq8CvB$bMI;iW?%Bnz4Vzz524YHS$-hm}`>zkj$VK}VzCFTNjB zgD;^seeqFm;)5+LK>21@lmeumZV>u+;B{vvf$5f+hSZ;J&fvug&+zTd@U04Sq>8<=6Xa4I)v5<{<2n^~ap0e0rR7MQ9NgU@2$qmWC66Cu|6 z;BtScAfSm=hrCIYqjqmcV&)EZ9z{{p+iV?7Samgb#{_|O#}VfPkv^uY^RvKs8_a_^ zP66a%u!zusT*&?_@J`yc>Q1KJ40~P&;J>M`nC}x>yzkciIA_e;NHU#e>AY&vb`vcu zo{X79*3L9~)_Wh1!$%ypmkRqg(M#ux!Z+u2#(*xeEp`pIwy-`2dv4SK0g|C6=VaEm znIi~1#Xz6*jH53N&iQGfYXYFx^+tFoU zxkEtkzqE39=GXj+vomb$PF{0F`}>4R$J>+1v~;W$JbLzi80Ci587}znQjFoio2n3IbIZYXml3in1grsFZT#r~4FE>=B#>eCn|&^=efH*Bq|>B@fX^e$_(=G0 z;917|;JGNeuE<&NOXoktk6IIe6GKD^g0RwK z?h}^Y_0^@nWe}CCeY)>eEfp3DyZ9Vzcd&GI3YVN{8t$T`4Th`{aMODQcY~c-3jH53 zvLOnqXOdp^Mzi^J-nD77sFuB=SELMOO^+;U0s9@yp|!Mgs`y&h?Fks;=b?U&43&=v z2V7WiHziaUA1Rk4&w_lOgkBXI+8LOyB5M}m{Mv>%1dQ!sc3yc#yeMI$==~Ev3u@D7 zVcO#FA|W5$)_%1dZ%$Sh7vl6#s)-j#rm$$~yTo-J03vDIT?iNNa!Y|%@5=<`;)zd3khjDZ z*mp`1pcLjlT+-U(d+;@W6O?xP=v2`#aGY6EonKE_BtH3E%>;XRL4+=g%1Vo5$+C=#5_1)a$RIVz|X`& z-jkMrDU>Ob(?A_dmsEQ~f2uuVXi>o{WYf42(a0FSbho)-rjX`#}S z=V?XuD)R^F$c(>ZPD@EZ1dqpMjX+I=)5EZCI`l=~&3XTPeYhghA)jWf(#0%Ap)!Qy z?OUb?1QQWx7e=AcgJzAAdAQY&q>Up81_^g za_MovxVU4ejwt}a1BJHBN81aWUMmxX{WMXEroi$>MUZd_(89(=y(SrNuPv{qRQ|A< zVflNU?-|7I3vsmET&~47-1IpcxOIDIXGMUhBzr0`&#EWABK*1iE@0XTg}C*h!hke} zJ&xyD6INJppB=2>bt*lT+wgVxA;G;*JAG)3gc2Fd80)CYkelnH!Ti0`cuBG$(Rbi+ z>=CuPN@V=jk9rFj32x<3Fsv#(BcP?_TuhxqX4jnUbV$F|%;BC~XPB37p@&o1Ftn89 zYqpCh7DPGIdmFK=6R^Nj4(wYw#62|S_F5UD%0g&jnpThxfZNI@#ZUKYncrz{Pv;A) zU~kIGvxSuV;W@Dt5#Xr(P{=|Qa`&VnGQ;=e<7u0^FVW-xCan*TXX#B^pFgkU?5gkr z?%r1sGLl0QT%A`SUov_(zApRCZR?~FV-Tb0dsZb+wH|bK5MPyYvW7j9?xfH_!b9k{ zdV)?b)XbW7Fc*djjng+g-5WoCYBYl)==HzkYUT30-&V8!Dn$M1%f~OcM95*zvq02Q+

d&&R zP7Gn(&3IsGEwd&%{&ad_oW(n2UuA8)pEJ4E(WjO8EpZX3pBCBfvwwpWy(MORVU@=Y zq-v^oT@7R|U+WBY-%^p4efQa$eM%#J4=8l@joM0@L2+=Dwm#J`dIKK1N9;E#IEp`- zSDM3W0bm6z4bp!|181dCBzGf9TJ={+X_;=?#3*S40R+7Zyzk+uyE}1Q%UF%ofxAf+ zkTkk3q5GrNW8ZlzLdoYiyIe1}PIic=*s}A+^MG=da)y44J|2>uI{l-h_h(QZ_5PD> zL;(krjfJBe)zvNi%*gqLXRyi~Vf1sc1WPZMoae6W&Al;xy=L z>i^5tKwLS`?6*@?VDPm$C$a(oF!(W1-vQIxoz#3y;|qbHQt`u_q;|KoywFg#>31Wu z<6Qi9MGhH%N_Q^Y@Df3fKh;sUJOE%g1s#OEm4aruP-->&;D_y9H^&M+&rueJ$pZkmHXR38n++9vjyaVF{5u3LXyejr7!xlB)8*5ki~-Tq`- z;iCg8_EbPgpBaq9Ao|tvv3dH`zS((~?nd}-IWWM%(8Pd<0{2I4DNgTkARy}u+z*@d zg@F2eNpOY|s{8nYV3Q}@3e}PgPH?nWCg6qVRJES|v_G(zEce`v^_%Jr0!n;NvX$y0 z^CGQ0HNkX>Lrzh8uJSk()`bL1l-Su_b8ur~DbSM_&zil{v?!p{#uw8CF1 z=le12P$dUcHvX$Borsa;+!~Lm@r-U|{Y%~S&9=X|gdh~J7wgwBGP3vAvwD3!$L<~i z?#is5USpi|roOt-Kg`=UR-|b86()^y-T9`I!=o)XI@we{95g5IBxMCTxxghfe~&!> zJ%mb8i~l>iPJvf$uJ&138a@{R47r_gEgDznG&KvA%|1``aXgzAaFk1hh~_pHk*oz# zK9;ZRd%?+l>f)dw%;i~s{uz61Ui{8#=-;%sxd6e{fJv;)0r<`x3e}B(n->Rc{&=j% z7d2j?`gr{qB!-SL-ytCH{7gDvtu``(!@ zw;(QSe131L2x1c8{96ZORXWGD~yZRg(<2^62#21#kEc|wT^Y? z2hgump$reO_n$03{$lKKEJs7@)+_zOq>2j`X75iB69gm`6Zel2?c~BogKf)mL^xhA zuIlJMA?`$*{|1;Q6D6-gSWW@ZIU;CcU|_o{cOW9Tvk&+aJv$jS)gUjrk+k3oX$lfZ z#q3rCj==D^7&?@{l?yZhRDcIGBgbI;Cb!UI9v96tid%}0ba-vqam9?f{d>{fjkis&^N6dnCVY+I+`=rxQGYW7c#^JHQaFR7CzN z*J*!)pzsO7*lh(Azz}cZxm<6;yZ-*ohv0nbtd)u6Dd3>StVIyn8E8=?7e=!66Aj;O z-~-bGQOH2?7WFY&2w`mfeL~Kh*Mi2PJ03efYoP-WaGwdP9nbi8^5G z6v)(m=WSJSeBU{wbF@`_m{Le@`o=%Cs>EeIl+Uge5JP&In5dM7&Bko&=E`nz(mNaXP4W zl(qZ5>7yM;C$HFJB$**APgrb(4<`|uLY^v&Q48{O)ksWc_@FfcT6fbZ?%JbgaaI8S zu9U!E#+}LL(MWm#ZlyK6dloa2lhn#7)3tx!rE@Lo{n#Vj-${BIf7fPUM59YIgl+-s zRHWW@{GEneY}E6aZA_ivkY|KbS+{3_0>)J5qBKV2=JG;R9NKJ9=Iy+w4|E8~V6r$; z(9eL~Zx)Cz^Xo_c21dH~JCEX+I6iADx;YkEy z0i2WTFrA4r1@Gs)3Y6UA>4Eyd3N%z5_;uOW7FldTiWc@r(`c-5onvb{8JWF4|7%_` z(kLIpdXUA8eFsDYe`Hn%P8UBsKtzZk9^lmVD|)k` zPkKg+t?!2$FQ!$x=LheF2%$+pi%obzc8l&34^Vo-dSle2S^+uBZ{q9xN9CmT(UNQ^ zxeAeiA?9BA!CzDj<7O63^OZ;dEOG~Tp=F3T+%Q<%hgR>at6W-WU;D4OZ2slTVWM@3 zb~^}e-7k8MW_Q%K`nriLluXvaR#VCZ#Ue!%*6zQ8C1}TKKAq5umVLeL9xVgMyCut- z-z-l7(U8^~c_H&Z{UMo|1(>*%E5|Scja$DoV_1~S%(0v*Z%YNdDL+d$u9KcyyMA}G zqk+y) zFm9K@JSX^!4!`#N!0c(hibCTJt>$d}OHh``PC(wq7DZPz|61qS(f3TZp zXJ&~iXWqUq`4NE~)?S?IvPKqOBT9yYG??jjeAt8MXmmRAM9Ji$H9_nWg5EU~NfHD> z)~|T!HgfME903(T~ zHgpj@ehv9_Ca7>D-NMNOvj=OlRP{eLQfd;zA7CwJNUG~eRWWzR)Fe7p zznOpTceCJ~m|$fh)A@IFqV6AuEjylXbJ_vW{A0_wNSp+%mCtxC{JMDDVQI&Nz?*xk zur#1uj|XBx!FN}JBwIS7w_9lG-3$#s&|#KkQCVH2ya6k{>kOqgz&UNqb4{4~W3LjH z>kUxd+4bFt%h0Qip&fsynkw8!J1xFHsKqvPDom@vFWPpkTec@iyCcUSKamRq&Fb17 zPnmzVZm07E2R?P8vr!I4UuHF{tBg73>K})_{MYTr1QJpO5P_MkuBP+raqT# zfCSM*uUUEWJ%GEwCR+OSE(LzyQBF>E`B=c$k{vF`Rl{6nw?EAaef@>TKtK7e*3G7j zZ}yM4g%(nJHiTB?1m8&7nrVu9AB{Moz9Cf^qeILE8WziW^t{M&+&tyFbmYki()P4| zlodOaKD>DMxF@ODi>xw@4JS+Jq>x1w(6V5!hVBF4>zi1NaZ`cM9^JR6n$j}8aXK~P zRNOwP=yGN%j;4Toc1M@{C*brwe5gBbthPSI79-h46CsW@KA*%?e+ImtHlxr&$PS%> z2y640j$5H-`;km!+;NncG9ki~RkK?O#-lQG#d@iFe088DIk6DC=D zBQGrU9CFtJ2Ro&V1JFrW(wo|MC?LtQY`z8|Z8Y+WE9<>@N3x$hDklQ2lXJZWtwzgI zsC;?FMXa$*QL_l%L}3!wCSFO-ln3{OUvL3Hs8H2P5M;kUx0VLCne`U6^t!81V>3*@ zmtysE*I&4Hj;Ou+(868|9c`=zxBHs>?>0))(afA4^qAqu=`7gt!U+>!DSiT5Vx;wnbKAUi=6R)nEerg>Eh~I-j zW=}aJg6{q?JNShgWJiY#A4!M=h^K%B!H&`Fv}+V4Y$orJ!}0GFs%M=mec29^Ww;hV z#9q>lkHG>NAv-v41CI2Sxi`jUBm+*e+6fsx5A~e%Peh=1hqz;iPsa4u%Dj~YT}$WVKV;4m_-E9)z;e4QsqxwmB{J)@`g#!s2UC+B ze=!vn1kO|AM~|X;uT=)0S&A#7;G%!8j_%_;Lx6nsJ8+U7J>PP#LqHsNK;lgUh{EJ- zz5f)@1(Qt=L52Pz0P`Gpuk>a@x#!oA5r|#QRkcXu4%ngN)fEmC)p2T~ZN7D&w!Ib3 z*X`Uwg$OT%Oq@Rv7eH>tfSy;h1p$bVuQad*PvXn~p4|_Y;JR{>CP&sMLweK?U*g~{0gkM823`E%wMc|c$5b^9+TTeTpw!WFnP2E zambt9J*I+u-zz)(~ zcjgz_^5+vji&zzj@8l?rHI@qu|O;$$fZGoak`R@?e^WJDqDHN0n2-yt--|ZJ0)5vCOPWMil8EGSy`__9xo-nKmvAjI>>szAThS;p^QwT4%9A~{fq^n zDum$|bG0U=hjWi`tQ#^=Cw{kj#U#2`mtTY0&MV&?48NnG=K*RNPW1fezrR0{+FQ8| z5(W5DbUa{Z>Y5XzK)Zt()w3Y1rF)1RUS5-TS!1OZ9jUy_=#5`jKcpBKn56=^!#g6M z`eOn-DY_b9#|jHdY?A=hngnBG-|rtCWD^9>mN=pts?*|1@?Oado&@d$)SPJW;$dcl z>1`%L)qq>kkg|a;`32DR=udqkScF_SD|#Sk`8&AF1_GcN91XWJJHK2xUvP@{4h? zJtcWRr)}Sfd5%=xZd@mwmZlKjF(0cDw})yhGw>?C-}B^Jk9#DiBhE`L%EXY_T^T(6 z5(B@?QU~-Ak z0_FmHLJp+;hxw0+fqIkA&o3u3uczT1@LN@57)4QQoZ zjeXfE4yJ4$KO-SIHa)w0!!4Fkt8Rgq?@Y=GdV_sVeDNYpB=xw`f+8s2^OG^35fi^3 zN@l`zULo#3y!Lq$y%9Zex?h5fL z7$T(oXAn2A8r6EeG;k}1Rg@`stnnl{yf7kGr$BREpVJopbtRf&WhJ#1^%Ph@I`*D^ zDGfl%!^G{)rr&7?_&sf08+H*cjxtpkTz}Kq7b>*OWHQgIVD9uZJ8`3?pJlT3MTAN; zU3kUL%^!<9@1$q6hU6qQv#br_Y~4nbBNBpgc|{Rv==a;e}iz5AGg*?LuqRQ3K- zk2#f_XiR|&hQtU@Tz(Pvxd&i}PTLj~Zlubvg0kab>H|Q_$U1(72=DA;y*=_KNL>tm zf1<*{&L(v*ahEN#_-Xx(JI-yXA#w2ynV;zpUokG@??>iS^)W_9yz(;6WGz%hg>?SP zq#4Us*X$vNJ;i2@XiKGUjvX7|%Qno_tbDdDb1F7FwFcr0?WreHqKVyU(~~N+CNkU z$C{eLy>thwWH5Zvsz8apn}RLVm=f2EV4tm^Ge*9xHbzvbBcj}HqyodhnlQFmT8|~d zw^(w|Ou>w$)^Y5lm1^o*Z|iMBfqse59G5e@xT-23UiM&{AO%)=&u8j`EvW;pyj0)4XomCdkdEp)RH#o+`J~ zwX2FBG)UOz9r>hFkRNHP^ZwI$h7Qx!GLNgGPwF8K2(TvFuQ{6?;5K#O64M_bHZ5{21M{WGV|#6E}auSsgd(5yMYf8$PY!yPWd;tGwF$jF@cyduI+BitI>4Vb~X~1umy`q zGx=+TRYKDq49Ss3AXYeb9m$l%v^yq}UYtA<^+|{9ZxsDbY(#JTEPs0GlQ)<1r4-NL zIum+)2xXs;l&w?M63GN@(>CBBeZ8x!?vH`H;pKWR?AsmVv=O*Yu6|#YS7-C`GkXj) zGtJ|wVqJ0w4L38u2Pbah^Pz1m+NiK-oV zc^ftaFz%;Cca2dEW+ZPFbWSA;9x~=Sv)&ushJjgj7qGF@5=dhCP7!T#LvW|*$H+#-b8!C(>tn6 z|AZ6}BQ9k|73@?#DB;?@LstSUUkwpP$TXEWX(v_$=9Qx^Xgk=tmfrUc^J9R{tt{=F z`~4$Sgm73m99>B=f+6W1*MGjmr>BLM2V2SaBdv*-xv4_pA)I+hP80G}ijl6&k9+*s z`jJ1stbuxtl5an80j%tH+XaFOh|H^pf;%v5a*fQ^GD6$){=I0l(G~3&d2>Smni|s1 z%y#7>uEBF6Ss)Bn6o8WnU_w{hsZ7Z0zDxaIU@lz26;)TO;*QMS@QWVy$eg=)I@d*M zFLU$s`VE*P3eJe$3uw&H;XYvlVT8^nfo=*D*T=x zLLSH2td4a?f|XR2+JuWp?DNut;hlWiW;c713?{S+k%NxM!*AFMJwYb)zg%`$7xi@P zOn_21>r1tZN$$y(%57qLgukwPNP5Iu<-|&zdkHNHR)JjfE0&p$R%)IAIamJL)pxi> ze_Q_2idf<5AWOVX)!1w4R8=c*X+<5-IG?0786vo!?Thk}bYLPWx3K}fqI^~!ew6A~ zW7(4DJO;m;wld_XBPK*2=9Sl!7&-L%b;le}m`(B4;JB;_D$~PXI*98_k z3=6%l#~yxYS<_Q#@655M+fpr$JWH25cBqD0F(-&NcAHKVg?|LF8w%#9_xFGE$9hQ?2KTGxt_j4$R=c!Mr zey>MvhOftG^rB*`-sUcR=C1EIGrd$Sz-ePfxOJ<|fMzzstW)0%a!&>BCpWt|t2-kt z@ixdgfFt!UhJQ?i__y0n#*@h2&4Ol8qWfIu5AwI|a-Ss%+CI z%_BFt-|;s~3@BBr^QG=A=vHtK5;F7;ed*>qaCcDIoa*YL z$Klxw`#-!LR^1}bg)!C9_Pj0ob5u8$@7e@=ngu1$C?mi7t$3s@M7i^GgAt(n=Lis+ zM<$*SQ0%Pep4t=${d!qU5OKq}H?&=4rGL7MTA*@o3Hdg{B(d|DUwP311S<#RN!i9! zyWP~{O^gmQ9Q}_UCo!l3ZZaLk`MS7OMhvJuSHlOQlX4MO@-tswxv6r$CGYOY$BW=} z#n|Roh6V9q?v)`#%JjRe#cnjact=+S#Q^p5&ntr9|FH@xXs?Y-p?wjAV)C36yhp6m z1k%r_8e~3EN2jk!g0L`qNCBqvh@6)+k;S}US^05N%GVc3vf6q#mLz)>HP1o|Qek9Gpf1)}y03ugi4o!z|p+MjRX_kG@Qdm1F-V z=Z*lIo=WUr0xb0G%dc-3*aBts!CZvf6Yy}Gm3zzdX!n=5 zQLTQFs3w-|CO@zH#^2-9%7nmjSvykZI4}1*U)EJ;D?vm?6Amr%HDF>*hF?gITEP&h zhO^1esYWbYm__b-LXWWM-&}3OsRUV1_xv8aTpd4ye)Do-c-()?BnQ$-c2(Xbv-Wj@-wI|S^xJ%x@*o7m_{5-BYFq|cs{DsiZs?H(F zsRp)%LQ|p&;&iK7;Za`+=Z&1iX8MP%zAnbmq7;I2C$6duh@O{CXv>2XnQTvjERbkC zKkqZRzi>Qpi)zNEhu{C_!2m;#h;Zg?pr5{BUQ5TZ{X7?D2XdTG6#uVI74XY|R#oV5 z`>#>G((*a}V=7%SH(cYOxRxb=l?;T0R7z}A>_jITTDv>Y4SD}@!%SFa(z*Q<$!G2| zBBif~;3sg4tFZXL{#@qs!WzEux7z9E=eC;<9~YKx?~y7DoP$!}o~Du=6=&lGzKv$% z32w^Z0yZU}i*c+Qeg>1)o+1OeJmiMgz0;}g_Y4H=CEI%?@|UjX>k@XzHe7o>WJGQA z=(plVdvLyHW&Lx+(uu=JE3f~4{H^=zbs(Cp{D!0f=ZPWz^BSbFnAsc3@tOqW2eUuY z5he(?hKQp+k)zV%kKOh3V9V?Nly~-SO)8mRr9!{dHJ9^&Q|BY0A0|=x3>$NWYvvr^ z%d{DFIgH=k2dbffe8qo`VX#`Eg5Qa$PgxAuU@BuaDXRN21YGzq58Uo0a@;2E0EKT8 zR-ZET@LvNADjeDrOH5si@YLN+&Niv@L8PSP?WZ z`vKpRW?Zk|#NT}8YOH<0V*Wv-u^VmM2Erk54JF2Z?7kk4xeV7Z1bzBA(?x#u(x3wEFlhmvSScY|4;Z*ay{+VUeu@L7Rd(+b}G#vjYYRO zm3#Iys@cRJq+mhk!El@4M-$T5R44mTfb~}T|I_?FA-#vl%kZs64!@U{J;p!tQ$n!^ zfdK5^OJ&_8wNvMd@su&IfOeW`2j@38P`&wa9-%%Ez47W&NTU|)OaECxm-FV1z$mN8 zpxo9DPQ=gXUI|%mOnd)!@LL!F|D3%H|JR?e3W9kY8fAc1&GmjsB}k_u@fSP(3>he2HIx+t{cv!XDM@=35Dz}pI`3{%<@#1_R@CCq=scDN(12>pBk&D|UnNWKC zu2)>TZhT#BE={~9BQ5V0Zo&6o11#V*DN$AlI?zYlHt#d@bY>WDE+)Gar=+bn}FBMT&|1(nP4f|a`M>-xVC zHcbk+pAE^@Ve;CdS36DC3P8COuO55x9)hM?iggeD)~ycRYaSZOAj)y{C=j(fyV3pS zLQzBT!{wO+u$`I`+(RyZJX+z^qTv-f8Ni>axi7nreUBKH`RjF&kn64b_FUzSaUEi2 zznQiy*Sec4&5YB5p&FX=C&ON`_}gr6Z}hNjCG9*l0Q@TZd4=pFgwnr?A^-C*9DiKz ze=yS;shdU&TT#UnR54(V@xzGyC4Cx2iSwdFMVT;Nij}n3TzGbXP@gO z$2^aZ3tJp0an|1i#Q4h9z1+KOIo?~QvD~|?FT$k$Vp#X8z#=kH8uhLAy7Hy#^eY5h zJ9Zmwx{&1gLHF@flgef)?2Pkc4*jZzEKRD8_sw4{jJ|+MlYw8r=ikf8m-obL%N1VA zmwn7|;U;v*)be~&#v3u%#6l*8?e}ZQ%Y#-DfU+X=mq&FKXWj=7RX#qX;v`P2Oj?Z=tI_D7F1Ygl4fNuLU!JU`4ORiI5u>d$UVM4>lb~#^gu&R;>*4M zMr7BCFz_O!II8uxBL(?r)Yk32frEA`F-xMz$SRFL&|>e@J_=9Nt_GT*f^7 zQ~i`SDdUnf9XlOt+hdpFhqqhi{p{&+MK9{gp7p)9uCgD!WJ22S`00D89bX0pYBj%| zUMS2uuFO*^z_@@K&{}wOd-lmBkhh38R(M``h7gS-O2!N;jA5aBEp5kUv$cN?Pu>h& zUaBl(vdysMU9D1O6ub|>n=#B#EH}IKCK2gNzHE_}cn0OlZ~9(h3~eyo^q}A4HaJV$ zb5J<#?8rzI$)cI#9;+GMxj{jcSS8YUnnJb>>lXBsep35%zvI~UUB-!nMW9KG=dB)j zBb0{?&FD&QKQalB*4@s9y+mk7sv_i$Uy^znABhLbqX;bhA}jG~25(F(ot-L@aK{;= z2#k&MO%IBFW26}3TB-gJh4u#SU;8SDiVg{#@p+ap#=Nt_pq-PA=k?oS;){=z{bLT} zM_yBg6Zg0KJ3O&h4cP--Jno}>+l5X<%iS`5xH+qy364(Z^tvM4{4 z3%e9(3OXl0l?$^LJ!C($mvF9gwLkOQ_3Pe;3%}g#gfbllCn`Q?Kl-ts+Xz}`l}Sp) z+ou>tVMkGPE+lH?POmo;6;5O|;MM2iWDQln4Nq5(R#H_~hU--?GUJdavN0>gCyDZX zK3Ij9G1tjc#P_UD#r!6n!`8e@{cJ3&$k6n3Pwn1pD1b_pN89xN-KZ)_NR%O7%g%D5|rBvw2(d z*Gs8if!Q^zaFoX_%HG*P>$;=dG*Vw+lyrY*KoNbHdo!?|Y8n4N9BVYl&vOYqr8S&I z{6KUw6p{8n)y#?w{Z7kVc{$cnvR{KVo?DCUG(y5+Do zqg7=tNsQtr@U#;(`YLlS6Vsbpx-dB`u8x!SXU_{B_DFNxju9D_{NWU}@_;SE_-=HS zPC@n{{OIhmt=&S|p3+Ept@PM)7@e2&vgGyUt(&jBW7m27&J^R&)H8V%nn-QtykM27 zLW~jX)cs%fE_P34a&CKO0tlRwf}Y-M?RR3#CZ&ZKOKE)-Hj@qNWjcARi7~H&Tc5&5 zC@njC7yE|9cMYXZM&5-sW*)grF8SEQL+y{*-I4a5jwl}Zy5>F);4(1ZX1NM){%5oU zjd)wWtSY7ilfXRdZ!Xp=Fv}z{Jp6_ImW4a%9n!G$ z&k5&9>t&P_E8?esOgkCv*2w&7+z4p*AVeD)Se1>TPx0BD>-Z{849#Llx&u>%3NIk5 z^@y3z#r;UP)`T7ASG8mjPD*S1+T;2GDDyv)Iw$3L5|vm}pUZs+);N7Lp%P5g{KleY zoxPTNh?|sVoQG%5R#XuHGB&gWla;Wb7#&*E`^WcCMls*|CF%1Vks%HF@@)S7MT`_ zxC)F`ssTOH{?~2+xRG=bgJ`nCNO2ZTLH+b&GLDln1C@@Q4+5^&uD!gb1eey$X{DN-XlK$Aa~kd7e7Q5$C>|#4EUBTW+h;C%hxC z5$(^nW99fK6%d|}kNGVOyEW5HLN0_}o(3)zs%@>EgmJJWDNFn#l;McxZNe6Q-5f^F zt-sfZQS<(fYYR4j>!T#z);4Wp3ogX?7x&#Uw&!3f*~@*CD4S8;R+A$}>J&@#ws@0v{8$YVyNxgFTEw-y-3?_GN4Yb+#6aHCSH4gi z?lePtZ-RL!X1C$e6l(-Ffov9;qX>4MUYPi^&oV~RLv;}5egEv$%PqGm<2$E#I(t|R>^&hSMcMnl!1m9i+JwC?(Kx9;P#m}Z z_5vmG){Lv-mxdcK#moV~cQm%aaW=>{--o&<^W-TV?>kuEpkFlVrTXDSBG#0gV-h`P zFnRLqRP@wk@N(FvK2l zqB>^Fv6ONE*!F8ne6;pm2zZkp_mDD1Dh~IeR@K^fUxgTZnx2DwC&`4Cz$Pd9;(Pl# z1xWuuh5(f;-b8}_#r&XRA+xgl1}}2;X98aJkItA{g-gR$eCoh~RZfD??4JCL8Q)3K zs->?{MtxS3(I1?uOgX1ZE;4;Ct@g+j_*UdUcJ{8iwQV) z%5Ai(bgu;y-Vb8jS_T*VG+I#XU??woZ&IAuWj8KS%vBWi+Y0aO;%>i71waqZ{_%}z z`pGZ_Kc~MTdn*$>3~UT37jYDqD5pQEl~L^#?k`ekd??Pgml%-diE04z~TSoL-l4F72F2! znMQu)0K3lRF3#J5ihG6UZu}XlJurmg7${#Ry~hEOqEN0Cd%rdzuP#lFxnrsvOWwhn zCcAo^!;I`aZ*b*(e4=3UK$~~){UE^toBgp;ffW$jhE9oAf-*sPEuz*Z2R}(x&lEJN zs`vsXKYQ@sr{`=EREs!Y4emR9gyP@@eH`U}+lS=t{Q{z&AyBMMepf#@Jq1fj=`H_} zBJ$qKwpPZXNV|;v%|1{?b3P>Ugc~6FiH^kF7wMGo_hW$b5o*5FcE<0dS;DG)QW5fq z)rS3jFR%CapnIC50ka!)-{pl$t_51nV*LCv?9UX9P}U*YCR0{ZSvGO@zH42_3yiM= zTOS2S?kn)>R*PjRiu2}#_S_@k4j&c)u~z?5a6D`@Os9sWwz(isL|^BLuGyz*4) zGOB%=ev4sUh6wmk{s)ZsPqY+3C&w@$P%7$*mEyEUL!Wde%ThoqzaA+%8fgEv7F2x&`}q6?!z=|7n+0UeCO zcTf(}TRjPSSFC#aF-4U@hGdKM38e>=cjf@l?{IRm&p&%R%u1!g%*u~t{|FX)ALh2b zU{oT^l$Xl4wpvnjd`Dh>9VS35eRFYiL=xI7w*S6YTsfC5{so8q=XIbG(7!OY|IEt& zhS>gRGX=l=S1t7aanJnkO6Y&K6`;Puiunr=_|Kkr#RZ)F{~z&x%3=R?^8DXNvDTSv z`a?QYb^}N`1wW(H`&7{Nat<6Y0V=Q)O&y>=EpL z{*?9hl@@6NbPf6%)XDZs^Xl(HoY6Me>lce<~7y2dv1jnGKs~qI2&>j8vA8T9oq;KMhuF(Da5*l>S zhxTEa|M!hxexP&P%8^>r+h=Tlec_9{I*{GL5@5HWpvE=ojTjQCz=&lF$R>@=YJzaB zX7zvaUF{GuiwYVRMZkAr>+-zrGEdrn!a6%*m@Ln7R^sD!Vrl!nYYH{qVC%+9%QdUtflB+vIlNd|GZI9#XF051#fU~lq5A8Wu z)14mP_kZ>ctHh3hDamA%pj-=c0S1hi>n(|(soA@75Yqm|cl!XlXIKv;>c zHPQujeF9|DM8rE`muEgPHK4Z&{$yto-$FK`ztB)6Ut6fNmAbxz`FD~sCilie4l?Quq1!_*VrrGj;#`_f=sIbb(WNN^ONqEs|kFx z(p22WoKgv{+^j%~)8Yvl@{BKM$_7^hoy-HlmT_q=;GphCc>!!HCY~>Up-ohc--Q5$ zPD7)|MMkTTQ_wfa;t24&TUbat0cx-*alWT@dUmq@+vNE>?1YInvu3O848UBET zH++6^SQk}W2SA4HvEBI~N=Ij4SncfNmi6&r&+9jqOR;hgRO8r=Z(;*>QfS8{5_@E< zz`0--gcALdKSklkG z)Si4oa=}qDl~I)$?QhJBY-Q_v^P2qxpnV!#UFYfhNiJqEJZ%an#jjTlqJaE)Hd5lm zI>oR4HF{r7SBj83B-Fe03)0#{HY5w7ZjkHo)>5L$3%|1kT2;~c;thSPv?aU;8$5@g zzf@xc^@HJNhR2uSUHMSr3*me)4H;AjSsLgfR*@m$brbTWC@}n1wAn$ZKxKL=^=8)Z z^3-Ia1$6WhehA32IicRbS!xPs)$PY08#-9@WkaUlw7y66Ph8uWwg9v9Iq4I(m{Z`# zo9$rEkkW}u&f63jb}o#1XEtdTC2qNnQPEa=KLXMFS^ukb)gu(tsEM$VkU<_kAR8?l zSqMn#B$PiWQ0%l z*O$R8SX2{T%~31^dR*CWK}W0Md@!s!Zi4x9i(YXmf*ll{5Mo0SxT_SXHss+CA_m;}{~ zP|?xACcmr6VsEAIsx#YfDoSUc)?4d&zOWn1*%8Jl&}VMVcQ<9GvPa^SV_Xf32x?;R z{S_K!GGl4apl6tW&N;-g5u*^W3E1CdcEOz` zI7IuP9at3@l~IAY-SLo)NwBgkC*}=Y@tysS8~`n{12WZrA*QmxSBh(lLUksYWd(os z7Exu_S=E2k_lT7-^S?u$9Y)$DhOVt>S-epA%lzTRwzy5c7|}Hy&uF@wOob>KW<+Xm z@%;#b92=l}K$!R*=MJ3$MZfXgOt5Ms0D0Kj0J1fwy`J;{m?>r1wBFU6H=Tkf(0%43 z{h-eU1O^TjW0uUMJ{XJ7j(3(mzBQ-kLWI!bCV9-wl7;>eKUv8>NIRE%gOp{#ikl(f zJ#40Q(lh6tV8kF`#9QQNZudQLHvpu+LO2XUDs$M4>0t&OfhLsKRoLArd_V^O~g9i_1J*2a|$I z@}@IhW$omH4atcB(1uIzA=|PGXxdO}w@Ue38dZr2^;>jbFZ?FIuFQKiFaBPF*;xcZ zjx*SpW)`wlgB0_y=j2jEEeExB`~6eR3qYH!F4rf~^C4nJh%NzUHDJ0SkhIHt3w|b? zm)RNkyp@2)c<1_cI)UD=wcy1E6qj<;C}NZEO%cxXE?XqDGQ}_t%bgc{FwnryM)8~a zl<|2X(}$#4dQmJrs+%u>^7uKRcJ^4GWQh6#0f3*+i|@W=9!gVUuu?@Tq6m*WxVxWK zQS-R(@3JGX&Vbv-3NT`HeeeZtCZfiTpxL^95Qg<>M#wyJR|sf_l(TUezAELii(|7x zbuK7)`74t$N-uMq8aEC{-ew}mq<^!x{z4q|qa1z|99(Sz4_BmR6vrpuL&o6Jh>d=r z=UFENxlVRT#Lxn3$euDPI{+Q1`54xI-69|S%sUvPyh7h zWA{Cf%pf(r8F!ASB@w5n<3*wk6_lWW>#xkON=#bQ;}tV9LR-qXCX_j5XGQLIiL{s^ zXnjK z{|9I-1Z7dyRQ?HUq0`Y^K(aQXi&9i&><`>{q>e4ZSa>&781Quq<NnMh%i|CdY zzWALNP}8@RUagWKZq$B$6aEatRr9Qa9S-9jVdLLRd5kqgZ=4{*(mH;nI1XjHVik$%dD)E?DbxsBBqUtY1mtiUC`<7CZZ_R zBtf1>Q3yv`FQhd_ZTb7{Kez#pX2SM5K|9oO-vNVcO!^(on+wemVTN% zj0Pyf!i}l#-*UNJsm7Ae@J(s;1Sd%~DGh}~B(mwoZf_OR@$lc>}OJ)l`5UoG0{^7q8qcQ%CayK;ANGO;tm&}PWgxbzZs zH%!w8Nf(WG4~b4^<&uz#)dT&Ol~gTvh84`eb1Y{!DCMwAV6(sZ+jRdc29E}4?SH4Y zS3x^eB>lg5`|dz0|G)1u^N>+QhwSa(C}lLvNC;VR>|NHeH`#?mAv?rT$lhe{ zy=8Bn&(-gDKhN*}-uK_nAN`keu5(@2=ks~LU+>rW4?y5wRX#KdgsS=f%K-*$f!u#z zLI3MVetRP;V`3CITw1Yw67WUU{A2V}o}FLcLRE;v*PIp0no-X9ma9wpk9pmw|M9)n ztlhO^&~pA;dM?$5VrTyLfO*%ib{zHTxJh@@odDgMar$z7g!`|9Wv#UCFx;~-K=f$7 zeUn9s_#Z&BFwhduaRW7*v>l|+vi$w|N#kMGYY?2H#Pmgr!+}10s(1M0%U3LYIxisC z{m(xyZebh)&M}ZCFAUqaETRc&ToD==%SKA9m-gkw zSeXwMei#K`_?LqtFXDCTGP>UycgtEl)whIvjkqm}bJ-|$?bb>C?yZ7~7x_$1>7cmb zw6luYd90~PnXdR);D5QLbJ3Lx9m(IpG2AG90W76#z_u@(3l4?QFB+KvkZ>?BjbTzn zVGRV>dU^p-%Yz@!K@C@~4}vMIM?f7b^KH<;UFRN0UD<57#7I@nEpV{IZIZ2ugZ}#A z6)XBhdM;1a)+P&@g}2Os?tC3IC-G4)gND`%>&fEZiUG5@1CV<=V!y_~h;F~bX$K`+ zsIb6Y!4WuID!L}IoNeWOetJ~S%paSv-Ce>827>>Amf7I4CA2#NBgX<9imyPXINWe^ zu7OHTh(e*z36eHosz3z&UZfZt3()|E<=3c!k}h+C5o^4|nf%(k~;NYnTK zeD%lhh{IGCT}qD1E08UmriQaE+B6vTLbhw^;zmLSWXEy!*11Oyv1C>#!xy=G+`3gZFFfN-S(e)ay5=s1j{Fb!m@M0k9n0 z_uLq(q`m=ZU_H6!sVaTd7oeD;9wdvDUa5JM1gIMM&M3EmZ)$vLtLWM$l)=0@YXdTv zpOSYUICI^^|6f*fWU0$B2cKdu3S$NYj2m^t{H6U0x;{vA7;`U0q7ps4*b&^AQNsl` zU1jA7FE6;KP}0n=SI-bo2$qgRc;mxJ#esFb7!P24#rrYFvFRl7J9ygG62J;6C}?i- zeE%Ct2&h{CM;EAMpMi*AL}NX$#O7UTt~BxIhaE|*Elin1hwrAV>j0s?>`@I1G`{v#^faZ9P$S@C3y}c$?K^@cRqqpuL8An z>8&11|2(qZX*B71(@**LB+qqPzc|Vfw@>eb7|ddWCIb+z^OGRHC7RsG@C(R4FLbYk zFAaW8Po)6Qz(_;REko;p{BWMfRCXqu4OA#RhjFqUvzn+ z{Gsa@)?>x$AT*WHtUnJepBLB2fJtfDPCB1v2RToc=1#F5iOcQ6vv@weMlQu}&D$p| zY6qPDNv0Ru3AIDJ!7JakAvdk{(Qn_ns^7)%s9$IO@`k0q6F8hg=ezFbv*X<|SK#b& z&BKPmz)frloZOsfZQ@ZGOh7l!2r$5x&lOv*%8e#XoFlakOHpCAg9 zxN+;sIy{dT3aYnTL+wsqE8`__J5uHv)?y{5{itR#+n6%i9QqVQ6pSpp;2avTwj-gG;A*3+y63yv}b}Mu6r=4b~-P~deWPH)H2Kui)CMcaPv8o7? z8JEeoeO*JcczB1((%ZcYpq05m@;Z%Li+mSGzCQH;_($tIej4Pjcj<&uFqOscUu)fg zl2|XK++#5?)ezXm4g82wD_i&ljw9!?bu@|B3A=K5=`u>T;sV%9+rO&6vmIBtG5%f8 zB*4**%;Mvq@}`Q2J3x`f0Io4j27sM|!`TSEhI0r3Xudj&Y29MKzBr~(UZ=v9YO>1l zd8UM3n`JQ};N2228uDrb5$jq?T6}DnoARFE%^ekU2c9w+7AC5&C&mn*7Jj94EZXz5 zDpqVYuf$5+Vij~9W$5O!AFdy^xc8Hd*&NB6&7XUtddx1Cydb_#nVsaa^hLpfpw(IjnGJ?xbQ*dww` zc5nxS*A$YvRxkDRKY;`|<(*!UTTk%bDd{x2?njQxDLm631f_*owC6zA1>F1u&L_v<-X@$C{%{K_Jl^?rF$j6d zN4H{o=V9}^fTgPC?sd6+l+md#bpZT05r*Z^>WoD$Hypz0Fpb?Gycg(9wHpf2A2{$g$$ln zN|QXwR&4=K|MYWLah5dh<<yXM4fToa>@=l?rm*?j$f9p`g_WSy2x?9lE3Hr z?&WZiv9caP@qSC!wiE~O5K^+uS;1flb-%dXSnb{+3nS~&Nv(Yt%3T0CejY9ZK)Z4{#-TqksY zp9)9$D#f)1-`E<^T~`7d;3QV`geYgj8&nU#re3|>2Hna)RVJHhx@*owyCb1#_|A`` z_Pu%_dQk}0CfMUYx?=+M$6l(#T>CLqBUnA=PJ#=qHG<#dL*xsYx|bFi!JZs_5^=V8 zx+9}FYb3PcABkr2NV?HhWPR>kY4|Svf~fq>94PF@krP@^0CIFX^}}(#De9*$fgY36 ze%J{qh)!ht&ZSL0m~{3+hu@toFXVVtIzQ2pCL(yp*uS>cZz!_mpHJC92q-*_EuUi& zY;+^%wY&|oAp7{_zyvwC9kS8G@68V5*YtYH(1O??5D?81`5C`cjAk0y*G`1#)M zlV~$bFT=puyniZ&ag{5WvQ8YvE4%QjKZoLh0_P9`Mud0Xl#FisS(nSoKz{PKcK?H` zQOa|c0DK|)uq{tM#)8ZpA~3;qo!9y4Av=f3iBAyo!jpBXKZ^i#rizU`;FpHOM1Pg| zV_?qp9?>CSF|m%_m9b&9*Vn=$UM6NBpFV%?Eqc-H4QA0Wck-~vL;UI)i+FmMXObP=ZZJ{ngKCT?hzJQUJv{C3RQJR2 zn@QVFFsKxLgz{(3Nd*`mvaXFW>KZx4djZA1`nD?DE23oblrkd7=ctdk0RNE;z{IK9 zcHKbNxF3|CaL3Ya_1RkY(!m}R(?rnHk^%NicYebkh_m3bxl7Xq09 z3LT4+6;rYnxkz)#TQrrxDV~0nl_~xtvTN&&kdo|UF|JVd7mXK8+YMgP(TSucod-cH zL2dd&=Cm5x#|nT!sH}UdnBnbI@ooBT`Gva1utRSXdYR`9(LgH0tFis{F_W%%wYg6PhN{ z>dK*}HF)_E?OVmI6_9;0JN3qtut_-I^^B(l%QT@$jhOK|l#s|SQeVyPF` z>)H^#>!#tQDr#Vr6)aH+S;eRA%9*6bwzvpIh+AQ&ubSM>Ym19$KWYw(@W65W1q!;V zxUIa1b~XT~7y6#7**$@a_F1n z=&f#_R#gV1i1@`Uu^qq`rSNpve^Df6I{uEVX!p;55TkqVGZ(10H=b4DU;QA>((`0P z&?MZ!1YFsy#NL(F-(SoQ%2{%pE6R6R8v^dJ%{wYW873SwvOP0yYQ=_pEU5XffU>{9V0!m z3SfzuUi7m=&KU~R=Udw?2d{pA9+m_LYpUk~f4xBkYScu0Z}TubufcVraxtSS;75o^ z^wcjuPg3^h%{NHpE|ESuT+#xLA0n%}O--(uWK8^1{>_X$HiQ%uwB(D?Rgr{{cV59gv!V&*+&Ir^Pv1F1Vbr4dcyKHMx6 z&XZM~dt$i^i(81M3yD?2?-Wzg8Mk?W)J{VAr0^%gBfHP8aO|%k6~mO;>Nh zJBVqQ}xm4kyzramTyWbCaVBsE$;%q z`LN2%i&Y*+8cxIF!s8E=EBSZA*bE{_VGQtFg!CsWj{_T7PD6zFi;*%YLyiaG_;Mb> z9GX9h35~eX{gx(7S$J?UA=z2~LRcd1N+cWo8Ves2;t!(JkxN{eiLd;pG<+T#-gn%} zc-fysW0I84cpUkrL}LP>?1{|C%F?l4kGcz25L&`*COW9HrHEcW6`-)~h(1YHQYm&c z4{!gqN!)3xZAew2rGn;YRs8}Gpq`WngN@YLBvbpAs!yw3}k-rOM}ClYek1aIsB+g`MF|BH8k#b!Y&rnmUk91q$f? z6xIo+xo_~aelJG8$(emWhkxooKeq(#r~pDDxUbje->!`hC8W7jr0qo33MhV2ZMod zAtQ3T3jSY1ZK#=@!*xumc)7)vx5NIK6FFZIUtP*hgLKac0j(Q9dUYj1jWCMj-wH7> z7JmyttPKIAdo?KE8z0GvGMV)X8j;AODG5?TEsjV3^Z))oI2I^#!3g{xNXNfs=KtvI z|Gf+ScYyxyRQ~VR|Ns8TJ$x=S71u+D&Dskuk5WCXM386|EVxU2n6Z{{#J~`Pri16wWjb zoV2J}*1`WbJJ|*%NR3=i#G9#3if>QnfO)F~h^PfE*7f~)(3Uv+5|D?h-Qz_GEZTyB z`j$##{do#NUSw{R8!TWQdC`*cIoL@3q69`vRW zYMl&T4O1x(5)r?!hQI_SZd>8ar+;1|U!vZFXrNiRsjvX0d@p{y*)mq8ZJ6i|fRXX^ z^W9HN?vy5E(<9)xo5>{Ryp0BiAqgf0sQ>=dpHd}=EkM2E7`V5_QMqc;M;u8Bm|?NS z6yrWmrjgXrsP^I8hFI@~nfiS(Xb77D_GJ04Tg=Y~3L=N3<-c zY?KD%kY$_pcX#%Wz%O?KhP4&e5$neoCd6M~F9NRW=pV_|7Z2pFrAz{rtV}7ZnDowe#_M#o6EX z!6*ru`vRxk@)FBS&5TWd7G*AmfiWc2>M6(uQP1x0kmqhJVa@&LV{ILSM($s|_HM=St&nPXTL6r< z-1TK=%CgghtJwj73r7z?;oo=$4Do~DLZ~i)8m^C&T9hc6_|ljf^hWVkoFA|9DMG$t z`)44E_cbumcUMZfv0VZN=EG(N*v;>o(#~r|O(Unxj5`42L+?`>mb`o*A-o^uc)Atg z4FVK}t&@moivIxq#%M8W4lE#>z1E>d08}kuK|V)+IDROL%tZOmtvj~sBW2^@;cQen zEWc>-_1S{Zx-G@^)4zD{c~dn22#Q;}0baywY6l>ZZ)noy27uUXD238a1Bl5?ViJ%L z9EoXe3$dAq@qbfgmv3})-(8vpxa*ym2*@lP@1|;rNzGb4fO{=Yd>Za_v@y29eVXap z>>dD^t@cO(GbJq>5GA@X@79=4A5soTOiQ$K*64DO}kR7x@Z+dcqCl-LX zRxBX4oxRQrAe$qezJ4XOYchkGfJFc-{Z3L-8TO-CXrN#r37dr*_95>tA6OmY;yP{* zk?o-r5{)JFAK}HgS0n!ShsVf2sb^K>uL7{V7^^B8fecMRe9^ARaR;mv$PNzRx|IOH zxM}Q0sKE&5sLo=??SHUMaTEFGjM$V+2XepXoe}mv_i#5lh+;Q^1_&Vo9rmaW01G}Z z_G9!9^C=|DxG$R(jEaufKAH`oQY%4f!>S?y#59=&CtD6BeANta{FjT@hiF)SBauPx zegcroqUR$l!^lg_}3;4vpww<+)k<&^nvb+0Ky5vmXM>Q5eMKaN6+Z*v93OU_6Km%bn(bU znf+2u@L;A5;W@0J{(CRfHuIl8F<^5Z1HNI_{H@aC-Sxz!5doKqe-I1KM)I2ALiyhe zG%Tn0r4d>n(#pKX4$zZqdJu3q483Z%9Bb-4j zU%(d;ARK@&$-DbeIK#fc#$QhtKD$4LR+G5RkHcn{$S$w+`1age;@jHnrj!`GfMQ%E zv+ehF;gj}C*56d3-pIE;Lam2hf`^1uh`>U(NU`*^s~_6g9-}M?dqhk+iB-$roNzo8 zP9)AuL|#OSvR)CwJ`Av0&dVzSb9uU1CjeJ{rwI~j9Q+C7n}nuhC}qgjetlxzfYrK> zI2+K7BLDjt#i&^)Jj=(lzcD`A7!yrsV1;^;Nk&D9Tw(0BAJ8%L4|yrH7~XCgqUky$ z&A-x&#}ka20}P;fAcGF$uA)g0+xNF4YzNT;w%;Jzy#@h2TyBGfp}}WP!#9j|E7Cm- zieC8tZj!HvB-a$318Q*rlKG)&0_}c%3gy`G#=m!gR`0DbBvjmq`_Wb8` z`M2*q?y4{2?4SW`2vm~w;VdqN$OZV*DwQb%_*)e>UP*BLN3}yn?@yb0>W`w@Z$$jZ zIC7QrA4V8~V-A)&7lX8g-C=#DIA^>zRJ6~uY(&?4je@+F<^-@jA1LH_Jj-F|6X44C+5WXFZ!w$fLCrJLV6h%*R1KAriMY$3E=B>XpJoJekn^(sXX(9rU8nq$&z zt?Q?yC*z{8l7=YPAHZ7B(X}j>p2(4K1ty~^g6D1DPIEN&x*oEGt;Xxr*XOvpxnQ{CjS zjHY-{Im`mj569xe2BTxMD2tGEG--Iy9_%N3H0l-C>I)rBg;}1r%y5mxbZ@L8Jc@iF z%y1RdIm1QAp7;${i%h)26X$akl-pv|G3_`SYIxzEQ<88UAPaecylS-IQc*CxQifyi zKSz~1Hw0-ZWo4ymAxc&F8)GAxlAq+4k?cAwgE9DOqLb3|2>}L&4Bb6cQDB zD}?piAcwgXr|nGt^oRY4;_)N^3bNdmiF~l2oradXX=SROXC_Ap-A*7Du>p#6AguSF z&R?xk?Bi@yUNqS+#C|-H5R@LFy>R@l8PysZuf+-cBkb8nuna7G;1-({V&@%QOXONp z0^KZ;LH2u#iq`^{hs8HJrJ^jPU(B;5#peI2gJlO=q+*?M=_BYjf zxSLz_D0lccQjx+H1@&22Bl2P_2o-N@r$Ese`g**Xwax7a?8U1ywC_a5Y!?*%B&Ov*>4X(X48Gm@RrcpCd7j`zBuUiI zL&vr&JDQ7Os|}~qcPLF2Tq>VVyJR7%fm<}(p}h@}7lNK|5a9JdE55w7P&>*c^Z_9Jv1i zUtpvRLw^)SfUFv_O?cBDSFvUItqjbj8XY)BQa+oB0l|kzmIbNEeh9TqxBJ%$|3{k7 ztXVDVb^Glhzc*6rr+p9Bf1B=Ar34KEFRyV(kzcPn5DqtM7p#6DHTZR-#0Hp7_MAed zORma}=2j;{SoBR(=cBikHfss__YNwn6l)KwpVx6GE0u;j-r-BT-MY<4+!lI#Sc8%u zZmf8ie?Q`DZfc+yJH838NX@2mfp^X0TNOu$GG`DQee!Ut2mCZ7zJKiC^`QSiB?XF~ zDTtVv+(ch00xBHm-RC03XYM^7sK^99Jj;op$EEJmb44}_?+x}{?IZZDFPRV(>6M9( z1hf~~utbGW6@cQ0gIK%ihZ27!@K96kQ+9NbF>A1z5lJ@zRUTVb0mqF@%xe3aTp>%7 zaO1+G#s~qrP=#v&ucyc?NDKnncMzdVcfxJoh z(qt@)gz{w2RZ2%ZlknMq8-kxk?Be`^gjxr$I4i4yv=C5BP}2Y7jvUsDjP;7;1|a1V zlSg(|Q}(d&9iI%$gMJq=0O@~n_nt9>%zj(E&3@tIXZN&$P2+Dn-{RJk2ZpH+iHsZs z02%Xe?SLZtte;Q3d^=u@_TUMF2s%=?7%=;boc@WL7`@sopf-ZMb%-Jo#ONtLkPWX* zpQ+lzuF(tQ(6c1&_la<#W3Xp=4wd`DX{cey7w(tfC+%@Tz?gEXG_h$}TjsP-NFFRb zw(!W-!!faG4z!Km7{m+7qM#$`W1x?#GN^*-77W3~VkW~#jKlJ>i2Us+TgTr|4BQCA46G?l*+i$4xbqG?W z69|MN$V)49K+QDNzvnwZu}pXh>hbVnn>Ix-*vlZR1P0aX_$19%Derl^`Fw4o>=Xjy zx$B?a{Q|FzHIs8yM@`F$vu@uhcy#NF1dUQ@PG-QAhO_m=I|rFa!rs`l)cma|3(qPu z6t#Tdp@wsK{7osKed^Q>4D46g7i83CK`6hP2flYY_vWH?`VjHPEHIUQiM(1G!vvac zU{>+Yq4;*gZ^6vT1C1n}6A9xV5j{fMqOSU#gr>K16huGh1s zTJ+4xjuFreoIo3?;SujBKWV=!=+tr}p#p$>zqn{fPIkANa{D>Nr?Vr9x2J%AaGBR6 zG{MX1s?zVSWs)b@MJIf@DBqg~C0|be!~7VM#Y*SR&#Bb=_g$%D2>?>lDlgeleDlq< z-Vw6`uRjoQ@-J^m0;qKc?#Y|KlxgrZggSpUN6q&I)2AkC`L#pIQ5#^O21w`k6kAhJ zCBLZkPzzpipo8NkMk|vS<>)-|?|+ct1}*U002;DYM=0;E?hP6`Lv&~;+7mKDe#sLp z`>A(O9~}k}ZpNVY4UB_6=Ln|B zB@$CUxCl)-vHdRvRjuJnM00M353?0S2|!!^9pXce{h~3nnuSQ>P~%+%z=H`Uufu7l z0!gqmfU(deUPHCcM z=^oMHw<8B!0qimCCHR``^lS$(riYFIa$vl6+8cGGW#~B%k-8674KGH*WA=_6nn4Uu z-ET032~XI8cn^A6I}j!0NKIm02t<))nU8+0-VPo&RyBrVMMn-9Y^!^$LA6>w&W}a? z-kGL<&G+u0U9hY4f^Nom#bLj6Q=5$Bl^8bXi z1AJ{EK9*8)kT+CjcesH0EtN62ah0W?ChZS!Vv;%pxoOQa`dOukPm`e)~5*5FF%q9u$bJ>I0V~^wI zPy2L5&t)cohttUfXeqhtnx(w~Ahl1YpHbEKqhh6)W_D2;Ue7ZOTBEV>MiedSKv-*$s6GkHN z$Iyf_i?0FQ)0s)!L4e2xnC?Eq9cXi!bX(>7PC#L_Fz;c%L1E;b?*1mz=7x;w>jIyh z4t2W6`z5R`|B2v$B_F8YpQj^u+(|5g@Ec>ZM0!Y$e|P?7ht!M|gWq7z@;Osln*#I{ zAv?fi!UV(exBkf2fF`bh4gI5B=Tk%llyq1`<3LWSoaLY3X%cQuayc%k<6qH%8MR<6H9XMAJ@netPs;Lb(nJR}^9UZMjI&ka|Mwki1D8(j-0u(;udav;IL zDI67~eYmfU`hfvhlv2i5GnZdhVIB<>^Pidd#EJ z9n6{k>ZPT1iMqLZK)kHyq&r&*zwSV&!lxzPS&6$e;J`Lgr<-?_wgNk<37%_6UzOwP zU6Uqa1`2MI&RT6;{%zGAi-<}SGPYL})vl$Cup2tSfU|4MK@~5cnG9H^@H;KeUD_5m6y{D;KvX;6^dcK(z%`2)5v~TYQB+SM$PvnJXa0VlxV4*tw2jhVVC_rB485Y)i z94QKzG+FYLM05Hs)h3a*gG(WVumGTL@!>>-S66S;&4G{5wiSpKTOigWm>(MQx}6wu zpP%O=K)wn;aztmK5(ts7X|M{~BE?p4+(ZwMGQ(ewb{0n~{&E}v!~mRDi67~JzPmZ| zYvwXr-4f9zPk2JrYc?+f@3gb?6N|BfES#NMSvMQWVy%Cz-Nz2oKBe6(4E9KxE5L4% zx&ko3E0Cwiw>rVPrae}FPU+uHQ1$A)n&kVoD_LYq zS8;-N1SXt)9vZqa5_F3g>W2eQf>ZnddJOFOVM0RbH=FMB!+lU}Leg1?ODNMIXb-I_XwB_Gl@Yx_8;@nGn5Aqys0JFI$VZ+0O%x+KPCvY-tdMoK~5#0Z4 z2Y#I^R&3wb&B!1Wb%Gr6*yRBwx+T)5ZuikjfQDL^FDqLCfAycYp0xl7;!WCL%8XFj z0RUbD<;wJ^r|YkbbVb{!z0L0lBQMGE7w2C<$4*O)`TvpB`j9yrk~f z?p4~gTzKDK5;cE<-HG)y5U?v@jO`Ls4HOVRZDD5I^;WOVb$?u~cfOP8rY|(G)D;z_lsDTsp9z`AX{w+NCJ^ZE^yGk@3js`61xS|XDTW_>|tBDS9APM`zIpd!sYyXoSb?H_`S5yRY&Vz$=%P1WwY0;)E#b(P$17JtH&p`N; zul4C6)9Uj@FjXlrP+((7RKOliXbOiDyUx-|mHt-vY(aicEGXVS?^N(D+ILD$f5C_B z#UU3?YPb5+a5F$oE)PYwJZ3g=<73UYo@vV0GLT$dXt+|!i`rh0ZLpC47QZ!&fBAZX zSnWo4wrg!n5X(1v5KLTF?qU=h+&qw8;$4Pfo>Ar?r^Q|p^L0Qh%C(*@wq8CL^Xab3 z$fbH3tUKWxCG6T)d(^=9PP8@LcQ)y6MY9A6mJk!8LMb@PC{Z%@)>yWTQ%1lR0(9Ucrk7kIXdB&so1|kO zB^HMJh|3LNBK>*NWOu`hPfE20<~=KzNB2jKYmFrMd+CE3a7I62a|H)JNsAKf9?}sc zD!kNAKxqw?lZZ|t*P)91Rwh49WC5+=})K7oj*Ue4)_=ou*VKm=k_skXW}Mhv6b6zXW?+){+k7$jLr%b!{9L6FBtJ6LP#1qu2(N1T3 zObi=zu}C<~+m!{yKUf_EhU0NusaZOd)_CEhMO2^)af<{O2b$CX*iohwZLVL|V${oJ zcBKpt))&qIFxNS`+j~c)ge3C`8wq`<80Ea03*Vph=>Q>DxZxN*O=$Cxg~#GcCyIPk zs;1cf4jd!)V5LBKNOt(eA7haf#>`1)eArVK=T^JdBcIM$-~*6LJ@c{`lvT1~w$m$9E}_ctw~Dpk@wo?B!xi@WlKO;ds$ zZH{y7Q%sd%Ae7D*RDbt*{^uvp5@;~h^JRg0eIkNEObf5|g?{cxHRxe?h?#u_(t!xM*(*nWQDuSjZluJsH=BVAs)nQk{$H$egP z!5$KvZV%h<(uPk#`Ca^2?R{gmJMql8dI|WTbd31DyqKP_)-=#d~rFff5# z5eoI8CTP?#mhc)AiIRA{Ybj@;$t*&E|0Dapr%Zuf_My#T+uL7)oTGOH&&1q+7m2nJ zx8A9AR$hIBUfx7!9+4yzdZ?Vc#4E}z-YQK7)9k>wCP67|g|<5Xt3cp1QYq&;_Ek_0 z{J?Or1=?E|BbHy+p)qvGDb%g)C;d#MV@(<)m;B=ciDSmxR`VD4M=bddfNZV;w1yql z71II2CUOzXQW@6!%Y99Ak?X~`Es~k>-Ms)=z$(Z0=9AAA&~)8#ZRn1!7u1%W(>@|q zieR?h1acf31`iJ)4k=x?!5%FLFFa!`S9`_r?6AZD z#i1bNAbhNn72RbY>zzu7oS5GZ4Y;2c0J6!@9Zi0yB_(a_5cRM+0i}CzuN)86>LXjI z7XJ=(-%3sPKth1T#R$GT=J}K|GhpcL`E5Yga+nro_&DKoQyh2dJKZBHG*62dn>=k zGb5zwNdvIp4h@UCAmI?N_ph4WX1r>6%eLqj^F=yWE(!Kp^&4zhus}*BizJOzI3|R7w3u2Y^Fe-em?1febpFqFu=?*W zT3txYL3MyYN3?axGrT=25_^|3?pZ^5=uj5al<=?#m4wrXF}#X#6kuK}kd&-b zbe3e4+EJ4tcWLl#Z&scy*?pRJN8^zi8{_g{1pA!FyMtqiJ%27U2V8lsyWjMA_B%yB ze7kgJa^7ZmMp1Zk($rh;;9S+aBQa5=LGH(72=&mA)vb7begPJ*vnu7Mh$ifiw}&Xs z+~U{C>{0BtS$-kgb#C(ct1=41bi5u`ft;>QC$(KgHV&uW3rvQDJ8QIB%pok^WS9+# zREE*%2Ml%ZFWqYUSx6Qu^(e9;D&GLp1qLutFjLRk&TB3DM5wrziT4(ufx2G6C00wx z(i5R}Ae|o_ki%nfouhDH&$J_?+N5iC1F9?Pe7359*h`2y`wSWNckOZ-7V!?cZ`CjJ z1j(EqW)d-u;usvPCtv(=29gdXUn{Dp6=0)K8tTxPVM6xd4Uh|toIq3Ai5;B@_8+iT z#vX11c5@U-RGGjTWe^f$Q?<-F2*RI2BHe&Smd{CGc>7qTWGDuNpqXu^&T zHB?R!0ebR_1w*gP(CP?;#&J^o=5Y&~)s*VOiYsXhHvhv1e39AA*Y)5!Ndx%Z;j zD6{e0PZ{rXqb8Z`XU4aj3FVbyV~nSVxc1Gd_;xaq?rG;MwSG7yyW++||U{N$7=|C)_ncoqgW& z7Fiq0AP=EH!!}^sVHWkUHZ+G`6Qljh^l$p(0jgvX{8^bRM42<$03@S`cz`^OE_5Uc zawP#8@xgZ65xG9H>z&WBB7(xcwd=rVPle%1dci8&eC)izgv!r3sdWm77PdrNZvj|E z5z>ZHIndhT$W6xe^}pzyt*I8d^|V4q#>2u}3Z(@aPFjAB(!0c_HoaWy8GB0KJo#RU z2wT3c<<=B2o-(^NxkxIy(W0~fD+e>35lehZu8$P7f5ynE!;#@`wNZ+fqbfhxN?liM z5N%wZ+-)6w*Cr9L#UdOr5m=aB(cV*XbNSPslM16NCIv!lXEB?&xCzjfN*Y}S>|Mbj zu6e-it$|P`k7hOr7dA~(U+~BxT$Z00!q=dKzm)7|za+WF&grAhs#j`mF&sFAat;`>d~!YTjN4fLn#Fyrj1hWwyH*ppR@^RI~ zxcaw@0e=nZj!Xj(9r?jaY>{Dk){{1IrwPYk!Q+}ptXS_OSD+wO8+G;%BD~r3?^OZa zYU^cC1zJ&XXBoAePG03zyMb0nmZl1#qbN{ckl&)6Eb}iD^Sx3VTI^)k%)Fe2Y>+RG zs${d3UPgTi6)bYM{ARv#xFn^~=$eTS%xf&uXgUHa*}Y%)VcSnWQGylHKUnzkXjE6! z)he-tv8Fuwh01q%Fe|E*(>z!ejjp8h5oLWOnHTf9Nx@mgBz&vi#S^sBx2sg3JXS%@hMQsA| zS{W(XlA7~~o;UuY6R|6bbxDyr7dTI^xWiBGgD~t5N&o{a~(1_(7?huc}EnhL$PxFkBJS z8;4v##q2V@Ro{>?yLk2W)9&)zLRjZ!nbV5{Va}+JJZOQu;Svp|xQ{?%((Pah+7^v- z4#(PX5FW<1o6>wopeG=o1IPkmP^7z~NF|TWUGx7 zm)-M_8y>b%Smq%XfB?Yw4Y^bu$Yu$+_^lHeAozg4A?$emZWF<9Gh??6fT~Ovzay{F zEX~Kdo_~*8eH;L4*r@)FpW+uwhuLA%O_n2Xb()xNJ=NxqDe+#hg*RHdx%(wfdK+al zxQ~on2TJEH^B5()lF24=XLh}srI#Mb31oEpFI5p+56 zo+sU9f$y)k>1Lf=o5#>1yA4zlN(=$6!Ws*;a%6EFXy+g%yiq`Y5 z-A0C$qYbV`J#yRHWqpKXliGdW;v^6Iad_^je2WmizOlq>I`AGlFnymB)}bKzXpbz3 zjO90&&qp!5mO+8r4GC{J!V9h(&9!#0QNhwdvWu=-2(oX_( zaXF3%ZuX{hE*)2m-Qu@Gzx`vBn#{n)jq=g2{8#gsX(=ZSb&b$O*Uf(33wRp;-|P9S zxL^L~cZlv@ZJGLw-HB2CBZZ2`cd(fWWXoAnJ=fFR zn(&wPGTvuKsT;A^JtA^W=I?L21yRdmX8!i3pv|>&;A`g6vLR#h?o6|(C+=>WPx&y} zNb~8+R`PiV*Vgc_nXi*CwMR>X$=0vZS*0-Fq3is>Ys6S9R^L|sh42|=jx2+6>%E!?aG;&!hnngVYE=I7>S0wEW`}PK-LSSbB6Y#@ZG4*h06C#fWE+`w zPc$LCyAtl!;BAQxC1Ajin73z!qFCQs`QOcl*9AM5SY>j>nBkFXNauH z-Uz^+m4+nf0iMwft&P9=XfsQ?k!l5FjPli&{`^>H7m(~1Tsp{7lP*M2`8o@-x};5Y zILuZFl`Ih`Q2VtrZTXVkmfi~?*YY~Q!jQ#Ci?((c)f$iO`ab017&?xRq8p{}J0}&% z9$%f#wh9%;$4fs})DkJ)yU)q>`+c#XAb@*j=+CmtH)>!B1PTeAZLXBVKj%!|#h z#%ZP?mhQ4+EvZ%_qfuovZ4v>;rAW1+XUIN@ZO;#mfaBt`uPGu0=)TLiF{8p-Uec-0 zDM38D&P`eu&s~DB^+ToVlj`-5HxptH8#^;os?)`CY=3rzF}?Dw-_aRJlyO46nYYU! zUh(sUr813vP!W1M87rM?#UN9A{*I}{Y&bpSXFx)db#b4?VKpc?xB zSUMlLU0$bk=YOnW9@(WkY16ix_C4I34akRc0$ht(g$8KnQsr+(;>$YFhD!J~Ysn?* z6=@34BcoX0o`hFf(Igxjbi>DrAr;s05sL&Q%BZtDTiu%kM1e(26Q$hO5rKKE3@AQz z>5PXYeLo^eUGoH{d12PPS0XD7wXS~sNLFx-OV&I{)D>3w7@;inE7NdUb|J?&BdDJ| zgI4BK{nLRb-00c}7Mp0(JZ+6B{o>n>_yF=UjT(pf@tu;fx%Lrw#UH$!FV8U!St*Ex zDjK@=1oT5sldIbjX4(rp^}vRd>mM&wFg&)>s3Wbc7MbgjMXK2{mR^#rI~T@H!sK&^ zB7#P(&bmj16GNKf#M%A%pi^jg4LJu{7}~}Kc#IRduzDe^m=FX z#dksMs&NlTtH^2UF(*}2`&mtc2}SiG>{+HYb(1+oYaHU6OXHmR=*Kq+Vw!r&-hX5g zEq97rK5?bCQ=GNOq85%1+G8r?w%0$70yRk|&xtJk^4bkmy^l;cw#ACvlVdf0R%#?Ib#ZGm#+ohx9A0YaSxSxwv4fR4f<+8O!pRhMqFkbO2smQ?xVfRGyE# z)4Pc|^eL;3>cH3C*?Mf}~FJ_u<-w{F3Lum*!(7lQNJ2V+x~_R^?(cJu3lWgw$dG)Ib z9Y;P{V)-_o6-dRU~{Mt^jDMR-DXX znIlTfOy!sRyG!#+Y3sZp zY<}(b2PtemI5tNR(h|;d&tvF0e)+1yiJ9RNlBMk8U#u)Y#^PM2EdN5xu1lEM(tgiK zR-2adjgY$Z{f3}foZbr$cY(P$C$u2`{=;F3m*PWMnv}ZtF?1^-X}o8DaBE5F%=Z-4 zqPAvtExyEtl)thQ4S4N2*%Bm^t@x->=R`Qe2HEJtt#z1K_{AG}TRh=nb^aO#+j)9U z{H3cDFa_sN7v{E;nVpbm5AdE53`YJJ zqWkYdIVY4=TpB+6$z`cY)q@M7&FKCp7u4<NGqbGAc)c;HMDex`+D$w_iw$&j$?n{U*C5ed;K?S%^IG(@9R3RGcd}tKk|SH zG;yr(&{r{XUr!IwWeq$#dt1dz zHz{iV?Q^ugsYH-d>d!KTT2@ajF$W^hs^>Tas0n&Z1 z6iCNjoGFZww$z9D1ZJtfjmqp<(;c{+ zp~-mQl4uaaNyVq60KDffp5q3k)Y(oUqOCbs2?KQh|BurQk`pb=Q{`>Kw1H zc!ahf9NABq$nA^T&Z$n}ZzeV|N8bn0VpK*jm|ccT^{&XeM-saV;_d5bb@oh0U{P6cG z%2}tn#@it-V!%1f-31#fRiYeagEA0bP)xgqVGiZY>)VYHWpc}(wk3wWN@^zG z2`I%0UYRTD{%|_o>$pR@jdQpoeu=Worpp?*S3wpk4qd* z4Rrb7HN4J_w@>j*_b_5ORl#H+4ln*<$IY;z;QQ&32x!WU4UBEvlcK-sEhwsbY5CB# z#J02P>q;w=9pym;_;X$H+|n29ez<_`O3_B9!}7gqi{|4Sz_zKn@Z|caYw(GJHXn$5MQ8a%fSaA#%Z!Pb;~Vh90Ar|kJ4e~r=)7eAY#i@pxQW&)Ca_eK7e5RzA`HQVU>hTy2&3AMr5edaau7M9dHhs8#-b(?o z^I6SHIZR{l8P`YE50b)q42NsI^V-!cpF9-=_Tf$6y|*>5*e3zEcL3Gi+O>gv<`#H& zKh^rBO1Tzqa0}h8(%dci1=_~opZW>G^uzb}oroYRnS^r-glvAzyv2rZt_r{T24=wh zl@dcPPrW&Ne;z$)Z{~23JI!jkV+XNW-f_H_A2kJf*XDSh(iEQdR-m%Zf}#9P<2q0z zmR0j#au&|EhsD`^dUtp*as6%s(i+mDlv>7oQpt1DTUtY6WZpCK;mjKzPJKj1(go2x zcx$ZKZiA8l`&F*Xu>rxyxh~7(B0hSZl`_4>)HHogpqly+Piotud;Qr7fUlK;Y3baz zVN@i1A}G-v2(zTpawL4z=pY7Ds0>Sl{251V zL(Hra$A66v97#Cwp=}`7lZFH=wuIddj4nfoYWR=W< zGa=at1=1)zmnlH^rg(!KxUO-GH?^`k`w0cQ1~y%Uhoo~m%>aGBQ<+)0HHSDJ_j4-S z8VIJMU#7Wzy+WDC2tSxaY|1W8bTV)C*(i139T@LI*pf0SNdK2v+9mgc3buQBXQxywU{WQ=I0|g)m_?~ynpx3 z*&WxHnLdJ|r~ke{0lH#%jNCJ2tiORgN^AtX;44!YbAm9!onB1$CAi??gT-GqvO4^@ z4AsaoH9B27fBz{Onq8+T43@`#1FK5Qzs{)W@&vurbc+nl>^9e#e?z()+#7pmZ%1H0 zXP)(8!wR`)s}e?A)y|NNbIQY7+TdoX^L-U*WW^qxhY-e`)Vs9fJ}dM znXoCc{A?<(ky3D2co9AMO|WK;&iu>Y&B@XmCr@DNFj+eR6K%!dHi7@Ra%@Rs=4+tR zjEpCu$--(zVdQ4bIcO@)@A?FjBWs9*DPeza<7SvlkqAv0V4z9r%^>yV_@f3Hc$p-0 zyvMqfcH~-OMS#WriN1yH7HiojViLde2K|>iKMTZ)j5kp7pfxbErNZMWS*Tb{L*QC{ z6Z3QwS;E~Q#>Z^|H2blnTPnQK6+kKzF;dw>-Fm_0*}OWzcPXSh%9-_2Z~{hj)~j9V zd~++CE0YSvhaN+?TFh<_kGGhBbOA-QOlwZnI6^0IQdu9GTl2avb+!ZbrQFyme4`(xm7c*57U%m-SuR< znIK0ls9jp2pkfhwPr^|2P>CATFa#pbGA+H$C>}kkk1ldF=*FU*vxjebEh#@W8@3XO z#mMP+{DRl#w&g9<@y``&Q6jDGzk0o-Wyl8F*g;$PLnUUOTP`>n&}*5OuS>vqO?6=T za!_~3g61o+Bqgjm>#4WQy`r|UIVhh~(U_U=ZJtw47f{h^Wgnf}=_iwWToykTBg*QZ zH(kG9DI2;>$i4{!%daUPk?Gq-mCeS-cbWN<&dC0=JeFG1cgN_)kiHvjVxt)<j1-_WS5{TxXkh3-75z+UCEZ#vR$7jN&omUg>0|8={dhx`i`~+QM2FC?I5O+ z`C8U&JxvtdWGWbi>0ffnwfFN_Otk}WxtDtW)0DvRY5eWDLT?VP3uKmR{J2tXrOaOO z0r~ikKZV9z;{_{$SNqxN+tnhmB;s0JicXovq$IP+J%tuu+E^^%;V{v1n+%_a##-Hl zeT@9J=&*ZT%JxRh+dwpFY`{YL&4leyX#xy!IQo9F0Ym7M@UyFnRe%R81{a?i*l{(C zMhZc-8KMXSj8vLhoJbNy*RSgruV4k(WrS8(hhJP$=W_k3ntSQ+EtMp&9FN>Y`R!#s zRbEeTF1oC`wATAlM?sSm9b|?Yj6JKbmY^wNf_-^!aP?hMD1JtWHyJnH=%1mVSRA-* zely2Ey2(s@SpUauZ@eo^40;}$@D3z@T&_##{WT1whd=+t;+mTYjBm2qLIyv!rd*dr zn)1;>HiRi~yAdf~@m~DxdzC^_Z6PTS!R&c=@#Cg_(X;2!qI{~rJb@hUjSc)2{R$wX zlIe;wO#0kl`tLmqd_j|QF(-LnOSIg63BQSgpHqw_`c!c<;RvD_J3!Bz9H{}RB&d}6 zG=Jet9^QJ2G(0U4qk{#lhyUH4zmh~6jO5CT){H-!qmVCLiv0TplP70yf5zVENnpeg z+KO&#_efib*PsZ;OFbz`Np$YB?d@ztejaIM@bJ!T5B(N4`s;(AgZw=+vQWrl`1GTR z!^2fb+wi&5*k?yD%v+3 zQ{s1Vt4LUf$Q2gJXJb}olaftG{ba9US;}+4>|^~IQGYr}j2@rarNRD&5TBOcUjE57|kAMYW5z%Lj!#DQMt#f_UVIckd_4bnw#gAVwu|&3ilzh}7yJ1qO z@;f@L=W%A!KB2JwnBCQmyz6NapVJR6Q`+1@kLAZZqPV1p3)i~+Jk19}A{VYCws`}~ z;0;yO4F;d*1Q&*@Ws*z9ffgm~M}KLb#^p3w4RB*6zOmP(bGDdBbvY1^x+<>5uO!S! z>-IWrdRw4yOWuJDWi%{uUhm>M=vz!)qdi0W9SvhB;ql>y$0wJw)>Y4pCcx_Nk|@67f8#+WB2I1f~A%9iVe~;vLXUYe@SjK6p>59PB)d4D6Q2n>*bU z)pihlxx-0K;0?UB8z{>Y-kB|^o0H`K!(?nfLM^i>57zHZy-ds5`mZ8pf7VnTSW`kh z_)C1qMIW)g|9q|FHsYEwzZS)a9vw~X{)fSYa`2U1 z=P<{>;8$yqNyKCdQFa{YW{MGWmWGb7UdS16(0fRg`4mIOgA*zMrmt*+=Q?=wYv`u{ z71m)4@*7GWx>SGzY=l%#WgG&L083QIQ3`k?b{HQ>IoTXek0aqPlPNfDUfp9S#Y;&& ze|^}8WRthq#|F5SmtMcgr?|*bgy0R->{7k6^(Y(?!66Mj=-e7~n1nQU0>Biq&K!E- z63i+e5x%SE7p}2xx>nj#*y9mWGyG>xuPL^0qX?GykeNF6zcn^ZL7R`py@nqyxwxApx0WznQh`aG}d@m z>$XI5{LhzKCp{xwwih^txv}Tsp1%qOTK&Exg1hW+5bcbnGn)R6(qGsA=`a@qGbq$Q zM@cnCEo`V#!ZW){@YQeF12df?@d4!J7wd;Q#3ciPNQd1ygp$YRMp1Em1!%+DIMTMa(7eot zn(V-r^ozr$-^AzPp%u?LH2#GDE4ZD{@M$K}`q(pu^5C#vqBQYJ!PZjXl>PaH z-F4Xq!GYXuSQSIjxkDuC8mDl~rVq>?m3i7Hx9drYV&y^{QMhi_dbjsPq`e+aNlHE- zGd%JA!tBc4En}=U1n$h(aN0*s83`sS?bf6KCeak})aKbj)GH8tF`17^#|U~%tDnN{ zr&E0`xOwr+IWbQ4HB0N!!K~2i_*3dPD4nDKNrf~Owxo^{@0wDxR7z7TUs5?&r_`#t9{6vX9n949L%ctxhMvm5Z(p~()I=l+YJ3^BprsZ@>Qz=AU^sX zMT=fJU0J>P`e}HAg%?@5q;TLO(!X@i3wu)iCds&;&2fQL`=`PBubWsIfRi8LteJTl zCEv{|5a$Hh4YB9OLDlkhRf~k8lk!D1Oz7Rg1WM)I9TN5|+GvZ5z%58uFOIYdur#cG zP*lUW%vfO8erlL>-xdZFVC#LUT@jqY#WAIprX z5IcqY_5M-k{UBdCdr%p^i5>FoXbIyjI8veV&tkS99;gXqFP00Y%Q$jQLgbuaG^UGQ zR>q#5wG}u56};@xQ`BEIES)T<5mjs09Je*`QK~}sCN@iIPC`gpw2``hP?_$FchSqL zE+SV>GrKe)7CovCCBcJ>?($_een+uy5MLJh6oUbQh_>h-stgp_z7cWa9!@YLZ)x%{ zw-A{-bSkz2jQGE`Ck092GiW0cn)ueHrG*t{qNT`MAI~kzKF_lx8~x>VFC;B~=05gI~xcP2wvyN#k`DZc_ed zA?ooq7Q<1k&b}((5KI@%&+%9(X$Q)xyl*u9G~8O5nYuqUEfBP^(@&gc4~d8IUI(y4 z)PMj_`Oy?dk%DG+)S63qMSi;m%Ae$A$J=vuXCj7Nz3%1bM? zbN}HFE>Ge~jqP{|X&WD5OVcqZ_tFWu+Vz5}@sZg&WD3MPapc_fZR5t`YQE~#)>}j@ zoE*qXS%i({8E-A9TsyZX6b`CFm>46=y&5z>1=lo^h&_D9AH@f`>-Fnp86FmJ%&d$K zRe8oUyIs^x@f6elhMR4*8%X=Jrv`qFRER-ql!`7IRJEa%?z-@i)LE24?PRLOJt0_x z@1Bpk5Y52{Q4+D>p6BfG?>Ra!PLX{68PpzzUro%?+o@j9!Emhk>Xy9Mf1p} zP~u(H_$Rp8=|fhgBfHOaUJ%`tH&$t<8Fd&j7WMnLM$c_Wu?Uot|-<1IYuGg`bB1RY8%cd>G zsAHO!?KzgcPu$|WXK#MT!dAW%eWS*oE0@if4WAwG{f5lK}UDPwAx#*hE!{?KZo8|9{&nFRuVrtl15X1a9EBU$IU zPAGK;iQ90$Xd~C{Y+kcdaF017aS)M^c`$OUKykS)0Q3BElIh59)#otOIPJ_+1ce?G7a9$_$@;$dMv zHWlzx-2a?aTX3Fk8X0H3hKW6cS|Ccs*@isdd@t za%a;&CN{`nAZc&Xu(*zu=+{5Ep~~r9isXHScm#QYF%SOihpD}ovn|B|OMOVV!{(gc zk?B=pvqoFsAbwuEY9yA=N?dB)3VXu=-tMW@v+b1tjC6M6H!cb;eUY48)$bq-X1L1a zQKf~K^ifJqv_-J%rqXHY31vf5O2HHVyo)!cEgWGuvo4X^rUmq7xmI?t-4n<#e?l4m z<@${mZNPi)Jen**MbeN^E*5;4kuPc0CP^f;-g>O_HN4**2Udk8lmSI^UB`MJu8Kt% zJDH`ttN-N*izUUIYf!UTf2|Lu)N-zaGh`I4ZIB%`yo>Ti_PHOrvf5U zWS@W>KZj&tl>?^yH(#yp&(C;W?G|dPJMCp)doGJiIVvDr?qiEzR19@XHNro00Gma} z@C!fgL261-$NSBtvH1sO;7~Bofx!O>>$(R=gkKr0XDLF*CJ)tufGwEPlezWThhvxDRQ!|0DBcNTyClPaP(v^hU?T> zZAfv-D26n+-_dPD&=k7;20t$L`%^E1D*H;T2e!Mnv?PWshKbt$fL{KJnfzuH*txZ& zx)YMF#v`u$jzEeJuN8gKhVbG|gYbc5@}BAyhYlIMQpYM7@HEI%Od;_eJL4u`YUEHR zZ031Tck`X_gs9S9IgC~N5+HV*4(GI?@^g^(x?cvvus4+QU24pP9mUj@4u436`Vp@i z)Q#kfI!@&1Wrc>{RO{RN8900`GrUeNAZ}j&RSNygJizhyb!3*X25DW-&lenFO#Np) zm46=H=vRK%@4RIT!&7ll9AZ`2+y)kEb9&+Hj0TZDiQ+nMuP{8vN@u)nx z2l#F{$L_gk48IUs)t$c};m~*hQ8Q%v5qNm9Ls5*_(CuY(<1E;K_Qcb9j}g@Y?RwoX zf_-ZR74n<|j2G9XQri?*l6W2mT&Loc8~jPnj*KJbYMAT5bE3Bxach_Nf|t7}z_hC0%ZZs3h?Plyt&~{i1c!0}*!xjiDW~e29 zJ>ig%Q~K0YFf`@pt5)Jw|m> zye+S8f4hu&@y5$suhX=E35`T90Z+OZ_ZSP4`4#AjOMS14P00*f_BRqW&XK;H+#y&x zjy8nw1;H>OM>xZQ2QQR#M*5#MOQjxwW;NKC4<2rGL$Mo!krL+?{79UeP8$f7O5gHj zf|}u~?E{(W6|Ttl57Y&YCBg3BG52T}a)RCltwdc$9M{bUmKNW0Bvgnwtb%r>*x@kE zYA^*}p*yBsxLO9N-SVq}V~-JaPz@0}Xf;r`(b%!#6J7@zo#JAoz0mdcg{})35ndBqa2UY$4PLTc|q zVg@}%#CpV2%YO-m+a_5u-TG`1#B@|6oQJ_PkzbE6bu30|Rq^D$pZVgi54M&O3pQla zPhIfzLFe`M&(bw={sA*Z%C^&Ao-T-^RoVS7|M(n!a$wd4{>(;ukrg=5hz0=GQ5x9CUe+{Z3<61H6b(Flx#@XrbW1A&=}ot5 zJk~UQ_+j>ej9}kJE=MiLhqTc}E2*4>SW4T7hhntTe)bmB>hkh(+fzImjNnB+Vvrd5T%~h1*KIpBrI_o9i{4wdR;=-@cC7Z2TZ6ghG_<( z8!_Xq?~XMjNm*c~E6m5^JVbNaWC7Lu4Uemc7!5ZMd*Z^&yUf!H4Sjc=EF*^L{U7&dAG9tPi@`f*GI`LVTBbN-rVl;VR(%-cE=2*|V-t--@u;l&VOi@g+n|L< zF%CRW)D-w}neXUydHd_#rXHZ^lQK5cEMSykD$Yp+PVygfWnhd@vqebeV=|A7ba|jS z$!ePNzC20k-XX*1JWO3|A*1t9x-uy!7AHmtW(qTYio>8RGbvCF%FS#JAi^>%vFh_g zm1BkV*X%=j@5u#c5>0TUG-ToG`1{|V@BjWI;|A-3cQU4yIrywz!+n|xxJaFDPn~xb zM09O=Pj;TZrBd2WDKR0x$Zri7X@Pw@JF~X6>^FEzs|$v=aZ6ykA55tXM!hbS(D?IEJM-}LBKv)LejHZMhB7d-^XC-eM%>7L zKjrNQV%|X0z22jEWnRI!Hf|HxU~lu@<8hV_EaYqe`wX z-K}h$O^8n)NkkKeVskC%h)G?X$2=7$3KqT`580?mM{~NfiJ3hVK9k=@lvBG~;y)%o zwNdWS%0J=~u^G1Ssa?a9`wmno7|CN2@L>qu;_+BD4qd>MG%xUz*TI=d@M1n*i}z$+Z>mN+6t&lmy>3d6|w z)qV9U1CoN$&bRUhMZPBzBm?BV|NH6x!If}UB;4uAcPIdh>QWDF6JofA$i?i7&TfN5 z>GvGJ&gcF7RymtLi>Lv2PTqWJyY}qezk=A?)C>sVOFlW%Q&899JAEO~^c#3~k0HZe z-?7&7d2;kUhx5q~eh+o-cpQfNIgn1k2NPj9!NA2L&_bIRiBv~E1kXjcg)|@}H26Rk zEgOT0mV{9Z@`1Y;QrM3pN$ki6>^j8Qk0PTSj{J($ff4GblD?m(1dbc$VCg0*oV+H9wz<1be{CjC>iDEFizhxklj_+=O z79d;pySEQ6tYYw?<`n+>eA+2fP|FpCz7GK7vpt4CiGObbN*?ak2s|>z%D;A95DzxS zGglifB2#_1Eo3mS!?M777-IaIELBek8C}7&?*!b&Ct&KG_prgeNIx{|?@uWs_p`GC zH+co`e5nY;6v%Bo2eB((XSXZ{yrsWCHT7&Pz{K3;r`>xx`dAO1z>(< z{rj86Somfm4J!ZN{{oF%ng93~u-*+;yRVq+ZLbae*&F_2`&#}RqN7Hv`K}P`T82V~ zS?eSY{%|x^oHpSgW^wq>j_)(UUW2SlaaRboEqfuu$p`157I^724omf*DfdRzx?nU3 ztnqQ}4GUqztOWQOXRhY*i}?co@i$QM&WJ4()a@4+GaMZ-_iRlN zjT9|LXZACTr59UJTJFLR%&$S5`ygI9?3SH@rsOaTMel=I{o4)5pFN;B?f{A7mfg!q z=-ym?!D8LZEe8!jn4k`<-<&(Hd$sP|-&=r*si5iurMZ38(lp}mGclWAmA?b#UANL( zB0z%p4l=nU7~9?_}qWpXcUeY z$NKmHZUjgPp%#YlXir;EyA6Ba?|~~d<&9*u1A;Vzbn;=pAJD#n{#3#vodV^IjjAq$ zn)8b{;!#(5-og=xb7lDn7~a@y4g)6elH%+sW31EfZhq-hJOo;!rK*rHG zn*=hP!hxnA2cC5jy0?ZiEuqlP_>By;IDIzFAGy-iRsF7Py#eXih$0 z8N9hUMvG!Qd?&LnuIn&FPI#4DwI$Ly1f9QH_Nn4|wXEm*lX&&N+mqmFcrFDl5g<_Q z_=kNO$zO-)$yyXv+g^1o71koI3x4;39V%4mHt5vYR}3Io#{$glJ3aBXkmTV8E!sU` zcRc!XQrayy&hLC9LL4ni^WAr+4}qof3#996^HG^Y9$Ezgc?|((#H8D5fUJwO*D_R& zJ*AJZgdxa%#M2@#=y|b7??#wOq;?OH~9fDg_XkIFB?WI!4Z~j%K}Mb$j~~~lJ1*iH)W%O_hkuW zlAJ0{_Dv|d6bXgxGL8NMs8n|L7)upD7g z|1b}c)WQjWYX$>tcz0r6e@XF841Cw-`g;qraG;s-<^rr>8>Iw$Q5AJvFx5`yu0 z6@+Je=OEidf}C4w4OW;+#2pfU@k_GA{nM!~F?o?(Tr?bb$=I+d^Xe}qPF+IL6#%oH zHi}?lfAH(kx>TA~Qcl|vE8gn;estC4=ZM#6m=rbOEf%LVMJa^lQIE`%jhXMQT`Ne+XjnX5g&#~5g7>*XWDQXolZUG1C zy7>v-==Vrs=BfaLE!V`;4jyx$V@pgcmS*eoMloErc;XuM1~M!Lu&4RjO|G;kr zvrqei!A4|d^Q1yrsXXr?!^Ou}VnH7+M44gwP)IC2n*~m5Jn|=-h7zHE4}}YU+6Y}; z>4V7B*f*Er1o<2u7IG&;m>ZW5z98YoGMzn{MBJ~e=h)6@ z`D@oN0n??p1s-_wRF)CvF9DvBQi8aCmhAzB!e~dqqc`&y>R;vS-}ON_>9%awoJ?s2 zs-GAd^Dba#t6tv`liFV7B5!2FJ&Eh2WVod~$;;8Nqbq{C2}=4~4DO)W7y)bXPnEf3Mq+W{pS$0--SZ)KZ~iFE+#ws`u=gXQMa*1R}2Pf6^NVTGBN zo{E1wYEfM=6^JQJ*Dp23@exjA@%inIOF_O@Zlxa zo1fpcaa*b37tZ?^ck&%0f1byw%Yj#aQ4PdnHF~;SupIfS$Dv_Nc-XEOj76cTK0SP} zHH8u~t?tEN$|sL{FKrhIS0`8YvD7Rgw3B^kJ)G@lc`;^&vbbz{B0_9G0|<7 zYC+WOx!*!uxIEOTI{7Wg%$L9ZZl&Q3FI~K>)3e@0%kEtb_BTHi$cGlc4f&YUe$Nm# zVQXQg7Sz7>2P(Rvy~TteUk}gBMh(1OEZqnZ%C@NmU@s2uGy`>BT3tNPu|RS%h1awf zI$%hoXSQgEGD;x^mNkRA7KwlB{e8N}*?KPv=TEqvi1?sVg&tOU(!{uPd+G>@K&&;5 zKyGbM6K#u9&px(kYOO?!_7rb8L(gR)fzuOf(UA6A4fb5Otl^=$$4X zFss5YOP(e>d)e3AaBMP)LC@n0_Nw~ZiK<`H{Ug;~w%WFO|0tj^+|GwQ`YoD5fw$J{ z$(wF|#%rL`MCosZ6+8}|Su_tV5$}!I^~lUy=$9td*E&rU{`p^(qF!s9$mV2|z1F#) zc~GglBMo`(|MJrtqE&nKyJ4%@>XAv{Ead4G=Nx1zNO^{|#x};0W!)-C*gpN|`EOc2 znzi=Nd%gg(wb7cH;-m1_59*eR|Mi#ij*9*0huC?$u~QwQn4^A9!!F;n4$OPR zBqjZ#c#b0e*vDeoDf&PGF@{8lAzQd{yGQ0#^kqrnEBc(fmS63T7Fa#B)q%O)5bU&O z#MC;5OO@h zEyGYwm(ta{&G%P8A=3)gnN#OJT^Ddw`m9;!l1r6!pt_!a2R>9*o~aQA=tizZs-x|0 zId?A>N{dBFM9ao6C6JwLutajfu3A5#ObA6b=A!|1AY01IS7hOmxz-qcCNy+k`k>Fw zrcxs~2ZK3E6|`6tQ1lNp_}gfw%Xw>tuEUfaF-+7@s0NnYAmSl}Oz6@Pw=feZG_`tx zb|>r^o`SsNWlG*$Dr83dxAkf~-TcfHGM=MKWi)`@z0QO@3eF%J} zXOPnwzl+!$!*IU9Zn(Ba8VLVGFp-)7`U9t3^5`?I^!fiUAtVL*SLRcHsC zwVa@yeUW_8w-yl;*?W3Hy;txS{f%&pUkUabO|_cfmnacj(+St><&HOcDqZcuNMfi% zqPj#JVGxHtJKtNBp-cgTSj$GbmO)U$+*%9xnspdsF(`?RcSX#a=p zbi$H6xv5Q(>b4@`qc0K4ZAJ&TS6`C}zYY?!Sp}LD{6=fMFb>HTb>NIvSlvC;t44Pm zCaMq1ys;l2db5GY`Vpx!3aj9k?gl@fHJ}Z;(rk;-&M1g={MBP$^O@i(&BF+qRMqgr9wYzmM%moUNKlN zI)bc;ty6|3Cl=-_RW-oo#6C~tTxU}6zX_8Ai^Vou$Z(6pF{sND^7R zIIE(Og%mlZWkhx_oc%R3%mB{}X_E=8$6&;wY(g*t1Mzj)ip|k5;pLF`?iHtMVz&EW zb|~}~2l;N|oJq#F!!Kx7BXrBdIhov8Wy7F#=Q+QS2%BBZn<<0t;UuID$66|)6L`L! zC7+<4IK<6$0^5=qx%j~5l^Ym|_uE;tmmB+u+^A#_z+ux9FFN#>PT`P}jVMVe7W@|i z(9C5uN(AV8IKqSi=^b{0Rou6h5tlgD=D`E5%nVs+50521KaZtw=({#uRiv0>I`9+hJI@4+K+?wM+G9$3V+V*SNUGI!jAH#ey-0P9VD#;Vu0 z37NPyn-rMV%)Ql_=Z#Sv7liSaEuvzB;Q{}`&f4tcQ5p{WQLN!Fq^niC4w{=S#16~O zb5dbEN{m0hjXMOmMwY7_IY_7HV2qvXC7o<20ZxwbYs+3M$IZo&^=G%A;1GYBlbGSK3_7jHqb+O> zec&e3uB?rjV3@VBK&POio z11~oPVMGYuiG%S_s>Lu&KQq~P5Q*Nz>aFVl-q&W^c?@|?#9g!3l%9!Q5A2pG4tda- zACb+Uo<%)YV<-oXZtOq>Suaim@ckCJ~RSJKLX# z%I{FUgJhzG=5r;WngW(G$HClN`O7u$RW~X@jIqz+k0g?IPsa-#^*r55Z zMC8YnD|vU!y`ML>fQ<@v_OKFJl%6_kbe5Q9tPR_8eKAPWnj+2#sggyD3~!NLb_+cB zs|1ux zq-b{mXEBk@&7jh(`gEF^r{~)NzWaPFht^>A-;caJy8MKaL6Zh)jj$;wB$ycK@%*cQ z7j89<=D|BuHKs8w>XG3ttvW{IV4XkqhP;Sk`|pk9jkIvQ5L7fgm34ORyIwH<>;Kud z{=eJu|NsBrt{NvLOFH3qU_1V%jmSuMK-f9P`R1~aVQ~X=>`hG1M}-;_DQK4`=MQ@zWu#R{`}JLs|Wg4u)ufd2U+jXGrN4& z8tWO@XaEQq8s*f81unyPmwnwD(JWZ{+*Rf&YSpR(k6A|4zIe;UrqK8dI|X8l^X; zHI>GNW{+wLfI2RXm_=RCl^QPqUBS8!qzF1b)e%zUIa-d7tlKX}iSSoT4F& z=-u3az@&5I6+3DxHIsID(e~B3bV=7J;o;a^3f<#ua}c`!inZ zo!6GLvAEk@uZ_3PpZ&cdBfGpST;9ddrNe#+ibZIQLOcRdV;A}W6PSJGav*u0 z1KOLI_4|Y*>;7Q@{g>EQ+Agq;?{n+GOtOU)77No%AjVXK5C!9)+jjYY>xmdv8X2Yo zKm5%#U7668zb`OtR+vS5R(u7lCj6I5u>Q0u$og6XJMC`-FF`h9X~2l)_E@b`MiA|+ z@dnUG%g=v7;!!OY;OV>%Pegb#Czl*R7HABD+X<{_u%*P*BZ?QmPGT%QU&RCNj_F4%y26+P| zFqF9?h$;iY^OD{zVSXSY?7Z3oA`vmyg;Eg9{06A1X!~{_u0z(km7f@RmT}t?yY5K{ zfHDA;_z>Vmlb}T((*^?3{SQZ&$Jv9Mo{jGQ-C42Is3aUXvY~!W1Y2Tjp~Rx`)KL{E zt?+|T!9ELHkcYaTG-?L^`fq^#1?Xcy+MFSOJ`bLMKD2$6SdyRSH=#edR0tkvZEVdBFOiyi^Y-~rX3D_sh zm1Kt3uTFn+@Wns)kGHB-li(GKq9sE06S(IK0LNH=7K_C@V885^0)%J8K-S4U!=U(@ zb3%FX5}5BBX!L)gdy#Q$5Z);}hvA3ww7OL0H&Eu8@m;kd{?4C{PzF=SD5|q=fRbM$ zYjyf10+k`0G>UFwR}~AoN2iV_QjkOy2g-oX0ve8DmkOhrkH)G-HYF&`#HB`)c}i9N5C4<{tF(o zlA<_{%%t;eh;qE2YkTT-Q^bEfF9)I z=4jr~sP3cPJy3q#7`?i)gb5n;?BfGV3X(NYcn?;brH^*bZ z{JUVsqZ*mGn%iVYLOP{@10c7A<6MY8oov6E-!W7Y4_;+bU^P%(CxOj+ZCaI5T0uQtb!8bajL6e}T6kZBMpqmgYja{vOK<|A z3eG}$UwxE5%AuP)=XEVHL!cHHT4g}WqX)}}(eBbVjO-}#ok=ZP^y;I0is|C(qt1Da zG0Y8Tmqm1T)MAqr} zOuyM#NJVkrov3_isadEqnNdYev=bp8<%08dMa_HuI3ao510&aS3hrGD7N$EJ|JL@~ zOZn2{ED;aW_+eet8i;80jo8zVG%rZ$mcB(`J$nmFRB>Cno4w}7_O_zeBO5mM!pj^a z{i?^5*Zsg3rF}Odu+Ru!xf=yYY~*LdRwj=Oi{M8s)N6zwW3m_4 zIv({Fy^ljFY9f80e_rZCaV7t|5;=L*F6lN^37{08t*ek}&u6nU)NpN{S3#!+BxF5k zh&Ny?)@VH`6Kn+UfJ1c^ZJ@bXo7Csz0T2Vvdn;$&tot+kGgW@TWZ@6z&EotRD>ID|IC_;rLMSPxA}0gaGph_1tT@ z*Ximu6F(2$BdJKi;6D3f_;%%xcOQt;7U{5|*rk7a{gZu`fq;(x$N#I4Xk20yu9f?x zp%=~w2dOq;TBzT9u+_NbBKbh!ENANxitAbP2=Xe#Lizh^@MEY1v+mwy*z7tcnx8hV zPoJ)_x&eKc{Qz>=;N866=`-pLh6x7)GytCp$t#k)JOR`xi?Dh;m+p#$MZ?p5_q>z% z1yMhs@ow#u|; zfE$S0UW%vW3rU4S<8ntgpTPkrdbo`mu`@iX5iZC`16(8YT`m?m4oU5p!n%|@Go9?Q z57iZts?BsBu>3oX7Wn0_Q0*-kl{-2NZ!oIdMPkmttEX(I+5h(lFCj-TdQuY$|HLSn zi};C2zzFt@*iz6wNca#hm|Q%8nD)cNuS>AIzk{-4V4@}N3IT-8$nOE4J{?L}h2d6a8-p?ayu|c0Gwp z>&p56I@L^$whwf_xGIfJ_2=$#srdw|mf${m_ z$JWc|+^@s@3%30RFdIHjy)#xu9Lj@lGd!wJTZgZI(Qaz z9*wu+EqUeI=#EY|GNB%H`k$30$p&&p1;``bKNivwAh#3>tD_+)2E^Q$jEc^rLe=)l zS@IH?ct+NnNFEEI!5Q$ewgt?jl|u=7k?J9gdD43?T+KJ>yON`K%Ib#TrEv^BoK5t& z+O(J|y~g&_fH8YZL=03|BfYQsUkLbeJI*@Vs*7BbztN zM?$jZsSkI5`@S-W`}Zyo-DMtOrlS1h;x@=HF1_idQzJXFT5;Gs;-0Dv!d434-~QJ5 z>KKwN?VaxGe^^jcu1%LHqYKLzzWCnbG1CnNT-zfbTnc65bG^^|-xLFi%|1L9=c4+eW_xw|%!~5@Lb`bWHH~q(LQWqV-#X0E zo-Y`j1B8r5uUYeE(-m)VOm=v`N;);%%HNiEv+iem5RvibJXsYSb=GaO6YI*uAAz{j z=wJ08mw?*fI*W;)Rp4s#t%xF8^9VXBaxQ}gmbYD`l#w5#Z4Rq3hQEJb#zl)J`2!+v z2Qh|-Pcja*#n`n_I?=t@!~W;%WUrLndmc&4C`79W&y(#H85J`N2F^G{^aDWp9mcfJeO87n;?e`TshGnw*(&6!G1@m%x0UkRlkSUB|j(qzZL*!EN; z%g=J!Iy(>%=D^zvCT3ro`5vq$QP8_E2ZK*~4+ahfGl=O#a{Qao`}zam;KY9Pv5 z8nE|yxWFK8>Ti9ZYT6Q1@nlo%zL5D(>6_7qUj&AtUI_EZwT0}8My&q*PKbVD>-!=W z0-3}4g3K+>ZxmmJqC?HC_}iMJ?`5X{eYsQWO~gOT3)VKjZ0d}?)R6?scT>?Nb8YPL zmj~M;@2o&uh+6&X!NP7)6H9~B)LBF<@3Lcd6FN9n63ZoWl#gok@ zSv9-yOMDlthuTx6=g$qGFO84f@(2W1tp?Hf+n4bNesnsQnX%KS`8g!j z&EGqFjL5H|sYvwS+c{6xM>hJqJI${@>^gys%9}R^IWgW=J|(aasnQ3Z*6=Wo$RT|f zpG%D+5mI#A^)~Br2r zK0brkx@d82%=L{SL#H>RMPHD9HRi6^#sEBoHvo8X*aI2X@pE0{P*L1~I?dq*;{ONr zPloGsKt-+hPXF6dyPo!E=bS|}&E|pj(F5b7Rz7AY+CYm(=u^I_M!OE`v>!1)*NPOpG9IvvlzaYo zrNddJBiF_xbp5MfHVBVh05>f0)ZvfI;Q8mng#e#%uMoCUErPxDKIA3)$o9y;*41E6 z=CCmf0ZE6kLH61VGsS=qc|uVnvS^>8fxEtG6%Y5z713$^ptq8wCUb@w81`ZQ4#*&p zzKTriV9T>m)b3S z6jMDCI~E97{wTCKRtw}f5=$a@I&Y;XIz@l}PE(TlnDyfLm9UGeRs_ z2sZnwQ<&64TxA`BF-*0c4rx;oVk zCd2IThaxXoe1-Ew@s85kZy4*8PnahnATa_z*K7n*v5xka-@OZ`AV)h2Sa7)Dix{sz zt^Zo_R9XTnAXfRE^F&ME;x_kT(ktg)3Xpvq45s7Boi+=;#~fGz!({Aiz1Rj|g+_~` zbtEE3x1Zlpxk8(C4EJ1p3jApDLU^=jWa|e3Kx6hMNMoGG3v-yV37z9HA57|dKKPMl z%zvW~#6)P&!nNJOQy6-fQ?Huy>>?w~9~NkP)TO2rS^-M&Mw#H=+(_P`IS7sq3{(0hK?L$j_^bq%| zC0`pdkh&VTBDeXAn9>Lk+2W4r08Bk?Bh92E(qNpqSzCSOb9TGCKjzs54`_{CVU;M^ zIR7Uz1YhukZglDu)77#rIOO)^*SDaW%&p+%Ok*zV5=w)ZUUR96`Sn9GdiD zzK3AxeG(jDO{+VS7}S6|A*I0mdd$nX-G(?L@Y>yI2Txj`)z+_RkBi;sx07`z=vA)< zB6aQ3o^0`YzusZ`IFY*Gr~5fAL*;TraG>sCSoopp9fTg3x8k{3mfTk!M*h$H^6Q9H z`~)A>RtTzmbw}sIk1h83NB5ML!vyc=sxDwUrKduAKUJ%_tQR78l~V9pIk*)@noXc`nU^WMNAg7i1jvWgfB%fqf-kAW zN9ERBO$er4w9cm|%Gqr%p>OL)=p<=crax}%eJTXB#NINWw6 zXVEa}g!Yp(Mxakyp~f7uOSAk)Z6R@0YzB}1y7~?Lx7IZ`-V)BHZ~dxHryL)NV|+(z z!3!PAFTy%p-r}))%__=9og zexY$$1?HyEhc&F2?7z;L_CBI!oJU8^eZ?ql(~3>Yar}?C_1Dnk?krpsN)wB=(QZ1C zxxp_@dGId;%sfCd7fsbH=kH~`+9{`SSfll?lI(8rKbL)Ba#Y~}AuEb85Su-rsPaTZ z+(}k*?{y2GS0=L}BU;n=)*mCE2lY<1OI7GM(VQ=btnI#fzqV>e_aPWmF0|Phy()71 z(nWL=i|YQlJKmC-j#3qGoxrMBcnW&!AH^1l+NU6m=(NMJb>aa!E=g(88LMa^TCGTX z2mrd7q1EsdI;_@;mFZa~>F6?HtGWvavDwHY;g%j&WA@LlkY&>@mBL{Drn*G&8?~=s z&i2)MW)QThi%ngM7V4Gee@;h-%qx;|%iW1a-yyG2CHQpurbU@}hvn6#s~2+m8&eF~ zA#!LU9uA&bi`t;l->q%hMOrC1u^lgSFFTr)hjL`m@^n8i^i!*_ZL{ftx`Cw-8`F-K z_w0ISZ$8s|&yxqd9_%%nz50+<Y3Pq?*1;_VI!RXyx+Kf$}##0-!<04yBjck}ZvuM2Vu^-PMJTX85+`asjC@thzufa{#9JY1e!(J1x7Hv47Q&UB9chL; z9Ik6i7(UMHyv{-N5`oi48)CRjfIZS1&rv=!8=~VVvgq8B3tsadqt%Go_>2$|qLp?` z<8!Tq2ZJJZ_iti%QpKED`_SWw8%VBv2c7R^QOTWTMIr#pkdCU z&=j^0FTO&ne77hXQIxQ%A|+66Aswv@nk2m~j$jUQLe3*uid51^Oam(5#6F6+)shGN zOz^r7^6b04rAQ8ga06c?0+g*_z`?y2CaJPkbvx$J*jtDfI*not2DhCV=z?{wSV4b^ zNR{b$&uedo++yQMv9l|aSEPnU)&*7072p_-7qJneepn-Mjxz5=;usm?I$H~gI_B_E zNfZU^`}DCxACyGN$-w#)_t)JR-BfWF{8#Q-Hf|O&g))&zSj= zd<~F~9o~Q&F7e7@fqz~0cnS7`)}?%nRZ`ZMd!l_7&RMB5G52A^s?hh-Wj;-OW|1`rnxN=&t(9_4!d(MS+IG{!JNlOXEU1s zB7TN>mIwYQ4$4V~kBn`yzs+|6>aFhzVQgNbEnn+2?1|6b9|+tvLs$I;NNpP{-6=T6 z&&kfaz&VBKx}5G=_%1z8q*h8DOkWTJfIfuDoPQR|aY{8>c0o2AuXc*p%tfO&n8i%s z7+D8@%XswQUw%s=yzrM)GHe%G_#(Hsr|UrvUllg~V05JuAddkuY0T%kZ+*qfD5GK4 z&A)r)RNQn3@e}~`)!3QcK`=y}8?v}iXaJ>XLBBChH9Cl4U$`?qJpBx|!m-$I1m+)} zmY*Gi0(c}lTDJA3s6O~51j)J_p%1{kCGCDQL8Jzq=Z!-K`wQFx@oJeDlS2R}(esRH zf-BY@etzn1*tTeu$e}xCkZ|{Q!=posMvH2;k7Mj4bc|^9tphf%)$KBECllo?lm+1t z>@w88jw9eE^hcC$JBkIRx2jd}Ln(il4-DRF_u@v|u8VQ@NlY=_iT=9dtIQWU5kx8} zjyFfN-jlyVj%ian3G+g-VQ-oDrPr_8!+n48`I(I-e}j5!8m9ucBB>vv;_>|pXYWHv z_RiPWT#Y(25Z$bMB~4^i{kO*wvxeV-X!M@l{Wlhf^4!Alx>Z>DO}A`lf&{xsBGpW4 z)s9eXz2?^|dn%sbn5Qi}Qo@R%RXK9Nm?~MWt#j4n;$t%?Y0v;at!e4o7RWsw_W!&%zd6sr&EdnglZqTZ9=1) zz4d9V$($Ev-29uP5)La~496#_?6(uV!+yAm?Ln=%VE9DYa%s7r14C{DTH-hvGCW=D*@Q6YLvF!ROvEOBV6reVvtCqUP0Ls>7Ph z+&iB7?T{e(w$s@}@4*`~+dh_01L@j&HJ#!bZ6^Pr1jo$p1UYwySGs9|^&D=lbK18W zJ537?ZvTSl#$f-1Uo8|oZ66xlXRYOMxUkHcoPFxdamLn=A^VK|ucshGC{)@`N=@H3 zfNzJ8Y~$AD`0>lCLgXkVQ?C0xMs^XGH_xxXMNng2CdKGB(hsj6&B(>H=r`a|@wg1>Hz{acwBC8?n*H!iWc zvOr#Zrj@Hh1$8H*hQcenuvYlbe4kE(wJT%&yDOC@V+A?2`7TLz4axYXq+{WA{Ac8= zT#i_-;XgLn3Zaz%?srp2+}i?1o(7*1 z5*2qLx<9qaO_Up5aou#V{D9N3ZF}Wbj!H9T;YraO=Q$>$&SCllDrQk&)al^w-M*?q z1YrphnS4Azi#sWQ(o1SlfRNAB^f)gaBGY}Hl)%v5v4mz0@B5!1(~dAa#+0_ipvGq3 z1}2Ur)=Lm{1Wo3~LE1^|aUclBuZzE#)Rl-yuX5m(E`=eoxam32w>pJF+%lImmT*>R~hALqS_r z^`1-9NG}^x66~bHQ#i6#<6{+Fb7;tE=C$V)p}@_3uv; z6=)t1$XuCE;Pie#GqWmDR_ThX*haPkfC|JbW*%>amsI<96qp3~=KzluPj_3>%qsiI4@DsWzmI$N4kVi`3<}Wc9}_Ad`3u(_hfSJ7zC9dyX;`| zA1QbD0r%^s(oLO)WTs*WEI~0ipJr!Nt{E^-FQ9P^->E7=E#pplZ6C}9BHPQ*5%~Ci zTgo0}>{zQqigMbr>J5x{7ik}RTLe;3DFpw2(#v*Jn0)Fk!7i#0SF!K~?&H}6m|r>- zg~-XhAd5KyC~*RTW+(tHfuR4ydCr0FlK7?Z=k{}Bu1{f*?Kjk^$Tieaw(UH!myRG2 z!TK^}qqND+0=OxdM%x1RT$9Kz_kve~*z9M9BY@GmK_T#{*LxW}f8h_nC?lY9K8H3n zi7eLM5%@*M9@-BAM5XKYyQDOkSYKI(fiF3HhS9Cg3$HHY8sz?*FC^PjY#mYgo#WzBX5B@ zWWqVAMeI#s?Rw_;oj22o0K;N(9uOXK$LKpVTMX>}p8?I_CD8Mt7(2RY#`>@!hrxzN6k zd;O|EZGSyX8>=sXsemQwNcQY z$WOLS-_CtS#2Ajncp!`mW@iB?oeTtIyLu$16+ni1u&;#L8AO%DK<$lu2mV)@9n-5w_d5W59mPJX`PleA`W^yQX* zi+>tk0rF{{`(S%#WNIyN;4aLwi$|*jI2J9LfSaeX9taRzCw?}0cpc7j-F2dYU`;>z zr2=HEz1#l4F~j2Xx~n5f%{7Z(b;zEg(K8h69z31%VJY2WN7?pnUv4(eFjZp4tJ^p1 zfN4h-S}fCEsN6D3N(g=@o|N_HD2fBlYozSV{XlP&vsBCo2Xq9KD2D8eRV@1#L0f=4 zzi!fJ5~#z~o0V5qW4rUAZ)Tm(`C)?$T7h+-wyE==X9IN}}pHDTDq2EeR`ltK}lXcDKAwZx< z(&17ne-8*5^kYK4yT~u$mNC9Uztr_c`=iYb!K|aaTh(?&T{218u6CSP^WCda7(#yj za;MZ`?QA`aR2A+`O=5BufxM@RaAeTqJK;61EU=?UrApp%Wzd2B@0d+1w&9$(rsZ}- z@zrkTT(;IhqD&o8xzPwrJEUsbaBHxx4eiep&MM41e@6dZ3Xj1`v-)W&oV zB(&CdCvR&K@lEO3v;xHow8KPD9NRI#Z~mXV7Jkx^i0H<^-uW!3LwW&+ND;}hTTUfg zZoDV6DJld^O+Au}8&phufDA5$Uhrsw&TDRRBaFPZvYSu929+f8``U5&Uld<|wc~tR zH*+oHRi}l=U1{Vy5m&W}a!J;(j&v6rVSdUZUa_=pQ0joD_1-4wEp~X(8QLLEn56U7 z!q{H(|9~mga3K#v-iK_EGxTLBq1tYoFRuZ zuT84$Hy~85?m=X3U}G@UE4JFf>;dTgzXU@Xz;pk>gIV`c3EX_Dy`}K3_OWZw*#{J5 zNkKoDe_|cZb*BZ*t!fM$e|VDL7%dx~4Fy54 z;xJZH%XtWF%HNhKlY55qV^`Kf(z!a+#|uFFc(=jDdC0?}5yl6PF3RY7SX z>oEe(jv`}E-S_Lt*&xeq(YweRis@o=E=&!#HD{hkh3KUs2&MbP$xBowqV3hbU=WEa z9EPe3_6hKR*yRah^+j{0`FyZ-ZnC_DO!5#JR2|mVP&bgNHd>QZm^Nh-`fmUj`HYHt zlfJ%=D2Dlld7`1v`rXR={`1#gTt-cg02|8l^jqbT3J6IGNUZNd8?XlA4MT#Pv+T7T zWM$dcBsPczN&1vcCD_e*tggkwtp6rbnf)WHySnOU0d5AsYo4zjhzb1Omv81os>0SA zmH~1!wkrdK{dfRA{+ca4hVjK<27j|Lu9xuJVSRU;T4}5gist_JX?Z|~A|fKHFj7*M z-LQRvNt+sqyHumg$GdKCkcFV4Cso$afCQhNx@^NW&1A@;_Q3N*&3MTWHH9oE9q3*l zn1DZh?_eB;txrgb3va@{yBP09$EN&h_$1gp%XiL#clk5$O*o+C|q#HgZkkRmq zw+jlPA8r=83Jw77(gh}5>s~_FdRX&u_&#khS+>5&T+gN=!Fi8_$%k>h2Y!11Yv_kj zfCCsKD=EZjaEEzcjud@W6K~sF1=ns71*6;~h`cTNW^3r~=@D-o09`wRvB_Ja28nPV zR@x4Dd<%qB28V)uAM=HHaaAgviiiH}yXhLAh+}}r(XDiDlbpb+8aOx7|(yNTm+t%p736O zRJH0mcRKs8J~hLHs96jAl54%3AS{ZHKZy0-l_iYO2Gk|cr4}XlA2I^ zUVyA{6Zd~=hXdNfivcCR?-&GsHM0qXNL}P6c2z;+HB$a7fU2d zJ$Z9llKo?}bM#G=^hAVNsPp-+{_ZZ@k8k%u%I3|@@Kfl=;g14Pyq3P6$is_5U$G}m sphHJrN^AGikO2sTsSW>s`)zX}Jas?wR3B)0a>1AB9xLNqBiGRX0;wzrmjD0& literal 0 HcmV?d00001 diff --git a/_images/docs/wait_until_task_B.png b/_images/docs/wait_until_task_B.png new file mode 100644 index 0000000000000000000000000000000000000000..00b300eef2900f801c6f4dbe1be464bd524c1800 GIT binary patch literal 77478 zcmeFZWmHsu`|nS83?QL&OQ&>5tCXO^AU#M)GYs90v>+V{qA1-%cMl-l4FiIJfOMTb z-|zSSt^2lC=9N;I8=&cE8Xn|-?l@(rkn*7SfO}qDMDm-93qslI>sC3qNJp*dexl_8E0Ua)F zu$o4*qNYqJ3}k!yUKtymOhqMGVnb#F_;+@2CR+EUA?=5VhPd(RnVhylw_%;*tD%yz zk@~IcTna@z=1`C#9+~v5K*K-(XI9>472-tw6!?{pGDPd|KVgPMc4htjL&Yvol;mI6 zF^5JnlSBXYAxdn>e=cJQe}cgO`!AG<64UXRZj&OS{WG2`1D-8wAF!PM_tBeSVsR`gONi-f|o!YUmQN&kN#*&E2kWcCRrC z|NgD*Kx~wM#%;#Mzpm9{*2)e620t;rtE4pr7|%#vP~ETsFf)B>Yg4A`z+fv=MH+4~ z0pq{H>attL4$K4#VOI$hHDgDK@RRAkziVwu5;dI{PZloiP;=Oa;j&8yTomcc=6F+s zn&3A{mWskirEnVquIj4B-3gVVE5M-|hUr(fR*(?T9IF{V3F7 z^=QYYh6CG1MZ7zhRPMaZ*lkqB@$%14u3c^EJ<+p(yR(3HQTv(lHkOTGB{HMcki6Nf0$ zkz6skGkm*j8u#z5MwRBv5=Ez~S?RZ|%phHq++n7F8 zLALZW+bcTQgpOl=te9(&UPCQR-Ix75GJCUs1EVb}{#cHK%#@WAJo2mf~`Y-?XIo zxKJ-0MRJ4+f0ILB0&{z<;LphVvn8LAMfZ7!{qyyB51;+|uk+TqenxeUi}r?K#Gwmn z(!ctC96yDB$H=?5J|6Kfw66%8cj={H47fdJ^jL7|ovqE0^=TN_mS04=w0Ax`8wt1_ zFV6dQ_h(!i*HU%W1XwUFj$gCgU44F4MA*&OmXw&b_|`8T@YOAhIW(V4P01}8li2Ni z`$N8jDB%5<>Woh^fI4NvVO zpuE3BLhH!Kt;$+1zdJaM=BYf#CEcYyu1WUIAr z`pN5n8Jtynz&PQXd?*wSGn;p)gI(>_<@$B`ov%jJ#**rgu9W~0hXX!CMFsUeKiyxP zH}=2StSxa|Y^cpD9RxQ(;z%JoJ!(QHi*Jic7Ah?VjdXMpv*RnAe?@>Hk}{=VwR7e4 z0_0q0t^K;_^tk1EE^4%kLEk%kiI2dCvM*U*nE3?);fPG2}QzNuQvr8 zr;R;o9E=;?VYqb8fkVgW+L9(j&hcO?BjbDfJbP>MQ?0j`b`;WhWxWhOh^{v6qjBh;U@>g0pGPC={TlvI+$F6dr8n#SbAYK`f3#E{@$o!-=8yd%VyQ2~z_YVMxMyTBc(| zKNf<&@fYNPWMt>ZCne1`<`i4%Q*+ZCzMTQ+i15j((LvL3TsAH9(|KKnyb^I(|GlWR((?3E)75^XKtXX~+PW<8#UVq4%mW;Yw^I5Ef8|LDj$6Nho z1MG1}J&;_jG;HV1ZuwiUFB<6(mdL1hdAZVjPeNlb!t48vReEWf(zR!4)6p}-2(zQl z>sCMc+;(}8x0lncUy7C3m}|!NZ%dv)mpds-fZ-?t1TiiI7u)=jt8 z-*|I#7#~m#3kwUY^_{g$ofXEY;}z;XP9&+OT;sXEK5k-Nx;R9$W7-^bWVlnpkbmGQ z6j3k=J?iJ2mpbV11y-h^p=Spq?ywLMk?S#+1S^P=+{aCM>J-(}G1#)$=s|kATCdz? zQJ`{uxrKM*ewH*E&pzO5<4wKhI14K1ATsDE&WZHD_9yH)`JU93TtQK$Sf5aj4bC&j3~SJx^;GS7gZk%NNpz{|)C%c%NZ z#(;$d`OfDNZryZe)16f(Ka@zrPPNv$7d}NWJSaZq5A;XeFAcx-0*12ru!pw&a8n_B zMxI+&)&w4wD=Y9ZL(Jhpq~wC4?1IPCh0TY}D9JmeK}=E^kUgg`=k7BK=t{0#j^qNn z3;W6XvU6kitFby}`3W;yECHmm2ets)jYw#B+NQ{e%yLh*VMk<$>^NzATiXHwqHB)2E$2!|cD!$~7udSfnZzl* z=v~_SYi9wXkXM`(5EAr_L&z{;id$D!ov%dQ1D*{(;B8!1ZW%8M%syiGrLSO*3f z1DNbWhOxaeDE8k;%7>qH*S$`eVh+3?v5%KN3>YThr3HTU{4=WNklx0?V1#zRHN?hz zey?uXad0(|^19(bUh#fzj~6$A=&I!TN=V2@j?Xl04l$M7tVoGCSR`neks)9cnop*Z z;OG3oBHbkvq^TJwXjxy~mxD*U@XD{8U@qqHWy}>pw4}g{jr95Hywi~1NPIeL8ZLjL z@-&+#wxcVs1D(IU@uj@GvJCcI@$bWxn&NOG2C}+OQSNdxMchcZNe`j078&82-Kmm2 zIb>d%Qsn1oZTi5z4sKPS@i;g=i>FOd^Xc5+z=q#y1Kx1waZ3v%&W^F;W$}nQ9%sx8MOb75XX!Rs5`GdAV!!`0qT!QVJJ? z<~LcmO`CU{uLKKA2lg)guD0anJz9Y-Va7#Jtkuu2hwHt#mb|a4`+D#%9PpBk#?V5U zopH$MCHF%qwD7uKTXxa0tjCB9;|-7C!m0U3ZBqP?PNF%8&nQ?p2|B__&q7F~`mhA_ zh6P&AJ8D&4P&6G4@L1h%Cm4WpVQ2s$0MyeFalU48)sD+pUHS1lgyj73mPK~FU$Kjv zH^=%a=uKAqv2(m%XwUa|k{=l+NZZ>y%$h{kSdft#Q9n*c&_^msaWEtG_M4aE zXbY&{0)rjM2=+|z!u9&vM9YamSN^+_uJ&>aS-gIOAMzm%T0zY7-Gicg(!;NtPQi_) z^ZTL$c8U@%+hxu5{RQ7uoIZK6|1l4|aTs`z=&?Pi8|4ss$lj94)-DM=x3?O8( zvgxh-NI&~ks{Qr#n7TkZY}T;$LMPCpM~#?|Sm3+~jkHsCWJ8)6xSyTRC6E z(AQg?qEcae^e!y+1+N*);m=7@bd4sT1Fc(^3Jua>qe%<^2mNiq0uS>)3hZ`FT`CrSqfR{g45<&bt6@s?dq$2UcDj>xuyyv(9lOQ?0j zqar<3eJ5u;QzsZNv%pY2a`)tRH zwR(3S^-b;M|IQqC>_>DY!@7&~*{3|78KmOB>mjZCCJL5c-&*3@rP9v*MMW704cU=7 zcsE`Abe047T;+b%0OM>_3X2+-0^#h=olW(j%No~yMRBJIvpU~fdkS@RYfUI2VQ)i0 z)mQeeiF^$7u8?FIL^=@te` zbVIG1ZyH;HX|$tFdWycqBvZ^t)mramBw3M22u^t zq5E^oL-(hamBBN*kG`qtYJ{5`nSc@KR5i>erdkI244YB)WPES2cU^uG9YlPz;3h6k z`v4?xfNYocuSopY!sZ^AWI}>8%%4$0WsCTc9A}q^uK8+4AGk|)W|~dM0PeW|_Nr=K z$rgwI$u}OG)3{7=SF?eNbSh}RTnTM)udCQ`s#Az1YTbg;KMUW$_)%)+Uwdo7jbs)G z3j{c6MeG)n9KNFiu@}V^Jp3jW>yxV0o&qzZyQZ%pj+4*C;U9bt9?h1e$HtIAuV;AK{dILqFJXO;6$^fJO!Q-2e zRp^B=c?T8dj(T5MAmiy%D&=_ngC?+B=ztr``;XBlo|H7JA<)LlElvc*j2@T0&WMTO zLaDzjwBK7xx&O8BqW()04*%bYsHGkx$}l2ME&*bU$n(b>>RW8kG0S(hH!ZF_)RgtJ zO8zm9l}tR!r*yLoak1@&VorL`%OpGf?*+mHG+hMM;8)=B{(Md^- zicK#zjNL*pMj&45t9TSr>6L+zDV$4*MsNCK`nd+N#E%YKMQ`vEJ)*#kHans3t2q?k z1R5Qb<^LN|P_+G4{XijfPNPG5fK;X6g}tqUF3TGKGu0#Z z6Z|s~BKiFo8=XP_^7KpNx?~5%mz?!WrfMkXw(nwU!PY$b3MjVDGSN+o}fP5KD1>9BD86vDsued zM-Pjr)5OO&e$h&LMO`wCd!K{SgjO=|3Dp6y+nA^RL}sF28LC*W!*GEW6uOnHnfaS} zQ0A15dfUDEz=ksi zJ#JOW98)>Zu*Q9fg^La&?5%8i%>gXXj#fDOp~;scap_`qzHxf3qcstm<(bo8BAROW0Tj zzTY;5J#DG=Ysoq${NvAgJNeoyzZFskqj9;6b4uS8+>yCnMn)TK%_V|?oXeZkl*cj} zFA;~IBErzodqgWIaTDV&*18(zPJ>$H%x2dX;NY=1oz#J`F1m~D9ygn0n+Oy48b7@-yb+uf6@^uc-@RPb@7PovZj-G0#G*6tJ42e%9lu?qd zWUh-(Q)lPmHVy+H(u}Ujif_)BidDpJ5mq4TJMnj$;Y&#Ok-KYvZh8kTWqofgOcLjh#ea zxvzH<*M8FNVEFmo7p1}m~Ua|)EbOt3D*@=31I)>dhJQpnHJ zq=XqMt98zW0?&FyP8tOe&j^gfMY#%0zVmuHCtULC>s6|{s?0iV~RoU5{Ac z3Q2i`ryV{~>Dl{iiovP!coRZiQal_1Bxu|OBqX1=c_pUZIM$K_9LitVqy&B~_7_u_ z!_`Crxb7<{8w^IjKT$xWGjVrc>OAmGv(W6Ygq? z=^2*M{O26@vsBVc=XurKWQxhE^!6>h#INhnczz#v5@PBy=VnmF;~)4={eLLd24CD4 z>WvVEgdWOgF%~iOLWDZFxAEiC4TYia40L)t?98cHdN6{b>bs=kYwqUatsZJ3gu;ml zbsrd$a!hy{4L|Ht|irE;V3)bc7-vN&TA2@O7V? zl>t(vcZa3Y*$mKi99f@yh(mrMN9HCVKq@K%ODI9Kg z>D5Mc{9aqkw2)!LCNFAFIT>;&OWc3Ql;wDNC%hyvwxnqCflZKOa(kRb^n`y zYQrE~Ob0G1s6paxbAI=|IF9jrsOyPZM zQ{zd&!y*7_gbCUECP0LaAswA?(YQ_TJannNA75gsAViEX8t_$p+g_|?5AP7ebqKyR zAoN|VGtACZDEoL#i+0g5wpPnpBotcADE6I*a3t;??x*5`PL+6Ft%z~<|zYzt|g);^h^HH3&-SU5CMz-}pk7U?)T7de_keWfn+Ofm# zuID#VMb1``$9t~>VP56hzQ3n{{2nD`z3uq3yeO{}0n>dBjkJ|_or(R*=|AE`tiMo~ z@Y9Er(C>Jk?e7r~5;_d9r|=tRKw+;P~;rPF`Woj+b*A5*K@2q6#`BgJS}Y>3F? zz__Z+`Mp6E=DG*x9$2%8HoGs!!dTA8=)c+@jkEC0`DQJIkIr&51jcn)VMrO75CJ0W z#D!FwnA;KTb;2N@@RVdP%+#1Jgmf8FwutteFnSEbK^}6rR21lHGLZ~jqz>H?71U_H zo-Y`CD9KMomNDlt#J*viV$sdua(jBu9An-t9DQ7VBA?b9y^}Jyye5pKb6})d*$@gMD*Ms$E zM%txu8%%}O)VqjfudT74roCJx^8`L0{;70S>{vdADa}`qVP|()A2^#1sO5=PIQDw^ zU5!WG+fO8jM$%=~?RML5B6F7O(5LD*mcv%L0;oIAa$LTes|!E3-lsk}a?rZJ>WxkI zm}11Jdf5ETnz>Se<7!ufNhozCR(#31m)^t3t!8(=t}NSQw(^gWL*-B)I_AP|+1Fc) z6bBQ(lUL%N&Xp9U2321gua5>UuldV+Ue(gF>&dG_av)Gh4py(eaHGusxxG!Qv){P zGyf0W&A%_Ua_bxfTCXcJ#ml;e@OCHT>8x@2 zW_ZzSD|>(1G=R9vsL_3I!J%%^3f8VUSq0cdJeilWe|{)Ub5n1bA$j#O5)%$HIVB_Z0kUBigbpMs+X8juO z{HgI|%5X8o(9sqKx$k|lvk5r4Cer$F5`ZgkEqPs2dF2QAkh79SN&lJ^pgjGD4%!-{ zfZ~2&MuWVY)7 zS1BM$Iv#EGJ4VpEJ3F=B)P8^>)2$nL%9?~XjTqwArDPTxU{JswEE@_q?51{X+^dCh zX1l%Lo%ojI1I*}RY2*IeX_~M-lnp&eNEVsasq4{AsSgJbEjZxj&Cq+U1huDiqCg3h zVDDUFSXb*;@x-ghgof8}R)_j^_Y?#V#Y%k67=dAUv88rk( zu@4><@0%cm+~Zs;l3jnX#>+tX^Gxh-R!IW{qnU#5e;V-Jo2$`$4h-e^l+{GkX1v^G z-(KY)KgWvv#Ri2(A9Dm;-{fgH%yF*z+q~b|;@%R|gRdG->Fp|7{uzaiU?(*=`Dq7 zh$L@pVJ5p`v>n>c<16#oU4UPy>CBR3*ZEein6jA?m2k|$!HX=<5{l!eOAfEKmJKFR zXV!bJ4R8gT8VX*HDR``1OFKViu;%aynSRJcs*!FTLr8dR;j%#vk@hRs)v*yLks77U zzpVO?fC;w>9#NWiteMn1C1OHe`*QUC@ku!Vq}_)mRo>Z;S?kes(EHV?G@lKFS;-YC zezDP2lzj(DguEoF$0H-}Tu%el%7Ilx&#@9b>BuzTXM#XU^}0)i#g2eE^vPd<96$OL zZo8RCvu7gUi#DoFU!wZsVFmH{`oIwo{^oPY^d3BLO6}?ZATE zM&SToi;tDN=`4Lfsz%elS38ID!a(?@gR2pY`+#-UYIY|G7^wj_yQUnW9h>FE>h$~{ zvJOxdQ|+i;ac5YCj1Vp!?7+(F`mi?>7Hdsn$7C65tXiLIF0O85G<%j|SL&k1;Pn~* z4+;*cWkz;5mcTc38O}I?St+f&?V`{o+8L3xTx<)%)I`t&c#eYPq~@39Dql`&Xo=we8;J3H(UPv1&++W5XGf@8Ls1@mHa|iV3@IA101FN#(I1 zB!t|Gl+1B~7Kn9pT)O99(mDyAc!9~)DWG7q{F5y?7UZ)kCVlF3|B<6?4G)sgG0vBO zHZuzPxs=V%>x##xbq;eKAyZu3vcy!JRh#zmr8zICdM|H<-hm<1?u9qM-}%+&`oizw zu^=I5{L`lUg2RM4KF?+dg3*zk$J6g|^-^9)We8i-@2nllqN>0!=@V@^{zJss>M*@$e6E z@!mUO*nN%EYy1%fctUu9a9v^1+wekL_E9&CWRPYpB9IpD9vn5#u8tV_Sg`beX=`Eda9C@3mujW$}H$I z@&!bqz-Z>EU~8gn3&vx_l{0c9;lbpW(wq1nhxP4!hhYWbZ^kF0Nc~6tXGS@hKs#~xPj|conr@eiSE<~ zH3LYg=o4p+H&2c#5`7;O5?<^(kAIf!8w#7}fZ>J;?kQ+V*5a})X-`EY-B&Y~&3{gX z-zICsbFmm`P(UczNXtSg#O#K|5IHEW-wO+>ll zbjiRv*7_bXq1B5kUu|4+;S%ybL3C$oxRZcAeK9O~r6W0dp0opcP;h7q7->b!TR|=| z_13NNJtJvH0+R$ck|3kWa*B68=OKko&?KP{wR=C^_@~6!UJPYI{EtCKR^~k5SA{WY zO7^SXksp;;#;UYCOf2qX_J4}D56 zJDgYIA0{h#(WzgoRyg9ZV3d@{9vZE>7=q(LL|LRD%*gwv-Ip&+{F{JGckC2k<`VH~ z84=itK@u#tE@-NXj3@yM5!n#v3JYGbomwSyCTWjFCW66 zUB21Cn-p`H!&-Oy?T`Y^a@*FSmW?(kc zejo9s8*HoAJbj&z52zL(8Sr$VaD=F5caQf6PGn)G$Az+evD5Pp1Cf$#&msdYis`1` z8M4M4OtF;5lo(Yr`3a?h)FUgaAM%^<1SXAoShMZq)TXKPMzHFIqYQ;eL}LG~6vY!n z)IB!jcg845bf8*yu6UF6fbp23vCbt#&Q}PpDd_j(A7&pq2qNG|f~CamJubhtx;)%yp zY(vWH9%Fn=g#grvxo|IxWKSv$n$_@tBgZ^qe=V{e%l1dq{^R|nw7YKr^3g~2BV}>m zQq3b7tI~39>PDQ$o|QQjzF^w)GsikgW>o*cxBt|~+_qNoH6RYG!Jnwn0?Vsx-b1G} z_19RXAO(PAYNAaq$e?XS+FTbb*_e#dp{3y{o zl+}*~0TSU!<*mMpdh?VGv3;U;yyxOKH6`*MJsWRl?YQZp-*DI&rt+9NmakkWdI^$Y zpHEKhHq03A;#RCANWOyOD~&TgXAzljzoaTY!+;Exgd{%ua<#jIf{Xvf54cixEhJnD zG}_81E0-+(SaE&lNuVt!tH`fpMq^}&>b=Md{RiSexxfEu!ig~{XA*506Ds{t&z<|& z@X07oh@4VbpLvdrOgxI<>6qh=;cKh`Ba5}JC@MdZxNE)TDkJ9q03PN8{{YD8Q5U)` zPM^>gHl5^VpLGiUe(RmT-H4pu`*uRtSO8BoSQ6Xmn`rU#xmxCYGGh6JEdXEy)%1IV zmv?+pc>a@apar>(ntNfmCb`5eT_!&jQZo^mBj*A3x2yde#%PpETTa!KwE z->1XN(a|fsf-B@X>2iiLd*Y8Wr~7hakp}7Gu~ok9&r3e}{FVs~?`dZk(0wxV;|6A# zm^O$O8RuNN6-O`KU^SG1J-FkGjh598HmKm)_?#H0JStQH1a*{ z)^mDqtJY1&at;vIwNas)2d#H4MaDjhSFdA3sfD9sYp(vjRkpE-tU(I*XYuxM;ikGU3sA~&0 z%}P_rQlt!LSaIRt6$%4v!~JFf!0umD61&{pQHJniPLvo}3A?(1}1M&ELJT!2^4n1@93EiCyQ>sq399Y`hq((N z5LEHK_{viX?;vK7nMrBRWM{Dlx*lqTZIVzb!Z2+6Qv?p|4^xxalBb0Szk(xQRByI*&TP z7er$wZk#b!%Tb9At22lzQylY9rCgU|g2(y_Qb@8=FIhAIwDae$pN`6dXTh5~xl@`G zWk1F+h#X$Bg52riXE2Wr6LrxFtzBD}!#8ySNMrIJom}{_x%sDg`>G+tgGUZ?qIJ_I zJ_aoN%u3DOQ8}eg_N2P(xe%%0nxBCtvB$Rx(1vU*Q8( zD=+K&G5m&L_V}BMQuLHkR9VCehR3lel1Ug*n9;wvL*d{lWD2}K>a=U|n_Ics977I( zKE-F@5K@?SoFdH|^P@;#z>r@P(GDn6)_H{LYM$Z#8xOx8>Wc)lbZcICQ+Ku~4eQf}Z@hdCz zn3Rw!)FJpxQtcRD7wv>B5hfA|LDtt?~DCu8kTf-*&lTiGwIq!aSvHWnDj z->o-1(RCeAHcCXxys#;4GzhsgFsU67JS@_F(Y3HcIk-?Bzg(V-wo#Wq3}#Lp%KQNG z>ThK=!aQc1!r6(h0imO;O2?I}k_?FlsrT3nvPlahtR(_A zr&kRA3p_mvGBOqOwCO21|Hra_Z{GCpgofU+^=Yw zq@E)ng4hi%`<-R;rE((6B?<;>rcE+kWu`jNF>&DR>M2+qWQRM4Ftx5AYN$UQy~Qn9 zOCLe+(nVG)0|?TFCe=2H^|}Ch4Y(0+A(YJSsLHGbPvf_qLa|?rg)hKL+u!G5WkQlj ztOS1K#p0T;*Lz%81*|%57TWAi@2Gl(<;*lCHe%cJ@A$&XpT8wB%f>br=&b1I7olp?s6A zET~rb?Ep_%wM8?{F^t#{$%a&hCBzP+udY3F=?({oc#Bn#q=MvitNT);u;Pqxo!Qz$ zLgBST$Uw-COnL7o^f#ngPo(&mjPaHM!Ho9zRjWpAdEbU@)5X3EvcuJs@o0Y0^uDp!0Z7D2m~#KgQnp`1$U zzQ&A4G~IDpYTWn*%h7y+Y3nOdn`^&tX~yH{o5y(!^uJYy?7FB4z!JH^8xWrV(A@61cF3h4$F2N>a71QKa zfX&P7`bIQ^eI?Ik*IKKlFD3at&My7DpCBb^X+n$EPsIz9VlTY&;I>W-@Kk-i#aasW zP{j$LJZTyT{M#amf-zxm*6%;dY%*I&0E+mnRe;le6r{l~k#f+mTe@A!u~t6erLVzj zo9Fib1$2u$fleJdIGZY`E7HLRl)SV!svU4KXd3(nUB}tfG8fRnD-nL7OH~^G4i&2- zqGp1N*rya1o(y7AKWA*#O^*HF#N5^!#HwT*E^vP0>G7K+H1Lm-eCA_HAX2bI5p|^h zfpP&*+-GiZ759DfTA4_irvt%or8k2pdIsy~cmTm-(i#L6QPtB0_j(x|ftr(w>je-> z{S$U?VE6t9{{>3N%Ib1w`*Mv!KPLx8U%p)NLDx>coSY1;wlY&GySIQ0Q04t0Q~YhY z1EFEblVMGa-xb+%wF$SMrG7i}Zm~QH){cHoroN@&0VVLSb;Dh4a*5;|?yh~M{!BOO zUM%Bk%1Exo34v)@L^U2>wHwn3MvC~p8W_QsA-n`&nl9xs_4;b!9?HV;pMgNPEcf5Y z29rh)%=Q6q5}xnshLBkNrY%6}q`)(~mQ>c?U(k|02ZSp?1KF{T>cRE@t)Yvcq;5e3OfjMI<*@iWbI)b?c0A1yo-+9lSBxW_T@GyGqhx`4>$dui{75}DYC|-VA zRm(u#OUAbZ6~X!AB7*C0y=7V>%C%iMJ)@;b4k-;}mlw$MMe7v{7$+2BexTKU)Kw<;i08GJ#;+x@H;3F>k-&iyCj}JrHd6}2 z@}kq-^dxbcuvgj-) z(SNEfr6c6Bm-Rxh4N2y_G$icJ2f(vA+{mfdNE*hiFx#{N9G<9ml067!QCYarnl3jG z2ju@zrv3*2K~L=p=5R`vX5tTyi6xA#$6tKi0L1ysN`J3WBU%yhl4X6A-iZ(nPcv+W z)bB;q5EIh(jxZcqIG3V$^|&J2{Rk5x@)kz(?pu+7yJrl$w~7z(Cr-NY?p8v7Aml<3&o^Jwq()Hk5%IqVG?CFR^9JSaER`yI!;#Ve z@4Fo2fPq2KL*SlU{&Sq%wjNKY_0*bIusquYV0s5xi2cR&td;R=F>BQUAuO?q6M*(- z7vaDSQUbk94*L+}2l6+67_pv$ct|v59@`ll{`&}B9i(7Bt^VcPa=?8$rTP|=NWqZ- zcES?6oh~^!G(w2u=mdVP!{HxtYE9A;6Twf{72Y}z=Ti@Ka!~JNFcn@j)ffL4k~sT3 zTgek)#2@sK6;8l~k0%;DZ>bX63n2dhl5M7RGW|*gB~83Mm1XtBF12Y5!y214Q-YDe z*{I5%F7F9unq72$Amaf`l_o;NPsMjLQSXu95_=h73~)!GAXTY@bZY0AZ)>E+S+_F| zHvioUp)=*9mk~&)?Q&sJ_vt^C4B+B(*`g6qRoDDR(L1FChRRVw+5_epTjQU1nQPk=bW_cba>ijcJRiCtyltY|O_* zuFsoh?X})Vn98rbM5I=C54c`TlpJ~=(BL8wtb;~YUo{Moc%S4wy2?^0`03sTw0G%H z-R5#-2*f6%RpIz=p*khr^-#gr9u<{jg(ayPHUt}lT+LR2!avV#yg$C!>EKNh6m}3& zYyRRtJrrwmkuw>4jJXL2Y~;T~(YT(A`iDAXrWcC9h(ewhWJzMn8&TT|X=LzjqZ>Ethn zd^x~I9}G;g4nz80SrKDYJ@*)(bWAsT9KgQlO1WMy{dZ*-QOw03DH}D4lFqz@^`ia{onRY|JHbTT-|5 zuC!ECJ%!f=m6$ICV?T}V0e}l6iaSv|eVq#AclD_DWzCG_oj59S?yDTG5u?pMx2eN2w}Z6zJL=FC)@0 zc^$zxE=5^CN-WEP=cGed&o*}*88K3*@(5<))zA^wK*199|7`JBSVCvOqp9iRzD#wV z14{2j@#W7A!mmE;d>;p%=4XS)0RsTT{MD-b)(?Jx%+&l-DiA4@BO-uABGT6Z;fZ?I z&X|hd$fj2_OG2oDOK)S%=hP4-bWA<$84Rkw=YB0gV~qp?wGmx&CPeX~zWv1H`*TFB zy|Falmkq7~U}Ld0cr;J2w(MhnW-XtLm4H3KS5^sDTn7z}02NgIJMXDt6H0_nvOTIQ zl=>%JzWNNz?Vu*WgP;J94OGkY8Nl0o{WV`^D(`V~GTjJJCezJ-#?&2wZvEQZ%~Vr& z6lXz?@)43P0$uHvST1daTX=)4WT#`WQ#WnXz`M~174KiKpPyt z2|z&;0Q3<6-J7qgJ29f3Y6f!8v1R}zsU?~2L#Zj*ey6kh0C52Ymd*9i9q^V3xJk43 zUv1SpSHQasaDw-MHujpW7#|@k1kE&1Hctbu8kw)P8hT)eT%c1kCIqm%d6ZPyYd%RU z<5^zPS#ScR$W=a5OkmW44k>->U)D* zR89tZk=!jg6K=?M3_j!z{>ZKuanJ&$ovf6Y>1hD;E56xTcEABZaqm$t1kAW_Q`LFh z;9)FMoomD{y=iS;thhM4K;{)W_Ro3$9S^YcG|~i_)2@4EL>6R#0!iK)t9S*Z=a{ zyhXe$O8Bs+-G2uN9wqonShT?_0F&U{-Q8V#hkDCIN64X}4uj_kx(7;2M0LBucBh7r zWeq#r^F6o8(Fu=basYMHaXt2bvGgHy~i|abCGmiKj-$NL8)e*#d zYf+>V=e`Q)L=AWo9RWWi-z`G;2c`Jss;fihyt&~rzz zHV(W(B(>*u6N~1vJRRf1jZxF6@{JHUo3U_@fy>knYWL+&n;?IGkDwgfY4sh!SECgm z#yNvdzYiTN$ppXKP-S9Bt*Su9*!GwETNG9S{Kcd8)~dWNWFDoY>y~9Q(aq3bg#m$4 zQpgQ-;r(Ca3ihMDyI^q$H+4$NwlXZkuN8ONqXbKmH-`LA=*zCC4cp0NAfEhs1W0Bu zCbod?t#t1vTJ=%tc^ue_WWM1!bP*^sNf_F!#nwinQ{LyhqQAQ?^=-FehwG>3D_CG;KeE z1qVklDxYqB0RRCo4e4{oA}~Z|EOB+q9LU}haMYNS?A^1So?N{N;p2T|)E-V@1Eev< z4#m#(U?XGa2?!Brl$KlOeRHf*ghNmX-V8=uRZ-HfDVLdz3!r(qb&56;^bM50>-9fm z1YxgxZ1xlBG&;?*0Mz5?GVPYFSL67F+q7v9ddImmSXSSe=_SNMfcW7Z z9S3;P6Z*WO24gR=^`e$X6{ZnjyGi}FljzAVKV?Gxk+taI_J29n@*LUL+_B`6Q z(_#lcM;sR(PfS&aT$+@ZssyySjno;6Ln(xdEg>TM#Ky=-nrRobWxSX%Ot5h?z1O%*-j+uc zkM&zc7x~z*tufnB{dKCM@fe$HubJBnFJ`;`GHTn^oQR_yImj2${2{;_|U&Hj* z3wz{E3f^XLE{eHqTJIUVs7hZSu0yF8OL2U!fjYu=JNjGX@7lSxSz0K+L&KVRxgp$w_+|J)PF zK}G@#x7Z74qcWn;;Lf4l@Y^Q<2#gI#1DT;~lRkg36hmrVIW8YrgYC*&(MfvyrHqJR z97^+N-6gG5X!YLbCu?P)joC6uU_ZcE^bQNlCCmD|%l_iV_gW^f%MO4d9=d^=<-%p*RnLyY@qxvJEM)Ld7`GxqIdLkqVZ+!f)qCFFhf1u zYeh8`b6LrCL)Uy~@{+QMAA(GS^xex5276Hx|oOteV*=Tsi^p{$8FvFwA6 zKB_BZDToljTf%736UbyC_w<YJ0R&ZiBu zSuiMS$ho(%M*N-?>Ds%%ZPMI5DXcw?Tj}ox{7(zBF zH{2!%LX{JE_Byb8DYVsr`IXLfB^`cB;P=d^iycdDkc{NRPe+DbM$-a#-OUdFQ)(?9 ziiIFWEc@96A!y=FB20{#?OEJTp>}_IDSUgK9nWc@R^lcld|sUqZ*UfUR7bzPvoC8+ z-(B|$GsgD_tYTV3tio*MUG&FRK!Hhl*T{z(Mw4egly+I)LpLJp<@r5!;Nvtfgeu%( zKYQeo-!0&^cKhiGF-=zsnuy-3v>I&Je{TH!qpVO|bOk*J^N5t45kHgYMDrm|82QM` zoRmEk&%3Guh6bP4GMc74zZt0G)wg0peHKJ`^>w$lzC>lLG@ZP~&&nHkq;Ac2wYd>g z_W8;%Wr*d_yyeEDLeoNRWoB375bCrI%67<5Mf3$uxH{d+rgtqykv9GBcWe%3Y4vx; zUrxY+FHMNpucdP(@QwAJWoirzRIscV;)FDUkn2^AE-E9&_V}K+t0v9Ljb^SCfvMg3 zUP?i>5dCWR<42W6c6pgJvl3z18tS6AI=woML25W;m1X2)4JATa1M2oPRBe9suqbxH zWeH{#h#Ay?a!r)e126Jlk=}QF+_+|rS>J-M=I|t`Ca%xuQB+0fmy~>^3{dmd(R=52 zeW)m5@F~i*y09Ekr4f(y@W8ijk#-wVn9eAisNG3pHRyVfa2E(h;^3Zr-!DSN>ddu- zTcYcdpn zA8?DZ=xb0#^F2C~&CNJLLSJJ_Y^*z?CYv94gI$@^@+2;kSq2fK(I)^Z)8kyOPLErE zPLIFf0f&584hSdtV7jeT ze~1R_mPbUKl-U%emY83}Qe}g%i`>gZ{k1|)x&M(UfMI;1h~TS$9-qDZmTtCZUTsWU zZ?l(YN_jWZ29PG{bM<0#;FKT&r1A_mJpOauhp@K;fD?0TB#(Lqh5iKPtKf`Nm<|zT zfE;X02%Ay&lZGlQGd15;aA(>zb;IW?DLb?MRvm&M5Bz>eqUgefm99%TMwpWnbxrpU zu=GmyqVLvz#io_=Ovy=l>We-x#4L8a9NT!a+k@0np5f)Qn+$G*{Q`PVIy_jqSw_Ty zcTs|!iE7LjWezC70gJQk>tPYP<<1b&t?CtNuawd00kze!>EQ))(R4*_%AR%|;r8Zy z{gUq$YNwxqKgjB$>cCI0rRReh&CrdhDLC>@c3z<}%FXFWH$}zvf2bAgkC4O&o7e!> zSX^>K(FqOu&9%-Q(nY`)Dyf71YQhk6Vwe+}^xW%Z(fQM=u??J_c z&Dz1to6Gm?$tr~$ba7px@mO@8)rC^_Vr~n{1Gq@Z!{lF?Di{My`XGhc#4mc#Ssu^* zbwQHI?A_~>8#XcDL@Ix9#?=Bt4_%8b)F!m&b6Q+qDh*YKltQ&WKkQWzF1dWAQ8NVO zf|M)Gf4w!5)M9Tjqo-}rX}1ceLU7II`j3mNhJF851hlz-5%a3P(h-QcGH_~`*;VSfR5~qfmRj^r1re^ z{_|{gV_fvHI}M>iQdlI34WW!8<-E*qCE7xyFQ#O zq~r?oKsjKwUpxPn6LFK@fDgrC)RVL6&h+Fm20{e^dZ&xyrCO9X*yl?*1F8W`cs^;S z!WoN&I$}aRLAgUk>kng6Uc+@DZDe)9Y97tatM}>-}-Xu(CTr6lfd4(!=c|K*i zXUE`(x8Wm#ssPF7DtK4Hq}B@DBiq^wAg>U}gyKho+Jt!M0(n|d-Pb209xM-8|3gsJ z$H|9sPhG$rj(Y-59ZIR8T1O8#(!3SW2|_6^_o_I7XXcBlwmA3{bypM^J=S`oy|Gcw ziv&23V#l^g8jtlkT*=>>hk#OK3;XCRi7XY=CCc{%21-~<4!<}0VyQ#Iw~cyhOW(F|%F z?SU{QB{UvD_H@sSdDN2Oj&td~Hg!AqiD>39uVX^WQPf1It?8+}7*vr5^^NsP@G5G_ zUU>Eg5EbO-xoo>Fpoy{Qz)MiN~YDdt5*0LKbS zsW}ZscN2tO2=n}r(wCFypO+8<$a{xRZQB%O>OpZ8yG>k(TPxL4mVPT$hs4S9XJ=jl z7$60{usf%TgaRq$Mvr%Rt^xwZW!wZ#P5HqmsHKI>`UY_GH-WIGviKw9NoxGE;FF+L zccj9~Kh_2FBK~6t4wr#WiaJ0_=|%bM&~E6A)iGn*`~B)(kRGBJGmkv(uF+*!T>X(t zX024F4|KXhv`(d}N(g#10&Yq7-$iD9@?Jm~N5=ugRGGRP5)cTw)==+2m}mf#Nkqjq zF)3-{O{<@sF)WL00#rkRYjW3aG>1EUen+ODBh^C6954)CCv-1adi`P7esSbU@Dx|E z4#UHGN)9`NEB+wkBECD#f$1f!_fbA5urcS zyNkkIbt_mG+m1FbviJ7J)_7R1NghrPE)v9m;eTF)!&Ch;cHdp;>zX7{=6`1QmOj95 z1mMTvafw$^qVd>Nu`qDptD#t{`<{rA0)vS>O`QPeX*Y{pjAtKq0r(}!^GJ!lg#PrH zEhdCUA!!N7l7w93!6Dn?gir6A%k+$qg-cu~S{A*sWdsK1te$jhW;HP5l1cmEVic}^fg+bmFZlTkjxX zK+aaDBP@+56kKW+_8xu~n-M7H0d%6TXiZv>)JN3O-XAUXe=sy%3?~S?7wMI9)bD(M z8u(FQPQq`kC6T1Z{~mEdfY8nt0btO61zhMpaXu81a~y-ez{WG$gQwxh1f`@yU+BFS zUxAWDwX5$m^>sLlncxyJHLkxH7wbrHhP4rVsW>~ni0t!BbCRZJXDM*H%Uw)A(_Vb_jNP~45}RBKJfSz`$@QDEH9T=If@;2D zna=yT(G?bc+d%s^CfW3Z$n)HOOW`M-vyX)D+yO>=&hdMq%uvySl$~fu zc@d}Sd%*gH-wZE~h1?s*XhI4y7692!&gVvyZ23LX>1f9hR6g9oxigAKcoBTPueY>C zr1Rgyq@{eM#$dPGALC~Pq#wc{MN$!gzJRjc2gQbyTlc~Pp(h%WQ+}aeVm#w}Q>;XP zn&X{+QAlPwI5Z=PFc{(QsJ3dc)9qR6bpXlb%6k}qX`T}2WDfFGaR)vyB-N3@TM;== zP2SzLV@I5jp1?p;sN{%<$2K1OzNt90g;+fjmq~=RgJwjJ03{AkHC-3O?*M_y+m8gk zUo=3QS7@#E(rq$c!-38#DOKdwYaQL_w|)mnpeUU4jYY`IX_pxas#)lapz=AUjw&3SEWDDP`D#P^{=NTF9*!$Vd*I-u3c~RU5 z4#Y0vXJ8A}$E-q_7}o;VTlFJ-Kz$V_;4DC!B)PboJjlmGck4RmMZbMrYSVjyAkhB> zu)U=riC_vql+cR5)4bPBg)d;-91mNi`2@?fA{^SVqdPqvYfohB6EFhQW#{Yi zl!{Q4te)WDP6j@)k=}hIwbVBp=vg9WBXBM93SdF!)=mt??)LU2w$~;v+nsDo7%~~! zonM(i+b{KV%V)H^Xi4hfl;c%ddWQFee^uEVBvu3WC*eor0T&X7s91%M8XQbq`@qrS0FXpCzx2$1K+Wp79ey7L{V+ z^!Mm;iVdN$gdGSPCs(D(Qx4yapKz4%{Ld-l<9IF8OO;5OQ9=ki44?LA73WFWHL4z| zs*^eO75bu^r^a);v*{r@rjiTG&Av)LCC#)mI;qXW%mK6=Fe)@GEev#%&`9GJ!Y9uz z#29EFY4Zw=#)}c4v#j5Kc<0*W?a<~B__paOohNsQE*=`wdcp0v6XTm)yf3A`5QfA) zsMZ&UZhjU;b26{HGttsy>C^e4ESF4Ir(!f}w;8HdOBeZBvmi?SInCr?QQNzc=AM2F z-!hUi#*Y3V$Q!(omWJ>_E*yQQB*E9_8{PW>Q+fnb{X(-H*9s_h^q(cHJet}{PzK;U zd17$jNq{1t*rUo(wWIV8p;UOoi8=5V20_zr!sZX;h~3tRhx0)a0Eg>ET&w3sEw)bY zqc;8Glo7q}Y@E7L8F0=smSg!l;ji{S=}Acb5R|wL6la~jU4gA`1eVGEKbL?2{~qVa z{K~t$$e|BwKi$Jd@`Q>ZWf&X$g7kD*zc=Dk?NZ?==omkm}xgN&?g2&ORS)iOf_tuGE@jD3&t$(CQ=z&_VVMpx)=Q&(5|u zD-phyf-QGTXJgoYiu(o-4=Fg|Uv(Y$NnORcD-kopb0>o(t^W_dP~pp0xcvL09fR=V zr0@Bey?ef!+&m%Zr8R+*E9rnYx%WG+?w2C$BCUS!T50ar@ojl6t@jM1?>TOhDrm_l zo)J9B`xug*LkCG8#n;qCS9mVROCN|%NC?5i`~vNeCxEK91yl~DwXl!uB2kj+B~6j@V{4SCn(Fl1Yuh%P#H1dPteO(OV=1Afen`E^g# zLOm4b-aB8GBEwVA9_;6VjinXDsk@L{Q$1g)xdluz2^=D~XXq(EO}#Vkz;?pUW(145d7XSKK)783+VrzSW6b^av&3xHWDM7NIFdZqdWn`JcLS?vRjD|!6kv{IGN z3>UtjO`EdTL_hx(UrI5R6B-o%Ra3XtIbW~3ghSCiq;*n!L6Y;{fcaIw6cZ-s!E->| zDX2eqE^PUo𝔖tOk|vmb^Gx=r7Sk5X2n;X1`JozNNOleIN<)*6k;yo51&9uxU6p zKSb#kyw6J#8fe^?>BVnNI*k}SlQ}`v|L30uOP_tZUyKHj-NMM}%Eoi(6{n;5Cc#zO z=D;^QB7KskuheC0x_|e@#cq5-22)b^iN>3gcUKh~hYg34Sfx}T!)~^WlYL5$#1(6u}widx@C} zCpOJh32rkT_}1%=9nG9m@tNaDaZs{pkgcBL&`Op58>EtQH_}dzK>}Q1q8PWsc#Jt- ze;zO~K&97itk4480S*&2=DW%xx0hZocLU2o;CG$!YI+dPGtwT1fGqvOj5O;8(Y2@G?sE0&3AiHsBUT) zf{*3E(Crt=VJ5FvmjQ5u`@Q9X6njbPVkasIa!1m=>~x;2aT&!2sq{FsacQTpfZvrX zk^qsJP2jB9X-MwBhX%_?04>0V7^rmE1d*jmhDi{ocLudY8pP&f<*&65 zKjC?GqW=Vp`zchL1yo|K^5uj5^coM5(!;FXOvG~ZQeodEqktTy=UW@Qe)Xn1iD!rtFK z`kgHeWpDtEgPfB=dkRDZwfJzwuT;-DtQSQGGWY|x0CtHMY$R%!6ih9MFsm$+@gugU zm(wyq4l9N+^U7<`lwP z_5!vsMFDf=6)|jm#NQ>4MQbMk>B+J*$)b^Jy@p4@-x}~x#~;VOQ$$1taSr4(k#RtF z(yu_lfL~>SXYyYFhY0a`02<9gWidpzj6+6}4bmfB0Wu_gG02%fv+2{M}cY3|F z+afOLB z5~`qxQovlb44ck8kzkXVu3xD$uU=2MM7cy^Ye4yRv zzNly8993b{-$}LsgC|Pqjab)1m2d=BQ?w4~^w8)4(n0&VOEcTR1k74NbGbKN^_tUi zTmvrqBvS{=n6YuMv zlk{p*4h1Yc{}M*}w%TdW9NxL7BUvZ`^Z%rrIl50g|3HUnskugp z+UY%|5SN}Q2Qdt+q*It2E2h&v7-QzS&%h`4yf>GBwj1AQJ(qTo>b~9j5E1H`(JM04 z`kr;u4t6SGg@zu3K4jG5U-oKTBuV&l&y8nGIJ`vVZ8~qpj^@S^%_vKZzsuOK#BN3< zE#cA!8KsYkta-30)H@=gmoGgvEo|;DoldRl+9oYo-;c*&v?W!{X8&35-Nd!$n*Ty% zVlf_X>$M+t4uO)^YneJVk6oHd&t?cGhg804SWW}gQdG1&d{>l)<^i+@NR~A85%kva z;oU*V!bGv*+X0VdfHtYMf&R~~j4$-5Q)ZNap-ZQ#3SPVVH8*`~8rtwYL z6p$FbB7s4Q@Glzo`otOew4Xn}!@V#m_X!fPXB(gT&OS7wnzc$~@cb-0}t2g_7r z@GgpM>RP0jP1oDaPXf%#t2J)DIPPVvaFX|MqGNEXMvR1A1`PdbW zz(q3&o-|RrT3hC+^Fo`?OYXPyeC!&OV;*4cWx05$CR^ghb}Jnk7f@4C>F-p;w*jHa z?a5t4rLN=Jnq0=x-G*T%Y9}n&J^=5ngWQaHtXp&4H zsC_I3VWe)0w4p$=^3ZBL?`?mZ{nZ}_(uVwU(i9W%8i@W|$??JC9{M*H4tz}cX*QE) z&dmGvh~A1y_{P8Rb}I{qZJTU@1`)zd%1{}+!$_vP+ha)Y;r1=Js$oq8{h7$tz3BEs zE;ZB~1T>8uqLQPCc!RDzC>PUrjQ|4oS41$qXFL%|p{SvBf^(?#cr(4^LRfC`%b{<{ z(Hh90UAF>9nWxIf!-AYsc{cg$uzZsO7yn*>vb{{OeBdWEpF2hc-Zz5I|m$qTq-e(Ac4L7(W>VRlue`LGR<@gG~9S{Z_n@A zL}oBDz1rzOur9JOeiI83lzUW7+MXYH23if3*{Mo9SFH**qKjyZA7BuHm^-nuu#(chIwXivZ@tc)J!c;q#T# z^gU+m!6+s9Yx6g6^i?*1`o?8?4>`Hq7Iyie*#`ARD7CqSRVnB( zhv`d4{|RF3Jw$`G)-?A^Hoz6+S*#QAAFTVbS^-u7DQ=b3Aj?E#QDY3F()gw856^@f z3KTs)e0BlnZqM?c|7wrOUG-`G#3h4FmE<0LIVm5c%t-$b=v*9PKh18WKk*ATyU_Oy zPimNy(bd&uG9-XPC?BHTy%n`)L1kEFi)Vt{)M_shj7jvhIf?wReW$`^>W=kXo&mmU z9_?*O4Mjyo^;klg(HQPQf6WX@I7IxH2))z;><(i$Na!<5rPzX5t)F6&>)92A1c3^7 zW=ikH2rXz59fPui`w%sS0J_+RskSKsLN*)8Ur5D5wR27GKRt3&Gr^6Ebo{MX_lNgDbsEt9i5 zh7t<;iQlk7N3ii|%IB5S2{p>*cTCjRJ^uCTWf0NW8Dbw;qC3$a%)b)}f5B+g*_Z#+ zxC2t1IIziRKL06U4@1ggzFot3SP31OWoDKD%h~KQJ)`c3q{V8o+7mE|h8m9?tx(i#wpkUJCu`y59fX_oClj#S*=~ z&9ULSC%|!NZMZVEud45_9Kc01+p%u;&-rD(z^^DSe2`R+>WBz9%dyPRc2rM9w)_8A z?#CbezAmug6R~1HL>rXwMZe5^POys>sQQ6Pi~XLn&9vqIVYAi5_|u&q4jIfd{ip9MSa_w?J*aI=Y;A2x1_ z`r7K=0=AezBJVjriima`{KC67*LGq3BBAlU()M?6D)H&KJpU!Exgfjr2p?x|+Tjtk zt)YQPqQW;FqKLH_P(6puCtPXUab(>RDeV+aZF=53w$tX;MwLlp$ys4MLw|izr!GCtui``j!(Y(l_5P^pCWc8BA0xCo@Vb>^oCPpP?|Ngt5K1dYm- z+4KBrIW<$5!0MO!!l}f@XoicQI5uuqEx0gG=Q(QI_8U{{h|YvSMCw#2)bHi zspq==JNsBF)*ie@1TbPXCE{Xapufkcr@~Hn-(iyGLZXP&h(%9@wZprKDVt{NA4A2% z0CQp0_IqbhYvImhzm{L!|?|Df{hMjlDaBlGlSNB5u$*b(r^s!8cWP_q3u!_L5JsVN#g@tG%Q=@Rk z&{iPkk!=#Gp;pv-Kdph+(W`hB&-qvIL(mt_=*SmJ!^Zovn1W~jBCXs7wZVgUlhH6~oL%nhm1TQmr zox2ENbMWewluf~=+LuEgEvY|7SaQlB=!R^7UpizV?kfXIFQ$V0(GzKv>O3L?6XZ*%9ZXtT(5 zjU`}sh>wSVe<7C>x#i0@dk3mkpja0lHkex1anPZ|5kPI)0F0@1EP~)eyq(siyRsN2miO<6&}VrL zL?_Y_V4SvnekN2_>4v$(BL^PkG@ZLj3Y}qTaZ4J!@5&B+aL_qNNM%YxyL3wOM!sgd z33%z4K>-P-+561-BKf*jSE+Vd369{~YHaytNa&eo`@TJQm?5Q655YMoV}WG!8vgD4(ggwvnncFVZ6X0De5qgg<9@|J zx0_q*dC#KozX>e0(Keec#YK$Sn{!Q+@*Z?~ZZ8xZr5)!jbgUg?UMFv^;_B=5z$B3H z)`zDxhsVCGSC9$PCGE=TsuGfsI4<@NFl#^jrHHkr#cw<@ep|f4_Qr+7G}R5hM3u~m zI?ot2(dn}8?wpj}rsF|#*OmEb*S0hdsE)X8Uj@vmWU1|9BX#2e!p|fOLP&zceSk&ox)nbELWjq|!^j9nVp96qu@=MJ4 z|9m-|!1ciLAEGE_?tsjH{G~ukDmLb#mqT=w^Z6r_JeQr;3@cO@;U2DXh88 z-6B5A`gl)p0pAy8i|l>jydSg4zF|{orrMCDyAo!=zlK}p_k$T(8TvMe@k~TWa18$) zaRx4y`(ydY^eMp+3Dol?rplF$IHA}=pfw4z$|s6oKp(5I>bbZJRFYTe#1jxC58AAG9h1+j08$ zbti+r!oaRamhHw(A2)3bRuD()&)cYGb(1a!N*BBI#9f}>lTL$A)YVP4CUzW5G1uB& zH8%-V{xr5$^B=>}QerPZHNYpIeu)|Q67ig=n}ZYTeZ1`*(`mvrwMe3}E?_#AQ?$)s=yfb;tl)rppi&7tXs}Kd4pnvy5Sy4WBUXu=KR^(9xCpHau62NRZ`rQm5KsG z<2`&Is$eLjTA@nTz{IAfJ9F4Dd;>MW2PA>!g=>EWhAMG#_i)2KCd%?A+bi1Qbh3J& zYtJS`#8~jgc!YUUZO2#^iW+-+$f~(XdK?xP+9s-A%Boj9Ov`ithDd?KVF8dPE>dBD z=*s&&urwes_W~^oU(5g7wnBBAPA3P3o%#p3H~=H8mjWPbqWAoHEL)>D?m)PH`eSMOf_8dM(%YWQU}r_{wOO%FM$)mhZprmvvF(z@h~Y^~zH zE(4|dgXMR5;)`qL)^WhX`hpK*@S?-UhnCMt& zMANeszwy-EtVpNQ8p$|T(GR0!SKC3T0+>_`@xaAn(s|6^^#N~-GA)Hnj1O2qY*Muk zKEY~@`z6+v+Y?5%tSSo}?|W9rS`@RtnnhVhVm4|x<>&JWvXp3JitMue$=15%i1BRE zk5%WB)5mX=W$tmM-SyMhQM{?rwUa}Q`U$9ce zu0vvp!myH0_4%m=;Oyy_$aRaaR)R3R+TIx(Y2W(^0s|v?Wv@H-LddtjQ|Jjgg{KIN ztm}%pmAMf-l{oHn`t^SilfW>}ZWqv*C zwBI!Sm8!nbu9*2u)%($!-bNj~E^!3M zA+>^d)VFtv6CF!#+q(l7liD+J5-k#iAV*fb^yYk+WkmbhHJ@t_6l9+?$6B6S>#3I= zy9VzZ{kSn$^H8n8ymHju|77zMeWuF@Vn z=iU|h24<(Sv)c{36ui_$hDSU*l26I%RPG`!lnK4YKmHY=6Y z1y1>Y&uS4!B1OtpWn}kHRi!j_=C*GuL;d~DwTjsxeL`zm@2MVQI2QNuH5>O~X(*UP z_EA&6z&pk6VqILeERhy_6mUN%u+O)~amNh@Wf4?dQY4rTjx7qv2{G|3R(bb1fel<$ z$srxOCcd!XbCYN$};8FY}gYN|z#$LpkWv7z!4@c{T{#%C*F1 zDJp@%p_jI|q;yjz`V<+m%f9jT8G z;1Q}L^Rb9mY<~`Zzg2(PEf1%a%7nNC8QXI^_Zuwa2!!C4HAlz_ZrI*tNP{gN?;8?{ zAzdNYw=~#PcUby$3qy}e#XuZ4w_Vd*fouNuCs{rEMafAIUgGVHom6YR%5epGuXa~m zHe+il_AN{#hn<=});zxNy0N#{0p5kT-E>mihl!{gu0zM4+QXiFdmXTSee=U*c#d2h z8jZlE|8>wyU~=LP#tvyvfJ0-;&X>uS@1M6m8Jvp_-E5Bb_$hBjustoVT?)@Fqg6e+ zm@}A7!K_EB-2dgBcHJ*xO9C%de3RZJ(&_lqx5_WJE?VUO{T4t*9{s_n)!ZG-mW;<# z&JDR?)z+5Ot>T@>K-J%2TZ}uqDlqVtwep?@G@A3S=0abv|Y*aUaG^|%iTJhEjOMBoS^ zOQ|g4*V@Y^Q`=T5!|W3|3lC>x#UgjhJG0b&Nf7q_!oFq<{FOs;-j5y9;vu4SiZq)E zc-g;ZPDV;@^xzc_a3+gqId1mv2TC3Ku@Q* zRln&fYR5__3%CXPAmlU;9Q9?mD=)#U=-CGoi-qKfqN0@9qEB!{3M zaE&|n=z=YEykO`)!{c$)u7@vBV7{r7fd@|8#qHd97E<1Sw0`t(nmK?Y)Qf5Hb{a}2 zAQ}S!{EMH!-NVlo;tN(brl4UETR|Ke(zFxJ{rYICE|N$Fn;3pNO3otY<9I}#dn1HE zZ0hVJ;^V9U^$R0?+yxtQfj}dsC)@#=qGIEMZu)oRr1&~^L}(RAdY}>-S+IxM?~o9T zf|QDFOyzAUhWFbK156iv)H$Fs6GI(6Ax8HRI=2sO^3x;f=wA%C-zeSC&`Y%7Vf-ed zF;3RxD{}DQ^-lUEg+O7@gZUi7AML>{X&5t zt$w8P6X?xttS?}SHWn4wwJ{bSVbMKFhJFo7JWW<~I+k`i)~g`;y#ZmN%J2sB9r}3i zfyIlA_CvpFA&^VDdlBZ*?F9+EUi2n)FB-f99}C?6E;oCG-5E8s^+-uBOtP+LQu~r> zM?F~j+Rqz!cMk(A%&^UuyMnUtVc$x7#9tnA?YT^(?%lUGYm7H6syLYI@XX$p-V#}A z_rfKTB$|=hHs=?}hG&@NB-GrhvvrnAMk6x*@Je@94h# zZ6O~b`51!ROaQeWY+sim@O9K|VLvlV^_tb{8WA;<4r$HuQP0*mo1+(fcs41A&u}c^ zuP?Ba%-h1ax9)zR&q(bo);LFOE}P+1eZLONxC4Gkz!q?7*4B|4-8EI)yVrhUWt#?X z57v#vXMTfGI}jI`0yCm@PS#<-*;JBXWbBA|fn|E2gPdvnY7x5OGEQu3O51FS>`Jw` zi(dHhOhoHeAL3%!vJ_8(&schxz2*33JK}*JWO=kS;8K*IGREWSv|6E4$sO%N=9a1 zE;WoE5<)4xc+KX#W<7XjL`OXu^0>0=Ewhhctq$!|W@%CD=f5|2Zu|dpNzhG?wO;XG zI{yR<{as?Ydr~(Y`SJgVE&S{2tA2bO$L&5Skc<_}RnUPxW=At?YRVjjCZHWSZ_(SR!eR%rc$SrQk*2qZG6@TD=J7GhgjFIr{i=xvhaL+ z+m8k<>8l<$bQvF%$Yd#j%c*I6nphJ7$^-(SdFssk9&zJKaSOJqpzHwlD@Q?+jMKxF zU3q0+8sy{%IeyYm$2@t%;$ts5fiw-q#>(hpo>Y_i;%GElzL98R5CNiJ{paQIBU);X z1wgEw7aq?=49n@0E`|HSzUBy1T#uhN;}gDS7gf=JrbLJf(6? z6Q4XthYnq=Cq1_sGMk6#ATe`BNN8$>lz$<;w@dPqgj*Kr3v%|#tS2=&Nqe2NX5*i% zmtF68`PKvbL4Kb%8@X!#rsi4fMe6TOD$YC&3x?S9jW0h)(P(GfbMr+&yF(p>5wR95GYYmfC-R2{ee`~Uhkv%_X zZKK-HA3ZE%-LikZq*jR(bxPvb>~uA-dIlG~)qX-xO7NBVB(q3VF;>*&Rgb;u>L)FP zD7x|6qjYMvkNQ$|X}zpW@BD_WJ47e;wXfyCDVMZI`CyK@AUp6Ec9HNDM000z5GUH9JB`%4(<#g5>dr)eMf#d&9vn67M88iXmJH@$Y)f=qvI7d$0`5#1lH5^v2V z(VBV8M1iC?!SzLyKjRfK)Kxjp20kk>Njffd`6m*u(B0R3gKbu-d2$#iSP_?D~LiVNZW!Oo?idC~{2a z4(B3-Z-3#saG?$rvmZTnxrzIaiqe|$k{#ctPsm_Ea`Az{hWUU(gCytHO=tQRFiwAD}jEfg!Zg0sch4#jRp`PT;0pC?LfUQI>M-@XA$Q2g8 z$3TBOx-G`5D15<{Pl=zfeVYCZ-_z5aD-mNZAU>?9{kuN|a#z|gpAVH$C``tZvvIgT zyPI%uP2#=lcT2K3fni)rm39gq^3mRa(a8pCHTd<*QoMGi-T0r}GU;UFZ|0&?hldS| z9snJ_!rr5QOcVM$80Z)@Y^}YK5o-xV+%1$AJtpN#_@2iPZx!LS#}-TVwD`?W2}_%BFmlUe=Js7bs+e-FuRwNpzgi+O)UyNLl{h?#=)E2LBoT z{@)|`53Bfp?KwCf(ULq(eHFF6XEl)VWt(Na49K|MQO1DTaR7li73$Z3QLh##ZCp9% z)0+He!HtzWl~M#9@%kkG`8=yRv1nv;;~p?#P%9U;K;=SSf+h&4r2~Ej`H~WVSVu)d z!OuX|sQdR=LVXdO2!9O_)E5JkN&lX_S65*Q`};Sqt`Z9fdRN=P)m6F}{(t^+YWIQM zR;`XN1$3NYSv*=>;seE_UOT;4_Zom70YG^7C_pCr=Lqo22h;%Z1zrkDd75^HUtCU`;!x z7P8jybh;WxdId%>NZ$uUbz7rQw<$myqmHVe-sh2~3JE3(y9Zt{1?m_0uf8zM{kdxBFO702r%5) ziLA0N-QG*5fqD=i(x$zoMo+nBN?;m>v;R>Noyk9!reKr@hx_{%7J7tNxkx zSNSZg#^1(Ni@!HDH^^jA{}e2p$HuCoR_lUksI~Ja3rrq(@85}${||x~)JXh25m9|E zP)eKsJgolT>TCWNzFcC9$nTAbk@JJfMkmf^c_F+HZ-VmfI#jz%l*ZFx5oqnCU9J?d zy$J%W7H*G=0hoDt52*W>?nm4q;o{bJ-kRPRue9B|0NN#P8C>U0DU>d5NH^$#wnI&n<6 zS64K>{3NJ;AWBP#N0EtQwik3S2jUxu^-Q;pccR{`OP!7(pVywPTS&uZj@pGMYp3^l zP`x@@wMo*Kt#Cc+h5si78yjFhT5PK1`3x5Tq?`t`)WVQL1=Wj*b#h<6pyc_UakAO5 z3mS>{*c;f;Y!#t$8?h=p4^$B-v{C(**H#!({U$(P1=j*b!9wYwD2n-T`lHYrs2iJj_u=(uxC=~!H7=L2UD4(>eDNbJQ!VL zLUrZ2N_IE2&rQr+REPrJxlMaf~I|P(Y=%JjM-x_P5wf6s z&2PSQzR&vdE!X%bKnH$k(23 zIo~gJl6!lxEFA2?jvMQm(uD0&V<(R9-a84* z?fu;m*M6Zy!tD0rBW(YsvtpwT7Sms85Bwp%I^$Dj`uz`vlY&Oh0FTx4&6_uPs}!lE zGmlLWuTa?n+#o98z~;g0@J(qz2j2Vtck2bh(f z#3TX%|6v>Z`A`lbku;oyvU(+yT?Dq5OF3S-8L=Er33KY2_cdEt>Q32c_9Z4~oEwl? zB&Ri(XFuKIoH|N(%qe$#6S&PXx)j>akC7?8-{*0j^^vMWFL1*v7k^**hnf(W&;~fq zZs=oBQA*ejm>(a#GUnqP!f-04*jH8L=;W;H=_ z^#ZRJDV(Aui46NbJpzAJl12azmdU0Sg{^Wu@f@{ID-U^eqw!$UtRIj)<(&<;uADYm zO#?m>c7z&`hDR#_^}y&9un2GotFdee+623!)U?bhlvG7_ z^>8-0Wg|sTVsx+q#5RnHsmX9Wp$R8I^2X(3QwE49wr{1fRCke7Y>$05Uy#4>}yx>_J8th^oy|utky~ z2BC^M1eAl6y%7T5f1OLouKfE(@Yk6IxZ>Fzh9+{q50BBij$P&9!mNJa)?*x0i+b$^ z1GT%;hu&`$Ao)*S((FOVLJkilDqS<`ry)v2dn*^v%(_IIG|8NVtChz%UMK>gld0oW z+Ywql?)oFL$~~Jz3hB#Ez#?|I!oK&di6iT9LRwx5YuKf^S`S9cgY2yUen*Ro^E2I$ z@}wLEe+?|PaCAH@@WeRNU{84?g|qrZQIM!W!&sV&|WYE+}jklzMziEqt`xtQHT)Gz(3=N_tz1O zl0i)I;h|`E1};X1i7?CX!|TN6wCF46MiY@kUreRtQZx91rd%xq0%BfLVD$&#Y1 z7n_gEQai&!_bn(?UZ6jaAfH88D@!U17&I!NV=Nt+ug)8sW@OQ6H92x=2PP1*I&2bh z8qA(zq&Mn1f1>5t1-rz1g!hnl=iy3bFP*sb5V3V45928muqp&qrR`I|Tejac)F<&^ z!5;;uvWjL_VZj=tq;ZocZY<_-A|W=J1ClczsTyIo;~GUD&rx%?OSfSPPss# zF9eSmO?E_yC@J-ov(2`El&$AHySw0H^K>C=L`ZsEoPM+7H%m3x7CqOvf5OgH7&yF! zVX9OJ>*|5pw7A2Y=ir`X!mI)~?$+10^0r$jq00>f!nq`+;tTTZ$LQO~!RUr=Ai80W_8kWgIJ2o}ZgUqGb8gR6vgTUnbVfr}h|;BlPLG@{vcUMmS803o$cu`{ zMOB8KNrBprv(YhtWP}G(t5Hp9ctCsJrJx$XiCGwjID;wRDgxBb6>w?}MMl5!z5YPu zq~3dD!b!BtxXd?FJ*PB~7qhLxb^jDGhq7;HncF7{8hTfJdA{z{HzW=B*Qn*0RK(CE z5Le9(!xjMy2vOgRIpm=UV$qiggYO?<=YnV)v`o3xz=iYl855NHSrt$$Y@zstFzCZ8 zP7G)X{PJR14}+e=nsuoW7Tb8jB}ZaY)O|>De)B>7{g-Kus^F8qJ4ucR#@T}Q zd2h!G50|xt&hxk|fwEOC{FGdorJ5JUs=5yhj5M&K9J%v{wl^XB+cp%o-<5p$4i;Of zs2;bEQ68+xJ!8~-Hj1=7wdnJ3^(=<`e4ls8Q^3-9{>oY-RqVr5{us+cXldEoWOkAr za3eCtMcf>sHbst=U4Xc=F<<)VIH*c)?LokTB->FWDgXR#(=D~=Z z+_e5G(3;$^Vc9lw7rtBlO@cqPG}Wj6Tm(yV1x>EZif;?pf! z*Q0U;&ux><**sqbS&r@q_BG=3+ARJYQX;}GLbWR!-+ivk0@KgKhCKFsv?#(eL`!C2 z{^-=I?eK|eI}4U-p_$?a$Xz!(rZ@ptsHZ9;WZuoCPKf47fbEVcUj8*nuueGIQrgZk z8xEtR3m_t7bEFBK8{Ql3^$}&0eH%e~pXy?Yq1_v%A{uoK&F5Yc;PbqNKsi!CP2jRr zj`v3ee4Y^Llhew`X|#6FSH$Mnr508T(M}m)Bw#=s;&>I()gk_;X#pZKqY3F?ncW&= z51u()4!$T^Pe@yA2x%spWo^D__4|dn$?)FTDY{9BhzIi*6j`x*6$E1G)PIq=@3<++ zWii?ewjIyOrQTnm5U=!g}W{K z%H5E}tfB*hqnFo*)E)X9PLB5dUrU| zb7t4;9+bjDY|fa`ty9VOyR7C)Pn5}z@jP)I$GDdw2T7bCE2H?ss%_XIf5BZ5D$75m zc%W=deHe+;j|%b5Q(c_Q89co~o|~3e*>yzO=_Nt`PX$+vC)^S}3}a9Fp7?#`zWlb3 zcv6gG+)9+=Fd5EQN?S3aBjwm){%p5*btFnraD><{REElsRSRh(ng17lPJOgrQW^av$id7Mon-A1eE z!VDkfq-1{DVwCQtco?Ca`U3_RK}A6>p(CLWcg}o;W@mPO5REwnZGUHQ?LJ34UgnHc zXt(gEdKS?2bA}}jek63zyS;R>V?Snek^P<0*^F|dixHN?{3=Ds+=gPln3UEg<12Crc10{( zX`nZJo-|1{ii!XNNc$pvuPog}Z=a89%9^_vnU2|+^_5eipQ_l#m0_>kd&Ko4KT9uzDv?rF5goB}XW&|^N# z8MIjS^_4pEK(b$g9NV&P{hE^tzgRS!Y8$9-bPn+GD`gEnF6V>|b5hKwH68{CZ#SNt zRqDf{tfQmLwom1Y^^uoo=QG)YwxdyUDHm*u6N|lR&rTB2m4motg@e;;lPO!Qvco%< z|H59gB=_wjC*8BNq|t&bid|AWcP}?jKGR+t^l|YG;+(QY+N_4I$S&rtuD7As58KEr zQ6f=@_DElY#ile!>X7MmwD**Fj%o`f<)ATRMjGYsmK$DGHi74c*)r?NN0PH(6E{PK>oCrI!7C#_@V6ftmJN%d*VFyn-?<2?Y(egNT)^0 z(^uFIT&f$YitG^Or7}z|ug@af%sL5pFpb$Nr#?tjV*;u5#c_@@XKX^`*qX|_!VZ>} zm&keRlnHXado&wAhs=+meD3Cu#G#ymj{u(RXC#A z7ZFL(8frvJg@ABV;wU-OyBU9YRrECc|N42@2-v0r@J4iCc51Ud2^*fktmf=rH z;oms>y4p&8kSp`Ql#AzY?r2?FJ)$k3)jNF>nTEAMWz3B_HmXBth#=wb{=DPHpfe0k zE0`D%xm|Gt*l2bo#v^xXr9Qt_Vn`a0fRqKJHL1d)WmU+qXD|MM3vv*vJ+q2FRcbU1 zS}kCVd^F}h-$OdidyJ$r1i}~yj&ohWvOrp29@*6B#}9HA$Kt+;>vmn8-)d`q_RPPXMUlf@2kjhi*Ud0_#GenZP>c5A zQ;XQnj;MKq5QZ`(kv{C}qMSLArG8-J4_|y(y5O>6U4TSc*pe@m0>%$z6Pu?|LF7p2OGkMq@AJ;Logg>Vq_ z;EkFab#7yAE5K{z*|*cl$p@iaGLm~>C(al8;TCe*!-e=WEyX=YMLIf3qr?~N*F&3P1o05aBh7qQG`#CXqHyQwL|D!;` zFDI1%gj|e_#=9FVDd&u|ERIKAnLJ{#i;-62;|`J$QAhiib&%uz$m-o z{{|ZVpbx|?IBzWQUv&vyzGWHnU}{UdFhQdZS#Jz1Y4Ya}?+4$p91m^E1;7n-L!}?~ z7kCLzA$A_Ahx`xE9lG$eJdNqFD`YP3XU4$avc1xY^24Mb{f$vEZ!FWZ(EY~;MceY^ z!Jguk+MChSuQ@OR=#9zz4zp37G7g{a%ym=gbTDzE7>BS+00RZXTlWLbgc*mR?r{VWb=OC6A z-aGSR?G9}*-SgQ-KSY&0h|>WeGzV-l8-Ux@+251?=XW*)k^+`t3kb&%fG5`z70-SD z0la&K8v0lR_lA>0PC)L<+JNlZZRbhU`QFD(VBwpfHmNH;y_6{XSKtspm6K=q2?6S; zo!?AdJtC$Vxc7HwyQ4`rL1+geKR+L8{nq!JaS+HV0Zy+C1Ncl4*Y&Y-z5y9x6<{5) zRpr$tqOGcw(PnNT@2}o{zxzi&Sau3dWFtgpN5z1EsDQhp?LW{Y3UuWVk;V|t z_3$-gdaSR8i?Avo|^7m4g2sA;lIRv zX0d>ERP8pqIiPT8=F@tGVeEpCn7r(Mk8Y-v`r4cqH-U&1lP7JTYKhGmg)e|N{0g}n>RfF?Jl z&_n_)M;*dbH$P@Ayx3cv$2%`2$}B)etKp`mzwZOXv<8u?*P{OM1WQNXyxif()xwYQ zGQIyeZMFOI)0D%BO)`_2UW zpMYz2)cpkBf_6`fJ&a*NwWcs@wE*vh^|9K4e!uycqxBn~rkZ;1ppKpd9Iy#a1L1^M zgO5v+@R;N68^`ZW#Z70m!Fl}bWBEaS9bh= zb=|T3@h{)UgVkR@PrZGlEslQXGjIyzHVwMk4E5%dHOm9Djl%~u@abnYPfbj!rVp+; z_lHNkBWrD__8-+V^}$6J+50vD`QLnjyhjw=ai$bJKdH>$Mwu(+f%XG&i+(bwY*VSa zX*r)Uk6qGl*X$9+@Ehp$oDDH}~3l(v@r6u8Rvr6`a@;g^hcb>+8USV-W+qOQ`+FsW$M+lpS$k669o__Ol_} zZ|ypTU+dd1+2X%2rP*@*iE^Lzzf{MQiW1wmy_ob)c{2NoI`9$a93YR^G7ZYx^#ZYU zY~zdQ;q>%lv%xT<9G{)4~ai=30SXrn;_-w^s)eU6=9dGeAY9gl7$5JlxfMHD_*B z#elSq=#X2P&!CP4@yZGnCN9>%2gbF-bX=z{A#})4KI9e}fy-Dg@=NRWE@Wa{he)Q>O2C!{6 zf!bHah{I?L0QIr6vs_pO#?W&9V8A;|wIiO?I|!m3s(<~cbpE4wir%3Y7p8rqSQp01w@68guD1o+Or7H6G0y#D%%Jd^$>zuFoHOWPVj z3ICd3u_Dr=^N<@nw)Ut0LjL|qWyKpZe%BmGt9xDUIzx`-i_FczU;DHE;h1wGb3v&C zVwK%c>7lm7L2G6Fc<3U4T9FbKP8!ss=ZWA{ zCXX>WxQ^DTDK`5nfP1N(-#^=IZSK+xK1w3Fs>$`)zgRWEK5|0lb0~B}&d;j$io(e6BH2rK!-hKk?T^cn*?&fhoX9`RP6&~|yhykfz zSSA)tTjJs*JUJ6r=anz6b6bc>@_YaKNwlfBV{HFNV`xV^|JPf*ZC$K8{bDyoIun-os7^#jIVV9I@!NQ-Uz0s ziS{hYxOS{0kla5GhXZ#Vrr~`ho*fe|ghDG5ZpQgU{s<7lO z4z3(cBYww(kExoy7-U0(+ybIk!WxM$vG1>m8o}P90x^x$3BL3xHmb*F(hZuEg-$QV zhh|)Xco#3Qzuoud^0F?}6$Bl%H|N!@d)fYb#q;apRpB_=u2 zisY4356b(HvFzd+)E;>1v`7}v-&eEIb_uW!@j7P9_#XFIY|x)2t@Op=&)xKpr6c?i zcF(f!#RwH5Zq^q%!MB$oDTy>)cvH3gOX2mkwd|)WZw=%)#YTmJ-y3+hf0!NAm;bNw zVAe?>oXNnphUqUf=%XHp9))9f)%oh>LDAfMrN$Lf)`RDC82eg7xSl_YYPbWv7udQO zWwi%<7L%smKI*MlyCe9;pf4HOj&d}t2yA;I{dq0VbuHr!6q}mpC&_PEz|e_*;s5sq zAwknIfMO`G9L@ai-0A4$^KK78hbB)ygLvQNGF3>*GVxLd8yIwpTE5arA(+2 zLB$cLe5ZdOy~9Ah?vNV;#M(Z$W?m>bX38M7#Mly%yuN=5fTWKHgV_(B716Q7C|5lYw}Pb|~6baYLfHPU!J z?-xrZuGasfymX=(Rz>Tfu|R_{>Purx5YKyk8BVPSbLM4JNi2W6;Mt8W#vSd;Sn8Wvgs_qq*Q1plPnU^&Og%2O??&1h}HD9g}1leCL@(c zis$$VXx;{Q3IVgL{T8DU07?(o|7_`n=ZFn@<0D~kfIvfsn!Y_1gxlC;XgN|3@Ro!f zlqb~zwwWZ*_uss8$7^HaQ9_LtAsCZq<3N@zI|?2T%t4z#E@l!ir2+vU?zDV%ZEZQe z3#5k$ZUNlY8rH)@hb}*Vh^;BnKIZ#d0L(dZxK!B5sO3ZLKJt7>UMUu$3Vf|3@Nhd3 z1O?qC`In-igyIJW25=UaG!j{uz{U^c#NeqYhrO2PVz7pHOwz7dz?9Xc_HkAdHKL0J z5zj2)^fEB$V>DEFZu{-FdTN1i1BUOvthxTa1BP;drn*_uu=yOH|t2}0?>#M zhtoc&?2Bk>?)S%W48q_~qWR9q7n z+BHoA>d0VXhv-V*Cqc8gG=DJ2)io~58swy>r{4rgCSUCp{12)E{jT3Op2O$aIE@RT zb8XzS@!W}Nqvl7^lFE^-qQiy#K8F(WNg z)~jebNt4a5{TiFRjAoyQ{6R-`lHz%7wkGT!?^?j{8k%-*yM|8=N>1|!$wDr(RUNy_ zbzWt)sPpE2l%k^Jc=Nl0!`rA3vX4~(lMB07d<`qXdQhMfz2*{qWuq_?~7?owJn#L!(a})*BJE&pUBv-)5$yySVZd}p!KF{ zq_OR|TM(9c^6gsl(Lx;D#Luq|pAtF+xMsq%BKYPV&hA0=4{zchG+?yg+W1t~KkQ3> z*bb?4+vk${9@gjIIr##x9(XEZQqW!=UyqE>043-5uN9Q&>k3(2fNk{@g$mf!qSdP+ z>^dHbf-Su`+=Ta1Y2e9fa{D8O(>~2u)*8ER8vnP=pgFC_Lpk1GtO2&+hG(|nK)Y?4aqny=%sEC6VW|PxX;pHk-iz*9YX&WGHk28n-;lZ4A9zxsc*Pfb~{u9N8-ZqRPL{@}q;4k1;(tFlme`!@-V z|N2ylpBO3QAZF6)uw)%;A@Fi4A_gfqDLtb2^d5|nRx>O$LHoM#cx3%pnUlqc(8$(j zVNhB7;ig8`9aDG(i$Z`f|I^aU8!>gVV2FkTG{d*FPoj;8g~^8ex=fc^4fi&ES|%H< zqU%6QK8Sn>ll5Gk8vqfWxOgiyHO})(`Xk^Md(g_}rpYbFi}&R%DHp$aZ5KDn^}A69 ziO*K#bD9Ie!+lIXH6Du^wE1q0JCUT^YO9$3aSC=EmPUjNox#jqxhfv_qdCyO#%t{{t!{2=IpAt~H;2fm zOu;ALvR0x`@|AJ84P>EQ#v&!IpBd31?@NV=M!dGfSNXlWeY{Et;2Nu#dujI+RNJKXD>)3Zr@l|Y zd!?wp_=Aed^9MeXxZzewEmsD`ch59@(kK`&>g#fZ&0up5jnn3VTQ>t%W4>HjXZSh` znTjYLAd%zaqDiKXWZ_b4ti7bhJ|n0kz-5QVo^D4ey4W}XOVv$7)X8hVmLPCG)B!5- zZ#4tJ7U((-0<5fF6FrEajg;PObD-`ilH+;p7T`0NZR<>giD=0uYyl%%9V+VT@3N_8 z&$T>f7|cDB``c_I({O;%!@2=tdsNsJEc$?)?wuWqtsQ`VNFA<%HYxPtA>cenKT!l$ z84K`G$nv-!$W!~Gi#~g9Y1}MKI$H@k;wK8_-Eh~>G+bYb$Y}ZeFn^_aH_}a|g3^9D zsOkXA0>Da5)MeJex5%)JsQW7SMIJGjyy0WKTcZ!X%r{o<7w&iI=503NSl!?;H-ry1o8j3$14qWRa=ShpvS9hgKH*F4UOX;p?j zDxRGzEOIuJ6LytQ0x6(K(&}se%W`j^l!>|x<2zWh;PD{~U_!{{`?F%V@HOH61~-cq zm-KMoe`x)>gx<1R{?j9O`+kAKyG@9->Np0#FLQ+aWiCQDN)_T<<-440ECbA?G}b=z z?Zz_gQ+U$J`d3*<$oU!0RDh2waY&PhnN3FJGG|Wzt8yPo*wH&bZ>q$Zxa;~M=pzsk zuP48wMk}#{ZATD63>(Ao#OHqQ=%dNzrjt?(xZ@S?6;}@Qm?Zl8fwjsMr+l&hm)`HE zJfLs?4)PTZMJ!La0e{}Y4N~!r2Cd1iK~`Z#kRvs@+A%d%_s9ge3~Tx~f$csl*7@5{ zG>YVUlGUlqR98TIhnYOVRhw%baWWb*U5AtT+NoLlDSWg38b_>N4Xe@qJ5rw{a~hTu zbhjijdS!~!6~-H(+M1N*=-+fx#7KsY3T@z$BRQwCy=m~0S=mj!jo-eDz)+wOSQ(PF zs!Iqlr#4;xTeNerFlzan%)$@GEhAf3<|H*@)JOgNE;DDW3fAWT ziFfK>&wwbDiQq2tAp23)8>hLMWrw!n<1A1Q*A@EhOPS-qy@`VbpO01p%*CD9Vq_9w zCr-4gN);3;IQak#83L}Dokwhq@MzXXU2r(AXYP2;I4`RcaK5zA@e|ej&dVjf*U720 z{ZJVW=9hO1^P|eme53jFvYc#Qd2in~uOHcrqMRi^2ADrHsdgtB7ZMF1zTyRf`0!el zyAd&pRN__QqgQy?j(^uQFXKs@PZnst$whSyTu{b$V;72nh80f^)jXu9dScPX$w-|w zU-|7EWTO9By?6;SxrAt50P~DSq?vyj3kJZM-=AUwmEl`V`z-=f@}DPdf5{`B9#=TK zf@R_;c|6#2uGH!)8|xKyA1OzN@U_2#bQ|=qIr>TfwQ)TI`4MIZ%c^GrKN42D+fHkp zK9#0nIR>_!BJLMm+Tx~S``eYkIYy(kS=S(J&zBL{XC~-K!VNw3-t#@}RN9MPe#O6Vz==D5%UKH_?B#Ws?gR@Y9O! zq~O0JpHloDQxSL`X(=tJa{PH6JV(f0hB)jMYTQ;aeatQ@ZQDuS;Ekl`P&q=mYwEA2 zH=O+atQ+u(4k_vgk=dFDNgJG(wDeSD_$_i#r%U|a3Gpemw;5(M&{8G`fagB(D(h&8 zl@nr=s0!idS_j1~hm@!DVmJuG-ARX8^l8CmM<5mgRol6Yp*bYf{k7tq!+xP8zA#dw z<+PF7Jl!U$XN75tIYSij2)kgGUf^r3zwjC#*{}&+yr`|QHg&7l0M1-TR^4 zkLx+6o#^qp9_A>-&g1$GJKyyyf4R4$4s_#6737`v{hPyl+&sjYnzuluq;mF+kbi6@ zPlagSWVSF>;Up-xgcX-Y+^QH@s=nxtZYtKC{z(U1Np@5a4x^gu!O;xYx+-f+JR>6n z7nl~a(i{$5oO=)Gqk(;81)M0$@bt(-wB}h)TG*YC^NaOq5?{JsxPu)dIsX=5D7NrYEz@YaKcSDbgS(M_1!>2qim+bcNgg zP!?J>0fpD_AQ6j($5LgyfR-gRsZ4X#n(5b9UTv|hIsI?Tl|-yaoGMB@@@(+x8wo*c z34`ST(R?MAvtDqMV-1GNULeH^Jh!cr%GA^cxkGmS>DZX(#aNUguxO|3y|@qE_A-|! zX8nQiYu%TTh`(Vmx2PLx8_ZM|d5Lks-)@d!8;AB$_IkZ_=kvGB4^tM7&6cdzN>asT zt`vKm+%Cf_@qCryC+DNFmv%%nEo-&RE#ra)w9;(pG*x1x=g(55Wcw1FXZyaG99Xg| zy1hUhPGx<~eO(Y|A>XIFc~HN>|4SJ?0wi{$Tg4n5ZBwP(Egmi8oAiygXCj)xwIbWY zZXz=z57g9N85$q1H9knArOsQsZ4%*yNQ1unyx;VmX{lJ5UBf!8=(?^Wsn5?BP0oX( z3FxEJebG$Zh7vPpibzGSi00R~1qnzR75X#5z}c$&pIwvne+at@({~(lOwwl>@+5c6 zWZ?l1LkTAxW8>{BFPvZLrZJD6UsiiVfEu*OVF*4S^|%{B5a#$7Uz#U*TbWum-MWs zOR@K?_0-}^D(&ch_lMqB{ch8+$7DOAbtJ+7JAHZ5r=Z!9=(kqLa{P(RDXd$}bZa)) z9^!D@miaVwPEAqvNMwcmTpTG#Y(>gG@021zlHbDktG%p8^J{{#vI-J<`PLg@7;WMU ztw)a3A-BhG_KBbnNw_7dkN8Ni0U;l{IRxqqzY7*q!y8bRs2ZZ6XMYo%DeU6<_d%c=0M$kaxb50h88JxlV z);jsP`Kn4rX{E&76U;Xyex1Uzl~I>Oe7hKzv>3M=AJfi|bisLE5gknz_F-%ESl3#}TBm2@(0?8s z!GwvsrBg?WKn0)IHKjsV@6kj+yY;nZSr|XXT^(JN^`=nmB(_e!EQ!Q*3)RB&*^N6Q)15z<$g)EAwb7n2YOy@2h6Z z73qk&Z&^@8@e2*7ofLO}%b?@@rt@}MeY>&SRW>!W_=}Lbl!=1yRvwfq?X!$I)27MIl;6}>x zpDaVd?6RJP{vc`|F18DDnBCCkd`p|)q}t$4F%lDIriYwa(L#(uxIiatK_rkkSoP;G0o!?D`V^o z1z-lLsGlwSYo@JSw9Z@Rra#Nta^nn$vGHb0+hb)RTM5CQPay`!{T#!#sb1@IjElrVpyeSjDUpQLYL|9nJMdjTSX<}eS&3U`|0u_+V968t#LIOk9-M)pFt zV%$;L+>!Uu59uhsS;~r@sdh>W6Sr4Si}aDiiu;!!l0kIc+g_Cihi^jlAvQXqb03+E z>)cClD_botCDMGA1KY`8OT`Z->-|=Lv!5&0q(qAQL2=hhF~_z$IHY86a1G}v)D_p4 z@#{bq*E1;PIBgWTUWck2DDC=9uVa6yz|HCg0dbghcJuS@W}UO64X>Xf#R{_?@k4b^ zeZhxOS;l2jI);+qY-Jn1(|E&1>CNdcj&Cc`^R=3`~s?_yo{9&QrDJ_^i>} zmn58qzP-6+G;o<3P&}UM3h2xJ;Q{Oc)qg^X9Z8w--RNhtx(YeKak(R~zdFo)l>~_b zGN57e;IsYfGDQzREmV&?FnhAAkRW9ohn4V0s6jtfmXV;HX6TOv0sW zfJSK&$|P!|Ru!BJM9@7mra&I)e*rRB>=mV-jeLJgyL;pZ(5s|_CLkH8j=$eMm}OYq z8jf!29O@{TLJJONX%9q<2z*4Z9B72$D11th^JVRA zw5eN@{Yn(a-NI#gJ9-Rc)jEF{P-zfA&+~QVp(QjC)1L{Z!~-{5ecfGo4wk-ww>sAEufqccGH%X7u3o;kwsy$nDnQTi9O_pTR0&pvXFUI^K zb}mVaIb(HSGk<>$SKyDHKV+hX%N0kF0vJ8tmdmZkzRz45^QChbI!TprPj7Ya-s!T7 zXp)6P>wPt~tD65hhBkvCBt+08tLH$zHt~)()2+GgieRbpXvskoEchWU#(Ug8b(M1c z3fc9s<_89?KzYP+r9h<5K(Zcey3sH0cLeqG@4cBQ6shUBZdyx9%V(Uw0-%qoQOIi` z%c%U4Nu~Z3A7)Yl`myS)z{RtNfjNN(CZ>l#GP!X^#EDlA&#bkPwML+Tjw1lK{`#ij zItyO%I(+U2qTjUK^U-&|H-RgpI1*ZfOoE*heu)d@-rE5B+3LQiI)DpKlvlt8I7>Z> zJ%}pGRHVGujs3TPKIl&0PF7Jym*3pjr!0I*bcz4r=CByr#RARJLfggW@3JSS%$r(t z3xp-pkUgJy#j8E_*cATeDV2jIB%F<2;{X+sjSQffq%e(U5n8j_cu(NGtm$KJ__rIn$*g=8@IQM`?>m zXWNusRMk>^ec3=GJN!JudUpb-SvK)KvBF{Djh&2HX%(8*q*&%R8gC6+Rpk4IiIP!C zfRRPkDqlFT0Z_c*6NRFOjj5MbhLLYZ13<>>@atF4Sm^J)r7oUpn*y2fOo2IbUCvuA zKs)v%x*$d3tnnC=d57o(yVPbT6Sjiqn$SPW7^`pr8Fj-IK;9^!Z=GnMLVEOY<%onJ z!<*(otA|0;{z?MLoAzSjRBO72&9^Sk;WN8%s~5Q(E%fbPk6+=hN875wqL(S&lpI;{ zgUjXevlp`$C3lM4tR1(t++Lx+h&OHAi85SQ z`CxtJcig^(5F9)K=j#^~^I%&nm37qUm~@8C54DuV58d4JNth@X!X1$=Q7i(4oUP04 zP|m&ZQX=uSX$>hku=jwI1yN1h5PifmF#bLq|bR1YbyaErVbimfR$& zj^-ci8*#$T(E}-zh~_^xK|=My?KYNKb#Lp$b9c5gzQ8m>f;U^Z-==O~7jv0}eDyA* z(auMJfEBQ3lH~9nX?OD50RBOk16L@Lst0b;@1Amj_M>vHtMxZhjE)jBd` z&GM@fMY10aQ?`|Fs(0ryi$ z=igN*QkLc|ky+~c7|T*feE0_y3F zt3_{4*FVE0?&O;|I{e~QxrV!EDXDT(7iJ=i;_n+aN?su^xlBwmFSBY&!j6GVN?h0l zHmgW_EVR2DMp7|ul7uI1Tfj2S)AG`JC++;%<|V+22g|WpfV{jsk*)(vUu$!$_|e}b zaHD%VTc?<0W$E-H-6X|85Y_yGR4~zm)h9?Gdaan}R&gd_Kc$}t8vjn3dQp%QsbIBF zA`R*m>)gzMpGEj|p2dY?jr(5B zb)m|y2T!s__9dl*j~E{3XKtTs57%R^;igX3heuLifqT-b7U-!Sb*xKELBQVI{p`hK z%Uh`?mU4*^aO#ReF^ojtuw&x+i@Nf;E>73Ynza+Q*yy|Sw~BFI7B~COC_`hKpO6Q% zexs8ZT!b=)ggGF<$gHeY6!IMQZdtN#I5^&2T?w>s84NUR;$#SkVOt!`N;D+W?J83w z^kj!R!>Olh5NN0G)0q{%*twy5vf847k_d8`U1j(#O8tbXID+5-#H#rdckA232Vc1F zh92(RSc$o$ZcHA2Ke|;;hQARNRVqmH5b`!4=%=o<7XW0d;VE08L3S)Pl!%9ujO6W< z11gB2KB@soQG9^byZ4_2CJRs|-qsZO%zCWquUE+e&=nK#9DOU2SO{BE@%l7645UH+ zBPG|P8ju?Q>x3c9s>|cPXugU`p2oGc%p))ljQA{lx_Egd6>iY6Y&_;5Q}i@Q@Sl~d z%50l(R|~OeKyniwg-{~q+oI}PjJ{O8R8F&2qE=xnd~)oN@$dv~)p_@=%VLsc!ILo? zPtdgCyRqWQLB$pJpk`^o7#;p^u%lsqh2LG?L8zTs#SoFL$=Kt{_o#7LYhRw*jlgvk zSYHI?1(QZi)&@x`0s%Syly3deSAsI5%e-x*{ z2QwsZT}2Ra6HD*lP$oyMz|z8DYdNqOg|d9{hnMU_7Ugf|MB?rf5=u6fGaaf$d2qBD z2(@k9O61FZxH85zt31~C8s-Tu?xp*ai|ix;DCm&Rt6&Z*_T$ZTF-~!$-bwEcOoh9} z@Znj7+$eM2J8=IJ1kI+P-^0lu6m*!FDTbuzRB3z1knpIhWn2gP;C`A_R!qm!&2Fc3 z+gaCz^K)!V@TDHNi(-pqK5tk1Nm}Y;bm~8y=vC6-tf+ojQtF4l&~@|A1<4WW$)&s0 zR8P59H7o5xlCSMp3%R%obPFVoni#w)$RvCtlwm9O%02*A_bOzVH~6^XBiPrLWZ7DI z>{bD;O4QUhS)SHgs#=%4yq{q6jW%ONREAiWOq@A{mp}GJn*Z7UDE#l`gJH#z`oBdk z{JjTsn5%jojRUc-s-{`g)YR_1ubM8U$6TfEKXVGY`$&jINU?^I`c>!?bTVVy4Z%e6 zDi!g22a+G(3R}7YgrSJ%bFGD=y83^0#s75Up9N-E7(cWV^QOy6-4GSK837fQ!u}pM zd;WWcy@O$SxMhtvj`ZY_I0remlh{{)PJA#jXtZ?H{5Lw$kx8g}Ae=6PP6)*LF-LPl zFD9lubWXDk_r|e#rmn@JZc^U8n7%Ttek>t3eAoQsY_Ww_w#g>%f!^A9D<2^Pb+V^m z?BUwFKwmypKSdig6C&(*5SF8(dXI*gRTHWK8Zw;*NP-jaE zkCSl=wl!Amqt1tJXE%w{?uBkFjbzwsPk#{lGQCWgWm&&Xl55!=ai;a}1jk1(FH5p~Wr ziU_6Aqh6B?&`3yrWI5Bw6X+|4w+L(VC3tdA%G)ERW1{b#eE1V|Euv0k=%YTnQQh-p z@N?g$ifCT4E~)3SXTYSj2xZ0Q7TR)QiwpEPUW@^e!tW+$5ulgz`PMls_kNc7U#7lcuY3Hoh!?)%lYG zHg>Fi8fb$AEdiIo$GpKif$w5-x}oOE%_P3iplk_4TNM|+LBI-cfd5#1`m;cND-gJK zO#>EzQ;JOG4A5k&^(u*Lpvh_FTXuVHF=>3X6Z=EWtx*e7cH0DDqh^SNN$*KGd@@Mv zPif2f#591vrK~0MOe4pVh_Brk;~6;}&M{B3ec;Ns!zUjI0xgHv0P5ip>5j%3v#;4- z_E4Oc4BY~PI`=${gbLChev~Wiwo5t#H*wuO3p%j_&ff+54CZAqX|_{uL$NbuOs2{ZGLu3=GG`u&WZLG;bJ&!5+Gfsmd!FC(d*1b)v(~%LTJJjR zto8cCT8Vvs@B97^*Y){)uFsWcS}>gPYSnZ0QQ@FN!SME|$JYbo#;gR$wM@crNcqhd zo58+W=qIb*@gqB$Z@Kq;)``(qDb7||;Gb4t1<8U#94J|m5si(tv_!;4#eMrfKW&xR zZM|nj4;X>{Nl-;(oG(UN2NG>_%%mr-NsL;!d?mEsw)VuJ#m9Kl120w=iz|0G8;2T+ zm`L_97`9QuEAo@UxQ4Z_j>?{i7QB^=EElb!4qx=bOsC)d9MjaHgl@Es8e?B9rz=3U zTbYe~eMWSz(&#A*C!~P8PtN4_7|HOVegY>0DjZ)sc}Rfk&3qV6uGJ_Z_XrLvdL!uh z@U4PDXlq?ch8kiEjh((}C#)jw2N>M?mr;v}tm(CWT`^NFjhute8P+ajB9)it4B zYm`(Sxc%eHBSP0XowYr+M|hpUJS*wwCs8`mYi6IMH_4k6Et)sh(!*_r)}9ZPVV@_i zss3r_Uu?T_Re_fkj?|G^S$Ffn#VzmApiyV_i{$rP|0j?@gSpLW0^!mDFssZP4KHB5I+7QY$FV}p)p`SXWpypfHX9w^4;2N=pT z`N-7W0>;_Wo%I*(I=Be6zhxvuq5CPT*;Uwk$#+>kzTl^ouC)})k^+FQi%r5?W(hJ8 z_CuP2a#Wo%F-)5&&!zG7m$V#N{LPQC_+rwn-^W_amVXvz zak|-@5U|nMdfkDpb(Eh#f0sE)=TEW9b_5q|U7(#$b>ZR9>>~+#wTJhD8Qz^SQLT=X zNf?npjsLS8$jR7Wh`X$$rZ(xYB~S4XTMYIB({H?smf5CcQx4sAsPHO$vgt%=yt~*x zz87Q7*uGB16)5e*MW(r7KQ4Z3rK(Mg;srFQWyF!x5VBeVqzQsK52 zITO>yC{D#0wou@<&(Eq~IICBZzbe>x4zGTAsgu4cE=!J!3RgkPzI7wvNqML8Hpnz$w4@Qoz)-#X-=h{u` zc2EWz)bLp;tQC!4tZ0Sa@DH&;4^Ir=>FEyqW2_4E!>}A*(SaW)UJ4sf?r-7}HCP)(s^7NrKvrRZADs!`5du?xx9<<=jdX$=IyM(u=%H|DLM z%8--rdny1S6c^1auB`?)Pa%H1oiy)N_Rf-`FL%P5=}#fr*R3eg$b$$(a6K1;-8YU_99Iuze2$oS<_;#>`| zb&1h@;l1uVo4qZrGP};YEQHi5dPTQ94Y7wmPp3~Y7y_XG!<<#+G>(Cgnwl#!Dtmq= zt4jCjhgrgF9gU(Xaivb1rlkP4LC7rHxvkfxA21VAf70D#`S4mME{%JGq?YrCMh6Ss z7^oQwuYgi4sDaTVql4w*_YA+gu!aqC`=HI|Ms87YosQ>q&Iw~?0*j~j*pW(kA}&nj zVou1p%RvdtS7pbYKHbZ*8T}r7?Rv-cDvm=g*+N7~_AjDu^rFVLMs#h@d7nx-{%)T0 z3OmxJU2^d|qqRm;5gPvtSLZ1-BRQI|x=D!F=s-PMG2?w=mubg9_&P5<8T(94OSs8^ ziO_!5TAZ97*!x@4*+K(yS_O@^M9Rp zF-=uq=tIS?EH01oN?$n8DVToWn_7QuXPjk#m+Iij{LO`Hd1{-D>Ju})c^_xl-UnP~ zXgV=gz2`!z6O+i`RQ6up@4gmAEJJP_8o!%M9dmcn-Q(m>^_ubZo?t*Olp24n(^Lx# z0sog+;qfl*jHZ}7CkyZQTR9{_VPi|rC%seEZg;M(vrhsT+%>5ryPCR?6R>R7J!3;j};X?}x-nSOR>~;J`~Bd<{9b z@>v1ZQS%7Wq{m{-UUHpitCAy}gyfNZK$p)AXQ&T&qQf173-F8sU$5+3ssu3Vmhust zhOK#5{fN*?0z%;qCMzEn|0WoIDkiPn^{2SeDx}D_uIQTaXv!ardwjxC!meM6tEeg7zmoku=KcJkd+g_Q3h*(;?N*|nNMeu1l#4vRW;z-6?3($@ z(}%P6$(xflG*n|UYq5AGEE9}{`m8@NZ2!>~9Ja+7-uLX4?^1CU27bEu9^KmXb~5@D zw_>+;?vY=F?9Jd0HgX>$Kkvo)1F5fnWgu%gtV;I)_PczH?PeQaSXG(*C@RSLs_0Fb z5J&ZIQ(*x;b?&x8;sws988h2(uY&g}kCzv+zAXZ>TVD=qhA zL|4OzHU!Vi#j9}j&_jo9E1Pc}!BISTM=OI7cbk(SOF>_22Vu7rO=;jNvHy`0qXF~b zo5w4Dr^NOd3gVZ46zhI@sJU%j-2UmFu+FXRZ(q?!|Ma!>7Za?DqGw4B2nURtr7CGs zbWtCLuRYJ#H?vTu6Zhi_Q|$APKrSi%&n0cn%UC$}Rk3e1mYH5XjBDPgA5KeEKhWRP z5J!upX_c|?USf3Z&eZF-pYCen*IVOyNiXSUFV^gbk)F)4 z5wOy+{t~`Z_I^Jr(P`fGQ8Dl3--;bv)B2gbcV$+_+g zWvmd_SZ%N)a!`CyPxAFS$w{D*7$J$h5xAf*;fp3Y*jUhSGksj##)|9DYk8WS);G~W zws*uV(#w@N&d;ezZy4{FMCYRM)F9*!7dDXIPSt!rWNn zmqJ$9cM)*9NB0VC^mO1wClsG>==pZ=F+du+@t5oe;Enxu-{Iu zmZ2+6*cvYbpyuxvSKbv07G{9O%6@&*J%0Eof#Hp|=na8~94Z@c-8U^P%WP1M!VFeUC&05S9uFtB^GRNxzrH zv4eL&Ie-W%_w^d6v=kasf6$vpXUC!M0VPgVTMA>>`9RH%0|0i$nT3Gz@#A!N(ik1P zK)fIoslA9r;;dr_DIyUPwVb#<7ToUwv3u&n+_;e#2aEFNcJAM?)d;jS{7F2MGtJ-s znsVe{`yb!wJT$YazZ>Fm;K%W_?z2`-RSc0nAH}qLrHE_%JH3@_&w_cok{UuPvOf6T z{y}s_avElF1U3^=i?%IU6lJXCQ&RDuGePLuMbQVw{v=oLCxPuLYCqaS z*#a1)c`slTZ%m?i#=Rj!0juE7r%m##a|vT3ENMS{1ny;8_4DD?xhN-i@oiv&8~cbx zhR_Vjo32lBcC^WWZ&jRuJGeU-JMBQlK)z>G%1gcbS$X-_`kMd>NanrXzjGfebcK{; z_|&;lG`ZZd=PpiEXgT{J{yAm>$7x*p!nM|fJiow!XVEC~?Clxrq zAb8Jo@u)8wXw?vR0@f6xFJ!8Xvr zxwwYFxxsr{d~G^W7KR-#RmZt`OL}9RtXdbWMD==eP4s|5)B~5@K|m}bP3lhew2HmH zBE#bJ{D7?M#Azy=_X#oq?8#%BgcINm-<8ou>nTU~AQq`jxsa3`s*tLn55#3)@d%7V zsyp#2rDcf|XwUma6r*{25EJ}kx)^b)vEVXaOpK^V-Suz*%?!C(XQRvRq>TeKo(z-K zx~9R+@sj;6EMh*^KO%?0Qak4hllA_5C`675B_s=cS$PgNaf*i7os#S`cs~DhY9{V< zb$p;=Sn1=$X_!Y1F_KTIPRo(-Znp)W`{aI)lr83wNG?y(84+twCESn4xqpgrllMo) z1_C)Q_qo9cSz|7#MvK%CEdd(2czhgC4(9TqQpZOw(l!GUYar=SOgPYAm+{aaL`Z{V z{Mh`PT_=K`VodQYY&l^jqlV}iGgp>9c$U0<_fnp&6JqVF$Uxu%-yt9qCjZ3hU*Gd;82S(SmPS4*Yjh{{~H-%_Ew<-R0oepI-uX#OBD?f>YS(fN7vBE;nGl=u^xP zM0h4f5hrS<>Z+dJI=%>-Q+9|b-y=knCoJyQYp`nD@zmk5WrXF)qsVQ%j)dFzPq*_{d%-rGW3p`mcd4vqGvDo_@;47KK_p~9*gYp+?9%_&k^OF9D2p<-D$bup&#b;- zwh8-tWzmN4kyXhFiKL7ti0*nl{}K4vfJQU~!FxY7zkn_8TYb|`$!WE}C7i{@nC=`xM>Ap92Pl%`>CtlXH4C3&*Ay9%tDzr3R%;d4UvXfuW3PT@taT)P@&*`EAjCnODq#=AH2lo9!HqA(NIX7N`|Cg7~o znhYzaOK1%y)Gu7nqsSbx%J3dW0$-u$d@#!1 za1Y3ka*q;t>0v0ySN-j%Fa>0Y@Wp%M|NO!Kc}o9FQ=?woy1(Gd!VlQBj~^qfXL$rF zfeLVp6Pc{^AyR5lVXnBnoi!cL#yNHH##*n1up2T*T9|pmuE6@Y=67yxtzc`UkgpY)I>Kd+hrx6m7nqi^+x$6wc;fBDcln5j!-2S}( zvs`+(gn>!t&s>0;77Je@^SVwE84vTLhs9tERNDFJUhOcl9J#sKu3%M{^vcpq;5L3e z`s+f0$cGA9J=9LQ$%>TguIua%-I(VLUYXnVP9tbDe=zSamuu4Su?np}Z-;rm+Fw4W z{<}u^OAA-7)sMm1=>Rd<%G0cA^?XiUGu=nXg>SEX;KoDOcjNN+bE~cL!Nwf_`nme~ zkzoAs3lB5yDI+`3(&V?*8v7qOWO%U1nFuRNDc9_t#P9DSum0MWkk9;I*>wIl{5l`h z8L*tM>P%JV>8OP;Zx9s06HpgjvR-R9I}vH%fE0yS&VbPBgk$XqM`I^MLX|!10SaMO zeGfp5^+4_;T6U~E&+L{XFfWQSYxBc0Pj><(_@7z}*KI}|iEHt(F_5H;h z6s*0hjLW*4p@p5?24PB|a6?{lrYQ1kl@(vm;7A#}5dBs$akk&giB1hMZG+cxIj|pM$|RGFHE8GY!kswevFBC@)3Mf|`De#1nOTq}2)Hy$FS?z(pI-;H(!E7ma);hQRYV{s{3n!8C*tzU(M1}$y-(hWg0kKCzQlFk6(cdw_LmIv+#TGu~dei8!^?e8H(whx=RGmwJjHW%$iTF@BG?fKRZoP zd23;inp1k9V)`+_jr$84D-?@Xx>Jjk8^68tSrXb;4DN2tKk}Gi^jwG3ZP&6f7E)A) zK8sV1zduBlASj7|jaY}mT`Uc}_9ucm1^JVJe%LVyXk^QbSoDb-*U`DeH_)lG4c$D!QV-@$;_vA@ ze>kz_JQ;7cWe=h*?IKrr!%6d1k~=FMdN9NpOp}^p50)J9=_`VaqI;K(wx6R(CGANr zb=5Mso;?`#w+1&gY2t}>=(XGp%=ZaRDS3@sv{DPQjv$=rmmaoj6eMmUc6fj^ShVyy zHcNJPA+=}e?%OnrTckn1t0;w^Abc+{^9$l3B|x2(1gC8+>+u#2F;W$p2I< zMnWQ_sjP5C!{5JZpl@}l*0skV6B5`0DGtKAeE+>y>pUeIX}4|0>q739b5E(cEw0N~ z>X$zyN|mC!i)@W3J)Pi%oWqZRG1?QvfZ(#3o^(DtsO2-EN_$$m?ASMdwL_c)SvtJ6 z=#47&$s{-lh@zt}$3D)pymeiwPmMOQsbW76B)~i+S?9dmnFp1xUo|td+TM124?$n8 zq1MPoT>&vwLA;R{Ka;##8+YApK3;Q%W>?KuFHdou%_C9#Dx_185i8}KyK~d$HO>J} zy8afxPjE=x#fp2-*}UtV{btcwJ+`hIg1rtb1c}ORn{^}bmrWQjjkS*8!t1%McDBhJ zLF_S(iCn2W_2#L!TS2|8z+Zt_)xe%kWea=Lae7+Z;uSRN2DEbta!(1B3zHJC(0H3F zz*UM?V!Xj=np#4qD~o!^O&YNW*hiaLYFW-8>}rGQ=BM5|C6*&vhz&?~h5_(m}1CC@HaBL`;oJpX~9zr@fSuZ0xRvd-Ed+8^L z&cdOhdVV25wAo*pIZ;4KQ}p}Vd}TjSp)rwjkcJiLHQ!OP^%H$_!< z*`#B{A8}+h&}E>s-h*sK2X|v!4F7D*x+nX6{4yA5{**iJ_6t6t;?8Ai+c<0#rIOIZ z*23_qXYqts2-Z_IAF?uq?~J-286JE=N`b;54uvV+qlWBa@nf`)fnSlm`f`Gt)Ag}$ zcbYl9RAxEx{#LKw=j`i<#^LG#Au62MDXMCACK-Xp8c*fCuMB5oWmmJiH6txc%vq<- zDw?mFODkU+8`v@$UE>}gi%P*xwZ3Q7KlE(MpC<^wpoBFQP26z;i>%McgnIagVgaU3 zH2yL$GMR8Dwr!-Ie;3AGI z$9a@&@|rFZx4!vDSUrEHxw$&cTwcrbSoAAJ=bfO)KOEuB&^@X(Vp0s>1VvTE=VL|& zy~o@ZCFbGk9&F+F$jnDCgGE3aI3OZqyj8PI(zDyee2;G*NKQ!kEAe?Vg`PY`-SY5f z_2c%(2X9HeUi7=@q4oU0_0;2tOYE@*)KQJe*PY3u9B%J=f}QwY>^><|^leheq(NVWC8 zhCU$GcS+yNG??RZq6t;qFQsnM{$E9+@=j}8Ppc?SDLg|mT zzO$6{)@#1?-q?EiJ5Ii7GnuHjp7X)zOyz2zYZQ_d{4gQO>VZ6X7d+E7rncY)?Ke}G zkSVIn?1Kp*ZBqy{O}>c%MsDY1n$6|`>z53AX8(yOL(wre+L?og4N_R@(zPF9JM90b zO!ogdsQjP-vHt+L?U?fLR6sq+#d985BYzK>1I}Q=(P(w#FhLoKEL?4a&L2J?ziPHR zHCXDn&4Z~@_=R^a@KWPluSNrkTyaU!-`;EpVE&gkId=2O$ur<7=`*^^Z4 zcBAMn12nBL!$k<{Hx5%tq-frd_N8JC9ldPvnmBzEnHtIJQ8!qyzYvEVNTQ06n)X3p zJuFAbNm*l*0jVyY11Z}R2Py%JrrAQEg@J`kce$Bl+o0)Bbc+x=R5+}Lv z^^hPhePUE475rbU^)&eJIxy=yy+;T}J)a{?=UC`xB!Z>O-mAu6nuCBVxXT50=Kcbx zU!)ZNAU9mL7i;xuUNQ|L4a;hCCn9tdxjsQGWfQ6AU@Jc4loYRX za1jy+t7uvrDJCdGnV=Y5J}uUx~>=vV)M&Yfx$`=2JG}MVTSs zOLO8<5mKn;b#T;|;K%U|oQi1jCcP0>hU*AQV=Q%dJ%K{STf!TQI5*iNl#J%2tj|ka zBoxUwjk|dt7qIna5HK0JAV>3ztPE^sy4pnetDDb3yKl##oK`Y{dmu;hVM80r=5NFM z$a_a##r`b<_hvB83hG$45VDMFryKPOahtj<cOq`qpAgPd>*h@GJNr0~uHdl#DtBWJA|fOPt( zAWt%#E*LgE|8|$9&fDI{ZE%w~8w&*|xO8K#bdQYS*6UH9Ad>W*h<@RRA^Pwqh&7E5 z*wR=e{;6iytbopP!+MYs!md`3XBt=Whz%RG;M%2aR*bZ=?Nih>Z94ajsP!o3!@nPG zo`Qe^hbB+V6%j*<@Y4t5ltg7V^$|ny7VI486mbZ-w}SEFY7(WuWklLT-%S4d?nvbm zD`Cn=(d4Xx;q-82C8Dpp5Y8^`>XaXFh5=L*C^e1Ts+52gPF`=WENt`I72T327AqVv z+FhUSwZs%7-d{0JUZ$yW!yq~BawobGQYG3sLkMZn^#XW$?wyi$fu{Y8@tSfnIuaej zA;K&3+*7S7adS-m`1^gwEScT)q{9?m9Y{fQPI|Im&@0JBuc$4P9QvVsF zm)lZj8D(^mVKa~ZB`fuE4YNUh0xQ*FDt|kO2K!Uv<8bNErOo}4v_&G>zll)wabRr{ z+=wq?;wy-KmUrtB1=SX)eP%9;72@l6nJ-vWG$YyFb#9;HgI}k71K!rvg(4J@*mdqC zvD;Ta-T#uV>4M@Ml|4g!T+F}g%AODz3M=7(b|U9OZHrUUdQ(I&ib(HmU%&pL$ETQ4RpQ$$q%6_W zaFk6#x=Pax!N_{;kxr;iX7f061EdvpaB7#GXaV?Y&a^p>Rd5SX$w7bs2uPte&84Z6 zh$}Z~!jrk>7MWmaq`0IMEYwZ3-W~(TqX;-Hr+*1IDmFCjzbS5?EVwKrlwEG1HzrCT zZgS8afo(?$>Snv4o1crmMgTje9dzQRi;9(cZT%i)T0!9(v~BtU9i zI}+Bs0}CKiDVU?csxRMyHR9RH`dnlY@4z!?o38ey#sR|Q@BUWQEQsy=1Ml)lpp2h@ zTqNx z*!_aXqjLQ=TD_EjclGbfOAQm`K#y+^a$I|;MtcGt1UGz5){*5e1s;V`)zbjml=}RJ z!&$3n1j_rE;s^3HkkyPZ`)N9>jqpeuuj;01w*)&Obi z7m@1?zo-9uU)=#X3{oe3-zVU)7qnjO@$#*mR0UIj!iSv#h-jn;Anx8tLUX+3GZV_cnP51XN0A5G*Y~FKOwe^r1+nsPfhx-b^|sU0Rz27#K=V%Ou`{x+K9?UHiYHx zYdDxKrGNzv%JHBAg$e_Jvg}`s$uI(NB#f@z+$h3hE&M#J&?^ z@_}og4%NDXJ*9$7UL_<7g_9ZwcWmE-TSfsb=^eRlfZD8?6kCtJ*)fr!DAYK1`5^mf zv;berhPxYI@UoID5APB}JvbsZnkKH|5R^TH%Eduot&Q{b(;cKeZ_JIa?uSDmRqDU0 z2LQEV6XeMl1Q(397Ak(brVHIYI00qX2)Bh`!NP%dV4NGt?k>J>;n6^|P}(sPa`Wsa zu2a4MMZ4c@_W^Qt!)a_Kh}B6|7cd6OD<~Xn0S><1vK`lB3~!rQcBBOQh|r0N_Zl(#YHLz4s3n%!9t@iY)!V9btsY4}md{b6G{r5JL^xY3b#<++whN#eBMKpm=Oud+Az?h7Efr@cutWW}?DVu^RFbyY6w=TF zy#@hzDQvN(T8f9!Gonf|mxwPOHx^rgo@>FTKJA|wb(CO7N03!Bhs+{Bz|<#zqh6K^ z7*accvL579L5Lja+wzf?qx!dtnD`1d=!zET%UQH|GkDuca}XJjuWUkjh1-^5BN(_E zHqm{XoMN7$-|exHK)r6B@06GGLk9cBd#Jv6#bvT%OXF3?q-5Q z%&m5-cJWS9x2@FUxgcn%_2l=i2k(!ojj2(aPzV2dW7zKYj)iMb1wjuGMx*AL$i5Q;|!cP zYm#oUFaOM`WT$nba6`KR`gTrCM1XIazYK96C4`psa zrs3>7!zu{nj04?wcEXAY*hvUmd$I&obBZ&mHw!M$tJg?wjE9L@|2e}J(Y+r9fN4bz z4GyxVCN=7VD(umg)ZUpOi@w^3vJ%@`UbpIL2_TV|5s^dfj92Yyhn>1r(E39pM%uTN zJN+IhRRsM{lrT0-N#MTs+08dlvG#QdPNSZ#tEX3S_-EHy+*VQ7Zz{{OP`2#_&~t8_ z>o-pK!PBYr%5WC_>c}il+vB6 z!m^6Bhg0B{YtUnrldiB|Td`gVS<4N0rk)yVYOfnw{?GJ!X&=QH68B#W0jbvff5V~O z$f3mHYYHacx|CpWgzwC~uEwyV1XRZHAVEVDu7HawspTlSg$SJPu_B(%BgA13k61FW zSt;?X8Q|={LM9utUW+z6L5uMv-*hRG4E{Vur4Y3!&ZXl;F z01XU+Ms5iHIT0`ESWsVAj?78mTOQqYHg|#c`+I;%40|Zu^<;^lT$Rc}j z{HM*lY=dXtz{w_OXetpLJ()RaLT7s5HKi~#3WOsC^KkSQ8jTgXnq)%^ z=b(xp&ys#pYbqui73(ygG}0bS#_qMh=@O?$%$pG4WL9!~Am@=Z{({XwPenJtLp^{^ zI1?+JzMixA@APQ{E#Ktc!l@_pM^k6=q3#Ya5Ny{TwT3+k?Tr!80<>;j4M0FYDXNEn8y_%jj9Z4k!BT=qcx zqFK%2Mt67C47QvBCr5a+9JTUl8p$HaxP>>_cjzfxG|o`qW*Vz}D6Ltscyg6Z)d(TI zK7^Z#_^eyp-W)=U^JBO3*W8pMa_Pql{_EDk_d{mLc^)4vI`--uOY1f*+^_O`Bv?W; zcmlE-R&pA)Ri+VQhm-3^kihr-i$63~Xr*Nt;s@A73+AP!Vt-h|rWw@b1FT@*^qr5Y zf%=G-_)&sv5tb9N)&6wR`b+2CyTu2u_`NflIrc>+yOOPFP^1GXW{7wST=GHXzxR$ey(9SNQ|>{gh?ehA8bF* zX5wD|E!I%gbm~lBNr@%9fV)KKnzQt%mFhpB5xtMOo&UBs_vf6P^&lEjDf|D!# z6Z@e9fvdhOO(MW{gIZd(^(^Hn#DvL`K;|Wyh_x-d5w@SA0y*5iZf^m>wJeveRWX0Ohel;ngl#C{%H66I z|3?)Yrbh`qzO(@&%QJThZ3bt|z{3R{Y~9X&K93M*yJ9=GET$4r3bBE8aqU#Zitw@u zx4al-yoBw8717Q@gh}-h0Kf>s#=JG)%+>G08bu0d_H)f-RG3B% z%9pCF?ZXXbO0AW%%RAG*dhU_ku;|NA3p}lSnwQG!fFuzBEF{p=d51uxR(o#tA!x-q zZYq%;6mE87*U|gTCb{pGMx%VCX2Iu~-b|tbIwMZzPwRDYVq?Y?#h~vvUl3uBGP$WI zJCf9JRkRk;*r5npn~jaJU>OI5P?EN!`gt(O&#(bw@j4X1R}6BRJdERT;GA+ z&G*q1Fo@!yov&$B^8%Ukc}wJB;;gp+Bk=z=Bl~)Rv)*F>lxC z2p+%Y6S&4GB;mWhu)%eZlS$C)bO)mqVBW+_n$qdY?6la|U%$Jbf60%+k$wbE?JBR= z9w%1FdFnQIDCje^j(O0zOC3Bm`Dzsbvc7#31>d-6pKioIMNY%18B^#jd+_M)_r0w&6gyCGs21&r^cqpFTW4w z-XUoHcRpXPr3jOaR&yBT;Qz*HU?K2V zRf=@A5eRPbF!(Z{E_+|EC_k{tgF^ZXySZ3yOBoqmEVlWQhkF!ru=DSzvn{kmRoT1e zj5ta%5DCp7C>Aa(0E&YK;UI!tAoE8 ze;pBogeA|Jpz+~G!oL?FkJ^I1%fUr##N6f5os!BZeV2hV$_(E{EW-S(!{J2 z)EXdV8?iK4K$lqcC%3cbUND|Ab<%rT@$bQdH(+s7rvoTPv`#ON3LJ%+V*$;a2Ui^- zU?~A^R)-Ebh>@t!r%dHy?|1&W3IM%kfF67EqN@8;g6jj^x5Z+p-e~E9L+yl4gk}`% zL!tYXft-Mm-KBhG6}&^-W_R+wJhacDA%!w|&6gS>0J?C*96~2M0KW282O#^lfvi1P zAP9+LaYWc-l%}Z>-zwww@g)d%1`MN;4z2-9_1z%iXyd;iHw*%*bwY8sR}V-TW|3|J z-Cr!b&7qEDYRn!mJ0--b*Sa6do+iP(nd=A;hcAMC79oLT*-Sp=dnx#?1CM;8z8%V4edHJrgqR z#Yn!I|3YJ+K{BXxXBDs*f-)P{!=KUk^X+_0U+A8DdIJMssSgu639aOr6g@#LKCs{9 z6v3{gd@!4X^cPu&68`jn;K4A9kuash{1j5OjCMdBW%?@Gezy5x_6*Zsuj)lO2 z_r9XQBAX28Z`aCeYx)4V_`57N6$uI{D?d+#uiQ7`Sd!kH;-PdCOIwj&cl`6SUiyY+ zBTp)Ta1CA@hho)yj9xPeIKOM*SguyDhXSKur0+@ML)NY4^P3ijegVj#WuUbR30AbA zS!Gt)(sj0XKBkH6GEGvy=K<(zsp;akcnxk42snSl0FqOr&FDV5M17Dt>GEcM_9BEp zz2+f9MYdyzji3dOBEwwIF{paQhDzH7EKSj)+(fT=wIdyS`wjIa$po=tHwZRtk`5V2 zADE;TA5@%1cNIlJ^pR&T?`l!-;ORG0z1o5^Z3atN1@uV;$hfd?RATfQ^0ze(Xe?{( zfuCgJnqTV3`B2ll5`M1IyC+wkS|#9Yp;cus#_)T~fkR}ZmLX#G|5^jZ1BR`%1oLGS zkH()Uqs)`5Grb)tCr}&cQ@80t%lQ>bF^H8Nc2*jg9ew;{{T9M?ehoe$&cPb>$AbZxw@XwLhO?RM$0B z^`G>VsUN)t%T?!UAo;fp@H0V7R`b@t&g1+`V@Nx7A=4d%>>8VO{){8+=Yp+#fkt)p zuGaXiAKyon|A5yH!t_IxJu#SG7L$cns+Dqw42(*e&*II0=Lj`!@j5-D@$zQk)mIl; z2mn+QkY26pjhUe8zKC%&MH$>|Z8Dx1EV0k)hHROWQhvq}DnSz|%F7|v{c!;dh0}Gt zn*nX>n+AtS^M`GTJ}!XY4npqrAPX?21_AJR={W0jGiV5e!ANOe5wN&dvq0NBjG#$h z9(Fb$Yz46oFb2yk6O(UVhmp-^4tNzj9RW!fW6up5-Cjl3wMzV@3r|(rPyMqL8NjmQ zsUhr_j-WZfU&PZ#tZxJV&us8UFy<=9lh!LpC*3CyK~|_-YPLkASuW6bb^zpeb3qsa zOFts?vQZIF%Yc)+QI4@w-n;3X0VG?6Fx^XmIWK~}_x{xYBjeCTBqu-Ny72AT%C3it zBcq5B^N#~%J=a2W7sL6q{R6-MInzsVR{Pq|rZ&fa%)l;;%Agk+r2(bhi0aF(s! zi@TvpE^TYpL(Fk4V6jZanaylyI7_uj)NF1;?c;W7bMagc2%nv2p#f8)+w#&nl zJbak$S_!Z1jo`DGvKfg-au!D>WsK?V{CGe_wQi!F7BeBa_5(uA*xCLs*5I42fd1EMcWh zh^u9(cd?R?jEU!9Z63#(bU(og6>=k@9+%9FvsWI1j-&|)67rAN*RP|ddvlDGERKZ! zF?8guo3PRq@X>ReA3AZIz&$y()DJ9OH}v~TqP{(dj{F=4vu=B0d2YDUfWSz|)GO_( zn0!KnnSD;TC|fryMDPtrfrK@ydZ4Gb!Q((U8^UqUKP}(blaYK~r@+Z4k1C~`Q#j~R z+@iQyP32o`6^M8Eo{5)nUC*`}y?J9VQrMsXhnc^44nMKo4^71Sx=%o$HOpQM9>MJa zyzPd_YWYxVeCyyZ-~t-P)T?v_a2Cn!Y+J_lT^VbfIxFNRE@qxz-XHlK_Px*w;)B}lso z=rDDxo)0gA@HdjcmzG-tp<=@}2)JW_eu=b>{H@9g&qJUWHjwKd&}(l%pK#U1cWz;{ z+C+${Xnwdd@^etJP?LK57ZIi(`hIvU)&@2(w|KON8N82OH@o=?jYD?=8w(o2)aps* zJH@07Q4*3LkA79@dMWC6m&y#FG0fsD<0V+3_AVI}jdlgzEBvFM96J`Vw+}adCMy}L z^cZG`b4nw}&UX%CY`5j!gV8N2W3S`PZWO&NyEP=9wY5{n0f-gP@O{J^%ul>3^@Nch1UUh*UXk12aHq+4L6 zoi_fh=;p6Whe)D~s|Hvud+e53dALH4j9yiWF|jmQ!G^afaI)C=10+AMMjbi=KX@lp z#jd6Wug#vG;8_KKnfeM%eiS}kR?i#rE*qBFA8z~sADC2X%vhS!@Z>y8P=9~Khjg^~ zg$tS-Y`%+=N?nm?auT&*fvN$ZY#Kd8sH@lKmAcqSNIWXxXOk@nvCvC==e9DMYOEzF zBQHaogk;xU(;GuVLb6GLgYQfX1o$q%i$6d@qH!(i5D7`@YxqbKH7+a-3CTOTDs~bQ kSs&yNJdgZ;_Xn*qyGe|h961egFjx}htEvi_a)w_27hSqV{r~^~ literal 0 HcmV?d00001 diff --git a/_images/docs/wait_until_task_C.png b/_images/docs/wait_until_task_C.png new file mode 100644 index 0000000000000000000000000000000000000000..0ce279aa17bce0049287620f9fbd85a9cc1d594c GIT binary patch literal 75676 zcmeFZWmr^g`}PfjlEMHI3esT^4oFH!NC+s1z|b&A2@EmPB}fd7G*SYJ0z-Fq2m?rW z%M9I}@0#nn?*Dt=_xt7j_B`9OJ>S?Cvu4h9=5g%%?^wZVuM}<*-y_Ds!MUxZDE9^j z2M>;eb7PtC7H|cI+Zcs|^ASf$PWr8@;YKP!3iZfg=Qa3VZ3m@C_&pCw>#%yRd#03B zrcVdj#s!PN(bX1zoPprnl*6@ReZZXQ_Y>jA{L;YP$lbtw?%Zc?zshc#zM{^+nbFR( zaT_D>kxnH;$l?!@A^a?I#aHvs-z;(qY+x?zRp4Jla?n?Qe}sh+ z(U$V}MHzNbu;^d+vG^-8Q^NoCCC}N>|J=svtB4}{`xA0EJ}3V3GYEXv|3kmH3(s1c z8(!LQG2VNzD69JAsny^&B@Nuy2V)0QO3$%fxQBDUb*z8xyHX4%_TMj?vsLORU^vvn z*z+6XfgVPPN0s$S17r0-K6=zh8R&jFMnzo=GcY1|*p$`_IsW=B_Ix;Y3`0JDI~>Cf z+-HL5QBmvww<`{wSz|}F3r}gC0k{bPWw*L4#}4@)-)~N2z)f=C=&~!_zaHlK;QwvT z|LvXswR6WNq;DZk+t2}%?$eOWZ}#$o2CM6CJMB!r&lOx4jz%F5f26tRo;O~fH=>?G z+Yrdj>Jryo=<(e3)fkUagLqAjR@hyE4vFJw_`pbVm}Z_w%5RY_4}63^?CaG;P=px zq{9HzM_fE)+NWE$LtvCLZ(Flh3Waa|y|R)s;Z;{>>oexbwrI)gi~SYOPIK{+fq;;#Vh2&Q}gg9WR8TT~1KYw&T|=vs`F6uHUXU@BLEEA{z*K)}JK6RihW4;xwuQYw;%< z7&# zNWIEFVDrk6@Ai37Gv~wRZT91zJO;^M7`v?c3x+C%*>wBm!zo=B0Qii@l z)Tqy0I!$9w9XZCXa`?$azc>15+>|`IGj*r?ap6g}6Y$JHrj#_0M?+vQ@nv$pmuZKJe3$Ln zt+Jt4rEdB=MT3`D$Bn{y56uz1SSuv%1?&>0n%=wYx7;=8xcx}7vb3QdEl+Znrr(MgH?m6gnTsv28T9tN_gl7EO zkh}i!Xlj(qrgPB$r}tXU5B@``Z|`$Rj_0v-?&AAR5a zNo8BK6!EM^$abquE z5}%7DrhJ~CQ_=+Y|45##WTB1>>)orFu6BYdYlwv5`1;S|9D5Om&O6=^eGB1)bagCPn$C?NmkYaC2+*1dXovYq3>!kDzJ{ z2M0$|&Doyh$voavq|l%7Tet6x3zl5AQN1q1^fSR%GJhpQcxz_Hmw?f7-?K?0f);O@E&i@HZNT}<+LOpba;b~o zZDcL$z>EzFej#O8WYQYQId3JU&-F0IA^?M{tvQ*z>(C^qp>6DQlq%+wJ44^6K#zl2 z_9RT|evV*)xSBt}`y5`>IvLvaQw5(DJ)W={NDnJ2_D873^VRLhP|+Y%N7XBTCUZ>b zpwk>0a@T15qLvc#3TnFXQ3bVI@3+bN*LD_KRhwAit!R%-jM8}4y5ar&hYR}s;`?E# z^ejqKZx}cGo&{U;EeF8j5$bIsou#Ql3y_M&i@lzKT=UtnPDT$@{AJ{0pR=KKnDOFOCY7WUR}6udqcNH8s3W!LI%=zL$h0mvii@ zMlI^^;K&-YbGBYMMKBI5M{6yRWJRs>=KJ-c_iov$$>ywx;7BRSf-F}Og9m7FC#O=B zCW^&dyz#Wx&gQ<~ub9x}@0Gu8k%{N+eBPhS$v*p!cLN^~JAshrrvq#FRU9-T@*E`D zK;fibG_P;pd{bxrq^gs$_I#^0IgSq>cdo(fJS>r9M!T8`!jka_+*$5Qk{RTo9cLU8 zQoUoyVo69$*&Zs|7UOb$-c0Uoy#7*I+4eM{@!~rVn|&T7T%4);xgJYH3nm?Nf447^ z0D|{0(s}=ciSlHiDO8j@JT3j|;73JY?Gq-4Hi}W2G&K~MG46E7?T3Vpc2eS!w{g-z zyd`(t##E_AKT1+O0pW@)BQ&~BaRa-I8MsW8TxT>%&0VM(Pw35M0s-D<`s$;x0KdP3 zKmBI}l4++nvWQfVt!lJZKmcCPM;GgT8B*M41@T6d2bki`11MRg>}Wu<*4{%jta>>f z>4YHCA919HSLGLnlRNZ}8TlA|Pdp!p^p2e%w@+?gqq(WvT|Q<=Z(wVh@yMFqpU&?# zIH-!W`R1^~F!Ckpa^2{f|F|Et7L}K{bmi_^0job8HQs(|h`R4QZj$6Qd-HdsXzR#t zDRRx=YOXX_R=B5=8rM-|$lFL-*g`4h=G#22e14!&YUIbMPLjH2PSC#V-+PsfmprAZ zT`9;s6_l?}fg9RBp)GDW(x-KkMq6nv@Ivj=cZ#~i)*0%$sDpkGjcI(p$P%d@5L{=% z{%en@YQNWc@=#LjbjNH~&%=Iy5s!z|-Z#|1wmrq=SBscBeUZOC11yknyF`Z`+$kb7 zs>#KO(crG0CNkNm**vuL?^}=HYRJv(FsuB z0uS7Y0)F8$a*is0M@b);zu_=HW~w7p zbn7N?a;i)H+f%+D5Yp^%K$1J$bLBO4Y6ygZ8f>5wq*~1<~ zl)4o6hGaTRC$r>4XC>Z_jfpQtr)96Fw9|R(nGG^=C{dKfF-z#uiG}&EJnXAbDjqKB z38Cy$V+mu)Fa*NB*}d~D=C$NR2T3tXL0B$J=gexcEjWoko?8dHSj)^z-(xX*XM3h!R}SNM>*#(O=XdtT? zpk8eX0w%aw304BSJC%F(6_2_nLBYX~Z!X{^R=?D81I(ZO)Lq?T!#pzm+H6 z>V)bN<*S7xxPJ$`K)`6M*`?{J8C0p}2BNsi5>BC;qH0m7BDX9C8>{AVcS5`t0&Z^x zOc^|-)xJ~EShC(y4=%IepM9kAqX_&vewc@$5W`ZALz8`mld(C(?^<+4F>sKK0}XUW z5>I~iTBAa?V}o;@gnF}Nrkk!7p2NSpcl`QEc0gNhDceA{?7mjp7(xF}R=dhTSl$<8 z^?{h@z7lKM8(UI{{sRK#hXwB;-Grv;>_yBA-iXJnW71Dmk$!Q(V=}nwPn#Wczt{)O z#2VYSZPJ-IA5B6E?ELS`+uOLLvuHRHYP zCob3W3Nw=fKsTTNZy_c66VtXp#pgouEQ5#q2YvE)T{`1;@UfK)>8@wjPZ zHIR2*4*@C&Bj>EJ`t`pH55XWfg!H6Kd>BYb$H2eP5`1 zkhf*BeMVbVw@$NF3+lwJlL6U7-cJ+6G z?D4C-1YZ7T{<;^kmG;y2$v?t!n{q3lv)su>Izs*V%5k>KKe`3GduA3NnrbXszKwtI zjWO1CxeyYs6Depj@COWAQ6@L97-LV-itlyFOW^M2=1US9xH77Aj~lT)9BePJ@eI~0 zuR=o8S7WAQ$)8QMiE42tny!x(=zkV1G@>J5yEpr8bAj#X;cA%NPSGwF%Bo zm)d)r*N@OVeRdBbN zNPximPlpo>MumBhtOi}Du-}lX&=@LvX2$WB18sh=o+OrS`k@?<&{)6!>zw#&z-`3{ z+NOUB^?z^coJ5JWO|KmBje9EfaLv?cK34TKsoyJN4AtTdbIaOwS3k}S&UR}hsBvSv z^@WgxM^nT7d;2@Wr9Bxi0c1E(&`ZSH!09a)TE5(ix0ErV&t3}uzJ{4`J2L+-u~p{% zkP+<-Y)&J)ty4Fg4S$YeNtAg+4X(co&qyqVt#a35#jhgQvRuf-TX-~;mKJ8*oF zoZQ=3Wm3k5`+ts(jAL#?ApH0vi=r@YXB96nSVEI-Vmh2*=IcZ@{1gP&oo~uG(yTcC74A9}) zPm~`6_Fs8chSQI1xg{Sro1jTgr{f8PYsR=E^sNbLl(=JnC51nn-N^fwJR3M$>YAg9 zna|P)obOnX-D88&y{`Pw@s7%kanu6i^SJ*HWM6~xgO6MF{Syf7S+^?Qo-}fWS2rSYUaZb!E3+W%N0B{^aQNUa6`onQ11o9QI3 zzbvnIC1N)OmXe&a^_u_LX#Q<;#%jlZ&Bgz}*D_qlK4 zAbFp(#rBiV|v?Y1NZ&&XlyzU6HR5)1vUEj+yJztcHrn3DsZzF1mW> zcEpN;>LcVtG`>z=ZDZ`uhqb62a*iV`%N?Y@O|D)_A_^)F80CJ3Q_ZS-KgdmSR3?e0 zrf^Xbi{{IDU6syqQ6-SO2|xPOd(iLx&Xy`u^5MaiSjfLtii0y*52mkd=Zd6*to#DT z-cKe)M)4exsTtbimo=D!4|)CQ1|Pb6tf1Wfk}>pSHT!v0cXXiX2wR&}4$dPg>5J%B z_u;-`aoPUU{#*H_Z=UX`znrZG4v^Br9`o1a5xHVkB38s8>4A0TAB=}D#N9o05gB}! zV+Eg2^(D)S33=!Q*bV0Pn%>8K!DOXA1(n|NisnEAJ9niuM`c=&Sd!%{BB5@!bmpj? zloBf{$#+SZS=TBT!n?J6&8K5(vwot^+dO8nw`smC!_6TcpC9>E6j@kZb_#9wx+P_5 z=@+o=IU3@skIXHV0B2@cy z#(YV+WJ~JZB)`+u7w`F?>{kInp9O`^Bt+afK9 z;A83sb5hCT0wyoXc5G>Q(uK@sP6`Sq&foRFiCX-|U&WO{9d0pJDcDbXI6qm8bj#y8 zHx6e!+w*yxmb~Xw5q=a|KqBoa-_EcpR`^HRTDU+PQH3aNjKIT2iP)WIaf6|wex^nB zw5YWDe)NS0@bjn=d;x-^3MWsTgfe&c%g*>x@{0wYdy@)Ojeg|byN2f{OL+OfIh0iL z!{@4j14JGiA}V=M^n|%7QNGd#yazT)(;e%Q{4IQoTQ7y4R(TS<_C_Zuk&OvBkPMZ| zTNRuy4S%vSD@sOGec5@H7k2nDQl*@qxGA#S`U<;!TlJ{shUbtRC+;N~0Y`pBhIiJaxCIm1 z`6_mPKUS5&Y)rI5L&G}x%e44}-I{`(9{s-l!l)2%a8}sPB7B_<{b5hr+p79{HTs`Z zQE?4taDo+hWeT2c@=tYr7H0(A%$k(k&i0y|;jGy8WQiAbNi3QTC82C9MG1&lD86{( z>d&wkxxOIEnDkz`jpw(azTR0CXVMYoV!G$`SBe%KO!H+(*w_GKmWij# zX?zH6v`0njJc1W>;cC&^@%U!&Nxj3gl?X15bn?d&;D4fpBdqukiA*C~H#^@-K0l|l1tI-NG{8$Li<9c(`uu&sC}d?6=uKZ(v4oI2aBrPw@nyz`u^L-XNc+z zL5NE3o$T!I477Dp?PLTir*zipjJ`naQuGEfGUa-=`~Jt6GNyF{$d5aQV^JiPzCjU)D3w#=JQn6 z3>pEpfkd@f>qv5K`i0On>&8B&XG3Q;bLX1w4)5MoX0*lRtKv80Y_Un6Z3M`*GmNhM z&KJDg_)y~3mf|wf`m$$#URs0&VHx^`+nljYe>i+BRCG2S&>n^zUKYMOGK8xVT3j>k zH0*P$t_|?oR&S~8_Q^^DJ?py9yW{D~j+Ubg{;wS+mlAHCY!ejOfx|(e~ z=&B#+j$d@OZ<7$h(}unk$MN8f(PeJ5yUQ$dlbYsyTFBw#ClZ@iP~JmEaSVjQ?2=ZiS*)+sxsXmdd3HOk^lV_JD z5a*pZB~v!xZON^YPx-M^h5O$6!yRhCZV4iE0+VR3Wu>@XOZP$8{BJPjLs&r%o%~v(EWpcH9EyR$ITXI5z-!Z#mNAooVNr z&1Hij5Zv=(@F+|=Ga@4(YTZJGb!=&dkAfMH=l^)`Wo&Pod4*KlqZnF(o%e^eP+;#c z_W|Cpnan=p{x@r&H+L27w?;lQauIp{C_n=Q0b?k*nD=-PFV- zLp45s7AUWZOOvQ=%Gg=4OWH}h{+YxN!wV7F`yklICW{nyslMO0#6v+5NlOyul4TwH z!nh>gB$PD?|A4#+ODa@m@Xl+aJ|*JO_y5|D%{^Z;3$-;6G4Gr9AG;1;xC@o&$J=J# zpEZLZJSi-E?h^nrp}V_#I_xg>K%4ku?Sc;gRp7X6@{V7fqiktoqWVQ%PryQJP%YN7 zh>MS(e5=T9)KE9SR#x10nMVB#h*Uhk?mDby>F!Af&?gi48neuN`Wf8RfaDUdevzRs zRS;5gGR_JKjO-%V=nOIvaU1yfjJm+cvnW8FMgo$M$yDp)OXx;e43Y$89TMk1EF&Ka z4q)|n-)oL|zGwPPoV%Z1@;821B`M36CmA>AjR;qe1cGTYgxr)5=VT{aGVC$?T6!Zv znV{{fXXigN=Xv0WCzJf|ah10PCJVUkyoP*6Hsp{WsChEyJ|=-le~jGGtuu?;H~svr zK&XIEv%pTc&2zj1A|t^-+q)~T=Z`7E;avZ0tx-O41eU~Ep&{5G3J~XUM zf3GL~5J2N@!CHd@BL#MI4bHRFj~(IVzk~sg*)dWo?UDr2;C3*eF!MWO^;H#M^=vJM z@X{qgL8!Ta76QTQ}Zy z9fPxVjF`KHM6PS5{V;^Psw{uO5y}OLwSf3MjWs7$*6KHC?VR zFjBUR3vZdA1=@v%u)_MIkb(lLLk{%W!RnIptQ!UpQ)H&Mb&9dFkj*{Bv|@xXz^Wt% z{zb3wx`2hDZG^{#K9@b0%X~f#uO&~v>6QIl)Yh3M*>1e{o;uoTC9l0n@@P7&$j}R5 z1Gc_c7dY5Xz9qFeMx}@jNgVu^b>0A6)TL|{rN~2^zRPKN|AbJVgo(`L%yM2~gX3QW z0bpUT732Q=+zJYW1qIPOSAzjZ=JLvWP<_)@Rs&Abrw( z3@N;}PBH0~M;Sa;L%arqTPmTne9qcNUgcBn>-qVwxLXyNy#ByyRym((LxKRFpz3II zYU;89Ko~Yt4we2jF#j)eR6X6s;Aj0K)w#rL&U0VYWvd!f1Gw6liaFrfrW?+;tZ$&h zg=dS%4_e8dakFJtOum0i#f2c5CXl6z>}&uain)A!$$1K*urb+-6u=bUN`dzkJ2JV> z<5u?Y)>eT{I}&lQ9^Aq!$l0tI4r`xav;{ zfKhO^1uVn}TLpjbZI3xPU&BeJ_3y8~BQv3*9ewJ&@oyrq4t?*7;m~|wGM$@K$UR|u zn`Afq^D|L5FqTu3VPeG>fNET0;4(9Uf3aTJxJ4#$pmyBFwp!GeuUqcuu~8f}Loc^f zW;J2TBNSgXR|@5_N|nuM8E5MlIQdADxdnR4B@vP9eH{;I2ho2KW*A2*cvb6e^VTQB zCs)J+_=JRQ8eQN{hM3|+7W9SZ9l4ImhC`m?UtHmjK>>+TJ_G~yD)k|8Ec~1#P&=vH5vTS#R+*KD=_NN)c8TLJDEg1vw73(0k{YRN^ zOahSIJX9>07b*|XMJeD2UecGcQ>Bd3LEk}-fBpaljWheJ7;q~E)Xw&akgs#g4Z+h8QXVPYP z&P?9E5q{@}+)Z{qou>~)O~VxlRf}StK#dGo>~G~T5L2+S2QDRoDkLEu%=mjOw2TyLQ68SHj>vXbF^vaGlewq{PQ|J?NxWk z&5+1r0PqnI*j10nV_=4Y1T=jQL-&pAWz|UO;~DvUNfsiWZ6#{*LW$OC{Gnvc!PItu zlP!F#j8urz8T!fzK3-zF7Ad{W=(!_(JT-SEWSz?O2>oE{)04#-`3MFp8XkW|R~`ih z2mdLb>q~+2AV7o!s0yh>5OI$QeY}|dBhk6lAL(fm@_NN&v>j`049vsz$;-Q)Om?G! zX`)EqSc;l3M=4ohWqtjLSfYclC(5_m*q}UYnFzYVS19#P z;5_T|XMlYLm=kn%NYo2L$NN>$?q|o_>A+5+Mv+VCfX`scNG`t9^r)Rd>v?x;G$bjp z^#)zO)G-BEJLzV11L9obvGd{<1L61AKV2m!vseb}pBX%GB;ofe?}DJ6>Z;= zLPebVd-H1Af9m*G(=VeJ^+g}tiWD6;RfcQ*9QA^tWd49(7e&8+$k$&2qlBh8-JO}@cSM&{0Kp^T@us<4WngdAlzBl-Aaah$h_EcX)K**XY8nZF~eQ2 z8EL&RS%lQQh5MpT&(sMDn{V<(-v~C|eZotM`}Qu7Xmq5SG|Q#95kB(!-Rvi?$2KWW zs98WOd9fo~x~ADt+Ap~t0l20pe$y4uJHq!(lN}Pf%z^cZ=lki`Hpf$++G*5Rx22$D zzMCfEOk+3*@eb$>+g>Mtae7+Hw|D_?dVN(oFHsx`BF_l)NtN!1TdOghCtAz~32+4s zCq}4l`1nWk-&<6%y=V#{>Ws`s{v0IxGj|1O1MiAnlXI$VXp9V@T7 z@_llMQS`+E&$= zBW7V*Sn}|FP)iws=<;|P%b|CPq>4F%(_xs54m-}Vef}R8JjY+3FTTjlQO#P}DwW~x zDolJbs_VS6VBNmQEUv>ix}jd0E1#o+8u7=juy<5{Ck*S&BNQx6L5(h@Y@h&I*)SHi z6MU9^2lcv@%uw!V_RJf_FLp>X`6xy3dT6(zBp)a^LCJ6xpOfgbJxq8Il0rMsD%2+n zBJDOqGQbib1h~HKiDLK^H~f}B)Ulre$SG(daQBUa+oI(@sARITGRlG#yeRmp-lqYf ziTQFK_Zi#8Jb~1cN_l*3;EM@KTiqTU+xeU)>l|J{njZjt@m)DV*UK9Kfpn9Ln3^pv zAkvwxgYx(^CfscMk}IU66}>`JsL2QSaAVFt;VjW*esGkks-TBeHCJd5aJwLk)2Itt zLq#Wt2-2nRypgIZ^>p3KLs_U z9t6)&Mg!Vj@h;?}B@6D;s2=Vzzmb4RglHR0K@j0feBMoedQM|az4{NuI#r5+hJ$N4 zNYmmJv*7AOmFtVkFhqXvmo^5iw@vOM2g@7BFvYC%l6cuF8mvf(2ogD87l}$FX<8;H zA;z$92^;aU8e``hZ;{d4(sEy^E5K=w z87cz~37eZvaljuFO^lFIBg>s0*O$k(jX((5?jKH$_Un4iK=Cqt6B3+D>G<(^W-mxK z>~MXi*2SDYo-^}ld|aH_sEO@2egE;F>RJ5jS@VxpV?MLJedfH8I1#9M2ls`j|79ex z0P;H_ONXF*=Oao_{5;(Qx*aX83b?^=zd|Ygs5F$El7 zFr$EByFH&Ek8g8f`y9Z>Y?JotR`C3dAn9kEM!*?E2@Hs3Q;lGTo-&Ca7}WP`BqBP%~NoL1)MVS-{7lQQeELcNG5SFiFz%mzSR$_;+7Z>9~Tq*2vpZB5icK zRwP2Po4_VjWZi)b}>ZOm433o-va74+k?k zIW-t=^qU@&w(h@bE)bFbYLFsoM2ZrA1CXoji{GW(W7?1LaQ+}`=>CMt6>q`!YxAQ3 zYBGmq6McHW@TKwoPy#7)m}M@*+WJjqGiH1HWQM8gr0{`HK%>;}QrI(uEx8gY9TBaMeaK2)2=q&ULEQ^@-LmyL%h}b9#9g#g=!+n9FGgCy=-TczXFFI6z5uvKn zfMbuH3jdg9K{7YN!pPNDnEZ9f&+_DZ`mZQnFZ>x|yTgwk*sQ6AJsKY={#~N+|FzjF ziC8AzCA#qVuOvv8OMA&y%bBu2dY2(nro;-Pq>lbJGhA6h7#q;>=T{8RnK|WYc7sKL z%zqell|-i}OOZUU8KTTTGQbU+K5ImHnmgD7`3uD3Xf=k+P|Z>$iNAfXLR}#nsPmb+ zmXvm9k!3w)ix6S05u@tmF{v(- z?rqZmn(uN9Xcsk&7t4GVl3&`UTdOUTi%mNxy*FM{T2E6k0Wq*1=fi3s0KWIs()dOQ z{^G_n5-Hns;aNpY z*F6#YujhbhU}fvje3KSZuateC8jhI99vPgJ@r^)aS)iVE8!qE@IHK*m5yYfb7v((z z(9_VK;Z*CdjKXuCrR!6bcIHOWo|RTZ9fxZpJqGYzLFd;+41@A1$=2+@Dixrw-oBUy z427%KWZ|MF`VkJ|ND|gJ(FI@mo8=>fqmB8#Y{>3nXy1_gKfFs!G{_L;_mv+}@Jk@Z zI@)nw(mpJ*>>&U#Ik(LijR{l2!N0#LQMq(K{P8Y6Qu53az_M$W@99Kx5Q8g$oGaNW*Q_Ug>rc#UXNxp9^K4WUwpJlx#xzo5qi)KsvHpCtvSFD_ z^28Vms!vr<%oZ3to03{HuLe%is#KTRi3k&~w}~%I#OH7c7>v);?OTXo0R8u2?zGQ^ zpA}(kOn)e{^7RuEB}*pS7V$~rwZw>R`G^(_0KOe8QXB$P)4k}}jsfJh77Oae=L{8k zA3hfTu%f1S1mM0!y~16&!x;mMcu*ep+YwpF#XQ3Z@=|7Oj4f%AQRuFkXFAWC@VBVb2V z+)@2`KCo$2bOFnH_S88q0rntQMp2`Pm7^rSH!Y3Ktg&j5fEItD#i4b`u4*4hO{{EEWQ9}y^96iKGy z<THxO*dCE#GYkwxnetS_kH(L1mZnIYmmRqj*Cq4tK z>FTawrMy!4-b8TgCLra-BRs~7OlS`9o1f3esG&5`=BK6Um)shhEqI?7Zkixy;SF9z z{>7fZI1X7so?g2yz^zHg)(?W#*@)~ zC8Of@z|q0b>)Ow33X}Y!^4)v!GHnbuY$waCD#8$E=YU3H+=DIF;Yo=77DKFz3eH88 z!kJl|l-4b#0UOJOBR|cN&CsKzP1#As^+z22)yq$@IGzLCZn8#Kg~2lVtP15G%`Mj& zG(=rqu(I6w3%03?{sKD`y(&sZ;YuX&z|cdvp;su~)1$Y9qe6w!_Ugx$QKNk&5rsb} zxG;y@ELvr1T3!Qnl9@n%u_%#qCSiBO7TxrLe`htl(T?Q^H{(STJc#^>udG3X_Z3Wg za8D_@@S(yCfHPzt|G2NQ`RnwuoVgA;Ynxtq9rV<#>GO`q1oBNXM(pSD%2Buqhz&W> zk2$8FI}{Y&+N2SBeOdJyh`q-s^E^PFvPNfx93nr+G7@E{T(Q@L12UMAh%*<`p<<>pKJh+%-l&l2O8jewZDNMWI#Ps?sKEPDsP^2PlFvS-c13;J*hfDPGL@fj-1Kk z0S-E6SF?+Epa=kh%u&fUopBm{SxsmGAZ9vW01G)zl-6&!wFWDDakh+i_y>SMaD)SS zykZ5L?gCIuQ?^{#_=;;gE|E%;!Ugjr%jdPQ3&ckla2jKo@6yfG;UcOB?hh9HLNHS4 zJyieb6y%0{0qFt}#>^_~9p>SM-s#j7(jpP=0Rkk}+Z6tY$5w}B$$~#4b=G8Xp90Rb zFktId!bV;SR}IwP#qB&~EgStVr=bb$Gi|X@o6N7_9E5K1!fC&A`;Q#-55o2hQN<{s zHa=j|loN>~KMW^(DY8d=r%;!N)qS|!o@$yY1)_5uXvF$bjpCgMj-gP|zJQ&q@Q>F) z+5SQpy1DZ2MD}RaaV2c=Q0hO4Ep%}qh)HO-ty6Mo09#hY+i(JEJ7+@p$QZMyzvl^rcfp zl52rK_n<8TyE8&Cl}^s2<=k-ySh(a+fV0Z;SpXGAL0|VS)zH}T3{j2;1C%V`<@0Z< zTN4B5`oz{tFg}am>8CP5rlPdZQS<=QW|f(A1}&HM43ul19*(R@ED8XOvC&4$+HdRC z;_Dap1c1FxqdM*2R%0QiO>5D?L!#<3SfWFBAL9 zi(I|-Ig1(jq4DEY#YOGhB`;e_#f-DwaXYP1qFzp=p_}pomMe}eQlSs01GgaGb9;al z&i9ZY|9080lt{PXb!0EYZ4|XwNb@?UHkbG z#X~1CzF?kcmgLbW`)B30wD=c9Vtt0Pxow;NB)@B=4vBBECE?R)sa}3z<9f3Kqe*^+ z`}H{OFJi!U>flZxJA=I7Ff(3FGF!wU$zx_fUjx;t_b@Ed&}9XY`~f%#)t@f_nxDo!5J9dG~FNzuYvDiK=nWR#n0!2VH0Rab5$2cFDr31xSoSB|_ zE-SyAM}rDttNhO{i(}ot2-&`0uObi2lC>$FE;5mwY5+qcyv9fK^_D-c5r=+>~c3u|lZex1u2#Wte0QRN+b!g@a{d)3DU=B<0jO zf(JP-QD%`z9uEY}`(hX?gPI=oB1t+?105(Tn_Co0cUz6DESDYXlfdwt_3sP?Ov-=S zwpN)^X%ZqTkG|dp(zrydJYj?HaD=5ZXxZ@Z>@IBM?$YRnf;cv(DuKRJ#IKa{r_VSh z8rs$=v;6#`T)&d{z9cewS`x) zND@)DNJxJ;HRfXUYqICD*`BTU(3+>|xb5iOjl-S5y_8FY&tWn_z@bxQ?8|dr(dzz7 zuA2a#dwE`LwUae^@8czfZyMn8BwCua@Cf*yslV2Ltb}PQmW;zSWh@pCJTLLuJhODF ziYwW`>tw#8M1s4~D&#lA?)%Ru;Nr?hQF24nGt{XeQStps+o3yMAwo&+&R%65UoxSA zMSSt)H%)`gyNR=O_*pDHpDN2e_{=szyX*V&=^GzDLPi-Kb(ZQ6=-7iZ1Y~!BtJs)g zf*&c2DP3og`BS&is0kbm`|1L+l><+{nB56APkLYY%hH$Tqy0(>9LtbA)7$YnK>Qx}PxJxBLo_KB)OK_7(Ft?l2QIi( z0kV(^a|}tuGGI4I*5n0?a68RXQz?J>$pE0c(Pe!Zkl=_UpzL2=|L^j2`kkTltEWrR zbg5lQl{wOC?k);amw&jVetjcH_?h`O_p3ght;A)%#}d^4ksJL_j`kmg@_%Jv0L18D8F_2#!7aiFnLEFb zPV0D0psp9ba=@`$_2Azry?|L!&|2EhL_z6$zE3uM-mo~L%Nn+I9|a`g`FXrCggvCk za!c=w@d~>Bj%Y%I!McHGe$zD9sXEhqXm*ruL(WLJI}r?S!*xT5Jf*Z-+%cAlm2Wd z;*dE_gm$V+3G*;nq&r_#5k(beEm`18al{Aqy1X&oRbcln`Fg~1nJto@r~pH@ zzMXyGK6D%Qp)kL*-Qn#NW(FzkHNDZCK5;t6{hCBFNb_xGP6vCtr`Gs3cFZd zqrk0SByDbxf&*?wUMo3EtkyeoE{YS@tpd=X&MklFYNvrfPmGjnE7EcVT#ZTgZO;?u zKyQ_bt`*rh=jafKUi-s%G|ax=d;o>DUwk;wrA%Wx6N>+t*t!-Z2$OG2L&u{x^G%R%a(8_TN_N#Mc6pF+X6!h62e3|CrKi071HZsVlJw zAj|Pd-JG%SHmS@2qHSjIF7-p%KqM`Ed3hZbjX)%iRtD+Jd+KnaX;8&(Yauu@kW469 z&vXqK2qVyI8 zHYdwiZC<8Kc!PZzg!JDB)!!sOR&-N_D)sz8-3QT1cXR|mVQ(UxVMp5O=J`OSz+4Ba zcjeeO83?~i!&uOx1-e$}Cbq3IoxAWLug{`md({GOIt8B|%kteKnu{!gUQZYuJN=cG z(Il8fw7*#RBrF%7 zXlFwEGIao2-QXJKTi+X3T5&@i*e4wSvzxXU5NBQELfl$%Ir_DZ)%glx!15VGDnCZ| zc8dizaaMQ(uFVUy^)4@x{sDUVl9BfJ|v;) zeEke-mY84#L)8&ce^WFuk=)&8O+}^WUn!<}tyvkcQIkwtbM{){`d^^%&rJ{c9b)}~ z1|p(w`@m%ednIn8gxV<+$>zPF$81_f`uc2`+f0_DSPX)dS4h*xKpVT%<$1T0Xzjyt z7Re2wuf}cP|MyEh)JHtDl0K6B_;yh|HT>_TI9QR3&9nbKrTxOw0u6!lPd{?bf}JO0 zQ}Kve;YxSaXbFoJ@lrs`Zvc~D@zKFha!F$W5B8={$JTQOE{;r+@cvtVsv4K7$+>W5 z+os95$C-KSH{}*{UyyLyF}N)_26QExd{73O3)Nr))8Ya5wncKocV9W^p$Rjje1^y3 zsd!1t8!h+fNUrKgR&tx=MXBt+K|!`|HIMC`F)NR>}Is?IhP2Xv$wgR=GF!SSZ(`5e}=llf(2b&?dP8#V?Em^;lN8PDtv%iv;rh@u{8(upiKX7_R$gQApS?6q&VL@u0`r`)dZF-X7yHf5+`uNHhgOFl;u9ZVe#_I@ z6-P+$p~uHs>8h~1{^|0*xh}t>{-fgf@bzi&Ql?>fRP*BCE=;D9c;VJJ_2*%4$hqI6 zf|OdTg_^npKL$(~9fF15thGM{l3t)V$zLT2TZ2&WPda;FbP>Te-S=#JgG^-pBXTv( zW2<=c*=AYHIiMA=DU75&+pZh(0^XW1FyfTiu=W9X%|ViVJ~>vI8UtLPl{MYw-PaO_ zZ$CKY>r~hzodd83hKA>*-cu|$Q{!{BpZ>XC=w0s@!7XgMtdae$Hj5*CvcaNTK>Hcs ztOB(^P?`6D{6Br*&14f*$@2(3F8o2W?H&fOWO>O)C5$=s2wj43Wt~@2^g@U> zEe4u_D!Y{=Ce22H=cFhazMFmIJr!5x%}M1S@Ng{<(B)+Q$o#DhYb$`@*pm1UPJw5X zuWC0+LeKxi*l1_hyfJc`v@WdI?@yD+%3E(Mvl>#7vn9p0SoHwLjR2a~3v1!+MTKtZG%r394jMoLsldPpS%Mx;B3lm;n9K$H$?kQhKIal{TyVMpS4Uff>gH z*3hLcccrt*b4*XI(LN8<1?H|Df!piC60Fv-LVMulFrR*oCEED|D&0EpFsMGB0eWY; z4lFZZ3f9wlRm>&ZaU?(7@q1gVGXN-Z_+c*bugePy3+vX3vRtYcDwi(-1B>ywQJ?NB zhF@j;7ZcS`qlH(Plg5s)v}!$I;ZjW1k}gzp^SFC zu))RLCrz&eWqxq&JFFB1q|}Ag_hdlhm~Zk_eAPE_bZg4~S9#>{l^V>7_|%__`WwFS(USQmbmP*3WWmCf$E?5njEzRC2NPe2 zN9?^?VZVRt3U2U2i1E+r8wdvLW8w&^kc_T-^{%ToNoT3%EApDk%-&mFB)m|r{Mz&) znC^P>>lG{XU>6C=c&#&63*L%-9Y6uYF(%)S4bn(wz$%3XoI| zMQTm+r}`MXBLMkj=p%vc5q$|Q3!+6m*to{75tQer3AROX`K2Rh6ozXcd zA=avTndmf4f7p3nL{e&71*a2`VG!{6ns{j0J25`;+luc z(e_eZEWuFyqaSt>{>Qtq;e(;B*yX~RNiSUgQ|QeCa)?I_SvSKxz2+ODV680qu}@Tq zk%v2X?Za+&X7~mUD-hZ4F9nttf(`LtHB0%G2Uc%&(^Ct9TFhnq^umC+RD(osl+*Hv z{puZcaXaj&j|x>>sc=+;md7tH+rbI!z=#?$a?hxIz*<__X5}yWYqP7S&N|K)EC6NM zpj2v53|6@w#N{-RQU#+r9I=nR%z@I5=Xey-H`%G)=;S;O!K*?XRUzh%iK2=@y@g+T zOc`^2mj0~uVmAuFUH5s#O6Ago5UI2)JS2#lDGN8O#&p#?DtE+Z& z1V%4C1R|1l&ZpU&6$yb93YTD|%6b-;p@C+MR4@+?Lm@2DGK*qb=oH^*=bD&HONS`_1ptCw z?FzqYsYPRra`jvtex;;}1eCo=b1-r9zQBc?iQ~b#JlP6-inzF3m%xi#PhtgQ#a-1h z0$`29Sn4nR7_hK9q620(PG9tv@}cotP5=zUrBR#=IUW%(VrIPzb5h%s*=)x{C&Bk9 zw-(Dhq8c~bmTsV3BM~{tqD(^2FyrgM9))-pn7FtMbDia0aNY)+(Tfv)fpYT2q!9DeT}CvBEh`66$zO$9S(7ocq!r^q$siI&^?o@J=9IYu znV$v8!nSi<(J@@mH?rLf9f~u6mx~nbnVs_?iMl7)~y2%)~U6fOmvH2TK_^3uo)T~^tz2{GNt-0rl{!m{_!tK zyeVTJFm`b9Z_t_XT8N|BOY|0u;L^&lEDthDfDq$Tko3N!9K&aA_iErV@_<;?lCCEi z#S^QB1X*X(^yYfa!|gg0vsq<}sS~eL>foa{=ZO^1Dv%483^foeBTR3ZJ$5V$^K)a* z6%Q?0Z7lXX!c%-$mI00X_M=gRDLvK=z+{%ToS=lw^^(!DkuH^c*o`!m@&z@y<3s`p z)+SCMRfagD=*xrM6$cnxiU5r|Va>GR;V5Cl(0l;Ana=|w-2fNXp<3a@Mv zlA7emEG^EMlJ;j%XhpxFHVu%$u|P=Pk}pTP58y@0Uk35^#mwKFcqm>=26cBhKz^>* z4&rLkJt9NL9ggw?S^g)+$?vHZx^*&vi-w|!7g+kMjqgvdRvZ`bJFkqce+fFwlJX16 z5~zF(n#|9@B~0f5dR1)fv{4pA9jdg`0_Zud1)FDOAS!of=bn-s8lS&2?~2;Bx6`J&~`43%jzR&R+ZEM{|DG<>}B0_*yO#p4QxB_pjqF;$&& zKXtT)H&8-FhzuG|p^svsCH6Cc+&zs62RAa6yt0V3$pD#UJ79!ToFfF_^z-*v5hAcY z2#|Je1O=*;LQZ*PqVAvwP)VkFVmFVEMB(EW6Id4AZ`+0NafvY%BxQS8%Tw#`e&32X z3#o;t(grhDv5}nWd+)(dKPHlMLfOSG!&d97OWC4%Ns!kmgv8KsT$y_*w@*rT#r45( zW^?)LN&ZozUMzzZ$7EPLP4$QW3{v5xLAtS<`=ijty`q*3)4((ILW#+X;*6}XryiOH zdTtDvv}-un`0HzL+E92n}3aoud=NCPQ^pB^hPRpR`JKli+m{qfDgl+NX9;?1(n8fYNmblR?jdq1VrOTg|Saf@*&R4R5^Z6 z`<`6*B12lsN-4Z@AyFFsBU5mBL55oYzC(@@;AZwm=Aa6Ii5qL&hG(*G+oN%DmLDIB z>xP;$@np4}pJ0l1*PT|}Y8bxkOVAJW7>V_CmYLUmt^4%j`#}H8QjHDIN`IUYgVE)m zWBa)-s44#H@d*yJDo~h@2m#{tUvHS_nh=&wpgE{zJ68Er&S8QDWdiz^(%*fo3_Fd?4b4sYCDz5vb4hK1vFrk^ZRzeyI0 z=U8(Ed8@H`lPQaKCy-R+8FTeAHSTY#__x^SKL#(couBF|rtaC7JM}(&`C6Cn63pi!j_dm246#gB?4DRT$IoE zOFqF{m_dOz?*5xLY?AGN-{I6l`*K`H*Ts4eJe$ni)&(h)c5R}~B!(0(Nhx`tR1zWs z!66R!=*+5(XNvVhv;>PZq~F5IL)plWM2>+UYI?TqXB5~*TDJ62T2?5rZ zkSn0&qf)yca36d|%~e3OpG)NR&O(1wx&JHA|>{!1Xueg zn6BqntH?&61p0!Yn_mGggEtj=d(W}Hei*YFJMBT2G-7ULQWS8cTraH|?4KMI&MyI` zmF15<7lHRzClWIc>Ow9aC!oryeH9!W1fj)W%77`?xGXWqgjzsU=n~2J?B>?!Yc+}z zx$(lj!VKgY{>JVy8t5kjD=13$*S8UzIr|qpZdup3BqkuE`6rNm~V~Fs3^)tWvX zQ4wVZPJ}8*piJU#_1UYo9aQpfy`9K%11wnYjn|}!iShNuK8?mmgmFOQ>NZo-(q0e% zDZ~gDnn#3exzmF+2-ixraiouwjW6$&3dyUzF6Oggv_#;KJAHdq@yC%aX-0gMg)^6~ zG?arBW*AKgBbK2!sR}$lJ9VZTiEoeVJo=ijzi<_wO^%Sop>ZSXdJj~!7YXS2y5e&H z=8NLrzr^p9+mGUV+ZB zD--0u)l3(t%S|{^jk}h4Ug2(u-MN%Pf_#L9oF!0i*4v9|)AT*t8Av$A+dYh4seS5K>f(U|R;=6T*gCtQJ)CSv18n z**X{{EJ_8n1PNtTwp>*Do}Q4gV{i))J$k)F5k%txazcb_fL&2;%uctnL=Z(}sEV(z z4<#q1T6xX7-AVuvqU9Gc6pB0qOz=dbZAg5Bua8iqWE zq#FgqpWIoB6Z%{zKd@T0*+Z4UYBd&)rAfEU;bDQ%<-!>Lvf!`Jf9CB~K83hpO>+RB zXwuip+PKCKo;6Z2A31Prx76vK#$^pcN^6+}NWM5A*_u6t#>;bq6uia%@=3yz_Tvy= zX6p)R;kp8-bpX8sn*daa_i0zw)kxHzhhqtXLG-+RBl+y5utUD2%5b`wbx?K#U)y*!hGi zI5{EyGXBmT!bYrDjWfqptYuY}XeGKJ*PhQwglP9!441vywwX|1-O_Uq!^?+@YpiVy z+@SyP$~GSMIl{`Amlo+ZfcaE=iwMwl#koQ0@n}2bNl`=Sx8NDfTd&U^GV2mf%Utst0)PE}MC$p2u zJC_2-3^C}-tV~HlMkcSvEiYoyKTZ+({)G7=r1*A-skspo1)uf2px2LZejA26X?CRKTW zin`Io5W;%33u!lpGH!jnDirDP$~;zSVMf>`E-E3)0YTCUU*Vd)xMxeoKqK7VAN7*M zopV+=CVZ`j{>iQ22+00?xv&sXEx|!$HU0)`E%lOjVmB;Ee<-FN05lE#fLZ23dE1d4 z4T;BxzLMdokre8sxL8X&#JHZ1uQqq~L@WRBf5w1p6J>?03o}~j+O)j^eNrfUeoF@X z)&atE%7#%4lqRPEytQT>V2VM%T^MDeB&Ls73mV~iJtcOBxzZfDWhDz3UkVz7VV^)P zDpQ`mzZ+EJhIwa@cbMrAXvBe;M zn2Jrv1un9PwRBr^{W1`|Ueh#4zg74Jj#yq=`q_r-dY(00RtQgdfu+&Cr#pw0jR!Cn z1U}e>x&YkT#rE5;(gjcon~ZzBlWn}_Ftm)iN!grYbx^%^I&R0H86YQ!F52@K)3+-r zUEss@dnfQr@c!D6Tbp!qx^<-S{1K?^4KY|B2y>=sJ~a5nLR|A<+1l1suu+F<1kZV} zjVt#40Ss8Qpxv`bqn-eH45H`H+R5;o{AG2*qYID1th*|Sw-n-=^L0tvt5!oxnAcO7 zE|^p@(+E%qL`O-EivXdi^o5iw0e;rr7t1t><>E2o_%!+C#0VN&VR?Y-pODOQ*lw5!9xu>2x_O`5pvrAwut@> zwD81zyr>Ex#;mWuHVv;$-ezy8O7Vuo>j{Y!PMp_x(#*PF{`Ng!xORXu+3Og_1rMQG<;auJlLqh7Fp-Iu33o5uxW(clFouwlyn`0`nr06>&A(hQMS z`g9X(n$#*vlcJ*O>J$bN2+}kL!Y#KXpokkOQOLyL@A~a*-D9o(ia=#NnN(XL3OqDW zWiSYWHwN3vQS>8)$(9IRy>@l$tP=|H{d`+N~6dJf6^*{-L7PVmS>yTFk#R1 zp5b7@@EMk>1w#>&-TGgSY2D__5WNw>z!Y}1khhEZ47tHipU?(&?<)*Pea$AY5+4*Zy(K> z5W4$F0;%{_%K2L56V zp~xT0pMki~%tsbM))^-Oy#kjoC9hI<(?RhQwOI&i4p*HXNK!14T}Ucm6Y7-~DG%0< zIi~wk<+T1(8!mx9|5n4-%C*;S&sQ82!#M;$?oCaxSTuWz?W!MQXTZnSCHT?ON>8OBXx&S&v~L`Pjm+px;clO|pb7N%@L zQ0Jwml6VP!?H}-lbM^V#p)P8srKWG5F67IzM@bJVc)Oiyb^emde`r96YwIeu_=0b2 zt)*{4Wa`caZ;1=kR#Y!DDj%-txP1oi%=Av96T541Fh-PLQ*9526r5GX_Pj!l)Wm-B z*UIHRF&^YO=hN(dDt+zxUWb1b#|E&?zrgy!uNNSyO<{i;$dJ9Sc}ntk!v9;Q*h z9XQEXyO;0_DhFzD?U<)R6slEXXlTq5iPL1^KCJVfH5b|Fa;haEB)gbAN3KWP{pf`8 z!HaRjfAxzY!8WTgA&@?t4PBQzKhkygc+bks*!c4z!FGP4ZUW-_;))dDQztiHCR<#> zR_2mR;%sIbmgOJfyB~yqWG>6Oat+KwEcPKpg?$(G7mKe8sjb&%ir8}*RtT$yoc(;0 z8RfF5+;vC4SSwF+tN zO)8cnPV7xik262|q`<4I*Rkvh-=N9&jwaAeaZpxEZ&U~X0v zsagH>v#b+Pw_4i(kLi&j(Y#CAZ_5HurPW%+*7??h@W@@$&7K)Qoe_W1vK4_%v$gS0 z0fMj&uBzD=bZ!8}bj@kjNCs#pamQ$>u}D3@n3};W9Eew9acSA=dBzM{8MtGK2#lnw zAAS~PJ)~L>#v^KalNTWAUgI>=(l`aWNodIj0Q>}-*?WR&+Y5TBI=_3{c3Y@c(*`2=t@v{P6w1pBIv$(tfs%a_N?=ot?{W;`W>riNi{LwMog zb*dSnkH>)Z=1eLzw)l(M-D4#_?? z+aGXgIQTS5EpACIoM|^4zda3r;e7`#%j?@!{_&ATLyNbw9`z=6#roM7$b2lo`Ply6 zj;u`D^77nTqbM7X%O^H%9Pb}J=ezH-q}-m?=0c7WRZ4fyKh@$+ud)BUs2-yI(Jxm& zlbFA1JDJGk5VP^ke!HW4E+f$*)m!8NzQkOE;dXv^H!7CZUwhG;k9p>0wVxMQYQW9~ z`d$feLPY(KQ#hj-LD_K{kCM3r6mO3?${Y>NJoL?lFw^9?ywv&pB%O|Nx5sZPq~dpU zd(T_ODOR%D0l#acbc4~oag`Wh@3d{W1pW{Z5K=StHr}9uHSqQ{f-$BYMQES- z9QH;F__NZ9Ij}VD2BlSGE|IfFSh9T+Kk-#pmMNb~A2~36ZePA3HPra_G*E27_&b-N z@;G0TPVz@z^yZn})(Z*f%QEIKKiR2m-4zrLnxwkbF_gLj# z-3Thkl9LIpXXZ#&4p-Y)7+5ASS71gX(nkn}*`BDCH}?Ch-|TX_a;VZf#G|qSMl&JH zj?N(c@%CK?*1`y^OKbTHpf+p(WLH7mb0^fg(vZ7JQvFIjJAVT)&ZIa zD$I}_nhy;buTcT(tk2gwVkF9a0a+;1L$K}cK5$_A7O>E3Pj!3&M!@-J-fjnH?4*fN zT)?MP>a#Y&*Ne2flb+cz2J|tt$ zb)T%}!hYaEs)J0LJc9872b!?{`iX_)y9G6uJ9!rQ8&R6;^+oE@pe;j{_3EZI={4pXOsw@KN`4wy@EI5K;-Pb6th4Z53uqwTCZ6^p6DR~f~ zL5e}HjQHH0gD|k}ncSr|G8c+8TB@N~?yQSOps>BDiU4)tdsWihaUZJ96dEu2(v-=4 z!;Jztg;(C^hb0#XtenEZoDK$RG?m&oVK1SBwfgTbEIGtpM%t@Eu71Tre`mRozHtDH zWL_coenx!&eVKq;mW=XZWpb6E#1_a=Iuz%)HhTurA6Hx z7lGcd<&4#)vNAQQm)w-5(i>BT@*~I<9mQV`>oEEnEkv$>fCHr%t zG){CBWg``cuUWl#u+BIxun!PTqw=6%uEaf>f~{luuI?0|>RazTz>AK02Y>GbcBLwb zpauml{)bFqmoZi|3<_$*WAhc6n#e@eAb*HsLxH;>(j*23HqtDqqC6=gH=#&UzK+KY z-?1)I*alFE8F=Lh?aG@upww=_&43prv%CUO@EV64Biz=Eo%Mn;&|Ay2wwfIL>w)KV{2Ms%12gv`7upq!kpd?^7sSNp}%Ef2~W!XV3mYz|p>e^F^xb zIN1bd&HnZFe8f-8YgU}95ZtA*cNz2tUFid+iUVEQAC^_~w4!hGr7BH{#kJk9F#ihd zyw&r5$8{<4&mnj5#pK)*x_3IPmK4IgdSdCU6Cot4!JKaacMeT1Za>H%MPC0wz^v)3 zXX#_vPq_K9&g~51s59wgZrx{crw>GNG!!2O8I(OVF6b)=Creb7PXT18o4i*qjtku5 z^!kb(xTuWU{YeN)iF9y7W%|yD6dYv7!dYe{tz12kP^9I&WXfE+ML#Ml?(fguZewf@4H`>y)z5?}9 z)V3q;#)U1h$}jYG&h+1^;^>dJqzY}3_;!kXZcOFQ>sg2sq`m9vSw@hms`eu+pz^}2T zdnm`B29s9BIfa@IfAzQgcQRt64=D}%ku-p(V9?LWDtI^Qfd(X1(RvH@EiF*6jW0u1 zqS1t=AcsYmXJ9e+TViN9gzeUUUq%#%#OCQla!Cmy+l_r1LiP-nY21dStjc%)eL)|45#QUY?jDm(a`S68T{3$5 zF}>$FyhiwlD>(Zp@r8BYNtV%fHf#@|3RzOD$=uXE=h+%d^W6+2Z4!3t2%)-wk=0DD zG4-!9)(&!FZ+j^UF`pJo*<0jJsu7>*_+Cg2j3-*SAkxdK2Ms9;*k&bBq>qTD@$HOn zTEEM>`*2)Crfn!Qgp~w@H#&pw{g3hFz1(D_41ZdTvU?TFmFJXd?ssg5yDEw6smZs- zFCQkZfZW-PJM%nVnC#JkPO35;)MZmGE~(^Fb3ld5v$#xlLM}1PWmtjF%X0AuSnr(F zinm-!hyt-5&wt%FkwzEYs))Qjgj^FnF0 zg(36KQiJ1x6CL=OZ`7tE*94*EzSEIfIEhXzp06ieI%+iv6&+GmCU#ZC{MDH!PTv!) z39?DuvIq84=ud7kGhWEB zZ;R$~4;gXR3&FvhXl}0yJqqU#=D{S8e)a?VR7BkqXuj`waYtcDv-wkhT>&AnVh?}n z(`V-?PgY$`hI|$Cy_?TRtK*K=KbI~5iGx1nzwrU)sKx>oXr)fl6J?5lO>+MHU|B_5 z(|SQol~HNUtMNdR56Ei-Lx*{7qAORRE#}7d!t@+n zk+B3R$!%q>5hfX>M4HBUv{1Lwf9aP5gcpM=|DLcQ{^{}%CJ#Nv-S{$Kl##}7G>^0L zHO!(pBis(4X)ZGyCXH-q&7Z!s$?NMSQ0Nt#9%FJ=GW4(=(J@yF;H?2JgTYR6UQr@|&gMFjR&6 zvc;Y^zBZo5DbYTdV5%O9k}wsOG3v{>U&jWG|B*3s(SXkAvK#mA*S&Q3;BvGCx_Qoh zxnug40NQl{pD(BNn)Fh!h$(N?toPySv@tIT;vdeBW+ueO*rGEZD4Poz-h*C<{m`D> z3ATy(TkFx$JSt!DY~$2+cG+~nlf3<3Pcl&xIkzuX;Jh%pp?>mXgrK{zVeJU_mF{N zIQZ(a$qfYLzN~|~EHR?PyQ(1sde=*=%=)n1v=jbeFi;^ol-9 zkS&n&=rgU3{qio=Sftg&797#O)BBfO8#1VPak}KrWJC+J{PMc>X5^Dhdj1KvJ3Ovr z9`W+@!`1Qrxnhs9o$1evHK{)nOT=%jWKQ(9#-0_mI;-u1^^z6xUvpyXN3@3Pp0%vL z23tRSuVuK#LyNEp1s^2Mjj@#(%%E|IOVByU|4_VnZx!cY!}BEcoaz>^`8)r!`2yXn`<-IQSn&2>&Ya{Ens5#1IPXJ8qhMBc5EQExJyZK-}DS2MKl&3$gu^ zq3MEkv)6ZbRz>zB1^M3II_RChe{nON;W0->?(N5}PnqKFPZ6UZI8M0co=RuSupai^ z#(ai=Q$ct`6;~^G6|u54>?RC?s71Y%sYL=YYvAzEc%WMzxMP^MB$V~@xNXO;Hjmat z9@HrBB#V$!ikEgZ*X6cAIexAm^;p-%bz^SPAG;-w`b!ygE`v29CMkmbSA(d;H%Kx^ zK|J>^S0sZ*^A1KDsDxP`=YpH(Rr<$SUpM=i-k1-FZDaqTUTc<^ku`c^FIMY+zuxlL zMziQs8&m1i)@39|aPf7Lr40Ot$; z7Q})$(jxJTnFD*cfCoGSNQW+x)0q{`jZzo`~q5A&y0&sS4lQ9oW z(H&{xBtIT$hX3@>~JC@H@d;PzzP`*7Gmw%-}FK6oE%S55? z0aVUik9(Wu7$2sr-xmX?@m-ntWlL%&3^pTDA1WeRE%aF2VRdSjoJW3{5{^4#JP>lu z5vIZ$y_0*4{e|kmniFPZd>NF?>9F^NjkqpW!7OK{vbSD4xtKs>RGLgdJn`wZ^%i8! zeLusB##xvI10F?fmYA*IxKF89O)vRSw878U4+KC&lFDax&nNE4cp|uwTFu^{7CfcV zBFM=~^l#GTWBZ>}fA<{+lSTpFh?S7Y0_990nszcBVd?{7LF`cLRtMxY2(%oiF+@L( z<*R5OldfrxNrNHx_Y`3a%g6%FNlQR)W(m!Zv`({@RJHN3N}5T!zrM(Z2g46PWZzWt zN#B_!-Eq%s=0!w<^#=TqdM@~;JaWsBn9>~coKPfU*JFW-@@De$`IkdeLzBXXT@ihs zZeLu=MAc-`A9*;|yN>UcI>UMrYK0-r$?DlR-z`MyeenbBqXN$1zW%BsUrK__n`LW0R_t zYtCK(2@XyWj)tlN(y3u`SF>8nKi;qJ)pxTS=S+WHQmr#$dxu0;dhZ+#& z$0UV7^@X2odzIwr1I4f`5f^25kLMuJZ3Hv|HTU;f z5>U$-`#Ry-oQ%nh`o-m?kg=O6-MpTmhC)pmZn2nD`QL>cbpo)6RfBqfdbQUKgIM8) zAeU^>{>c~Z!}kNiq$-5&-H9dfD3}{B?fTt?!1W*4bY1(f@jeH-k_MS`^TuR?G|UZ) zeU1MRSVIA@bE;i(uv9NpM58aAQ@SEH(W1V}?-{#P9emt)uzA!zjD?MeInUok8XI;6 zPI5GR@+Cy!QiN9ZfkZB|(SE3aNiKuaN`7Es^_o5%@w}qw*1-mnEsYsN{DpUQ66m%pC8B5maTHZZrOLUYDyX5tZ^@8pRb3=!mT zu4Q)ic%_QmdaHzNJzO$Vs5J2Bd)aE-^CW_uvR`1|AJtwzO->y_*gc|u>904F`{ZnB zIcO-=*yrQk#~MqE<@Eh^vukh9-KN{BJ$o>L1t{u(Q?7uEVpY2gXGc39f?#^*DIadQ zT7VGx{lRFSeaCL!GbViUwbUV_pFyYd&hYd5sR}0ZvfhRZa+7!K+nje|g*#>Nz~{E( zX?LdJ-y-J;yr^p8857p1w z&&8`A&q_p$Spa9J2Vf;&%L3GE4&oPW8`Ac8sZ51<{)DL3V~^;K9%?u4!V&Z}|8q-@u=j$hZs z5oj{rJhZW5>|MBs?zqu;a`P>Qg6qZ&sxcUM{QK&=GwUAA)jnNRAEi{yd^^N{?Hp9c zzmA7+vA222QF&ZZSXcD5k36U+V4dBeXZr}j0k-r7fls{B#tid%-isVCH}~u+w5~Q0 zPm7}j4b1m3($d^72Yqk*_0N#xN?~@_8>2!JE&T893kbrN%7`b;D~@%)io9f4e7fkp z=kkE}v%q&RB>s)g5YG_iE8>A5AT;q^5}B`HE4EmEXHk>BYPLYPX^lT0>5=Sv?l9#Y zV9HDwc$fyKksqe;s>tPyK$%$ zf9ItPi{$INTCGKW1c9>sQ(8gg2i#$jYD}ejGgBd~o?W%eq~oG&H{BCZ02)R)A|Z4c^0X ze*457j&24#H^g&VIVXFT-gZ$cf0|0l=)chiqis3N46@$6t!(c2^?E_Y-Tvq zDGh`MSm!}HVJ&Z_-#}4%J<6{id9qT*MV4CyxiFsBaI^ab!cvC0&-49xb4ALhSA18h zqIkmyJ;E~%HdkBkwkN4dVN-T^#5?4cuwf@c`rahT#tm0p6zM!9c-6{Ze~{wL`|i5L zg4(wPJfpFrS3NNg+8>8);^wBF#}+HLT%Zv-55*q&o@MX`?=O@L>Xd_M0XEA1m!zUVp`OI_q(0&ySQr zQe*9VKP_99hxrHg8SSK9s$GDRS0au&oCQEFUmn@L!O4Uq6iRn|o)dEgIA`a)yBN9_ zTxKrjNSDS}6DvRsLus}ZM}D~ileR7mVme<3-n}&5UUoA%Y4%+;?W3p&&3gQq(^WoWw-M1JMIvBi>b!}#_$zrmp@row$iu8YN*nq|m9}EZ0md5c2 zeaW`3{x}XUpk-~xNjwq@+LSNu?gJR}dJoPw>bxvMGB$XK5%mK#q)-Ky?DO5F&KqGd zST&!Xjrv+i)YH_3-b5n6p*Dbd;|0P z_vU@Zd^t2%SvD(YRPfeD{ab8FFX|!Z1fp*vLcjFJNGSJYyU|U^m!^M%y|&YL*wc=d zSRRdelq*=CD*YxJVQOdoz|Q4*{x#Y~aVO1-mHOAwu5WF0UU=qpU!Xm==&=uQup)oS z&2EsT`hCs+ZTl&WmzqDLo8bOAI~r|D4O$fUG_Ou^ZsgE!^sLGoBa+j*j>)b1cd3_AG*Xn1*lGx6TtYA0Hy-D?$o7-V9D8=>F@Gm zD`g-c~i$=n6S@2}h%Q(<51+fnS>^z6acG`^et`>T<7VA|v{g}`a2D~*t zn)K!8nn*X9{?KA*^C!%8#%$pqiz1!DzHbElaHvWXh&fBCwm^G7mQ=}?F7KeWpkIO= zAHHvlJ!TzSUs zJkqZ_PQ5!$R{0FY7ULq^i60s?F6=3t!UPl-d^=1NGhQL{Us#@As$+VGrdq-a47XYm5*&7trnTXH*8(j_otgFMqkZH7vB zH$rTeRGn%ex;(c34?89mL$R1nSsoMuE_HxZ^?VpS3@e@!~UMp?BytA!T5 zT9p?VV7o!pD_F;A+&dFKGLvk(VaZUM)VHEcDXuxxE1w0kgu|PaswrsRm_A}C7MuBW zD1v5;OCN}lj+z-bY>wu9X8z5$-xm@{RIF4oV3f7Fsg=~BSbEA4vUOMI{FktEF$XNi zmd5mh>_Gp+V+msmSsblx@2^tSB_iutb=d=*X(uxM4Y#)ij)V`H<>q7R`S6D5STk3Q zYXpvRaWS#yPjHnzwk5ZsidKh2bRy0%jbG0>mqm|1qy+D`pEsJ?Rz8yrurcu0)9pKm zT0=Guv@mC4ey*5Z{;%j?;a8Q$Al54@k@erJag>~BL-JC!I&dYd`mc%f5BT9fi}wRU z*aP=ZxY%@Bk?S8v0?jhz$KKnp1fd|^)!`~I_Q;8CLI&1j2EBbFb@^;ACAmkBJ2aAB zt@DPo6Ky%f@m|=wru(jq4RSk)g;d!Ghzs?0F8c)LDF3}tU=Qf9>V@Cp2e}o>V0N2e z?##d8mw1@GuIjo86C`V~cmA3z=Dt3Qa2^HwhkVG903Fodn-yOcS}w_Y3=-Z4If@$< z$?AWHiHfTXc4R9U)quTVmlSOcE3lpFhf}lHXhp<(Or{?DFO%)lMtuem=aM9U0cau@)a=(Fxr0a~!*OK4(TP`VF{ybhGLSdB6SI zYobD{l?U|*dtPv6Pd>!)no#kJ?s8_I?iJlie!!DL^B~Te*Z_^=PaFdh*BVvw>aczQ z#fVxdve{5`b8@DkXoEu?SVrn;$vIY3Ql3{l+W+w??KLS{H^<>Zg0u-o8rRQqT5g%| ze$rGj9C!BNX)+o@Y5}~1)6H|AU5=m2?o04KxqqEQI9KQvJ2H(3eauQj`Hth5vr0lE z>AFqkpb|M>KLjQJCxYf zWT1mQ9sP!$W;N%BA6Ikq8Ic2tiOu?Zzs{{BcPP1MAAv}bz?3QU0(t#Cd{m|G3zd_& z!+C!(XUm}4+osUMLgoBQ9yDC4 z95ULjMCy5B(U_{o|F^r0!3^E*K$wA3+aiP0f}}Z;GB&KylUNR)IWIE?tsri-)LACvqJWQ|kylYCjoo}J zQV3WlUO$-K&OFB9OEDTQrmYj1ATQQL(~$#4XxP`;glm~M@!DYIXpZglS$_GKw9A2@ z_*7cnYWdrbSYPwsPpb+h?`j#Wh~j%8lYDzbwA8JRKhc-GBc0b42V*HfcTyvhd)IHS zln$sn@6B1C2%1{5-Du;u&wld_9~0f@F3=C$${S9=AB_A}SNQD1v%#b!_oe9Xf=jAV z-DRmv>v^XOUt4)rR^X z5ZM2@z&~}}|7=zN=LrIAGv0voBj$Net(h8?5_v)A9FF3S$1c zp8u~-H+FSzWkPJL#~nECXJsr@SoCfK?lBhyHe>_W#0MI8=JzxJZLD^?eywTX>0V#g z?@JAX41jLB#X>-`YoOE8oeu20r!QT-$>N>y`z|3+39xtHR@KmePXTwN0l4@FthBXH z>F*!I!H@Oa8y}W~etY}%*1hq4(;y1No^#;$pIS;d1ybD<>Vd5hx962V7gLG@E=IKv z^Y~kVM)G3$pAVz1$OG4DaSg)(VBgfkZ`yFP5o;C$4g@8@UV@JByCtlDI7;RB4G~v` zfH!rGd;M|apyW!!_4`E}o|Jzbo(21!T1pC&!btzTICAUnJ<15VpIY zVTl1huoXMi)npj}%?r@v5{u8>SKeRVSCo3)3K&dabaZkP3mF2cpZlwIFu;-q6@C9a z(QsV|FyzJ!MS=oETQ;Wx7__%*hT9zMv2+*k%W&PhP@PaM)={N3Y?%$h#`mX6l!?73 zWg`Giv68(P`F)B?aC?eZAKU-_ofWo`3AS`++xM%{1z_vbhs+=TGbuI|1GPUeUiiDv z^5bei;9dZjE!d&2i9>q&jQG!iYo5-f%SuKnIA2RSA-MZ{LOG1wyGnX`>-2V>5_r(R zD{!Pait7JMA`JE#|6i6CvGs|VeecJ1Qh5r=TKs@*ibE5k8|Oh&MsgVcn{4+x?guwUY9HPA1ZIichL|P5bN0lFM_ZZs zu*PM+3vpse&H6E*$K+QTWTpscM|u47jmyX9tox1Ttv>5O7!bFSn+*8mX(h>rzzU{h zkyU>lsD#}t0&@oC{x8hz=TL`BSva%_XP|Dt9JCjXDMnVZ$Q8cW~ z%Mi|_`ZMd&*%5Y_jddJbN%tYt~but`Fg#c$MHBG$NlkEY&4md zbR}NH!Wvh$fEci3 z0#AH1GqtFB6TXDszN_Ks(d1b*Hjkli4$91~-w*KR;lG2qG&3G_pv%=Fw#qp2!rB9AD4LJA&(Hp~P zNOB;5=pX}$P@W!(0|;|5%hs26{`CPTnm<_uArX+H!m1-~M28-H_75IZI2#W``lq^H zBdkx@%`}VpY}*Z&+G-yyw-~|F^zsNP(~YDkHUZ=60gqMm?`~L_?F@OZ;Ogeo*&xfx zDFaqL?F?s&S?m%3Hos;3y+Vj1!%jZ{&ZP=>fw$ZG~AQZl2m=^x9H>Y0SeTFI5wij`n~&P5Hk6T=0D3cba%RqdfGnU#} zz5;}}5`PE*y|V{tsclBbu9KnIY*Fyo1~|iA^Ax)&LHt!R;v?AU`>?6CtAJ#C0v6xb zk$h8EfHV=k>kkfpjtZ4#^pK&8lVaEsL`I}@3z9#HxUd?zq?4W%bK^hOHBh3xV#6)q zgYI*xUikd_E*cV5v`EAr5487q?@x!PrgGrg0tU?!n~zE?(|JGH&i=Y7#5ELmSjiRomqXOEmw@Z+sYYnb+rs~eLJ+g z73g$an9<6`Gi)!WU=5RG0F3Ke!T)n6Nts1zM@s%U4=xO`l+Cn}fuHWip~dO|?mem98HW7GNo* zbZZ#@f4%(Ie_K%w19kG~C96`Ba8YY#Y3mh-q~|CkJp3sUc&E&;-Z7_~Hjhn-g*(A- z`vf=!uJXt0A^ruLC`4u3;(3Egav4)t`{BgYM6qQezm^S&+@`)uqihHV(DHX$B)Mm) zazpcTdUiZEJqqx;>n}h^>dU&lwaLlO>u{cx_OAd!9f2|Rh` z_2XWf2YE~7Zy$2x^7qlldHNkEWj8+d^(fQ-ON(dx&4Tnn{l|42<@1UJUF1`B`vC1p zz0HJYkI%T3OfF|&2Rc-XVG=oV!b6zF;G?T38nRWjM%ZX@z*5>CGAJmBiR)v=VqYma zVLL%jHloTazB4yM>gG>YKI|e{sf{tb&il%ZI9t$g0i0%tg1WrPJxowI>?9Z26{(7! zz=B8WCsIVX_&1F=+}wZTaNBvO8Um(qM5Ybx$= z%>_SS6+ODonGd?xd}!CzA&q8EBqcHHYzw2=rs?NXjlpM+>&UY4~DF76NLdzWDrupMMryTLyypomQhRyR8tSLFWRGzx zUEH0`OlTE!WGY?YM#S?Y3-QK0IJn6O7I{~vZR`2bfKwV)0gC(7;DJW}0G=$ZzgpVe z>-p|RTTrb=mm_*#IaSuR&Z7|Fml|j1dAVWX4vFdy^AI52Lb-1W}3 zdb19MsV|RoHm8y02cLhn#rE@KA0s@I`#0^(Ta@YU#i9_(Mdq)SQD(${4kx-_RavO1+z-*l3BjrfGoQcyo3sVic{U@?H!L2$F0A6orRA3DkeM7y^F2R zK@n9fG@NHzUpGj$Mr^$s96cp&u$n{|>B`|nLZQIM+#Oec{C`d^n-crhJ8qP_$BGS!8j&SOdB2j?$}6L;_@u5)pQhb_yhHe`Qe5Ul>-zvDQc? z5+wsQx8Big%@}5F?=Far&NH>16 zKGE6)Vp@6m;ibLFzzV6yCSt74RXnTFKCy;8NChfXWdh|z#>^y>+f->6aj<JD?Mu>wuQxy1m=-hTuOGA|foMU8Ul%qh7jHj{)E=^DrHJw*sHnLe9d5L29 z^xdCYR;I9UPdk-2AAS2BZP{!7qpg31Tmgh-IVYN*vS0kwSw7z@+@S3X>##riTlQn)NU`NObVDv(JZj_l za2Bq<;4g@9Z;RagAAk9I62*w-F<@4DDut00hEK%TIJ#03)ctV`->kP>RiS zv`eVoF{2|~t*0U-OvVk~Rke{)m!p)RHWQ$b_C8T|{6K;rP?q@+VKKoGQ8911`tEL5(S8?!ekrHMFpg6jv&fEM*fb zu!vkY&NdS`wVj{{O-)#dyDeD!XBzZxcc;t9tu!f?Nm*F94B}Gbp^)C&fcijnEDjAZ zIlz*+{8SqdQCwDVZ=Kq7<=V7lAccbdzMCE!`8V!7u0Ot8Vi#= z1f#>d+lXX)*yuzKKi|`0%_Q`gD79}xt4qb&D2hztXV9(F}vo#z- zdZV2Q3JhmhS}XU*X6X?!d%Xwz`4$>B*KD2NMEo>zt?!lD(sVD&#{VC?*Uvh5FhHSm z!fw5e&BHreysOL=sIgCth6{|xp_6fB?=WnDb@NiK~^vNQrwz@G)O4yBii zerP^n!}P#b>fbaCLScP#d)KRGWHnMUxjX` zqPJ3dlj&{qet)g6=a?KoT`A@8Fa8EVYIg#Kf+rjds`sloBdTB*Q}i&M3Q1HhiOqGa zQdNW!CgGB2kEFpI)B#mK=|DmgFHDk#+j|^-bDWXW{Z=>|1gbq>NB_re%l~=AjT-)3 zM&dI+gwuZ7kB82k@miU-EGd4vZSl~-;Ajct*jF!?9pPKCv*ZpdMZg)Th-Hpwx{0i&pGy?eM z;pd&;ge~Vy1O%$E!Zy&aA9dmhSeeM^b7O`KEH5Eb9f5lO9d=X4fzEaLyvTq>$o>ieAW&TV+j zmXr@uiQ1qdGkM z?+=KL{`eR4cV>e(c1YaRcSSsvrLJUQvc5hK64l&2Opd=_w`eBveQK{DX3MU&L(h`CD|odIix$K*Kzn}BcWnq=Zxx~9CYK9-q~I&4gR9qp=g`|E6>#(RNacPt&D!&vvZ_jt{u zevnMQ$^Hoh-6pbJzeMhWZA*;TB6-qXvBiKuQ)z6#wb1q=zQZMItU&yaPyGr6;Z=BV zVYnWs34knFs2|f_EaO5DYcFEmNp(>@zWHMJi%mH}gQ5l?F@k~;e4Jz-Sp~15j!eAp zcF+e`u`k9yiwUGUp|e+=6W_wpMPXrxbiwMUU~3MTSfS<xf7Fls zK(qR886(vyS6JF}gJzmWT_djM`fc=;pcdA;Yf|TS^nem*w^lhzdRxD#4ts`UBP26d zlxIJs4?l9ac6+SF0>|I=6_<;Lya>3nm~kY zdGt0vbyfFk_qq2Wq$MTT?bXB!1nq;7;=~unpx<}K3vf~4;u9|TtSoH9dgldwx>RPe zgPT^T>TeAt$_muRs#g^EeSQ{WN!ke!HBL)8T^B5`aBvU~?s*I<`Hc)`)W@XRaKd|2 zuG&T{U0*yiI6sl-ysQ{~%>UhV!u||BYY|iZMR4=s0W873XL{$2N$&GR3whJ>wgKZa zMO^lodYepOIa9#?^ut8+iCC!Z2N$Pcz4zN5VK&*RCl&=UbbThV3Md-}zEiRv`~XRr z`V}wVx`tEmL`-}rAJf+RqN)joSV-CSVJC7(+pr9%X>*IDDFov7tGJsPOrA? zfj}mCg9XpHGq%z^1DtRlh1qz2f&9KK9ZWJTLQoh%L9l`<1ts}4K-MQwm!fez`bE?_ zsWM2PSIYs6W7&lKHp!nVmYZqo$0h)*l<-_N!scsGK6fi#X>6hDYeB2tBy!h+o!ItC zsNa`=>)!9LaRfBSeVhDbqmX!hnb^s|v+OA8Z*pu8pz-}^^{ZVJYK-O?6kQM?Ey~ZDc?p|#xYH($15)U>`Q`b%mTSmLWnCK9 zLGqnn5M_MSBPG@Ig>}aNy_}a?wyxa#WyglIm)u$@oDbfH_%w+>_+P%&rm*>SP?bg+ zE=?woD_|@_qYJCAE1EBw>yG9)^cfPYc_Yr zX5rcs=n7p$cN8zUJwJz`6VNA#q2O|(i$H41A=+43+*H#wV@=zp7!hw}coIvzobQlH zNxxYQF%3K^8$_`GGIV)1AJYzG9J2hL%5bk|H2Lo*GUK#SY}`d&Em9!g<_TbG_HpuK z4P>xay6DPAz`4x$quH7?7K+fH&7057l#P4=HPJ|}`PRfICoSADDbb<3K6{77~y2pkYKR?(PNU#XtJhgmEk~AqBz%6nI#Lcuq={9}8Z9}7reANR; zE+UAxBxXSl>|=53Bwnf-MRo3%)|%!&Fco9a**l!sp5dOju{K>`i6Q;4B+6_Ue%VXMJr9@(tKQpX?Y9yF)b*L#`KVB)6>)TQz`Fst=v0iHm}u>Ja@KluC` z+s>LiNs@Lq3L_JQ+ClMDOQZD@sMgTj-Vctwi>%yDAe*_nSGsu-^}V-7tTPrCD%mAn znd+cp%0hC3fz^(ua(O2ALO7$lx|B|sIL$?d)ovnxIuWagDz+_4;;|h5I^QDly3@lY z49#ud^({rVtC*xont3QbUo6VP9kd$f;RmNs3N}92U|kk4T>*@@g3b?7x&|^nwaJxJm*g^`k|IS(RlY?EB{mKViE+(wRSI z=SR&EW>c`O__6FNivhxQ?D0VM>q|Cnv9m^l6iAeW1=FgHk-YPuSr6%)^*NLr{^67~ zo>PN<+!~6)LVD<8o#?uD6DzYrSU8Ss+ub|(^nxA})s62NAE;ug*pkR8PgB4?YT!_m zczDQeMxYqg=*f%)CF|7#y^32AMRY`L5cPN;5(N{Oc0)Ld+y~NDaBOQMeeMJhg{5|c%B+YzmKmI9LNc)SeqS~1;&g) zNqvn(E(30|N}9}eQx=_B!sHIS#DI;EzgGRO^_=6EKS1qu{mU!MY<`S4f^`=+#x95? z{pv+Lr1BL!LxR5~iBdu#$I$ja>-DF+8-gR<)L{Dkh6O44lF_i~WE9gPp@d;)`DDOR z6?U+kA68TY|BfC_+h)09!I~i?!r3<8%WRR< zj#-L`h1}|+WsiS?mj3m&qzu&T`>@RV|ltg>Jbw6-l|3Sz)QRQ-0 z<8@u`uO=ilUhkCMn#EPno1x&KaF0)TN=1uwg_t9Q=6e%3i($TdVBE&pQi!zbJR@cK z`i4b!pW?@l@2FTFDEbB$3NPaP*Jh{qxYSe%CPX8jC=Kr-!Rosy!qpBgdb9J>EpGfb zh6!-mz3G&{oDU{&pxsNnnD0W=z5kvjn{q8Z`C_x1ibikV1&@v$WCEE(|1%uC5?nU{ zp#hKnIhtX$VE=r9qHh}lHLlvhWmMDp4@W~%8s2g-tG6oE>c&)xkA?iic-bb6yq&qe z;hgqSvB86kpY{ILs=-fDv_L@=Ci+yr`(IBdmI4>3nMBrZbW3rL((hB|Ik8Ne2I_vb z0xCr+xqk+P|F?3BSRMD^@&44)#sxw)6)_~i`8aI?QioWA%tX4p~<+jTx{|0 zx-QG=r@6g(qCE<9x&h2 zDk!+_hVUFV_N+QPsz1B^zy9pJ;3Oq=amSIL1(Q(hOZe_C+f71%LnRi8Hy?H=^)wM5a5`5#pOktwX%eDQ7`s=SJo^eW`M>dqw0=PSS{ zVQ0wLqjtbc<{WK;Iyl1e+E$F17h`T%8A4rvh9o@;+pe(9b-$6fM}SFM4Dqq{g#ebU zop^hgPs1|%VfGQ!*N#kU%@>7g%#P}?*=0bqDNnaWot`E)!3Qv3yWoY8Fl#vHIcoo< z3R88!gAQC;b|$P@D3=d8#?t?pyrzQgYpXGN#5?UZO@Y?w0Ww|)c5uzq>s@1@vdsuR z(9<5c2U|O-X?>ZM8LiC&@mtpF&sMQw@*X5_4HrZ*OvANEmqAS#EOv@wF+RfpaYV;o z)y2+=SDfn(Z1{g*Qw<6#XD*D9eJF+R|2sCqVKM1YezkJe{Q?%CH`=3Ne9tr<*>$Z# zj6(SUo*5x&vh`!^GzF&AN58$Rn0MavKHtVdjoh(1@G7<;JKVBZ1yMn4iJ_P7b*uFH zh-K{Wa`+$6FgAUJwN!|khZRBY8jQZNJ|E8p9KwI*A-kXMTn#*)xFa=3<-67Zn=NeC zQw9M>*;o4?+p;VD`%t}z&btpMf?WAWjrSHRw-h@{_07P_X0Bv%`|tf#QEV~pLG3dJ z%1p;AE`i9vlO(br2f}z`MKr_@pI{CTzyERGSIptw zn#=uqtl?^Rk5&0}r!Ww5H^(5C(2jwo)u5&d( zEg(?aTl5$%7=$OC&wm-gBtJ~D@g3$a)rr>(Rp&SVxR)wN99e#c9EP1|28YL6y;>2i zU)^YppS&g>=VYvy4r8cZ`1NIM526!O%-}+TPTf<|e~D4@CqCm2&Oiq!>{b~|!-XzG zlG+fI@D(-S1XXZ*w}{NY7xVPnVO*$nJ}x zFTKHfk==-H2}Bu4xP96VruI~XOxO|*J7i>m5ezxKTx+eQGfBGWEp7yu2oww`Tn@D^ zaW1Sod`#&Y;U3D+D-$4S#9zzcWQ4-OjX_R;iDC7X5^1rB4tVGSv8zT{Ulkr9zfgosz}=Pk=jOi~WwD%0#ITCM4U}&+bf;+06@X7Y(*-yB<2Kj}yLZqa65-1+ zB#EX>UMmOF&7-21U_Kk#)le-}zFP)ZW`O{ZJEO;-i$>jx=Rfy?mcn3vMB-r&=;$g( zB0?9VI4nra+iJ?NWBRFOFe44g#Rp0GYrsUgg(8Us)57SQG0=8)6nNGfdTmGop9PnI zw$18yAb2qT8l}TEU_RFZK6f{)x#HnU-25jJ4RYOq+l=gbFnFZeB*pqB=6Y24a3i9m z7U?Kn-oCnZj>69bW!^U{+WSk%{}$>5LG*vvtxK6SNK_lU)iH!`#+Rjg8yYx~yH#El z;X(Dv&I%0`!zCJ1?!P0w5^t?xKDF}I4dm!xx2d}D?;OD~NEawmx&PF#zKE&XIdLtx81-K@nk4>>9Go`k9=sQj7b8$;^GB z&bbyw92IC(PVE>J$rL)!!kEPA9(uwkUgtOsa%FvLB>r24DfYXv`0C~wn}8=B@o&MK zG}GBCNT_UY{rcMAZjP?}ny?@SN=08vH|G2w@sYl&#~Z(Ut2l)(9nD`x4&e0WaBJkf zizNBiY5#x)sVmZ|$RE-OM-J#&&la=;MT!Y3kEVy(rqb+Uh*$-XBsITP&s_?3XB{o- zaV%;iz>E^XC6I&xS9eLs&u4Iq{9N?_yyvd0AVjU|3_)VZNN4a=(|L-eyTCLStenCv zopCcIQdw;@#3b>DNlr_9{~^cnLKTknD9|hg?Q znlLP~g(q1~*WlYv*AdYKo2lBFGkuaVdQ)vR25ul*$`XxA7`zlX(B#SaAL{X9iUM>9 z&^%Qx%2)S-%dQh=GJ9$_^9sI?x6X>b{-T*tp5ShPk)9Oo(KPcyq$^!>VCxg(U( zQ|~~pQ?T6#Z?wkZVHv4|JkB}5Q4Dey)2fWp&Gu;qKCine2i~i!R)AclDsfbz>6ruZ))b&0r^0@ zICC{i7n{ezSGP*Hd&6n86>36F$VNnfDL(c6{(V0M_DAld<)x-F=M|5ogeNc4YVRr? zZ@fG4Kg0>(Y`D_lcdJ0b=c4JbflDp##|cR?#p=)5x1_gl3$$l#msyO}&z6DL^M9BW zV0aD{-YhFM!WFCw-RyM+B=o=f8C#W|F}%;OdY-! zhdFGal|G#{cScQ|lqof<`sbT)_dCg<{9LZvG`3$&#eBn30ia+gQ|~CqBaklr z{mCSk^JzS>Gk`-r1q)Et*iGjzI8USOpBkm9AZ>r|6jQYp)>}2oNCYk_4{vq1tw_=c z_&!CYCC?3cFB^TDdtrF)YVVA9=}Ovtj5pFk%_<3~7OA3gZ*F|fC2`!T#zIKk%b;O+ zeg5Q$$KjHGG}gGytSTAztc`Ha6KU?iTr|NeQ@yQ&^?NiN&io(vB*sN zaP{Z|*5`_do1Hirc-ndyFGlHyE)%St7}h-M5uxpr|E{m4FHMMMI1(#xa*ldtw*l&b zxTS&o(My9Z3x|anm4XK$JRB0OK%-Di6zwT42Zg$%lS5hXXDpmysaw+yH&MCZ`5YO7R$gfJ^&4Ls_G&@0G={xSEVd>t zZqr^Dd;Uu5uM}QJ5AZDUjMFM{175ALEXe*)i*NSL}N_*powhW2&UB~&sO%3pEHD@a%O@tmBP;$N|T{) zNq7S8@#4eB(pVS#9sQ#v#c48rOlu621D;ik(oa8_Hze*SH;-}>hl5%@SjX|A$W9j0 zak(SZ2eg81>U{Ik32ECNl|6oV*&)u1r}3U@ze6IRLY0@Kc!pnO#9IB#|6$SY;W_3c z!7tR&sus;BUllk~WWL%Pc#5=2zy|D&+kbhNSk?>Ys@;%u=n@Q?RtdJsZm7~dT5 zR!OYWPir4|-ML7c7~4DyQ|H@ys~_rWD+wmPf<7#Nc;_;*M=jI4UsacIx%)FWoF#7BOom-ycq{wHGT=aZSjMU+))kLz@lf|e(BW)0H%I;*ZHVdRrm+j3O-y02I}LaZF4sR3|u z0nPi9A=nw5e8HvTbQZ%TT@A+4HYcc(oUzn%r+{;$&?BUNHH7J*)3oT)Iog|bvjl&u zpzC&G!XsSR2yeC$h0VhV;7~CrC#RDJ%v_F4S;s{370+@L}W!&+D z{xQiQ({JFa1s%3`AG;FGcToX)fVWPRTDsY7nH#BsL#*7W0=kJl5?C%QQU&$IaVOP1uktaP1Z&nLd z7jqYLbp7YOt)Xj-eI`C^g!}}TjK7J|+y+cCcd+*5YOrGT-{Suo4<6R4(K<5_k+h&? zcp5T)<=1!5HL>YX%FpmA<#(fnHO|Q&goay0Z`X-?VHId}HwTpfvxO zT|9r2E4H^gfic$*U-*=Zm)t1oWS@wKQM!ql?d7W^ooQ^e-0a9;eJpnY%owAN@V{6H zTOT2Ra#CGpEj>Ls`l6#s&lSU=r7nfhGij{b^w#@S0z>@VzA63KSErENkhPoin7b{g zK||jI5(~fX)Mwqh)l$OT_Uy6!DJgNw7D`mR`cK^L8N_5CEGeXbb&GP$IKP!*V!!8S zns8g)X0^p&d>g*{dX=otcJ{T|wbQQ^Vb?7gUJs?)K2FayX1wyNsMn~>Z^yZQd&udn zxZUDajeE7Z#)X%V_40MlBg`PWXT3B<#eb5#X#+EwaVP@!{2*0%2t!cF9Jp#;+9aUA zlqBd#%}51&l%T=<9UF`jR=fNDw}t9m1FP36j|U}ixkEmX->?f%qq~|J$zxuK0BU~# zzW#2ct8&8+NEe_Aie^o8(HoNt6H~JC&G|TJ$x3^;Ox=fmm3xH<*<$7c(wCY(2|gpP zF~x@j_)K87>(qJ8uK7#s+v(Qtz}&oUh4#z^Uj0(PW4KQT_v=QqbBjVBoQAz%%Z)fA zd0*YWVa7rfp~q-{Dh1k;YU$l3ri6(Zw~x8%^KeWP2N-MVE_N|tiotMW>is65`oKh$~2ah!vBqdTL*dq=bIByurR zE_(Sj5%V<9g8AVC4QAiG$3KONCh!%~ce8^hE19h;N7!1=$_xA2DSR#!U}p<)lDbh% zXjrYG^+$=6NA(J2-cqCcBt+|vd2v!h^tMI#A=aW2u_sv6fZL}W%SYF(Y;VyXK<%xdY1WIph)5~a^$;^BOxT3z_8^m-dPelY(bO_1=9MOO;%t+rVnpU|!N3RL zGO?%$`y4CtAdnGxR*eajI-D%N6nYbP7G5zK;6@pHl!TWcnVZXK$`{nKF3Rs?Aq^Bl z@*;cFc#}LQti&}tbOzydo_ZG+l-kSt(h}B0*Ji;a#^5iqHA(8_RB-b;4{GD^(57VD z`eT(~ThKbX!ew$){5-W0K_(a+@V< zw8btG_H?YAjE}wM%Ufs+n~}#w^R525F7(vY>8Z#bsjT0ujd^sKeMFCCiu?8ZIv*aj z*jnLp9d2yQX8dfa7rTVQd4UPT=Ob8WZKm*fVb0F+l6+#{Z%8RS$tq5xALeefU3Q%s z>Yw6T5Lu7giW{-P9ZR3=xd++#-jYl-UBCO4{paNyIm~^W!esl18ez30>+klt>MBv4 ztldn+$ZdzLrWVhp@_v%|ApPt|)|ag;ct^1)huP&iFmN8zImOK;DcQku$oA%D`%Ou`ll?kL zn**2N*_OTDjn50bZO@VKs~-8L=XiJ4NgnSm6(ZhV(IT$*%hNuY;YR3qCM)fd{q+d+ z*{friY27~0K}qmvy4CK3x5ds-<^g8DP=+!DrT58{Eh{5HdTN|5VSD(j`vI@UJLBKO zOXWjwe-2&<80e>Zed}_FTM?;hApS|GS6UvuSm`X{7u~Y}OPQW-;SE@;X(q$!@mvI{ ztjkmzv&p9qNK)?kv1Cv6y^S=xDKAZ+Wq#t_tk6W6Aa`gsSEQ$WKDtx0c!9H9J}0a= zc3XjCnX34bBfpkxREWy}$KT5|56KFzk)}1eWp(g%5ot4iVGpL$m)QMoP?f2eJgIg* zfB!%)na)kra-AC2ymfay9V|)Wii}!3TSvr?1T1UyreA0YNHOF0$>j2II9$$TP!hIW z#2Hc&f5qB5sWCyAl6=|Z;hkrXb1g2UjMC(N&d-vpys+v)L;bXo#bWCxu$UU`vx%iM>fLF&%tUpRp$NDzR6=>B0J#i%v0H#L0H|TQ@vp!^vS+Z@rMOOVT2x z?nS??>9OLM3*?J~+E*sxGwNANj0=st6t8S!^4v1+w$*rC`eHMG zDQ4{Mr2l3BV=rTgmsUFeEANBFdI|2Z`6?N2nSJRg@q^NblRt6H0&csY-Q5^}?J-y8 z>@sUCE_c?MREYmDYPs8(nW48j`T0Y(CZa*J`07>t-owS5EA!s>3wEm|f5yjXR2~>{ zGurk@k^9&kj;xI$`=5PTby;WTp0hD2Cu6RXt@T;x(5c1Kr4+7_r~W#8<{zN>_mbje z%4ec|QiJId&K5s&!h#B_%wwc>M(!(83`(t1wh}oBoh?;9qGKa!nPnkVvwpo|<(up$ zqkS{xtZv)Nk^jvX(HyCuZ&F_4d2iFU!}A;&$4(`VMg6z`)Gn0qpX#KFuD$auh$_0U zyOI!fC%-m)C2%c>;a7P5ns&zI)WYrb`lUwoH{SQ$%hKSxA6=TcX=hgA zOv1eFeGO%;DP}@~)XUwU*7hJ}k@Hat5#HPJJ(-nTT0|baT2RSG>zs5DvF@;CSD6cP zr1fPK{tY=p(@@5R@Nte2G%yPL1LziK_NnuNVng*O8VE;VrkfruxE)G7TU=DrluE2VGGh8<7#)}m*%=VFE1 z92RKR+ik`f$u#c$8eQ@ke-tLA(YTdwwBq6R{;?8Lkn%Q!wuXB+h- z%Sn;)=`M*QWl_`w?Xjt&gaqFcfuqu&%WraxEK@EZSsQe;J~cgLL0`FuJaJj>d;i

VH?I|of@!xc_UV*(!F7ieb$a;Ds+84Q==dxRgE zFJ&Inus#u@bY#3!yNHr!#2gwuy>+;d8iscx2*>2F=ol>{^O!m;i?u|i7AWsf-Vsz-DGJvbwnrp-rL_u^*-a5vr|ty(H!&)>fhO}5DQ*ddN+SbW$Oa|@`(bc~GoI!8? z_jxI)i*Tmps%Tq8I-bust^Rk$DI&xg+Fwg^_+}}p*N2Qr#nbDrsM@)&E`p=?^rRM! zRCU{i3+31L*38xAC4w0hR-%UO550A-S-BY<89jZ>cstht-;&Rde){E}o6%-9QGr;r zHB0gZ3w7~zi63d4Ws1JWg@$>$;Zk86^012Q5Sy%=;@z$KR5NY7_UILh&Pt?rAAlC} z4!?|1A!`t(#+Gy>pCy?Z+F#gHB~cb2@WoEc)u;xNJYx>#JN1UVKeLUl%)slB;{Co+ zlLGSsBD`wmTDVloNuNaYl+w@klVZEzhYUd*Z!;M1MOAP85v7X{>Ac6hC?8(s*R^Io z?tNP2#~-t+P8}QIrbqdE=%o`U6*UEh4jpo8S5v2;+dsLNQRnV`mdY=8w&x-4Db@uO zncps$68;!5;uPJ0W0aEp`upB1jJL}({B6a$5BHi+kD2j*v&49-df6B=M#;*3Y@d~~58Z*C!ZpHe ze^xaIg-aMrl8zu}XJ+kHV0fGG1AqN$$-5m{qpB+5FCHK?%MxUa0yk9W?7WEFx4ZJl ztarKvxHKMrBE$+cOXX~ z?6+WrljV(t#B=jaVs_05zjn6pkFeQNQ2w%`^#Fzb789A_eGCKWmf6M-!ZwHfG+2b^ zF$Tx=Ld99M0Cx1;T$}`>bm-mQ=^668@!RqOAJEIltf(yGk^<ZrfhgP>vFr*JSb$QD7Uv2sTu{z%Qq}Dk$mr9PueO!!{5R*`v!t-Kh>p< zKBHF-+hvyRO~a5lX0PM~e^CbEqiY^RAqykeIZ0AY%>Y=#_>9d;YjnU)eV)M2ZF5NG zP1mTFO4r25x|;p)u1wnZgY>#s;$Oad&J$-wq8ieaQMT9xNlp9=#DT<{$aIgxoL z{Xw*hxVBYBz0m2zh;5Acl5M8|@9`EA#6vd?CUNPTxT#?VzgEUIZhA8DNe#*xP-90#XgQk|OcPye3Pw z1GftW#-NQaFaPqA0c`I40#AkESYr9zR`1Ura-X`r;>;1v9o?z^6(%J%gmRCS-OZN$ z+*Aeu@vZ)HsdM!5HN=nbzx#v|mV1Jz5;d$-n+&RE)`hU?=TauxysS@jIx;V)8hmia zPoFKT>KGTQKaTqhs}N$a=rfob2r)m7H8x;1if#*)Vun5JuNz*2`VXSpYDo3iy!~K? z+C0lHm%68Gj+dd}s)#^cgYSPKUiVH;ZR`tU1j_BKg*N;pnxKh9|L)x#-`(FIl$>-a zxb{Ef2!~sU-o_Q1&av%H->3vKfc=ZBpCc?$dkQ}V?#~+VOur^?+2HxDV08~Mq>_{hH<3fa z3|66?7&bWP0+BhQmvqXaLO3jJp@F?!cJaDuaqf5CNBZWySE)@I1m3BvbP_N9Uw5nP?DeJ}CjT2Xy zzeocp!a|5gquEf{MX$0pM}{?rE{*=K8@*!6p#8m^Xt#@z51jv79mjc+{K&nQnVt?4 zCVK7y4oA3D6QTUJxAw-+NbCY5=I>G>H9xNuYK}Vv%u{YMJ?1f=gR8FEI$!U28UPR1 zkI*V`d0m%A&B+CbA^*4)sA3T(T47S;6WOggjai3fpnSD%NuhKU*axVNqI5iR$&f0J zE~H4v=+goL)l|&w4>J2@88^yJz|Q$rpctRg_B5Wka|`u@{94j&=`42*Q|XjvLxF|p z7t^Iz^WO%9iY@$cF$c@d9hhd@h%KPHA1@K!wC6(=pY50nx+tBT;|;4?v|nfmqPWO3 zpcMB}{=x0S;gzp&auYPaziM(F&Zh>tZC$=hVn)1s1E4}Kn6|~bDH5FY+r1zf`mu?& zeVKcg6p2r9cnhIUM09KWouw3B68SlIFH3s)#T@DLtOeyu+}yp%pmw^q_6ScWN{ zI%1`o$3*E}rZq4N8mR#P8gCuLEj zPH}vYDu&WGy)8sK8E_onGmE*nl#$4(!S#4yr@Gc-5yXH@DJJSGd>TJ4B40ALKVu6e zR6NHP))w7Orn;rUcimA`ei5GbWg-%g?+pcdkCb*IUXY&Tco|Ki;%+KZzvMG47!kH3 zY>b|x)DqJPRUtTN??wD1JS&-y(b-`kMrzA!D3ioA@y6?2%*mX?1i+pBD$TWtIO{66 z`3ua4{5L@gVW8S@F}7VRA7Kw33nFBu!|Nu$3qnQPUc)K#(-HHsdAg6!*Ww#BMVc5V zaXuv3d}A~{Y@WkpiuHb+Y5)6L%!Bi8pXuf8Ez6sUpScBl6Yk}fxBLI5v*L1aPU5f< zaU~t=nAe@ls_sPm=e0ly?H<;LUq6B?G3W4~SAvj$#k}^I2#kJi7jOc2MX429&s_<{ z52)Ol_3={rp_^dtuh*6>M$IpeFHCS?MxVeKFi?8Q`!Q}4tN*XRNR{Ui!!&C49}k%Q zcd!rKBi0YvObL9!R6(Bt9s~XR=r6@RZ%zFRVzGbRbd@$sSHzgCeTnaS8!mp~-UkWM z(r^K<-PgTdH2Btur<$wPNC0^Rk<~K)B%$ujb)Qo%O>yx(mZLjwRAZFVtAiG~PWE1~ zr3$MBs^w;rxWeH#KcHHI%5Lr3jx#JC?Ud`YD#;Nh#5F6fXT@uzBGmiPVN-m@IjJ;J zf0#ooS-vcEaHrq&y^}f$5x>{sZ=kQ z#=WXXKDEv+@8nQ9PQvTzi2ciUFSMA>1YZ8^VC7ShLX{B&Mcp!Cjx6EWlHq^gAV`Xr zUL#cNwxxo2Sk9@zXX;QeywV~3<$9wGQtaxd-Yebg^obc#L#G0I_wD&KbhR<>`42hF zV{SbxFnjtW-FEKrLd$epA>pUt0y+`(SDYG$$Zy*|;}ayv$D-RESsmQS);aEXfixiK zS4E5aeyvJ#J~I{XHC`syJ3pIzeB^z75e$)u*V%O({EV_ zrT@ZjTY3M_MB~dPB>45{+VvvEkXZ&PT-^N2CDO@?lwjj+cY;-RL=0kU$T*b zrvtrQ!$zSEGn3O7`18qiZ+{CHf%8iLU(c({^q5Dn9qq|mm-HmJ82wi4z06|{R+2*N zK4B3ENiuSxC=a855pZ*Upkc1gK>Z$jB4T)sz*FkbmHZ^7sy~S}?QUc2s(?0g&(R1s zccQZ5KPjAdL!)+NV(mm|Ttq7l=Ql@76ae??dmi$7=C-O(VRJby|A7@`)=m;Iv`!V7f(*?t>`v$W` zc2~TxYWv5T9m+IO^Xu@BhkNflCm#Bqf;Ba!mzxzKb%;aANIpgsL##{uWMx!*_l-Sa zwdb0NuMmf>JNke$`Q|&~c2n=U1cO}|wQz8=_3lp?uq1h52bM2}8Qt62`UVm$JB#P& zwwPQ|QC{+GEAZfH!#+3ijd_72Vjnh4nY#a<_TD_6>b7kcuc#==s>qZ%m8i8?nJOYf zGDXXf$~=!r%9spMEK3oY3YivBks&2QtgvLBl?tm&Av0m0m)`fe@ArA$-*3O4{l|Xy z{(ScRPj^}i>-)XF*Lj@Bc^t=eI&PQ$tZt#h82i=4MJ`UbALf1w&lub^f^LF}i8A%w zh3s)+v3J1m#Tew=geUjv*GV_x3GGLiBZb^m^xhcX7{N+a(C=2-OjeEHvHN;^uNJ~| zqJmd6VL&hyk4)hK%$loUkK0#|h7t@mq63r#kn}zTrEbW#5jy$z6fT$20vHOW19dC} z$7tKzrQBxAUXixhhbBZmtFX*?Svf0rF!0ca2u7R`2eD3Z-boJ#BeT#dR%W{(q_|hX zj*6pbz!{~_eXpxbTJ$b*7d^aEe=e@S6 z;VqU?nrvSOE4K1#sEg()^_T|k5IDtp*nCEPz!%(|?%Yyk+vNneN|qIa{`Kh3z+11u z7ew(@6sw0LW2<8g6Ax`i_6~f%&vf-`!;d%a1>(LE8~2~cBd$1#P+1c$?0PYcORuZB zLAlwn3?VPA{i}1u3tV3fr(>~{)fdd9dL{|#xu@rL$=SqN#k9d`sU9c&Ai-q0neAWi zkm}F@Z|EReKrqV_opp0%DIFvu1(PEW*r2>J9H!5M%!XqkN0alX;fUHZ2NOK7-JajHwukvcSDt}^_I z>=E8h9Q<}fT+JQRGqGHLzo#4&f;@-G=P>3Kb3+JohqP; z*SE#^e`&bU@t<9$>2jhe;dg~5FS%9gxY$iYIFSAuMiBuSLzQU_V|6QH-C5t(QX;k( z=510Qq|hetU}BQO1Cv5}1EKt?**>L)}c^_fxL~ z(Dgf7_#Iht865ejI;>Rk3mt!vn@2X@sq2O|h^1lqS9k`}8r$RNpHgsN*>#2w3wU5e z8QsQAn&BCI#N%Q5;chD-7FOA;eWMM1A}zQC`u)rz;zZPdVV^<#4Fr5K){NsNoZIJ$ zfj-T4s9}iZ4y%b*l4PUVn#VQcqw5ZK043j5{%uZo97P5=JYN(1*L7pSy&;_))&b$} zk9rk9(QI3K+4$pZCfemCaJsTgWeen*UAP#7p@r%lW%=2)Q{)I?m_f4o;?D%t56O&H zD_1jQ`KaN?f4H7?4_ zF8X`f2YNMGA7G22e`EXH4kH}ad#eu0cni_s67QcS@Hy@Eaa7D%i85`K`ka1)Ef@KJ z@1lW;zPe|0IJK(}`!M1ClXTePHk`##r{1Dewkk)LpAHME(XNl}$S^h*QX3&=UwwO2wx;nFFx0tq!CC3ec zmHe{z$p+~~$0kZPyU~xsDp!OO3-Q!Elaix6UGtY@0LIhb?Y2(Htw`o#(o)=?hXYWr z{=s*~He0q$$t7xj=@FqwoCx0 z0!)tkb5E)k9+Ar1|88%@js}iiSt^jxnT}BO%KcV57^*pZCBf8k!TY!Bga7QKA?F0{ z;O33typuD20uONJg7Rq`gMqxCf(`^QD?IP=6BDF1Ti&0fn6j0+K;&GGUTxQw4s}!0 zPIfp_WH`O2EMZl@q%GR=#9E@R+Sda* z5Bukb%vXY5fVf0Ferx_C!uY#93*H~glst=DQLtEKVhSaxQ!6a_T`KYK@=bzLxM}Ph zQIl2u+vtL*pjt!iQ84+VtK%>DSw<;+Vd~Za}QSayu6}L&5KDw($#+PjNM(3*>Fi(+8zYW-VcxR8_F0kP&IYVRj?}8#i@2=|0~gclPzgw@iGB z(~SbbeVLs4M?+-hqF+=lG3@9@!W`4=O-&k+3YQly8JlpYrQ--Y7|Xz1YZ_Ew9;KCW z(zKr}&h|7gsA?&6*XhNbkXHLs;+=-`w=;%jZ#nc%mnFdj`NW({#|4|*9R-y*b3S&` zp^XuZX4f>D2zb8`j{c3K=6rjLqB7Eyxw)34Tjog}39)GCH&9`HSf2as zhRJ(Bp2^~ddBygkg_BpurXOtOWBFA~=@;Hukfoz?F_k#2aawQu8=so44WV$<9q`#B zWoEbV@S+RKgyUHSLm9#Jrtud@2d~(_2fF<~fG_4}skdclMiyG9;`btot9dLhH<> z_Ajp^S*L2eJm+u-SdeO8noFu;XWI#9d!B#( z33R3cj=~AnPbT(V@8W-SweC=%4o{dFsrKz?1b@_py{9>M6F|uIaTxq?nn&Nx=*l7q zji>M_c?fs=Cb!$t1YC2&fJoIrd!*h2SWp+@PV7g?lmZ5gvX4bmF0S$P!WQ3GMBe~A zV6VAfe(6W*H3Y;Y$3PWn2U|kKyDf4zZnNs2nQoN#8{4UQYEf!y2PBJRfK*hnqt{1y4B_bz9qkI>hB#{D#K~Kpqbq z12LLA3V~=<+%C2!B^PKdJBW6Um?%WxuxybQHe}kfk#_GQY}Tn9LjY@d8$=kR>EFSl zc2umeO&6oWm{k%t1g<>x(F<^`EI8J*uod*fkc5-fE8dRUt^aWIHdOX)+Aex-yB#D_ zo(_5niEJ;r%}6Xt96~hvy4|wq!*w`s68I^rN7#MoXrIw_d zIsfbPnVg4Jl~7kSf}-|3e3|exe<5FUno{;gq)fI_QkRaaS%y|1VYZ_eUwZO(vU2;5N^VUyw;vnnLNvg1hoO->8l(q^h1NtqzSU;z4ajh;UcUO0 z0;W7UxhMqf2?(4 z>irMFB7khw`R1{LFB(ALW(T17u7w((pzYAcbL<#5fLrPbj`?c%)`@Kr)>4cICs+|~W?x_8r#QVoYWd~TnLui_4T zac-sc#Xs$5CCq$Vxm5B8*-_Cgyy;35R(q)&e=Hz-pYJe(lm-qt{gnMm#-LJYLkFNt zc(o1z{X9UkDA43D9ESk#_{mqac!&7Jf`n75)e%k>Oa9+{uH=lu){k%7y&C#~?! zue!qy5ei*nAj9p;9Eq(G9JS$HluEsOu<@7wV=Yhj5#%Z>InXm(~yT$dq@ zXw*bfH+54LLj)XhrDHB+fT2oZSb1@^KO-AT%8Wjdi6}#iytsB z+12YWRf`nT3p3NwojegGq?XNAm6-O$Q&=sMAQrt1(Zk`(pG!R*mbtz^G}DR{%90hq z(101>kr#jKIjz4MKCKxkq$XH?HmC&E1xPk_jXfJse1AUX=?VSwPu&Mj4EVseZTawg zmzh@kX)GUg>N))Av?80>^M{z+;Jv!Ar-|G~-&;)tendK!3crxrkT^AK4=4oSCteDc ziLS&Rfd7rI$7brX)6n~`a?l9dU>*#==aH(!vu3gILn7;}{@*wKzwnycOMv3`&SXul zL+3LLZ9xjiBiMwV`6Zwmt&gQ|!TM4LnxcqQkeo&eQ- z;jI;V3qm9yW}^hVbdIY2xyqH;GUe1<#8_e2;^tt`MH1 z&5aUph3#?c6fV4^-Tc40HLPoQ;PYo0!Fmh$Z~2Dl=R?rR0O@ho@mbBi4$t4lphV2J zLWjGawuP!=wyltw^@%y(7PLX z`@j&t<0r3sn~vT3RQIFv+u4o+An1TjCPNGZ|H;XBbgpY)EWbOBqIFsTQnSr(W#%@V zCykhy=o^~d#;-06WWo_5M^S7Vf~(pvKd@O*PiRAa1MnyyW*VSrf;0`H9?2$c_EwK< z;L3}rW-`0&l>dDtXC6pC;&OE_EZ+nGaS0#6l7T)D{1F8?s`E>ktw>K?1LQB@3i2iRE!SIh7A26|frwZQxOXr545R^2`~)^3!?hM+ zV8K-dnLhiq0TO4W{D$A_`Cp$X#O&w%>?-)`XTvH%^kA@zY23LCrg^*~Ps#}3UM`w% zX^a)2)5EEQ5W7w~0%&=JoMb(2(8jsZ=ie2MCl{@Pt@#jeCWcep$(zsxNQZ&27&=;@ za2_R748uJnWp|gatxVwIgJ$0N?0JAk3UtMuL3GAzfEy@fFZ#dqm;W9*Y6rJ7?8T-I zO_qJeu@(vB>pM8{2S34?EqO;x`!B2^ercZc0F)rnWcE4m{?BnQUn*aPhwn*+8?e3F zNW@>)b*B_o&M@ex)xg;6I9>wtdvO$orxR|~|0>UfVB5V~QwqRk>g0=tZj|`(#k&I9 zC*I{o$?4+z5r_RGN+0`LodhIi95_Gq2q{vA;ht!q$gx#A1$I$!yj7o09PWjcT zh*xk!%57UzW8B5lomyvWnT>?hoE zZCH37NS$GBlBL80(*e7R&3lOypU<$kxu5T6*S((zBllL2uk4|CfQjj@g%4;P($|Ts z*D}Hf9$nMzlmBvyu4T`8jr&E=3oVF}c2e?ic+d2fTALSIWk)M96jx}YG?Cnd8;&5^ z+naRwu`;*zoCSyq&OmON zZ=a7%kn9y0aKspU4KKX;=56Fu*lr%Tjz)q@`a9J*IvbJvZ4GCWFPlhU)t z{=D7vVIbo<+yHuY%m*Yw+quS_K`yxLHJt9c7Vq#ZYllYV)%a;ELeCEu)dl`LyMX(` zs-8*Sr5Ewyeieavd$sUw{L{3NI~~C#%6l&t%*E282n*ts9ACEur7ZcIGoP4zM?ULs zapt@>i*uH(8SLZg+rE=XZP!!7ayi;zsTMhizrOv|yR+J2SbU|5|K; zU8gs>#2QC+0uHe-IaaJ>FcSL5e)pQGC*Kkf#9?|JxE+>-=pUGn?Ai zq0+fw!vS?QB?W?9i_kCmwMFgHq%WsD1P%_q1N+d!tx^ao2yPf0*`;?##DC_Y0ClKL zH;7Aw08P8K?2qKY7D(=G$-&;}G7C{Q%$W!4<;$W7P-Jx1*>WzZR&i@eN-P!VR8vFE zNY)P_b@8eb$HK?%EltJuG9LIyejP=YtnV@(2`r1n9u@^nUi9*t^f4>Vza)=IQT-># z-t#~6{Co_8^aHNosCnZhmGR9d3fO6((fVZ(zkPqrt2JfRiuOye>K27e)UKoHs!Lo! zGTE+Ro}l=u{4kT<$aIwIPm6%{NnMcX)WiKexxh~&oR4k2QDR7=cUMB0$IbRy(uLB(^p_X*0$-KN|S|BqZdJwQB@fY zwQ`Rdxm9uVht}EFluh?c;VCTx*gX~4JQGZSUeM!y@7!czG)ty#v2}e}n#F$qu=%eXEu_wG@ zpG?cr*_q`$l+B(h)3H@NK#RvdiRDzQyof5^ZZO3AnYqr6IzfHO;4hWe+YBOY&1!@CL#`(lv%mZ9WE4!1EY`klr} zhmB2dMW5i?mU4TZ<+`+WX^gvgpWOU3AFpyy8q8vf=VA}-M1t8Kiy|k;17c{ zkylTKq=4ZMZOqiK)xa|B%NaOZrrx?Q5;-BA zL$fSb!ZeLMslWa4Z-)$b-C5+GoUiV`P;=wV!q%jE(}Ouljb@c|5P*FsL)x^5N$zFd zhEGO+13B*ae_f<#W`vY3Kfy9*~NzQHHL3;T5+HfQ)f-?Z=s#h<8CK0D56P0Zc_wTrS zl^$Tih1Wp9wZI+iG*xuQx-P<}lcbhf1ib{{CX1LdOh>FCH}$*<>yeNWgu{fX8AcCq zwF^+)*`w}B+`nNw58-#_zRHAjLz}Y3Q5Pr-3}Sp9Q!+@Dml|aQh@&32Q8KBU5IZ2j z5t&q56_(U^J#T_LP(Zl(V{dbpjWv;_)+?;bcrIZU%EsFrqSrGABy^O?sczABpcSv^e0rEAs1Cme^bQT66BoGCzywIr%+Aibm=TTc}i-095Uhqvg10}e(yBniIjZC^Z8D05y^9&EizU>d1%a2W>J zsfYHDT5%+m0K-gKhK;R`x1O_iX8?bL5@XyfL#T2pQT#0Zh)C8i^fa__aL~@ak5~gm zNkK(~-zKh#usY1ffDN0nEoR=z&bFN&z@Z7bPP@Pc|Lk29!Fn^&DTNKM7ruqT*dQY# zvMmyO<2^?8y>CY$KoXUERE2bt@|$)!c{QOKw*ks}#M?f(`$QlF7O0e>r3F6&eIqm< zQa`6Tiw+sk%WUBe3p?`qAkS_ZgD-ifn)0mKPbm0mT+Xk|#;3rpV4g(Ya+M3T5ccgw zDAGSbV6@TfC*%wfPk8}8Z0pc@FL$*sONGQh`2pVJr+!{(`t9q_)Jt({^bbHcch72B z_y?WcyD|3%ko0#a=_}FM4F(q>LF{`vtG*%sPbpTK$K%i@Xr<0wtPyG#V|2soP`iSW zh&{ljOy}-EKRUy0se%vn0rW$@k%>Z&@}vvZ!F!$cv=EJ z-SW|x2}(Ao73tMVCzT79B@i3GNibduKbAtZ&8Tw)*~jAgOElt3^;c9 ze#yUNXAcZ5WenP@=O;6|X`swbM2A#BfwWFh&Upjw7~ekY1Sd{W$g7wgh)pguBe|bb zqk_UAOnQ~THN4%xQLeVERrG;^Zm2H}BzB2-NYGZ<-B8n{eNQfIHZT=62+e6l_L_&o zvb|6taMuqmiELISWq8kYgEarmx2&{$nu6tG?70xdJL@KQGvozDXcs=8wi2 z+!qf&h(iIy(k_+#P;*Bq^!`cj--(n4Tfac968<|kOoUoN$#B7Y-^xDJ)>R%?y{RX+ zzGehrt79JwWKl8^Q_&T&v?4UICtJdr)?A+=L{VdJya zm;?b;1Ty&==2@tJNJb2j2F;XPT+@&XNv4aJ@6g`-&NgvoK=4vaPNc#)aYan3PQFW! ztniGpJ-up-#L3e&8$_7&E6XG}tzEq~DO$U2;V1#!kl;Hje5$3NHTXK%MS}s^)$)f4 zX9Aa{GPYf>)W>Jo!oX3y2b{XnWty7K9}gzMDyPLY-Lm5u;s?JOil0=7CM+U8 zd4$O1wvVcR(Mc~MiaCh6G8iwgzUY8z8Z~9#A64c^WGg|#lntVK4nH&JzW!TPFJTV0 zjzQB!?!)l}@urYA?tgz9a%TNk3OwTO|9cs#|BPObVctsvHYE;h91_R85TDrs)#8yB zD2#yRNq`ZF7;2SfwWWs9@CFshvBrSyM`FZVjvx^>7%^eUOQjkSBrcupEYICRuD0 zo?s*JVcSQHPQ^J+z^@i}6ZY>d^$c;MZ=mHBRANJ{&}D!F!^kQ#F7}Q6ms~&>Jn$yo zj|V>9{65Q8ynAdnWgMOSVzZh^u7l4>66Ia772qo#J9VGjyqqqx7N&YNEFJ*98$MWZvEsfa025~pL6V7bd zThG9S_qAMvOBRU)bOrBssi#2{qex66z?@;&3Ayq&mM?#oUyDPv1rK1T0Ip#s64{M| zn#Jzjt&JGN8n{9|4q?nd8Wf0 z=pMkaBmp5>qq7J#r7Ug;E>9Ffp*;fv@x+#E51LM2F~68)iupnQh}jm#U>ttzYg&sW z_(91SW?d=Uc!|qg}M%5c{u$ z^O}0w#R&yJPR}D5?n$^6VEsU6IBn9mkd_4X=v~umkP+J!u;(lBd)RWVtAO+_-9;kU z+tQt#PR~hAoUhp+j9;NQBUN0;hqz5yB$#tevM7d5r#;4h8@CyWmP(Mx1aQp|4%;sU z+aT9236TO&fU|tBEn!h!Z##(aZ0jCQ8ABr;a26B&+Wf;;72Z5Z@;nkR#Mb;UoMlrb zcQlzui_2wnBfc;B>@|AKgXCoWKug4cI~B%+9Wl*&o#AdBE%iFMsaen9GV8Jws2MY} zG9Sxk+mG!|HS3u84wzs!>nXWZL*IHh(J_eZ$hHED{H}E@A9Wwd2@0)1@>G@FZT0N8 z72dZ2#3J!{`Tf+E-;uN&;Ofl+J4YiN#!)p%n=^}bP>H2u#ctA6c_$5VXXe=(0+_z0 z-U;2yzZt=KrfZQpDRpp7^ugZ2&TR?eO-E*#jSFVaOJR($h97*l}0^2Xgd{&Q6Z9Q3|g(>Qba{G$~xeit3o#6dA@YutA zOtnVVHlS7(`0Gzy5k%pXnQB4Nr~gGk7{%6ZjFOnWY( zu5r8ef3-)l0>n9&-hk7~G!W_a8lGi=pmSmXnDAN>YzJJ*l zIwy*^Hk|auaGqYaDEdk*IWETy+MB!cxU)3afw@Pi6To&_EHk>$YmoYZ3XiJ+bi?2V zV9#CjIKW5qqX9Cji3vB&0>F{2#CuxIAW^*_Kl1gq&5aD zku5}tvL-LU5l{9Ly;rJsSl}CojMT8{8r+g_dwq`I+Nw_N;9JzL6OMBbH#6Ode28J= zg__&5+;;sRPr?uEfvm;uUZMei9wb*0BYV@4uw3|^b2uau$iqqEtAef`m8^^fbzw_J;h265eQ@qpzs z_4F^SgRth(NhImC!V6xy)~wtLuGF~o)*qsY(*eMgv(dVkD?hEbm4I&WP;ph87GOHk z3drg{8ch_y;iF0(0!pYp+MzK>C|go1oCV$^$%>Ado{|BW<~ zf1p}CfCd`;y%dxg7Pjo^%}~g_`*Zy-u+knDg9-X@r-@(q5IVO64V}InA6$f+RK`Xl zL8ZY%_EIJ~!ORY&<&IeRz8iBiy1HImR=_b=jC>gg0`thj#lq|%k0kwJ*}cef5&d#3 z(e2~im1+|>kd>jrvmbF;1#P-qN*2ubVgxD9EQ z)zdOQw=xoCsQy>npi-nE2r&*T6*B=Wd z=%0BJTG3{XMm}jUwk(%q*x^r_)zzU=%#a`di}EZ4ZLHkbNSXrp-I1(zAcZ)OdBNz0 zn$NHMP6r5UDm(|!M($xn0JjjUs!R$MX*lBzSR9IJ)RyPt#DCoJS6Ef|;LZ*yy0l0b z@LHs!Q5LXAKSK1Bszb0v2r0u_&8`s7J`+@eTAy54WX+ZlXW99KOj`^=eU~SOpReZ^ z?q|5DjGubCGsSm#E*Bi0GkL!FmzKVG`9v7Qa|M-{zk4z)F#2>Y@hfrwv_;vQs|-bA zs~xzeK_IDgUM*fumm_u8S*wVQxLL|AE;EvjN|sQEg&#wRvQGs4i2$&T@EIzlgVcDY z;Ue4yE>R17y?K(1qR7Sw-$9qa6gN|^cy(qp*Z->Ahttg^gGQr8<5QG!am}R(w6t3gA zK(|4xs)qm|4C?ev#84qU z*#HqUlD&~iluEp0O94c*7ZY#Z1Yx(PfSq{#4PEZU;B2mq6QBdQI z6+rFezCD2wD|@<0A9K?G^mGOxOm48hTqhVURA})YUUJ5^Tm*4F}!h zF^H|qBhv0OH7UG2rSfL55ML`u#Q{qZaPtZw1OX}bAAuFePnpPy=;l1+Q!wREYn}+3 zZ{15Qa|t(luO5HwF>LNgdwUmKBl!fzS-4jWblK;I1%xn{uDajHQbsRq)q8^)q(?WG zhVzJ6Wn~y{-z;pj*RU`nH6P;8xP5kS^xC6H!%#1iVC{ck>5~?S%iIeUj%NK^7 zGpAD-tyJ`E;Ta@iPnillXb#!IB&*172&}hY&N(Y{ai@;P@bR>|DAlV%=XRADcB1B^ zPp#N4L+t~<4~r>7baI_)^}Q8-rWSdUoOceaWT=hDmX`CJW?)|txGGAPW8Qh5aq{(& z-Bw%DnSSw(6h)6Fb#j>|bD;IyoquoD(<^?%pyJm0Z6A5(4#R5-!5*d*F@P>!6R%j{R8- z+7KKmsEGYg)gK{hJ7U1SKQj3hOb7QEH{&ZWfx$N`9lSlj1Q2+t`pyK|F|vmyoud%8 z5{5=HH`|7qY55Vrz6t+c*9!R}sh1@s_g?l!ityB7A>T10@!Sn7?~Q(WWf}kVs>HP5 ze}-D>AEyX*1TZ3mNkBg>kVIV7eO zIWSdyLtE*r_S$glt%QMl5v?G2;hCnb=x8*)w3~*lJ{BOhoeT)1F1%QY;I?EMX}J?`f!LR>Kf8s0^t~gd43b)r6DE zK!9OBvf=Z^_ey;lq=qF3dzrJ%zXLjLm=;GO3LFouH-)~#aRSUdpS~O;+IqrIt#)t$ zX$S&cnLxEj2yZ%&!#1_3Q3DL5jq05`hCIh*C|X7yv**IZiVS<8VTOqeTICu`;Y$Pb z9Wu5}$*;5x2MjT*9+w|e6GRU7Z)`8=qehQ^k#=Q*i@(^jSZPl7#;?0B-A^ z&3KfPviupDBR>IFe1!BDZBGrJlNS&bWCze$8_8qE3}5jG z1Ka<58=XV-#8opC$OEY5P*4&~ zgi_{smPnY4P_t)UKKHkMf^buUw?=w+hClrq)B_>HZpsHH>?CMA3P7+&@r^(D3`RDt zNm!{WCW$uV^~uH%Y22b06+h`CePpjG?&#vL{KTo(uo~XLJ%ZkwunSOb2OgTB^!0Z5 zY>OysHC75pGKMr@B%NRIWQPZ7S8`L1r*u6ZGwn)*@_@$o2;S zx9SaQLr<8_=RPSJMyzJTQP3DPQC7fK+ujifT<6j3`$01Crq&P+Vx1XWBCq}L9Sac6 z>>q;UuAuEP@H^u<)NS@14K4|n>^Uf6#8EXneL)aLA=Rl_U!a0txLC7+H;5A?AedJp zsxL1=&`Jx!ydHkeDAD9e>{jjy_}H9!rvi3uym!-|qgNxH)O1V$FLoI@V3VT90Snt9 zl7N;31r=cU_;G0yZZr_xYVN&#}W3GBCO|A5;Uqg}G|^v8IUd#>@zwcEv5u zW-#Ouj%VsqOtx4si z6K_PBy~goVxA-Ub9KNYcuN5FX`Vrt<{+aX$#zu*vxU-*NmLChFfkzDKvnj#WB*I=s z^O@rM^MXw#_h!ohPwy}`Q5qszCm^iCwCnWC=B1n0f|OLI(hlwKtsy`1#O~Un%injE z$f5c2l@oq#aM}%P*|SBZWbkF|W4;LSx;dP^RSh0f8eu_i45`luuh+JJdIpg&-+fdM{wo)LIh@I`V_t zb-PndAtg0yM<|oql0@`huiYB2+F}!a(VJ?cBA;(QT}RA_4A)!|i%uC^-z1&t|Nkuv z{|D%l|C$1+r&l7!+dvsuIeJ!W79nL23>PG@PQa9w5}^Tl?P$Nh>=Mpj-uVwhf5M#+ z2@a3qqPMP(UCV$=vl}$HyDs2Tv;XktPgYCxog&k=iLZMnbT>m@AR=r7*3AHs1ch}Y zg<3WrQkJ%?xs)@X*#Q61ulRi;oibs-3c11GPK$5du;G8-|8C6nzf`}&A?5@6P1KaN Kl%6S?2K*1~*GB~a literal 0 HcmV?d00001 diff --git a/_images/docs/wait_until_task_D.png b/_images/docs/wait_until_task_D.png new file mode 100644 index 0000000000000000000000000000000000000000..24aa29345a299e62e938b9732adee99491dcd5f5 GIT binary patch literal 73845 zcmeFZWmJ@Z_x4RGCWVsKC%ACCm^5(p`h3f-pFQpdd(h_YlGWqI612 zch__B^SbVJUH^5zc;4O5de;4h#hN(hoNw*DkK?l^@|l+Ey}Pt`v9Pf2sXbA8j)jE_ z$HKx{BDf7a0>f^O$HEH4Qd4^T($jP!4L_A~_^`_=va}QOIZ{P)gQJhuM?;%;5NRnI znRmo~7Dwx|aZ4KU{MIcUJW4_W0t7SS)4`0-cH`z{^S0O2_<4ABy;E{p7v1dk`6-b` zBYdSFGjrMq-;&ILD-f`Rf`C8IyH@6T{`n91lL#jJ_Y?0F*q8tHFl*Qo%$>ilR=WER zN&fe(2ntpqu7ADafs&=xzpsZtr`}u_c;*WzQu6QHLZ7hw|MbEL))I@urxLd20utw+ zk45c&eo;%{)Z~yEH2dZB75nD_Xi_3YQ_fzd^{vO_N`Zw8wp zsKT8X7;+`a_f=PhH#6~8enJW#cvBX=no$7XKcB@6O$!0$MJM)4VRI5NhX~gAs{Y5o zmAO@aj+m(f6Rbq~#At;XxN;(!{dzG6F#A~qUkc$jliBmG;&Alu4gDPXzqj*$N9X_O z+A()%=?eY3`4Nd23_`u%?CX{Ug5qtQ|;)%wnC_2f>E z{CD-+O_O~oB3w;%rsFj(pNETqt-Y(s(T+(GnQp#16gXZtyPlBUMUxl3_^PF6JCZDn zdz+}lo0wLVyGe~e=bq8$<{7e^Q#6afF{Xd+El-j2B&@#he5ajc0X4M{C%4rPK6jLG zUF<%|$=dm$NHTuf701LhOX0Gbom{tBJv(!cQRb1YA8_-VY=>i3anr0qU0sj51dMA0 zoAUGy)<*{}w>+Aoif3Lk&mWK5GL2T)zmRy<4RToV+F$MfzQK0D^*L-F9l1Mv*i+}e zzQO2wTt6G*^zgp_X|I`zd&5e)&y?BK9<|Zc$wJ&heG?w7kYS#D@YozF3-CphIt^j_6@@Ln=f3Y1B`RSoMVO~ zL3l5rXk%q%<$hNav~ff9+NZ0q=O(pcAIN9@w;PY^2>EN6ZB0_w`t`|o_jOf$XMI#X-;72RCmvI3XpB-izYWvte1{{25s%7w)8r&@H zV%%CrImH&J$$B4@_}p@8*bT2=e6Nn_AkF7KpLOl!(@AluNycYzi=TuK$WC9KZ*QCW z9qJl2+w{@a&q{ArBurW-n-usp)YBiI4ZYBImzeSV{GoaJ&E)uLiL2~hH`|uF+1dL^ zua&e-Zz?{+SJytJ2WRWWM$#w3q{H+Ham4|b>u-ua@aP-fuc6thnuLwm$epy3Y#1Oy zKAD@P8_nJZc169zubi0rwQu=T#L^q)ql+2%cx2}pK3la_7eCbn#`iQOreC=)`s;H2 z!16FCsHwQ+e%>k3H0OP^aUZ%p(^!8#Qr%=d*|ZZTfUIA$c5?w4Gt0mgB^D*e*A^a~7gzVe=lz2O5=9JqsXN1w?m=w~U z({C=@+|Zr|4ecCFI!&sI?_g_7ni4t3L5`TlSf=zRIsyvH1uR3nr=8pHZ2>ztu9I*N zyZLy=r=CMS3F7mN(=v7?sP5Mcf#UCv0(E~_QMLg`OHCSSQp5en6As1WRj}#0l$yH3 z5hJK1u|hPQ&#Y;xNB&hYq_nM|5fSOj3KHsS(zwWNfheFkd*!ZA2l@`lOTSC4QF)ZV zlJ330YB>cNhy}$j(4Zw2cb-G4>Lot}Awx^93b+L(`82LkL=f4Reu%+mylK zpO{@5kcu*1)p7;OO~lSKUMu6mK~}&;WthU`jaZu6Rx+4GK-(9dzi(;PzuC;%yo$i{ z7u~VEOPIRiGkcz1xUWE)e;+z`r-OdQGTmWs%Kv<`ia!In;BTICkYvZ(un|>qv}5cF zE2tnayH52IItC7@(WFa~TUV#cPB^_YXH?X11wk6Za;HuB z_w+;q$cm0>_d{TYO4zg%89d;mohfT`%438j_LG#*N`T#+3?Vf6`d*~u&VZQZ5fEU- z^qIANb~&~QtuiSG(D9dFT5tttK=iF*xG~1 ztH^g+V{eh`OBIx}Kr%`MhjlTfvJFmwx?FdJsAF3XEc*$Q6wvfm41_`F9gTCBJ4y1! zckGRV6Pc492)GFx4Dc+hH6X2wv%BKbc$6?gLQGdRbF=lp64Xk3;bFFUga**`v+L$r|?MMjlG0GhXroyvMC$50g&+ z>^A^shIkYHV4Jvqt*s;xBq*#aAXFF}vp+;(*9IT6h){m4$>@J#0jK+1FoBTd6(~>) zb-ucNk5*~Y7beCNnHmcWK;00!J6iAxO1!Whc`;myNb7uKQJkQBu32w8cnEMy*y{C zUt(M|9c@#X?$IQuqRKWproyOA?FJ$SY`cYOFlBL0_{`jdR0jUY)`z|2U2nFe9rKXC zkdiESKZ{?wKloRUB%X%b3OXTB6cyx*^^()N4dRDvL$qHi@{044PvOlE@?PH5f4M~9 zACXV~RBr-7Y&Zv-fW;i2ltFR}O|D(>Ck8XBf?*Nvm)Xbsx$q72nIns{S>-Zo_WbEA z_wEHBaocT|FloAAYK!4)b?QkfZOs-Mab7lv7mY+1^PVL!OEke_-`&!f_)Om1d?YUT z$0=mRv%m%H%{fojdv9gIbE`D&2QWnVLm_7@k4}QHgtUWqeZMGUSb_CmBQw3+JPx_)X3vfqg zTg3?~e>btA6h1G9FS7INkDu>26?le|0z1N7OA_b5g=a?#9@yg$l5IsmUe^%wz5^24 z$kFH6>!Pi$-##Lq)QYuEASQ*{q7lgG1#}^GuUHl@vE1DqUJE~~j0yGvY6Xgjii1(c z|5cuYc|cH*M>*du!g(NSYQxph_u^c9>_dOkMGGxRA$~uyL?cf4Ih6CFBwH>IfKXg1 zZrx^G{_T@YO-~s~QBH>Mo|JSp2;wN4IVA{0uyY9Ve9N zVCJuV*i}iKqyNH$SZU#5*TM0u8_$Xsut!QQ{A~Qbrn;+@y!!bEBl@su!u&EdsL^$# z5GmWomjNEU=e10%U+QAjFAk_ZtXe{6>t{DooW&nm^`r?mV!Dw6;q}qF54}@arHa!Z zJN7ks3qMNq@}a=3S7wqP;YLCZ-!_|J9nZ;m+l^#?Q^nEQ>?i6_LWcDOkXHK+NxaT< zBGyKy`?l5|xw+20Ik6&h6)d2zp^&n|i(#J6hmiIpt^4cYU?2U8M$Wkko9_zMu+yJ* zUZ>G&N7tS14u!CFJzlsvXSAC`GGE@5?eZ&$!^YT@ypS}j!z`~V|MrRDL9ffYM~bww zDb-rNIhxKU6Fi_6L3q|K;5@r&9Ggp47a2x<~R?;Z)|p^rp>$SJyJBx^57%oszs{nFXzfNq?hc6BiHMwAUd~Tx5TMtPgI~*05?{(VhBc z*kCv?z3VO5JgQJb)M5#DB*y1ZQX+eu2ewEUm!iziZZ8z^879`VGRJ1x!rpR@jqNJur1GHR#Bq7fxgkwG_F znpenG@_lESq{b`c+|Z=7YR>GqRWu|)R`ZLEYfX5^hE=7(Po zJ^R*h#3F00e|6UD2*@l`MblH%hWr#y_4p|bo%)lUUUo`Zo-RUn4edn1*YQ+ZO4Dugu0qv#?^;{E+VciyM_!xk@j}1*7 z0yr69?#m1hlnLZ16e9WO0S+SosHpj97(zf71I){3m2XXty z8M>&@T1f}0fog6PJ4IZ8-7uF@ZR*JpA*>VM$q26p6pHr%bRu6FH~aQ3>Z|D&#@vSk z#?X{2e=haOXBnVc_)#EV{WZaBuuU~5`K)*Ags+2q*6BC@CnW?0DAuMNY;yMK1=S)K&;iwQGTS?ijU8j8MoQq@EmH2hFR z+aLT>9&`V|KNe|J{wmXir}j{0=(`eJr9@|@Q`76h&a6jeagU`}=D4%HQL%f>?@oVn z`W{tZxsTHWy4NK?3V^UO;jmj{F+z333q2dlX_ORrG4-}r?1z>NE`2-vCHYkodL6yr z?#H4WCJ-StMskPY<5)RbhUvJ)@9=PMU8aI=lT3TE)OG8?5v56!0>5T?-HSOTq%>%- z+UOMm_uU@ts&rwx^jTFFTv@!IF_oP*T>mg=%|f~j5qV6>Ju8Qj5wUnmyaTma8Yt$? z5VvMHr7R7cET{PL=sW%~`$c_A`TFEX+i-8^&2cxD@s&6~P=R8`x!Dr@Md@JG;MJ}> z%McI$vfbz{HvGEP#@VuUO4bMOH;NPF|6{IhjvpgR_UrViC6035){QtHC8icO zBe~ZwjTZc?9V(JBfg^S-rl}qA^OFT!;8ee@GcF?ME5Ri}kM5vn@`liybbox8(plj^ zbB-+TE^v6o^v4J%iLXB36U z#+0Z@2A>G`+8fiwXG($)<}p#-D!9j(bZVDVKsq2tA1OHzy!gkr#C2f#)f#>UPus_; z)H753{Bi@BFjT{&rfVqKYi|?#kZyWejlAy7RkbOizxmZqJN2@D5&6lX#pUn*zq}h@ zPz*fGXfhhSJyvy#4P3R)>bCHJ6Nq(5Ubksck1~nHA|+i(U8fC_$5mn%cLTX;rjH(! z_XwB9IH>Z%w*)O3Jq8sQ%P}H|rT&oL=(jS3E9*z}zldkSGR&m_mM z5vB>5G0usddn*{*;Ko>rm#CT7YpRla&NzJQW!*;=0RG9V4_-{F#d zTykeHW;m4OIXDo+>uYQ=e1Bx4sk<()G9nHv@22~<;;ux+cUgBTc#Q*#jEwJ({U~2D zURsf{PzUh5Wh{EB9VG|ylV|;OQgeH)`zrA8wgp|Rfv~zYHkD+{+I%60;6ZKuW@^O} zB8fyL2|qNO8ji3RKp<_WD1H=G6ywiPaY|*(mlY(Ye8@dJ_jBMvlfhGQOFF~O$7erb z>R(b``1Oo7k-;q;-oN_qF;%kU-_N9dD+%5^i9dE6W8VrS=_^owNwsZbKrPgzDoVu; zUb_f2vLG8$!4#%Sw;MOKd9zqz?=JGC_|H$sR+7SfpZuC3pLMie>H5}H3W)|%I^GEZ zdJ)y>k}Qq2sS#c!1fif%vcXE`o2bos&y%;BqjFK!EoI6kQds8MS^H3Cs%LOatLX;2dC` z+p~YalDhN1qHq~J_bCPnDet-Gaxz z@xNB@=2|A0kvGA#eIUJqA#Wuqc{K?3t+4#Ci<7h&ZLttS5oK^;MSZN&`M^b1>=rCj z^S*5d4R}ou$mQQn(peIXYV}8z>;rjS3ETH{0FMTx1!Qn3=i=*yU7u+V_Izm{5VcNi68J zfuN31^-uVNAt!SUzBE4AEfEr%Z4n|m*I7RCtNM2EiE&j*l(}Fi{WecEZWi z+i^-9$v#yOCW+t)y0eqz<3CpQ8HAx~>tL^|1(mT^B4+~xXdlg__eR?huXmOAk&w1r zXBr81xeAm+Qzow(=n_?B6>5q+P5Qne?d8@YcCt(qqr}%;s_)GiL|3Q8iAI|5wR(DX zUYz$_H<%f-jo9U9^e!hyRTGY!g3?8NlEe#F{Lus3lUUfO%X-0wE87a5+xI=5vJZjQ zFqc`TO??m83iK(kMfWis>-2SUggQijcM^YlJBi#ztlZVf$?MUt+Dy{hYs08|tVEoU z+xJ{aWDlPCy6e;eM%h$6%ec@j5}BPq>FbMqE1#j51h$ ze8OL8Gt=O;wU%ETTUUm@#_rH_~tZPv_Z0 zz&893a(z7c#KLll34O;_QrSc(*Xj(5n5h<^dM{r6IK$Ja8b6hwqLNWX4BY((Dlzu% zm;y{`GmmlW6DWHK}1TFcjJ z^f`V57>u^Qhk7il#|2Y2#Yz>i5-i$C9H`JJ;{M@NikyWcEYSqV8P^wGCjO^OZ!kZz zKQ#Bun|iLKc}!FR@9*L>e7R~9dic5}5PJ*oI`aW1)78A*_Gn{#YpZ^{%F3yBiAuu# z^_v|r=Pj-b-=9@3Tao1DTl|0`7b$&t@M{{lN6q6Y_;~4U#Ry_CY;@C&b!F7#3qPi} zo2)8apR5-C)OxbJFio!g%5NjZX`&);eWVaIeB4Rrv9@%eYb@Ay)&KzJ2LzQ|t@Rw%FoiESIhT zwXWJ#VaER)%5$89g1HJb>?mlZacX{Cgf(Bjkv{t9Q1sn?_G`L#&qTz6-7krm?m7`Z zqbkfLa2IcGyyf9Y>z2xcZ}~-K@G$oloQWb6>H690lP1O7~1#?`^sDkg<3KtB}4-Ul#(G5j;Yj=3NC06apYI(m@@8w={Ge$BwVxfjuJDJ~PYP9J{3>9!Z?J*6^^_G_862)lV z3oeh#!_j)b1)jQjy9%Mu!R|pIqelfx#pPXCf678NB~wZXGvYH&)((B>+Zd$sHm2XQfkF z%7o;yka^ILDZwkHBM>_@X1sO61HoAZ?b}(|!-usQZ@0JbGZg0?1s|xD8!-XA9tW zZ+`Y$>iNL=3IxLVfP6GSbq1`SW25-4kA0htCL9J`Sb$nVNrR>vZ}9DsAd`!PdMMQ> z7J>W(Nv~}t);&MUl z`+Wx`QSGdI;iTtlcUyV&`txR)G}Z`N*~1r*peis#8QIyQ2onwt!)%O-*~-?=AZnhx z(gXxpgMUam>z0p)n@$1JO%vb>NdY~&9Hxuk_%PtRi8;_Pof2TR;B<7IkK1N2XaeX> z^5+&R-#|8-Z#e7JE3FC@|0d_Ogb}JbYw`cI{ z6Q|H|p_3oa#O;dnV*kVZRQL26rTz0;^}?D%6sA{o%T{)asYqD~OGOgy)VqIUIm>j9+T` zB^>zZZ6#W+$UEcWJp&`;sh9seqy)j0K1EyE-v_Tk?J0e`Px*qL_$|6cg+RWMltRc~ z_$&@&<4+|E_GB$p^iHX>zU)+-CQr|JwyR`xaHm`mA;^8hF@8w23@~9JgWq?C?ptz( z?mmq!y=yT=mK7G~2W~4BWmyL4LPp!{F~|*pE(9_N7k@dC96$3%jf+)zFcd(7IH{cT z7u&(6MFKo#SQG_H(Sz;62p{%UoO$LNXSM_L$KSLt)86ZaoLPIM)bPw~KK^BZaVhC5 zT52aL_j)}K*wy^Ci)8TT=;ZbjX*4}fw2SNRCSrFDP47MhUs~+k$&!RS;~yY4#CfKa5lsEMWkDqQ{toeuiP;G>E$;Xc~a#wj|Df^_=}O z{e!fc2XW|6u9q?vlYX&6B$9uezY;1FXLj5X(eme0$URs3F3){_A{9r18yA(1ZxMtv zXUH7(J8_GX3uy9%LVmU_E{W-UK(c9K%}sm{TS^EeUrv4YClq$Pl5@}Zz2#5(X9Bz? zjJ)rSrC$`CTZ9!VK6y9v(JT1FOLb*st?|&`U(*7QxXRcv=k6qI^FfoIGQSY_y7rYt z+`aQf3{gzTqOWg^aS`}#&;{@EL)=Jkpj!56vr!2$IR80I9LKHd9uVupt3@uk(o=wX zLJfDcBY6bsO1hc18hlu`Tp@1>@NkABYwwVA*8I|v=Ie4N=3%iaC#VT>u%*$stZ#y+c(l&>v?xW-8?BkjC4Cn`C+ zX+rQJlWpS69HGU(ZUWOEFcy`OQg-t-LK3ekf{CQ&w)~3SvWc`*5@ka45?1NJ!CBJl5IXPalx%t8bU41PsS;j@(=R;;i&KDSug5(;M zvwZ}eiPUOI&DiOV)Ivy|+3#fxt}sYn19Fjy*QBokY)`|*5sAW7+4dWuzKrNb*7`b| zD21~#(S83KR2RQZEYT;lNoxS(fA8_aL!JOmFS#_v_|8ktK-<-!#~i%1b|1f0?4Y*i zII^n6`}X2{wo|dlCbbg{GH6TXhcbMLhT$t))@@p583V?VgQkYa#Qn(Hk2h`v!uW4K z2_vtOV#NbV&Gf~}Q6c%dNAaX48Yp(65L)A)+4S~<Vu()vgekJM`E5wXr=Nyte}xHAzF zU#JvdEsfkXvRGLe6@^r#nN2}4a%Y2an4V;TGd6nvley&)#BX31Vh33~B3Ux^*{rk~ zZvU8cGqqXaXTIA$v*qFza=`$?S(Q=R=^d8uX29xZ+$Q0^z>7-HU6N|ClJld#uay_K++el5S~Ib zBGrZAqf##mJ3(wz?YlxcCDveJQc6f82%f3Fd@}lR(vw%dA|8vj+nUPo+nNFtO>gO- zr(!(sAK8+f*4c0o4gJhFQV6jLjuNtEGZO2Tr0O+@MNZ;bK5%Sb%T>czC|6zzw@FNq zgp2lE#V3*!Dc|_n?^*snC$2~&G(xhTjGy^5vGd0;xdYo0D_SLvk)bdyB>xL_AweYo zi>OYPyk&jzAfn{j#UeZ##1cvq9jD8FLZDZ9BGlrN`29^$)LChBgnMGIi2TFg60I7; zvvbv*`%|io4jh)TpE!p;EHu^}GH=+C1kAeJw@%rk8Tj+~BFr_q2OhOI#E^s% z80nv2W}5bo)3*F^(b)>ly2{XwsrXKhW!^Zu)A&d!wDBXxs86))&9@88hwR-@Tq5Ug zqS%!jfRf~L4^WJthmQj-#w{5^^^kE;W(5OPPrN0fHanrwy0{H6RAcSr{@ECXitjJo z$(~>$=^K#bhxnHKYNUE*H^wTvH2xG*BZ?7(hmNyX#CS=_hElZkwj)bQH}_R1`nZ-s zGLX?g;RvzD(N1q&u4U)^1OANV=e1#vbzieBWAU&YS`^TazBOXg*t&TB>b_C6rTv^` zKd&DXT7TthmSqA~zshX()~%>oj4Ms4@IS2;@7exNwh}QJ{4frk8VKBjG4K7a;gF9% z3mfUqHcWI3u|x5#%1fSFgejhQId3bLxX_<_?f&k<=nx++g)ni4xOmiP#;%WvlBo{C-5mV_;0s_vhDm=KoTs5)Px6+9$dj zJn9SY++Y#i9RDSJ)xm#k?uhiHv zI};0|cZWtNytTw#Bu7*;R{FFn?)+YR8^|e!HS*X=sIN*Vo3M@=!fLO}hyUue_{Wg?4-|q=sG5>xVzI*BKqBptQu9IHy*0WXj)ykxgZ$Ov zN~l*Cj5;i8NKL$!FPW>pkf@Yk4uH6Oi)|J}}E zMCv+d;f3QG?GiI{miPtf160Wce5I@(SlPRB_&{lp#qLQJKT`MXSafRcTT3@$_GV7j zrMCtz_;~&EfQ>+#`y`-;2@HJL5^oIhg87*1bB|!*)*5#eyl>t zScq7`agjUOq}=IXzca{tSm@ozmN@_}E_Y~H%|SWJT5i>?7r_De+%4J6zqWq2lMenq zGQydE!Um}E-pHIc19b#!yv%wFU`5NU->3S_TW$f`fJdQGb(PY>#`&Nslk&OVtt=q4 zY*$JFDQ@^#m4GF!L9f;3LELzcu=Dz zO1#MDcxzC$)%B5i3zoFR=p)~g9lL-?NgYZcf%82f0pNsNGtBm$r7Xdmt9KDZ_wj=s zlWk?7+Yt^5?(6IqS2hgZ* zzNWn~tni(3=}M8d?#MCg8IZg7CAZH+adbJy6m*e=IgiX@&T~) zLy<+Z>$7Br`dR<;aW9Was6=(2_+*VDiR@6CbK9M*UbCw*XaLY?;CNkwS^~yx<7f)5 zEggP%d8W&BgxdAJsa!V$<|Dc40K#f|v!tDv^LdbiIo;t2z;atyGrk$KcsIOz@Jri6 zdaLHM^zT62sT*{1#g?hFndGhM~m9nIfzcmEtk(nqIagzr~am?q34q(P*9La zkKUC1!-F9^6F_M*4ItcPh4mX{y#+E#^wux>o6ff!tT%yWp?5S^I!VvX@fzn40U6qH_aEGy{(X<7VlIw7%~>0e2+F~-hf2CYwClz0y|a1Xak zSbvbKVJ4uCV@kg_*_E-M7g^u|{NVdpWVt>#}q7A19jN%+>UriI2?j+ap&+^YnUWoS?iaCwg zSi+W4S5YR-g&ERpQq4Dj#ZVgi`8s<%QXLD&+!x?uB^-td49cefp-xvF9plXWhafnp zg)0-;yJB;ika5BOkbEwvdnZ^B4cHdWfgI6GgaQpel1hJ;M(f@I_}8R7ZI;LSjGn)- zCz;l1%~#I=MF*xpG^(S-jf1aqcPQ%8sb=oBkqTbvRHmZ%cR?z#r0p6ulqj_WeJ^AZ z;Hw*!hzZ#aHpYJ??MF(U495At$|6)}&m!FQx=|U#l_o#Of!9=GXsvr8bPsxs?vla@ zM45*0NPCZpOzJ20fMy3PBSs<1P(F1`bgMVy*+BuF5H00-6Mo;aqXD3eU}^p0893xj~lxx99{*}SoHaWn`c9{28@KAr3ZH6Ho^B`o+u8zW9Ad? z5WJO}lnxjVnVDm)vW<5M{8d|hZDDo~76{K66pazXsK zDVVbPDdZQVL|qc3s@>^Ei(EqJrm5}#akV~WeYrE*?%Pw0m&OTE&sAf7WC8NLxHjrJ z73=7V#l9uXW|qI|-Y(${n}NruC$-iGW+&_V`6z2CBt`1D;xbP_twj;!mhsIUfN3i(a$n_5z4vDzjq z0stkj@92Wc+J_)G0SBbsv2^&J&QeFH?G4a0b`053&vX_9YUwSR9OT+o}&0Vhk zxS9%KPV3?*s}0|jIxd!F=R7>6iA2~YbS6r2ib=8Lm6reUlHL9F@hR=HEC;=280W`4 z0V)Z!?GxjFSUH1REc7A~hXOPF^AT6m;mA@V_hx77#N5duP~OR)l9u zW8AJD(8g8n2MAb#bF?e{eRca3MwlB7b%06_Yle@^VPT@u;qwqSwV7|JQRV9ocfQ`3 z0XTWgUmAY5%92;T#E^aowVoh2Rw;PR>m#HpPnJ&EIpRg|GB}^(P--O=o^?oV;`WZ= zeD!O_L|Ju3wf6|WH2S`?5R(m8*9xEdZ-)ZDN6dT zi=$lJlHcKeLq|ba3q%x;mbIG~j*HW4tm5`uRY2Zl5S^tmo{6+VRTm8_y-G1E#Y}(z zg)SJFzhDVi%ECwUzV~6vIFe0PA`*owbdp_74*HvIeiMF&qHTEa*Xc= z03C0wQ`Ro0iPk`lSQY)Ra~-54e_|1EG8ci0`ou*6UrbT76Ko>1c-CV{9Hb&o)w4tX z_{l|$5Sn3OxotC=Z{L0Pxln`;XRC?tIM64gbfZ33f!(sv97EgM^7plYo?}Ob;~*C| z1T-mf=Z+EU@>m4asVPP7xk=u;kz-yyAT%;d(aeT9FmAmKd-efog`wy785e@bQHk0R zgBTS>x|lgjl}`V>1Kh@f@C7p`okC=}5S#(^QJr<^cX+M2(g<`YE~TA}@-E$41R-mi zh;;f!6}?czm?eYN?rX9fQ;bk&e<#Mee;YRu5XoG-Fw+b%Df_RwHd#t?RM*>t;1$^W z1o}$s)yiyo2VpGyqZhWL|kmDST&X=<{8*7!I61>S*6@2#H` zVYPj*W=ag*wdXyrTJT0bISmZV=C9G3SGn^=#ymjjlkMf%A*W%Ab1zY*{}B1;)1Q*g z1=`jiC%Pl+^Ki|Voo^*B?v|X z0!VxV_hZjRB@{-c9&Bi(sUxH~M%_!h(BW%fA*#-a7ZYcrhE|`#8K>S2$`ut35FlVw zFmPc}qfj+sBIg00u_sBg8ingTlFTq6A!VgryefRV(2*MV@qS%Q_#p3sGkAh0+GaIU zwX(wfv8cM77j_NIOZ+1Tl^&h|>wx0rc$M28P5D!m^%d*S?_CRqOKF^K?D zU{=FlW?g&%XjC#?d{2`R3p9V7Y$@YEUj6*^?9Q=j2AG+6E5B(=casf3_cSM@B3y5& zGaqv^<|+Z4tXKR$J?vkojQL8b&OQn01`+1QnLhZY0+6f!UB3LKS^syBC3>&Od!Bp# zj&%+E&23RaVO0G93zOxdNcjZ#gr4Z<+rnw-&$Rs}$C+&}1+SijSB5DEvjbRQz|{u# zcX8(Q?ibbOi}Jl{D=aKWA3F#)kUQS8#$5n|1qcJy<3lbsUJL%A$DtHBi*5Vye^80I zH?8?0e@~RZTrtP@eryW`GUoxbgpn=Yv?q#7=NLHR`69(5^O7|%%Na`Y_ndY=-SEsR zB@M9edF7TxZSPGJK7EAJFYGt#ax4SipbU@!c%oG*y|Pqzn7pQ*ILqF|`^xitnDggJ zM_K;Z&y(P#WumpsW#TP|mE&L-rZ+}-1!k>=R;~6EewwqH$&gDoQmMeAjB3mgAa$co_{L$ z_i2hTmav2mjsT%<^EgD!soAc}>)|vn&lJF>rGybCE91TVV}sPj2pu`TTE7i5?#dZl z7lR>;NB5|)OEf7 z6slXqkDuvK=?MpCFkdKeM=Su3F&4JdM%=nLSLv@SZhnWA+pY1{N1%CNP$+SIJ&a(# z03c|3GPO1qa7&n%lLk^9CxKo8+Rg3E8FemwIXwYlYY}k)C9j))eqXh^<|3zmV_X1q zt@y~MC{do9%s4C&50AEWvy2l6c)+bIkvSG#)fL^GHqjGJwmdePV)_jO3OK8lC6!Y6 z#$-I=BQoJohrmzmA4qv1EJg1K!vh>gB!FXv^}+uFwpCcRQ>dMz^X5rRK3_73jEU+#^S*tq+;HwHdoXJz+V z=qA+XR+=IDYy>PUkP%&EEgqnovUV^4Zr=s+K_kS!foqc!81)ysb zWOkX79e>Q5QKH_KF9-yjM%{owmOjva;AbDE0dI~ApmK_&4JUFpeR5>rm29j1H*yT; z7tkY-bN6XpCnKOp0jN(tloY>VC+$iHy&gZw2pEq6q-5=Q-nm?c@T48hRI6Ybia_ET z%as!Gr^!rc0{VLem;z1!!Q+m1_653KlpjNoZ4Nh6beCiGs;=o~iV(E`67#T0Dyu2< z7hp#%%>>Aee#k2t(obtT8!oN`dgwd!M zEx?bJa952k^8)Slu_$5dr@k+~ad#YVlq&(#H^SZ78&pftwCgL{k0Gaqi=4lSoT6~~ zMSnImE%sItJ@oCg+>tT4gO3sp87Rr>u$W?`lB^1|I?}*E%fLmc($g{aqd%5ij#Fpy zUsTL?-dq3d756@d5Qs0Ke9vIlr6}~0C_At+2sFW z?=7REZnyAZ5QIT$0HtearKG!2MA9OpWJskMksLr8=>|cNP*IRh>FyNijzPM+-g|tW zbIxxp`%ThW1F`4qX6>0R8LoYw)KLYm#~l6} z{RnzpkuT6ro1yF|G3VZt83fGfIq>n5Ex#((whHRAJ*o<;&{&lqyIgI)Lv(AIuVYF~kxc+^$w3OJfr zPXL~x^$94To$Ah)cnts%%0_C$>34eI50eO~VYKZ)8PUiCu2*Q2jw#@JvHZOB+xZd$ zzF}Xg6d>4~8Rcw&Bz=pVN8fS+-Pm{U<*C_!EaG|YG6D!YBY@#FQRc94Uk^1&t7Py+ zBh7XKZ8{)9lrs(P&xVfYdmRu#Zlt13w`^P9brLJDo&&l2@WpQ>nId-_N8oG32(|1#icBz5%1>L?e4@({vu)?!A0}Wvv!Hy0CLq~vA zX=NrhJr@R20P_=?pPMg}J#rCNq2=twxCC#gmB=KX}@wWzqhr^Jc9F}@{ zI8mawwrN36cwgKOy(kcXw2Gt#bxl1_P zl>>3Qy*zCS8XpEo?VJ4S-FFj!g=CN{JZ6;dpgn0*KBY>@Gz!JGNOk?3lbu~~;XLJ} zO-2v-EIMN7{#^oi;TQm-mHu+?2b;@`5S}8N(4!1}KkWIPlAr1bV18rs^ou~RXwx5S z3q38xml#|BA=7+f3LIBo$(w zL?X?({PdE$>HV@lOcO^-#xIQ*U*&nP7(ZECf%I#n>ANpXI_2=B;9P6nI5?5Ex=*?v zjy{mspA@*{R%y{R6A9YKN6aRKbD zWLk>qmGSroo$a~@cslWdI5dq(xuE>jZwem)-ArkXFa}_ z=jcwuo`Xo2W_Kxgl3X9?n+0sH0RovK{lX2YAu5N!yR8q~PtI%4`$}W4eL7A>#&eYR zVmd2N@{u5({3tE|dXv!}-vm`~N_>Hv@Ks5Y|QYYNp2bw6c#aFOETGC)e zKYSmo!se60=DAbcpi0ecjEtWlS(@EQG*7{?>C}Wu0T_Vuk!S zFweLt0Oc7Hl0)%XFXpjFpR~$<;{ku}$9~*6kj_#5gn9aWRG3T3P!aQtx&2SG!r|>g zl9YQ{X$SBh%5bWXBqhM6tnPOp5TR zOf|7#T;s97Pm%x9zvnOmi=q1O#3LQ(9%qI$|5gk18paxJp0iFHRHQMZI()hti&Qcyi3L=+pRE%o)FGI=41L%{JzbqKB>*;_Hu_yy<-Lu^?8Xt)GN z+hdtk6wDGgqtL7?p3S2G%0xRBXu?7KNIMOl=djQ!9KQ`ZbH(+%`uJM+W~mEakg_a+ z4iJC(LqFv_-+Jz$h&At3z}E?LZxYf}w@hN*WifN$!4@3}I?IhvRGz~7?32u~z(OUX ztf)Tj$LFY6hRtO2SbIG6bcfbhm+Sh&9jP;}sIuO-lD7VeSzNI#3xNrtoL|uXg}43? zR97K#ob6Fsw-mYci?aB?kS(-QB3c9;=9^z=SZq2gR+@&=kaP1cz8KEcB^P8SsGVz| zi?peLGD$-nbTE+9!p%1ul%TviBRB+<&|krhNMr#etdlYUCy1a~>FV;LC;FzwbM?Eo zm_&(aMf>B$`quL6Y!8;bw)oqfG#MC5SQv(0UY?%__qkR-Bd~WT;En)I0DfcD5@oyV zSiPVx<9-BeyvF%Sc&Jn!OhDtJtr#RlX`(&aBVl4kgvMP?ZWS7|fn6+lIYGR$)X*Uv zNu-4F*FByjh-i2w_uGTZ)YAv=>2ve3gVJ+7ZnKw>|A}qDo>7*O^fBEK@vV4VqPH9% zn#J<}c^u8=E`02r_-HBiD}YDw4^nbb^7V74@pbgjjQ2gWepsgF*9C;fg*P!AKp~7m zc@9cgy_`sN%ExJ*IiJJIO)2fV;}r`tz%b*Bl4dmh zXCSPGqg-imxM7V~qY$r7zk#O8!R=lhX$w5T)r)vQbJA#HI~_@^)(!fAa~v;^&gU4$ zgksu=(oryqscZ@cktnonfbF1!uD0W2HUcZRG*&jFyXOn4bo3?J$uJgPi)8fDn2CMv zWkB{X-CpeT<-55nHHTLK3abM8?)OlIX4is}mKNGG)s@qCpKxXCU2~|I2nR~t8ff)e z=gW-MY;U}s>)GlfK`d4)se5GgvyjE~3Q6Zve=1YDz#(}mT4ih4ed(#s!g|0@5% zU8nQF!!g(vKhYemB7}_%_Hq-2TF})mcY!%|~wS zPWqEDuid~a`>NuxJHRS~e{2B@m0wLK435;L2wGHD?1MjI*h3;+Y7F*ygg6Av(iR$C~wPdijO~Nqz z*2A&qy-=~MW2--2$wK7SCLs1#1CGqZeDXIx%~O`S!{A2V%EjpCbVj#W`lms{I|*nc zDFRU{b}GL|^3#@5IInxm+ogTH*zMviXW6g^?0P-JAM%W9*G|?Y7e|>#3=6X(j#Qtj zeRU$LxOZ(~5`bn4Kp0PbFP-HFD^G;ybD_H3Ew(f0lH<~3(t!92f~mm{lgYu`CX=mB zV|C23Pdf{^{4xU>Z$p}&?cM2`A1zofRiQBJ)lEWOhk6WY|9j^J7lE=)trnC$decIE zz*g`#TCJeMzp>}v0GtWwR3019Ej~_`bagCIy*S79Kn7KUT2*)cC9#$mm#t<@;vXBn zj=ZA@yE=|#JvB}CRa6V@$yj5Gozrzb=U>mXTeR)?Cad=PWMqJ!3Dk@H_-*}iTTWQw zLfduHD0dc=wBA2YTQg>qxBVG#RYI18-rEE`8KIqpd-Tes3le5 zQH3_{G>^h+zC}){IFB|9JW!yVPX#oxGa#F=A!qCSEyn zkI`*f1fD-QSb|HP$6vCmD0%{CMV#`c3?X)p$5lL>#IxmEYjC(>1QX|l%?WXn@^*A0KmfxT0 z(6wVRgb5pX6VliOo^935=(8$_0?E#usTvn8d8;Krs(GQ@a8c|XcL)v$VZP&=tk zE3A&%nIm+jEcfn`{0Mv_n_>%=q!#&zvYun@)mhzD@fygMuTp;sL)y_rc3GH-N8|2~ z$3|O8?f*30G0=kNfdhLpD@MJ@RdE6cD=dfEn@7<#wq6AEiPZvq|2YiIy(-FXq3SvCo3 zDg!c(?O{E;O0-cRo1(b$ru9Kv3!*bN7oP&Y3G!EgITCeG52_8%)0HpDtVLEMd7H6M z)C*0#FW$@`ot@G81bg`ckF$xHGU5B9DR0JK4j;xkf#>^P76^Epze@pSmIk_T=frI& z2JGMp;AUxbNKkkI*h|GW-Y%Do6t%OTHPYz6W97xU&!=-2rnqwQ9LP}y+Qx@kD0Vv# ztp+D9Q2I$6k@7kB%i-Dx*V=+6b{?=(Jyf`M#+OIRSKh@_Rnf-aH8~zwCdYCOPOP$r zMlZ+~Ax~2i00^`gt4FiCCPjAgPdkmShuyHxP->kY1WX!h2C(gjdCuPFn3uL`Zuv!HC=#nvT{HT^%*?EHsJOapBR}p|g zHYT}DY;e0$dic>*e@~I~)->o=jW_|nzfnm5$S=#~7I}gE$L6GiJxx%>k~Y_DT?vDX z>peu#lVJ9JmxHGfe4mhnI@|jPIvi76|nsTr2_5q?=v<*#H7B zE#llefTlW0M)J%d$hzHA`XLJgN+(k?Lh3M4x91}deDhO+AwO&fZ0CmD`>Hx`Aiw9! z8Gw?oFtZ4>pQ|y#l=_+oM26u68xnx9eN zr%;5T86unD^%juK!j6k6nV2-X{Yj^}neasN) z`J$uw$335m++xc~&2k5%@k09A4LOTONgut&)>5ks!JEqR$;U%fAeGSuN}>dyZOBX| zHkJ0QF~d35v>Po*4;Hr*YWx&ds2lo0zS`IyxXtpFg+(|vzksaVIPO1MVji})LhI2@ zBx&ZctP;{FeGfnJB0F-ULap|$HT!Zh%YO%2Zc6T9=2dy^oXsf|CG>tI!%sG;;@iFr-mBhj#1~E_ z7Ezw0E1c(VC5>8XGa6<=HDYi8X09ZrxxY-Dv(8-ZcaRfbrF(J5t0LF#fwau`HY;0@Q<6$W zKrF#*w_FcE9h=`m>cw*8FanY6i>10S&5G% zI|&-7Z$6I%*+~#i#v?Zn0c}OflVHelavDJ;(5grT$89I0ER$g@Id^IB zfQMVj?Ds27^?4o^(`vVhX5rUgyZ-@dSwie{1-zo&Zbq^Jt5W7h20#PnNL$-pSOHfB zc%-F;&eNr_7E}YlaYcDU%kFH#KxnH#%VoxLjhz9c2boiik9;Q^2hzrcNke&Q4}#T_ zbrJl1d(pv}lW22{!P}Kl9@@MqR$_}#?`tN>-l-_<{{1!uA3W`@S+vyrlU|XyxeD z&fFj-c33g}UPsu*r&M6%t!V0=Lm!6_)*5o+#YU$X&l8bBAuh_D!sHKPY_(E;Pj8l_ z87QEpkNIu%P}0X{o!xKU#a@;yQLzx-gD5W+AMIwQla2)^=I;(i& z@xmV`-_IHXUnV2ax+(kwjOuwL_>`Dzq!Slhd#gp!w!axpLA=uAc&la?Vh8RqIm$EF90 zj>w7-czTv0I3{wh`^tGUJuXn>FXOq1ka9m1lv8L{VN&7OC?FaoBDNd-yUt$Qd>R>fene)4o(=7Cw!q;`Pg+uuJb2)%%t%Bc-SoU1nde$OZ{ZIfP*$!g!Vli5 zA+csJML?I`_E)v;z>jY)WJvQh0KX3Lox6BrMCdFtg8~68YuxZ#oCN---{iu=`N9JJK0?~45u-dk6t?( zt?3S0iu!)X3yQtTYi7?|`30i*u}2B`yxnR|IuolNyEs&khcVWo=N0HZ96wzvB16cE zdwVea)Op@mXzY=)Cl^kWR^DjObvC=&HY(8v+}mwr(grc?A1MwM((jPq{Kn|KAyZrU z)PI=OkD+ZLKDb_f2y>xy-ej}@`&nFF_zRk$Um?VYpVUJ)@D1chShE-zZ!p7uMQr$P zKZh36w^q*$Qj!i6m$$FVqnMe3qm?U%LWGY7Xy1yH8OLrY+7Q4TSvOYik;ii%W>yz` ze@T(+?7%UihneH+zRGPQt23bHZ%W-g#8m#|kad@~k2!I+l$%}Jxk!ORS>C5g^<8#nNf<%e=PK!9a z<=7p*ovUYJ^paM$mMi$=vok~|jT3cey?WY5Nq5Z6v}JPts8}xH#bi!j<*j1QnGYU} zDDtqe#g0fZ-fLlq$a9aWPBZhR=X~zpentIYLRAgHkg>M4tPl10-jG8N#Fn(y9UAVyhbEIy z6%IFTvJQ)Q@m4wqIpj%INecbUii5wIdiN1VZ`j?8%G4(MdIPQ!BtMl)_- zhH>9F$zVhM%zl)4-$XE&^^n>G%UuqNc~4I9-lK<#pPo0UZ`C+gyv~}um~y5&oJ0m7 zY~M=QmoFbl_en0Ne04wUPAT;&9yXK^UWhbTYoRrayN&$uo}=++i6A7oi8B!QmF2{j zJJdUIkMJYO5fBLPwB$uvO`AL=2_i=NcS<+I2@3J+1_l|TiPI?cz#S#SCcB;SsCQ>- zy1?ol6+|TWVfWm3`PT&+GTiT_#m1a%fY(d;a~)HXVc@D#nzH*+q$)o4HUSMQS9H-r zoXSzMYKU0)$ko{SRT5^;mWbWA;7Y?v7E|vL+tU6iCN$q*)n{}aj0fQmgJ>^$!ab^9 zN56l3zfZTU*_?JT7ue{=9!JWYj)tx579qd9-Mmi0)KG0JCu;D#8`C&-Iwml2PGsm) zVkQGcW4pj^5BaZmV%S8+!SucCgwwU}HPc#B4!HH5Y=@?PUoEW$6MQzbcleHnVBH^% zAxG5Pc@gP9k=H_dCl}TR_ZR}wcXXD{VduZUA7p5dd<9xq22{u6sObjd>+RIOdb<^9CfHb3in5%H3xOEWXey5ACEg7@5o+RVc zRD1ekf~5VzPNBWN}})-usn&?n@(xue3_S$2xG*Kr)KwRK-K&R%JG*vbsA;2~MRyAH{ib zcWKqdhg8JJAsfFE_lDd?@~otDLNiv}Re=CS#rhCEO2+uNSXcaL=%3Ls@0!iQSeRif zlh)8e>nJPyB;F?Lz%?5F2W6l+Q^XnFFc@K>%>ZMzNHpVT`S7(wI1+DvuMd%~RJdc~ z-n&XuNcCqX&CNe6;yW(dbm9mAH)2v%!*?I-1N``XYR$AL(B9ZcO5t3Z6O^Nywkyw8 z37uz<)MnC$8kbKxhHNaL8;pdV8?JNy z6#9VlF$HM-uew0%U0=jnhbQjfnYO`_@PxGhTFx`>_Cdn=4Y~nQ#Elhxbvja4X2NvL z!R~X1aJfHAnamk{Y?M#bSq6GmWY(2yJMFf{tp|W_o??2ljNERtnreggBWRQe-*ssx z6q$Ts9J%hh;9}^u!s-lqcgfCCyMb_`N2dUW=sN5>Ai(9dpbKv*LW`q>Ec=1`-AxwZ z1;$}Q7CO9`@?%$1r0Fh}72p@>i2PX({BXeRc#ZDlfPY7mpfp|w(+Xs)ek*XGKxbK; zOql-ky+fW#0*}xmpYkUQ~8d*uH^o=ce{5JO~M^Oa#w{OhvANP=O9s{odZ~w zk7*sOPx>quZQrkkeXuz-K?g)fTA#smia$0YY@tvtFq^{x=<|Jnx687%1ok|5XeP@8 z#TFXQz%gXBtp0T7Z2IWWtd#&_2HUmcyDD{Q+J>$z=sqwV5F6Y25(?YLu;)u>^JE-J z%$$S=v!9kc;#u|n@j?`HHGp3llznXHP{VZ^zWY=hXOEQV%$V>C&p?-ue@p~{-p#w zVZIZwpcG+n0U{?nDwZ6YJB;KH+P0n?)S+Tk|11Sk__xucTn4su7!(o**D1$>myBt#DI{q=-dwcFk-cZNxyE> zIQZ${x4lqkA0Q@zB0%rnyl5S?@B|+PK(KqM9$}>?W_AOenR?k77zMIH8xmZ3aWpd% zhx_$A$>-RnkjnmvfPVRUHyvC#e~zZiG9cM|UPM-Lf=VWPOY^QW4fJ#KUjF>-NrBn` z(GkF8#de(D*Y#qaeb{hghEje)0Er|lvX`do22n1!!DQD&8 zMfMW7+x@*_@;nbC^C!1QQXR-tQ0 z-;frP70>{I7hI+9W#4=D#yJeg^JxpeDhQU02n!U+aFmn;v1E)C9pJklerkz54rmD? z(Y`|tu;*Vxfc?tWHH${<9`OaX_4p>Ncw-Sg@N|bN)7X?m;e8W?wfoO2PHs@*V`X~3p1l{kDBXA!>L6B)wuquno&0^xF5pN5~ozX(SBIB7_q zWFckNa*HR?Q%iiv`dCxtAT5)CU9}<&x`L+e@&+}DRSV$~Tpl-hbJEIYJl&laqm-T> zv#&+9{Pbl9Qq-GF!V8+AmwnR<_iM)*vD>>b#fXJWyyxWL+qRz@zS9@V74PuFp6f6a znw!M;^!dwS`Kl1Re~NP5gu)?gI5ZYWVys6RD^o%z29VYyn)CT4wu0>xLfeCEJmnYt zFL8ELMc!l+K9;i6-@G!B?<==PzF@S+A;fK_@%7O-%Sa%+)BADU(?hH?A~N~dQ|T;~ zC_=G2Y)eakZ&^7+%x_~c0x`EY#Cy<#F%LQ)!-R!nR>75_vZH=XCjB4f*d(FSz;IZ0 zj}ZePTMwX}l#T#1rnrSj5B!#xh}Ddjo|bwYpS;5J; zc5eWxNuEhtc*h$As{8ApfKpuv)N=;Jrr^Xq)4+#@;TQ9{O5|iF{k@1N2YOLaIPGBTw~mk1vK? z^W7H$KNHI*Dk?K^Si5!v=NumTChpDONuQ^pn>^(s(DK4$8+S28Hhvb4EoByB)S_P;A;<3hgMr zJkZQ>l0%CQ%!`mjz;K}={3KFes*HJlx6hXrYyFC&wt?7;w|Z~_^CzTnkRt*bJ@Hv)uwJI zdO#_x7U>V{Ok^u1{X!jyrrq24R*0R^>QnDMKX`bg@@caxhc8&Q>(J0p!ryb_bGNbO zwN}`F&*>}h1#X*6{-6xn5eo?(4OQTSB7$a%y1A_!jJ7lXJT zdM18%=yyL$Y4b)MRl1rWIzA0{`9tMR|70uZr?X$05kW;ox^sD409Ye)B+LXmXaw1b zMBT6(6HY9r#6&Eq0uijf2Oa@YgTjfr#D*Xle-JB!=L0QOY-VIvdt--KZC6bWatM5D!35IT8ftkmeD4L*F?4zeZvrD#<&+9^LA*+=Ke%AlB$~J% zl9^+F?`u9zX;HLpO{WAeAU({aszl8*U+4MQ7Wp>+9Jk67)$Z^5wcU+uO4S3ov%7*W zy{*n(%qMC(O!SRr_??p3Dyejj<4T5%#s5pQNjCNg(G(t|T4%FFEAjPr$i*JwnX zn=#hf0<^7$XFIp|;BcbP9^*aD`f9T0gmxoC)iw+6CC-@=HI~!DvL0cUGn3(JRE`%j zDXa=|zaLHWUAcDAP`5UVf8Av#^!B}=*CSg+|D9~;v_ZKtKw?=oU zLT49Zxv|+9oP2BH=&Diwe&lAVr=b--vKUg#@)B>1Qm^zIL0#~5Nr!#i3DX!gE<6IP zxIkpT{I=%_^l71O@LwCg>D1@$y&^p#yQ5Ioujn4Mlk$I+5lyGpcz=an*4S8Lf$xGF z{C6GoXZ9o$`ZNHf_Vi^gJ&-1VN2hrE&uRSca;u=0QMcpwRjGPk9tn$Xl8m$nj|I{~ zzKb>jSsFYlr@ggfeIoiLdaVdTT)0p^s0sNm3!Bm=_u2se4Qe+RYpmxn<5C#$55@V*+ zVogXVB_7XsS?R!Uyt-VOt`BDQc-xif3L>L>EGRKhYG=Dx+QM!@$piV$EuILIVF$@! zvm1c|A62_eJSrUwCccl)G@H8eQNHtDu;(FAn1%7-E8wZ-aIA%Trro6Vfe|*{($t`x zAojut5<9dw`*v)aD@nZERQS`WL)@hnY71ds#mXMRlbUw)eJ)(GkkwXaQsMuI&giwu z@>3bqr?BFq;k}iy06H&O28q^cho+w)`0vERdrILn0pB5WB72oGg4n*$jM_g@#rD+Gx3_IvE%-=H^nE2wg?XR{)H z=rGUx%-{KN7@W8^aZE%OKp-r=eG*`+><`fub@HJZJmnK{9%39hT9H^MiwYRsO@Hgh z6TWupR;1Ay!5kZ9Of;GnMp%B=%eq1^i1$#!s-HsnnDH8ssPvgq5I>4;S&L3#Lbyn- zZ8?m_e8L?wB+;b*wc^0BZGIIvT+R0qcnxQ9>W&NWgnEM)c=cjwmcxx{PK9bF{HQYC ziDNXXSP-60O1?@l8OK*P*F0pn@e>Yki~G*DW*P36eo<@{7duiQOfO(EnTu&~&fJk} zLpI9pb$_vrk#>`?1H)%@jQ$izV9-Zuv2`#AL0EhV^olfZTN!79=-K?j?S312SgiVNTUbLe+3@Mbj|k(KE6J??g@-0m1U&cek|i2|U8L z@%#yAYQ7NiiF_QZDf4{aBEYuXiqcboA}-!f#_hkQna+Dz6pD}&Ehdr|=B~dHT$v7J z0Bb(leVY*{m6(Gh-4F?sg9d>|t=#k*Fsz|A2o3E3RgRPeNSGZs?yJ9E48ilGx<&w7 zVwZIAcD5c**h;2&)lAbfIj{R9#^zmcWkDY;J-=Vm4^o6nDl{TBrHz+;Q=YHQmB78! zp~#T0wf5(*yyOl+_~y_Zjc$J=3a8YgUos^|#**=~}el?IjjX+?lJ&w{gKSg^`LBQ)BGC-vt1Sw?Xg zJp9tu*T{qAM6Kc_2MV%)E%^bwsI6>)M$VmC*W=AI94!EFmC}wMe%)X9(+@J+eE;;` zBR*|I+iRg3A2p1f;6!%T6+{_ByzJ+K-Kdp&sZjY`yZ;VO?;btqCOH)OrqK0n<+@e% zg8$CkYnLU+ujIkAns+A}?AHQ3?Oih2YG($jr7n_Dn-a~F^}u@m^0$hAL1v%!GtecV z4-%F1+8`yFf!w5(5=G|B^!^UL-L2g&LpomQ4dxd#9guyIg;xx zgT$Igj_EfxXps-SR-oWq9Ymq zCv+OWX%X~0h2c~mZx;|6CYBue&p)-k+gf8q&(7d!EV!7wH&1#zhIcLw z&iyb5(v8T?_6+5*Bep0|U+!kI=n9fV8pq$`e>Ip-2-T?FVl+-#LAnk!y0M8a_wv78 zTJzTE?BRo!oy1n%`^h%GC}mtZwxld|%V+nAh0Drdq)SUe&7Is-iltRoC&wlD)teqI zR`a>)!2^b2)-}B;+-qbN0`t<-s6lZ zCy4SGebj~}Fq>3+gc6Y|ih>jo@>%U}AxiF?&^B(O94$`|I(_iJAAcgVwh7|-`*XIN zq;l~=MZ1p4GU*n9iroVVwgdYehaYOKvC`}kt&M8o{%c3wUdQp>dWEkGX^!=Mv+Sl) zNG<@FURt&#M1lyhQ13Y71{Z0n_P<}kB1v`lkXa;M8&^e;f2HY)wQGBv&(1ob?ADr~ zdNb|C^mcnxwndanE0 zyHoT09EE?Oy{DG6zmLl7SFzV7;-Alx_a&~!$M=+ZzE-6#GT=!RY~|J~aEn(yEVmq2 zB(q2lB;uX+=`h(VdUnbc$0B;$s4`=oQe`(BE9A3A_rLC;WaQbupYuN;*GIvXWa^>~ zwN`^!UpLuPd4nt0{{iNT-{2c5FjlZKeKnYM`z&}_ZAj`L2(l6k1q#*;YC+3__v~^{ zEUKYj3ZL>_As-%mvik+#6DmzqPj~;j^ zE}U3n!X3?cWNy_-u{{=Rxe)|j8%d_3K{~Kt^|8cXzz1R`GS>p^#a-^2>}h%O=U%)T z7r9Dq4o@Q!Uv7sG>j_T<*NC(2b!q37?C=Jbxfab|+RexFK8IT0qA9k3|$8cu;96Q|F~>ZB8+30JxFZT0$D$M zI7#FG(H11OA$BYG4&p&^1=F;FLU-SOcZED8`x%)22b+UA8UDA_Of0VF+ZG~LeI4wt2g4>Qm64zbdn>ea5pFwN-}l{^j^C@Xee&aC z4vu6#k)&e~zqC{e?nqEWFO_e^mZ!C(28^%Vw3lE{oF9fGDcEXG^xMSj^IKHXKwY^j zX+X_x37rXm6Qj*q82zkIM;MZn;Jw?Pu3gz0l7Za-JSpX86l`P0oW#2D!99 zefV&wiW(V2xKZ0>_Ot=5v*TH7AE7GX(CNF=)>&u1#C9XQOV{_#7Hjp}m^+)#TIEU{ zJ+w}$A0Mr_(pOgxU4?qq7@U0j(VWwGA#UN~Rdux-Mi-x(mea*+BRy>_IryugQj^`x zBtVOHjk_vMi^~AMlr~tEgO0$QnZZ5pEWDRPb`QM{>$Gq^@_T|9KnWcQZlo7vFI>)1>Zx>u2Bz_(?g;1nw z*Did*8pcoir0ZJ;an^>Wvi8Qf3wgX$nBs3`wGVS_l)~*Jy)px{2qf7(>B7aT4W77T zHXm(^wKeteRanIH>YDCVcx|+3wMcbKHC&>PB5Q%ApSFjz+YIc(#QJTC=+5MS)(R{) za+{6%&cz+-Q^7k_1S$9F2)W}2K7K0famHcA#UcIT5Nc1kb6OmnnCYO@G}0uk0ALsD z_n?w53K%-xv|A*6O%$q2I@RH2v#_RXDM}d~}tDLC*09c5dat*nanHx!PUJuHJIf z7c9qZ1=W4~J+oh@rH!uDI@^V2&9LVKT?KGGUv*V_(lXqyJxK{BpZ$cBDl2%~ zl|@?j!gcxd-x!6Lf69wsRkWx)4SpS#FsVo;FT@ zE6&q+01eR1151QYRUsLNENtOzpGAVJ(pVxX+C5hU?$ZjZcHTLh$xg9uKaI2k;F)Q-M(DC`haZ_?hA(WBiG%w^E71iIS#fSCF#56aI2so69eq>{GZz=WNT^v6XCx;?Di*Q zoTbHU5|kqstktGK#D%53#;S}=TszyR8n4-pnG1 z7kk(VdY|a=DfyBN_*(e5?N5XwzkK%(bOrQU$4{!Y1V5 zL<8Q5_=m4RbURDb0<4caP{D3sAzmpqNkh{M2uzSZ5r!NLK|J#x5bB3;W%PA(zwcGQU zykgmV+o|d5-+VTjG&MJ4wrjKT`2t;N#>*bLl^I`|T~dFNL{wAGrY@f>|L`|#1(ycv z^YRW{j&pq2{mbi56~{ydI4bSzfEw`m4xf_c2jZVt)wqI(mR!u{)gzc&ffNWq=!zFs z^~(Kh|C^+U;opSRzQ!|xA4!zwLw|e}hWDOc!y!~Q;*pf`t2nvOa53mnNA+<=_j$q7 z>x3#ZnxFZ8x6r01xF})5?sL$?!*|KzQFCtoU^FzOm$h%Sr0TzS3FkyCT!=#>%_ zrB4CuZY(#=7;dOvxD!*SCtUjDA8fVI9z8hT^)d0Ewm;iaXA3c*a(iEkU^R%mh?kUKDqdt5T;IJ&oS|Zdc ziPG<49QGmUi=@HwPf~dOm?xad?Q=HsDe0g^Z_`Da)4>r*-|ORRAEDJ;vp?*K_8SPK z#xyD5L>11i0qgIdd61G4>UT|E4X$a8)Jh*~%!%}gnk|S22B$)nT9|v^T*{;_MOuSAh>J?->x8p2>6tet0%RW%v! zABLz8dDW)OIymc=CBW}ExnJ3D!Mo0^<;q)l;g~$=)Ga3GLL4v~r^?WVW*nyXNJAMs zjq1f+Qf?3~$kymOGHeCE7TZ$Q;o;r&US_Ng_oQE5nv;fXVXpSC^1HA}>c_k;g1UP? z?r`DwQs-G|kuB+*@{C?zMy9Xp`Hqxex_kf0?wiY#U#9^O94hwT;e@ev3Rpy<5n&}`5T{PhP-8R1WyENI-e!jFll4j=R z%k>VZHb;)W+6z5D#+6ls!tJN(sJG7ln(cBj6NG?cfBVf!x*}~atPXb zLmKV|w@49xMbj?;dl)R$IL!_TyK0uL3#GevW9Qq8P=0Lag8Ez!d|izAMD(J)pD*a{xJGn<`eTtjRfh+1|>c@Rfg)@vmk^Y@nt7nF4Y+D3X9K9Wn+E^k?SbemFcLq!*&DJBHe^*%aK$JgSJFxSu ze^(c`lX%+;dU}x;=Y{s&e8a{B+Yg^#-K5T#caF7AL4)o^4HD-2*i`q*QNd9ICkcd`qff~f;UZM_s*v3m#Gsi zi=i#?gmeqfVLGSM$SRtt$~eOC2|!PCT|nIOd5bs`{xKD{b?A0aj9$5!HkJLb%e#}H ztV=v75kwU%z9Zx*k;qAmGdFe&rV9yYXj`l2&N*gA4{^czS8%!oot}Q3P=!9R?VX8W z@UJ&v+{5hIEEV6wlGC`X2qAnI-cEh&p};9}w_SAYiD&B#GDFb5p=Wp`7_3h*4M6MwS9C#93+VSnfbGnxr-ir(eqL^ z+ox?5(HoSLl#g!u90f-XxGn@#Dl^pBOf2B(k@4ZW43Fl0zSw~xF3(8{wJwd38zOKb zIchgPl6uJPX7=N|PZXJ#eG;2O0^0KJ79@6Y-l5!|cZXTeG=_N;`y-V?-9Y1^*?aN_ zpadf1Du}%{sPrNh7Fw_+ebM65sLa11u_WLbrYL>TAsR`GCFduCpHB<-?el0T6bETX zII>Nz^~6J60$UqRT=73A`MV2kW5Y#UA^6C|=E#~877 z*!l`dg&!=|8*Hx&IqRNVT9C+?8eu*AlxDnnTw_CXkOXEtJY0>b$pbs}KRbzEiO7BF zTIn{(qY zY?^Vh)^Iyg4#tP8FfM7F{v9GAX$rCG#5X-!pIJ8)`Pg!yoF*sR4hXPghZ-{#prdUq zeJx%*J%W*GFhr~wHiJxLGuwq_x{#90K_ui2(3Ec`rN05Pzk=Q>XhYCQHJ?5r=~b%x z`X0@>VG5`jZ}t>OdZ4506tDdF_YtUuzHgnmo?vr8gsc6#P3X3C_qsrRu;hY*(3w(A z^rYP#jGqgh7wO{2q(EG{`8_cUXm=!g?kNo~1uW-vhJn`8%7T7JJuUFpbD`F`8XT+_ z)1;kUJx?B9DU!ChK))Ni>JkNMoG$u1t&n}xnQ6X}Zt0}?h={kSa?`Wc=FiBK`~Q30 zjP6WKTt}5GH5H786`1rwG}Mex8kObl>;WAI`tYzXkgdoKE3>6qQ6dHGtQxpWeznpa zskBS4*tTlxoFav5d)gkw&AlP|E@*;!~gux8Tx-Z5Wz?P)lL4tm-lb{<^Mjt|G%s~20PmO zC3dzmKu?cQC~^)$kwp+tkSsX}MW&D_Ifnuy z=M3N4KJPi_J!gE~{il2M7(M#m6N;kPwf0_X&UxS0%?xLUo~M6b7-$Z1YoXur_l44B zAP@z*jsL!oS>s=a7w8>fQC$Bo|2kD;ezQSL6HPx*X1~)5R~C<0P7k1eYQ^^Vqa)RE zz^6^I0lL&AuiW=l+a34&lc4zr_)`Wi0mQcP?sC7ez!v#48q11w8bNb)7ruY~Zxc26 z^Z$fyZ`+nHg1l+A+0zd|7oIId`u8G8<}m?f;In(T-d8qUqZu{^GNry;ppX9hz9is% zvkz4iBsruc91mv#vR~i+*AHF&`$OdKM*zWW_uD`JG4KbFTMr(3?OuK7L1ZCuplz>qqfZ7FAY`{2YpYQ>2cJo zn*aJ5p~dnz=gT!bXod(L;liIu>`IKg9YD;UHGr6T3drzI02lT8QbvTfMP1gh=vMMp z&EM-2c&vO&4?^waeyJMDlz$;e)(rtSz|#N7607^@Spl1aOMA_r1}q$&%Zq={{NRjs;B>l zF36qxSV*sbLM!g!<`Q*seo(&wkq35HT^e2}i!MA9JDT5J74X?v1%bux7eKWhvmvkm z#mD~EO<(@xOZ2orn(#({KL&uyN0t~AeEFqWbA`>E zc^ZIhmQMjSuq}&hck^jp z9c2a#?{ro`^9;EoUikwluK=PzKzF9mZymrHK6J)$l}u@v7x@7ZYWJ!uaGi}ES5XR@ zqbAI(YPO#6S~d7wT~>OJY|^X&6T$ylt*^sC-X6Cju*>GV0%`a-FqXzSnThCl9DMgLA;5nD!^4`}4Nk5@6NM7D1>dsrg47Z?A`tnPPmtJtpR8ZLGZe{?K%T z?*tG~8&B1uXn5Xvxq^&{31H0;FSlKIs?ox}@Hn&vL{_W=4!^^TEJYiTbl_M}e_oY> z26nsXGZ**)pb1pq5Iy{f`zB4y-JHs24xl6jikgbP%|RJ8!a(i5jqO6g(GcZr0)%WiJ5HTc0h(QeSDQomq z3+RL$6g`xaANB$Xw1zV{(?hAH;}D=>=a)0Q^@lrH4{N97TyJAnGf0w!4n|uUJd=ge z?B-m+ii&Yy_!1Al@T1V?>0QNZ9`F02@STXX*j|FXJ0S=1z<^5}`&XY>`Mzl!eDc?S z(=v)Y52~jsq10CD6E8Ulm2s!Juyp`GFNuj>u;+u79s z-#_t6!(zdofJ(1(f5K5`C|xSRK#O|sZ;FR-m}mG=2E$p~1o%72e>s88X6)Q_-0qq9 z#ZmVJ03W<>od9^tym1O`r*!AWN)U?oEl~3%Ycc&K1O8Y)i&;NvNi$PeHP2W zwJ2aq?8|J{1bM5g>Jaf0Lf+&huQC7_hGi?@X`CA^)`Pum^bt@kH_`xPi}1lr0K@SF z7RZnq09!_#2NPoth$%nkg=Xzbx&-YM;y8<@H0PiY3~tOegpdRp-J;*{g~xyzKpG0+ zAlD*X@`EMy)gj)JTKx%AV_&t%LbBMehLC()A(uID}-JOHK`@{oA)2XNQiJqmk= zrojR92;5&FB6d}1@-dQPQi>a!C}3vPxk+hJ+|Jf+bGH+aNRwBESNSOX-!LA&C9o00}o=PAt&GB3r?<7}!bzA}I06cszj43h;6)^txPc;Df^XhiQKc zu1R8XF)x|Yc_K>($pEmAmriMN|6v31baY1YbS@I&Ad^~yg4hHOip-S{02If1g^;8S zW_{Sq?J+|wWSPvFVVT477&B8TIv2{9S4V1ZFY`Yx!AkUPJ0zw^nR?w6SfH-sf5oj~ zgVe(l7bl(<-9Jov8@rMb{a7;pfOnr1J)m$54B557O38GORIu%#S{Ffb&_`Er{@96j zP-DkRre8e;NX=?8xa>9|@nT6QHh&PPR4P9*>VYovEIN(NmAP$rNGiJU$# z2cP{|-97_We<>`TzRBxC9?u@m!^jlT)jX%$fZi=@&8$m1S<^cxUEE(cTCiAk4{ zn8I5((#}?m$v?|eEm1fEY7PLRFHHqd9B!hCg?g3UFX@FpIs?!j%Z2^3J1ah%seG#P z|F+$N4e}khkKqNcVY8PDuH(srRQJWdap6v>*KMS91P0Oii)cD;1J*z;5Y@?4xAYoY zxe%u@F3+A~FtxlPGbPXsVVFeVvYrTrx**giZ)MM1Aa_Ix&T=7NeSiDrZszp{-|RdN zuxRZz(_9_WyNC7fATbJMn(7&PUt9 znrTN^i2=oW%#n%2&S}4b+p>1=)s8yT{8G94$JRdp?bI3f4SC4!AI%?imObsTM7Dhr6obGs^u<`zQ zT%k1g<4y7junRaSiZ~gl?rJ~i=&ajnn^vj<2EOstkrE3kJef8R%B*5pn4dO1Zq@;> z7C2+I^VT4d&u{kO!4MtIKc`_Ge_CYp@8bHyH%Xoa$!;OZo)wDevW7~OI!X9Ch9A$< zwxgC?zetJr2fcvF+<^yf0FDW~1JsZ3pu zcUwlzZ&EX#s`J}ZFQ2=HbmE&24_Vn1S@R_B+KPIe1V74NCv8iQkE;4JR&KR@;(eW7 zPUM@JLR@zOkZeKK3*`2#nr}`fVGj65T>T&a@qcex{!b0||1B?L_HQWoN+Avxq@Bx$ z6a1_~4xEAGk)w-)1hh%ebP`c!y-TtvlmA|{&%>sv&P}lXOWl_4(FeH#jw}C|1^(^W zOzMl$pI$D~ZyjwK1_{+`Rud1ZSM}y61_LlxwDq!f{j(73e}uN630LVU1So->~o ze|}m5Sn@(ca7whCEN%{=7`rq^pxE_pAr*L7Q3nwXB?ynZSdi~(u>vtLp?jTekdl!O z_&DbP@co_R`O#uEFe@4efO8oHJ-&~>bF`-W*rDU8v-%`}w;8;l29t;A?7vSP5Nn3s zH7~mHk5U|}1pjH_X*PlJw^!gXa6*|+Wh*6Np|jA=u&O8IlC1`aAq%Qm6A*uB3q4&S zwz$%grd^jnSzcZqh7PjWf_lcW|_`IJOOV zT>X$;cpZxEIsy0HGUU!C%kjI*hP_5iZ+_6*7RAyZg6y}86Zmg6fs7&?4pGpnpyb0k z9dLiG1An4ITvw7%ci9Pe)@uP)_5|dZb^3XHu(1LD34Y=M9#)m$u=HSr=<){)ytP6m zgggP2VU^0xg@qi)LWUi;PHNqbY{~q-zx`1>rHeAWi+%V&GG_10LHwv)SrK(bZym6f zOE#>51F#Ypk42B@o`Y_+N@WDF2K(+Z&wypv1xjP5D(7e5fDo&F>*{GdDQ{Oub|e%^ z?|h~ggxhxIoKNJmd@JoX&iz+;*2JQ_k=66j3afXhyGuRcuV{wDVZoz61@x;WUz8Yi z_2mu)LJ5z+9(PZ)ni14cZNgaao7VthHBy_)&YzG53x(6CYTfcI0A}M~`C3{#fCabk z8^4v2x^+yGN&3zTTDySorX4Bpxj{s^8hvZ%7;?8U=fo89m;(oWA)qD41!Y2sl;BSB zEWu^c9-e7usVOE2tOQ4Sk)srHJN{D1e2@T|^a+KMq6KF7@9ly=_p)doBet;4sV;x+ z9pvhqar|>Vc);}l#npdZ50MSce(*FFuWd`6fuyM-gDW^92ekDZ%15ANSrZ(7hog{u zYZl#tcdz>?CJZ2;v>luw>K~x_cV9Cb&>>L+i!J3hDfjxJC)?AEvcDB0fC(#i=ikiF zEf^D-Nuw?o3OpB~ALi=&-FH# zwEf@<3yv6&2^$wZf;boWb3D%51}kH42~rIQ@8Qn;*0ee>nas^xf66TaH zxujnU_M&{j`Z}-L?_m^HN{=yT3*4UVNv$RFG)$s8fzR3TT~qErOF|CQo5OV5v)W;8 zRmdH~lamU%agKl#R|WZi=|x?JHPnc$EWa8{K8JN@iYEt$sj|_~<1>S~ z(lnRYN`UrtB+d?uG>J#o$9?ev9U#@$`cYcpr(K$u;EScO=_A5;(kt45i6Cr#t^VT7 zil)lXK1kXL6yMPcrxee-YnDbp>8`nh?OMACH}iTOc_H}g-Y%x-6cm@XP+uTr46&FT zgJfZ*RCfSd!&osmX_R#oBF={bQ$LyS+V9JMgL$HpniK@{MF~ANWENsBbQ^n)h-E(5 zc9C|`hUh;R><}~ll`PUtD}}bE4R7_lJ0^O(lp*gdSz{bd@ov@EB_mD1eh(Ddy~mGU z%e=*GiDNoNfn92+ejUwTq=f7yLo^=QDxYk&0a)CHDn)aR8?Z!e()y(zA$4rIRfuX{ zq#qoB^}z4i%DdVEuowxPb7C!M8M>Z5uaoOJ#M1mjz9-<1ijqlK^gcmu_eM;NSymBS zr>U^JDZ64}A0fy5cTT5AM{DWk2BlddoQoB#toNnC5K(%b@x$4VCL&`lPQRRufdTCy z3RWz{KP=kRB{NR3kE61uCQU7e%Zfqu%57rT3Zm zeeK6vp7IEBKvVe*_OgK-hbuDm@@%V@ zFI>lEEyl`zT$nW}Fx?fhSI{xr_kP##;*XR{yNTv);N>4?s=R%`xTzPhBU_;-dpMOP zb`N5D7|-I?pfYG#C$}4akTf@G&b5Ro<>9=EB0bQwVl=0KHy3Tqs&8#!9;Z{5EpzJ#r6Z4}?4pSaC-CCZR zuLJ>)E=`*73Z}I|ZrAtkX)6jUiE2i&buUsj+*+xtFc}*(gt9Hl^ObYX*<12B1wDl{ zlTxpjJav`OoMs%@LuGkx;*-|jte8I6B~Z%rs_$tlG~K>}vY-r!xd<-Qp;cip2b(EV zDG5SXhxdGr!hO=JAK25x7fg2}Ll~4o4J3*m z@IE~V25pfdof;1>r$(uzR%Sy*DS@u5x~ORmqH(YDsBo5@A@0)+i=DN1UR3DTcAJ6wWO5N${$c~KNV2P_hAO<(os6IjuMoUgU{++eWrs5t~d z$^dqyFIg=OLIW4z_=q|nDBvel#&)HOjtw>_lt6SD$IAr|C9f1bPCRDD*4(AxHIU=A z(h5Q#FB9tFl7H@SWle}UlnBeH4%Vy5TbO)B8xXnCIPy)tGRzbE^5)Q3IP zHSo+u_34?dI3KYUr5-Vf9Y()`T9S}-p&9%|OEGI`3eq>{BY5mJ&mYsB^vLAjNflv4 z+rh0^^&Vgb6UglV@+E-c%lRk;nH{X;19S1_)k}Mn;lv@?G5G}0MLE4tqRirw{`%sD ztCkKJ?bru{HZTNhN~FFnNxB^2d-(H(k_nB^FXNo%6SO@uB9d4jBSH;mWA&m8e-M8C z%+%$8{NN1Q9!!O(*DoDLssO-^EKIM4+lx_`1{jHcP(HeYwEn3;K%pDd5>@=m!Q-tq~Ya=J$XLq6_bB9c0xj1P%~ zZybGUXxZS2$=xsukW1$#a&HgblX~h);k&7Ptlf+Ha=EJxVs;Acn2g(<_T)+N`((X!tKG%Hel4bb3xtw4w7&B|EnN z;KkhdDe4;tP);PH4$i?n*4iFpm-zY}HP`H2KvBhI%~f$Orc1qf6MgWK;8V@&;0Hkkaldpm{%t(NolcYa zlcrn0y%&A=M#2ZMtU9xS8*<(xQ9nJlc~c5)30t+&%Z4Nm&HljY0-b`dj{cn!nJ7N*LUq^E6xwa zLL-iuSYwNsLko)$^_H(3inoX?Xcy(-Nye|cV zm(ya++1~8v;XEriIHaonq9SHmq%;bhH^ebqK->U2-t=)$imcJU6TVsO1di8z-T12f zPA*b%w^};Mn4Tt#4zC=0{WAfLIE|{(9PU?yb{I>NTr-jk#62#DA{n#PLLh2DoI?`nB9K6wZJBQeVU$a5%yY z)>x6H!}brZ?D1bm2cCa)%C*o{x{8-=yx~;dy!I6RAB;dZb@*+zqBb?Ejb4 zhyNPB{GY-h{y+Y*2d40YZ1J=9Gcd1L?uMXnvBL9_Qhg;E`XHTY9a1}V=f^>uyX*8$ zj7Mh>KED>kY&B4?_=9<0PYNKbFOLZ5fm!)F7|JPj3wCsNS^(f@On=B=Fx0FTu$mMR zb^ZQna_D!h`q-lROzf6rpR83iU~DOH-@N*7{>-;}>l&O`XnGhfvfZ}3`hI!1DB}c> z^H8VZsu-rhze8Gc{jJ$%2k|g!0ghUe?@nM0G_g5@?k^b%K4!z#c+m`OOPpkcEO%Q1 zrsBUzyEF-bWY8N&3mnu}525s}LZjxZX^(#Y4Rp(s3Lt8CtI+^cOFJF6Ek7=hEvi%a z(GJ4o0b09)2b9MJ;ntKq4wm~{%dU#ZDT{0&*A{za83YPq7C}ADPpp~oB+T3yXf@2w zL#g=2Ax3^V7+NLd_#*5;rc$bN%b?j{UV=v9JBeZjV}-o`1SxFMYdJBbEKe%H zv@_2k!cPyHRyaV|ow&;cfW)EMrsH926e2Uu`gRD zphF3n?V_PEFc`PGJ1&2TuWAXSsRo4*2KN>LX!TftksuW1_5rH9g2E%Al!Epu{%ula zuwQEypMo{}HK+m1IIBR3IyeYw>DGyR*~znDO7gngp#7$X6`D}!LjZ$EMKu@;O#rmg z8q|9j`uc*M>>jNnH0hW@-W6W@xCs<37 z9O*;oCd&}6GC5qz*2Bqzy2bO2i}UV3r$7@^W?P_H*%y}v=0TR=JGBQ%g&*QIZG(Ov zyw-6y^!Wp+51>kLHSr76ZtMwOZ}2B9HHeHGbf6od7}K(DxVqd$AiVM)_nVKCLJFR?ubqo1-Bq}l4K(N0l6hgnwIJgFcb4}z@Vq5;nAyQK&%^i^8Bz6=weSW&r zy$1B&e)bLnsvD1;DQF>iu%<>0@+Jr|2e`@dylJ34hp#?7-))nf3rvd$yJ5*J`w#qQgOS z9+{zz=h+V~DcYkAYp}ShLb&UO>j2nugF#zV`ieGu|23yb0bpQZ`p}Lw-d;Iq7OKI^ zdPKz9)J@})t{W+*>!Uw%ohKzpj0eV0aD7D#2(OYH*}~3zMdMTU)w(+F6iQe$jYFyh zm;Kd*aw6?MN$}1bS8j2$r#68}0PCALayzk_+s{Pz2AVSPJ&!tdZeEs0;F%IiC^Fkh z!CTz}dhQU!oEQhtIq=N9evRxNfe>%NeXLo}=J@hP)RSC%GB#)Id%@p>eB~y`tVw-9 zwqI)9QQXN@UL!_30RB{>}^a5HK)7p2{mAk%8rPVO!(hE3?0XlfTVlxd^9>1i*J>7h3WQ0FeB5 z)O}byAwZ-^$ToXY-w}_O@u+6H#nE*_Ln?CME|gPo<8&IdH*NNEfHT>Tg2{Z^Qr9k z@B@pr(|b6xyas9kae(*$1PkBvmpYY46rlX-&m8ad3s!LM0B+(#?`&UOdiur_SP+W= zF-#W(Nc*y1>!wU4rJivz774^XeoIKjoB2d9{F(?;FpQ+EdCn&uKWagWl=OBWXvi4V zLsF}=e1PYdKF4{^uLrcdWbm^tz>njqYMeba#Vxt;MIo zX)4}-rE5#Hj+-G5WHWv73aGR8YvcsD#c_slV>8}W>6dDI$unH(GhzTNk?V}rJ1Wtb z0*y(M$%i?HQurE3Z~@u$EI%v`=9}-5oP=*~>zOTV8(ISIQ8Z5r0)4`sD!jkY+%rq{ zfE+%KGVwCt@9`1V?ee71H)`lVVELVjsluWLqN{9b2 zpK&9zoADsc<~u%k<}pORFX}k|^TyU#&g=#Efetg!RNczR+OMip0e8ENmlJbP3pgTR z*TI=j;f5sYQ+KFb^o?juM$XNLGcr3&kp{Y%Q{;qhalLo5bt6c=2BBEy?ga6;RWOD* ziiieYA^v>xGO~@yjZB%QbyqS2q*gvO&^k6^Qjrt$c^yz}TjxY|=Ip-MH&Ts-g>h`P zNB4Y9pNa-NAl};a&B6ul0$biqxDaqnwY!N}_t(Fzy?C$0gtQyZ4I6sT0CuFO0g0n4 z$C8l5Ag{+OdxO>o*Gd+ph9jr94aF_TK`mtGv+2#)ND{QwO0CJ13Qk3kjZB zCzCa&G~tP?If+N0$#y$JZdn49DJk5pBpcaQibCq0a)8t7bs2TQLV>O%0gRoMcCY^tkg} zMa&K24X9=UR>d`+=tv_S($jCk%oa}NOmGP3yd6W`ZA7NHdBYgAy|#I4&yQEyi^23s zYzy_=IK7pW`yTTMTHr>>8|FuqI>W}Oqga=N*+I0+E?u74`;+7&5BugA?Z8OTIs0=v zeU1t98xTnp@UyYR%9jH(oB8Y}-D<1>!nBwpxp*8m?qK+P4vEP!PbX;n?fOY+x@;2d zdzKy60`fh}l*?pO(se6f&bH^mUW%YKHR^e}v4=_*LXFpqiI4h@e_Rfdhah!+TybGkdU}zOPd_PB zuP`OIoNj!niEIY66mEu#b3R;bC2JFEa}+UQn4$MclBdS+!CZ9&k6pIe#A;b zVlX0lp~pDV=HN!yTzMJPV;rTt9v#p44z=0j_lB~4_TgU1`rr_ua#BE@gOhx=$7KI; z$;;=K%#m|9nP~vQMUKqJ6oA`!#QpTb4QcfUr@3FP_?DHLJIIW)53AJp^hE}JHBga$_b=jWnoG(fY8G&7#Y^9)Gp z;|yN?2ga`wcq(RR1Gm!rl~kc;Iy0jO9x$-~0jk4I6{q2T@O&wT!i5idQ~v*>?!)~n zrprJYpfOh`4@rc#8URsvtbEYGpP==5u0oq-`zFB~sj^NU{Dmr?x#%y&Rr)bZ{JA|c z>*!lO@~ELfG*HCfb(5!z4$U|q5cqIC9n3PmP<+33HUnxQigKVS7(l|0$>n2TQ+j>3@*`4orUe1Lr1&Yd)8xbgWdvn+wJ1=A^Xnq=NNe8 z4v>LIPZ2aKR-{~4#a>5Y$+){9zOV0d=^f0;0b_Xec0{ML$ zf=}*~&Wn{&M2MzA*;9BSzu`NTKS1kH6~!XUw!#O9Y7%@GMXmG-P0S?EoFO#^Q~>YG zP?6XX^mIKQB=8E$zC&=<1Ohh<-faR0$4jc`f#p&9wgfey07+eg)N;A2f3RMeWSYKg4O}MHdPJLf7{nHGI;>g@@Zrkz?lx1&%XGRX#7 za>hFDI)?N7pKv|KlhFF!(}U+kcC@W{Y$(P-i9IKiQPafc-L)jePua`c=8$IwCMC8&7Br~jpSP${jL$*Xne?bGB}v@;^rhT*0=(9f203$ zcMHlv&A0AiHAdZ2TL?|e6J}qEd{2#LD16W|q<_v(e_o7w_Eeg=SpYs?>2mujXmphlkB+?RQ$8be`nZ7hP%bT0cS=V8}MyFDz*7QcJ>h zJdf_AmPCXOy~bRuL>?f>Xoz@30-j5_&+It_I|?{MPrRYb^S2)A&?D8Lwto*S2wSyxT81Z-C5k@}2DiY4u4URoC-8oWyH7 z{mxa|BdIELI#hptdrYq4>X`cZ*o;+d_sm8*E%vb5PzU_}++EPvxV=-JS-Y4pn%xnC zzYPmJJBU+VB@j&E3OMw16>&cVtwb%M$KJ*26 z_*}X?yNj;0WILjc+U4pLa~(4i*H472M`Ql6*?9lm1s&vSlG_hMT*Z>252(%=DAX~-WH0 zvFicC|8$~|R`jD@PljWbNBtRL?T0PT*^QvNo`=8ESi>;iYP4VLW)j$emYn=)#r2oe z-;7RG*fLeqSx9;%aCf$Rg)-(~VgV=d)EfzA-xKcqe$Ysj^DYeZx@7!_Pp!MVi15r5 zxPGX?zpL7HapECIfSW~|f7zgR!M;ctDYu_XI#zKw8$wa=RWMBKc*%mu?!_~NVQ#AS+CC9IiQ`)R_6;kW$v$Mk#ymP zPXgHlG+RwM5Z|XI;a2**rqA{C+~h;NPYgUOC(rAYoq3F^Xbi`Y`0kKr0e1S z?v`By|FiQHA-krbQUGq@XK)^=*&J&rtm z-HA;*9N(dPuGVM8KS036@Izk+Z6=l|^d}vhWivEab@&F%`Lb`^zb59ncZ?r$V_vr2 zk3;hMN9k|xY4yLoL||&|rU+Gk=<)2NA5~1TkPbX#!+j9Pf>C|RI$rpokPBD)n-{_7 zXKi16-fJ*P$?yxmh672i8c^5&hNrZMa5krNRt=i`@20H4-viy7>GsBp1LHeupFB_33Fz%ju`tf$?LZG4m3W{MRk#WdfLmvrd?;T0xG{_uBnY zQtO9KO8T5L|FKsI>at}};61}49gei-YxxXjD72!F(SHOF--66_%p zahWfNfxEkuT+etLX-~ADwB5lJ5qL_4t+b!05ZS3Q*+4%rx_VAU?9X*0r6A z*qi>$dvIjNO@v24sI;APTBM|Q87~o;oIXRJ4|{Y`;CyFTP;3L89gv)>Mr?-^GB_7e0bI41ub^x&FtJFs=F$PJl*i8_m)8C$DOw+gRyaaSb;FJ9kYTi;hck*ipIKr=vM9SwU^*jUM%nbq5_pr9LG|0V96T{=S-(LLY*-D-;C zxlg9=UHr5nyd0So#I56C>jIvCv)4s#XQulhB!8L->Cj&A>a-N+Mf9}n+B%*i{b9`A zVrn%*)Q_&u)CsM3xt?Ja^bi~tHL?p~jIwQ?Z(Q>sd-=6|qfW5ax%D?Z%(cJc07FVL zV&u|pPDmGO&3Ty2bbuu^HNsmbWbNr~+F9sS4th@u3-3<$FmX9aUCEF)9XEbreY{p5 z_Tj0NK$I&bo<>@|SSH!`xJFvtn5=kQovfYH7>cyJjkFDiKaw7VueIqC=+rA)i!7B} zh;h}rpk;cS$Y^upxkV9iYn}^KTeW&UR+q!(njDJi-8Q!Bbe}zEf4#6*b%VtMmBB(3 zm#&BF@_ydFlI2zwSH-kXuN2eE>Z|1HjO#3OvQGM_3^YlifFQ+Ehc3~FOO2;UJPwWz zsnPK?;QMe?^l0m^W*h5yi(*+lJ?i!hf2Opw$TzMwLqc#IBVUDRjk<=+AdQgp0qy$oOjM4<6a>D2##%OVe}0FIR>%+4)YpdTFDb zkIWN`Y?E!T-(3}M{pg;(bNkU$`n@|Hy5Sw{o_yoJa`w((s2DPrv=NcnPbUdi;u(3h zPP|}m2UdOs*V%+1b=;1k#p{J;Z;qQU5$n$Hm4!~#7IKzUt{$)VGx`1|+jf$^&SteA z;o55J$GM(Ro$IL9nnNP+%G;zxZd2E#vT~udTb%kJiBxVh7#lJ^*HY%bGZQ&!jTc%Y z`!jQ>&DNN0x2?U_%*|nvBK-Qts&NcF?r3eV=bIgF(E&rX@FUCgH+O4Qjnrlii7L6_ zj=Wa}yWB(EJSrXK#8&1O>BC%CA7)VVua#R789p0i8>KVv9nbt`jIb3!O%-eQ?Lzve$w9_N`I}h zR`sSejAOjMDZ)$=N4zl&WSX1ow=VY5uq}o94uxq=_!@;Rd?VNQ+d`*xkZKLY2kxw#*~aDfyk^CpqbW@W^MlG2Ol zANi$6#|DryF3nq>@-<$jD^Ur{pklbp{Ti|SDlPo&@byH3n+|r_>>t(}s)nygS~$1C z{Dl}{MsDJHz8jwrA4nu)q^{5%+>Tph85cW0j7*)R-a0ER$V>V|(VD5rW#EZ-NHzBB zpsk2$H(uDow8>>S3-V#t37yx$-rU^~)=imIyw4YopOaD?o_5|&c`qko(gN@0vqtwbWX7wI~Tt3Wnn17OwUH;pX ziToiJdsNJTL#pxbZ)45rh>c0l7i#ZEeO)m*>H^`lS^McXo|5&Z+nck z-}vXX649Bzax90;(8-z8&ab{#Y0qazRpWAN( zH>h+$==bziMHjlWjJGG%kc1)R!MU*Sj7{oS!?oInZfECX%OB0U&D=DiSzqQr?<)8_ z08#a!doHJUO;o=)OpbCR@5h5Vs?N}@>Fo*|?)p>P(2&;0Jp_u+C=Nb2rY#yWTC^x8 znS2h?6RC`=+GXg4KcJSnL_l~VM{({c4ZPxdg*H4QIQkO{mS8V+3a1|rG)VU&4~8$i zZKN~|Wx2+oO2FX`oFz?W-|Ue63f#5)+IHsW`{ngAj7*^))fR$kR$` z56v;Drz|PHp`1A-TVm!mLW{OkUZNl;eIKY-`~Ur;XdNBY&+hIn|MXa+HV0RQuzFv+ zKzLM+2Ak8N1YEGDz&IQFXDGLzj@tM29MGYJl7Iszaq~}1UOdBIxA=wIC=guqLk13_76N7gCC9I5K9UueR^BXkmT--hwld_#qCf?=Gxu>&~xww`wBdIGcRD&>b` zU_?>|dD)y<@Vf#lx{s}|?L8oN3O_$PY2{Umd)Q*g+4|@J*d^F-QurPtd_(ydANF7D z6?h6D{MEiuHn{?aR`ApJ2n;-|p%h9AQxErU?99=8Zg0`#wFtyGR$GY;qdKqsNu)$QOkg>?Gx9M29{?;3InNH}IU7Qv+c!C=Gm3_!Z$qmUaAoLGw?@|A-;dbi8Fsgf?zpIU z_j8ALQvc^k871_P7UHA`0H>HJs8-%ZQ`BDwN3qJIrwTO-gr8^Q*)15w@mnRo|MvB> zt*ptXsuCbr$cD`LTWAk(#pFXci{&s1U(9-CD3m(6>)rlb| zo6%J@Wjzez?YK+&yhPLR{rY4Tq2Ms%_o5c+W#ILA3M@*>iSK;yKKEUh95*lNiu)z9 zgZbOmkY`KCguy_@WSBFaGc=N>4FF((GIdLTDx*MaDN3lL!_4V@ln}q+qu;oNX+6kJ z^9WwNpI0b}YxFIIGYL)G5WZ%pfhP#HY+_D^50i%VLb!s5sHU3V=YD@xll2X;gW;nn zfEp=>HMV@6*hbo^MJSl{0|?m6ti&eXhiVcy_vPRrbB0zQi}{WFQ=YAG*2hM)6zBf_ z0S z(EluewoU!IHtK3~IMdnPr$9k`#Gn$*y6lBao#hjX$&-*aKoe;CE#GD=Dx35+T4 zw1e+cL_0!YP<NGCwWS=(ut$G#WImGM-U+7}9t7n@0cyVypZk^sUw~yeA*|b62XrSD zzNu2(&ZQM;C_P0O;%cnlH*jC2@eVt|`}(0TG}i{{|J6U>#p0;bk1I0Pu_i+ zi^Zy>e_m$%$bRKUm)O@qn^5Y5z4Mce2tzjD@nh2sx8GsJd`#l;c~5up^pKV0W0GVX znwGAr=f2?x7~za(;@pxP1Z$AC!QbMGWZc%ok6WQIw40#P&96qq&&qr^VqM31N}r;ZcMkDP@fyA}^AA@hV&PZO3U~N(N15R6bTBpdE!VmCfDvf`Y zQU2X9Q$x@ZI-UvF_QizU_a#*vcb zZ1yNd^2DQwa*lg$fgGrf&~#kh##ac8O#$VKDbdTj99C2kJ~z}VgP0^99H`5ai8pGs zi0bF&6+hj2q@M<}uGGJ64kRwUqy%&hB(H`qLVtA7g<4l zZy2-Ik&;|WjvW>o)Uq^cw>bl5HPY@yz=xRiWc9L6Mbo11sa&@B1*ii(1~5XON1jq{ z;$S(=J=`u=yc69sO8@u7Hfm>ccoeX)wksW-Nz{|NvKRO+lgMu6d%3n+$)UFhxF8+Z zQZjnn!o4J~-yL_A@scRFocOFK=m+j& zs<9;3_W8-j+GK1wu{H%7mVNQU{=L$ZxYZ8M43lv#!- zW5%=%4Q4qqi>MI7HttMOiEJcO6cXOg*Llx#pLL%5UF-SlecxxT=U(ext5bXb_HY08 zcep;+=en+MMt!``OWxYs!?Lh>>|X#5sYc(mgR@OxWd|(3SVl@F>{){4w-IIx zUlw`$RJ|XkKUNzk;%1G%VZ}8yO6uPcBC>_YkojB7shw7YA9hanP6=WJ7acSbLRLQ@ zzj8P0?=w_E*&-e{$!=D8QuD=+R7%X4q*9Q>{4g{1kn&qi`=isO{sSAbT!0Brm!Ko|Vko`OJoUT6>ZRPlhW`NhLzoDWG<+KtZ+C7~C{v(~zp z{&wmAL;V2d$bWo#ida4KHaLm8RdyWT@F26W@QU%!Gg&oZtE6gWL}K|WH(RDY41VXvn>_$deJRNj>&Bz62J@w4{H<;}>|p!|`zRF-Y-b%!EDPTHnv*`d;{;3x z%QzL}^s|lH6?h4tHR)RY&+P=D0{v9+Z(E+Vp*}4zh04U4ccka7* zLmQzm#$Rb0yc6?rwa;_6NT#aux?vZ6n!PwZQm$Hm_*TwE3z<`RV)(Ba!A*0pK!_2v z=)UrR^z~uU=msruTB5PV9gI1g;d_3w=f-Yi#wuKD?5E&Kc!3VUG%qqSg!4du zz}<4_1h7x}PCN?jKFy{b|6=XOpd0)+O|IB+Fg|BMUX|>0VLekrwRLdjd=uY^X*f)M z5^z=IG;CI52V~*o^y78hkG=qu47;nwb~eo)%);8eB!D;Bxmjc}cmgIxytLz>sI@e$ zyf3`kSl*=-*MvH2{%riubR?UFifRDjn~F;{a#&`7+*vwn!K?PS{SmLcY4>fj00ke} zCh%{6HsYNx25Q&dZ9>Xq=NF!I$MZ~s1c06Ln6qpud-HStOy@DE~i+2hj#ov zDh^iB4Df0nOJj>D062_sqkG=O>n;8vn=B3Pg)GQQ+PCLJYik0_5E7}2%>GgJC9mOF z8F0{hbBpy%%&z=V_V_>&eN8(t>fswDP=&rUMlxzgR+{k($D)RPXF<*6r(o*~fnUVn zPX>l2!eTyj8XUCs)`fgi_vf-2v2QthroFBvJz=ObtCUntI{qamJ*-cT($%Ka6t?=N zC8yVA57#sGsMP_CJ=BgjB=%^_Fvu_pob&SmV?l!g=hExTc5I ziEZQy-HS1_`;`trp@TX*PL0z#{_WFCFD*Fb)qW3^+h%IQM9TLD0eHAbF1|KHQq#H} zx8(f~zQRnq6p)&CT?@}+=0H1}6%ZRYT*ccAN%Z|EVs2>6a>s?SeFONuniaDoA>VirHRcG2_F+(zai9iY;p{O@V zrnBuO$JgPOF8$|Q5T&p@ZUka_A|+UC2#$p2wj0Jyly}rMj%o{5b5G zUiPp*hB@#cR{ML-4=CDgig@Vc8eb$^Cz@Ei0M3o9X)7^Q(Z~6p$JPF|r`6xi%#)c3 zPS-VNW22RR+Rc;g7i~PDcF6>d?^BNxmPtVK*5CB**W9nohp(M#~WN5AFC@9rpZ=$Rhj*F0}a zsF*4v>Xa$libq)A({s;I*WG>MAJ00);S79zMbKpsDLT9JI|xy7ue6j0@53*NK~dzBe?QWvcc&`L7p9 zX~t%FNo`9rWq^LbM}uqGdMbYv~mxhQpiToLMu*G zGnT+th9SLwej}RiK3q3vy>>+euEcWbaNQ8th^P`x*oEh30;5@$VxA}%>Q8+iRv7hx zQl$I#(|tsp@27D5l=-LdF&UpaaM@?zR^g8hoHPPMeG2@MaJW82jF<$kkIl1A(idhV z!M&X?VF z^aB-zFxp*RB+z^6U*WPp(fTg=YlCp;{p?9IKadx3MTTpj>#4!@jQ)@=LnaGu+k0>+ zd;}wjtH4#iRZopGQ}gbH%K^V}*(Sh0EYfq(@MdLi-xk|;q(zpTfw%wM4zHczN;cJz zXxKXm#x}bYZTRbMzRO9}YkmDstN{sf*#ZLzZ|0=ohZ2%aqvU8wlX1FA_9?2Hue5@Z z4Ic)3R*?(*1;kNIhUz|(&o^dQ zIg0pFY*U=!om}%h2Pp2dAJ%SMe7`#PDV0|L1%U-&}=Y^5yN{Y%jpXCLDz+R=c1Dv&K~F&< zv+tpPm|p>-r+wT~1;CQGpiLB+m9B#H*5v$I5P=>^0pIq|z1R8}{nsU%VGTIVqCt z$l5U=@?uZm5SZ_no93aB=Kx=<9U2dKkQ!zJ<9+%v7Z^PS-`2nkiYzI=eN(!0cun0G zvMyaHAK{{nn)Ug4XwYc(;3#Y5A3)5I>vDb>o@*H2{I9|dXi5lv{ys?+RRj*;<%KBE z``3YxX{@z)76D+|*Tdhd&3yGR#TN=C zmSq$XhDrartN%tXx+fX&m~NB@y@|IV+HK!#QAgy|2K9i#%95NS~}e)1MP3Xzjt@C>lCY~98uOm~tlUxeP0|A^}2ZNEG)QO_(yu=F;hCWIs(v+ z+9C`$Tg6MX@X}V7vdIp4c)QMrcI$GW49*57Qvu1PT`02G2}dvNBB4-iQ>z%&$M+Ac zo)LC^x%T5MJV^g)+JeXKK!LW?14~FEs)STo(Uw{zR1=%~nax!u>mZ1X9N$=OI`LTU zGZcMXgKhJlWRHc4JS7}nVeD;|5Pai;g=^DfUtnc;zwRG=a45|htNX(eMvD%Ty<+z> zGq0@ImOq6`Qt#^6C9;~U_>roK$4TuU`?#*;$I#NeXG-6mKbr{#am8)F%g%glg|E!( zZ{(wkIwe|C2ud{LmIl2Tj;=Hvk4B-#Su)Uku-k)`#hL5tO@bBI3rgV;bIFs+1@ZxW zA6IzGdh5)VX5NS2ZCEp@`c`#{rKNn40tC)tPTU%Ajg-be)g|Q|!pIvAjV8ql*SUN(-z7uIv%aXFwJ7Yau;W zeGa93TfBokk4+`<6$yUC*Dq*c0w3u=O@MYOyw4hY52k`lo(Gx%qe(Lmfj<8e=8MLY zf+`1z6RQRVRn|TmTCIaE>wlEA%NL~ruZj_VHMWw&#aaw};H>|~>fMBO8>Fy>mB>rs z#8|vOS<5ncMeE1=O+ZyY84bbiK3+{kBV|fF* zkMv11CMm+ZBOrD2@I%}@PaH0l=EIrlcJ1YRn8qxh;=-5^4@@Vf7m48}aK?a~O7jzl zw-S(Q&qFDn=mecyF>`9E3xt>+GG}X_aHIobKFZ<;%zRAaFh?;T{}8RS1k`?+AWM1J zeB)X7nM3TY2}OIp>JI=1e9or=N?QU;WrY(A7)^CvPpdc@c??$pGWFL#5)PO5TWHr| zdwL_he_-x$663rDR=gkneDj0(%O=Q_q^$X0b+$2K5>9d~Zhl;{H&IlUc?Po+;wtTa z4MH6%rI46T{~84U&vTCGB|K(bhOw&(yulen%IG~ZwN5Y?Sz$W~H(!x&@h{LsrG$s{}(fIOb?r zBWgw-O32ZEstYD3Vr)x1Vxqhj9bd1766RZ?WJhj~n3uwR%ZCY=S${oV8-B(Xw60%s zpV>G{E%B5KQ|2!wKJkKCYwEa1@hTUp0<4m_nLx?Nxunvy81q4h!GJLEEy?-RE)xC^ z%k?1^4YjyaCsk&KgF8?EcH1VvryZ(u?!mkDnsD9aqr~#Nxe2;F^!r8QNDp)pPIf^=lyqn6qr-T(r-^iopAP+Rnt?o8kL`+rKRX9`@ z1Z}jono!phBJ4GY+ES`V^Cv@xhqfF*QM5h$-Alv$kWtt~TTF`{r}l(vLWBd$(nUQv z`Qe+}M?$>|EL`?noGB`nquXDeUKIO!&8=GZTI)n%@SGavVGui6zX0-$Szawupo6AJ z6Li#@wp_u6U=+V@Z~HM3A7s9Ffq$4EkMl3^2xvJ!!+fi=P7>@!rdTPOuvX`Lr4ELO zNQ@>>X14QWfjwaOF9EKtO|qKhh}QGM@qQ1?^}{{)#Y#1%gwM%NMu%? zB!qY}XjCp~m_e6!e$Cpa7d9&M>LZpH7@G1!SH5{oB$N(iB=kk_X~>Qmw*!;Z;OqL! zcm77Agu>QOd_G5-lD{v=-GD5JcR-I>+}hdqWzhRy8Js9&be%*xlGnXwj zcv$|dJpnrAF&lIt)>G{9ueI|AneP&hmvYAZ>t8wA^mE(im(G?@6UpDN<2(LKc(fp^ z9Ht0|dK7URhjB{LxIEYUuN9>{Zck415cC_CuQ00P@;Sr;3VtSgQve-AmQ*mDVibq) z-$-YfaF?Z)2P>fPmu_T6#}she{=xItr}i-OI9yZUC`?f)jc|n(X@ZY_PYVw=^OnP`e8$~-16<$PZ(;>DK**S__xdn7MfpMZrqxbhO>_K<^0jf1r(eLKkJ9S8KOOejGM;61g zR|+acc5J7w4ezLgLm!fP6jmW-_pFhbi>i+es3tqC9=h(>bJSmHu;ImcK%dl(uJ*yM zAzPb8W;xW%_KcpkerYm`vPC|7Yyi(b3C9fRKxV$9kYWL_?H>eX>sO|8oQi#IcH@JiBK)czKdG=mXd-=KVTnZl7 zezsm(XH{`T86x^x5~}j^ui3(_?aei)%>eafk>91rj6`%odnubXUhgXv5`S4%pFx4p z^b0hImjPOdiCw2WM{oovMG>V6;mB>GODkKp@C#|4Rv{3hrc(jySn!oYWK6$E7F&z4 z%xsBy*8F|%=`tg6BUp3RlX{2z9#-N)5l%rJg@$F9^a#l_!CmsX3!YG}z2)SjiJdmE z0|n02Z|P~?Lzta}Pz*C2^EsYmsIbxTNz6|fl!Buo^7gfk!0@;|8UvVM?9LW9NPTWv zr3(jn%EOC96fJ#cJU?7n{o!XhNH2bXwDxv7{T0q1F-HljuM{nV-z1)7R`~&~gz)j~ z6xTD3`UMzQM$C1nN6f25;1tBWC!Whi5~Fqs2pj{H-O&x=T&`91@6MpEI+Ax4TYtD> zNV4}q{Se>|u8lNkR5ZwQmF=a;^7@EExnN&S<3JhLyGfD#U%WO4hG9tMPDR*sx<09s zmTv30v;+vR!emS^G_g+b&`Ej@r#^+-Zvs(($fKSxVwZ9;AWFK?Pzu=W(M8yE!v@4l zD6zMh+1;`nc=o%v-2f4g6F>=FwrxdeVu zc7wtQk%(YkW*X`vSiA#RqxcrL1T7&o;XJdp5v3Y{l?7%2IEXxYX~C81#at*mGe-Y_ z)Tu(RN_`_q)`D%bi>OhcY!iH({5a6E(U)|J%0cTtLe}WUy9395XQyzF>`dJDrTsAS zitIt$bcgxuoW@g+CA(YDXz;^ykr-hwj{ke_{cUTvJ8 z^Tf}AXgE~mL07#cXWRP3?=1DKvFHN z_ib$2^rH8zV(oq|Lt*w>(FSiMl)@4S%B7S=SR)!-;l7pmEe4PRhzC|3mI&bKT~$j? zdDROIcMiq07{K`8l@Lw39EfoW7O2~)&CU>szmQ=v0<}1gqA4#_|9bBo&L)j6ESrhN zeBH$^5y+nU{4(6XK+KjFul_w`-}3?K^3C%!Df@z!HAn3BD4E()uoXC*uMrQeldKzp z5}dCo__7}q0czRDP-`Y`%bT^Rv8)vLbK{$gij*Y9AVNn8qY}*IbzaEIn$S7%FqmIi z`Cv4=`dA*;&IyXy3A*2cS-grV#wTib1+xV5Emg66#Tbpfg4sNt0f|ZYO{?Dri4|-h z6UNLF6CC0BEIN91+|E!_^dRS;3iV8{ZjNB**tFg2wJZ6DK*qge*yiKp?h*xst?XyF zjdYs1_ZZki>*|m>_3XjzIZ{8c0_3}BlT_7>t@)l4^yfqFfZaw%CH~weHTp{spn* z|Lypxe=%rkRk#Y+U9vcBk{%5-p<`-L8q(r}jbGU=MNBBiC=2$Z!ujcaHP8ySM{Vr2 z`w%%ymF_ds*II=(&ZdGC55m1{x$zV!)Zfh%p0Y;d05qzuj1K0V^KJ(qB;;NlbA+M@ zcHT)C&yh_i`h5}TuNsdv5U-tHhK=2uYyT9k15PyIa(}Cbm@NolXBM~$k=|O+GgU#f z1Q!sHNJYDs3OVD2rSP+71B?)js^6=x6@vz6NZH$Z*cf6!_W6FfTZUY)fqy~tNNjOd7Anh;; z8l%FN!`o^NwULh3w`S4wIvJ?6vyl5fskg>^skBAx$=;{j0H%G5YJ7h#YC;xWjWA_m?1YPWHTVvT)e#ED?Iw>F^mOFi>vcWO{r_`Q-_^J`$eNJbfhU-LRsB} zr`e*|@tWqMo;fK{hd@Omua>=w1dE#sp-{Q=QLHMJ0>?ESMIJ+YsC>>KFQ zwjzyD@&|r0tj`*Nlit^Hba)JyS$8$Kyb+j(6BokPEKk_a$Sw_$vQZXP7RxoX@Rq_k z3XR8f0fVquEVyb7B0&b2+jz89NY_3fq{ezyoJIQ--17py>oi*?#3PAju?RuRJ6F>k zYg@8?ma#4q3Goz;AJLNAlsKyln%y+CczoeVRigY+ShusG6fsqYi{Bhj%@Hu3d-d+h zQy!JWg6Fzk$F%UOT!n4yNZ?x_(KtQ@T?+zZ4A?aNzV{eS!uJ<5zt?3IpOu~;?OyT+ zVDAe*A?Sq)au9a*7m|TSByHK;QWk#Ff|i&ajO|lDfj+fVM7(2gUxaT*ZMd@9U5XBT zJ4_OROO6+HaU~+Bg@uA}6(FN!Z%Q1E38I0_JH-a(;3AA8XncD($`GTNn{Vh+^{zz> z^nxf}()`LYCy4XlJMpAbLo3sxj+;dTkcm-z)(b>Bziy z(|60SE4D_YF&!VcUdlqQK5%XMU2rZSY~NBREXM*7Hw{rjn(8YDrlt^(3aX)EfF)xc zY|l-rV{4yf^%?{-SUE_fx5aTf^11!l5lmV+g#ow>@IEvWE71O2tR`h>Qff5*4;xJ zs{B<@VOVYe*IbN;!b{a4()Y0prEyIGDxk;P-q^-JaUOt9Vw|C=eWu8)i|z+HHZA53 z1`=XpBqH+!h#cTESJhi-wfjjY|+W^q+C+wugW_!mDSPSXXY}J0lIn!RW{eu-$B1 zj|eL0X*-^#7o^8tQ|^kvuvZ`{0a@$3ictT&d82O-vL!2IJE#jEO_$V^(hA&fQ2)&p zdx0GIxD0qd%M+4fQTSS`R76!{$0J7D72SiacV7Z&B0S+-OAgvQ4%&oujLvbSVOfMz zOw=?UkEqS@WA)x!Fdp}MtN@6Yid^qC#um^&(A*_nsEmAZ5U*6_n$*g3uk${Gfi&$= zeKhTwGk1*%+<8=&R*cAFyd_2PO!rXiB;hs2noxv{{~=`=6CSs|>`PFRKl;ca>A0kT zIEz_j-!zn<(Y%KSW??ppC88is&;)Pe89ehWqfe_>uFs65+H`P{G5}|Z8QYo{z}Ld< z0vDD@Q?#WL$c9cQjed}ow|sO*WUy&TnO=f`m-gAc3D`2CB)~QzX2>Xf?mBR&YWp|% zf5p>hiR2_CpDGq#s<3vWzC=n9_B+FBm}YbgBqm5pFal?$`~y7NjWr%xqaSc5yMepC zs5J|RUeKMb`Yw799kbFNq)t*UnPrRe8<VJ|RQqOz$b{KYXwg zZ*QGzErqNPMRfR4rm(&|2zDNqaCjwTG#^|l3t%FAa|M}@&SKVmiJP9DL(gCXQp~$I z03ibDvCYLp&TrZ>W-V^5u!~V z&Jiw69yi=yKMR1iqsQprPyctM&0#be=|+s2Z%JB$h0h^n?{m66WTbLM_4V;t8~ETNW+U~gJifHhqr3Ts(24R`=>ge4SjQS)1Ss(++xF2f$F z$0!oYORKXlA3$nXdrk)0KD23TP}o~sn@0*Ym7pDKM<^^#N!Q_Qi+w>C;7Erh3FZ|z zyC(&a(K+1#9hCrhMj&Wuq0NG)%@g%xly-bs2T0J3TrOIczOY4*7_HieX^b-*j_Tl;doDqdSiVt7{tioaQ#JMh4Ru#sw74qv zK$V>jeOec-mVUMJRIy=Ds&rX#H3e^dk385OY4bJJfMMo&A9(f{7_AlLp>ozDHIg_3 zBP?>Pp!!>j?Df=(e*q{RZdxxKNrVRskp;~+rL~0z8(OfU+RMYKDi&OAnEk*TlmhkA z7`*}g3}MvpQ%$lwj=2&101kfC(u(59v z3;|Q1$%(WNJ{YBGsnLRw4nDyfNpu2tRP@~hmJtXSU?o25fYlq$+I|Nj{y^ z_NdtCsdCV+lP&`v1;NxCaifhYTfJ#Yfov0T->VZVK^9p<~ zq4E#~x06|sICUJ-3QAvX+m!)7l5o~S4GM^y=lQk{GxS0*+U>-m2GHSyy;45-@wK=$3z99R&Dq2;JL&F2&rH$p7wWc2Orvh!Cb1z$yJVl45C+y*e!6Y= zV;74a;Rf{As$4cgr z@X3zRw7MbKN9LY;|HhCq7Dgh$o zE(cR=E*7>T3%|<|mg*ey^VW{Pj=YlKh58^FKPePngx#8qQ~zEXp{$d+8Dx-maR8v( z#b7xxR|3Iat;GwCBawycYSVH^N%VFe>YXNEQ_5gJ9^vlF-e@g zpFZ*odQJ^WNW{Ssf4t0q zUo|L_=tO$;XND|c<GZY+-?^w1`>fP zNyc}V#$+WBPPPh!(_+8w>1l=aaB{f2beZ$UXdF&8ZHR#`fn zN#2fCld4L~%u`o>Jbt>4PMar}32w}#tBXGM#?24dT#X|0JRNnc%W1d7lN#yC{*6yY zKUB~SSPyzKS-*M`_9`4fl6r6KozK5RJkn!UdS@ z_G#iWMbFjYQr{H%Km6HT<1gM6v_=uA2G_WT8SxhTNbQfgic`4uM=`VU?as@7m9y7C z?Rf^mt_|bd-H%NxZVu!k2wtKOq*uhUTJ(ZR)vnQ~;QYL0S{R!^(46wzBL-_V13Lg` zcW}yaig_AC^*eU(W}677UdICSq-PBo)TtJ0!I<(mG2NNw7-daa;ziV+d=lhD)rz}& z3S(tQcTza#o1TP~KPCt@ONL6Cs#M;{f#LA+e$Dbo??y?onX7n9LJsYkKhMIvi8WsR z^9RY^K{L{u2`cpq^aju7J_2fjRPc_5k#n+nIcp}ha<_{;RWe6V8HBhi!JJTCzZd2$FJ1ZFISI!vtZ7n+Jo*W>z}fu zRt+8+2iHRd-js~Qe*sH~4B@jJl1=X9wM^ z21<^K3+O5VXd!sDtj93Y`3ald?4RqgbT<%##g2;!uZ1I&bK*&}6eB1`TbJrmFwi&H#VSz==Y4JYNFcFET6jY!P~Z z>>b=-&QWG{;7IuitF9L6q-<89h-s+}ugyLROd5y$P3u;U+sU;>CL17Ci-)Q|+v6o< zto%g1Ts%OH#x1>$&X$FM4);^hv|liXAuM44bHuSITL4E{*TFCF(XhO!9_#nOlQ9y`qz(|78NT16##RaPWns@|vke0j@ zuuLX`J4ko1xzQj3S^R7#8Fax^m_rHRsd|YA+lXKp~}+_9g1 zx#5SE>g~eTnazHvp@tnQNJ6#b$QtB=_|+rsY{wDUTGlL&_lG?2Uzf`wIikR@Qm`Im zA^R$_T~0#j8fA}4|F0*SzCvlHv+4E#LD~ApY`fEcXS>kRZU-_Vz$(f@K}{w%w4760 ziBZGn3r_0^kCwp4dOD@uK{yh*Bj*ce7PL-k#qbRs zRsSvGX8b8*Xs7!Xfce+rKEiYe!)im=(am$7gHVu!_aS!&vMSIW7c(X_b@t*yo!(cm z_Y@(fVInCQr#>Mz1v!3%rhcXJ$X5+6pNfF9Yx1V6ebfv+6uE6YwFSVDSGnZ3AQ~ix zE)cf_bUiy&_6Px|q8jtX?!z%&{3IapL*XmZ7JqRkmOv;D^{GB{caUG`n}kjWzbciYNCD zsy$80fBK96HIud+C176N~O38Sp1;ziBpyR%&Q>Jvy~VXc7W%O72euPNuF0=i|eJ!jmPwJTbD}9 zvLq;73_BB~$WAm|1rX_~wud>}4l{Vr8G$D<=Zl^T1$kjg0T-%%*A>kA`>e%x5}N^n zCvU3K-mo0VDIW{F2sm=PVCroI?z*N9B;b_7%@2WcYuH>Sumgr0w?J&WKE^mW7nVBh z6AZp?uCcS~>0C|4l?;Ly5*T_k5uqEbc5(=b%Mujk$mbdr9iim0B*O|Cmd82x0mP;v z#3%U@lmOq${_x~}s^5wP>dC_i5OmQH_@20^@PUqdAdaOP9P%T)^5sXDe&n*~{#9`S zWgQ^!TTU!G)z2PgP^6CBgtTOOlj@9OD9$&Rnw64j!;cR6 z;exk3P+2%V)0BQ+DAliXpb4l|W<{-Ip|3PMt=?B^3Y}s)H|Y($bNCAAV!zn!Xz_Io z?gqqOmK2qy=&k1N0{cREKo`mQansq}kLOF&w%J!&CPYk&?Xmj+-8jr`0@M8;P{{11 z8v8RP^50ENwmvT{#KEe@kjA+65sQ)cpL|(9gk6=<2Zi7Bw#wM1YRkVdwUf1;5zI;o z+8}E6F_sn$q!V>E&Khja zPp)-&-=ytrg7ydAi~`GeHN{LW&lOodMhCkH#m*mJL^_{M$ocu_Wv%~>hX3C(5dZ2( z{6Ew5W*QO;uJjem4}oo=exr5;?j5AB(Wb$b(5Y;S)&j!=VPn__Juc)NaGD#gorG$0 z<)UycddE_&XX6U0sgUsiIR}Jtf8Ufm3H99FbPB{eyxA16X-Zpd+6gkaBsXmX=XY}= wwUJP6$foQomT+oQb*Y&r@c;GOe{O7Lb878&CVW%g0{_!g)j3^o@^aw+0{s1VfB*mh literal 0 HcmV?d00001 diff --git a/docs/mir_actions.md b/docs/mir_actions.md index 669c78d..23f9b0c 100644 --- a/docs/mir_actions.md +++ b/docs/mir_actions.md @@ -84,6 +84,8 @@ The plugin also supports task-specific move off signals, such that different sig It is possible to submit tasks with move off signals that have not been configured in the plugin config. However, it is up to the user to ensure that these signal types are valid and compatible with the MiR. +You may refer to the Examples section below to get a clearer idea of how to customize signal types with plugin config and task descriptions. + ### Setup Users can configure multiple move off signals for their robot fleet in the fleet's plugin config, up to one of each supported signal type. If the task description does not provide sufficient information to configure a signal type, the fleet adapter will refer to the plugin config. This is suitable for users who only require a single signal type for their tasks. If signal types are not configured in the plugin config nor the task description, the robot will not have a move off signal set up, and simply wait for the full duration of the timeout during the action. @@ -135,3 +137,13 @@ ros2 run fleet_adapter_mir_tasks dispatch_multistop -g waypoint_1 waypoint_2 way - `-p`: Further specifies the PLC register number for signal type `plc`. Do note that this task involves using the same move off signal for every waypoint the robot travels to. + +### Examples + +**Example 1: Overriding specific fields from plugin config using task description** + +![wait_until_example_A](../_images/docs/wait_until_task_A.png) + +**Example 2: Overriding WaitUntil's default field using task description** + +![wait_until_example_B](../_images/docs/wait_until_task_B.png) \ No newline at end of file From 3678eda2866111629ddca4155ea0101030fe1008 Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Fri, 6 Dec 2024 14:13:59 +0800 Subject: [PATCH 42/46] Add remaining examples Signed-off-by: Xiyu Oh --- docs/mir_actions.md | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/docs/mir_actions.md b/docs/mir_actions.md index 23f9b0c..8200d2a 100644 --- a/docs/mir_actions.md +++ b/docs/mir_actions.md @@ -144,6 +144,14 @@ Do note that this task involves using the same move off signal for every waypoin ![wait_until_example_A](../_images/docs/wait_until_task_A.png) -**Example 2: Overriding WaitUntil's default field using task description** +**Example 2: Configuring a signal type not found in plugin config** -![wait_until_example_B](../_images/docs/wait_until_task_B.png) \ No newline at end of file +![wait_until_example_B](../_images/docs/wait_until_task_B.png) + +**Example 3: Use WaitUntil's default timeout and select a configured signal type using task description** + +![wait_until_example_C](../_images/docs/wait_until_task_C.png) + +**Example 4: Let robot simply wait during the action without any move off signal configured** + +![wait_until_example_D](../_images/docs/wait_until_task_D.png) From 8010fcf1feeffb4dd58d1eafce9601ac390c52cc Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Fri, 6 Dec 2024 14:17:12 +0800 Subject: [PATCH 43/46] Collapse example diagrams Signed-off-by: Xiyu Oh --- docs/mir_actions.md | 16 ++++++++++++---- 1 file changed, 12 insertions(+), 4 deletions(-) diff --git a/docs/mir_actions.md b/docs/mir_actions.md index 8200d2a..79ba771 100644 --- a/docs/mir_actions.md +++ b/docs/mir_actions.md @@ -140,18 +140,26 @@ Do note that this task involves using the same move off signal for every waypoin ### Examples -**Example 1: Overriding specific fields from plugin config using task description** +

+Example 1: Overriding specific fields from plugin config using task description ![wait_until_example_A](../_images/docs/wait_until_task_A.png) +
-**Example 2: Configuring a signal type not found in plugin config** +
+Example 2: Configuring a signal type not found in plugin config ![wait_until_example_B](../_images/docs/wait_until_task_B.png) +
-**Example 3: Use WaitUntil's default timeout and select a configured signal type using task description** +
+Example 3: Use WaitUntil's default timeout and select a configured signal type using task description ![wait_until_example_C](../_images/docs/wait_until_task_C.png) +
-**Example 4: Let robot simply wait during the action without any move off signal configured** +
+Example 4: Let robot simply wait during the action without any move off signal configured ![wait_until_example_D](../_images/docs/wait_until_task_D.png) +
From e9c0700b918ac553cdbdd6a5dbe2a4c85ff3d499 Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Tue, 24 Dec 2024 13:05:19 +0800 Subject: [PATCH 44/46] Address comments Signed-off-by: Xiyu Oh --- configs/mir_config.yaml | 2 +- docs/mir_actions.md | 14 +++--- .../fleet_adapter_mir_actions/rmf_move_off.py | 25 ---------- .../rmf_wait_until.py | 29 +++++------ .../test_rmf_cart_detection.py | 50 +++++++++++++++++++ fleet_adapter_mir_tasks/README.md | 0 .../dispatch_multistop.py | 6 +-- 7 files changed, 74 insertions(+), 52 deletions(-) create mode 100644 fleet_adapter_mir_actions/fleet_adapter_mir_actions/test_rmf_cart_detection.py create mode 100644 fleet_adapter_mir_tasks/README.md diff --git a/configs/mir_config.yaml b/configs/mir_config.yaml index e8d7a27..dd2a274 100644 --- a/configs/mir_config.yaml +++ b/configs/mir_config.yaml @@ -114,7 +114,7 @@ plugins: rmf_wait_until: module: "fleet_adapter_mir_actions.rmf_wait_until" actions: ["wait_until"] - timeout: 1800 # Optional, in seconds. Timeout if there is no move-off signal received, after which robot will move off regardless. Default to 60 seconds. + timeout: 60 # Optional, in seconds. Timeout if there is no move-off signal received, after which robot will move off regardless. Default to 60 seconds. update_gap: 30 # Optional, in seconds. The fleet adapter will log an update using this interval. Default to 30 seconds. signal_type: # Defines the default configs for various move off signal types. If this field is not provided, the robot will wait the full duration of the default timeout. Signal configs can be overridden by task description. # Currently three signal types are supported: [mission, plc, custom]. diff --git a/docs/mir_actions.md b/docs/mir_actions.md index 79ba771..5011ef8 100644 --- a/docs/mir_actions.md +++ b/docs/mir_actions.md @@ -61,7 +61,7 @@ ros2 run fleet_adapter_mir_tasks dispatch_delivery -g go_to_waypoint -p pickup_l ### Overview -The `rmf_wait_until` plugin introduces the `wait_until` action. It allows users to command robots to wait at a specified location until it receives a move off signal or until a configured timeout. The robot would then be free to move on to carry out the remainder of its task, or complete the task and proceed to its idle behavior. During this waiting period, the user may command the robot to perform missions or any customized behavior with user-defined move off signals to trigger completion. +The `rmf_wait_until` plugin introduces the `wait_until` action. It allows users to command a robot to wait at a specified location until it receives a move off signal or until a configured timeout. The robot would then be free to move on to carry out the remainder of its task, or complete the task and proceed to its idle behavior. During this waiting period, the user may command the robot to perform missions or any customized behavior with user-defined move off signals to trigger completion. This action can come in handy for various use cases, for example: - The robot has to perform a delivery where it travels between pick up and drop off locations, and wait at each location for an external device to load or unload items on itself. @@ -112,20 +112,20 @@ Steps for setup: To submit a multi-stop waiting task, you may use the `dispatch_multistop` task script found in the `fleet_adapter_mir_tasks` package: ```bash -# Trigger a task using the default mission signal type -ros2 run fleet_adapter_mir_tasks dispatch_multistop -g waypoint_1 waypoint_2 waypoint_3 -t 1800 -s mission +# Trigger a task using the default mission signal type and a timeout of 120 seconds +ros2 run fleet_adapter_mir_tasks dispatch_multistop -g waypoint_1 waypoint_2 waypoint_3 -t 120 -s mission # Trigger a task using the mission signal type with a specific mission -ros2 run fleet_adapter_mir_tasks dispatch_multistop -g waypoint_1 waypoint_2 waypoint_3 -t 1800 -s mission -m some_mission_name +ros2 run fleet_adapter_mir_tasks dispatch_multistop -g waypoint_1 waypoint_2 waypoint_3 -s mission -m some_mission_name # Trigger a task using the default PLC signal type -ros2 run fleet_adapter_mir_tasks dispatch_multistop -g waypoint_1 waypoint_2 waypoint_3 -t 1800 -s plc +ros2 run fleet_adapter_mir_tasks dispatch_multistop -g waypoint_1 waypoint_2 waypoint_3 -s plc # Trigger a task using the PLC signal type with a specific PLC register -ros2 run fleet_adapter_mir_tasks dispatch_multistop -g waypoint_1 waypoint_2 waypoint_3 -t 1800 -s plc -p 30 +ros2 run fleet_adapter_mir_tasks dispatch_multistop -g waypoint_1 waypoint_2 waypoint_3 -s plc -p 30 # Trigger a task using the custom signal type -ros2 run fleet_adapter_mir_tasks dispatch_multistop -g waypoint_1 waypoint_2 waypoint_3 -t 1800 -s custom +ros2 run fleet_adapter_mir_tasks dispatch_multistop -g waypoint_1 waypoint_2 waypoint_3 -s custom ``` - `-g`: Takes in the waypoints the robots should travel to for each waiting action. - `-t`: Optional timeout of the action in seconds. Default to 60 seconds. diff --git a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_move_off.py b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_move_off.py index 437d33c..7f5133e 100644 --- a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_move_off.py +++ b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_move_off.py @@ -13,8 +13,6 @@ # limitations under the License. from abc import ABC, abstractmethod -import requests -from urllib.error import HTTPError from fleet_adapter_mir.robot_adapter_mir import ActionContext @@ -40,26 +38,3 @@ def begin_waiting(self, description: dict): def is_move_off_ready(self) -> bool: # To be implemented ... - - # -------------------------------------------------------------------------- - # HELPFUL FUNCTIONS FOR INTERACTING WITH MIR REST API - # -------------------------------------------------------------------------- - - def register_get(self, register: int): - if not self.context.api.connected: - return None - try: - response = requests.get( - self.context.api.prefix + f'registers/{register}', - headers=self.context.api.headers, - timeout=self.context.api.timeout) - if self.context.api.debug: - print(f"Response: {response.headers}") - # Response value is string, return integer of value - return int(response.json().get('value', 0)) - except HTTPError as http_err: - print(f"HTTP error: {http_err}") - return None - except Exception as err: - print(f"Other error: {err}") - return None diff --git a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_wait_until.py b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_wait_until.py index b049fdd..63c0b99 100644 --- a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_wait_until.py +++ b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_wait_until.py @@ -19,7 +19,6 @@ from fleet_adapter_mir_actions.mir_action import MirAction, MirActionFactory from fleet_adapter_mir.robot_adapter_mir import ActionContext -from fleet_adapter_mir.mir_api import MirAPI, MirStatus, MiRStateCode class ActionFactory(MirActionFactory): @@ -44,18 +43,19 @@ def __init__(self, context: ActionContext): f'is invalid! Unable to instantiate an ' f'ActionFactory.') if 'plc' in signal_type: - if 'register' not in signal_type['plc']: + plc_register = signal_type['plc'].get('register') + if plc_register is None: raise KeyError( f'WaitUntil MirAction requires a default PLC register ' f'for signal type [plc], but no PLC register was ' f'provided in the action config! Unable to ' f'instantiate an ActionFactory.') - elif not isinstance(signal_type['plc']['register'], int): + elif not isinstance(plc_register, int): raise TypeError( f'WaitUntil MirAction requires a default PLC register ' f'number for signal type [plc], but the value ' - f'provided is not an integer! Unable to instantiate ' - f'an ActionFactory.') + f'provided [{plc_register}] is not an integer! ' + f'Unable to instantiate an ActionFactory.') # If user provides a custom MoveOff module, import it if 'custom' in signal_type: if 'module' not in signal_type['custom']: @@ -75,7 +75,8 @@ def __init__(self, context: ActionContext): f'without supporting any user-defined signal module.' ) supported_signal_types = {'mission', 'plc', 'custom'} - if 'default' not in signal_type: + default_signal = signal_type.get('default') + if default_signal is None: self.context.node.get_logger().warn( f'WaitUntil ActionFactory instantiated for robot ' f'[{self.context.name}], but no default signal type has ' @@ -85,16 +86,16 @@ def __init__(self, context: ActionContext): f'the full duration of the timeout when this action is ' f'triggered.' ) - elif signal_type['default'] not in supported_signal_types: + elif default_signal not in supported_signal_types: raise ValueError( - f'User provided a default signal type in the action ' - f'config for WaitUntil MirAction, but the default signal ' - f'type is not supported!') - elif signal_type['default'] not in signal_type: + f'User provided a default signal type {default_signal} ' + f'in the action config for WaitUntil MirAction, but the ' + f'default signal type is not supported!') + elif default_signal not in signal_type: raise ValueError( - f'User provided a default signal type in the action ' - f'config for WaitUntil MirAction, but the default signal ' - f'type is not configured!') + f'User provided a default signal type {default_signal} ' + f'in the action config for WaitUntil MirAction, but the ' + f'default signal type is not configured!') else: # If the user did not provide any default signal config, log a # warning to remind users to provide signal type config in any task diff --git a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/test_rmf_cart_detection.py b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/test_rmf_cart_detection.py new file mode 100644 index 0000000..f703d47 --- /dev/null +++ b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/test_rmf_cart_detection.py @@ -0,0 +1,50 @@ +# Copyright 2024 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from fleet_adapter_mir.robot_adapter_mir import ActionContext +from .rmf_cart_detection import BaseCartDetection + + +class CartDetection(BaseCartDetection): + def __init__(self, context: ActionContext): + BaseCartDetection.__init__(self, context) + + ''' + This method checks if the robot's latch is open and carrying a cart. + Return True if latch is open, else False. + ''' + def is_latch_open(self): + return self.register_get(20) + + ''' + This method checks if the robot is currently docked under a cart. + Return True if robot is under any carts, else False. + ''' + def is_under_cart(self): + detected_cart_id = self.register_get(30) + if (detected_cart_id is None or detected_cart_id == 0): + return False + return True + + ''' + This method checks if the detected cart identifier matches the target + cart_id, if any. + Return True if cart is correct, False if cart is wrong, None if no cart is + detected. + ''' + def is_correct_cart(self, cart_id: str | None): + if cart_id is None or cart_id == '': + return True + detected_cart_id = self.register_get(30) + return detected_cart_id == int(cart_id) diff --git a/fleet_adapter_mir_tasks/README.md b/fleet_adapter_mir_tasks/README.md new file mode 100644 index 0000000..e69de29 diff --git a/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_multistop.py b/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_multistop.py index 9baf6ab..a0d1593 100644 --- a/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_multistop.py +++ b/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_multistop.py @@ -105,7 +105,6 @@ def __init__(self, argv=sys.argv): now.sec = now.sec + self.args.start_time start_time = now.sec * 1000 + round(now.nanosec/10**6) request["unix_millis_earliest_start_time"] = start_time - # todo(YV): Fill priority after schema is added # Define task request category request["category"] = "compose" @@ -116,8 +115,7 @@ def __init__(self, argv=sys.argv): description["phases"] = [] # GoToPlace + wait - for i in range(len(self.args.go_to)): - place = self.args.go_to[i] + for place in self.args.go_to: # Add GoToPlace activity go_to_place_activity = [{ "category": "go_to_place", @@ -157,8 +155,6 @@ def __init__(self, argv=sys.argv): "unix_millis_action_duration_estimate": 60000, "category": 'wait_until', "description": { - "timeout": self.args.timeout, # seconds - "update_gap": self.args.update_gap, # seconds, "signal_type": signal_type, "signal_config": signal_config } From 6284a28aaad8aacdf6c916a3861128606fa315f9 Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Tue, 24 Dec 2024 14:03:07 +0800 Subject: [PATCH 45/46] Enable multiple signal config of each type Signed-off-by: Xiyu Oh --- configs/mir_config.yaml | 22 +- .../rmf_wait_until.py | 407 +++++++++--------- .../dispatch_multistop.py | 30 +- 3 files changed, 246 insertions(+), 213 deletions(-) diff --git a/configs/mir_config.yaml b/configs/mir_config.yaml index dd2a274..d841b3a 100644 --- a/configs/mir_config.yaml +++ b/configs/mir_config.yaml @@ -116,14 +116,26 @@ plugins: actions: ["wait_until"] timeout: 60 # Optional, in seconds. Timeout if there is no move-off signal received, after which robot will move off regardless. Default to 60 seconds. update_gap: 30 # Optional, in seconds. The fleet adapter will log an update using this interval. Default to 30 seconds. - signal_type: # Defines the default configs for various move off signal types. If this field is not provided, the robot will wait the full duration of the default timeout. Signal configs can be overridden by task description. + signals: # Configure various move off signal types. If this field is not provided in the fleet config or task description, the robot will wait the full duration of the default timeout. # Currently three signal types are supported: [mission, plc, custom]. - mission: + sample_mission_1: # Only a unique name + signal_type: "mission" # Specifies the actual type mission_name: "some_mission_name" # If this mission is found on the robot, it will be queued when the action starts, and the robot will move off when the mission is completed. retry_count: 10 # Optional field for signal type "mission". The fleet adapter will re-attempt queueing the mission for this number of tries. resubmit_on_abort: False # Optional field for signal type "mission". Set to True to resubmit mission if the mission gets aborted by the robot. Default to False. - plc: + sample_mission_2: + signal_type: "mission" # Specifies the actual type + mission_name: "some_other_mission_name" + sample_plc_1: + signal_type: "plc" # Specifies the actual type register: 20 # Fill in with PLC register number. Robot moves off when this PLC register returns True - custom: + sample_plc_2: + signal_type: "plc" # Specifies the actual type + register: 21 + custom_1: + signal_type: "custom" # Specifies the actual type module: "fleet_adapter_mir_actions.rmf_move_off_on_alert" # Fill in with path to custom module written. Robot moves off when module provides the user-defined move off signal. - default: "custom" # Specifies a default signal type out of those listed above. If the task description does not provide any signal config, the fleet adapter will use this default signal type. + custom_2: + signal_type: "custom" # Specifies the actual type + module: "fleet_adapter_mir_actions.rmf_move_off_on_something_else" + default_signal: "custom_1" # Specifies a default signal type out of those listed above. If the task description does not provide any signal config, the fleet adapter will use this default signal type. diff --git a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_wait_until.py b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_wait_until.py index 63c0b99..deb9c49 100644 --- a/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_wait_until.py +++ b/fleet_adapter_mir_actions/fleet_adapter_mir_actions/rmf_wait_until.py @@ -24,88 +24,77 @@ class ActionFactory(MirActionFactory): def __init__(self, context: ActionContext): MirActionFactory.__init__(self, context) - self.move_off = None + self.custom_modules = {} # Raise error if config file is invalid - if 'signal_type' in context.action_config: - signal_type = context.action_config['signal_type'] - if 'mission' in signal_type: - if 'mission_name' not in signal_type['mission']: + supported_signal_types = {'mission', 'plc', 'custom'} + signals = context.action_config.get('signals') + if signals is not None: + for signal_name, signal_config in signals.items(): + signal_type = signal_config.get('signal_type') + if signal_type is None: raise KeyError( - f'WaitUntil MirAction requires a default mission name ' - f'for signal type [mission], but mission name is not ' - f'provided in the action config! Unable to ' - f'instantiate an ActionFactory.') - if 'retry_count' in signal_type['mission']: - if signal_type['mission']['retry_count'] < 0: - raise ValueError( - f'WaitUntil MirAction takes in a retry count for ' - f'signal type [mission], but retry count provided ' - f'is invalid! Unable to instantiate an ' - f'ActionFactory.') - if 'plc' in signal_type: - plc_register = signal_type['plc'].get('register') - if plc_register is None: - raise KeyError( - f'WaitUntil MirAction requires a default PLC register ' - f'for signal type [plc], but no PLC register was ' - f'provided in the action config! Unable to ' - f'instantiate an ActionFactory.') - elif not isinstance(plc_register, int): - raise TypeError( - f'WaitUntil MirAction requires a default PLC register ' - f'number for signal type [plc], but the value ' - f'provided [{plc_register}] is not an integer! ' - f'Unable to instantiate an ActionFactory.') - # If user provides a custom MoveOff module, import it - if 'custom' in signal_type: - if 'module' not in signal_type['custom']: - raise KeyError( - f'WaitUntil MirAction requires a custom module for ' - f'signal type [custom], but path to module is not ' - f'provided in the action config! Unable to ' - f'instantiate an ActionFactory.') - try: - move_off_module = context.action_config['module'] - move_off_plugin = importlib.import_module(move_off_module) - self.move_off = move_off_plugin.MoveOff(self.context) - except ImportError: - self.context.node.get_logger().warn( - f'Unable to import module {move_off_module}! The ' - f'WaitUntil ActionFactory will be instantiated ' - f'without supporting any user-defined signal module.' + f'WaitUntil MirAction signal config requires a ' + f'defined signal_type, but signal_type is not ' + f'provided for {signal_name}! Unable to instantiate ' + f'WaitUntil MirActionFactory.' ) - supported_signal_types = {'mission', 'plc', 'custom'} - default_signal = signal_type.get('default') - if default_signal is None: - self.context.node.get_logger().warn( - f'WaitUntil ActionFactory instantiated for robot ' - f'[{self.context.name}], but no default signal type has ' - f'been provided in the action config! If no signal type ' - f'is populated in the task description, there will be no ' - f'move off signal available and the robot will wait for ' - f'the full duration of the timeout when this action is ' - f'triggered.' - ) - elif default_signal not in supported_signal_types: + elif signal_type not in supported_signal_types: + raise ValueError( + f'WaitUntil MirAction signal config requires a ' + f'defined signal_type, but signal_type provided ' + f'{signal_name} is not supported! We currently ' + f'support the following signal types: ' + f'{supported_signal_types}. Unable to instantiate ' + f'WaitUntil MirActionFactory.' + ) + + # Pass signal config into verify functions to validate types + # and catch missing values + match signal_type: + case 'mission': + self.verify_mission( + signal_config.get('mission_name'), + signal_config.get('retry_count'), + signal_config.get('resubmit_on_abort') + ) + case 'plc': + self.verify_plc(signal_config.get('register')) + case 'custom': + self.verify_custom_module(signal_config.get('module')) + else: + # If the user did not provide any valid signal config, log a + # warning to remind users to provide signal type config in any task + # description they submit + self.context.node.get_logger().warn( + f'WaitUntil ActionFactory is instantiated for robot ' + f'[{self.context.name}], but no valid signals config has been ' + f'provided in the action config! Any move off signal config ' + f'will have to be provided in the task description submitted ' + f'to RMF.' + ) + return + + # Register default signal type + default_signal = context.action_config.get('default_signal') + if default_signal is not None: + if default_signal not in supported_signal_types: raise ValueError( f'User provided a default signal type {default_signal} ' f'in the action config for WaitUntil MirAction, but the ' f'default signal type is not supported!') - elif default_signal not in signal_type: + elif default_signal not in signals.keys(): raise ValueError( f'User provided a default signal type {default_signal} ' f'in the action config for WaitUntil MirAction, but the ' f'default signal type is not configured!') else: - # If the user did not provide any default signal config, log a - # warning to remind users to provide signal type config in any task - # description they submit self.context.node.get_logger().warn( - f'WaitUntil ActionFactory is instantiated for robot ' - f'[{self.context.name}], but no signal_type config has been ' - f'provided in the action config! Any move off signal config ' - f'will have to be provided in the task description submitted ' - f'to RMF.' + f'WaitUntil ActionFactory instantiated for robot ' + f'[{self.context.name}], but no default signal type has been ' + f'provided in the action config! If no signal type is ' + f'populated in the task description, there will be no move ' + f'off signal available and the robot will wait for the full ' + f'duration of the timeout when this action is triggered.' ) def supports_action(self, category: str) -> bool: @@ -124,7 +113,59 @@ def perform_action( match category: case 'wait_until': return WaitUntil( - description, execution, self.context, self.move_off) + description, execution, self.context, + self.custom_modules) + + def verify_mission( + self, + signal_name: str, + mission_name: str | None, + retry_count: int | None, + resubmit_on_abort: bool | None): + if mission_name is None: + raise KeyError( + f'WaitUntil MirAction requires a mission name for the ' + f'[mission] signal type, but mission name is not provided in ' + f'the action config for {signal_name}! Unable to instantiate ' + f'WaitUntil MirActionFactory.' + ) + if retry_count is not None and retry_count < 0: + self.context.node.warn( + f'WaitUntil MirAction takes in a retry count for the ' + f'[mission] signal type, but the value provided ' + f'[{retry_count}] is invalid! Ignoring provided value and ' + f'using the default retry count of 10 for {signal_name}.' + ) + + def verify_plc(self, signal_name: str, plc_register: int | None): + if plc_register is None: + raise KeyError( + f'WaitUntil MirAction requires a default PLC register for ' + f'signal type [plc], but no PLC register was provided in the ' + f'action config for {signal_name}! Unable to instantiate ' + f'WaitUntil MirActionFactory.' + ) + + def verify_custom_module( + self, + signal_name: str, + module: str | None): + if module is None: + raise KeyError( + f'WaitUntil MirAction requires a custom module for the ' + f'[custom] signal type, but path to module is not provided in ' + f'the action config for {signal_name}! Unable to instantiate ' + f'WaitUntil MirActionFactory.' + ) + try: + move_off_plugin = importlib.import_module(module) + self.custom_modules[signal_name] = \ + move_off_plugin.MoveOff(self.context) + except ImportError: + self.context.node.get_logger().warn( + f'Unable to import module {module}! Unable to instantiate ' + f'WaitUntil MirActionFactory.' + ) class WaitUntil(MirAction): @@ -133,11 +174,11 @@ def __init__( description: dict, execution, context: ActionContext, - move_off + custom_modules: dict ): MirAction.__init__(self, context, execution) - self.move_off_cb = self.create_move_off_cb(description, move_off) + self.move_off_cb = self.create_move_off_cb(description, custom_modules) if self.move_off_cb is None: # Insufficient information provided to configure the check move off # callback, mark action as completed and continue task @@ -157,7 +198,8 @@ def __init__( context.action_config.get('update_gap', 60)) # seconds self.wait_timeout = description.get( 'timeout', context.action_config.get('timeout', 60)) # seconds - self.signal_config = context.action_config.get('signal_type') + self.signal_config = context.action_config.get('signals') + self.default_signal = context.action_config.get('default_signal') self.start_time = self.context.node.get_clock().now().nanoseconds / 1e9 self.context.node.get_logger().info( @@ -209,7 +251,7 @@ def update_action(self): return False - def create_move_off_cb(self, description: dict, move_off): + def create_move_off_cb(self, description: dict, custom_modules: dict): signal_cb = None signal_type = None @@ -218,9 +260,8 @@ def create_move_off_cb(self, description: dict, move_off): # action config. if 'signal_type' in description: signal_type = description['signal_type'] - elif self.signal_config is not None and \ - 'default' in self.signal_config: - signal_type = self.signal_config['default'] + elif self.default_signal is not None: + signal_type = self.default_signal else: # There is no move off signal provided, we will just wait for the # duration of the configured timeout @@ -233,130 +274,40 @@ def create_move_off_cb(self, description: dict, move_off): signal_cb = lambda: False return signal_cb - default_config = self.signal_config.get(signal_type) - task_config = description.get('signal_config') - # Configure the specified move off signal + + signal_config = None + if signal_type in self.signal_config: + # Signal is preconfigured in the fleet action config + signal_config = self.signal_config[signal_type] + signal_type = signal_config['signal_type'] + else: + signal_config = description.get('signal_config') + if signal_config is None: + self.context.node.get_logger().error( + f'The submitted signal type/config is invalid for ' + f'{signal_type}!' + ) + return None + match signal_type: - case "mission": - mission_name = None - resubmit_on_abort = False - retry_count = 10 - - # Check for default mission config values - if default_config is not None: - mission_name = default_config['mission_name'] - if 'resubmit_on_abort' in default_config: - resubmit_on_abort = default_config['resubmit_on_abort'] - if 'retry_count' in default_config: - retry_count = default_config['retry_count'] - - # Override default values with task config only if provided - if task_config is not None: - if 'mission_name' in task_config: - mission_name = task_config['mission_name'] - if 'resubmit_on_abort' in task_config: - resubmit_on_abort = task_config['resubmit_on_abort'] - if 'retry_count' in task_config: - retry_count = task_config['retry_count'] - - # Check if mission config values are valid - if mission_name is None: - self.context.node.get_logger().info( - f'MoveOff signal type [mission] was selected for ' - f'robot [{self.context.name}], but no mission name ' - f'was provided! Please ensure that the required ' - f'fields are provided in the fleet config.' - ) - return None - if mission_name not in self.context.api.known_missions: - self.context.node.get_logger().info( - f'Mission {mission_name} not found on robot ' - f'{self.context.name}!' - ) - return None - mission_actions = \ - self.context.api.missions_mission_id_actions_get( - self.context.api.known_missions[mission_name]['guid'] - ) - if not mission_actions: - self.context.node.get_logger().info( - f'Mission {mission_name} actions not found on robot ' - f'{self.context.name}!' - ) - return None - # Queue the waiting mission for this robot - count = 0 # we should attempt (retry_count + 1) times in total - mission_queue_id = None - while count <= retry_count and not mission_queue_id: - count += 1 - self.context.node.get_logger().info( - f'Queueing mission {mission_name} for robot ' - f'[{self.context.name}]...' - ) - try: - mission_queue_id = \ - self.context.api.queue_mission_by_name( - mission_name) - if mission_queue_id is not None: - break - except Exception as err: - self.context.node.get_logger().info( - f'Failed to queue mission {mission_name}: {err}. ' - f'Retrying...' - ) - time.sleep(1) - if not mission_queue_id: - self.context.node.get_logger().info( - f'Unable to queue mission {mission_name} for robot ' - f'[{self.context.name}]!' - ) - return None - self.context.node.get_logger().info( - f'Mission {mission_name} queued for [{self.context.name}] ' - f'with mission queue id {mission_queue_id}.' - ) - signal_cb = lambda: self.check_mission_complete( - mission_name, mission_queue_id, resubmit_on_abort) - self.context.node.get_logger().info( - f'Configuring robot [{self.context.name}] move off signal' - f': robot will wait until mission {mission_name} with ' - f'mission queue id {mission_queue_id} is completed.' - ) - case "plc": - register = None - # Check for default plc config values - if default_config is not None: - register = default_config['register'] - # Override default values with task config only if provided - if task_config is not None: - if 'register' in task_config: - register = task_config['register'] - - if register is None: - self.context.node.get_logger().info( - f'MoveOff signal type [plc] was selected for ' - f'robot [{self.context.name}], but no PLC register ' - f'was provided! Please ensure that the required ' - f'fields are provided in the fleet config.' - ) - return None - elif not isinstance(register, int): - self.context.node.get_logger().info( - f'MoveOff signal type [plc] was selected for ' - f'robot [{self.context.name}], but a non-integer PLC ' - f'register number was provided! Please ensure that ' - f'the correct data type is provided in the fleet ' - f'config/task description.' - ) - return None - signal_cb = lambda: self.check_plc_register(register) + case 'mission': + mission_name = signal_config['mission_name'] + resubmit_on_abort = signal_config.get( + 'resubmit_on_abort', False) + retry_count = signal_config.get('retry_count', 10) + signal_cb = self.create_mission_move_off_cb( + mission_name, retry_count, resubmit_on_abort) + case 'plc': + register = signal_config['register'] self.context.node.get_logger().info( f'Configuring robot [{self.context.name}] move off ' f'signal: robot will wait until the PLC register ' f'{register} returns True.' ) - case "custom": - if move_off is None: + signal_cb = lambda: self.check_plc_register(register) + case 'custom': + module = custom_modules.get(signal_type) + if module is None: self.context.node.get_logger().info( f'MoveOff signal type [custom] was selected for ' f'robot [{self.context.name}], but no valid move off ' @@ -364,15 +315,13 @@ def create_move_off_cb(self, description: dict, move_off): f'required fields are provided in the fleet config.' ) return None - # Trigger the begin waiting callback - move_off.begin_waiting(description) - # Define the move off callback to be called on every update - signal_cb = lambda: move_off.is_move_off_ready() + module.begin_waiting(description) self.context.node.get_logger().info( f'Configuring robot [{self.context.name}] move off ' f'behavior: robot will wait until the custom move off ' f'behavior signals that the robot is ready to move off.' ) + signal_cb = lambda: module.is_move_off_ready() case _: self.context.node.get_logger().info( f'Invalid move off signal type [{signal_type}] provided, ' @@ -381,6 +330,66 @@ def create_move_off_cb(self, description: dict, move_off): ) return signal_cb + def create_mission_move_off_cb( + self, + mission_name: str, + retry_count: int, + resubmit_on_abort: bool): + if mission_name not in self.context.api.known_missions: + self.context.node.get_logger().info( + f'Mission {mission_name} not found on robot ' + f'{self.context.name}!' + ) + return None + mission_actions = \ + self.context.api.missions_mission_id_actions_get( + self.context.api.known_missions[mission_name]['guid'] + ) + if not mission_actions: + self.context.node.get_logger().info( + f'Mission {mission_name} actions not found on robot ' + f'{self.context.name}!' + ) + return None + # Queue the waiting mission for this robot + count = 0 # we should attempt (retry_count + 1) times in total + mission_queue_id = None + while count <= retry_count and not mission_queue_id: + count += 1 + self.context.node.get_logger().info( + f'Queueing mission {mission_name} for robot ' + f'[{self.context.name}]...' + ) + try: + mission_queue_id = \ + self.context.api.queue_mission_by_name( + mission_name) + if mission_queue_id is not None: + break + except Exception as err: + self.context.node.get_logger().info( + f'Failed to queue mission {mission_name}: {err}. ' + f'Retrying...' + ) + time.sleep(1) + if not mission_queue_id: + self.context.node.get_logger().info( + f'Unable to queue mission {mission_name} for robot ' + f'[{self.context.name}]!' + ) + return None + self.context.node.get_logger().info( + f'Mission {mission_name} queued for [{self.context.name}] ' + f'with mission queue id {mission_queue_id}.' + ) + self.context.node.get_logger().info( + f'Configuring robot [{self.context.name}] move off signal' + f': robot will wait until mission {mission_name} with ' + f'mission queue id {mission_queue_id} is completed.' + ) + return lambda: self.check_mission_complete( + mission_name, mission_queue_id, resubmit_on_abort) + def check_mission_complete( self, mission_name, diff --git a/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_multistop.py b/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_multistop.py index a0d1593..4c260df 100644 --- a/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_multistop.py +++ b/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_multistop.py @@ -52,8 +52,8 @@ def __init__(self, argv=sys.argv): help='Number of seconds between logging updates') parser.add_argument('-s', '--signal_type', required=True, type=str, help='Move off signal type') - parser.add_argument('-m', '--mission_name', required=False, default='', - type=str, help='Mission name') + parser.add_argument('-m', '--mission_name', type=str, + help='Mission name') parser.add_argument('-r', '--resubmit_on_abort', type=bool, help='Resubmit mission if aborted by robot') parser.add_argument('-rc', '--retry_count', required=False, default=-1, @@ -132,22 +132,34 @@ def __init__(self, argv=sys.argv): signal_config = {} match signal_type: case "mission": - if self.args.mission != '': - signal_config['mission_name'] = self.args.mission_name + if self.args.mission_name is None: + raise ValueError( + f'No mission name provided for [mission] signal ' + f'type!' + ) + signal_config['mission_name'] = self.args.mission_name if self.args.resubmit_on_abort is not None: signal_config['resubmit_on_abort'] = \ self.args.resubmit_on_abort if self.args.retry_count > -1: signal_config['retry_count'] = self.args.retry_count case "plc": - if self.args.plc_register is not None: - signal_config['register'] = self.args.plc_register + if self.args.plc_register is None: + raise ValueError( + f'No PLC register provided for [plc] signal type!' + ) + signal_config['register'] = self.args.plc_register case "custom": - pass - case _: raise ValueError( - f'Invalid move off signal type provided!' + f'[custom] signal type is not supported via task ' + f'description! Please provide the path to module in ' + f'the fleet action config.' ) + case _: + # The signal type provided, if valid, points to a + # configured signal type. We pass it to the action for + # validation. + pass # Add wait activity wait_activity = [{ "category": "perform_action", From 4a0d55c83eafd19d4ed7cc8311d5197c3a9bb428 Mon Sep 17 00:00:00 2001 From: Xiyu Oh Date: Tue, 24 Dec 2024 16:04:08 +0800 Subject: [PATCH 46/46] Update docs Signed-off-by: Xiyu Oh --- _images/docs/wait_until_task_A.png | Bin 87288 -> 122703 bytes _images/docs/wait_until_task_B.png | Bin 77478 -> 132975 bytes _images/docs/wait_until_task_C.png | Bin 75676 -> 114917 bytes _images/docs/wait_until_task_D.png | Bin 73845 -> 117110 bytes docs/mir_actions.md | 47 ++++++++---------- .../dispatch_multistop.py | 11 ++-- 6 files changed, 30 insertions(+), 28 deletions(-) diff --git a/_images/docs/wait_until_task_A.png b/_images/docs/wait_until_task_A.png index 1418ab070fd89d6babe61fa630de885d798d10c7..2ed668dea6f60e40b789f45e5c73f9032604d5a4 100644 GIT binary patch literal 122703 zcmeFZXH=7G6g7y~-r!yZ3sSBUx_~sP0TmHK@4cvWklv(Q;nF4aF1>`%LoX@<(xn6> zH0d?;UgzZA`KJAtHS=SB%$i{>7ZF18zRz>cKKtzF?D#7wNL{@|eTj^W>?%t7sR|j{ znNTva)88(fgP*KL?25s+i+0l5j$~xy-%0;YMY5CMAtU>n4E6M}+G~TQ5jRgfKJjF2 zXT;IgMxz-0=)wne<7TQza!za%!LnHctE1~o*Y8plWaNW$wiF>q3gcrfhgd6yLU5d= zDmdq~ckh0%9o%?w;q5Eq>PpnIi?`1Q&yJ&S@_)R0SCiIAo{_3xv<8PQVz{ZiWh|9={+#Q(n_ z{|`q%e|wp)-gD5+p$fUpl<_jWiI8l#>v4fukPVVj@T;1hOB#=i6oK@b%s66K zr{+I~F^Lh`qJR8*OOIp_@HEobr)w?$bDE?-UBB?(&sf9$zx*`x5FIQ7z3tj-J+7M7 zcTFL*7;dAcU-63WA}&imn}Y8+w=hQkASxUy&y9Ml;LEIs@&+<8GWL&m>c_I0!vY&$ zUi$c?wY3%9FkUD?AGy42hvuqH&;bpKk->GHDhQqL;V<6!GP7uLl#QTTX7xSDV z*>0vIK5Kp5A<@3+woc*mx0fzo-uh(}I#_*`Fdc1}A8%9DLMOIN=dr{+JvBAgBg=&o zNL;1!-hFYER#?p}(K)Iql)gY<^tHrwCOIVqg^(x?UDFlso?RBb|Ml8UI}>tl^P0{j zICd5ZpwMNn22)v8Gqba^r4P1=B?3MyAyWxrCwpC1YZHya#M0g+dH3}eW;`CBp=s!) zZg{kyN$g+_(k?Njb>8YcKksw0z^003k#JhD=W7%uaA1|jAUuu&txyCQ87z$%gj_v&VTprkH(ip;S*LD$n0MJ4F%&1 zDmOo0Avidgjg?i|#igvwW+ZoM=@r$D8r*YQ zZEfLvyN&_R()yiB7YphQ1`K^_eJSWUtG|8wmR^6JAxv5tO+)VIvh*t@FYi7TCFL*o zT4uV?wsE^3^PUA{HLmntM&0IW>gwv$JjVYxI66{=HcvYVPumGPZ4a6)w)1wC?l(=^ zSL$&#PTDWh1Ox=+ZL0-w!~$y`W}YM&G`X3N=d?*qC>;M8L^PN=mLD z9BCXps;a7jJ2454_geBeSQ@R>{rX&qk&zK)y=|3KP@rjMmIXl1|FwH+1h#p6weZOSWW;;e$Wo8)31 zd=;c2?21juS@{^F`Ow3|_btmaEj7?3cvwAJWHe$Q9j84|uxbC1#$LhSA zZW(oo9lYA$I$7uPa($6sy)4XY)=9ItrK*TDS>M(fxK_)P zLdnA&=y<-wBKPiqgGZY6h_&2%N(25~cmNyiM?){pFZ zicPvy%bS{J?(O)TxH7cx2?*#m&o8D1a`FIl;JBM&7-gewMYoyIz5adb`h_z=h{-MY zjuF=}>!Af?m-tCdm@(;oW4OH60-MI|w07L~)~8KdBUtgIx4&!uGe~Nufx{c2oZb7rsAuf_uh0r?#i8q?RnZIO{5DS+CGjIbt~p> z(%N~|f@bVr%dgwFw4!Ht7WBY%#5p?5n6q-~+G31XN1_OX$k@@cD^?5e10^fVi*5(p zm2-9dFRa?8i#zWM2n>j>eZSuSus2Il0NoBCXa?9GjF?<|-F~z)W()g~d>d925u1=e zv(d_4pfxmDFuvAI4^NKcx5^VEQxF|W+Dp_v8awIgb}`6<=nBSpYeRkWJnLh!H=o=Zq z)*o*bxX-2dEsg90DsQbeP*`m(;4N)z`Zep;sg73t#MJwXm?LB9;v~4Vpw-^k&LeO`&D`1_xPDRnt+rPGep>EsI+VnejF~5Xo7tV_upN z=-vHT-SF+5pAr-~MMcUdd&ws`#l<|t!4j#lljEJ~E%&XDT%KQZedBn|Lc{>Mn5>5u z;cB{9d`>(_%mJXSPiQtFO=P*EVU(j~Yrv2T<-U-UmG>)EGO!OyeXoLuyis!q9#Zi# z@_2WWTEHe@x$eM*RMdOko<8ri(ILQ27pgmi>ai{#$t>{R!tBrb9Ggj|DSJ)c8T(n| zwy}A%;$sNOmlPKtzeTk55wVD`V^T=SUh&?kZk|56O7@AwrGB5WMC<1yzv+*$)2SA{7aLL6!oT4 zKf;*cHi+yRc@NP0SkVRDQ!j(KO-xK?&WrCpR>>Qv-5Isw;o*^Ep)7t09LRLE#w`eX`@H1R5XU<$$g47~>sYaDcYnEUeO%N?XYs$JG~<1=cyvN6r&Gib@%6yvd6 z*)09OKoo6k;JGG=@d76EOhx6RjA3o0lz06YjiB8ZKsRFfm`!?;W&9}j$rQ7=1tK>2 zVCU;W_xH#$(j~$yyC*k0Rap~MM z)tf!C!3akpZh+co6eG%Z|9&Z3`|)O$_-#~XP0cW&(;&sMLTg0`2_dVI%${HIO*)4? z^j_FMEnQszIRRAcP!35q_zYcna(ocX-PG6D7XxV93B|wdmXRFLYkT3uXK1ML0!=lV zZhZ$hh#M32N65{e5>Tb0xD4Sw4*J`?uaYT{tI;La{JYx-U}>As4?U zumFpV-E@cAu&}(W0sE!m`G7>x016qg07MIYr|6}`Ec>$42Y`>?t%x@E75UP?L0Rm;aew15{!6+sP0)Y1jj&Hj1i z9OG8rR&O#~y;VoSD9#yz**w^7<=d|?>2$OAl!xB+q&n##n30*uL>#L(M5CK_;7)MI z8{#LbK#6pUUVgmh|A9mwZ`_1k73V_f)Ol7?g{Rw3Ho?70qXPm1;XR`HwNjLR2xswj z3N{2}={%^9Zl3JMYZ`LoWbH%GvX~KVfQFyktlyPHsi08)f4qG|Djy_jN-gY^jjM}3 zqVcFV-18K}=;R7K{B>}OOwjw^7WY~_p9R{5NXT$r?4N&kne%71a$2d~_!Er$LTsud zUR~1yVz~+^$mX}pTyyY*x$5||mqA5-A-{@#Nf|b~`@A2vVm7Pt#`e+ zg=I`%_|)Rj&qNv9KT-d?yQ$LQfq+YE1>O-MlRzE)7)o@l?aW{g>1~s8~b-ZD#>5i>A#3Zz^zuz57vLc^EcQ3& zp^GT%m#*3-SYfw4R%$g>y1Zwh=_K`YD)wi{1cg44P#Mu5|M$YeLQh|gDnEc2l+d=7 z9ZYKK6SSIv0cVccixGNwqpFDj_RY;+MOm4A&We?~13uSfy`woPaWq0*L&I`;xH3+} z)u!is9n>aBXVz=}b5P0g0(EOwN!}@UBbRpybJFW4j`W{`DLJv_Q!F14cP7x2I?{~1$8;q3tBG~AWOoFc_sfw8WhMP*KmZ_tjL%$;2Xf$)RQd==2&sJ}HBDYbE5ni`9_I>H9VrH8W+{>uW8gMT1=WKUupe68J}936#jqb;L zv(8ZBEq7PP`y&SH6x~H{kc!~Re!+=~msf2qbir2y+l%tv!r6gTMs22wNKzsfDz{?k znMuU99D`7lu&^+sQTmGpU)u0ia-*Q_wHAQ>5%JYzinfLn6wo(dWQioM5{QP>{AC4!WM8*3lNalSXc^g7%g|@>sL=X2?Gp7QLZE^ zxB$1*De8z9u=@7lq7Hy4$UdW4I|oKV-JOXd(>n+1Dk?8+%WfQXc61L&Mzz`6I{&?HEoRUsq_8cU2Fua(IkdP4S^62T^ z*M#FG&ySXD>P`e2s$~1R+S|;9J145tp!Kq*XJs)X^%su-e^K;@9)sed+a@QUmRzbS zP)RlPIi2(Ge>(~DyDVt|0~nqE;9}LE*R8IppHV*Mt*e@)pbkn13C2KO(up)}4glFQ zQ-Cg{YqocHZIU={G%@Z+-wz3w3q3Lm7ndS*L+-!do_B(v8>&vCbXgh2@>}))YCu8H z^J>JkeoXxLugr`Li}o1q?N#m_K;gw$v!re)6wX7|b6JVcWwRXEO)?LPlkhi>izGMNVpGf3C;w>~hxs)bw(pW}?&^z?KN z4yO*(%pF+t`GhAhL86HmDBovzjKC~G&PfTu`?jfNZ+%ciQS_+~ScdVkU97Yl|btyoDzu4Ok ztA5J!&)$AJ&r%$&W!{PH))hkhX!QQRJ2YFeAa6idGRz%o`T8CKXBEA@GFAZG>?-u| zqnxMm~~zUQ!dr~?wjTSkc4V2AiDt4Tv@$27q2tXxY)lY zD>NbyS^`@^sDHC_7nEc=VWvx$E~zOgJ*V)QihvF};hQVZ8fbY=FU=o33!%vgV>lmO zvF%>l>~zFI_QjvLTX65Z z>AU?@8fFb*i_V4VdgRRY@uxwy=QwmaP4=ZZ28Adk&Y!4T;crydh)IeJ5%ojjiCu>Z zDRD9$TK?uwi}DMRp2LmR-(;RLY!_zW9KzX>eeSc~u&`2YAY|kk9{IY6mOt{>S|Gi> zf`%F##H@1n4^}94D`A?v*KP>W&@Zh-1Sljk_#7*FXvxQG=6H3H2iHtdd-U3?9}yfc zk<+FevYHLWBT(~=CJq^A(J$Y=OQ9Cp5oS#N3wzK(5l(;|5o434`&w+#%Y+{ofCC`0 zZ>C*I))eE2zKUb(v$CytRKbI{KTW|BCu#xf8e8(_}tY9L;RlM|5ws~@}b>t}cwQSx_2l|L7%9Us1={Z*rLT=VjyrE5-! zeeyerwn!20T!h~@XMW4UO65d(=Kxn%Hfr*gc?ZngrVu*4Y-EU%P%Voly=eZlbYFpX zu9AGlv(DQ7Q8=Tu`^MmQ2Gs*lzvZv!`Hk+}>R$q0`%YNB${xBVRHoaa4u779?D1jB z`s|G#^IItN!T_iG*FHz%Yxe53n^KWUI~Mr5J#8_VH zW018uF^-m4Kl2WqzRxckVZbM6QF#`P$ZEqrdhGu)@orXE4v3>#V4sC^)H=LfEK-@&Ciz!HS z9Y-MZhSz%gv<)%R9)S)`avB?Du2ffXE#nTX)h|;M=n8aPUMaaWK0U}}J$uQIv`aJ! zSv|g#Y^AQz6C?VUD6fkAGDr<`EQsW?`Ukl;#?0tSE_CbTN3twNZQisBHNIaXZX-G}1kmYEZ!rMa*v#U4%$1K2v zL`b}WUgqWm4^G`$xgwt_$GXs0E+Oacb+i8tEYG5)qQ|pn*tYD>b(QdP=@atpk0NoGC^xpp@V02P^L@ zkGCfD~VL!EXk&XSQmVxwPbje*rmzsbU;4*22xkT~#Zjh8Zi43nQJeD;zo zBZ^=4n5|s=v%TSARg?F)RcpRrW0~LM2isr1&~Qe}-Ls*f4@(ogPdbsMBf+WNQ_=a@ z0Oya>ZS9c_(`b=TDNjpvZG5T_tb|dv@-8kRnt+cIm+%@Wrm&iD@7I6aUa+x%-6$4UY~5{+jA`I^aiwtPiZOl9ADH``EmF$2g5n z59$fKG_Zmr1at}-s&gGa4!)!DW89%FJ~mA{TOMsZ!CiYWM2|vWTdQ!XT|E!cel^j# zXq`Ek71c_^t+9m}`|0cF%?7dB1Bc0&8Z#L^pMWkw!^l87%?3jGR7ZQ+jS0HE8db%C zkdG9(N8PkC-zTYErv;|Av#bDI)a&=J-ZnD6b`k6Gn_S4tLU_w}1yk!@4fxrftED4; zVk3kI-uuR}K1-#2U^7yw%rPXu;?r|mn91=xV5!(6a-%C$grAA7qdD}@ljXUc@s!)t z-}vX`oWd0%e@jgrHo!&_bm6F)mzIZ^XOyi+hY26zOo% zNjN07WLAgr+U?n)c>6ylnc+Cb?w<)>PNlWmH-9xqeX;Mmm|(C?JnyJL?zi!Y81kWE zJc2pKf`a}!A_TU)C4m3`?ChL-4~~y(6rT}2*r)(c$>Eqbru`OfKuw41$W0O%XzBB3 zkg}A1@E;!;7xKn1kH#N(P)HJV`-+X;U+eydM=D4i5MYEuKA^N*8V#A+6G%R?{N3fu z&iU8$!rLp#=3V4MdYsciiEN7QzO|QCE)3vV=;oskZoI`)ZJn}~icc9x87E}KgmD`Z zzA9v5sv<&0V@oPvZ+04QrO|eADAiQMVe|!~YnEEoYFDkIEe8yfm742DwmF;SC!44& zwGJ|=2RKwG_sfYLq(o|?Kh_P~z9BS1*C;H4K+zt!U|tYapcbIFYmO7FF*{s@ZqD$3 zh8mjN!-kW;N)7#OsO=jgHECND0YmskJ+CS)iE@t4#kerH zRJJf(zknkS+p9+Eb9d7n|GdJdu>43#!puvC(>AVlKHcg01{+o4wj$EU^f=seP-00x zBoLsDN=|%$E^2eUro1ZtPU)V%2XP!Bnbj30?qjZ!XWZXNx=fQ`VMf+bOo>JPA0IRN z$H-P68xerg(@T(+xO(f2@SUBOX<1brg|`G3Th-%q-aHC^*a%X+TgxvjewLJ)7dD9{ zPKMdQk5s#rs*9zVeV*IG_9s1$dM69DdYcI4QG2K zk5&^jD$_Ga#&bo!PL~Z{jAHE>&3$fB2}MT1QqdXNF*K@fHYo-ihd<9tb@`ERkHh5% z5gW^%?VQqOLTXtq)-#Tq0le&U*HQ2QtgfmBnfd?`_^R7D1Ky4b>(CEc#YQYlkk$jvl=|e*>b8g zP}bGuY$dPqsQYU(0ErvT4ETQcWggkq=avrtfm65D?2JKKVu$a${+*o~Tf!*Rx4Y~h z`2-8&5*N4AjXkzp7$@w7kaYaE`s~pH@{F^3=sxDi1^F%lUFGdfBYRZ#PJ_&C48z9e#=8w;U^xNZOR6l1ns^Ctks8Y^i;^o#Q-Uy2s-f zAwK;|2x$Onf{E8tk>c}mi$|*E4nr752l< zO80W~2_p6b><C(EUnJi+(|fGn5Lj5NjWow~%t{vp1~<0_zpy z;;viRcGr~~;+N~i8Kb%6A((_lPM^?~coS8e`2~I;CUV{9LxGd!!%p?pnPnkbB5!t6-vR03gt&M10H=|HuJk3!2sX2JV?6fI&!I^nsx2N;;|>C~WfjHd(Z|XrOiV_g;AIKho3@eSTdzLu ztSF~rwbR6X!XYDzpCzU`Qw(>z4oEfM!gG2l8y)YNE;g8%^?K9(s?yjC?<%f>&Q#rV zo4tQ=r|o*X8qo2Ni#u$iBW_Pslc@*lIeZMle3RT#5Uj9VWyq~NREZDGzARp(jAB#L z%0(7%iN<_pS*~962FA+gu#D?JKLI;Jz?8GszOE47R^RdP@s*3Y3$LOlRu8-a|CR%T zA5_9TM^z$NOI`(C%G{DWy`FBCy^s6Imf)QaT%(wsiH+JuGmqW#hage+*p;d?0Si1Z z8o~IIn^bhZ_JnEBUk|mI8nz039k%(uv>0t)&%Pg1=j$uUmjh%)_o;eC+*6)VkkxFQ ztz#3S+0KmEzcUFiCT!_yHKA!6-7u{JcMIKF`b%2k`k9h_T4vj4W$Rf9*r$A{kYI9_ zfzBWCh07d?4kPuXwSiZKjZ&HPrD78mcH>DjVD6X;Bv9iIN)KO)JacSNt? zk#~{Yy_6RvT)51b%&V+@nNqVYh-(gli85TAs_yo&gxoR~J?*Dq}Q;xdJxUbH~JC^vuvaBA~ zzk*v6Z%8jpqPheT+}!3~8)EOfPN5c1qBN)pX~2+bD9qNghE;*C#j(WdfgLNtDD&T5K+4(_$+ zhLrB)lbconp%Dq~g54FOVpngA%S)Cumg*ZMU-RGnU65tg-}V`Qe-8t<5_~W*!00F8 zVPI&EyXxe_b`zP|vms`LeSzCsGbFgzFprKfX0>scB_sUP8ac z-!HyGk3Mdym^}&;ZSt2cr=e3^cWP}2QuWcZIK_BRAKCkvoT>Vyexe^@T&3lfn9lY5 zYIXhd3nVxz6LYI?GTcafY_ zG>9kE5oCy0n}OH_zeI>%p7Qm+8t259i7zT^EM%UhSrRH#&_+K8Cdtp>@t($t9|FqC zTZtR8`Z7?bJ`11K&0YQd{Ec%7C^IR#&?yS3GUK z^3^8$=nc33bbF`WPc2qtC*3jB&sNg)ax3S1)i<4;#S^80x9%C!H&}dH@5erUQe?-H zV>q;IZAsWwP+4j~8wkpQnnrp5b`CVxmV15e>!u5STyO82YqOEF6i-Oy?bO6y_E7@Vb*LC#H=SW|SZ%QM*=Zhk$~Eq1 zB<#)lO|S1wcl?MFV9@Q}-VvK)O6^YiSX*5^wfUMKDw0M#0w58ykGC~%kPwdq-ZQ@> zOH!yL%@PXY8hyH(q?YGn*`}Q=zJEMPC?&2Hl3KkQpU}v33%!#v9;pz`y{!D=Em5AM z;36o$>wyLR%k?M93W{BQMK6+f^?JfPRDxAuBhmSu|dC+!vu-8_| zeNCC}-{CqSNS?Mo=q1r-Yxjw0knli5QkUqeGXJvT)x5ZPi!6l7PYAt<6f0h?*-#*z zP4|#a689GihT>0oe!p)}qm{h-of$zpXlrkOSUR9)*<7;0h@y%f$qo_=yy6oB+4%JS zz382vQZjeKmF~IkK12mL`%bN&CD(Q|djL{`+`Sj-w7;&JUQMEi0>R|2CSkn5^~<8a zB-P5olH04=h7{0U)sEJCw{58RV!3wQdQ`f&M~ zn*g*b-J!bdH|6A!CzZ9s<6ki`k|_gERODemOG z8TYz@=;cnMaMHZAaxAEq?=9XZOw;K-l#w(qA8H)W3EC(!)WQEF&uO4 z57mitCXdlkBbv!3S9Tv=lTuOqX7-zVc`S@+WNB#y`!z{5_vy;>+A-p(-%lM=kETF$ zd_#e9U$cY$Z0QA*DsHKNtrlqaevkS3Q2-53ntzYFl)8jvWDtm~jWY>1cDl{vo-p-q zLjmEs*pBOj5>-4fcxl~0fQ9We19lQ{dH9KugWmr9 z&k6k((7${9>d~o0MRtjsQY8PBG1d1ppO9AhKgvTZvd}Shgr2CZNk`XOeBl-|NTnr0 zXdqwZcx^D^v3d!Vfu%TTtW-#NB$A~2`RUTnjnRXdK+v~ze0E5DKw)p)+QIu#pwMZu zH(x>PCnF1y*|O@&v6vLuE@Xt1I@{ZY^HY?;iU0x9M}l-(l82E1nT}mc#m4%Mg{^Y0uPY_dTorml z0HC{m)?TTk_s-4f`%yW-)HoLUzmsOr?oG2_`f+SA4rQsd)|ZGQ8429sK%ERnIXUb#pjEt|)TVrv2KX2_Y!~OU=x2btH?P=s~W9xJ5nqC1#^KPzi8>(J- zHJkBv{pT1wo|^&{X$P&W*ScoDVAIeSc{cgHpL z`t=}BA-8ptY0KGUdJWgbQz(^t)ZJxS-W+~I*u1doeZ`JxxrQE{gtF+iNs)@*>qV*# z%UL8%w!zdecQZ9=iqK~-d+ z$pkV`QucJHy$|FDzCasIiP5dp@_*kpou7ple8qQA~E>nT504F9mdQF{2Nsp9h z4=_}Ol7;{ZU-5b^2`0JnW6<-NDgIk4YMvLqhi;O9horvcd|94`nFJODeiD@eb`aTK zrG=(sp~-}PC<4@7M-b+fH_DtZP2HsD@nVIvfIR`pA=OS_UPTwq@c<`tm%gzhP|yP5 z##546^~#%dKDf^f-egr$Vne}GGeZb$d&Le^5M-h~*c$&V(hj(r?ry7TXqbN|DB}E8*gQbRU*A=7tPHuUCS_KjoK!nvRkE?u5E1J37 zN0eyy+|XCjHEc1r^0y$K~zId!fh<)Y3{aO4E-pUn4Ebb9`2 z=k?iWEw9?!+SF?;Tsj4z8XzQ{z2t$ufu6Ffq-433+nFiM?l$FAtI0pLxknkgt=7I< zyrBl;5Z1>>Uh5RBDjIu&SB0i`nf>>#!>V=qdO<)J40DH5!Orw zf7_9Ui&nYSE9bc3fbcdbXc-TH!ANJ%%mb zrvDnhO{E|rbyl@Yqay#=)y1eBli6p%b%#tI%@lILnswL&TB0K{zY7DBn2UsH9o)Up z`}C7vg?qSNDu#KQQ`zREDXzdVNU_!iX+7?SOS4ehL=TOHmtF)VAEb=YpvV0`E&>TP z02+&ibAhz7lX)KxfoOyq92_mr`s?|HYd?IJQmejTnH!GyXo=|?>2dmzO7QE|sg#VT zJK>6btp~Bu8t>#=Mb7uDI;Yk&i+WVwl!E@|+ix#G_e_62FAbsrW$s|km#+cXw@t4f zgqQ{)=VL)3fkop&Sr&}iEOI{pc{G29L4*@BdoK0g-Mj18n}gPlHiwLhYMYG)-Un^3 z75J(^Grn&&gztFh0AC^Kn?U-6-=&;bY~aKgbkSe7Cm zrc1wlf7z0PuZf5sQr|l?(qOYVI;@`l#5Z%f{714Tf_3W_kXZ){s38^yz4b>YOCzqH zYU=yDYh9bhD$*45e?GZPd*+WG%AnMHoPWHlx|C|wh{ulwe3YyY$fwnKA^DiH52s0a zh213Qo{ah351*c0NDoVDH*P&T;+{gsA`ll?rrqid>Wn)bmlGYkq~($lHfT0S>vmn| z-gQpZz0Bh$a^0334K=hgUi9JK-S2h#mPkgkd&prKN~favFmmbm;>qr^6OD&ze3I0K zyC43XWe!edu|C;~u6RxwCKEl{>jwZ2hZfS+bSrKfBg8-X`%08twCsLD1|St=R|kxjFT{op?vS^qDWMjy&)rWE!E09n9b;bUUauDkY<%+k`QNs+TTx~g-hf}u z9ww^YA0}^rOM^5phKxV4OPZt>_Z9_vqiq_US(7YR?bGHET9k~;1h#zi-h&69!1FU) zGGw7$>A)y{yqjjWVbRjo#sI(I(Cu8h5naNqakukau!3t(y01o-xP@L?_si8S@#&{m zSL3fq{nqJD+u6>@`2JVL!f^syZFDSy_>nYh^J`xPSu4lkxS1KjaYfgk8zIdj$7}b^ z^YM4Q9Vag64czfO@=5;wmr|_jo7$Dyr8vykJo4k8PcC#nM2lXVxDqSm$ONv!%~!__ zM+TERrRIP69B(AU2>BtH7&fjX{{{1plQ7zt)G?dBVUhRbLUc^q$KvVNqM2fPNo6((SmX9`!_Dn&(DJ!kAGpLucgT(>hF^OF$-`uUtNGXK0IosFMPx% ztEwta%xnL1@BGij_>*8C*^L1$Wo6}(4g3S|tX}_;NYxMEwUd^WW#HoK;yv@o%L{q? z_H8vawb#CCU=D;qILF^#PQm1xZXT{{+}Ox^evf)zn1&pD5`}}Xk2R##gxmfD;fClu z4HLHa9zTA3<<^5YF)_FHcUHQ-zCVxO1qaJ~KlaYWix&}0OxJGSY+k@)@Vj%}X<%9N znCr{Ao+#}65__x?TjvUr@GnM1-2ij6OhkB`IrtRK9z zFFCCYq#jvIOADB|d`;S-Uhq_gn29;f{du&%#lXbmd+PMLKPf4{4_7+k58U=)O!sjp z9deie{$k{oHyKm7e>0s&(2pO|zE^HPk(R!oD7yAEuqAP(>1_Uoe%SH(pDCx|s#2vw z>5R?HFl+rYrA3E_o>$JDhIAKQ|G~h~FDN{Cc#87I4Rk_+-0RnZu#=1k#0O0SH_705 zIVKwN^Dr;^w~&ywwe8Z6FovMpyuQDGKRH#C7V_sm;ZKP)_}-KX2SqkpVN^Wid%x7=F z&}xy>yvi5#dXi~!3U)B9tSsu=wfA>|?R1+cS0MZ-f20aP?|N zYU(>Mu7KycIb2b!Wwh4gPW=|^!A|{22N+OT*x4uH8fF@A8XAKSFlmG=j`rpw8JSDv zqwee)m`HH?s;H@bhoQ#HrCthmo=Qq8tE)?DY25-l`IB&U!Jqqwr}TV|w!p;}79K8P zZOyS#yF(X>+`g6UxqguhCPC+%ghxF$O}Z8BJZ zOtYtX-l-TYqOfvn>+3IJhW^aivpN3sZ<3H6>#%ta(~+9jXlb!!0xX=IO_sP^e#`x> zMJY?mT%8IJFef3HnH|9ZnASTF3p^bxF#5bJ37KbDPshc@tk?~e}n9HJK7rX4-AyR;2j#S3Oul% zcnV%SvdjyRQx0 z=QEzUzPT&my9#zl5(1FDd-pCz(Eerk_rVsi^Ib({(|ccVBi7^JJ_g<5eh22XT;h`i zc?Dghi!9cxq*X(|1q8Q=Z1KH*pnurROO1n0?921TH0<|Wx6Eh`XY@n=dD2~QNBU&d zaOq_3s*H>E)<2g4zMkm)isO>I_g%YBi6X0#TJ(4BQBUC(D=VwN|8?ed80`P(NADd2 z&LQ3x-_B&p*(b7)ELck}BH$4<_q+_QT7XbhL)XQAta2&Ia=&_fu;MtM5q<6U?Ur9f zMzO-qY>6VS=k!+6ST3PZC_2q2Iy!OgQ*K6zVtWX%sAs`$z-;(?tAg4na0cQkuo$dp z_$2@p6MU|^jWrgQ*U^KxvQp6h+hQ>xDWHF*;DrJ>qx=L>Ux{~gaZJHY1^9z%?yc)T?8=@@YQ`C12V-3q7X^ZTKiw&~oMBO~lvEk7FqxGmxMb{AedT?qI8m6f zYU?@)t}2vJ>(YnIo9;*mERGu)oE#jCfB#KJhSg}xO7?Draq&H{&}ic8ieNQ1aXMc0RCHGth*4N^`sA$4SwQGqBQK#b~|ja7s7A$2Qmr zCtjfwjmc5XayO8v_dXJhC%eV{@{Auj?aRghDoA9C`}$Q80I{+3-n(yMmpxo;qs&rF z?K)6K592#H?snf`UL5NeLQ-Kn#$f*V6xd77#~}tp4U^kTEqZrhAiHv{=?+RkVWwM( z-UK{M3jsXxyi($Kf}fQSkggj_!Eb_9!8Ck~g9%uaprkmS9PLzZi9~j#ys$E`>KY*U zWIahhxyW)z*4un8n|rVoX+rtx_|%)9ViMfDyDvDnQuv5BarK6;%u1U>1H_~1P6sPU zIeXuzQ(o)Sq-)Snl{|PHjma|BZVO5>HdOq{K`$+Y~n{R$6ofazd@k4}?kk7vR z(^S~5#OCryJPfiw0M~l?_WSb`xgRr6;kJLmj?DFDQIH}ZM%5>lt5@J7DgFU-Rf)s2 zOn&XQPC0!|GWcmB0PzFZy`_?_?3|o&umu>w0DR5<0%jOoKc0tc&F!(ge(-0i>gpN! zum2b*D+L!0hFwYY`gN|_&1;Zm;N1TRA9(Q`r$gc&$v($!B`pkT-O}>%!MeIOHu*zV zZ~FSw;FBV<>PG9lM7;JlE&3V~XDf6ZGoju?ih1lTzp;{3o1{{t_gsCe+r1u+lm*_= z7R6x%a3%*-AN=VjnJg5-O(pP?Gn)#TVy& z{f1jQ2Q<{7IBXa5_Z1YT7xn}`r6IUM$4{s|lBS{fen!0{Qu~@fz2>Tcib( zMA^hE&SNz~g+${L)KBiZPdRI~m9Q#|JpKO3cp)IvZZ+Q3LVV7l)EzmSN9E^D%%S)C)=jF02x&kDvp^l9*;$Z}m79R@P7G*nLUMjfMJ4<2ZAa&p0F^Q(s? zUI#Aaz1!5g2M1|*OO&Fblrkk0jDq@OVW<*mW&P@1Bq)H->i{+xs-&qYxqNjB_p z)Ms{Rr2Q~)`A)C=aWxV9xehd2H}0Ja&8(|>2eGL<8PNMSm4)(^j%4@RnZd#AO2of# zkiTy&e({ohoK5BQ4PXW&W(V0xs(0X2?5^|j0C$FBwF{B#mgwsT1$FyuC8izU+S)GD z)6>Imy3CTjeE%o5z5=SMwe5C;Vj!RhN`s&XN+^xAsB}mONDCrJBi*0~0s_(^-QC?F z(o)jh-Q94X#rOU9-f_nr!*h-tVDG)wdfzAJGv|EOvuPL^eNC!QL&&(TZr#59dC+hU zgt9u|T%#WuUUV=#e%1i$8X`UiPIYy4C^RP4*E>Mr{{#iv-6k-SumuIx=I$;vC+APF z=1|B|P4(TK3pbgAupg^Y?SzkyzX5gzldG$ehKBTD7=T5@>;@)0o*>&#-&9FQM1-I> z`U5ISCPJ(ckbZ$#11uD%_o-odu)&*-fF|Z|G=DVW>yaPcVy>F`OwN2r$zVIVS071a z(Em^}G2sR_|FP^>Yb3KCnY3COfc&A9qlpFrd?O3%P}l(Kj=OK5OcsWQ8(IKlMS|=q z3KBWk)j$z24Jw+c)+g0}#>b<JTtdR8x|{rep{&1N15Qdk zPMMB4K8-_t^LSGg-Fi%#)0VD<^%(fZ8p1<)p`t2#%)-T)waV(4E{Qv|a~pV93G^(u z{=W0?3BH?VRLudXfwT=4uBhS!9cw9e6S&_C+7^!WIW@O-foC6&00WrsYiPD@1PZW`}Xa@!2$G0y)zyjLqp0-%gdut@g*fcL6{a7 zAHTV6-rLF<2K@(Utwlvd^kiQMXZPnrCj;84zu=eC^GDv`7m1=ugy%D(jKaf9{oA3z z!MG$O-h+mFSaRy>zFm5T>{njP$<@IRU%PSRK5fdO5j8YRU_u1_XZWgi{$NvETYYP5 z`e66r(9wVD{q_Ak&_ot?mYJU0L5Nijc^bS39}8l!;1hG=yPZ?Jp^gX?>wm$ZGqSKK9y3P}+^ z*UMI`>3id+d-)Gk`7f<^vdBFxr{a$M+?KxJl%L)g9>+O&*kEWk!gu3~9|ci#m8d}S z%il-kMUf#%r-Jphyv7~(V6T4bBRiNff^4q`u^v}co2PDy)ar;I8`F%qK-nmtKf<0l zOya?V2R7{Givzjwy4{bqx3{?$n+>mgaRnWq9eeuU59Wbx0(yG1v9YnnMl^Wj031pwC{lnjDXvtv>$mG8ZLBfF1&-a~!ot zN4w4|w)3_HT)bWJ4c%GV9BErPKXzA{iTe^)o$MKjV_JRo*{Ukut_C*zs9q!4t2(CQ zioagK#q~fMy=H+zWaTGG)5#H;h0qfy)5sd7Ud_*nnF>Gfp){!fqjME@km? z=U(V{s`bVvoO!#|gbt^RJd;wzHubfYK@Eyb?;3*4oifljKYo~Lsr0fe#|Cf6+-VI3|zT0bK5FteaN^^K)EiEm;AkTt}mFQ>Y=BAdH#pUIL zRQ_(i1#6d-^z{3Tj8dy$2?O{FhUQ3#*$8;xEbQ7jogM1pzxucp1tMrtZmaKZZkG#` zGlx%k*&J|u_{&3vG8O0!4-cVGgKWSQE{#8Bw2C%r~zJeppKpc7Y`H7%fWOTiM^qF^N8TxvsNSwRI zm#&W8!mBaN*8Gqr>))l;Kgqh`{~|l6d*q_9Y5#cC{p;3zDZrfO9lZM~+5MR+9<`bi zV9irJ#O{3NP-d}+?gDcG@eulV(3`_-0n-I8VXi$geNO}OJ_Jdm4EpioR+Qu3Tei7H zK-}sypKc`cpL#;SdK(w_Ibb%(!r?#N!9%c3N=nz16k6~QjCq&=J?`gPO#m5*Tzp74 zw4M@{tmL&4vgzY*Zf<@jeU`VW64^r&?I37j!3xF4pTi);Tyj zf=}Dj)P$Mj3)(Z#W7-tZ^1MN61@RVq>k)bR^kyJ!++cczHLnyjpBPe0&30CPdV5MKn%g*AdK zE*ZE$eUR3_3K*I&g`>PrrbcxXAP(BON{AcAPhNYgbju%AhjS$0@n;L->FZERz{UqG z>lO(~EC1Q%O^Jti8cv7Q8qTMM^NGgnh66QFzY%g-=mjzrzlUB!B9bc@KuPd1s)aU1 zz}EH|(m>5etMO+*3+ebboa1JESChus76HI#%@DB&dF@yMoU<+;=U%UP0T^Qk&o-8s znHedU#Wzs%qq`u!TWX#?>55OF>1y~;oK^|GDh?1)Ao^_e$VoGSffcA@R|nhL09Qv- zq{^rTFg8bt9*dau8@vIcq9wPT!G-4t`1oZ6PX%}vEVN3gf1}R8_JIZbLZB#i1Jr)* zZ&(Ew5h2cJu<`=H2BbJ4@D@Q?Jb!k*f?8@73P!O z{q&)mH8Li%3mpcW1$zc*H+9SFQIGSwpTQSf{mw5epZgA}LrYRSN0CCukU(Wmff4RJ zu^_!BI-K?*j8u7_O}Hp4sVeO^gViTYYWpI8c-5el!G_!&vZZZ-R_(kuin0aT_h+x} z2keh`JQ}IONghpVAdx4S$vKb57)Tptf9R1J)kLW{MbVED+4a(N|Evd}Ty`435IutE zZ`OJbxZ(*WL%%1`I||2hBT-r~g5=lQJKQNA4v6n?*)KkPcnG^IAtB)@fP)aTJ>qD= z?Q^^O{L~LN-@jF^Ooepg>n!1Igjh61*eBc3=MVV!$Xz_h?Y_ai1V6^-hK3nKje(G` zzygfS)zuY@8aBW_1s6so(4KfIr0YO~3}$^^fB#B!h>y~G2|@=2&F~&p;Q}E1fFpkb zIB6TGZkKLRP)Gwp0ne$Tf(MLdz&>%Zk-}NtfKLsUu>%0LJo_W&6)<5~Iu(5J;%%iJ z+kZ+o=8yj#z&!72$=pMJ{^*erRVbiG-m8;9e!1lW#s=XaokwN$iumBYh(bUb_~qvI z_Bm)yK1|fOI)FzNY6NVyP&+GwfxYR9(-7ZfWpCg0{t90py)f(xB38X0cGbvrgS8uE zS_Im8jsG=N-Oh8dJ2?>MD6sv~qdjgB1O!B?Z1^pIuI(?pv#%udSosUudgnD5;!ZV5 zpHpjX=s65E%H~jGs2H(LUJ^oKUahvfS~(b6!&v!fEVp^J3c($Bme0Qt27IrR74Gwz zwIH@80W@r((($RsE1AgXueBT~b0vJ@RnKlL@x7Cmo9zrQv50*NE8M>O5pI{>p@iZ!+nZ85lrKm}Z^6C~{tkT%@SxISFPH$y8D483RRghRq^UGDy zHybj_vy?`uz zW&$4(5>#Mw!b41wp`jz&Yi3NFe#?SN=eU>m2}M?B`{gRkSx{`kTPfM}@qj?!4kX?r z%c^Q#4WG59+|w+hJeqjU$e@)GK@U2U2PyW>R37S{&sJWll?M7;7tq~$ zIJdQYePt;0z~Efs&DryeJ6U$d*s!>MY$S8{yjM|~%|3RIJdb+Oyq5XWuSCd5kyHxi zAUZ_c&1Y+lfPz~Vawl$-AX%iHArF$s4*(N|#l*anJCXqr{4W5C+cTjir!ce9NTisuQTYMM~~+N(58^$**8^6l%B z_r%rG(+Miz#db6wA`#6O387;XriV{WCj`L4l?aCKwY9Y_=}EnSiuee{zk@OA2;dAz zdB~tr#A;g===d3r~G!g@_7i_XR|^cwxUQ6JB&#n&4pM0Ktu+4~L5Y?^-prS#Q3sbWO0* z#|NYsDUU~`!Vuh;`8=IRl#ix!3lO8V1J7w;I z!`Ohrfe8%MplL=hSo{Dr^bGi(umunoWw@rNSgWa#f%g|ltk7y$Ff!SQpU1~;|0!SK znsq9ZDvc)ZK9`zFRJ7eO6w}=igr-SFiFcrniOp1*VL`%(e>CqI!2La>X1$Hw3p;?~ z;fudzDjL#9Vey^Wc)aXfEc>`n`Ij@pQV(0GpaHL1?>|)w0aCU6fMNg=#4OB1UIz+m zH+-i&(a8MqKU@H6>aPH)?7n1?#%?Un)~Hq={b0$54F8lfL-xm=qrr{N417CtUTF*GmJlm5sNK6#4sjpce~rFmW9h#3s|V3 zJOcA1H<(>@{J1qwebKLHokuOFKh7bg`{b?C>TSlgf(lw0`fMVB9#cz`cPS)~O5eBS zcI6w}wZh+qZ|*Eej>U9oW@lR6Nmfv$BOxLD>!idx)}gsqN5k`Ls>f&H`$OogTUhpG zHQvtkWk2HzB$(SEv^0p!EW$K6^fc1V^l6qckr_{hio|QG%IkVeRa(S-6@}>nw&<8G zd5t$xd;1ic#Xab+A!CdU6MXSApbmx+41J?l?{V;|bUlAjzFj5qH2#zd7G-+g2&mQ6 zTp7r90Kj@_a}S1tHJVRV7MtMVH9_Tt z(i^Yh1urS$OIL9&YXY+A_Vp_=l!r1Oy=3WCB^Y^GtU1g%+mu53e)QzYJmh}e^|4AY z5qACa=OtpLT0Aw=R=SuJZUgH*S2vm5i#m82S=ek=$x~yIAGVD)jkvi_1xvS8#;NR3!pMm)$y$Mr17N9NkWvML_ zRi!|U1r;^aV){lg+riz7GtiI_`UpW2`>Tf;T@gDD$}0y4hi_h9TUgOd6plN%0A)eE zS78u116#N4gK0nWlt%1^Yei}ez^4N>wvu<78zF$Ll!M2G^2tt_{CFmaXK&# zn9gfuyd;(B6wGO#ww2#>GG&Ci022!g(&q=0Xr)Lk3m4kfEWdg=jS3iby_?F4fV#$G zY`BpDC(9tR$j+hx&$3JEbxwa@NtVGo@tio$+^zT*6*~n4cuE3|3fX^z>zk+Io9Tv3gFk<@e1J%Zt_N$ zP>rR}GI5hx6_9Hi`Ak_%<*@U6Og#RvS}-^g^#*E}l3V{D+)#h~^qLuNryi@Ddzr5S zUq6K0JncrDjt}5AvlFW=+<#L{IkTwu%}W5!!Ar3||M2@Ul!OOx|2%zsX2HRhn~jYP znfRfgac-&HHUpEZcQCSb0H-XaOa(j04G+vNXLZoCv-jn{z1DSw*r!NzDuu~MXjtpt zi}KQBFql+E-4SsKGRU=O zKc7S_C&67F#^~8xe34QJzF!MATPt0|iQq(U8GD|MUt0D;C%6uZoHdWIi~+4Z^`>Ax zx{2c%Q+6-BEa3iukQLO4`~sI;Dzn@JM)_qlY_YOqOa<+51Pyp9KOg*mNAxlgIAVK- z_n|S_-C^_S6`Xvse7*YpgZ3jkxZ>Y{^Xgb}CAnw{9;d|$=+k8Op5jP0E9C#QpJ_!!aO zaPSQeU9}fev*;pmnE6gQq{@9<+|+wW+wR-XIunl`7k4e~{H%+6dQ|vAck4Il-LKE+ zF*9pjYWt(NzDEY>uDv;?5I+xII-!TOYFPLNaCgx+YiKa9kO|9=URmdRecX44VzP$7 z8!Ev`GUDfZEjLrzJ7lLBi7nK}^jNntgOT;Y$OEM^td0_qUS!or3J4^Vqkf_b`etLJ z$7`Ts9iP;HOi$MAZowl!`%hbt+?r6{rDs{N-1BAY@1U{cXS^qr1?!2Zfi$|5c7Bo9 z#ZFL;GQ~Gc6ATlfU<~kY%>H`);>-BcRZoJ64<|{ah#DcoX^5<#C^fL3fyIVeQ(Uyq*f8TchR{b zMV_*$GbL;@!!Y2F@|qYq+_cv!sscdLKt-^V*geS~(zw`af;6ysVarkJ7!rttidt)@ zr^W$r`IauEdou0O!7J;nl_eqF9ogcP$j1h@k8BO9;F4Gzm6BFj~^ zbI-ZJC4iUz-Nxqql4DfG3#uIQY+DOvK7TXlol_Z`&|>CtmdB0WrDqDpcg3)jN}14g zj9hYwV-4Iq#K!u-51TcsSAtyd7%P^_fFk(WB8)2*?wa?gKwo%CRa+JxX*kfXeUnbG zng75_%mBbl$UmybH+9&nNP(5o6w<5IDn2swpQm#9f0kIiZPwJ!1`s zF+N30Y2g;=D{k$1#Zx{W<$Y!0)3hU$FEmy=*zX;;$+@1GNUVPDu`g=ipu&Oi(u(7J zw4Tqy6Rq2wdIhlLo?^I}PHY#a@Y;z;o(27HPI+KsRY=WdZsT< zbKnSLF+h|D%XU~*POvjZv@Sy3JokTRPmj!%9*mmUUh_!2>m%jYrzx-PlpDEdKF;D} zS8mWBONVCN*6=PB`nGrD$JwzQ$EaKUYwX2Uu(RHH>&AE83gscvt-OPw$eU0?C-p#! zYkY%XwQH|Dvgi$6cR^n5j;L*1UmoA@HZ6gNh>vsEi6`D%TLyX^S!-2-QAXT zP3ax4_HAkX25kU@nyAS3N4*$>2QRJeWxT_Xzkh{-U+|dCh~VNDGhXawGue-WXq;!X?^KVUTGda~`AsWlymc2ZDEQ6$+eLy(fj*=}fk`4S$gmLjlVH*q z$6{ye-fdIci-Jjwy5jwd7$X?*2Dwk) zynCL6*`5T1HIDcx$~b8jFXI;i(J23rii0>aB1Zr_Nab z?@%dRL86DXmCz0YcI4KT9cecn(nH!@uWa@ma`%FSx($ZA3;=d|>kok1l=`>r^|CdQ z!^wuv%7m3;dWSiyU*2~$S{&}PTs6J^N4O{h+v|W8rktK=amV+TI@?>qN&%)LQ10;h zOnx3k^kO{A`jd%%XYlyx;nmwi`?3XB;)i$Jn0`8n9&}>?AaJ!>eThh6Hsk1~dhH}k z=Sy`jR%Bco5aQi#eRgTDytXiM!(PpY&NC?2d+9T2F`rMd{Ko<=0HOvt>80e}IQ7{E z^R&F(r6{<9=c;!6Iyh9cA=%{LX@~QR_+DB6O1~EdRa9C{cQ}pMnX6R=PYR0>F2-Rk zuU?_u-^s2Sc%cMl8_Oo+#ks0&C|e~oKmY(4ZJb`?74-7Gx+f1^1JqP<6v*#GnDr6r<1x2kMHRmC;H6r#5L$oOOn*`I$Wf2O zA_U9an6$K({I|37^Bz*k@f8)Mzy-o`H$UbyOYRoc(MjZ5Ggo`{3Im8bgg%+)3MZ=X z3YDSZ1-6yF`%9LcF+LdX3+k;?D*4_i_0pvn_?nn;@cxGXpI0eGDJ}zDcpK}T!B%AD za>T@*-Nr9;SIo*F9XRWG*c>$nWfM|W{$54!#H*2Appcu#!}XAUNeY<^s$_dr+pT$c z0k22*e%53;!g2=~Y%-^$$d33F{o1PiBcO=@<*#hC+c-555}e)0-ucsmBfNn`j=n8f zq`Gu)F_?|A*29;nYe3iB*rnl^4QwdpG-3+XSpN@-X4X;=g)JD-3ao6<>u7qP8xH1S zl#faQl?b?xrSr4ZVWY;nAhaOmwd-NAP~O_w>M@Icq-&6Yg25fVO3~l^Lk^YyqtJOo zN2d*}^rhu~b$g#bFZ=fbia5i!t*bUMG4E4-#2P(6;oy=k3H+h{r7Nt0x7^cPe&y%& zne6kBQ;N#xFtFM1UUY+mR`V(2mbp#PP=B%`R){vab24${NdJbgK|K@cu0oyyJ&n;| zYXXCPSj)&INZ`^I#@_BEQNI^mXzZhEj2)p4(^}_#@}qL=MTQRbfso}+$qTu@JS}*{ zgbvaVvK@ySH6QUZ5h$N}j!!Rse;83@w_At=Wq@Q9$UV3JAtW&96lVuV42Q#VESD9? z9X6gf`0?-G2#9LS#SI&e?~LW;(~pS8iT%TZbCEPnSNO+h;~6gCl|AOvWH6CHk?bZ4oxzIv0MmNrmqLID%m zD9Sf7GPs}(Qlh7ET0rZ!Ds^|JYiZ_KN3;EIAA6=VVkGw4gI{j4K2PoDT?WMnj` zy@46e>G8hY>(>)~V^7=N_l+}RVq6f(hOF#VUly&`P;o+n8*uK5bJ=}|SFKRUaW7{_ z{ncrX#05L#)jDT2z5LwV;V{o)C#n8%*=kL)(ZG1m@Gb#vd16T9jdRyoC0zCA?~rC~ z%0eqU^UA$@Rab%1jKZj2L`uOSOG8JDnA#N&X&cu1RFWx>8!dF% zs2sCtA>hAZ2nY&(9u7%q@FjhQ0IJt;a1gv1#^zlhgMj@zm1I^;4zK@2=XuRSBaS4UxWEDs1-dyViFJ@p1$V{ND4BjK|a)< zKb_Ui&N$>e*Gi)5CQYBha2GBNtzQ*n4U(%Q#KbL#$N9r;ATP8c;;qxYVdScTBMo%R z91sn$@d48t=6o=?HykPP2RD4zk`m5-7iC+&aV}?=sv~a!Fevi5y}YJ?>L52QsH(T4 z{y|H4TwpF#T;#l?S_CMGl$C)Sn3$LDZT(9(Rbp6CJE8&x6K-Va;2V)LY_9K>p1PGKsc?`sKn5gq9_PO+;%JR zs~4oQo}c1CT8*{Hrn9|heKx}%3DSBo!zE+9hDSY1#FcCa?(1kl$l+UufF_Qf!8Ve| zeXPtEC9Mr z3ou`kfR8ad?Z>YG#|#38C=S&E;;CTRz`JD)S=DEDi7;mp1D#jhd6IHngYlEb@lMM`b%?<*ol2+(@PWvG_Qb}jF=0F}9a zMd=16W{`^u3SlRUy?GNXtEiX^Tvu_X@HR0xpfQd%t3xBX8))?sGC{;0B2Sou3&LLy52);q}G9WgZc?P_wfuAV-A4&D#Q4kq&kmd^fYI(Im1O)PENz z3BdPY7#%!pTrLUgSrNYcl%)(O`F#cpB@lUjktgR$IpJ~+*;+n%D>fVZC2G<iSOl|Mnq&8wywsbLHa&qu|ZZF+l8F9xP zJIs9V)GzKB8q2(DKYQ3wcD!0DCOP@8Ba3FXU|4z)W^{tz@*hoa7YAv~cgSKEW$a;j znn(2T+@4Q_rFErk^9UCkVF)KntyQ-b4jLj*KJYz0gLd>%XRrP^~0k5H2=xX6H1git(G9d~<;s)WCUvFI{eq%626XM1-q zz6Uaq{%SPL`nNz0l@F>xgcV#A)?ExRfL=#{0K)JgK>Mc6Uaml-YTm~7Qb?$bw;D#CaPG#^ zF0dPJ!UkxZG}U}c2&6t>@_@ju*MNAyuqd#~Lm{1a_V5_=ptZT$jhvrmt|4rs<74E2 zND#ty>g$*#mvnyYwC6Z2?-MZ4v#(^5Zc`)ix4?jY)P_C!c_xqF80u*5oTBrW90U70 zMgP|*Yo4`1hZffPTG1$^+2Y&>v^FBt>10#b9h+osaO9z)yO>cnNW=9D zKLLM^ZIB60U9j+}YHsi7Xat2{whD{!2qz+6LJmiO{D3HPVXEnWUrmJ#*crlFT5-en zfW-=&vJ^P^U4cQ7h5aaK7%Z1Vk`X#m@h}n7Z%cZMFJ4}l|Ni~!>4(BDIfxVe*Mnu` zE+_*{NEAl>{>YJbh=lRPd2fxIr{%HH$$_<4QbMTceM+BB!IXb@F29gbc>VT{e8^*O z49mB+nI*s1(#o@EY090X9oUv>J!YsU=%sOPz z5rmnyn@5Q;mxAvHtSctlt@m&~ihjN%FAWV1a;7cFtj|riW<=Yg`8!}C(ZZo+&7LqQ zp~3L2DU;5Tk~VZO3hy3sWbNzQm7~S4I9@A1={P^R3G6905MJp1OArMyP+d~xy=$K@ z{`}4qyX@yStn4VD33|qz)#3iEyIht_4+?D|!-ao;oaa3H3*Kl84hmt`X~BmveIqdG zTi{rl=kRzm$(Xb|obKcl9i`~<$JJ{-Eg zG2m6}>?cGWDizJw20V&^LIVQOcxi%G4>{b;n9e|89nm#G;REqL2xve7iQ=KmAdC#R zYFou4-W&e4w-%qfr&^71|GhrYDiix$ z$y6|4nVN+p3>kG|VL_xLs_%^n(AABELV>^`C6+d-I+2|F{W}(9fI65}fY3cj{tWaD zqR)LGeIWC3IYmVp3?KOX424G06uVQ?(?;mzG}2K)pSAZIhhWBTwKjsN?DX*NA;(Mt zL)fTi>xj#C>j50vJOQ^c3CbOM<$`Y@`u+@Y$sLaNg@Kr%uO)EVBDk%6q2fanILl&2 zaBhfXdo|nM{J4_+-n(i?mHsC{F#?IuIKuA(4Y)7z4-_wUI}5;tGW2e4#CU$|^2HzH zJ5-b&rYhZftccp{Cf|Vzh^w^N!$l<}bsD}C!S%-|q!Yp58b(T!phmtA3JVvIS2Mx+ zRB-Gv%HWK|1u9Dj9W=Wd9lgDGN>!yUcu5#QrUQzWiI%oDBnb43crQ>8ye%=MgsnO= zGm~RF`5R|f#sp+uq|ZKG4s3o2Bue1M%mM)s^^1HNJ`Gct1ms2UsVOZ`!~zMB5!7t@ z%%2zSfFciWV?W{0A$%b1f>#8>-GuqMjh!8OpEfVtLIOtBA4z|E$G-qi?(CqEAJX6G z%!$f0JW5dPHu_P3h+(*=P?v(N(#hD^7-3gcz%gE+%h$|R;sljD3K!Sti6rBH7yoC| z{BkqrXPCbwr{IZc!Vp*D7wdK4>lVx|3j7Zj0OI;}Y-}B<-(4*2kVCdR7cHQ0gWCr= z_%?i4R+EZ%k_yP92T}ZQxIj3O>g->MJ&K2y7ZFGuz&hRB*r*vDjRa06l80~Kz70LZ zJ*bAk;R4|^tEyeR$H~Da*;4!%=yAfHzC$PWaR*@@690iKc$t;A4@evE_6<*}Pd-Z} z*L8LI1K;8ssK!~F6D@eLL3e|E4Lv8I1YZIJ@vhz^e-D#W+TgzDesBWrdq`$H8#R}Z zFotX_Qo<(uA5p|ykF>yg(9UbDU0`bVPO|mk^>B8 z|1>mA&CR(()_`Q>0EA7*B10=0x7_wxc`Lk60(1B3`!nbnTnmg0R=mIBl*#NTv$=bH zx*gB|TV7FH!?Nw{Nqce%A-;^rpd=jZ=8<6Q}i2dILsVPXad#q{JW(c|B_17VsHgMS4MQ3{BR^zrkP_CAK( z1@;Tmv$MU1;YCNU9|vbB<$eY#Uj(8|`TRNI&hMo{iwx-Weztvpt*^r4v78A~eE4pV zSR(72j9fS&NB(iJMWwg5_aj=`dk-EYG}{)2cIm;%S@=($WIycgj9GP5ZQBKAqH2YW zKM+OWP;2GCZ5H|8e0+4EU=%psdUc&6ijT&pr>zz3S~L$qXwB2|yVfDUrX1d5V(42( zI`*!z3OSqT<)f7Te2<#XQkNd9CkPl>Jh(+{^N` z?07b*h_gvJd{l2;p8W91Y5UXTPyaSZNWY$UGVS&LmRu=5T$Z_IjLyi&Xe4!i3&IZ5 z%^wmE>xPGis|MU*Iq=%;gm4CcARG99Vo51S`>-o+8+UTmcYlt5kD{D{Hg1cOL zubYR*FoF2U=%|spy{+x!?5vJlpNv@I?Z~WIe$>!VW3MVd#De+u$W?EQ=Q-xj775^* z?mYX*dDTru(TV6qB6)S~erykyjKv(G8{M1Iv+i0$s#vNSTTPT+B$o+lQ%xQ7t}H$@t9F(Vuj+fV!|qB z>>gIIomhJ`T1-{}Vey7~(1Yj(YFbjiEXNcEhB(ei-PB6)*NQX$cs=^oxC_qy7FhBH zhccJK#e}K4D$ZyYaPil0VWzR}(zm;+(emx%F(=+$=c{{NT2!f@Dv@>1bY|Uj>*m~! zuF0_C4anWUB}FAv@Q`3X$suPqNve}t9cQ&orQOfbMAp+2a#x1XnGp500r#q~?&Iye zlqRXd!9K&3`#RIfO+jKKzo}>|H|X9nsU#eImNUbT;QA(R$|0Xc9&x@N+7pD29`icY z%+#VmNlw)4x9CR_6#ZRUj_jDZPiV%myj{A9aBih?8lxnyc*EMRX70och2UD(sH&8g zNze0EOs8ir`>M|4_Bvy&wr74@rzd_CV+*|@GFpM|LK)Vr-hhhtXmRZyG2>gNNkRaq7l*jNW;4 zibgByOLOXBx$q<@)~ugWF?BVZ^<75R#6SO0S~g$#Ih{ajLkg+0+V^XRck{bkBx3*6 zb`gD57C&oNqJJ3QwwF1&UlbMA*Pcwz>%T*B_9b3Jw}*Tz!T7D{Y@!4T>y6zfzg6n< z_w-U|lt1+iL`KUnhnNE7W~bZ(opT&>k>X;cXXxBm@RnP+pp#QoTbc$ul49ciA8RFF zUzswkU9C9AsncSTQ?t2_@-ucsWyC-KJJ%5YE``2PUeTNJ(^IibJgKwD#F#4rZ{9Js zyH1u^FJib1snPggf7-g)(9HjH>-&SWE%O8;RLj4>r@abzJndy%aVmP!?U_ec-y9Bd z9w`gs+r7g2Q$9Y5B7EGE(p2iA>vtwgk-2EGZ$s*cjz-%d63fhSsW6-dGuWLm@Wa%C zK_*LouWZBtOO^Fo#WTZIE;X*AtK-k(J9o*oM*H*Jbi>55MK>`mLNTtT%qHRU%9aV_qX zStER`pV*c&LMReS$=NqqtPDCCLBkS@Ij#o@r}jGi^FlPkjhC2QIR z>P{tJ_iEA=>w;*{DYctMjv20NIJ=0?oATVh60@hrh0&`nX%>ZFgZASQKIf4|Tp6bZ zCV4aQ>@&HPo}WwliTy_Ybi|)xntSynt}GYfv@_zBx%;D;saGMsM=3c$RJlaz z&DT=-J9A?9{r_IMB<5q3Rb}wcMt8OHxuTvWwp;^O%Lm2P5fg)p%Vc8<-8S37{-Mr& zXqmJ@u-x<%6(;B@@qz5mlfY(wZcfd$8gojd{wThU%X9l;|K5F9Yh82A;b>g)jT6q- zWItKENyW0WGe1>FOQoN4g1`uT^Gn^trGp{KV(o%>xTLhCYRVJgq8*$RiZnr9(=3LXl(OuSj@YnE_d$y;{UhQO! zwapmWQP#1&hjRAR`;rE#U&>|7n7%-2Lp}b)0pZ{MLvkq`Zc8@mnKsfEJXeN zB@f{K<45s*mUt)}`|q`!s(>xavv2Tv!qJxCLss-}$kAju?4yspQZ`*J&yBnJVZXbD zO>Y=EPGTeVY>AquzwmEMT~^}Ml$4tKdJH&xG+2fHF7%$JrlvK`%~ncImX<)tM^jW( z4Bwgq)Hb$PUnW(4?~RM)qP4JaWID`YK>H~vE29c+h1U~^ea%`v zQeFwYpUZMUc1m8}?Jx?XaC{(ELTH-{HpAvnaK+U3#38kXJ!s$+UiYo6l;%$4`YL%~oiM58Tw~lJ? zI2?jJA!g`&to~#*Ti!JDDT4c}R!QELqRNT8FD1>Mz0>KEvrJ0QJ;hthYfQ%<;68ix zbrXcfgeV@aeCu25@QLf-k{&8z>+$GqXLP^eD-s6GzB0N zpmIBdQ%G4r_;oBv#A$kul9JMJsGzwj?d{$v1*q46mt}T#Vhhd|i1pRC@84&(JNS#o zdxUg!sGXdgeo8z9_%xhedOQU9oS=mM+bzwHU30oW?kAP34LorxhU_tbkq4@ss~wq8 z0A_*nKu6U<8b|~1g2i5epw6*ZGQLok9`pma_l4l3U?~xiZ>LENdHg1cvdzFT{Ry3* zQQf!*h};p1b%v|jpgWYiDG=jFlB{ZM1f)H_V$8`^SD>>sJ3>@L}kej77^MhG5;K zABDw>>ti{hEM_~4?=>9WD3`Ar@v>wxkt_*3e350?q}ChK!$6nvh%x7pIS$tSnX^=O z9oWs*zqZ3e<@^KP$0uk{JbZJr?;2~7IfqhRGy3-JTMV4ENy_Ii@X)5fpq~*+*Aml7 z^!bkHWCO+JyS#ONu%H8V z3yHL}ba_bTaL&6+T#+~+(eKxAZUYy)_u~m~z+?&?h@i3?dVq-bTlUCQg1OiRIP44& zOixa})3E48EC%4-u6Ua~=9nTXztgUA%lHm+X+^!}btQ8`wM^g3z9{(o_09`Q$5S}D zS6H)rC9?E(m79otP-oRM#3MdU$>TXsssMJpxGx_W3422}gfptMkv@3Rit@AYZ){xf z2?L;5auBp{VZ8S2h?ooxvJLtytlJ(DTTl=LWNuL-@F@h;`DN_uTg1d(d0me=va8R^ zSk;=|GmD<9w=G-`Y<3fjt$EMv|Ld1mcsL0xI`-Y&b7lIwU^?-(K+nHzv!D?q9VKuQ zd>3>|V4A>i#Sa{MKn{BO@@0|k;lCg9Eq{Hjry^SqlxFAWy~n{33Y`P!96x7tCI8(W z24DmPowSc1$HBR`pzU??TAG}!g;|wh%dhUC(^N%JVuH2}bgch+GLDu%vWElE!rqM> zEQ>e-va;eADl;G<5u6t>zkUYe13(oz^$VM3KZToLUKU~cD%fRcJFT5j9pclvl$|da ztGCah0Cr#?!ve#EOsP`C)e056y(J>7D~zfoF5ccZ(9p2c&;F-XzIURK#rMwRUV#<> zND*9?UQ7DROKhP}H0FR>`JIHr7j9#&`Mgx>Du_A}UoIGp00fWd8KIY01SKXMW?u(` z6;M@(tVTve076L(Qx(}5#KFXR%vM;xTV22Km-ERq1^C!?#|z&C#g6Tazc9#T+V-4R z2AD`mNq2Z@{4p!0!z+WFwQ?rE;D}fUMO9#&vfI6X5udA#30tgW_{e&=_ zWMX0hKL{brG=%UCiYf8o#{UddxUAPCpaHrL(B>)xaOr1T;z8M>IV$pCj3obfVbY2FSRuQVO*|(i{04R zm;f!O7N8K&<%_u{QaGRZ1KJBo5*f?D@#omUzK#QnH-K&sN)9Zd9j2wx503i5a zwKG3}NB{)7AlTS{^=|+L)Po<@tG92vU#5X?A@U4?wkxZwEcW&-QQ$*K#D@)VGbw#* zK!#!QgR1%chYuk1COA8p=jT{z=2F%J7=&E|w19z2!{*L#MSaZ*oDx@uBV4 zD_B!t_(qG5$#;HYUSu-v3yK7|5ul`o`EF`f)(1dO5Y%qAHM3L$1vhyB%y3{~!Q6-i z<|S3fYut~nKdbr0W&Pcx3d5}9M1)3F3^p^h>Y_HS2LZZm$y9vn{32nWs}ET4fS+Z<4EzN3Zv0O9yIzeh$hpw1x3@m)Y$79sT!ssp(8 zne!P>Yv>c22M;bo5{K3P6ZG~FT@$0~wcY_u;X66+ug&SkZBQ}1V(6Y1N^{)RtkXvLcu55qhY}3yfTqfPc618B4;$j)} z)_kR-d<-P*jg|Xj-h#0c$SfLE+JMob_|6Wr5%?U5QjkhuBZHHd8yq?>dT#wc8}pXa z4N1JfM6n22M3HN=mdCez5-}92|JSTlOw&3K;8b zgApWqGh27S5h=URB`Tk=wz-GTV<6%TR9IPALCG}~q?QR7FpRIom6eHa5HMbjDJda@ z{f`(cZntqXcXT8J?(TGYG-$|;-0gk_xcdo!R70 z_6eeaO2x)x&IffApwPSuPLrU7OzgUgjd%q`pY6~9L@FXChU7woO!7C9n;?JiFHCa4 zSup~iR^Jb>(8c2;2VtllW#8Jfu3gGF?b$cmTR|LN!4t6Xf=QzM}lo=ZctI$GePw(=3_^l4`aem~HvVYUJg<0tx~x(|Bxf!^I;h zIYk0x9V{JpSntTt0>%-9{7x0}h=>`Geo>Iu!}L#Yj;)393Ub>fp9Odxv9C?zop!AxdC=e zGbq45;O&$WGmxbZ8Wt^?g<1Yvn5aXny~%diU3jt=_BUOKkwAgCCTC zbaV&e=LHI;@R4CVa7X}XHV-6}Kt=%CfEGL{=!$SDC^|qtZv#;7Du=-v$C_2;firAq{pcD+D>gKXzhI%FIKks5*Rkx&oH{+Ppi9;a!_D410EC*5bW zn*5ECm!HqQ<6&)nTC51x8pFjVx`0N5h3DAZGLm^<@&}HDXyE5rQBlEZKKH$C4>AfB z;vv#`WCq|psJ%@B^#;LN0dm;D_r6l{p)!7$176LbTVP`c0c6$LkwML#DmX8tWM$34 zc_^|(NS^GO%k`t+C)d!>Kzsa!_bDg#3jpfCF3-p$WSd@>xv zpUN*K+BsT19?Ts#TO3ed+QBXz1FZCi{d#d@HQk*UD{%dhx1sr|e+lI^c3>ul>WHzqO+R?DPHVxWt*~rJvY+(X($3pCM1z z(u_}M(G&UG*ygD$|1R|YBI?yxFJ5&=*f0RZdr#{qx(je6jaQ;AL;yE-+F1+6{+r<5 zP!}WC(7wo1Ya&!O4@RD5Wo04039x?#zjL847d!wPOVC)F;PGs2Y}{jEkrPWI!^5is z1RqN&^i}cv!ooGBK!X1HTXv8i4#Ds=43v5>`k?`b56N)$&518JVJO!<)sr;G+V5=t zN>~`oD8tE~F@wv%$;rt9D5X#aF?z^=iqC-%qB+>1Dpff=gWP&4qY>4=* z=;DCe9gNy2z;z2alR$2}2lKaQ=5qra)entEqk#wk!%99x!2}Bu##$9n{ew%RJHjaF zGlwG~kbxB%MgQd`kx60Wa)RR>^`Z^^%I!Q%Q#_LOWaB2zl*Y|5fF1bmV`CXd*vIu11 z#_fqzKRwX#r(|Rp-sX{|#fNG7JLa$wsK^ty&iBvHC_vx^bHyp>u^Ueh1y<9&)({ManlTZmE#oBZNdN4X0@1{?2M zq?9mtyKe04Tt-&vPbeGGGuW&cIs~+RI?8#;9d~5@7k6(RR^`_93uA8s*rKR}pt9(c zZWN@u8>Bk~=`uk6=AX1n^E=!2Ux%I-a0_!ryJ2C^3$xCKiDfbAdJ&b-~juEqr;n;|pT z`0;82tb^&&U1jlqRwt^{pYKx|tXD1R0G-}cIFI#a)h!|leIDzY=f{RBNyekg6F#E5 zp6@=zwq}-O zY@GWJ6h}d+FKml1yXS;98j4T^%cJe0w(eUjybRnnQJI$4L}J&2Q5VCoxw-RKonrn= zn{0$7V>#1H5%NXoECP)UfaciglLj*=KzM*rd6Dg~=0Gn>;oO1gwY3R-{+QyT-cx@$ z0459Pvb?J5z%Lj07y`Hj6A-Dfp(klLvkDm#;fssrU<8P|=m_&0n9S}p zlDy)9rERcEg7!>=u~s)Xrvab=osAOO%&Z4~x$<3Ti*?cjxL{^x#>vGczF(N*GdQS5 zy->WzW^3O$pA=N?!i6;zJpT*tp7Fr1orI3+Cp)j{pGlQ4pyYCkiz42!k*bN_(st?f z?^AZ(`7JwHbt~D?B>c2$C`R;-U*w)wjrh#+K=eh$pWfVv4lxzT>)&XIG8pjs5V3xZ z*<~a?k=*_G+*A4B7uIueN!Hr$MF;quw+X32V|8}!@TJf{S($4t!(YQ=H}iJ*cH0(2 z%$HS{r@E?0FQwwhM}`akewPZJZpxo6hJ|j$RfsLpg2XexH!sh3cznTdW#k<{559jY zW8HKrHUc6r>=WgVpxpz#4(+YURkU$;k(^XuNkLv0BOJBR}N? zwhN6@nL!u93GEl;At@&k+AbfZd6E+g zS*^0jU}`1O(FcLv^fKt}a;E0Yo&Mmj_D%T_*@|5ZB*RZvgT_=BA5qD0eoW7~^XknW zXUqjbxwP!E5Kv(y>{FJng?16cDe>uYiQBzAHaM=+Ih@jLmWc#N;tB zjkbGTqNZ+!A9Q=zd}tR+m@FdsXD_|G_(Z7bGiWLGdt_-^V_nV%Vh$?_OMLHovuV4$ zVtt1Uzc$@s{L;%UzKx_hr^J4uCH$t9QFDV!RP(Roc-?j=A07zZHmAQ98U-g?WJ7^4 zWcBw&W_a;lMbpm1m2t%VaCx~|7Hmg?@fniyX|xOz`7_8ugdJg?@xs>bwd34*_#YHZ z6m3cY|KUVE8gm!pYwB(sZ02V8>}C`J{Md@-uvgcQ&ul#JTlLuu*!$TkT%#NHzbk3K z@9r9^&d{d2!}7i5T8M_Ip>In3VWhOkOk0TVbr?oN&rR14&g9{~zqtafwFh=%z0a&r z^$ri5@%C@|9DZQjf$C}+ zGSI9*KL$oY7>N5Z-0vstFR0L;N!(9M$Hp|g=&#i~Y=HeY_UYTD#J@q&tAggJ#-;cO?<;+$7i;bVnaTVh&CJY`1>P zAJTyRi?U3xj4mriwrz<=w`!u{d~ATLSUS7ts1ZXh@IFqh%&SFAoW*PQu-Vc z@(d)a=VLkJ$kq-J&u^&R`a3$8Zb3^)=^1?F^4q6C!IzhFgV|43PcOj(|9PxkIOL~h zX6YXI6v0>XWD+E$q>8v~V4oQvw6GwT5KWNlEVDO3?C>aOB{em`(ASI$3H%x#ZI8qh z=QvES^mKQF_b4yDqpb}(iS*5B0A(C)F`~5({DI8r$+6Yqwksb{3cY=pN<$3zZyrC+ zA6mN7zZ8!~Khma!yM@~)>~fFh+o{DXU%!P2Z2Hrf%Gi4r8J#A&pR4IqJvor!_onkP zlH7;&nzI3s&W&tT0$daDIoz{&&W z1?IE0^u;t4HT5|thVli$2nQ&#M`UCOD-BYF0uu!T0}e)`4g5~N&|?trJ91(kyV_Vl zREioJqOjgx#)if&zMy(cO+ud_bDHOEWLwaTWqNvAC|9TIH*`e@l6Vf-(y!!J+Dky8 z{hFEi2E>OTTnu!>Z7^j8v%U}{fe8N!z!Ir^fCkK1w(Gxy;hsRhGVN*Yb-)2Vklta% z{KJMnuM)7ST)zypS#T9V0FN4GM0T0ZB!}xjQ)fRAPhj*S{j`&xJg5aaV^7bg{dbO+dR}F1<6$9f*~bZkw$*dRS9Xnm8p_lU}HQD?LWY01+BtC zT}c8q2kE6!Y(s&(1JQ?&{YIcOCUm|GhIR}f99^shWv>IenSc2BF#&8@AVvXi8o^-` z*9)~B`jBZO+5?;cG~jC+v8j=^wq^i9YZf5UP1iX?B&_*$dADCsRATa=AsDgSG zaML5B@vz&~28`IjA`pOXc6D_jVHc7%XyzjfG9lRXn30WkpxeDajI=0Fmx0tm+C@r} zLRvW#bM$t-%pwW&NQ7u~N{i$}&v{NYE7(|C_{#2==|-hcBp+t6GlU*=D)gO`si zf87wIV~f7zAAxUH7? zK!35m>PT#0=zw_z6C-em>i~w)5fOvGZs*OmhO@YCnSw#yMB*K17R~S z=_e-{@FmHv@1^sux=lfR~Mvhi4No z{`CBO6Fg#^TEJpRk~2HoFPn!;%=rW!KSClVc`ju`pFijyy4!t>6v+&k#D^|oU%mjE z$u!cS=i7&ySm16B=NNZ>3si$Vtjb_a1%Lbz2+yL~Dz{*>AYj-Tw;%phzpbdLAvLu? z1}>^#ds`y)Lw3D1%ZQDP4jFQu9Ug}JBa*S>jv4B))gh9iyJ*Z>&Fxq&@5WxHMz*zY z=WgI*C+dI)?MwL|^wzMFVq-3(~s=B8ADOJy+#d<9>o>ySEL1>*JIZ?eMJpj;i@JV(n4aHQ(S^ZI5NQIxNYkXC* zPNPa?I$?tKc;=gDM`I}|H><`EHEr>6*~iFR>e7WGmdvddGyOK3xuBNoN{PIpK96*H zvcdUU{fE0htUvXI0!t7GEJ6B@HmnD5KH#{D@E3stQox^SVABn2T*Ku9@5)<`cN(+N zw92NH?pD>Go3ZjDq;ALZ$n>9_qTLLgd~$-}OrIX<73>^`S56;3RvD7X&Y`D9?f#Kr zI4O;7kyK}QK%#;z<;^;>sbZs=C=I}zVq&G`)YqX0By8B!kzxrQme_MwK)#upnL$+n zX?@vp6U7z=!_$zIOf~zD3HtmJe^7@N;Cva&#}PFkA+Au;5&dyo{LXlB*5q-d+^}N zaEgw;{v%)-^QkR(`xyB6Vqw~<C8rP4RiSlrRt2t5)~Q}>E`_xJPhabe&9B--p@>9^i-UTaoVg3IIot^A0(=;kFmj>qBG}sKW4L}|Gy;1bZa`+!y zZc&k*Rvr56K^xf)8sTovHeekTn=s=cEM(%x0W;8y1o?c;F|h%L&9r;?@j11;&tA-7 z*C)K*rx#zwRLBsXOX}NCT;CF=2%h?V>lH%dWN+`v8C(l3)=u;urlmE8KH<%!P9L99 zsD7?oSCn$BD+oiz7cfDi<w6#0S>tkvMpd?G{3K~jOH{Z$yM#L( z$z-)~2i7=B9*i2!*o_RP)jiL66E(~?GLTY4!0Vx3g+wpj9(s-dAv`f+Zd^#ID(LPlI*`T=YuZysyAvG$4oP_SXg>d%6}`CKuJyb&c$ zp{}9n(u)q4YT1%_to3eceL6e`&5ZNZes-sk!##&MLERztl}12x5x2IB<8NR}3UDnO z!CRW$K9N$*h9vRh$#*^9u3dOCy&&0=(y_kk#ev2A!1-wUhoK!19$Zz+jJ?Vs33e}R zdLKOPr>l_tK?D1%(C*tJ3ihOV1^!r@|CyZKwgyE$&_%X-?Zb+q~q zG-62s-hv@g3+O^%p21Y4a2Te9KZ6G$&Gl5sO<{TLDp)fGljpkg`Sx%K-{=^<5fK1@W`h=gzYN!z=uCr;lwDBjD}sKSPVaGOVc5QKA1Wl@bXqR zi^T^l!j5ndaG=I?=##B^hfDFU#(>|44-Y`bh8&#wi2>8Sz1eVG=dCW$WJjctA1EeB zQUND}NQLP+`4HM9_hS}g`8_la_(6088$Pt4g|2{S&L|)p>p(~SR~g9&vEnp8WLDK+ zbhf-8`owC;NXh||WEEH}B9k{)kxp9m)p1~ogVXn$18L&+Mgx7(6`d+eQT}2PN28aw zUa8EBnk|-zV8jlK4tKo4J(U2ydT_Og0U)W2_dFlDa{wn)A(+6&(~*2gLdBkrKw$ z)m0?V0vm}BsDFA;?BTkFw4y{B^Etb+S0>bGfVTvcwaA*|6`L&WiZG~%fLay7U%!40 z^EL%&S-gT=QBFaj9=1Gzl1@aYdR})P@>bwh1A12>(+4f+4Y-?Pp>_ffGkoAZK8|Fn za4qT}WP%_LI{5~ivt-7=|F-4^**g>HBc#753I)yq3;L_7IJM)S@GO6(f-#_@A?WYcNlU9tb30J7{vh?+Tu`O*+ zydF)eH1sH0#4o*AuTiux0jIF}W!pL5;coo`97}RAiM@DF`SkVgGE_qu+ zE8Jjl(!mtBOz>k%qxJz>_v)Wl4%?jCYY&lwTL%jGwDcu*g=O1cU6lCt>HWn(H{vn{ z@r?snCY?wMptf!~ub~#ym-l@xy>we9s31X5^i=x;@LyS3fQ~o;W!@X69kpQNR z0-MXVS4iD!p}+;oBkP))uE3vv1Yy%IBKAVS>v>>&K(IX6!;pPmI*(ZMGauW{h#_3` zn@iWBJ_QB3Iw&yki)*#;OzHvhA)UQxLVdv=!VCqROXV>~U@ZacK!W7rLf$tX!q#q3 z@%gpQe)$LH@)A`hc#-m;dJOdS7xwmm_U>Dbm4|}AW~e9@L?w7kKV!IhQY!NirV82O z6lo?7CklPWJ5l*N$OVK@D@H&W5cCBFH4qPKy`jUvIiy@2zyi`n0_>>J@fq68R!WmX z+Tjl5JakPR3c3Eq)`OF?d~$|JOwXMd=FfWxA+yEY?zD)4A{5?Nfp7ZEQ!}KWaysP9 z88|-SDOW5dnHf186i{TwE6*h99ag54NJ}mClcmi3s8^QsP&A5C-YLdcOW81gyXg z2Y^D@)U|)cb(x~r*zjXzplwNE`XLnBA)5{{G0D*&tql<>pmT``U8sYL!C;W`o~0!} zAJHCJSxK&xxP@2Fm$E(@5f_~FGB5o(4?RLWr^*tz|~{1k(fy?Wu6}uB zCCa+0S7p0|R~Ok4-g(-%O9i`!D^HQXY2t4IbU_Vp{f^%y@SbWVJjvVbP^a z7)k69+yA0rnE$zKSF@!X?{j8v=}Vkc6m?vjml_l(G(|FoO?Gp|faf3Ke1vf*CgZ$A z*)+K+EC!5!ogPyJ73wzCmF-VFMc@Y18sG%9m-_6c^w^F(asO2w*yVbFw^4hGeU_eD zoJ$D6O*!9qp0BY1M18x3-`2pZ(%f|dT%zDf>(TGhU7TI_hOHw^D&g7Xm(d&0_k%P% z*z@7;ABKnyXRGh0 zPlyL5OQ(u3R03%jd5_1D4tBLW*TFw>6uqi&6)C$(CtBdCe)?dR--OnpkzlQZX;2_Qkl8*n$B zxB-$GNf~rZ3bucK@8K@Tj0040=+~8NXxU3Su)WF} zI>_Wo`406>YCltqa|;^{3n*5rzvJE@ER2wX3WumM-4VKbnY8k0m>)CJcl+}qq$A8T zqqVtYAU^-Tcayi=;p4lZH=Q_$l?d@8PE3%3BnY+&2xxP_Oy=9TN}kO@XwHk2F@li= z=ojD#nkrp3m!q#ik|wvIvT+k3jZZ&^H_y;t4ycXd5zVQ3Y~wW}ab>0*yT=`$hAl|8 zrYlW&)6j0IC@tVGuNkw$uM~vym&|1>4lAP!%(KeA=<=ywQQ@~@j1+tk`kD+&-LK=; zEAabbbj~t~iyU)f!4Hl|TRS>R)Co^C_74v1j`m)FJrD7}f*rX%)}}^p37Q83^Xm@{ z-=Q-z?DA_7tyq$?i}{DwMZU?G;S-1XoGqKK?ivfLRp(i zH(cQyg%J)5K?>EsIX9f3_|N{Juw*5Z9AJukP_W40w}l<$f9@U!Ul7w-lK2j%6%ehm z%TTGqM=0GBZYhZeRC10=QWkaWb2|BZfB@se0feN23-zs6-Ph--B#-ei(RY!0z11%% z#YG?L_ZqMeI-)&rUxJODjdgBl^_n!LbZW59*b>D;w2aBvyUy3oz299FlX_tM;pziR zgB$k@-kP))Shj|-;ga`hrH%`e;t2TDl+HSzN8^>^c?=8d1!7{w|TTOzxv8rZXt;z+LH3*-s*}1FP_TuB4yTd zx_h4++}ycGO)Yn(z3y&?s?dy%aG`iA+>_x7d4dE;UZcLfHP8NDQN0%g5NGMzaMG5$Vpn0c!oYT|aR+KIDAr%ddW zP%Bo#5rkvcKZw4uoAs}r3u*{Ha3yd4^v=kh+oHi%bI{8(3P;5 zwtFCUoHg-@s2_^Ddmy_yWvnHVmp;4kV*!Pu=w%rxm?7;`rbITZr0Kluh>vn6V?!({QH$|MKv1nsI8B(3$;z@=IuT-2Y7mX2;{UF1rjoab0xyHt>g`c)vudaSoccm)%}z>m(Dl7xxhR+9+Gb4J(4)w z;Vx{<`e?|qfG0rqX=c@WYk!B|$^2;$Dpc#wRoc0h=7Ft_F-jIf`Fd8PQa+U&qiNd3 z(Vd)aHMFI7LYb4th%4`YFh}cDYf#(N=P}L`3z^2`fwW)U7FkUT1)1h-^A@L?`IE0= z#x0v2D{FiHEH_+pD8@F6wT!Q3=&sK_eK5N&r>r`j)MCW(p&rh1kLs&4+*KL0)wjm1 z6&Y1m)1TfW#rg|u8ER2wSgfX|b!NPl>=iN9FeAQvZk&yLAt~UyTZib6o#|52T(W3xpr=`h2sI?4N%bLWsb^ z`jc-r(-scbOH<+O;%feEUG52c!{cTBv3Wsw`so()#*tkg>{8p6;97CY-f9V2MGs_J z3>+2=tKKgJzQbmBLn8OyaN*+UiM8uq%>^K|W?3IgU$w*ApQdW~;X0HiDgmfwue7IphsCW^>*=Pe`ek+-Syn=0EAYqy@KVx` z%3ZD%v1e}8w~~wBC$&^cs!>IUD9h73dFEqcQP{+MX{&ssR5t^uomy_pN=K84Bkwku zaJ`1h{hGMi@Tmz^!$R2Df)uU^>q5bj64U1Sr59f?T(fM# z2X3=JTS8IW?5mw!CA!MrCJbg_<&dEiAvuTjs*vGkVEPV=Zcsxs8!DnRXq(aO`-*OO zYMK=K_A+lq&RDZNdo0hmqN8#)P59UYYV|EM&uJHn%{K(sQRLTYnWbqN#Ornv?dI>M zKcBl)Fof-LO%fmX61jNJ==n0c>%CPbneOEHlu|AhL!}}{;dH9&N91S}%N@nTe(aW< z49qYmuX;wstaY<-p}r7)Tg5ZsO$Kq?z>lYsI@_xg>FT?i>uV zXazBtOq{V)XIIc385*p?iN5`x7?EVa7NN%Uz=wk;a%~~R=ErZM=&?Lc66w0E>%Crv zHN^rOWJby|%1_6RZuvfoyf_?4)#>?cMRPm^71@^98b+KYNlWvFQB9-G6F5Ne&b!jBqO zo3QNS}6^>WAo7W_8fq05n8a;zB0cAM)k+62_O;31YRsjvh zMxC)?Hf(AmEmg1Lk;fQ1X>@U6aeVW&{%cQhh0~y8Ar8{6scpuLh1pa?r?OC07D*S3 z{q0qAS+nV_S*p>#FudTTqhT)diSnoH(c0dviE<{<2i^Tjg#I-y@xubnw0tr0bevy2 zI{6vvzpUgXy$cabGg-URP>ei~`)9$3;#2y-MEV7bxc*{MPgG4U^>a0n93N5UQnhX-}Io?k%rT!OkK zS=kGF5$U$;^KIxL=pFn+WgJcwm+lNSNq*USqvY~Z3YqeQ|U!9kH+;nqv(cK z&}JEKYd(v^$JHqlt~L_UK@s_Bc=>6cirD-vljEi6UpTgN_9!4o_cD--c+uGK)B-zY zUE-SowCyD3EgXl5Nh5DeR9vx1!_ZlU# z-mPq%-gz5XiCpT!LoBRzE>#&wMvmAV*7l!VWyu+q^_qS6J_(i%+XH!CL0@Q%*EcYb z>a+fM&aompzF{i3!tW+l4E^enKAam3-wpUqmJb!#PZjKnx;AE8dm1=#Z{NL}2^)GO ze|WdqG*G>R+4>vK8!PGg%uPDF5D!m{V#~;==;-a>_@iggUrg4O5c#uhoBaut(m zDEYAAYxSrQVW}7KRc&;zOn(#Cn*bp{hKZ3I(|JRod4ai+?>5d$prg0yJa{}t{Cz;$m^!!a4jc_JK2SE=;zUHWr3zYwwCKMulKr+0E&6_qH&uQ`$^53JJDs5=i$ zD&jH*oyF0y?A;%#8ZLCkG`&MKsxqGDBYK}+@|G!@w1fudCazUxK%zrEf~l&}+3%Ul za9>wOqh$3WcaEl>hSD9pLqVudh9KHkzJQJYQ;P~NUbdk)p@NfKeKuIx={g4wGO+I; z1DnZOQDrn^?m(b*aL?B+MG6U_fF8sZ(lV8+3k)t1lV2xZS)&x4R`b3QLU8nWbR^js zmG!+(R;^Br>AC*~f%wZWvg=}MS?&3wiS{LR(PG-x1DU1%>3CiEUohO5mFg(rlM+? zCMwwev&;}~SZH=&3e;D7Bh*h)X;25T|@AHMhH!!y)$%FUNr zLztu+&mW^9T9q~RGfBYeip&-lHhTpp<{PPuqUuJ<<`V@v-mM;%z5|ZJ2jxA{akZ;2 zsZ-6Ph6M&6h%-+=UO8^a?RB%%CWCzQe0G~k&gmadi;=DXQ8aP2Wn-eA@Zn)r1ZuXg zU4A}5+E=t5om5P}6spbDNAo<^?50VFGniptUb`i~^2?hwNi#NomG{3HUoj$_k0wW)!T2$@8Lam!zE zVg9*k_9GQS8sh8?oud`iv3P!$4vk7H8^+V=?ktB-?KB&cTL0Pp(L^S`ZYy?`g~5k| zmOPG0Ix_#mje$W?V*hPt5rgjr1w==De`7JNuV`<7hD=wvde2;$PCF>>`^E1z5Dg|# zLn2x~hgV-F`+T=7wW1BvN%Tz~Nb-?o>b4-HMs7+A=lwS0lE6$`l>f1_h|m;(tQfO~ z;~`l3k=N&E>j>*vS!=Y4(7GmnxqlIfLg`gTW~!s50~YW}&6Nr}lmD5lzSA2RdGlG3Ah!sV3Zwl=A- z$jUwycfH2xkGD8hqF5JjhpSSZCaQ$9;msZ?E~OT2fn8P%L?gEj72%_*jZi6t@ggpv z;-kI4c3)DB_E0-{2EkdtI#$eMcb=1tbb^)^0dm)iN`6DR*k=-w{wJ;HAp6TDBhu+l z7>JjajhAoR?r5DDO?#Wmm-(9PN_Wqq*AyMDx@1S-#u@K6ed=mBFkXdYcp3JD(MQt(ox^b$3n%t z9PPahDKOC-+)KL-?$!>S#ic*_s+@;{`0dql9?}&rXR_HA7FZD80G@Zk+`&BSelT27 zrp3G)jjnsB#2uY5yxilTs^sFZ4EcrZEp(P`@*!b(=R0F+Dn*vI?1_{^$tbhnC1v@@Pho?(_ig|L}r z0HhrX#W0WR(Dsd#Dqax9rRj8hRxku-fM9Ka)IQ4(3jZ4{PVd=eCYGhUEjKdfaINUR z3g8P-_9J1mQo)~skOjs_)UOu~tD{LzEDDLoE%7@v=>SfK?vk3z$u>9wa5wy}AX@Y7 z&4tCiKUQ$5una4%S2h+@jG~irVxwn&wuhc}@;8z_#Fx_jvfM%_uCN=2dwbawGT$_h z)@ZvuJ7nR8Jf*+-*oUyU(58ZzB;I$9A&ho@Z-1S1l$M1gd~88!ca@%5i$qz+GclA@ z21ed$6{#5d5e)sz=uFt^EtDl$=2FjHWVIjK^X(g7Xbqa$Q3E#X_YX}ArE=3qz$lVI z;|%z1npw-@ih(7~&x`m2E?wz`yrl8XaZ8+1@bZ;t>DT?n+mNC?H_7}p_2uhpPsm|f z!nNqdfx{3*NH%ngIu~W-9hN)FhhZG}i`L5p&c%+ zOgHt){VApvJ2DY8wh)$^B>{;+ih!^$q@I9Fs0X_MH3p@AQS!L5lLnY2^RIjByJ;Rv zmm$l7c%-beVkxem+ha}svvk8eQ1;3aq^qk(kBpR+BnfBjxqPJts)KUyjp;HV`A8A7 z3CDx+Kbu^GO_A+~YB?;C z2hK$R!GV@T3&$g)hDM#$J?M7r0>|T)ZdiaTI}2^1U5ScYV^xz;wUNT*? z+5CaYqT>6_bptBtxn?CBscpe+)~35XxKt!pCD8{_j%KHRvOt_ZYM9OUbw`IVO%HGW zWHkEzwIw$?_jTeG%xUt3`aY1z4!i;Y=U+*laygryI--!}bblnC_|V z65=jj&jl#Z|C+7i$0uR(=$S2})`eD;-PK+E)djI3{)BfL9DNoOn}IYWIL)!T?t+h* zgM$t@Nv@jhu6gCWBT%*8mU6K6Qf*t(`HX^i1Nn2y)J{ueth){N{hLOmqjm=c$RM_F zq5$ef0@a(hs0RsFh$@Tb$y;o5t>bs0)^1+0I49eIc6V>XQ%(ciuT)whsbFW`9hXY_ zxot{LXN4G4oURagaxSJtbaN0PLR#PSq8UO9o zg6o#$tu1e8r3^cq}lyr-lJ&grbe7<^@#&cYWm0L&}&$5?RkNUf~O#je@UV z@TH>g+sf3&f7uaO=OPsFKu+7WVp4fncZSEk6!9f<<(umz$;n0Ud?RaSthw6LJ2T4x zyv<8-G!T0{B!^DqQayxY3I(Q-*GzO#;=b?SA`3jMBtSZm>#B$1RGm=HN~KH27Ki-@ z32Ex4yp0v@!?;Pd^pf~cN+Q8_=)2CI{a%4Gr$x|tE1y|gH)YoONB3dS1KX~}wclTq zm!qxOUCf)Kzi@3mUu$;9t6a;1fXaO|su?B%gdGGd=O+DnXCJLB zpPl7v4wz8^7)K^a8$y>faGO=bw6r|CDRX)zZzoiz@DXx$ zqnvaSzFzQvteqyVL=DF#tbm51)yp&(N9KhViR+HadGk*7?uTA zOVzSgVDWcLP}i#yh7`Qb8jc%J{4sH6tj|5UA)d6NA>ElXiLZk_GrDl^nzk)oS~6yYKAJ(z$WR8Q^kCqq^2QKoia@e$^Kq;-KOhzk9W6!Z&N~! zii;#V(F&d>Oo#aL23Pk2IPF$?u}Khlm3a$@nnY8F#;h9?o4e%x;fgeP zybj|x?u3H=6b5lrA9LUD=0HB-oW_gc8>_ZI0^Y`E(?nF)x-QeFf0j}VswOGhyrx|F z{3AmC124_(WL@l=-2EfIHRu!cO;8ln&fd5k+H6dGnia5p{E}wgBZ41FcS?;^bG9?t+ zjx`-kUuCH}hqHFFZGfF|ls+BxSily*BPOwt(2eN&@Y8v8(XT$z z50NQA*rFL7i?fT~3*rwaBUl-BN~$YhUKI;0sgxqC4hROtm{0{yS!oU~#-qIsZvb(#)e~p|VZC>;=x7Ub(;qQ146G zWu#D#_N1RQNJHv2gq_OG@2+V~$3<=|2YFFgi4MU!`)?CT&lO^f&DewJHU=1nX@$}r zO$P>aO=q-oPZ04ji^$a;CDuuxgOA?ag%|-Jt+Vkt6O^{;$)yxOI%^$^qWxGT72r*6 z#)a1e-zvVt`#3#8_jaXO{*E!7tEI1gY-ljL=ZD}}`h4#~tGtSO=x|9^_>>)Kv}cia zQ1xnvBPo93_KUNab=-MyV~f>tVBF-y!q#5AseR?%#Nk`JOp~-z+hD=iX14l+KvuXc zm-?^64GUJI$@gWCp210|<3pFCJf(!3oh@TnkoA5poyH&}dT*IQFs5B;By77SC&s+W zX@vnY3i4DZ5He7+?Z#vt45G}#m^G>9C{{#HwRpHKrdv{+eU$L4ZYD}kC^y}h*BBH0 z-Eo{n+eBo^0P7YM0zw>m_q=dO+5R}z+;xA~e5_K&m@}#SdN_3|&A#f<=pq4Y4wiq$eL(YeHO=aY-xQgG;prmecS0-sU9vG3IECBfzu z6!aBO$*(gi?|0*y=XmLikRIpX2-hqiigI09fp8tx6+r2UotGTQ`^%;Xu2}d&Q&Dmw(Y>PTx-~Hu#)MJNgL4)lYkbXv=5A z6%L>Lz%>G?0yeJ%MFQ>|3_f!5)RC2=Hd*}ZTeKDm8?C?PX74f%)Tyeb8%^s166xF0 zTnj}>SDnb*SKBOtAVJp5I!n!pP1DXqL9tZF)MbE=4=TWnd7 zeo$T`J|qg9n)zN&?yOhVQ)Av7keyP9$Fptd?cVKt>`X#`t9H|_NBZo_&ifmTB+g|M$NEPsxIWuAdPoFu4YvKf| z_6;P<%)&@|1{grOE2h^><3B^>u@*_+=pSJ?_Yhcc0Fnm_xcFf_l>lymtdLindlUpK zQ$b7M1eZ14JYSE4F`dVa=fCpFy-%92)Vi2J-wAVT>waiwlM5~MJg(QBzeftxHK7V0 zN<5=tTW41452Koi1~0LcOe2ADY}CwHjwLj`q6uQc$G!X=b zE<%)X>;7Qk+uWmvd|AWM)nNsWJqwQ92ZNuQ3`Ob*Hi3{Gd{RTK6K^@~UK8L^u95N1 z3{qcWH)+ba!)LsXmR7O1>{Cb74xCx9_Jk1l8M-qD7?yU-s!iBHvM3|cP>4(08_A7F zUy;FXWR>`=UWtzLK`Mva;JiP=PkB%;p|J^9DkUj(OfJVtkWMFBfZU3Jdx-j(`U}2W ztQ2|c#}hymP0}%qM%u8%rvLqj{Pc}i!Fw|CL{GCgG5A?9l{n)lE&l4I>kyp5NQ=x%)#=4oz|y1jLI- zzJV2^_`dK?vJb2~7wvw1Q${E;xY&EXK*3JlCZ7=~lKtq+%lG&z2upzA2D+Sd6u+$4 zy1I@6eY!z9OnI8%ac%cyQffyU2XtK@>_*nNzq_^x?dr22KY|k^9lv*5x zXYRbC*Vs_Er6dwmZN1{UVFEOpp%W+mb(|y)f)arKu#UOjceM)T<{ylRQ>kagzb`hv zar6?PV*0}D1a+sQ+7;N;aC{)(>jh8ppX>N|vY`Zi8Q^>XO^BTj@xHWKsA`^`$9lDH z(1s*b{oAaTiZXqy%G&D-TfO3$T8?i~09Wsl_eix$OszVu>^HpC_)~Hk6UR*sni67> z8Bft}NsnS*&d%wetcW{`1eb^A_%GkBUV;}}V*`EFMsH#D8%N)YXBl)+sxF}Ue_dlK z@Pil|55+FenvK*BNm+yhYQG;H@}VhIz~glRO^O&=FgAN}xJvlA&7XN%9t4lO;tE5J zt$@uWzD+NVmWcyX!Bshg(h&QL}!AT-KnS$Mxf@}jjsKG89;-a19={i&6GLiWa z+c5xpz(Wz+odb8MSy3rvLo!F=W8k;QP_l|1`e?l$k)fV$Tkpzu-P2CyJb*){iE+@A zcun?eO&)Z3pfy`EVh3r$x?`Xxy|TOv{1?hxii=829(DQi zZ9f4Ya_R1eahKR|vs*ER5?sx+8}h&AK%zWbK-AL%!}mr+F$~=A)CnG5uFqcgH$d3U z*x8+sYQ8+8S>)8$U^jcGMN=W+nDJNz?k*s*6(H{v0jP^R zgSHr{)Uk@5kdxWI0k(&t-M|`!vB>!%A1e!92PD zXj3AADOZ}e0N*3oryt!x&d}H_a@}3|%<4)C^4V&oATS@~720w2%7_|ixqRYd_s@|g3iOe{6X%Fv=?@oEQG?@T6tGzmBP>m4%i zf+(I8m7!4}%Uq_!{6{u>VHXmdnkVIU^5=`h9S=b?+%tu`Pw&mgw!E(yGlZO(9-@wnN2eX>p?2P6iXy5af&!jPi zsW=%I-&UhSBDA4DAt9iyuTKtdVr;|%#F!K1xp=EX*dy;T1V-t2O5{JUv2?7^zi{%{ zpFc8J-wQ5{fK+{RC9mPPpZTou=U&YXGVza4x3M$F*(PlK=0|t$#=8X0m>Jke| z2b|zn>K1OzYJ!_d?X;Nnke-=n!C3@PLemDcGq!XEw!ch ztOI{d$+-^dJC(D6BPfK$B?`aLKOe92-?(L`;|#Y9E#r`TtN-Pu)xHtispWDh>cyd# zB9O4v7b^N-C`ljp-iM`-!lx{3xbMeX%+Q6BUp1jfZ?iKWMw)ifKpgP zfQV$`s?)UJ`|}3eDzNsh=Ffq4e=j^sToEYM9uO?V(WlRaBp~_)43}7cZZi&_+Mwzk zN~sn~xAG2Vk_L){tFrlx;1`TKsBM>NZ^pgRzr+)$K^6q&E*xua3dq`ib>)3M_5jVh zsko%6Y9eU)4pPrU*#xv;xtR$qZwq@iM3F!ml{D!yA@_>b)wsqB(&s$&&&;BlVkXe@Lc4D)?@|UWyGI2qGv= zWzEF?yk<x+)0~@)cg8Q?9?MN&V=u2K=;+-60 zGVyQIzM_I)?&(%UCpmMXqV)GAX{Zr4> zNmy$m8xW-%dHwi+_+yb5^O^Y+{_*M)VsJxV56F;g40-+E|29!qxXc*0lezC_?jTzk zgtU47#!PKn?#waEX@cYcwHH4tD%0wk8My*+J895(Mj<|Ry?2WkLC_HojK|jnx`p7I zYPp&aTL|(p{Pu%vlD7c1j9r0-+vNQd6O7`n&{1T@u|m-f`uBw^l3YOE*Dg@}>`{;y z?)kmF^2LnI-a*a-?U>b?Q_nHz)VrXEyrtH~+svZYWsW6&U&_@~&A{pk^4mSpIW#IFDmL_H*C;zi(*5 z#Y#Mp0$C>bboAknfL&skg(OlmCdFh5+;A=YelJejXdW~9d(r8bH4n0a@86Sz3801V z&x!wD=*>|&=ZBSFn|H-R6_S2eLGs_O_g`xK8{28Uu8Wn^nK3QIH+9pe4iuH6bSAhEBL0lmNS7YWI++KS1w{>}&`Qh7vIsIf=}M!v z%<5+E-;2GS$|TX0uHN3>WV)GACIr6`Z z8NB%a&)D|=K8jyTr}RINQCn-}US%PdBqE!k&6lphliJ_k|D!8VQdATWtK^(mVxFhW z{@S6!{(kfKpR){y4j$LL3gN2}hW&A~F_wN(Y=%;7a@m)e!<)K>h6-U}cbF|}`I5wk zis{dvV|!;~TPL(mZWE;4%twDCJw)%p%;8;M&J#h$zhq>*c7ina1R57tCj_lDX^ut{ z0TB@)GlciqeWx0ep_S%C@1AFkLxkP{Hp#5JcJ0-KZAKS#${zGMT)^KAw6#S?{jye9 z{Z>1Z9N@e;JtFqA*YCFxBLl;f&(JSR@0pmZ^Ouu4VN`oo))zvgKOl!{8W|oI_GA3c zNz+L6%h16}Z1iA*O{!V`VyL@g@k#_Wt z*G|5AIMiDSS+94dw+bFV)+L-e7FRmdIl6ILF&k&cjfnEkr@~nnRO=S}8K^y;zpTc3z0-jtz_9g`y<3?dn=O zXBQUZGx<9u^fK?_t`FkMMMRt$N8dt@>7dWjT#T`!<7cX?unut>t|QwSoO18py&aij z5sUqrEsh6g%woJ^EcjAh`O(^Xn-H$WKGw z@7eYGWS(ivy@xPczyJ8PZKUkJvX6=M=Yga`=<6Wdim_|XzB%$m-_Ng>=NtrdFI5eg z!YdgXtGJO1m|5o_0aH0!P^E8aSpcygVbdoX78VxK(Jh}`rMuhPlg}4c8x~eC-6QOx zXT5s!Owu4qa(-#<{XHl}2nY%;Hf#|wEJ3W4OuW>qIlgBD>QtAX7y^u&=rjP3i;U!|?=C>>^E?$yOnAMzVi%)?Vy)2IP8s7iC->;9}^A(dsi0SDuY&s=&b@IqiRE&_jIWm??xJq|_{77ufSHFf^b)A*}Wdc!t zlV1dz9_k1`U}rv6HT1iHk>dwMSaND=ERP>Q{_WRqDDmB~^c>lkZ(bo@JsnE8ZVy0Z zn3{ro6{kqzGs0IRa zlDp-u7}r~CSGj-I<)m$=@mo>W9GlGwVTW+kYERh@ctb=;g+0p3QhzJ=E3XE>NGlpd z_rh~f7xnr~C#J`lCgQ%XE|nyeveV2U65FtNFVs_(dM`Q% z{^`H`cKT55&xq8HM-O4^ExW$<-5X{w!50p@)5t9N6SE4c&nIw6iHV7(&peC&{Q0sz z=y0Ita_{^1*>HP(l%B5Q2aDMg4q}&x03~I?$8OUwJvDV30tyHDStD}F%Z){r%w(r3#(ii4cAjM-1f~=MtrOC_7G(#Z-%vu!9PX!=+W@iU%w_U zRs2X=|C!_s2lNxG`>i|%+~QyvlMUG|&3Di`bc6DPX;69bQYUOG7CroyJyyp!)*qQ& ztk}CZ?xJ(bOg(ugjH%AW#>7n3Q*y9<5Nd)hT^^(`b5l|jbsu}W;){t%hYZuV*6Mt3 zK{tN>;AsZD5ccvPCO_x=Dmg~zfrZyZEG`hTo>d6oPoN1RD9;{e>7D)1dxl@w@|kfo z#55nl>i+diOYy_1`T2_$a8So;?}Q@FBg9z2zXii&!^^85DNbB}K2p^4Q1k4)%+h@w zaH4Vh=vX!l$wWOJov4cy6HL|64i@0!yUp`^eQvFD{|oyN|{SY*6xNTCw7_f<4q9YwTx zt^7NgXn2K;nSbdO6uCM->+4P*Ex25MX@dHPx9o>9r^w`FPN;39V9$Ed+FD{?0rB%a zd3q0_X^?7K>fnh71%b&RxROvnwlH$duG;JSC#F_tTSF|6DL>hvJ7@2jRknV^z`y|4 z4I4*C$EXWAp%7Gt4nUFbZ}0N*@?=aM<0^OIxw*MUgWNpG_mulA@2^?=c9gI_fVxKC zGp~|%)=Yt3es1m!5EuxyEDR|tE7P`&!a;l(@|{8&5ijET1~!PaOpslF)L&cV!!LbTkn)+1D zYGsAX*e0m4Z>zQx*-p5{K=&bUAs#a7<*yE$6=k`7|GrtK!Dy}kd`@7qqhx5v^zGX> z_9`Dy5(5)c>Z3;*=H_;Yw=Z75&R>8xhlu4wl*~*uH&^)Y$%zTsrJQcFEurhjt#iB1&AKa(1jcGHf9maM$}$G&>i2( zA!p8#3ul*9@5LF2&_p-c!c2tlHwbhzyh{Q1ggQ9wI8U|jA!ObmZlerwQc-MjE(VHT z94d{%zHJ;VM|od02Dr(;9BxVS`*S!tI=Tpc(^AsXr|`TMmY3Dl)Pl<$VksyoZQ>le3( z2#wj(3v`8CFeBnc>~Thx(^Y82fh}JRVnBodG*W;O)Qmn;oCBvKb<4zIU!s(o2WKXm zKWjgYD_yfy6Lb2jpu1)Rrwtft%NOAjy5|opt-&ae3ND07a3pTpL&_8hfR3=z(Ym<$ zG&VilaC_ECjthN7ifj!K@Zng4mwEI%KE~ggBF1)|sF`huf%a_>=>bUyGT$yO~Y7Z|j zFQ#7}uC9Sv8Q0;RhTGr!q}ex$eevGp__#5T1qSXWK6W?f>xI_|2PjXRII)6o*|?{f z#rCBCSu@+W$MIc+9SJ9%7PKgoD(bBjU^fQKYLWtr-dU(0Zr;3E0ai)~kA#61Csxol zR*AYlzkhv&skjMGC^R{Y&SaK^ysx=>gnG*su`4UiuG8-}!d|`M_8#R0$XnXtTZ$e( z7U-nj$It)r)K1a8%34RDkqSxLLC>*>tZylWuBrU8vbzau0=eHm^axu6NFyqno3qXI z7Dm2!@!}HYCck*-dlE|%8b`{`&PCdCa7;>RI%d~PMM447o^N&tYCjtgI0)TV+8t(y z2yi%u=;}jp%~E1ao5C1ZPyz_OdhNYD9|6mu`lcq;72S`e=Z)B;T{puugK#BMJukDs zLsgYSn1c~F1A`Y!z5~2{p_}2|WdOxd3<#!v5TwpErVJ-PecE^7PVr<41exszpB;wu z2k&+=5`60ESXeg0rx31L>TJGy*eBvwm%rdvG*a%LI|pm}Aj4cj*F_ZSQZ6eAQgH2n z2@#KL)#B1pGj^bnxjCVnpED+~tCL$>P$q<6#1po9SF^)+XNOVlV|Y_4<{O5G=VEy} zB2tq4VU#)g{jGcpWL5*m)us*W-*!T~^cHlb$oxfvM2!hSQU)%HoSTB1_D*V5bX}7 zO9lMPuQd&p8Gm*7-BL(RgF+OmXeaPhJ0JRxE(eAQBVmD3nRB) zJ-Ddz{^Lhwfmlc@F{x1CwgNXExubdolo_ z6p<~^WC{kN#Q?q#CCDSazc7hdZoQ#$9UesC$~UPXBm;3e;U_aU!^4$f-9#FOwi^_J zpH6Ybz*`h;B;ng}Q#lQO?fG`^Kj>u62NK%bqHq^Y8)ABrEOxSiD0 zq=G*nzA+*`o+Z38mT-e`b$z1BYz0|Byk*2Kr`v(}g*@|x7FEFzI5p<^l)yZ1$fHcZ5bbyq$t5WEYY%a_X%~boC!U z?t*oyU9`GsJ`=*=#M4pX>Imo}rZDQ+2}tid5K!-r2gM~Ue4H)EH3=iRapOir724)6 z_hF58Ptwsrr!YC0R9sx#@awEs{*~9kTX&uk6TAMC1@VM##}2*exfo=pYS>IVko;0? z+C(n;+u3ISf%V&V4;8rNDZ6@j~7-4JKgue;Sjk+Urhcq8#-G*rs_}=DqTT8;jhx?z!#ngOK;W7UXF+grHv5rwM zWfi3@7rs9o^qv(y_CQMKk?r04_rqauu_xiIq4zFimZ1?5SM9?;y}QMB_K_;MwrcqEPVc$~B5a#bc}E z)RC$RO=@+Bg{ABAV;6^URSYc+4Gk}B>c|!FvbnjrJxTzjEBL1I$w^+JxUBN>cp^YV zYh|2vbUY5WzO?I<0<1VxRMLBA&tdy)a9LelCEN}*Am09Q3d-Qy*k$5pdh(AN8XEFM zY1pqUjHGuv+z5pWXc!4$v@FmK`SwYet~7|#=|D~V9NwX#;yT($MXmtdJQbB6298*7Ow7#mlH{%m&A5FTObp(>TR_MUa^V#IkiS$`Q4vqLiPgm0 zcq0@E*c5iTCw#e^N%!RaYKqwC=oH!6+403MA&&_=)pOWZDEzThZ-fd|d*HgCpm4Hz z|LhOq{r;G00SGY$_HNI;w-$5X)pwdfy4IC?BCDSvq;(OlzjP#1$OWD&HH~ha_yHiA zo=ykGPRLTUVZ1^|M|h>><>dwbO4S!QH~7peEeS_pz!k zHGc} zOOQgWFh4->YtW{uEu!Oiz!g7*x6YZU=G&OhXBedGij_i37DK6Qx{~_@IcI2@B9@XtXF9Kz_D{f5sjMofUb1r#-mJN zrfX5<9x>lv!M&XdMi&sSHRG{tgz)C) zzM(SZ+wbdurOPiT_Yex$jeF`lYdk~*Pq0HUOp{#|W&$Kud0&~tBObR%+6oFJIywwD z+=}n2R%1*$;Ri^>veQmZCrNxmTu z1S{#vLRIlub@e&Ova6id+K-Y>$JtpF(;T90sX!*93kyY1(rd$Bkt`Xzr2v$9@AxBa z*>~vBA!%s40&0}@U6aC`kH8+q#TIaEA2(bcsA*`j@Ze05ags6eCULkQ!vpLov^t4! z43JY5OE3lw8jc^IW+2C>lD{o;Aqh(a7ETpaRh=~QYn(ilTD+0OTM^_5gGYQmH8u4` zQ&W(C4sT@J+c;u`UcO9027Vhe5}Q+ak5KNj@eU}_zG!Y%TZ!U6a^ya4e*d$(*v~eT zP`}beO@BXzG@951R8A+zNF(JwEG5-G{_@W8T_WmsFVj$o(vn8LsA_A|0;GHZ^N5$$ zqV0&i2ojr@y&yH*h1?jJ0Vh`~iaL5yrT3x$9o^NR6LI5nbI1Jt{N$xeC`i%Dp!fAZ zP#a8KII>ahfO_qHUKIWa$68P*#a$A?nb>e(Y^QH-ehh9V$*cz*ZmXs3fr(3$3?6f) zwA+j}M0w$HVb(BfBoO-!6D9C!yx+}MI5=QebwH_i(7xTDeIGAx2vq)^g+1o``JWYN znIZ53kLyUiDYmrc{B5ecDQU)vuF&io3TyAN@s2c~2jd;pKFga))$kQyU}e?9pb){> zkmHk8ub!^%)WXPf*NIn*HUl(rEB++C+`YxG=y^Y--^$9$lG3+}jFv&HV=z^Ny)X6K zd~_CV2GkE{A~oEx@FQ9srCcUtnN4H1?Us(gO~B?6>Epg5M~;kak&Vg@dI8y3K6&}t zV}jl9s6wGyLF^FNF{ozg6X-?gZ>VTYwVoDVMS&@VDCUz}dsj6F0`&eZk z3@xy#JwdX^gH_Qlz3T1h*$(g^XyV<=G+aa6xpS*1OX(NvU#7hi)`jnlDv7uuB@@+G zN7=D~YT0+6d5WDZT7w7sHk5?vNPDu?RATPk6X>V>Ui}LnMsj(BFx9<~B@??h5(pfR zOfUQI-)i!V%PB{g(*?w}4LN3pfh`tX7AR;~SU zTLK2FDl4fc7$YXXJzE4i^}iy-%Cd zgHO!)hH~XIkahor$@ammQAp>SvV z_!C|*kP6)bhtcqF>aln3Y{=H9_VMwtxqgdk$3A>e!*dN1w&m`hSxInpqd0W2UjeDd z$d@mX7%4@8Sfvyk(3ahe=xtZ<6GqGnk$!8+#+YBe+4d%GvpuEpE9n3`ii(TrZjIO= zHHlq*kHycD7yL}26 zrKKq;uSOQzo7D~ITwTWq5P%tUF$LkUQ*^#}|DH|pnMoYtr#Iu5-+~7AaP9hU5p2+= z-UlL^)`C_wWg;A7mY$RuF(Of7fq4Rq3PT82C!|%dx{jyyi>6`_kmk62D(A=3*88E! zsf&U~GQ)Zfutr2ypA?JLGB{H-KB~LnnNjy0wg6*$dp?vIVOW`|FcgoM_mcw*BhZ+k z%a5`*n5diymqTo$a22;a(-4fuMQC`hpmQj+DacPB9S3ICLl?KAA=m#Mko;DlCiLu( z&Td2-keXyaR3nQWun10yPwYF$kx2&B*2<$E(4Ce&Bq)2w(JNiIwU9<7lj_iE@dQ;b zuh7kCjkf(3V~t>1E`H`it$)R;(7fV0GPe|+G&POm#~In-F$BEyIUamtt|-cH6~J?t z{gyVz?@1^k^F8rU<_2mt0(X#dow`lC;aJH!S?11d@;}FS5cZ6KA{!*xW4#8D3)!4$ zR-b@_DT%4XU?S$g26F@12wQJ9O!K~S7jBg5w=noN4S`gMGQzrgdO;$Uu)KMWIV*fi z@bKZCr4HQ7sG?>UnMu`j&v&2rvclF1)7pKL$3M@XRKFbj}l1U&<@6Q6YLGMw} zF+tY=v+p?)IiXjLt#3bK+YX0EsVyiWL~TyEGPljEt4R4Q34taO0jL!wgTt`AGKNkw z5?0jadoG;CCPYA1$XVU4tbJ`^+$YQaY31u!XlQ61;v5+XU=&ybtE;CLhU*)iTZ_Uc zi-Sa{sGFBNlffdX8NucDg9lqVI5=Q5xdA&mVgHS$Wzbbp=II#EGfg2kA|uP}UtY!@ z07oX+B9rQrlis2hZp1naGSoklbu!5}b+Q{Pd1PiL481gKjBo=X+-?8i3BO^U@gB<{ z#3k<0aXMQ}ed+_ep-94r35N)+oYkqAp-Xim2s=NSXlYJ7l-MCL9twPAgXnS1iv%Tx zfT^*GY$5>+Oa@*>xTiPizefcQgG?0{7cl}y#}c=OSxID9Ln;!9qS8`TNYbw^eGbQr zv3ZxSIqG0w_+HHJ^y$r$^c);Cf1PB#m*#HZMmB#;fQ?H~FDIbUM`zDCIniY6hasa# z+1QNS=_Wv_Jz@u3r?g=UixQU(IcU4R1bQeU)^>J5z`B4mZ6MuZmo+_8iE!hyb(iE; zOjT9n@u8au@m_$}V)pHvaLqC6D$IFx>m0<_`%2FAvW#d=hyVK2n-3aMJtEo4=-lmbpj>MxZQWIw_rCB zi;xKJ*|%>K$r&wUsJ?4?UJMQi87p}!rwr3F(l9d97q4C^rKv@b;^|dk9o1yz_j@Ck zl8Ooi3|S(Oo}}d2V)VO=BZ&hAzDe))c7@wn~x6cFhd2 zDx_c+y)U*TFhW+sF)+3@{B~H`k&<%D^6@p%w?%gD*s60Zt1D>%7^lM{+^j3R4e{j#C{m=`adFIqmy!SD4QH@J zn&zDyJnP_)qx$ptEq-{hwH;32(91kV_Y?q3i@3{oZb?bQM@Aor>=OkQOx2Kt2E!~( z8DGm=YAW0&&V&LR;37}9zLsuw49YD2efxq#k9B61IdlVNc%+l|s_m(vwzdKyI(Nb` zH55pQD_7yU(D3xeu>hk&v?Go8aXFx-N+8QW>eDBN#1mYE)9240#d}HZu!d4ag2X&( z@P6|7rnY_J+j`8iPV9dC_;D(3>fMj&PAY|<1GaY$S-Vf0n7rPQV`OK#{B2X)Ex2m{ zQ_&TOh54oi;NmB4vxejfm`^IFSsOpRd2@?_dLt@e#IQ8jWph1do9n;O7B6<%)>awi zoKix9SKZt@8mt3{{&F$&bv>At<3r*5c7s4(NSHlg_yW|TiYyw^s4z{-E*>Wlm84Qi zG9=x%l)Q5&HDx_~i3c?>EP@HtrsT|P`lmGha0TKK+7Y{3^kZk|9jt7k8YdAwVxcoT zBf`VEJv=~8DE(&A%ZW=waRivcGBljBe;*ebQoG2Ke=UD8i`hZv z2m4FxH$c8X;<32XqN!<+=hJT#l$z=gB&MSTYls*GBI)O-MbOq z8+NA2@pN<-2cJ<9`#q-}7ts!T@Zf>Kv+WfX6&gp629%X8+t$W~%g)7=UxnwlI4oF<0mIJ<{8|i8{iM!ll|QPfhqq+uW3W zoUNB-x;2L?o?e5Dj4U3ADH;h*bUuRsl5fIrEu;S;^90O8pue7KL^c=us*+c-Q zSFWttMizhNYkL`jz%_<#b5zuJPOJ~1zs>qbIuE^Og%#V!C+E2L(}(V$y;Q+QG%@W? zrl#6@_W-RB*j=K^6{WxO2b88^^f~rF9iE!vyUDotLbbPVy&Q+ z3Y2#n+|QIF*<~9Ik_3a4zP6tyk1sfC=k{c(cCE2&uk^PJB~a z=tMTcQh6wm+~2&Tep6Nz`7QudUXtF?MD!eqW*gk?>#zfVg)LinkEbstx!FX5A!!)d zCt-zwj?T6^iSA{zP6XFff1lg3ZJR1q4lN^N5P~?>1{d*WOJ9WQt8-tE_O0I{da!uw zBg1@F^oXJo5^f-)89^aHXJkjz7+acOayLKZ0-)(S*VmDH0m;P_aLbyN(Jh2+*l3&_ z@N~2$^ii|+Tagg)0QFm+J!>>C;;Iq|tXzYKKKvrzr|B!N2k6kk4k{b;Zat-NETEo* zoE?4>=w+clY$D-!h-GU-tqO&clM}L^nCTNXa%#kLnzR;Wf!#3v?L5}J4K0nj&d$!% z6JCf)h``%nv#pfYVU3PfgG3{d7SaIhkaC-0K#m-QnzR9!JZ$Dh9p?6agME!#X$cApBpQB{+u2CgGxU-$IU?HV2m#2A6wzC2%2SvBv%>u#G4U&MuLc;U z5SbkE!Jrj{FrBiC7SBKheq>Q4$tq#*kC=~C=3qYxu_sPL>_qBVcWuL0aQ2KP#LAvN zZN`?UgZvHb8rFh>f_S;B(xF6Wct^A~vdU&`qAuUYHIaPum%D86Ki89hJ-QyiF;ZY6 zS3{wqt*vcc9ElLejv4yMs#Xr@Krl)p)3y)#4>8jl(2hn|p72{L0$|E4{b!@?&Em6J zKve7pDi8ABvLq9TrN*QhJ%!Ha`UVsyeV5yxoYT|D&?Qn3fBu9g=Q{VX9lk^X_^$=~ zFx}3bH{jnwPjUvhc?DeHzG|OCXeZr%_;5S6a;!;m67aSF)QvHK+{dW)!Vh$Wz|uD*4* zG=p?vK|{UAPGqCF-J7yzs2%1G!=0VT8i4}>Su28bJK-Z`kFZm!_cmm!gx8@>Ya-#`K(oVoAA2l&C;06<*S9en`v=B*4ws zxNjrt@7jIPfdPdyMX6~75+)W5x)Oc9jF^}hF~!wxvXGHrpRJAD|~eZh)5ZD{Jz?(DW{J`_ZmKNp0-ZZ<`yG#@Rg9qS} zC`l_nf0}d^mzD-u7MAe|I%1S=Yh@5EsO`I@DM-Y%07zQ^4l|NpHb|de|DP+LGa-tH zxAj08Y$RBTMMphAnEDvaZ#@Ou&k%iqCRD1<)9>~o*QUg}C5j(9R@N}oK?1MuojHGA zaKC`EKNN0s(@%H_Ww{M-Jr=;BI*S+cJU3wG6nXt z1$Lt(Yu4G#qOWJ%(Mo%lTR%9+j+FN~q8=S1<3_HA8#{OjdJMsqL64kiF;_rBf&rn= zj$WNaumez&BHELa;4O6xbx*j%-+RTsd_E9iOfLrQNQA;v*u@aDw`Tp1&&tXQCvqr& z=R0PE&C6+FEUbi>29}9fSuHU z@p1uYhS+?7XdQAIYy=9E+x59E53!bD0K{nRCFmML7L^QWDUn0dzMX_3LJ6Qc;mO-^ zFSEX~3d|kst@W>7QKRHl2al#0R;w=E0-7gJwh$~5w9CSjN&cX&q+mT6gYXc#8MZhL z0F0Wt|7U3J=yU8B=$3R7z%3xq0(1|MrYf&7ZrrOH~sdaY@ zzkhrnXQLZk$or#tYfb@JPYrM0Y)9S4z`O-Bi$mJ?whEV*{WF0s2e%-L0ko2k3^g_} zvF+YHg4AmNnST>mZ0X+c#qF$325&_W{n zbNlRnxd1K%4Dt6ZhMPRh{`+UV!1xcL_|KxWsDQYUposty3o?I=KA3&bioq%*+7MFi@$Q71#QAbre0m?5|^Wf$jjq`6#z(im-!TMT-R+vnt6l zQUf2%8foA5-k}@B_+a)>z^nXwwB17@D$PN*?L#8|j*F(w1w#zCHAtk&{tM&0P4$Ci z?BXK3LyA>G9P+D_ZEQo<(r5X~uWlhF7ZnFMF5YX9JWBm7YKPxW!=)21Y8khjS7$EY zShF$PoUHok=ADyi+A%J>ntmSEIO0o78fI$WM7`_C)TNT!S3f@}60Tx(&`# z3{q;XNZI{b=553{F1;GNOAM2xG=AAAm*KUwM&tg~FSRMI?g4FDH}a+qD76{u-Ym~= zwQi5AD^PPhZ7FlBDl2mH*PGv4ZoB;9o4YdG@M@6i>k&h$vAsLPN<%-cZh2wvU+pA& zT0Ke8p-awY;MDQ`^ADu2rx(d{mKZA8*wSS8$GnI#F;Px=8f0k}I(PnTkQ*sET_fO0 z?UM2x2AU%r^5eYCBRw^*Nu=y!+e@pM^XAxykA9xth`*#$ZzL&j-61~RW*YRPB#JYj z=0~Q>uRhRKHT*gqo$|1xG~gPFMl5zq>a^m;Y_m|{M)n) z_U$n+z#P-a|2M&ld*6;-l_s#%hvK%HVwXlmxF=Wb7&7;AS@)NX3gofvWd5U6nq1(# z#eQ2|OqW>X#u&E=2K|DEj|MAukrbv!ug&`9`JZil18AyEqR+cGIL(Tis8e=csNao$e7> zSxciK)eV;IFUU)zv9OfP+igB<{E=g?Dl1lnbKYmC;)k(`-2LQ3*NfB3+lukxi)XHE z5y9(QsLgz&x*f?aE=oQwco^I=WHD*ZDj8xnY)0~rzAnR%J}6O|DbRGqJTf(1l;eHx z8)8Ia&D>n#iM2Zy+wymXi|7yL8;}1u@WwifqEV5+&o2o4JGiGLSF0a~+H(IG_ zD%MD~v0rO5H5tjX6%RUS&MFabR#5LKcS`>&R+9C^aA4(z=HztkfVFffp1Fa*drmaL ziDevk@*VC}!KVfe>`edgs8i`o{$nAY)}~i4VjNh)OG#0p`|nu#tXFKc1Z!gRQt1r$ zr?RG^?@K;;fvkVSQR_`Vc4AqXGfYl${_fXly!dlxubIwZ|wYP%Q1=v*g95 zg1CAhO`i|ZhV9ar2)F!nrPKun3$7>yuHrWKor`Yl3 zGD$m+S%~~CmMnScx&Bly8xZ+l+e6u1yN|e|p&KZL2r3c_aBJ&a=azx{2Nhn(hotez zs+tGMs(kiMv!47NT)vXBRXRWW$cG_|r$Tf;RD*8wci+}%m6VpW59f?}xyK+Tk-yEp z{kd_TkAp>VnD|BR5&2!i>n|myzA!5kJjou8Kb{|weraR6pGQfqK)`%WwvWZek5^g5 zS&sEiiS-rY9el>nO z=i%#?jTJegw&V-#w!ZP=W4yBDH|Fa7$0Box#oxEQD{r@j%@;Exw!dkMkDcuOlL5Fk zV}5~N2V!$tlpILWywy@Y8+Y61xA@If`jq>I(=j(x1cHt}|CFI+>36S-;`D=Gdgf~% zbo%=0^QX;5M|-cA-q|%nld#!VvsmhHX1}C0Hcsbb16F#9VXlpx!PEOHii%{Q&UDR$ z`9bh>>!u9=s+t|D{>~04a6=nukEEqXOr|Wh$c>H9UyHrsiu}1jSuf*K&^3irPXMF87U1b35@+ ziFBcBmjwHwd_1Ywzh_i{m^;Yem;&qqAa7p!84yQ7S8pw99J4b*jg}6nG95krDdOE4Cr$)+*f;KS zdPb&s_`o7iVxqDFtsHGEh7b<#?F!vXWbwBK>?O$gd@MHwkO5`T&eor>YxG|LGM{XHA4!nrc}cZ?*44#pTKEIQ5`ia^^T+EKTLT ztvkij^@Z=CaxxNe z-Xt=ThCtkilK`!)TTrU)=-J>8Si0AVUCl+dx`d`~KG1%}o^r;t0;(015%15#HlFj3c;;XnhI2lDyDIIzLOXa5;T$8DhY5(jxuPAdJpV<}&ZvP#170|Rc_^ZV;V zAhBQQcwGpfMhQnY8qks<8mOS8JqI(x>gpmRZVl_2jD*9F&jYD;v{$;FM=O^gVxRy9 zqn!Tf&)LFS9R1l%+#J{iBje+ND1x`RG+PFCy;xVcbI*T#VO`ngL%?LNiDt^C(-M2# zT6fgiGE(d2_5>|^iQZ*UE)=F`-aw+hIHc4Qd#9oHT)yUWs+6yrSJrkdaJ-tqN_ z(b$LPAPt1rCe}`$U=v?mwgRVLjAHkh_AI`w&Qu)#w>O9*_YkR`?JXR`H8rCY*3s7X z|MA0hYSH^xqBNubxhoHdRxJ3PVA3jq%YDJov7_Yd$&|%yB%(=ab>-{E?QBy1Xzp3@ zQIY`FJvraI-Nwd7$pnNm)PlhI5LObmhtP1Sfo+*Z!y$HxLhTmY4RjjOZgHLM*#_L= zN#8nt_t%e3wJGW86n<-8DM40TAI7&*YM1^U@tQxY=h3j*0FI5nTAJd0Nk>4an~2UX zfjR<|A^PD#O4sl;=uY1_q_a16;66@S4<~vIDx$R=6&Dw>wswU860ffQ$QCWW6BkFB za4Z;|P)1b#jIWY@tlq%!-i@H>5Wpvb>|G%f7#!28sH=zPo&r`(xMx4T@SYq&`?07*R2FzBL z&$UksDEEJ9janFbP2|h^0zcDQUpMEk|Jl`T>ZVw&IJU>=Js1C6r0!QCo*>77lP#8y zj@YyPSl$xlzLrdTmWY!+CeGhNtAG5TcxWWrE*nWjz@LaQv2DJ2?byD6`}cPd@ThsU zHzOuI?z3Q5Z?5_Q#Rs9pgjORB5=^YlCzPXI}CK+SDV!O%HCAt#)%#(Gcz-^(AyG^ zFavus2ChGSoT_c099V^LWt8m8MZuFG#lS8;@G^07h5)GnrG`0>qwUdvW^)Iqngo37 z_>l>dqqLkAq~03W;6X>SEOM@rDqMa$n^wWtriC|_X~-~VUPBRBKDhTP*Fhrh-JNpmV8ujUE)Le%V{tUqW@k>;B$72c&d z65qA@D@e&}WPqVR{IG}+GjjK_D-0yP<*FxRlu>cC8yww(ov-W-Voj-OGo>oabfQ|n z%ZsAAU)I)psF3=G{-!TWUs6XxtQ5FP*tQM(_UtZ~u-{}>XnNZucbI8~iTVrA22N7u z`MCu(};OMsF^A_1*#ul4i0 z$u7%^_8>8O2n7gr6eQvtB|&RIh#s+-zo=i?YJ#90v>um59Jx7uya}6yGurytQbq!3 zfWrW|*OUuGyuha9)>vFgqY2o|#662=?Ebg?bYmSZk+3%%~ zM3BJoy^hS|y9m~esO->AAEawt^GE0}l?pp7@1{DJJswgTaG-16(qErCql6NFplMc) zCQ+9PGdP%yH(L1b?~MuENc#Poy#KH-?WGLXAP+s~<#C%n{qL%}eUd3h4M*#TqLNs) z04*p_a-%%tA+ND-NbV_zN!&@)-0Uyx75aOUY}yknXO~Of-S&ANb9U6etg~0}E*5&+iPG;&|J|urh-W{5hz9E)ojTXH`{k8Nido_#bF;$sKVnzmzk-*wePtQ~R z^gQs3>fxe|{Uj7eiI8e^Wb5$~(FSx;NJMZTZ{)Y!Mp^(v&=x!*qMx;$T_zNrQ0w~Z z8_Tc!6z?AxAd8Pa#+d!;u)ZA!jq>T$3^Pno;#iou`JT(-6pubsqfsl3gKGK?TlN|3 zZvQZ+S(s#uG$blI`Z}W5C`g!yBDpXl?wI^lbeBnK|;aRj21I-L6NVgYvyr0 zQVFeD0*Ze2{ml{2$wUurSsXf_bD?$m|fG!xn zO_mI=UXMGNN%cB~rQZB_+bnnZ-NNzyKbJ)ixB+*CUjJCuZr^AG;KJE6jVx8!ukLqV zm3H3;?(gqhBv}85@Ll*kqF+XZT<%4sH!Hi-Q|2$t*Y#~SwtV=*$Nx^DQ24s7qn}Hx zz}KJZ?+ad@RMu2vzsT`16A4{*Gs= zGtS2~NSu48GDUCrf#{Xi-y|DGyCz=NM-q)eT6+5HXh0LE5JPX?BvNW*awLG)AOLNN z#BMkS?h#YTO#{_0gViozC*du`19WzGS3_R80MhUtaPgot_0W?sJu8bF3{P+~kQ6<~ zM(#4wu#tFCTwK?@+B`P#`PiJYOqvO*0hgJWX=d*doX0}n&8SbH6H}?kOOPeb8^6(h*q%=0RSSGwGu<{~~q=MpTjovpgrZ^BV0xs17zRNQ? zVAJk$;Oiwj;y4?KDL5C$N{~U56$1h(^i^-jHe0$e6^_?3&!5dCK!NxnCL+lSegA|= zv0c61w@;i_DtHXQqKlQ1bV257^6MHwq1v#mO{V?*)$9+2rR#fg?`rRlA_2G>wrun2 znqEKI=h-6~Yi4=)UkP*Tj{02C&Li$Zf7ZUAB+ez`Kr}&9#2H=pXE@Z0eq0MKhZJA= z6dB3?!5$++-hPuq9>;U&h&&`2R1b7gh?5`2HCGOU6`<;KwH%GCJzQMm;2EhSb0#C< zU`{ZbW!dP$~ z0%>#*niI)L-uU_XiEVXwa`LQLuE{xYk%*9vy*j0LmJY|0vCyf$zM4OdehR8w^gXX3 zL?9Hm-9JQw6L%B0x=&{s=DIA+nS`5sWY2s&YxHno!TAbKKxt@dl97m11n1N2&cvas z4n`~H6>+H51w=>UJSkc~}t%F-Df87?y<1FGix;#*YD!8NK<+>>T8bw$tx22x2diZh|)r ziVI3^t3EY@QZRDCI@r8*YhX#q0a7wD5mDBNi8qfok?=jB)hlDu1cMDNFfoXp5k0~` ze+*_Nb>1JAc_TM?b=ksZ_!B|;#3?x97s#!zUB;lII2&6p@tAbc>Hf7|XZ5^|^t|Rv zD7nCBO`3_rUBmqqPwr({3LZ7{UG6z3_&X=Tt<_LZFwXGvnR|va-As&^4|(XSoYtXJ zRR~VJmf*GiC;o`~rx%<80}@tmTLLH_EKgp3^Rw;nfx2gtR|YA$u7jX^m?5*k5s|wb zbNegezY_YnPJX|3;iyaA6RVm2#>Pf#a4-65{p68Q43CUl^BDA^#3(Ca;Lm@4*%2>h zD+(=|eh3ZCWJ+7itaRHU@{6);wSSjRg$V{m?ln|%r@-EvDflnl1!^!9#Hr`8JXWdI_-P%c0#!zfBuB)>vk{Cl$;ko2YU9$dFZnp zYgUR$d=uQ$y?ei@EVZtCy@TZQ*CMpuB32CS?>CS{jbc)!`p8xqpOTZxe^I79UdYqk z@#x3t%EuN*szVMPYrY=5H(^G5;a7olnUAWfSrg3unGSO!1>|q`-SHXa~Z)C z;}aHE_4F*)oz-}KT6~0HZ%(^{*PC6r6T&7h+S&p!3Bg9*bwyRfw%9aZ>guWljtkN5 z+VycbUCA-dduv=3P09PMX&s>;2iTe6kYz%`-$V2E_KzGQDkml;>g^?nL#l5+D91@3 zA`#uj-0m=(&&|?%=>SXum3UA{$mg(t;PS4oxko`!0M7)(rHLn`pE&!7F8_>kTn$bM z(SmiZbZ$E6$YG1HP@KY`gl-V_`rPH2+*ylDm&8FC+~VK)jWtJtcSnoSehN|}jo;Qm zo#GsJzgwwKHb_;tF#dQb*Y5K(`R76lC)0uLS0y%(tV@lPU0klAPE;wZ8fJXYkZ`_6 zWmfEt^J?$G_R5{KJ=GlBugYwo;!X<6E#r7~N!;bqm=@`&U^uy{yTZ8ehLn!->XZt6(kzVP_LS+ zte;dh@-c5dyTVP=VwHU>S&F^)WYfW}{S(6>o$cRhsGMn@{JtpsQZDQ!hg`^;;faM` zd@|GS6i=tANm5ll8!(X+XV3WebZf^805`*qaufVzqG8mD>H9{aHiJB-5oQ1Nlp42BMi+Z zz1=^BiGO@5a+x}Q?a)rcUf*@TQ>AsLdK>aTHW^(zlW#$;>`c*6IgoP^^RjYY)C&hE zXMN|6t8{4)$|FRn781gZ(;fuHA6x_=H@Wj#KjOwyJ3odQAG)NZIypZgL6+`zKx!bV z=k>s}x4Se=Ve1JtGJmyPx5^>;ux3@Wv!fb$hF$tGT;++j`8_fPm&l-{#%c<0onGX**R89C&phdhjPjyr$frteX4CO%g{JHb!QWGU>z8NrKJ zBLrJt2KKzR79^iPejH1bpS9qd&%YR3jD)Xuo9EB#iWHmb=vk(2Umu~~z8?HeuO;?NM8@#K z#c__l;OhZLv~NE?I&j5;U;Z-rPs*oU9>2UFe0ZWYaHTtk`n$7tt7&}L+uZxk-XEp) z-uOH0enM^eubMu?vr2;q^Tl*QlPL(fw@E{{%wr+^X zQJnI?7-VcevH~jAFyMr?w)NM$%3D*|*Fk?EUckZEo|(l-`@G^uZ@)uVLDcKpxT$Q{ zrn>U~asfgMESh$PjO=C%kIqY5xOJ`ow_P;<+j{dY?T~d^_C0i=yJc8k&wFbOba7^; zUP<5YWwiUxa|6bQLFyXmpMC6ODu0GCo@Kjs^4MjT1KXchy_`s@ICoyzE=O_cb98@*gdqOIc31yfb3`~m2?2FQ1?E>^dnDpVA5>E1hNRmK}iBx z!tr)&LbBL6pwG~d7Aco=(ShLZ+29boCk_~P9}ferdF;OAHqeV^GUY9loBgWwk|tX? z{Mb-%=q++pZn{x-AeH|~!Tdtl&7hvw!|mo44k{yPX=gs8VBZt9`NF_P*8J_KN=Mt? zB*prA(|ifPc+kpQe0THB=j}e8&$)%D4NG?Vy5#HV8Iq5EW$;vON?BMQXrFT3e6e>! zfgEJ8i;cD8D=8Vh4!7@oM%$Hn|DF56Z%aJS_02cuzQ5W3S)QD9<^JBf12UU})R*eI zTYLAA*~Uu?C<1O-b>0XU=5x{|*?L*|mAOPP=?n>d&9D z9{sf81*b;>Qd^9iD@T$b`C~rYv`KAEtfC}0^9aZ-D|~Em*5Q?wc8u?4+&bS&Y3f6@ z3KSmYRQsi?E6*pk#ZE|-`3bhg+AW0H2m1%!@^6-WxN2|yB(&0wQ|7s?^TP9UGiSPD zn7C)|))(m;aN$4B9aTA1vJGRVr+fkb$GdUMA#-|M@MQ6!c;E8)IQv}^ zkAnN3VW3V~LE#>d-R_m#9>t3oO};Crsk!6TiI(WIDS%)C`JfnQ=9Qm@yf9D>FJ8SG zy1rv<@M2tEl2DiBX3t}Io1goBebi1OaXF|l7)G+He*uIiu|O{NdPwA(Fw;_*4nT3x z4plZo?+zXwIv9VH{0wd#IOb7oTAOLHv8KE{>sr`vrq{LG?7xV77t2|5#BhuH8>Yhw z$@PkzUxa@>ukHJ`Ie7V%_gWz>lWl#{ED}H4m*l!Ixqloly2^VN%s@x1;?=n6l|wY! zKd^`ycSLmWE|aIF$n9X!TT|NngubTqbz(rY@l5s^$GOA3@3-i8_~H_Jle}wy4XnU2F)gRl)asCZPe$q+G|3kQ)ZqYRbn@WoSM}*xr5m&;@ju< zO2!kb@5V%|-e*5a->qk;FcZ7K?!>e;D{l{rrLf!a**k-{y6+|PG3D~GTmM$cYmlRj z%cfze>i&CiqgBN=OBo@V+hN&zq8WX1XWJr0Y*yx(xCy8zefu)%wQbHWH|%Q`!x9(s zf?cmU-|0&>HLw+EC;v4Pwb0~=b|2lYOqblS=boPBy7jYpo3ZgIYDxajqtyup-?na| zV~S%a@vFKQ9(}YiL2&ahVWe<+qZ6Y!CSr>cPV;E8RO_Se9U`Fm!$S>-KVuq zE)G)FeyRONW~O7~PI{IPL}LXOyKo33rHqE+^6NLZnhXD6b_3p@Yqc+y0I{o$R^kDW z_3h!IAqg$5=O24Pco0e6B3fEFfLzhnfT?=dUS$a(AUeE}+3BAgqM|G?l@R$P^2~;j zT1bqWL_-I|(E-DZ;nlaz%?}V87Y;+X!?uZtFhg#w(zIC{#<&jyW0MW}vrh2rK7$W% z`KndLC~?nT8q67&!R0|3M*PwpJ9n~!h(g9)17}2N-8dBVFLQFXptV;Nu8VS*nTt7inXBs z$U8?k=W6oYATeI1dHTH=0wU3^Nu!+ygy;&(`!nRNHX^jG35uS=f zhvC=0MD83KZDJQ8c~AHs;bHlrmHX#C>FQtH(kl^`fr9ku)2GCnL22S=p~050wG{&! zh+La{VGeo5IxAW&^~+CdMjhB5DJMMnKJDnILqjfSWa%J@?7aJpL3n#cksPicB?D4s zaO6ziSZ>s|u5i$Ln?RC>RQ6JdO2_GMZ8=+C+}!Hk|Cn9Tzfr$x@lJEe%E5`Z5!X-O z-_^R5DU{WB>fwr7p7u{~IBkQ3T#m&!UAEmkS)6_+I4n*i!@+|gF@W3GTDmwe>O-bY zK}5Y!-nWOjYd%B^9?c$?IomvR%JcbMpGyLZowmO??ts51`K0-0VdmdvpD~uB1O3jE z&m9atN9k?oHD!GCfibU2ZF}^D=6&-)x|qzRJ<%(>*jgUyT6o@d@Gy7%Va7yX=)HT= zElVYazBgzvl*HQ|g|a7eVc|O?T96%;g7k zC4R?AwYMeHYA+Li@G*owzJHiVc5(93k{d1!d)&MiK(o3){oF*G9BSV`S5Rcr zT7A2-3|*HKa!J>LRFQ;kd>D2+ZI~u0>Pgvs8rr4AtmEqCRYE>oHa0Ivt~>Er-z)2y zEc^ND3H157bv<$iwvl)>)Pdxi5ST$ss{&96 zn5jg}LP~&ahl?jys+YrrL~anV-yfuQ^QYxl+suGD}Xf-}8NZnU=6TRAWB69;%~5`sWR(HJ zB(_#u&4pk=-H;viEF*&mA}qf@cM*W>8`e&qfe)U=ReP3`cG9fRMkG&vulq-ax9O@p zX6d4V?sQxGw_R6%ld4AJsT`rM^RhOhKqkRuEMJA``lVLyT>DM9T0E|_Rk~#6tXEbF z4SN5&R-dsYZ`bH*qh-|knY_(~TaE781#P5Uva_u2OTWGPhEtq-^wzncCvF^HW5>*qG(XG3k4PzK%%5 zv4U*)?XoV5A0;^ai^x#RpJy%yEWTB8= z8G_o3kx?~O-Ty_Df{{7#=4=wTe&gzjwc{Zl@dP$Kk>9F` zns=@Vv6NL*+;VNM3OT5N-~%6>>09kHQ@>6bVx=sSKuVhqPKZSk$tfwmJ7DhJ4K#y`d4g0GanITw>DF)b8fn z$HZqrvMr|?6SeNGJ!H~xpL&EWy3E39Wd*PB?Iq2J{jj0A2T`4_Wn|o*kTVLG2Q2+c zV1eS_c(|f+m8D8yfRK4NA{NtXKRpPkJX5zV9^66O$wWmJl^E+L_%alJTjwHgmMaM$ z(rL*5eRMpE5#qp~4BndY`WNPPYu9!aGhJ3}vKi~=>@4wOV)Sm%u#vO1wS9MWAJ^bU z4;e(zbj`tGS)+tnF zWSsi@#KCQEr|U=aE|2tZkwbE-8yS-ngRiztKPfhho}RcP=(|LZ07G?JjEs9#lu8R% zM_{B`r|Gpq*`&|vmY%vZ!+~89KNS6btseC0Y-^nT8rqV0%GCZ6hps|+k-w`_-<)2e z+Kv1+9=cy$mGPI!D>$#9%J17-Q-+`Ac45zhJ$e-mJM@0(GbV-7DV+31yIYZTlgZWf z#QUHy@T)0Z>)ZtEVyf{cCl*I<3DxN z3`rq;2Hl?>O7yPe{%VAjB>E+)DV99Z7x1xxKW5X%2sw@wT#k?J5Wz36!>+%4u5g-jx5`ZV^K@qpa% zhj!eJ&!t?bFZy5T*$!_(VNwi(2@SQ3LFk9+M3YhW;DPR5oY;#f=xz1{JzPxX&l&Mp zvw+Y~OcbCb;QS)Nq;Sj^hSx`wIlMwi6i}rLc|+CqukiJ`E(hY!vnJsTzH#R70RJ|d z1=1N-`eSYgF?tDnn!ygNZ}0FI+dnm%?6nbCgO1CN_@RitmMGsbK{Gx1@Q7)1dlh~(e@*3Tu!T6FcE z3;MEYTo<_2glQM4nH?L?a^OgmOZQlLP^G6izA`Du;H>4<)j2OaX()6!yH6cjeoJQw zkc`Co&(DU3Sw%Fm6pkdRndp|(Fx5TGI*%f1OURrRQmiWdEQ zuI)L?t6p(8Wj47#-0FDdM|cAFC!iaGLMu@(qB>g|7jx)A$?BI`ue8h-^VKPxy4*R^ zwq4t4d+E4E=Ha{~H-Xm?yA|s2EgW`JCD9t>+&|vYT5q&1%yx7I2`wdeIxJj7i~MX|H<%N~!q$vb9Z9?!4Wrk`5!@lofEBRl(h({i^RJUeI3 zVp>hQkq}X{l}Iiv#M$e5=E&dmH*?1}+Ruy}|2?2G!51}fiZ|-ALMoO8P;~(f>po5r zF^ac{^8D=U2Guy6Qqte%{^rlA*qBigSG$~|*l%AM@syKj?33LxYkS}~>sNH8+p>PP z0wW4A`TlYfMa2}~jh(Yy0z%hS!(w}e-D(uT9CREVG7 z^~e4-o7x;!#s$;Ff3-Ir8<&!c;%ig@G!+<=fA;)I94eBu&x-%9+w5~6ON+53e%V7_ zt7X=!_n`Kck*=XRm7VK%&baxNnn9ytPcOS!SvE+NLczCwvb0oKz{cf+P0LF1rq-xg z(DJ@MCH?!2-S>}Yd&*6_2Ak<~{e@d*3>`QUoU2=D<^FgUj3{{k7Lt~;;=0?!SqQj@ z`tYOLyHsNiP}hxr0R3-UH$*g@Y7P2&aP2PpKTGo+Mwe=)z7^k1pI60V=_10!6f$Xb zP@lV8Gm7`P?3|77j@H1fM><>bE^lXF6SHAiubh)d@S&!|fA;0D2eH5U#diXL|7}){ z4-%->Ct?oB<8eE@nrl6z_eTNYQ60!6ltMa&{bc(xTxtm5Wrc(7EqL;C8X6CA5G|q* zuI81Tybl)Y=drQ$NB;g^M?J$)kt%GZir$LmOME{GY<*s*PaJ-T$gOIR_HzCM6Ya~- z`pFHWZVw+S$2&&Hfe4}ui;1VAE@{u4N zqDkwH=Af?CMQ;GJ?1Cou;Erz^HiP@23*)Z1{jzr3XwMzjj6V4bvK!`deX|EM<7@jr z*mua545em#|LwYY-%{mU`_*s9i)6N6>^2_)vU+X$%X*jD!S`nr>=}&OXeDoC6`sEo z-g5YBb@s_y5!0!P!H@nFH}?yW?$LOf&LRJW_3C4m9|zaObiWw%4-r|4-fn9@P2-Xs z=0_!t?sBbL6c^L!!df_J!;XCuz*GL*Y{EFw>+>4xGdJJZXlE6*4#g`=96i2x$8E>V z`YufKGrd2$u1^E`|xvj2j6)0Pdvn`cIUVr6poN*N_<$kB!IrpdcsQ=y6u7#Sn7b zK^_c9DR&I);4B+K0p9_?@>^K?AArALMA=@Xa7KJdf!}fys4R$jv;N{uB4i}3+CD)+ zB5x<02KvSL+zRVULz9~g+Mo(vb@*$I_{0`S=$D{E7Mp0f6&V?M);;PB`ebrNgJmXt zZ-}_fMriAIBg*hYe*R!ubN?^(X6%;{jF5p=!(QU{Z6W))za)NBM3y5*ZPg|Y&ETv9 z&{l&JI@A((1CNo&ZV+kefuFM+26CcD-iwJ5$dWkOcU*WU0#!^;Pdo2pJ@R1YUNd9B zmnE+s{{lQJRk6%4{|d{|mvtIGUozLn#cXa8>$jw((bL~0Mm75$ktt!=ezQgwODjO? z;*GSJtNeNUJ{+SBE$QAG(ZnKXa{JEfueT!1vL|W%olR>m+ji^BBp$DOE?Ou2`cK9+ zGvmD?tPvFlf8xZuy}_sd_-(oDrn`;oX)nql%scD;Wzi#4X{V08cX}I(HrEGdo(E`Z z3J-!Ef-1ihy*=v#-Y`|BF?DQU9D%ByLhb~B4md*>NuVwJxC<%E_@8|25aLrVSR=-v zo1)rxi);LD;~BA$`^0KMxgvTJS2CAVe%+E38R_bJtErKKbvdPqtbEca;&pEM z^O-+@kNvT~|1Jm>5^zMj<>%+;AWjOIjyzKs{u34Z3+m;QfMMQMRml+z8-P9 zad#awIsE7QOZ=L5b#+SA3BY{asAS6zP^GZxNAWhuh}+wE_alZe{0!z=P>a&KqnMi23EU&egar8j9vqbp5Z5j8ni!IT130AG+AF<@P5z(;r{W$J6zR z_NLo%fe6dM;G8>$?f$5b`BGrbh#v!6VdH5Hd{xM4hRE1@#!-#C|ksRB9tja-f%QUc;zN3DJnk8%3`s%XX>{Dt=iSo z!_LheE!im$Tm_{Jpx9Uo_w}01;^+XX15EeA zkS!Y2Cr)+xPRCx(D|ku-Fwx+_mV;~2L6X>4EFq!;fJnREDq;_NR@#PFKkjeez2#~9 z-u|69SJ+>~yzgSXw2o*2@z$b?7yu8D&z1Iqo4skYb}G^ZTX7!&2ldWLW3`_vDH>92zYuoap<9fEs-p^ z#`}4QO5njXu;IYg=RQ@Z^R1M_ITU4%TvHAF%UcF*hyZA#+le1Z z&Sz#)vA9sRe?cfwtAvk+1Ud*A)YG3ldGZ3zT$u__5?V|`A#pd-P%<(yC=mQU9>x$e zkD>7~6_s=6?m(eO0N5lX17UgzF2k*<)*92$-V0#Ph1p~>95BmCf&%2TWV(u3$~|%u zlOtC20XzmTvDt@*haKS%LmTb_Iey*qnvP;YS*IKSY5_bL(Tsr*BBE{F!obH4bkxb(p$7p=G`Wnu93jEtA|?(|yD<}kCD)qYY-QAw#C+Tr|bnS1g2 zwa|GZ!=Ivv7Lia%V_7BvvO7Uhee+e(0G+GcK|ZootDItD4C1~vq(MRVjO07y*=A<- zC3kgoX(HW&D8OZRu0w8d{Lmt54I`oZ(W?1nt-wLYjKMiU!Z#m6 z5fsM2&_1>7SV2;VN^5FLK(viuW>z~+Y10YLtT3_6k=V?_!=GnmX@xyg!Inl4#)&g$5^mX~HkMp#o5L`0nKxxSQ%Dabk=J$Z5uQhlx)<0Xm;3b$%AdAYa>Nyd_r zQusUlLlB!GtL3ahr|l^MZyEz}#W4~cyk$J$q1$rl#kiWv*9+R@9LC~B|Kn74^}IG- zXaY$Xf1`FI)WQ*R-?wtYt@rV|>Q&d}{ulIND+~NAnT3tE9F>yte)Px@O;RjE1{?j<3nnx6O<>~6OYB_2022<7 zjV(de?hm#J_+1lJoIHQ$#?$j96B@2y$(}Mq5;y1!uz`VVX$`$T0nSooprb1S7qggh zb#pTj*-6|&AUetE4RID>e8C5!$S;Da@(vtUB(nuO6F==5D2dbEhd?h z_J+0qOS%@pN_fK0AR)#!EjThab;dkx)tu@>@!6Ic&=e zdncNUmmky9aA3CpSti4naI<5UjVm&Xwo+tH6CsAF4+sV)V9KSJSfAu}BYz#2ijwdZ z=wylC0I2?2!Qd)TX6INN(D)GMDts$NdJF_+9ek%h4PcNsiqH&f$2co*Z|@7)=5ZgN z;^T&%mjfv{D2XMo5WnJus9mIpkr4}){Cdo3BD^!KY}DsD>m`mP0<5ZP6-X#D!-cS` zIOzzO-I(Y4E!LMugkN??=17or9z3`RYp!+`noH)~sFO zNjFCXON{3@{%8JUj73oQ0j5$_00t}8PAbK7<`ffCheeM|IYtS?9HF3>#z>=8;Gaw` z@bmF0-Hexq|IHU*BX@>*|Wr)C~dSwy**xBhQUy8!GtomoD+)aPS2R zOt=%=RDqa0Nj*ZbeiF4V?ynPo@pmA4voWs;Y~(I5%gMOdP(||c`Vg`NJ^@AXJ(I|Z zUgC&Ew-eweyHRrZLTpO2jSRVSoo5g5(OgSa3luSVK{~J(m;%t;e38`o*w7sqD*}p# zbOr3}wY9a2BoNt*y-!{d(w5v~Vq!p^G_c;q%iAP+I}+r|KFeWE)#R(Vi0A1Z7|=XG zSPZqOQm**!9E@r-1@ya;f@WkbGxKgjX#5^(y-1zF%94?O_4@TOOe$FHh>Gilqf>@?7sSNHp8B{cg!`+{Z%8zCn^7Q?2 z+mG$!--nHk-H|S8>rKLz@cKdgoj!Te4Z2+(717_S*t^st7&2WlE};qsUn|4A(E~Rh z;gx`>xEE`K2z&Kv2ju7;_^Tep+TMtlbk#`k$L;6lS_%$#u_HNj!LxEenMj&?D;N-D zUd=YdxRyeUy4dk{-$xn3YT=$8eYft6E0`)wQSxvt#j!1e?h8p1@b?*hfp8R7!(14lPhcLc)aVK6tC(AZ-FciEEwi8CJ+vxtlMcZlKOSmIrze zLK&ZUK&FU-O?3Ec#>i*|iWbilbQ@tLX$)6vrO3y+z#(F+19x*|+?zLwR`)`|0=^67 z^qMCjlQ_G6OfOKASN|It@^MR|mmbb*cJ_TB|FL`8?9#uGDJw!Oo?r_P+RtRTs*76f zFx7Iv>7)E7GVW5gGF6HWdP@h2e#QFJa&o!XE{|P5G5Q^nfepxL3dG= z7S6>UIlZ~mBSF1tk#{oEmAWYz+1V8UQ+%W~vEMOpz}=OcF-shgWA<`fe-xtsa=!Ey zl(yv6{2pv>cy5QgVH5}Hf$wAbXISw{;jnA74g_xDt`YbitwK3%mq zh8H{XUPzR%8tU!p+MU0eh3?65|DXC#j-wdoU*a+mSwybo2Kt>|@t1Sb{_d&Nm@d%} zE{TV#ZVe-<`^xS1;h21J7b%7$ED`c)3B-M~+73&?WnZM9O1!@~ne&U*zxabPQ{?y9 z$Ow%l5C0{96gk@=`N8>C4CSi}-d3mEuBXOoUa!-@cJ%*%0F+ z-0?Ko;d!Eb`YwXrUq<1+X2_ozrK6zeV5KO63HisXfji5$~|A7NOWy+C}<5)pFUInH$Ik{>=iFGPxFODGMF~_xJ=4t^) zFUBV^B)uO+jd2A524qC#Fc7ds6fwxDizu6q_XgnXmfAugEs-Fp1fe5}B^@jbP;6jSm5%M3=xgoEh6-0M2_f1#p`qommkMg*{nU zwD3xO!=5~TY>egp4SKEPxVT{|awbBLwzm9wmfN`pr<;#mh>rQzmYkb4-vWJ)zLdqX z?^1dQ=b0Zeftv^9HSk$T!Tde%978NCjH6N*nn)DK053@S9dO`AkoEqEA5Phu`w`Gx zh@~fh9B%@VFbnF^qjnueRUMVB@$RWK#s8zhzU9YBPRP_T&y!}}vyC0!Cse<|*-KF-p@RjdUloGcynJHa8N6XUqE|*j(Kv z&2%qf8d8rOS656`&}aHti~?Jv(qn7t+rR)F ziMkcHNvmf`3z7l8bL!}^!JiIuhfvNOCKu}@o*bD>K$2X@z3{LKfY`0tD@l7ACV~t~ z2kM^wIDeBZBQfuf`l5%^W{4UEscu4Y0^yE=&!5a-7%AHoriqF#wf@DxNzIt*dh-=4c0oNiU{wvOa@;kIV@m(jb`9aI-zfUcCT^H^H01{BsBhB#yt{korV$Jp0=I zjnk86qFWEoPF~?vd$Sy>9BDil0YH0H+Mytt0{0C(K4YZyMP-RY?)J~GTML|a1pgh< zBqG{YyXx5s{WfH700cma@gI|#VIsxdy+vEa02^hVZkV0Yb9u+8Y4a6BU;e)6_<}oL z3VR{6rUJuHh`b5(2|^L)BhGPmlPR4b-UvHET}=A5jMY+ND)|C0dK4N8lEU+u?3F`p zbF;#j4dD(1;h0q}&ajP;0hvL7Zh3af3Rn}d^^k;oG-@Q7pOin|P$u2#wX~TS@cmlh z@5VvUfIme7__%uDVI(mP$fp02tV1Wgm{2ijB#g0Ocs_;j>!5t`&oR9Qc_lOt>%ca> zZYk_1!aoud3M`}X`sh21$3v1ePAUIS7av}BM_(@=BJ#XN+a9fxC2Ae&%aDdy_*2`_ zlK>TMM~ayO1hnQy$6~_sa^l!TZQ*M_&UJmG$CC6`^Uc&Z`0`X9?;ev=MU2WR?H&w} zFT!oBC?4Ok)uQDN1fE1mOvV`iIrX#|%3MZ{7BYwnR-EfNmqtK1bs{$OJ(TqB2oI5z z9{zI0>p5Bz$`P~=ZQ>;*K}gaF83B?z?dM9zK{2WTR(*ohcgvfk5*-N{U`a+nqi!iO zJkUv|NkY^0QkKhr9wWV15$BuOXekE}$alDaB5WHY9(lq+3F@N=C5cw5S`v^U+v&md z0F;*c1_uDU6UQ73Y7aoxxh^M(5Cwkgvr&K7VzDA8mIlHh$`PBS6Yp3GaXD1;NHfS1 z;wlC3f@R3*-PzmQfI;&RauH&%2x1pB=7}hp5um5U-)oKM4kN=GM6r5vNX;A1OM)mS@K4Pf4!Bt`9wO7 zy_2wi;X3y~+B$|sN|HcJqb;WwB;^CSJWCG8r_bfZo~JtLb$2T+UNht@-pxfkIFU z6hd(S(ox|8$*zNwJ2^SInk~%Cd_f@|Ls{{$7tNb5xq0kR`io)sH^Y+hiNWTGEz9uE z0X6x8Q-RrcNs58K{wo}?<>o(}a_T@}`R?tzEeg2Q*WvHLpEMStjmd81v8l z4u~9*zGA@i=qUjPmLWo2&47n#8l(?U;A6m135Jinm~Nm=icR2np0|uu=d}W*X==Bu z!Ka7pAen>)I%?Bi?fZ}_xs`@rP5@N_(`xxRlCGB+^S%IXWC)@|@!?Nki37tqL^J8L zmozuz-c(=5cpc*%q`W7vls#}MC%3HO4X~SvPt!br2Cg>s;gXbu%Pih80S!`ff+(U( zNa!#u1w7HGwS`y+e2%&`oHCPgTaJsGKS=)5g-TsP0EGDD2SWHiuR)JM5Cm*704Cu^ zdED%Gu`015Af$X%Z7rxW0Kpj%N*WsekTG*+DS|c>5x!_FFX`>QR!|=i8Mz$GAuc5& zv(fMvT;G78F+uIh5oO>RkLUCA!^6Xg;qZKVUk!;ahE~klOYR0}A7Xuwks-jsfbC&e z`Ja=Y6(n@W#l~LV+DhVNPsHE+Pp@3r0fT$-tMMT3A-Lflmau5c zHWCGl8ss&DFbjU_`rCQut#k7V_iOR{!#jw^^K<(#MDxF9*dLvkn0R`q^Sm9BmXQY% z#c(Jig{!rV3a|`(qf?ebI!c+sIK4TslAReHfdR!$Db0a-9Ea%^@gcGK5hfWb7! z=k)xF8!09I1~I3l>SGe(_#LD-16#QvORV>ou2c_wea0~V3I4r4|EXmywLD(T4l%sq zCc4k0IhA(UWOR7ec=d8+mp+z~E_`q8e)d20TK&XZ#8?}KJw9InV;Prn?erqcnSA}9 zKmR{{4xyqF4S6V0ViwpY@(CB!;w-h0ludlAaJdd;d1ZRuM8n8(k!+2*J=tW-VOJu13c5 z&eDZf9->WLrvGpLdG?5n1*?iq;GDxu@y>0o1(J+1ekab|N;f{aO5r+pYVpo8-gHwr zZi7(+)qX`aRlnCgkF|9ID||ft{5Y z#3=u-xk2VB)DLg`7M@raH=cDD_oo<@JqCTe=%rr+9j{Mb_$1Vw@Q~GYL@kD7k!4O9 zr|K)EJY4vDukOC(@QyhvBLZez_c~X^zaJR)Zn3qQE0q{rVrkBUrNmr{Jcar5N?JNz z10PfT(S}PFTR|sK)f!p#FORQ|xU%qhW@h2T%{--)Dpd99Q%ZT(Kd&H{yn^uPAg#~% z-e{EsBR=4$_$pPBZTBu!ipGWBV*9H~J~es~=YRencO{J%8!^~2-Kdp2l}rS{7kO#X zWWeF&%ay7A>SEUWuSohj1&*X(i_KN#y{ay83h=a;dL&fQ2z9pkuF}(@ZIGW(} z0~H(i4meMG^?h~HW3LIs(0*D*LKhmZ(_?ZXL!XD=Yh@x`E!p zpWhKWD&h}V6!bihd~K9Ba|EB^kF*`t3Z-aUqBjB+?1|1Ka1gw2XW=q7Auk?uPg@$) zZ+WKL%EMEoi+|B$f&!ALAgDb#!;6GljPEs?a|Yx0gSdc*{vk;B>DW$>vEy^{8m=*Y z)AMWCyCPVZwTx33NEcC18U&&gr4VpwQKoB&qW(TyL!%%~Ot5(a$3To4SM6^|1fGoP zSW-A{C}WW=Ab>~G^Z!=;u;KSj&;bNXsK*wQlC6Fk4k3VNM4dR$|G|phuPZ9++ZiF)>jiK>+teY!$!RV3Y5gH$o9jph&CXk_k9u!H=hNpy(ywOynX+ z9X)!tF+DNyQDx-=3+BpywE(hWVq)+&zW?;=$Xp7ZxOsN#OoPCK6u%FlUadwY064N+ zt3fav#omU5=b^$OpJnO{F0>G_5>Z|Dw3D1bEOS1V2>2~Tl$-)Wc{VR+2!<+Y8JTl& zYWph!!EKZ2kL1^29MSH%p&#bipZ*#v)l^h;B0TWElT+YNtHU5UfOL!6$xqgte+Qr= zK=NGom4V)sN!_P=(-07tH1$E zBZ$b8Wj{MF?}O~2EDzjsDXm87f?(GKThI+(nVp&PbulSxZVpCmwr;})89*0g1{3Bf zYXZ)~9L`|G9>Iv*m}8Y1$-A|Z)qZB^+; z;u|<=ckCaaq?<`|oA;2H6;_4q3geo#0=3NZhV%nKq< z_uV@(i3!4(s=csa$N`tWj=_3ZcZiU51%mP3kZJzt&s4{~aM}pM7>s6V=~FuRD6t7T z5C)ffAgl4$0ZVE@%%?kzAPnOELyYQcta~_FP)%6&h5K`Rc3>D^D*}H&#qm)Dm&1WY z;s=Rk0Fv^X&YO_z$%#X%q_s5^`hgKZ$;l?2$5ztOO^r2NcJuHcq(!8d7zJwj8|KhZ z0(|iNgYGTnxMn1Eo_-u&PtGH0HY;pAduWT2YtAu>&e{}T)JK`kMKJROB02nO|}%dtC5Qqiicu9$d0iJlq)X2Pc-NL&D) z6V6}AK{~NSbV2-3v6r&_P;8QfE%@e;c>M~{JaDjm2*rG6>ktF_*pv+S1jTdEv}^fl zv0)0p4|vcg2qJRFX+rY>Oac+zfSQ(oren$_x(mW40QIi08v2ohz@Z^|yfhH^?3h{H zgJDciigot%9K(f;4dwhP2})bD6BNK`NyG-=?pR#@vj`A24xs1ZyAbp04`E3d4i`E+ z0|b~~&|zj~Vk*JfBe{;)c`va8dn`6EGnc~rxaqL12o6^$c=u`+Q1nH}9;5a1o5Z;w<%OyOyL5TnA%y3y-GF=nQ4n{J`CY`r?E)ot!lD_ z$@DRasmhmx3EMr#G3UJ5Xd4zO47#S!PYH@an)nh00Z9WO)@#VlN82>&c%d#?S-w1EB@_fIw)sW9k?*Q@{B!ebg3*}vLycbm;pO_0vyh=Agk9F!n80tEFK zmaS%e6VgtOFY=lRvvtt=cjP8knikUvK3qOQ2JxBB5RRNp&=9AvfC_Lf_hCen@K;L? zB~EPQ80lbW`Q@QHVVPK~50!DfjGiaF;<~#Yfw_@VDKH5pD7qmsypQ-0L|gCG0wevYk%Zp!5`=DJ%ObBO?G-jS);^ z?~EOeMAb;@OE9m2`v*S#sqV$i6M-YJr`LHjH@Cn{VqVS2KHBy|$6)jbABpy`umD!S zm;N4D7Q%YqDmx=7c_%gdG$h|G#zm{hL4CcR(Pxj_=-60y*xXEnf+gfc(z?2@GXu>r z`1oed$kMa3(gHE=0#{)MAUfXNZ3$7YUfpjt%JziS))9*9S%2Hs z`R(UDx6|o39;1jz0P5UPB(T7;D2-|s8ZOzVVu9p5!a5t^;>UaSg#IYyEe9k?gpX`B z>U|w-v=19;RupFjJAMSzwM3VS31zE%YVIeI3BhE|U`rFF6-7RNM8P}bpfQH&6jP8n z@Z_pN(-I*HzxAe1I3UQ~hjF1XseP+^ySs~V_B$h6932gMzfnxMB>9U(kQhTWJFq;*mdh+#d3V^_g`^9x=X(XklA_YXEfN%(=>aY`{H(uCB7*gZ++xteh0 z7dJFO7`7aD;&qf{xH5HcM%Bk-hy5b;4?;J|Sq2r}4Z+DM{U|l1r`G*k*rO=yU*lr;-egy8q9b#f3q@N9@nZ(-y zabor-ug!XZkGvZsI&qJQ2^R?v?Ke6S(r*pfUr(7q^Ga$1iPPQl_g+`an_h2qMl6Gn z@y1L=^w#|PVO!zE#*9}TK3Y=mo;cx}YFir{Y{Y+6p zDjpese%MMJXppl!1PlcR{Vlu|^PfAKlhlEOs2k7a+uIqaF8tEuTi53l(p^jEGDsod z=t#YN`xd1KSnazIM8Y1THOM`GW}3=;sN`Vu_E^KhQV!;}2pj4k28iO>21za;iz-3{ zlFXNcfeI_?AMmSm!|{sxg?k-H?*9Z@0;8Fc1m%7VavD&d?~KydtyyDS#+Gltod^t| zHb*y6zw;CJKsg#;Qt9IZsqgVnK7alwIfH(@0@8~yxm9X;nkXAl3gQQ7-VjZ|Sydf! zkZ9tcKK+v~v#=S<`SbG)WoDO+eXqTTUeFktt`x)-AkP$%(y-KKo#!}{ff*O89k|hw z;SC8di2oW)6^O0MF9SP#`s~>c2QQOqWbBOx5%7G1QrBSWE~&dw>yJRgs~WuUPUEfr zocY0?{|N#iGRQO#eKYh3yLfm!0E4Z=Av5^rNISAXwsUj4gTNyLYz=5?CYauGkQ#EY#L<-y)*Uq3&hiz5pX z5NDt?bLC zrKKGi8QFgL@a&P$*?b(Sk3vJ`fWn|!uh)fOn*_H(!Kr7*z?0p|@a^_iWk@nO1O=a< z{{09yBivmaxb{N-0OrLD=daLlUAXQY4*ccZp^^iGB1r~E(|HO%6`eK22((bc6rihv z8aV>|!WY8>cn&4d!&4aYU4++<7UW#E`3-V)L;s82w&)x55afF)a{VDZ!xw?vXkLo} zX)Kb!1I6dGi?rlf1Mx3WRuUKh+H zP|b<_6kjwvI@*D|YbQQvJpb9hKOIz9#@^x=*5X>|Z%8{(P66MGT^vH|r*~4n>F%88Ql2%_fvY2o52= zD;k|q{05p~6e}s1`1>noCC9M`-=NvO3I!19VPOwKEc~@Wa}B~IW6~(>O#7h&4u71Sr;mA*LsTwr^eDhUyu2bJeY9w)M48zgXc2x{k1Aii8*ND94KExhnYL z<0elS%+t3*-1Py$Y7OY%v6;w6kA^t0dGJSTwm%3D;98EOj=j+P?JY@+M%xEE00mq7 z&z}yG6OpJhC9H-`fqg2m4&B9xu@9bETu_zMY7qqhuS2{#QJt*MFD#sHgv%W)8 z*Y7!aFz`5=oe%0*HsT(TzoEP#__oSoSxDcX;oHdDLW>{#mnfrt=`9@jF`jQZGGE{W z8i=Ky<5`hj0tNp=+z&8ThBQGeAV7Z)m`rdgWbD86fJi;F4Ga6#2<;gTI*7zRM%m+@ zxP064YU^2RJXU6BNt9zD{S;=}ylXf9hE~v7gDNa6L`kI5Z)F76)xn?Q(aXJJ!+vUG za>fY!p}q*=A~u3#G<#TC@9`FKrb<{{NJIH!lrwS+9Zv-;(B`%Nl>nG{Ye9B6 zddaOv{t}8)lwma z0{VqrB5)tJu)NJ5vdQsFO^Q|tf53UbKp$cGHvDinj14FDQ~VDHkeFPa4q>V+kAb$24G`xNFahq{ugkv%?0fBI>({`Vpz+y&)O1x;YK|*DQ zDM3)E;qvO~`R1Ey)Eb1!+XE`S(kTAJla+}~YtYM<2ZHXeO&FogFZYEm3iCr_Q~K)bROMlKKFqVYh2 zMkTqge~x4XUC{|hybGvZ;sJ&8=ie@L{vE1?j3mx(63`8Vk#y9a+}|H>Hg%~l6sD)1 zf!n)=7D*TG8nM~QPB2oTpi^*r>mTm7|6leU4}LeJ?j_o6;&1o>y8;-d4D6W759~X3 z+(!%%anzEAq%~{5lrw!{QBl#p$0^V~x?p*bn0`!~Noq8N=8ar7`t`AHE-uSRUJX8| z&p-rGBNGq|*n6y0=%?_E<3Q$KVI7cD3A%I$M6OMxR3%3 zfUa47^F@^dI8Z?hsCSR167UY%D#8~-DV62Jvt5;mwz-!?Z-hn%6M zqo?12QdDhLil9XVbHiy^{-4&>MdRIT@m+dz z|J_|Bk9`gjMQ086x@T`z6trod$^FJ$04nK>N@L}Bwg$wUNn%}~@DQMx}ySn~w zps66NFr69ji>CaV3f%0UNQz>F^7Hje%KeUT(U%smtgVb|*q&kRdpr))Z6KQs5v zFbK7wDOCCfQ#oist59`TA=yjkMh9${$ZtHzi%SXT<>9HWb>uIS_8yimw{@iC1LN0? zlNB~kZ-|v()O9<>@sG4-#sc(GTP)xY03YjsSm2e=Tx-orRmET0iWd68X5ngjuPqGA zoVDg*B&6FKK2%XtE64bqgLZ%3sK)%juEUX}ps0BD#=flwP45HLDz^1nNt!ZFa|V~9 z*v7%}6n*lCY;tGfm@G%h4Jab@K#FnuQGkHO@C3`FFeY~wYUCaiR*TE^cFKhv4h0qF zjGA-Z#*Ob=GH;EHkL#k;_p1%TQIZH3AbPJ@If<#ivT)>Pl_+D^lQEBQ8@+E@?2~^S zUSzc2@@7Q>mD9IzlmRg0;^Q;xr|tfWvlm@kWNO*%yn%U19i#UgKR~gFrW`9l^guvW z_fRM*Niqva12_`s@i>6w`Ga@{*8wXHjF0zmb5?BOz|8_b4^BDgayfCY=Aa1BJtP5) z5z$JdTm(gl*j-X-SB=BB=Z0HMQIr_hhUf#S0U1M)i9g7-1B@ixoSTzF5cZ021F$RTO0-iNNuZN%iV1LY zQ9h?&T=$TNlcSArmcX0w_AAHH84!aF7AOh>f)pS=D)@Qxf5)L#{lX+i832IgxES%- zg@X$KDV3yK#gbA3S-vzb^UR(g1JW4+6n`BXTWOg8=)a!qVW;D!W#se3Cx2dDT^55o zK<2#0sYps1)LW)-BK!gz7?ff^l=Dj-n-`4PvuDp73AO;nmUNPoJ$x1<)sN_vAk+b1 zM1WaTZ^2>qf1*Y&X8Sqz^^9^!A`#r4&e_zoyraGSZuNGi-T-blJ zgs|b4N0=cNSOTc*D!4Q}yG0~ufWpqJI!vLb=lB1>r=IZ$kk}J%Z%IG}U~#(9L~_F5 zvb!z24``zHYx042vsL;HiF?zPyCDk zRg0sZnC+ko(X)SuLhqZg2$7utJV50SgUl+QWm2SZ2NK(j4ULdDcN}vOs%Lw%7Zjw7 znPP+^jtAyS&ngxGP;R7vb~RKk@+b$dH>dI8JOqnCJp5qA-lJ*yf+dc8yPddSq1OL| z*{MUBy{u%$u1`(!3I+yUh&Rw9)1vDj#@_zVQAN;u^ZnG=54ZR;+og{IT~aVZ2%`^9 zXc@FPXx6_T8-WMKUk>(-#MHVb>X$eVtScGnPc1-fp~SB;Mq95ugPxZtBPkMMKz0`l zlPH=a(eZ>>k)OR@3Y+}*X&E#XzTpv@#MehjD~$kpDx z-YAX&!-}e^Jn>4Z{I08_3b2E^LT{<&AX3qPr? znM#p4emwXH(oS%}LXUM{H71~#d{l7k(U353uo${wxV8hQhv9ibNvj4#c7ICir%zAN zK|gu=)Tn+o7~c#cSe!IRoSen#9mbHsuRS;QGrKK*kh z5N4I5cnf4U5(+%yrp=&8ttl`g4+wEI2F(Fb*vigw9CeL(c86eOAvQqrPi5GVFhuSU z!y0Z2ti^7~-cp{PLN!`#b>`WOeO6{>;G8o0OZm1tW7Cmmr)*=&f7<=m;ahPJZK6&b zjui@q>c;^A*Ycp8nNm!{m5fDmBp~>#)KqLZp}5GPtlg{mxcyv}0Oj2lHQ%85mst2Y z&`Ct#-XazKN8ca66cQ zb|F*^Y>3SG7ZfscuOhy}uq`hXN(OAvG8`0D6NJYX#mnDMOHP>)*tnbr}5_C*xY~i z@M$h_@le?D7|57o*vHGk`N|@i5XNl`G4TQJh}qYRe3lUsxD)=Dw*vI&yaR=AvLdP_ z0yZ@vw7%P=oFC!9MB()_=NALPrx20Q(<|bSGbpI78EGF}yLW?casw?CU{`Iib)gnE zwfc~}KQk8Tswt-3r-;Xv;G3ZO0fzvx9Kj7rOVAx)Y?VO3iPMVc@-e{dEj>F<%PI)j z2;E7M{;aFiTVC)Afv!LpO@UYY0{8@+-a%+DdQmtDPpdy*v!A?!iT4z7onBCTj*uoa zIT}{o8&K)U;te8=hj3hY$^@7i;F6e1B~Os_O*kq}o?JnG5lASBDH{Oho)B9+#2Ril z7D0iagHNvKV+QI&V+gg3vif$yQ3J|c4?m$N?|7Kq_$H!=04D)*6&VC2SXq{^#aGps z@Z-cGdL_JY7rdp8_V&UX>8;1Gn<@|g$HAYmN$G|xyGkh8c_tmw9i5%HYElne-iY;6 zT3rp&^e$Gz#bD5+WKt!7b_9(3R(u%$+2#eI9WDS=$|$1Hj;r~0&Nbr0IfknVYzF_t zx@caYhd4^X3&`T|jjIA;l8gogn+g!0hVKN&u3au@%Q0l2?~Rs)6ShV`Sd=!$FAp=k zU4Shp2J%u@h|HOlhFw`u&Mq;|y%{in@-DyD<2|#QumD0rpVbcFE;kuWZBVO_=RPtR z!(A`##vcyjC_%*y8pClKhTK}s4uNw-M5q#YgW-^dANu2;iX&%sm9{EWs80 z4^bsOD~$~<%)`yi4(S#$V$^~ugnad4yS?$-Q%<7Ds&rHQYOZ53fcvUen+?NsK6ad= zXc`wUUAhkiX2hB@qx2^j$`BUDb|Bajbs=CQS(*KXo*}e-RCsh!osMnBo0RF}-<^64}Cl z?n|K=z!DT(FnX0n4Y_MEL(Lc@si<^iraDsP~jWqC^;GF{BQ+9LXxz5z<55 zONx6~@ZU9EZGza5nBt)i4tAWgRY4DwbbzM2f(5arTnIFd-t4TUF##%-yvR3iK1ZE# z!sSJBK@A#xAkjqVLTOo9(t(9OsFY0tcjP|Q;SaVR^22`nm}h50aLt}Ty-H1-Z-iq< zVMR_nH%O)MAM#hANd0dmlh0pJ+%TXtXgadXl>>JVZL4C zO+B188*);{Bdqf@Bms-7um8Bd-Qcx3<&Oyi$CnSm`+@B|Z97s7%FWn&#p#H6Kf#Yc zVohOl3h6}XHmo#Weq$ycOW`qT_WOtsfyt}PbEJ;W5(e;)3TbaMgX(3xuzoSU2w=)7&~JE9`U!(sX>M+gDde1U+NWQBNyU5{Uti4O z!&e@to0!pVqu|S{Q{VL0KvhN_{fR!(x%T!2c&q21SbL=8m1r>( zr|>}6_B3-;=_0+`mkJBdqbSm@n1*df@nLt$G zLY;8pbz?SD5O-i{god|;vtRqy&qH)V-j`%Y90chH39pIy^$9J>5f6Efht@RR2rG)W zBPFJue6Gp)lDDYJo$2zs4zD!RKI=HXTUf-LAyFI7f@!G+4#F}}1pVXg zd)1IhGa$ogJ-AD55NDnYy+zH@kn=h)VaYKXLv?kv;1lS&7i$;v+3~8CAG4{2H|CNB zMlkkZm+|s_uS`J5fjPH?97Uw%6o3NnZi@i_Z>R;CAsj+HB)jEcwD$UAgV_D;6zGItgZjX+gKmI~@Keu1yTkaqg$6IZ2;j2|0yY-z;El8b(D{e29@x?BN zq?f=ay{BVgW7NgZNSIIY6Me=(HY6;PSna;`jf*KzdghqQjLY+k4i&E$RX4ssY4?r` z$!5V{=G+8o;0_!fvLpwPU%Iutz375kn-LIN>jYfOs1Nby0DPu+Q27sNcp3nZ=q;mKX0-A zwfM#Gh=5^k{^r$bU&+*D4IyF35g5EhkYgQo2bK=f(do=s2h6eJJ0rO0PYmKBK}M8F zTX3l$#1;{;(6eybiZ=lCX3l;SH5G-bstC5H;@&sPqV?u}&H2}+T>Brqla_cg%E(+!!vTyAsB00)+4!E*u zWzBv7UWdB}Y}95!jsJlCMbP`Lc=K}!S8kGco?c!-{5FtcN=?q&yH^M03EmGZOd2! zwBM`-J*;M(I(PoZr6#(7dxN};nrvBV7YYlVxQid1oEVfh3kqv*?n49$%pm$w7v<#z zA-kHS=bb0PU4#zkVH~y@crMs zexNV^;WfMrt^o+ppma}YphhZQ>$6zQJKUb`)c4p z4MyN7N@xYI8w3~ZTU}0@(u&-%UE6%8wduPGapOpM$83(U*n?3+0Ymnr(6~lO0DjbhYMge5 z=L`PKV+Nc|0EAc;%RLp(CJborjpEoBeD~_nr`29A1do|f-&Bt`{(FaHMJg%^Ff5E< zDjdsyUzYw+kN2BUCTtD1!^6Zx?uqka^fxD9_!ALx$oiP*XgR)3W32zq(9j-YmLqO* z#?fLJF`1%>=}|*Y8W0b}^W!x6jHH11OHJ=~I3}$kRC3&FFnp4n2gQh#MW6w|_b6=I zAn)^-uSXmTORIb+raJHvbrpMI30s^|T%YyrTM+nO2clw^zGHu*b`3*5hb}lrZYzke zW|v7nRqCmh&N-tvW8CS+iFFVF`+zGY`zLjPX%)K*YWj(%MdNfGvYsVPNU~?_gVUA$ zlTb;2#gvs%b8Su?^3x~d~SpzhtoEsI)dg&9$EX3v5 zyvW*`>^4J;xHS>ijigHws-QQ%aPG0=BFgPEqq^k4g&0VU*3Z2&zRyZnd z>91~#L&0^l`(b;NmuXP?pu_Z`r@9yLseC7-6PYeyGY*8Dcr8yz?76t*LOAVV;=^%UcvXk?_4 z^^ZT-46kwRt$Z2}O;_IeCv7u5Kl{weBXv-M`}SzU7xC5Kbk+UeSemR6C$G8d)@34= z_vqbw!M(Kpg2ax8Nz0AB zX{G8Y{QfaStAPpb?FXrAE-`-v#P+>oI?iMw-%Q3hwy;{@z<>0d;UB|Hj!=fqk@ZVo zRm`w?-5*B{e|M>F<77jdDC^q#dL`zCr-!wMO`Paxw0jmMMz^T%(s@b{F$Hy}ZJGmQ zyl1Xw;&5L?o4w=LS&>_m=|Q1dd{R9mu@xRyq`86|ZwUo39N}7dF+1gfEt>Z_b<+O# z7{gNEWllX^qsdUBJ{8zu{4btdA(J>v^b(2!wa1Q~4_jTka>SQ<_H&jjISBc85D0b2 z>$nF#DpSs<0*x(y1})LM&ph$*=W7StXrYraoiU%j+{$j{t7{gM2P z`G^TEBQUz#&`+6Zza0I+C|v$o<7H~jF-8{4*VymYzW?@5ahSS~}o^_}&4_UJKm(3#VXS!|w0yEEdbBjeh5twfcMna+q2$<4t?YIpD58|U90^G*vute>-|%C^~M4MjTG zIkhNev-9d~2O3+fCr$dZXTW7tFn26>nns?xsN0Uy z5aaLmV0CmI{}gbGuk^R;e=JKR62zmOM1JF+HQMWoK7A4aVv+eFAf71mH?}-YqRu$+ydGSrI4Y2phC$cjRV8 zG_TGB>f8^R%-YgY*eN#%3_r|^!gS_+*cyNmRt_Is;FQC-y+f2ziP6zh!4`g;>TSp@ z^M^N1{-7{`qV-4bL}E^pAQ=&nKzZA+V_N^w`xqpa4q5NdQkCd~{;0yy#=7Tm&zIRy z`S~S~WLh?bD>X+g3WQX$wz4`%iFlu>kXMNM51-xhuHD@In>kQ;#4F)}s$mCY5f&~p zMe0UhP6Et0;1<#uHp~*BWyleaacKt&px6(hJmO=ws2%WjV{K)hJJH>Fsi>$7!(Zr* z9S2B=a|p|rbfZWp1rHU`%y?D*_6aYl1~KYWrm0cej6R+~>fo5pgK&2$hR}BHKYl*1 zSD^(qKMBp{$0Kk$G9M-=mIArr;p(`W7YT9uis^kWbP}#mEFM_BCo81laf2Mo;-`F3 zMj#W`OKjk5;9>ki1bA0=y62T7bHgN4w5Rx4K?g=3fKZNqeQ9(lJHa$q9i1%6219aSOM16F~a=8KS`@tk~f zpSD{?G*==&K#iZ9p%oSy>dF;$OV3YO7iq`Zr&q!Do<10dy=HeYFE20tr=Xw)UXSwX z2Xd3&_GFUzH6lzpJxU`M96c9*{@l6y42-n)^h|=ziKi+rv%3!Vh+(*Jkex%H@yx!A zFwe~`g7cJAOFv&S#jz_EOng#vKu9y!lsa+|z6kHhj;9y4zqvON#YcxBBGcv1D%u%* zvZLGIw`pu_%)Pv5W6c-a&fm%!yt^=#baLA|D-uf5P0v9=r}EUZL{!uFr>ek{Z*!K$ zo+TBUnn`R&Dgh-VdEu1rf4kM->Sg|1L!4vZbIU6Rps(=5K)2$De%L=_)UvJmoQh4zqby*0# z#KVL9{L`0J&VxwOWbh@WqT2=zKUZDf@@6FtRj(7Lyl-v7!l9y$*X(D*#Itk=5HfI| zbXYeO>2i~~AIUTKUOH&} z+A)Hdeyn8Pb+Ub?70+bns=5WHhK9?oTZ8!oIcg0XIdV2DG&)-O`{JNv0*U&wCJiSU76G3aDaqFwg z0c9i<8#_BCEL(ncwFB;%S`K{#cyw*N)MomDyZ4$k4K+2jBktO=7O57av2OCFcU5ZJ z?0q8VgzwJZN?@ZAU1AANL@S0#G@fqXc-tTyIYmj&wg67nmnzL=cJsqZThv732?=c& zeDKnmvOZ>!l%G6*UdDCMkZjpPAQ66j%KLBJsypjb~4?9 zJE+eja?qtwc0Ed60%&YIdB9_Xw*$hS3M(wdaddESm#2@M$XoY8V#=f>gR@_{P}~I! z1Jw#Je~2->98|@Vv^(^)7#$rkGYL#LeDL7fUtH?P`n-9$LINz`Ob5Gu_dfbecQ{*` zv0~{{@6F(seCM=bOleF>X|DNIS6_cFj10myeQZ&f&yw%ozn|Z6lEj%8O;{mq_YU|x zWjR&9r3`8}+>kJY7Z%uON^AS%5A-mx9xAJIElRRWpTSt(V(RB)qz!yxQz5}4h12tC z&|aYX1yN>qzHKt@4wg)2rYCJL;XI7Y4J!A2#bt9y+jAj23+|dO(B0XwNu|cI87n^N ze=Bk~34!VMeSX@qWhgil!Ul2jgql?+Q&tXKd-ggEX7fa_yL?glu`{s zqwpP&{N+)na(i#@!^DR$Y8O;ZXr~8XMod~Y0sN5X6yD?2>(>pa30-d-%VyAp!R=C0 z7xLy3z4v5&rYzku?WGDer(M@PJ;kNjVbd4Adb#QuUbvhY^tpV)&6Y<`AB^fEe+1=! zcI#91pVYBw;}@jj5@?@0R4Z7iFH~1oFFui!G?Rl_P^7vwI~G#|`#%2bJ1}KL(8dz5 zi&MH?hzA)Ee2}kFJuXi_al(FHV)~7Vj?B`dFR`S>4>i~q zY#Xs}j*4xON>dGF&}4*y+MT8#nhH-NvoWWZ7dAPjU3O2u#1RAcnb|5>OdcR9+2omR zK08X~ZZmUcFvIjMQ(v7hrv(&(TQOw>RX)|JA6QTYY6%+cLJjCkW0O1LDU8VutzkMk zGYC7jTnY6-EItj*rRq1mYxGk9a6`jzTG?a{J{3;4rNeDgtl<<^_|xIyMyHKJ`HxWQ zqv7lpw7@ywbORzI5G?_$slcx|kx*nt8`>|y!PZC0_EeZZPK*Z!bohV)>U;e7xM zc?htw?AqZ;tbdfU4g zUdu4^p>v4$){Ov=`#@c80E%XC9xG=rfIJS#WN49fAMfK8genvVZ{ECFzua;pu@~NB zE~6SGgyr~B_JwIdI2IaMX~V~$S=NqGKZ$OgwtL$^-5jKAvTN@#Q`tv;ghHk>#B6MB zfyg~mrDw(jU_6a>a_PTwDrtuFr1lo=PD_I4A=#vz&Ju^6j~r8b`c?u|iW4 zws|+hOiUI)ch$W}MwFZdM1$23U=4o8FCRy3ce{zLUZ^a7IruY8==LJ7s%^kP_~UCnwc5jk;80RHIECjP+u)&4N)wrAhF?N zCd1>G(!%4*^Ny@+u%56@23EwrjkNVm#eGsWnx!55c4;ck!3KK4Fk?Sm1*@t(;Pk<8%F4d(a9Z9OJC)8KMi7e3Z1OG-89Z3Y@{qz2H`IOr*bL^DD4gMxH*eHlA6275~T$!Nry@pM{Q4SV`bFU~{nGwO5r)(xJ>Fnhk z31ofmUdGE;wX#kxm6zM1<+?L%0&E2l{&h%Slj4^Y%ZV=rmrs-l62rdvW+4$y*|Ufv zjz@3|1k{5SH@|UdSI>rbA_DWf_1~3YPW}+iC zJ!4`<@21!8dnc@)he>2baw=??na%EBA(?H_EXqg^tLT>!f((nefFF=iv0Yk%`tIX@ zKCO9m5qq`;cUj$0~WISx<*a{gCxLTLyHycYJP@aLC4V0hK6?U zYY(z#M}30@d@e+!obN;KPk?pHT{{ajM@}Tgh9)*FU+Te4S_v$c$^?3QT`%KZ!jAU^9LCf zz&7OsBh5GkF~1J{>PM^QGv=w6nrf#+5~6cH^7Q3oXru6rz8g1g4EL{5uZvv{udKV? z)G6e^8lg`Jxsbg*7-x;=VT40gX_enBIgAFL>GzAx8acc zWisH zeAMM{U_<|Ru~6e?4}F+X(jO#NH$zS%1OS)Y-LP4>P!A54pc#~I!z5a<=6vFm*nMmMEmAN00qh5E$0MgTfk;uZp4O zX3g#(Z|qE_qsxd-Qiikd(r8NQ>n^Jn+8la!aBJI((`$P93o-1+M-Stf(WSm94Am=?gNK(~fun_AX)G;Fs# z>NGK%tRT@jR3`PWe(2smg#oT9S_zmzVt433H6SS%hxelq&W-b4TJWqJ(EZ`h6tR|) zsJ3V-{{*U7pabAhMLuv!s}QoiroHWj#7_!a!VTlY4&ag~e&cF}NAtB{Vz`oe$~7Hb zU2CA$KL6(n%xu}F#3<&_`9{QX$48g7rlw@Ve|B}AG>h*+I30`LsqZP{9kP*ba170U7_4r zOhmPY>S{siAd;offgn2+5=jv)=lMbH8t$_!0f}pwkyEaaHYMDX{YuB)Ey&B8W~J() z1=G8%I?IN#NLabi>)r4wYJRgJLyl?^+JoPd5)&JXcVMCNxqyb$k$KK(b!ZQk45_8> zV<4xtJutNK`PshNx4Db9`j+Z9BLgH;>(_I#vDQTnwqPnzOLf!6ILP4$)4hq^mj4T^ zy0+p^$-QL?$|pQiF06?+FUCA(O=yPq4{~y2B;9Ey$#~o0HC(2U+FZ{Y$A$BH#p?0S>WR_ISL|^MxPPsu%UGi1i zqYs0!w7}731if|1pG;GBwy&q?ItUD#198on^bOBwsBpu9g!#i3ppjX9ZS89!xUusP z8-2&!HS7H`irNc=6r~WfAS6ld{N~)7k_Ise1^clL$)mv@>W8ZrG-3Or-O}=NJ}=LM zqmI(g_5ta!wO#35>K3=#!2%2_Y^ap?juJCK!FN#4G4g^?Eo%H<>|Jr0LY}guQFHdI z?Z_1KAjz!weWE!LZ0ZHH0NaVKT4vN`-v{uK+Ge7-H~mQhA_IQ!I0Xt>Nv@-i~jFaM$F$at@tXyL>8sBW6gc$2YZr)cSsN8PRr~pPxI-$P6$cDb<&dAoxaP zOKMn`jeXT`%;Jb=*YbjQs58&Lj5Q%8hX4U7tchg8uPr?Rc(vnHPi*|ww^Q=_$S#E6 zYUOFBGPh~~x&@{L34FO$3>j-q^?Pt6&)~-kp9s-GNWi`^C)vr#N>!Z2R&S6BlbNXl zSQ}8)q93mGO>VK7VPR2*$MqO84DzJR%_%`7qEH$KKZkwJgHNK@HnOhnSKzZ0ZHR48 zf76ma1ad>0|;VL1UVR!{xByzIA3%eaMyLx&;q z_G*Nwp{NgNG*SPnhS%6F)878c8{YZtpDaG@ug1_CXNH{}^!Bg*i(TXGU)}8SZ{~R5 zcr~x85jgk%^@n9few=Y+S;f)sklo(hjPX$C{*x3vG&SAz-phE8p$ie_a)CF`ECFQI z4)mG{q_l;e%ItE}lx^Yxk}H1uqaFTz1ITi3Z)(r~b}Kixo^!hm@u6n*|gn zI_h7a;WhT-f9^T?pT1#JTHt-F)D`Rg^$DlgoUdxBfqO hJ^p`iWeM#cuKv9Hny3$Z|0K)A>^ln%##prJKLG61LCOFC literal 87288 zcmeFZXH-Z;wr($Y=ge=wQdK8$X5M88%%2!LwjYIDQ5W_~Xz2+G)D}`QWJ(qto99u?KEI z5qHriW79z}AiOO9IvbbZ|63~rOJ?$duHEV$`Stsoq_YPtnvEbH`goF!K$3rordeH^Y|;@%T2?_ zJ+od1%DOu_LDU|sX5O3^S0~NYi#Dv17xVbjU#0ysLN^2R^4Q$2P^-E#7iXi*RkK_T zd(WK9$!m`%tfn#W#R&BER`q;P%kd-oi*PxupMHabuiQ@OgLKISXT6+GTCixwcCRm1 zB?pvEp1Zr(emgiEQjIKn@JwCCJ9czE3JhvUSZ-vi@!8?}&e>+M;P+7EPZGnipc%<) zRR3CDcgPZt5a=vrcqy7TG})}3AK@5Jmog)O#<#y>})M_r(#H@+!+oXHSp|39(<;-wNDjw zb8Y*KTYfn5(B}YR{3V)%5CRFNnl`JJBPT zn-Z+hMBnT4S!VwEyx3qo_}=UOG;x2IJ@6p)6m|^*5{Evh9z)E@-V|Xzvw9_3PU~ii z0s3UQhl$tV6q_cqp7@>R1jDNLKC0qJv3Dufk1oK2@+mA{_KO?H?Y#<{bFfg#?`11Uudb?KZ ziB?g?tf3F;TWY8|Q}Sx`Wu5Exd-tE>Z%T}$yFD_jmbl#cjDCEKb!pJu>bYds`0~R^v80tl^#=<*0>Fu8A{^d`+DsA>Vw>LchF9HQ1uJ*>$bcDzhqk zfV^VWvP%7Km)+ZqCo@%EtEp~yeUTq-+#*)F_Q#h< z6mtl$HjRi}*{+)GqjFz@?#u_#xcZ(ArL)hT8htK7qCN(87`N<@WMdq?<5LZt*_DEG_&?eMxm4#|BH7>{NPVLn1 z+FHs^onlKKkC_zaF%0(F8FIv(Uk#;S{nmFLc)kN3IC;|Nd|Q99BV3uS!OQ;2t_j8b zEr}_*bTLA-&i7)GW~ci}amD6dzecP*e-92>Mgxy)0y>S@;=?cTj4tD@3_a`Dj) zyDG`WFh2J5#MyVrHd~Rz1V!&cZXcY(C9g^+--dE*xt-$QT$f5y5!-K%HUI3n%v2&1 zgy-6{ch-Ed%=IbEk#hzM*^-kW_H2v>JX`E#r`=NG?9~}m#8-a`D~&(REv=9>-TN43 z<2Ix$c&DcZpPfR)IhR7zwV;tmeRWC42z3*S(#Wsl8Ux|v)z?~a`Q$2Vb zS0r)5V^Qzp$2%zxB=ThVMOH#2+{?bdTmNP&V-{i4surDJ+%#c|Sr%7&zS}%|Igjs) zJu<+9^DI?iC5hkak#%Un=|Q0M*eNXwm)KN(wsP{DfFMtmNm<&w=MRT^hb07kkwuMh|)TT`f~q zU^laG-85o-+HF?9_=}B5jce73g>iSDI5#X%?UuAcfz)Z-OshrP#O7iB+|W7TF+{lq1mhr(G+`p2#P8KS?iXj+() z*39sDz7f&3Q(KynLEl8c8%@(#P1IKc2*#l{?x}WvCohhVDNlbfylR7^qt&*7`!aE; zvpBMop(+jkt;ADQs07X4`A&VYcg1tjxm-Kg!Eod0FH`F82i8h3240e)2l5(E+i}a{ zgp2OB;K`^zi9x8v4J>Bbss%^c8$t_MEBf#CkiWd#b!$FPyuE6ho8{BqgH z=mas)QCa1qZfDemWqN!Il3z^o+#y2*?ehxS&q*bpAU}V-#Y^Tx4Ia`xnFCTd4wrLn zJ9P?7cgnLb+xqgPsKnhAk0&ROIZ9>ZH8F9G?aKP;?F?S{dH3bX%W&w?x+&fV1D*Z@ zWnxty&(b@2FOfl!`9*cz^hpJ~!}(gYPH-AuuM&>8HN%>^clrgPCRKk;d^1%Eo`5R4 zr~WIqLpP7nDn?v$-2qe%5*%5EFM086WY%@kM!je2{;jNN3-fq2`Znkamp)SgSM-V&B42VCbbgm>i!`|JG~G=sQ>LtW>8gFK|iBY zCpl7HLv@F5Si!r}u&?*xE=!7$Z^OQOn{XpSZFxk-`6+w!)%87)o>sCXAVt#UL0_Sl zU3w)%0Hu5DueaCIZ+Bga(< zJ4^F9v$WDB#Z)-kG`xP_Y{lTDzL_PiS@VXawWQQEqECdD0=8&iisSp+C>^BPV`8I0 zDf?4VB*8;!a#X}&gm4<}u^G9xDB&yng)WVi;0V6md>tg#y_H79Km_yx3AL7zswEK< zoZqOwn%+;niDJu(7N!%Ru8kc<{i$qt=o4C7v9QU&;(ze?YRYr)SC(yy&IzuW$7 zhqE0tc@w^p=C8D1VVN)bjVhV-y}q;&e=D_0KF{`fcs{>~aG(C|vM68I^OYLT=2-_g zmAT~}O`9Ipdbn%!LgqWjNMeqDtSZ*QeBOI%E&+MiE(*GcIu1039cbu6@oop0c)&6z zy_W8@NQcRDMK{v%VpY%j)ay%%zZmR`sBloq5Ix^2k5phuUHG+rZ`0z*ol2;%l;*m& ze_mw8;-Z^Og0RTQUwI5~y#^In#_RnMs0fJ~l?a7;;jD;R=e~vXe%v_WJexDgnmsN; zT^~>JCo&=jYncP5a~HhViSFpx*3 zu8CyZ!>K_NiF+KDU^DwsKH`A1;gF%agG3je`S_l1SC3@o24Um0${&UmT|uABa&AS4 z?vx1V9es-`A?75p(BX+VmQN3g&^cwePv1c!AlAuFXe^@f*NMh8 z=dbzull!7muKOSzs50-Dsee%=eNiLp<9T=W(kv~vjDVi+-})_Qpp1Z?eaju`-?U<= z$nnpRr!O>gPvuulre)6g=(BNc5S*W}zV;?!g%lO#<>!(yrbK)R_IR*;pjPc%rnvgt zhf=;ux+s8PpPqBM^6yuzcP~ge91P(ONahRr3`Kq|53;O6BN=~r&S8diFaI@slO0rE zvcpfe>U3NB2U@cP<7OW|+1ITZ3+V4AHRUKW@5t2I1P~l4{(HTfOs<}qwUI&d(p%>1 z2DyIMkk5BIEse~i$HT{@o?K!|(t5@S{vG4G$6~i3-hNqXR52THbxYh6Qu4rU(jx!T zIdF>%|8|R5Xl25b`TyM`M<*&PE4|69Y3?gz==#J8CO8C5w&TQ_X9y~7W^oip9w&^Btr4z8JHY!W*=v4>>iT?IS2qjy9qzh$nda}p%4Gg69Kr8aiq)o?-!%$TCh{{WMt3v> zuP!@|lY`Y=Xnpdv*xh#%y7QhD~3m zB5dGXqz@>qmNV|@3SLeWn0{w?vGiND)Ky zq%E9z!tT5DMkvf@Q-KKf)9khKm{Dtxvc8!DQ~{@z&u+`@cv3^7mKbNXe(-8qfBc8R zvFC6Z6O{Y|x&d-S4(s#iR1CVq zg4}`{jGPtCvp1zpvOS1+*7$gQW~5x;2AIJ$Uzw;Ohb4;E7`N! zuYf(d`iP9-jQ^Y5xsiB}IsUash1@#==`3p`%kG;a`3&3F9d=6jU73P4+25NgYtRwBjt($ zF?i(|*_HIWDI4|aU;d;$0FDKJv7SZ=Cw@AoI-mv<^%2TahNHQx)%+3c7?ks0w-Wlc=hnYrn z&Rpy>WP}ctIXZl+EY1AFO0<1Y2Ca=#WGgi9&dcL(DdVo~rW7}ta90Qds;zRGUeBf% zS|<53_MukuQNA#z5uLj>$h?t)(t`n6yr?w4>h#h+_1w?GMVD4pUR?zbD9((W4|1kD znIk85k$!gmivyVW(#d0`u;+*G{ZupwszXv|%8p$@xdggdR~2ken#k$^b8*&pXprxs z5^HOAA#!5E5$TVDD$|rZA0(?7iY?6tci=NEIU1KJVbir|D;9y;9W5+5%I@l1T`M!RXt%YBmX}9_Aw)XAOKGpD6$Qm2nMp#Yk=zql|hsTt>&~Su1Z#bWp zxw=NJnw|JM+ZTA<_jF$ZeXF+nrf1x}Py6(Ww0*+JK!}t69f;Vc>*2;b>Ka6rd4z_k zpKQ_Hf>=@96KfM&y^kAh$HpA#BCns=J(v+dS*f5Ck1r(0tftTF`MHrqExs=mCcBci zg|846)V0U*Y$^2LZw19pdHREk;&+b(vIp~|O1h~B^T?pSs=N1U=gGO1pl_<70gv0X zPYC{OhHarWd+kExBqpz*m4$Eh+j+0^-k?Wq6afk+(#l6U(O1)3VtOV|lQhqk;YGQg zo3UmvBf~+ZtZ#3THAcdVzZ_-=?ZgsKt232-QiS`@c(s;S!bpuwHVC(I6g#8Gzu7uQ zx>iM4-O6)u)T4m!v}GTAwq*Gkr7LmodF;b?8F!>{LiOB*3@opA;<=_WOArp?Dal?s zLN3orQW_ShOZpFsB^)&JwI&@q5Q{Usn6&FjS4TN557G=Lc50+f4RIe9%AGP&%uVB=2_GWaj4_ZGa5l#}j|T z_GIggP+viNZR1uHXFPG0`@rDbP^AZ|j8@+V7PRVrb8$SkTDJTex?7yZWq2AQh$s=6Za zh%{=kpoT@U(S{S897cw$FkF~d{HvcK*I0gwL3!-``EdqhD-T%FpFC^5}@eQmt8pj zdp;?*PZV@b^v>eT6{M-FXe66%fGXUe_b=F|tFZ4D(i%H{elGN_P^V>5byDI%_T9UNf=aoyAl&}wB z-v5MX+*`a3e}7!F%mbxhOpdfrt?Q(ObAn0dE-|w85~t@O>SxgLps*Qp=dhXq_gFxH z30*~2WXniMyrWH4WtQRS5oRDuG3f`Nt5ZS&*7H23&{rdJ^CAS6gMECOzZTXj2i2E5 zDm^*eFGF00JlrbsKBPJKQ}^FqUqG!0-WmctMYw_3eUCR@j z5oWKk_B4&Y{&GI^-#_-~hIkJqo9JL7? zqUn5B>X}ai9OUEf;_LKISG74wmhLUpk2h&k5qC>VJI&owasDf^fZ-ffyKZ<=63M`2 z5NKl{|K<6De_Zp1r?rpf_e%GL#a~24?_l|eaV)(B|MccQzJ0ALJ&6ZSbXu^?UaEn+ z=>iiIvjoeD7xw#kXp)S?ra<;59KeyHTZmRm&<6BMVfg-`7l za$Kqc%;>mZx^xOezf06<5qTvNJ%1+er6B;xVtdF>-x{Z~(!gql z^Q^~v?o5u~d#X^SvmnHUHB!67HEpe&BV+EJ>oBcaEhKekYV z>5B1r!WP>iB42S4DWNuK8MI(el!9;4?95l}f08(_=i*2rH0X2r0PbRm`|<0xf^O32 zEwhNV^y?4!J(LTdrPLpiOh`alfY#;rz?LQ!lo+a%W+$v(9P^QurkuJ0kd@Y3Iz(dr zUIhm!_LuVUA(MWNf<>2`1HBj-{RWA-2tq3QYjHgccN{fX`3a*#FEu1$bKWQLfR~6e zG_S>YLvtlX1J1EN+M9RyfakFPW1kUEQ#7dzAB7^9hAq)46#;Z3rkGt^frUyqOjUU(3_8uOfg1v4zO5TEA4O9^A( z7R~s<%fM1jk(^GAmF%PSt!~WYH=@>-Xr{!(M=mg%?ug_4~De4 zl9#m1N_vcfqZ+~x9F*@Dw&{4EUu83}IsNe7zx9mYXd+gc8McUemUQ9N;_`Wt`IayC zzWeq#DKFeJ>=0u>`1*oY214|yDnHmkfEP|<9js@LV{?(4cfX6RXS^$AThIr>O(V<8 zvLG+fv#IxAnN6qpyc8UJ#8Tneja-jAkkMdLI_C?s6nriT);62(7OHSKBaO22=Q+`v z^O=dwJLUM>nHM~lziwOim!57*?hp`9^!}O&K9VR~ozD~)lKY^-7|`YW>+`-05pC{; zVm;R!Mm$@r7lf!0+t;2!r-ElmWSn^l_TtqqgNmvEK1?6mo+#V^VKF)yd3u|{PQ?tH z3bn&qaB*WYcNy|^YYcgkvUXIh)_k62C*>qPsh4$5m1KU|B17Pk3-Ut2K}t`%qtt6y zWsjb)qgv;lDuf-imfgrOd}uL*xr9Ib)V)tgU{q$}w9#4R)m-71^$9$lR{P6&rw?}* z@Nqyz@XnI?S+{V*#|Qcg22jbVggtFPc_!3zA0*<|Nni!7BeqEMrMK*$Fh2Y(l4|ak zg0i-}yPVfBBrDQt>BAOLpCU4y?Wg=Z(g@3W8TO{beV zRLr{!d!U3MwZB}V>3>4i&6uyia%aTtY9XD^S2eu7zTM?O0#;K@HR{lKfaSZFNZr8I zU?>*!gOBKu2_v6gW%6p0q~;#`d7t|SgXsRj{NsrIWXX4@f8A|8iSBz7FqXJf-q3fa zOAk+7U46`9wNLp{@e$epbYhUrx(`#H)Gjglw7l3IH(tq;dlz{Xt;p%X z@utGQU-G&kS)_6$kCVUD3*{*2>r*CJgd6x&Iaz?CPRLxdKzn|r7sr?VHx0_GU%&-u z0>KmhOM4DvX{Td_R;|PA2Z7g#c&d;mo8%IwZL9KvzXPA}b%CWfdIEg~QI&spbdU`6suqgliYh52;Sk+x!p39Mp-Wxm| z*7`pD{(alyoRkHLYcW*9^%-;e?s&F}-aRZrUxCl)DoI`yt>Nh5EwMQ%CKTl(3BQQ| zJy=5{PQ=1IaU-Js{V-eTTmTtxC(*9at9WS_cvqZR&#TQbx!R)<-Jx#EQJAIS$Z%{& z1eIuA`o$7UiKPL0 z=(hipq@K!cY9PWB81VJLS4!^Os^4w0E$#B(FY9p2$g_sYOxey_B__sQ7*k{G~P52}>5VjedtWXsVQ^nX7IsW6q;C z8|}EeaxAs&`kaV{a>@c=Aav5IxRIR~UKvIq$oYJQStVsnMf^xzl&hz>`RYsxZ?r&X z5eS14qF5-W!vVQ^Y5!=9)2sbR->0bMx*2ztaZFYOz*MFzb5h?~uGZC@c%Kz`Leo7q z9#^;FiH`m8?`+ZTrs+;7S5t}DlvBU>G_YA0RfOhmE3!14E`;u^B->RTQO0!jOb%-q zZdXk?DpsG&cm`mh|QwN)1-R<%9TSkEE1)`edb*?=qQ>+)P;wp=;&Kd=@(Jn(*k zXnblsuP;q^)tH!=j&DkMo!W=C)4EI8pdIyQRIl9>L!{W-1HozMm=H=0tf9*0MgJ>c z1(nVME1Rd(YO<=ZmqA}k&mr*cz{YU?G)MK+0x+V*bV_^1?-fREG|- z9kf`D0^mpI?fy{19FhAgx~xr>6n$*Nz{lMuN5Gz&(LM`>P|2 znt<%;Ytd4G@txK-;v0=3XGO~gcahKSvev(n$jlz(Vm)RsTm|kI^R%>H_9zWo|sF zI3^KqU;!a+SkVErZv)tIan7=3fQ?9gnC3E~BV8})A+!)IwLM{rma%9S_e zxcw3FeD@j{%qD6O>>kS1)i;^zIbU)TglVV{SpUpf5Mwcs4E=SfFy6b*y`c&#q@xi# zvt%?8wyT@BFe8rjuRTe*`Xh_uR0+5xw`3l6$S976GB3bXR+zo^vX@nzy+r;%Mr=R{ zXL1t$czcgfg}9nKnB4KGS8!HaLnKcg$u-IF$O|C}5RIM8NC{qrukX{$`%;8I5zslQ z;~;L+tTxqq-HyQb&L-n~H^$GPK%KWoh@!(ahAqmZv!!Q!dP>h8MClmpiR@zW_ZEl1 zgKv9`kx1X`p&Z@%OI$nKfUi7Gcu<)_Xx0b!fk;MaGhL~;+l8#w6qy&BSYUyeJbfSFu# zL)0d#Rb}y8dEHv>kQ9uLKn48eYZGdnp@=&AKSQ+%2TNklrl2yS*ZSpZNdPzIBNHW_ zUnMjo1!WbT8Nv*+UW~$NnhS!9oi|OiQMO%|y!ih5eyWfcT_Ooem8M91Jdt+CHC|-SBgjr<_PAMnb1umDXWfO3l|2*=%QiK zk>{AgB-fpkal+8|gT2KLm5EvS`?Il$ytK{g#_(1l6Q3I{88$v&%^@%^<0)=rM`UOR z&;eMJ!mo)p$kT3?=WlXKq#_7Q3lhafIy_Afm8_t243KAhN3vE1U;MX31{5oxRjbxC&D9~CoWCqWeC>1rW}bF;WS}U#lj=94Q}gxZE(h5_zQbhu_M0-Z`nJpHwliP~L z)qGL5Yy&{59k>fo_<0-6)!a_QLEkUJk^SoC%ibcQPX#I~AM-u~%*OUtEzT+vl5Cp* zledc!B{e*XMg8Fi^5auSyxE97kZqJ-5*UBI$NoTpSey1tftoJbIEo25sKsTL#!9Bf zBlVj=8c7N4nzy505Oj$tCL;wpRd^ved=wp>7$7xSoNOUne;(2JgJHVj38ONEpo=IE zddo4g;Z>t1?`TPv+x(9oJz+#0a8zs>m7jDzYAyZuvQ20So#1h4^YJygJPAyOwLo0s z*?lM;en$I^=KF6EAGGB^cBw3UU@-9g6@cxYI8q;zjIu$Be4o+!-59Q+YD#O2If5rs zw-QeEZnK;&2Jy|`nf^sq$fq>2F!EXk)hNjBn9SL?0)J;-Eu#N;!?(#Y?lDnm z*i$p-^`Ii%Xm169>E*5(nZ$@UoV;Q=;{`P+^>T+k1>0R~0^;LawD)&vc{%cm-puz5 zzXt9#O3-5zn22)S!KNS-7<^F?!WNtr`W|+n2!A|Z}IC2HQmTd$J6TMJ1$mO$?bcw6oMxnEDKff?PGufz|yC#_2Pw@;Yj3h!a6^|vb#Z!h# z-acJ)RK*wFD)}1pVhJJhF!JfZ=Hp+rUsNSeQfIiO|9*v1zeD7S;Bsj|v^MS`tpBpG zM1%ElO-Vatuq!3#eW)=kd8FFu1td4iPD`-bJ{M3N{P={trnjRc=#?OC@m#Fbhy4f2RT( zw~$<_Z|Hl}rN==xA=A#Lugll}`}=GE+!qh&J?2%E9Bn505vRi}MP7$rkIXpf;;c8NdAsHCs}@o3KUXqo!DJG1yXDm*sJRs|G$f% zeu=o#-GfQO6sw#HRaT-08;eei(fIRkd=zJKIe=*2hbIWD34VZCVWWLGpiJe;3YD#! zSk*5TI}V*WI}SCgbW_@t2It<~B>c6GJ@8h}6e@g+|MMqSkHCD;@S@xF>Z3+oMdn@qr%8g#q z0l{T8Qd6TaVvwsY*%X5+4@ z_KEykidHB5$BkM_4}z0!KJeEb$ecetp~%6;pf%{kJJ(QB(R^}3_4TEAH0#4=oBP!P zKWNDoMH_50`~#T2m)VF@2D$2&u+hDc9}2)vP89Me-T$qD#R~h{MgqCpjf0u2cWe07 z_lOs114Tu-y7{zz>!MQ9njvFMneLm3BRS>EWGJboD7a6Gpd?+e5#bNl;x|5VKB!VE zlHd{LYe)SYh5Hzvw%nsk`}&_+71p5eUXuEK3YiV<$(|6|BxQnXnnGv!FquU)^3X=@ zv#jV{q=@c+Nk5=)ed-(~+&-kJL@70s`-m*fLXgxg_={%z!#`aW^0&4Bx4#S0eq1V# zTt@s5$QN9b;lbze39vk;dmw9){~xFQHwLeV@yT`_2Peixdu`y?No=Q(NkI=*MNs{I z2ZfDNc}?rr<@<#{2yOsSxJm^=`iyR;0hE*R)x$@@Wadr9yE>HrX&vzskji_Gl^7o< zQ{#i=9{0R=ZaC~o0{+_f=mx}7f)A8Nh(?a8u~z*L^MTAxVY5}Jm1H@=P%2Otq%L!q z%=1J3cNdjXk-R*t;DwKw!!Wm1@MzQ%WZHu#g=O@^dJk39-0Zkfz#B=p~(pz7o6qiJ;QO6hFxV5J21r*-4g zZ2$eaR+DxcC3zyt{3mRRq0#X(p^P&YBDdIKp8s?5OwpDAoqwxEUg4Yh>~?!>!+KwWRe_I!0@S$ z3mwGAOZ#Jtz4oYx+st86{4AV!vF`bJ^NXZATm<1}6z6?CBTv4e{n_My-Ur=-K+5~1+&@-!YZmdU0X19) z`n#(yeybP#t(Mg<^K`9C_{K*f!f$Sha)6p|EqHDKp;C-ZVvX&W%`PLDr z7IkRgZ5LgTRsoJr-3GEYQC)nMiE~#R;Dl44ayN-S07ZOlVbw%8QEK$TgUW4XkUIUpbI^Wrx zsI)R4mV&X&O7pVtLi<}kSr9>UfF%Lj+M9F>H&hc75XRK8AfuIFx~!Y{U>2qzaCIrD z>}u4zp&_t#dWvT^mgoX$M3WE->~>qsE|&9;;vQl3w3(FB*#TR>V%9a{#K0vpS+MMB z?BVtUYpna)5*hn#%o_aCs_~uVY8APN@f))TF;K^jvIGBYzRy#@FFf{KUI-M(*4J1# zTM4H~lUE$A^wb(RT3Eg_Ta-%j47>Du^xt~-5dv3m%IMXdVEkyvAvRiWp^zsBT0ba? zC72$_9fk(0KjdtNqRJKYX9N_UKWiN0F%q+zd>-d<)91KB5wdk~sT${kqT|e|+T|bTPi_B5|!opj(PP(8m_~q64 zuANO0nr*JOP(yM}4|nNRV8q6#N{rL1sWl+b` z94W$qdSo#P23KXE5`&XEp z=!qyY?d4gV(#oV8M`MJmnBD}f@vMxExm}xY$~GTmB?Ff@egu3tmD?`%QlHTBUc>+w zU4Tin&FK3lPL*`22({F*)5R*=zTlh8HlgOs*NFjHgt(^X!0Cs59Q475Wj0byawhTo zEYd&|NN@jUnexqZn}R9`#WRu&fuLGB>9GWr^UKBm{S84!J!i%_^+{fUSMbB$oYDEl z9<){xXnZZadAjt^E7T64!n4L*Ux=R+yrI|NA>`+B>P_OuIhM-?Fm`iuf&wz$)fP0f z&_YKujrSpxgJl<%!=g5EIFQz7hXv#8ZYckQMap z&iK@|kx`7LAs;eG_W{iD0ycjmR<)#3&Os3>YepDFO=s`(MNl9fVNC{@MdbNajOXR% z23H~mpq*ePg{=%0T8G>TVM!~Qm80>l2+zk76DXbo z`90iyaVu8z93Zd5Ob0;SFLl+W*d(+P#6P?6K1GRS7#==Uh|MqA4z(R`7_aIRA<~K3 z!mZBot$qj~UCJS8{+D^OgAp9M8N5M|K?8e~pJ~15?U*VbsQ_p$)vr(YY;JG6(N8Z< zG`_nPd_P)ZVi(BgV-@41%Ps=)D{pUT>=O{odW#>(!?(t}z*y{|q;mY_x;3cC6<&#G z0Ude@=apLnc(WdTy*i){JD#@PhFiy|>z2XuG#$RR5APjk3@u zT}rZP^)DSV*adTc^>Qb*yL6mV-k0bZ+_+jr&f4}2AKbvtr)m5T1!U*vJUz3_I{-2_ z$vcr5Zh7g|9iTU`-qre@sKEc>AVidRHsmf<-Yf#8v0CJ@~mBgKys zD-{n@e6LW)UiMASQJC}}tockkqt@PA^~e(sC{s0>qZl{?(cl;zFHr*W4JajW#a};w zc0c8*arJJ!u@HumJq)k1X>ua=_^yQ2k3a+2leEtCe@HK2Z~PlO`a7wnhY~Cq*gsbh z-F|8{+rf<$CYOMhmrd_gv5TYSK)i_t>VUL}{x!(Eg;xfO|4?@ScLzJ$H_Q~LlH$5l zzM$bI<+y+6Y0zj-%ie7#oS^3<#i|-{y0y9VbrmgTrkWwi!dZshyqLu4fHX`VtF1kn zf%TN!1wTtJ@JC7e7aj+4b5nXJ^2nF~IU{KKOCp&*ZK) z3da5Z5fO*G5m#ma5UrDhf4>P7CnYJuvv&gf6~F?M`Pqe~PE(*5Xk0`wxQC+aQ>l63 z<`0YcSO==)%fX`TlrV=(j!29I4 zhFUtTO@8cIXXxNCM^rh?3kja9$3Gf(>`0NxB`uG@CRSOY29I&6LkI|ZCkrd6_?^L zdZ$l%OpLi%zJh{JUb*nxd!Vs*%xCNVQ!Iu%E7}yk68A<# z1t&~@10C!Jso!0-tGPBn=kz8Bbvn-w!u`f4X5Ew1aPwkY81g95h7yF~R_T^`1I z(g+Jo)`*77sdJ*Cv~5cpf*JDQ7O$2-jax~77AMElLfQ8gFB@&ul?U$frV*@*2)lE} zQFQlw8$1(5{o+vp$g1`)ng8c+e@)7?!xy~FSA7K*?f5g5n=@u@!b~G$71@-#Pf0%At%hY% zQ8bFRBIvwdXIQJtP!4bH$8Ll}kV5e!Pi|YPSvr(RP+7~wsZJEC-HF`@Gg#4%=v1R} z23d&oZ9-V`84Anlq?r5D(e`>+y9=63tIr0nhf-Q1hPhrVCUxPU0R+wFE=b62JwdZM{1rxoDD=q283GpV^eHw-* zyQTfQW4zP?{<#y9uQW)FH@~07DXZxZ_HB8?Z)#f~cVrYhhlv@LEZrb3cXPRJ^Aq%Wb0X1?;fcvIdd0t-!<2e^Jq` z(&GN4spOe|2(nbmsQ>8v8~OIZn&net+D{9$;IUmNb?ceFkl)eJpOpt>-~;dtx{ahW zw&Kh`^j6HKXO-6#WoXK&?cVcu;JaWUSI=z?Q9@CA8}-dYaZSx2H1rQ?`d*9_`SOQ` z9d9xZ!_vG^n{4-W#cyAbZ1^k%Rs_^Yd)8ZHojn4VM=JkQ*5`TlpRQ#mJi~Nck*wWQ zpS_;vzy0qVJQEt}RX9l-Kw(fBJgl&&NNZPEDPsX^7Mi{?KwYR(&^SA8%s-(iV3u#9 zO?h+ZXSl`1FAwCSRA!g=w%6;H-C|I=BOM_G8PAW7upW~8WZb1rPJ#>JSfiS$2)xgv zFZmV0bsRo9)=BhOMgDn+218w&(!kA&TelLd@pHc0=75FYQQ3e?2G+N5W|BmF3?kfi zhSdyF=hdR^s$o^8nt%?~L|uAmz`KC@w(gDtOU?FdG<~8*UyUwAf=x0en>Nur zOJeuwCFcDFZQP$b7?(`N6e1irLznn{Iy;;fPmp(ec(kwHW>>YJnI#5puuwSy4StpN5|276D%oZpA;~c=I>tbk>5f`b#2e9 z08{?%aR$r+H*`Kby|p`nOIP~7i(c#3f+bNdfc2AJ_HvNE-6Xy5HB!R0bpin7sVvSe z>B0+M`NuvG`B(wFZnZnZ}&G9+fs zdJJOTlRG7yOJ0p-O9pIQnHY9?h1Wa!OTJgYH46Z7M&H0Z)ReQ|d3R=d8knw|%5F36 zIfcH!fVR%V0p>QTzWS4e#B5Iex*AaDLP%B-0e6WqLf`)c+3nQt?_H6dJSH7AzF<); zlw+_Q;0A*3$fdOfOgVvF9g+Wj?v*fd3qpYa_HjIpxLgEB3hxa42WmzRcBf7-FX_$Q zn{^i+v)xBnN>>oV-qhCcYGb+3IbkmWp?=Fvty;4P|-PtiFl6IGcISA zsJH#L(KER9-$A2R?BMrn)mjWZp&x@pX=&caI=a{B%rqN!8NC|VZOTE;*`Y8u|Ea?^ zFtlHTzb(egzIiT$uw;ZfEhO7DIbcyagY^!DHFJJAQ@VDIX3ask6f2y~7s$>>>$N*| zo9HB%M1N|o^GN*Qt(L)_jdNUZ3C}&O3~MJ@pT&+!-|1ee7?GDB-oS7)%nLMECYnr} zp=|UYI*A%JBS2PXU>YH>Yn)87jUpf2sWfs|Um<9GKE#szORdonL{V_~(7; z%{~cpkR)w*^ZKB=fr0HN375(&Piq(%pLH@fdZnueFPz_jvWSPuX|>OVn0QkTXRwrc zpDuxu>*HbxXG##7)|do!tBfuaOv1a)M)5a0)wgfoTpPI2D8Mb4A{^{3u$4G)$=R^i zdSu$S>TPDW0q11btwM}AGzbw^pKP5&fWemc?5xVBf+JKmI|Fc_=rpKuBf4`atB>P- ztT4pkO}fglCy2zhrq8CvB$bMI;iW?%Bnz4Vzz524YHS$-hm}`>zkj$VK}VzCFTNjB zgD;^seeqFm;)5+LK>21@lmeumZV>u+;B{vvf$5f+hSZ;J&fvug&+zTd@U04Sq>8<=6Xa4I)v5<{<2n^~ap0e0rR7MQ9NgU@2$qmWC66Cu|6 z;BtScAfSm=hrCIYqjqmcV&)EZ9z{{p+iV?7Samgb#{_|O#}VfPkv^uY^RvKs8_a_^ zP66a%u!zusT*&?_@J`yc>Q1KJ40~P&;J>M`nC}x>yzkciIA_e;NHU#e>AY&vb`vcu zo{X79*3L9~)_Wh1!$%ypmkRqg(M#ux!Z+u2#(*xeEp`pIwy-`2dv4SK0g|C6=VaEm znIi~1#Xz6*jH53N&iQGfYXYFx^+tFoU zxkEtkzqE39=GXj+vomb$PF{0F`}>4R$J>+1v~;W$JbLzi80Ci587}znQjFoio2n3IbIZYXml3in1grsFZT#r~4FE>=B#>eCn|&^=efH*Bq|>B@fX^e$_(=G0 z;917|;JGNeuE<&NOXoktk6IIe6GKD^g0RwK z?h}^Y_0^@nWe}CCeY)>eEfp3DyZ9Vzcd&GI3YVN{8t$T`4Th`{aMODQcY~c-3jH53 zvLOnqXOdp^Mzi^J-nD77sFuB=SELMOO^+;U0s9@yp|!Mgs`y&h?Fks;=b?U&43&=v z2V7WiHziaUA1Rk4&w_lOgkBXI+8LOyB5M}m{Mv>%1dQ!sc3yc#yeMI$==~Ev3u@D7 zVcO#FA|W5$)_%1dZ%$Sh7vl6#s)-j#rm$$~yTo-J03vDIT?iNNa!Y|%@5=<`;)zd3khjDZ z*mp`1pcLjlT+-U(d+;@W6O?xP=v2`#aGY6EonKE_BtH3E%>;XRL4+=g%1Vo5$+C=#5_1)a$RIVz|X`& z-jkMrDU>Ob(?A_dmsEQ~f2uuVXi>o{WYf42(a0FSbho)-rjX`#}S z=V?XuD)R^F$c(>ZPD@EZ1dqpMjX+I=)5EZCI`l=~&3XTPeYhghA)jWf(#0%Ap)!Qy z?OUb?1QQWx7e=AcgJzAAdAQY&q>Up81_^g za_MovxVU4ejwt}a1BJHBN81aWUMmxX{WMXEroi$>MUZd_(89(=y(SrNuPv{qRQ|A< zVflNU?-|7I3vsmET&~47-1IpcxOIDIXGMUhBzr0`&#EWABK*1iE@0XTg}C*h!hke} zJ&xyD6INJppB=2>bt*lT+wgVxA;G;*JAG)3gc2Fd80)CYkelnH!Ti0`cuBG$(Rbi+ z>=CuPN@V=jk9rFj32x<3Fsv#(BcP?_TuhxqX4jnUbV$F|%;BC~XPB37p@&o1Ftn89 zYqpCh7DPGIdmFK=6R^Nj4(wYw#62|S_F5UD%0g&jnpThxfZNI@#ZUKYncrz{Pv;A) zU~kIGvxSuV;W@Dt5#Xr(P{=|Qa`&VnGQ;=e<7u0^FVW-xCan*TXX#B^pFgkU?5gkr z?%r1sGLl0QT%A`SUov_(zApRCZR?~FV-Tb0dsZb+wH|bK5MPyYvW7j9?xfH_!b9k{ zdV)?b)XbW7Fc*djjng+g-5WoCYBYl)==HzkYUT30-&V8!Dn$M1%f~OcM95*zvq02Q+

d&&R zP7Gn(&3IsGEwd&%{&ad_oW(n2UuA8)pEJ4E(WjO8EpZX3pBCBfvwwpWy(MORVU@=Y zq-v^oT@7R|U+WBY-%^p4efQa$eM%#J4=8l@joM0@L2+=Dwm#J`dIKK1N9;E#IEp`- zSDM3W0bm6z4bp!|181dCBzGf9TJ={+X_;=?#3*S40R+7Zyzk+uyE}1Q%UF%ofxAf+ zkTkk3q5GrNW8ZlzLdoYiyIe1}PIic=*s}A+^MG=da)y44J|2>uI{l-h_h(QZ_5PD> zL;(krjfJBe)zvNi%*gqLXRyi~Vf1sc1WPZMoae6W&Al;xy=L z>i^5tKwLS`?6*@?VDPm$C$a(oF!(W1-vQIxoz#3y;|qbHQt`u_q;|KoywFg#>31Wu z<6Qi9MGhH%N_Q^Y@Df3fKh;sUJOE%g1s#OEm4aruP-->&;D_y9H^&M+&rueJ$pZkmHXR38n++9vjyaVF{5u3LXyejr7!xlB)8*5ki~-Tq`- z;iCg8_EbPgpBaq9Ao|tvv3dH`zS((~?nd}-IWWM%(8Pd<0{2I4DNgTkARy}u+z*@d zg@F2eNpOY|s{8nYV3Q}@3e}PgPH?nWCg6qVRJES|v_G(zEce`v^_%Jr0!n;NvX$y0 z^CGQ0HNkX>Lrzh8uJSk()`bL1l-Su_b8ur~DbSM_&zil{v?!p{#uw8CF1 z=le12P$dUcHvX$Borsa;+!~Lm@r-U|{Y%~S&9=X|gdh~J7wgwBGP3vAvwD3!$L<~i z?#is5USpi|roOt-Kg`=UR-|b86()^y-T9`I!=o)XI@we{95g5IBxMCTxxghfe~&!> zJ%mb8i~l>iPJvf$uJ&138a@{R47r_gEgDznG&KvA%|1``aXgzAaFk1hh~_pHk*oz# zK9;ZRd%?+l>f)dw%;i~s{uz61Ui{8#=-;%sxd6e{fJv;)0r<`x3e}B(n->Rc{&=j% z7d2j?`gr{qB!-SL-ytCH{7gDvtu``(!@ zw;(QSe131L2x1c8{96ZORXWGD~yZRg(<2^62#21#kEc|wT^Y? z2hgump$reO_n$03{$lKKEJs7@)+_zOq>2j`X75iB69gm`6Zel2?c~BogKf)mL^xhA zuIlJMA?`$*{|1;Q6D6-gSWW@ZIU;CcU|_o{cOW9Tvk&+aJv$jS)gUjrk+k3oX$lfZ z#q3rCj==D^7&?@{l?yZhRDcIGBgbI;Cb!UI9v96tid%}0ba-vqam9?f{d>{fjkis&^N6dnCVY+I+`=rxQGYW7c#^JHQaFR7CzN z*J*!)pzsO7*lh(Azz}cZxm<6;yZ-*ohv0nbtd)u6Dd3>StVIyn8E8=?7e=!66Aj;O z-~-bGQOH2?7WFY&2w`mfeL~Kh*Mi2PJ03efYoP-WaGwdP9nbi8^5G z6v)(m=WSJSeBU{wbF@`_m{Le@`o=%Cs>EeIl+Uge5JP&In5dM7&Bko&=E`nz(mNaXP4W zl(qZ5>7yM;C$HFJB$**APgrb(4<`|uLY^v&Q48{O)ksWc_@FfcT6fbZ?%JbgaaI8S zu9U!E#+}LL(MWm#ZlyK6dloa2lhn#7)3tx!rE@Lo{n#Vj-${BIf7fPUM59YIgl+-s zRHWW@{GEneY}E6aZA_ivkY|KbS+{3_0>)J5qBKV2=JG;R9NKJ9=Iy+w4|E8~V6r$; z(9eL~Zx)Cz^Xo_c21dH~JCEX+I6iADx;YkEy z0i2WTFrA4r1@Gs)3Y6UA>4Eyd3N%z5_;uOW7FldTiWc@r(`c-5onvb{8JWF4|7%_` z(kLIpdXUA8eFsDYe`Hn%P8UBsKtzZk9^lmVD|)k` zPkKg+t?!2$FQ!$x=LheF2%$+pi%obzc8l&34^Vo-dSle2S^+uBZ{q9xN9CmT(UNQ^ zxeAeiA?9BA!CzDj<7O63^OZ;dEOG~Tp=F3T+%Q<%hgR>at6W-WU;D4OZ2slTVWM@3 zb~^}e-7k8MW_Q%K`nriLluXvaR#VCZ#Ue!%*6zQ8C1}TKKAq5umVLeL9xVgMyCut- z-z-l7(U8^~c_H&Z{UMo|1(>*%E5|Scja$DoV_1~S%(0v*Z%YNdDL+d$u9KcyyMA}G zqk+y) zFm9K@JSX^!4!`#N!0c(hibCTJt>$d}OHh``PC(wq7DZPz|61qS(f3TZp zXJ&~iXWqUq`4NE~)?S?IvPKqOBT9yYG??jjeAt8MXmmRAM9Ji$H9_nWg5EU~NfHD> z)~|T!HgfME903(T~ zHgpj@ehv9_Ca7>D-NMNOvj=OlRP{eLQfd;zA7CwJNUG~eRWWzR)Fe7p zznOpTceCJ~m|$fh)A@IFqV6AuEjylXbJ_vW{A0_wNSp+%mCtxC{JMDDVQI&Nz?*xk zur#1uj|XBx!FN}JBwIS7w_9lG-3$#s&|#KkQCVH2ya6k{>kOqgz&UNqb4{4~W3LjH z>kUxd+4bFt%h0Qip&fsynkw8!J1xFHsKqvPDom@vFWPpkTec@iyCcUSKamRq&Fb17 zPnmzVZm07E2R?P8vr!I4UuHF{tBg73>K})_{MYTr1QJpO5P_MkuBP+raqT# zfCSM*uUUEWJ%GEwCR+OSE(LzyQBF>E`B=c$k{vF`Rl{6nw?EAaef@>TKtK7e*3G7j zZ}yM4g%(nJHiTB?1m8&7nrVu9AB{Moz9Cf^qeILE8WziW^t{M&+&tyFbmYki()P4| zlodOaKD>DMxF@ODi>xw@4JS+Jq>x1w(6V5!hVBF4>zi1NaZ`cM9^JR6n$j}8aXK~P zRNOwP=yGN%j;4Toc1M@{C*brwe5gBbthPSI79-h46CsW@KA*%?e+ImtHlxr&$PS%> z2y640j$5H-`;km!+;NncG9ki~RkK?O#-lQG#d@iFe088DIk6DC=D zBQGrU9CFtJ2Ro&V1JFrW(wo|MC?LtQY`z8|Z8Y+WE9<>@N3x$hDklQ2lXJZWtwzgI zsC;?FMXa$*QL_l%L}3!wCSFO-ln3{OUvL3Hs8H2P5M;kUx0VLCne`U6^t!81V>3*@ zmtysE*I&4Hj;Ou+(868|9c`=zxBHs>?>0))(afA4^qAqu=`7gt!U+>!DSiT5Vx;wnbKAUi=6R)nEerg>Eh~I-j zW=}aJg6{q?JNShgWJiY#A4!M=h^K%B!H&`Fv}+V4Y$orJ!}0GFs%M=mec29^Ww;hV z#9q>lkHG>NAv-v41CI2Sxi`jUBm+*e+6fsx5A~e%Peh=1hqz;iPsa4u%Dj~YT}$WVKV;4m_-E9)z;e4QsqxwmB{J)@`g#!s2UC+B ze=!vn1kO|AM~|X;uT=)0S&A#7;G%!8j_%_;Lx6nsJ8+U7J>PP#LqHsNK;lgUh{EJ- zz5f)@1(Qt=L52Pz0P`Gpuk>a@x#!oA5r|#QRkcXu4%ngN)fEmC)p2T~ZN7D&w!Ib3 z*X`Uwg$OT%Oq@Rv7eH>tfSy;h1p$bVuQad*PvXn~p4|_Y;JR{>CP&sMLweK?U*g~{0gkM823`E%wMc|c$5b^9+TTeTpw!WFnP2E zambt9J*I+u-zz)(~ zcjgz_^5+vji&zzj@8l?rHI@qu|O;$$fZGoak`R@?e^WJDqDHN0n2-yt--|ZJ0)5vCOPWMil8EGSy`__9xo-nKmvAjI>>szAThS;p^QwT4%9A~{fq^n zDum$|bG0U=hjWi`tQ#^=Cw{kj#U#2`mtTY0&MV&?48NnG=K*RNPW1fezrR0{+FQ8| z5(W5DbUa{Z>Y5XzK)Zt()w3Y1rF)1RUS5-TS!1OZ9jUy_=#5`jKcpBKn56=^!#g6M z`eOn-DY_b9#|jHdY?A=hngnBG-|rtCWD^9>mN=pts?*|1@?Oado&@d$)SPJW;$dcl z>1`%L)qq>kkg|a;`32DR=udqkScF_SD|#Sk`8&AF1_GcN91XWJJHK2xUvP@{4h? zJtcWRr)}Sfd5%=xZd@mwmZlKjF(0cDw})yhGw>?C-}B^Jk9#DiBhE`L%EXY_T^T(6 z5(B@?QU~-Ak z0_FmHLJp+;hxw0+fqIkA&o3u3uczT1@LN@57)4QQoZ zjeXfE4yJ4$KO-SIHa)w0!!4Fkt8Rgq?@Y=GdV_sVeDNYpB=xw`f+8s2^OG^35fi^3 zN@l`zULo#3y!Lq$y%9Zex?h5fL z7$T(oXAn2A8r6EeG;k}1Rg@`stnnl{yf7kGr$BREpVJopbtRf&WhJ#1^%Ph@I`*D^ zDGfl%!^G{)rr&7?_&sf08+H*cjxtpkTz}Kq7b>*OWHQgIVD9uZJ8`3?pJlT3MTAN; zU3kUL%^!<9@1$q6hU6qQv#br_Y~4nbBNBpgc|{Rv==a;e}iz5AGg*?LuqRQ3K- zk2#f_XiR|&hQtU@Tz(Pvxd&i}PTLj~Zlubvg0kab>H|Q_$U1(72=DA;y*=_KNL>tm zf1<*{&L(v*ahEN#_-Xx(JI-yXA#w2ynV;zpUokG@??>iS^)W_9yz(;6WGz%hg>?SP zq#4Us*X$vNJ;i2@XiKGUjvX7|%Qno_tbDdDb1F7FwFcr0?WreHqKVyU(~~N+CNkU z$C{eLy>thwWH5Zvsz8apn}RLVm=f2EV4tm^Ge*9xHbzvbBcj}HqyodhnlQFmT8|~d zw^(w|Ou>w$)^Y5lm1^o*Z|iMBfqse59G5e@xT-23UiM&{AO%)=&u8j`EvW;pyj0)4XomCdkdEp)RH#o+`J~ zwX2FBG)UOz9r>hFkRNHP^ZwI$h7Qx!GLNgGPwF8K2(TvFuQ{6?;5K#O64M_bHZ5{21M{WGV|#6E}auSsgd(5yMYf8$PY!yPWd;tGwF$jF@cyduI+BitI>4Vb~X~1umy`q zGx=+TRYKDq49Ss3AXYeb9m$l%v^yq}UYtA<^+|{9ZxsDbY(#JTEPs0GlQ)<1r4-NL zIum+)2xXs;l&w?M63GN@(>CBBeZ8x!?vH`H;pKWR?AsmVv=O*Yu6|#YS7-C`GkXj) zGtJ|wVqJ0w4L38u2Pbah^Pz1m+NiK-oV zc^ftaFz%;Cca2dEW+ZPFbWSA;9x~=Sv)&ushJjgj7qGF@5=dhCP7!T#LvW|*$H+#-b8!C(>tn6 z|AZ6}BQ9k|73@?#DB;?@LstSUUkwpP$TXEWX(v_$=9Qx^Xgk=tmfrUc^J9R{tt{=F z`~4$Sgm73m99>B=f+6W1*MGjmr>BLM2V2SaBdv*-xv4_pA)I+hP80G}ijl6&k9+*s z`jJ1stbuxtl5an80j%tH+XaFOh|H^pf;%v5a*fQ^GD6$){=I0l(G~3&d2>Smni|s1 z%y#7>uEBF6Ss)Bn6o8WnU_w{hsZ7Z0zDxaIU@lz26;)TO;*QMS@QWVy$eg=)I@d*M zFLU$s`VE*P3eJe$3uw&H;XYvlVT8^nfo=*D*T=x zLLSH2td4a?f|XR2+JuWp?DNut;hlWiW;c713?{S+k%NxM!*AFMJwYb)zg%`$7xi@P zOn_21>r1tZN$$y(%57qLgukwPNP5Iu<-|&zdkHNHR)JjfE0&p$R%)IAIamJL)pxi> ze_Q_2idf<5AWOVX)!1w4R8=c*X+<5-IG?0786vo!?Thk}bYLPWx3K}fqI^~!ew6A~ zW7(4DJO;m;wld_XBPK*2=9Sl!7&-L%b;le}m`(B4;JB;_D$~PXI*98_k z3=6%l#~yxYS<_Q#@655M+fpr$JWH25cBqD0F(-&NcAHKVg?|LF8w%#9_xFGE$9hQ?2KTGxt_j4$R=c!Mr zey>MvhOftG^rB*`-sUcR=C1EIGrd$Sz-ePfxOJ<|fMzzstW)0%a!&>BCpWt|t2-kt z@ixdgfFt!UhJQ?i__y0n#*@h2&4Ol8qWfIu5AwI|a-Ss%+CI z%_BFt-|;s~3@BBr^QG=A=vHtK5;F7;ed*>qaCcDIoa*YL z$Klxw`#-!LR^1}bg)!C9_Pj0ob5u8$@7e@=ngu1$C?mi7t$3s@M7i^GgAt(n=Lis+ zM<$*SQ0%Pep4t=${d!qU5OKq}H?&=4rGL7MTA*@o3Hdg{B(d|DUwP311S<#RN!i9! zyWP~{O^gmQ9Q}_UCo!l3ZZaLk`MS7OMhvJuSHlOQlX4MO@-tswxv6r$CGYOY$BW=} z#n|Roh6V9q?v)`#%JjRe#cnjact=+S#Q^p5&ntr9|FH@xXs?Y-p?wjAV)C36yhp6m z1k%r_8e~3EN2jk!g0L`qNCBqvh@6)+k;S}US^05N%GVc3vf6q#mLz)>HP1o|Qek9Gpf1)}y03ugi4o!z|p+MjRX_kG@Qdm1F-V z=Z*lIo=WUr0xb0G%dc-3*aBts!CZvf6Yy}Gm3zzdX!n=5 zQLTQFs3w-|CO@zH#^2-9%7nmjSvykZI4}1*U)EJ;D?vm?6Amr%HDF>*hF?gITEP&h zhO^1esYWbYm__b-LXWWM-&}3OsRUV1_xv8aTpd4ye)Do-c-()?BnQ$-c2(Xbv-Wj@-wI|S^xJ%x@*o7m_{5-BYFq|cs{DsiZs?H(F zsRp)%LQ|p&;&iK7;Za`+=Z&1iX8MP%zAnbmq7;I2C$6duh@O{CXv>2XnQTvjERbkC zKkqZRzi>Qpi)zNEhu{C_!2m;#h;Zg?pr5{BUQ5TZ{X7?D2XdTG6#uVI74XY|R#oV5 z`>#>G((*a}V=7%SH(cYOxRxb=l?;T0R7z}A>_jITTDv>Y4SD}@!%SFa(z*Q<$!G2| zBBif~;3sg4tFZXL{#@qs!WzEux7z9E=eC;<9~YKx?~y7DoP$!}o~Du=6=&lGzKv$% z32w^Z0yZU}i*c+Qeg>1)o+1OeJmiMgz0;}g_Y4H=CEI%?@|UjX>k@XzHe7o>WJGQA z=(plVdvLyHW&Lx+(uu=JE3f~4{H^=zbs(Cp{D!0f=ZPWz^BSbFnAsc3@tOqW2eUuY z5he(?hKQp+k)zV%kKOh3V9V?Nly~-SO)8mRr9!{dHJ9^&Q|BY0A0|=x3>$NWYvvr^ z%d{DFIgH=k2dbffe8qo`VX#`Eg5Qa$PgxAuU@BuaDXRN21YGzq58Uo0a@;2E0EKT8 zR-ZET@LvNADjeDrOH5si@YLN+&Niv@L8PSP?WZ z`vKpRW?Zk|#NT}8YOH<0V*Wv-u^VmM2Erk54JF2Z?7kk4xeV7Z1bzBA(?x#u(x3wEFlhmvSScY|4;Z*ay{+VUeu@L7Rd(+b}G#vjYYRO zm3#Iys@cRJq+mhk!El@4M-$T5R44mTfb~}T|I_?FA-#vl%kZs64!@U{J;p!tQ$n!^ zfdK5^OJ&_8wNvMd@su&IfOeW`2j@38P`&wa9-%%Ez47W&NTU|)OaECxm-FV1z$mN8 zpxo9DPQ=gXUI|%mOnd)!@LL!F|D3%H|JR?e3W9kY8fAc1&GmjsB}k_u@fSP(3>he2HIx+t{cv!XDM@=35Dz}pI`3{%<@#1_R@CCq=scDN(12>pBk&D|UnNWKC zu2)>TZhT#BE={~9BQ5V0Zo&6o11#V*DN$AlI?zYlHt#d@bY>WDE+)Gar=+bn}FBMT&|1(nP4f|a`M>-xVC zHcbk+pAE^@Ve;CdS36DC3P8COuO55x9)hM?iggeD)~ycRYaSZOAj)y{C=j(fyV3pS zLQzBT!{wO+u$`I`+(RyZJX+z^qTv-f8Ni>axi7nreUBKH`RjF&kn64b_FUzSaUEi2 zznQiy*Sec4&5YB5p&FX=C&ON`_}gr6Z}hNjCG9*l0Q@TZd4=pFgwnr?A^-C*9DiKz ze=yS;shdU&TT#UnR54(V@xzGyC4Cx2iSwdFMVT;Nij}n3TzGbXP@gO z$2^aZ3tJp0an|1i#Q4h9z1+KOIo?~QvD~|?FT$k$Vp#X8z#=kH8uhLAy7Hy#^eY5h zJ9Zmwx{&1gLHF@flgef)?2Pkc4*jZzEKRD8_sw4{jJ|+MlYw8r=ikf8m-obL%N1VA zmwn7|;U;v*)be~&#v3u%#6l*8?e}ZQ%Y#-DfU+X=mq&FKXWj=7RX#qX;v`P2Oj?Z=tI_D7F1Ygl4fNuLU!JU`4ORiI5u>d$UVM4>lb~#^gu&R;>*4M zMr7BCFz_O!II8uxBL(?r)Yk32frEA`F-xMz$SRFL&|>e@J_=9Nt_GT*f^7 zQ~i`SDdUnf9XlOt+hdpFhqqhi{p{&+MK9{gp7p)9uCgD!WJ22S`00D89bX0pYBj%| zUMS2uuFO*^z_@@K&{}wOd-lmBkhh38R(M``h7gS-O2!N;jA5aBEp5kUv$cN?Pu>h& zUaBl(vdysMU9D1O6ub|>n=#B#EH}IKCK2gNzHE_}cn0OlZ~9(h3~eyo^q}A4HaJV$ zb5J<#?8rzI$)cI#9;+GMxj{jcSS8YUnnJb>>lXBsep35%zvI~UUB-!nMW9KG=dB)j zBb0{?&FD&QKQalB*4@s9y+mk7sv_i$Uy^znABhLbqX;bhA}jG~25(F(ot-L@aK{;= z2#k&MO%IBFW26}3TB-gJh4u#SU;8SDiVg{#@p+ap#=Nt_pq-PA=k?oS;){=z{bLT} zM_yBg6Zg0KJ3O&h4cP--Jno}>+l5X<%iS`5xH+qy364(Z^tvM4{4 z3%e9(3OXl0l?$^LJ!C($mvF9gwLkOQ_3Pe;3%}g#gfbllCn`Q?Kl-ts+Xz}`l}Sp) z+ou>tVMkGPE+lH?POmo;6;5O|;MM2iWDQln4Nq5(R#H_~hU--?GUJdavN0>gCyDZX zK3Ij9G1tjc#P_UD#r!6n!`8e@{cJ3&$k6n3Pwn1pD1b_pN89xN-KZ)_NR%O7%g%D5|rBvw2(d z*Gs8if!Q^zaFoX_%HG*P>$;=dG*Vw+lyrY*KoNbHdo!?|Y8n4N9BVYl&vOYqr8S&I z{6KUw6p{8n)y#?w{Z7kVc{$cnvR{KVo?DCUG(y5+Do zqg7=tNsQtr@U#;(`YLlS6Vsbpx-dB`u8x!SXU_{B_DFNxju9D_{NWU}@_;SE_-=HS zPC@n{{OIhmt=&S|p3+Ept@PM)7@e2&vgGyUt(&jBW7m27&J^R&)H8V%nn-QtykM27 zLW~jX)cs%fE_P34a&CKO0tlRwf}Y-M?RR3#CZ&ZKOKE)-Hj@qNWjcARi7~H&Tc5&5 zC@njC7yE|9cMYXZM&5-sW*)grF8SEQL+y{*-I4a5jwl}Zy5>F);4(1ZX1NM){%5oU zjd)wWtSY7ilfXRdZ!Xp=Fv}z{Jp6_ImW4a%9n!G$ z&k5&9>t&P_E8?esOgkCv*2w&7+z4p*AVeD)Se1>TPx0BD>-Z{849#Llx&u>%3NIk5 z^@y3z#r;UP)`T7ASG8mjPD*S1+T;2GDDyv)Iw$3L5|vm}pUZs+);N7Lp%P5g{KleY zoxPTNh?|sVoQG%5R#XuHGB&gWla;Wb7#&*E`^WcCMls*|CF%1Vks%HF@@)S7MT`_ zxC)F`ssTOH{?~2+xRG=bgJ`nCNO2ZTLH+b&GLDln1C@@Q4+5^&uD!gb1eey$X{DN-XlK$Aa~kd7e7Q5$C>|#4EUBTW+h;C%hxC z5$(^nW99fK6%d|}kNGVOyEW5HLN0_}o(3)zs%@>EgmJJWDNFn#l;McxZNe6Q-5f^F zt-sfZQS<(fYYR4j>!T#z);4Wp3ogX?7x&#Uw&!3f*~@*CD4S8;R+A$}>J&@#ws@0v{8$YVyNxgFTEw-y-3?_GN4Yb+#6aHCSH4gi z?lePtZ-RL!X1C$e6l(-Ffov9;qX>4MUYPi^&oV~RLv;}5egEv$%PqGm<2$E#I(t|R>^&hSMcMnl!1m9i+JwC?(Kx9;P#m}Z z_5vmG){Lv-mxdcK#moV~cQm%aaW=>{--o&<^W-TV?>kuEpkFlVrTXDSBG#0gV-h`P zFnRLqRP@wk@N(FvK2l zqB>^Fv6ONE*!F8ne6;pm2zZkp_mDD1Dh~IeR@K^fUxgTZnx2DwC&`4Cz$Pd9;(Pl# z1xWuuh5(f;-b8}_#r&XRA+xgl1}}2;X98aJkItA{g-gR$eCoh~RZfD??4JCL8Q)3K zs->?{MtxS3(I1?uOgX1ZE;4;Ct@g+j_*UdUcJ{8iwQV) z%5Ai(bgu;y-Vb8jS_T*VG+I#XU??woZ&IAuWj8KS%vBWi+Y0aO;%>i71waqZ{_%}z z`pGZ_Kc~MTdn*$>3~UT37jYDqD5pQEl~L^#?k`ekd??Pgml%-diE04z~TSoL-l4F72F2! znMQu)0K3lRF3#J5ihG6UZu}XlJurmg7${#Ry~hEOqEN0Cd%rdzuP#lFxnrsvOWwhn zCcAo^!;I`aZ*b*(e4=3UK$~~){UE^toBgp;ffW$jhE9oAf-*sPEuz*Z2R}(x&lEJN zs`vsXKYQ@sr{`=EREs!Y4emR9gyP@@eH`U}+lS=t{Q{z&AyBMMepf#@Jq1fj=`H_} zBJ$qKwpPZXNV|;v%|1{?b3P>Ugc~6FiH^kF7wMGo_hW$b5o*5FcE<0dS;DG)QW5fq z)rS3jFR%CapnIC50ka!)-{pl$t_51nV*LCv?9UX9P}U*YCR0{ZSvGO@zH42_3yiM= zTOS2S?kn)>R*PjRiu2}#_S_@k4j&c)u~z?5a6D`@Os9sWwz(isL|^BLuGyz*4) zGOB%=ev4sUh6wmk{s)ZsPqY+3C&w@$P%7$*mEyEUL!Wde%ThoqzaA+%8fgEv7F2x&`}q6?!z=|7n+0UeCO zcTf(}TRjPSSFC#aF-4U@hGdKM38e>=cjf@l?{IRm&p&%R%u1!g%*u~t{|FX)ALh2b zU{oT^l$Xl4wpvnjd`Dh>9VS35eRFYiL=xI7w*S6YTsfC5{so8q=XIbG(7!OY|IEt& zhS>gRGX=l=S1t7aanJnkO6Y&K6`;Puiunr=_|Kkr#RZ)F{~z&x%3=R?^8DXNvDTSv z`a?QYb^}N`1wW(H`&7{Nat<6Y0V=Q)O&y>=EpL z{*?9hl@@6NbPf6%)XDZs^Xl(HoY6Me>lce<~7y2dv1jnGKs~qI2&>j8vA8T9oq;KMhuF(Da5*l>S zhxTEa|M!hxexP&P%8^>r+h=Tlec_9{I*{GL5@5HWpvE=ojTjQCz=&lF$R>@=YJzaB zX7zvaUF{GuiwYVRMZkAr>+-zrGEdrn!a6%*m@Ln7R^sD!Vrl!nYYH{qVC%+9%QdUtflB+vIlNd|GZI9#XF051#fU~lq5A8Wu z)14mP_kZ>ctHh3hDamA%pj-=c0S1hi>n(|(soA@75Yqm|cl!XlXIKv;>c zHPQujeF9|DM8rE`muEgPHK4Z&{$yto-$FK`ztB)6Ut6fNmAbxz`FD~sCilie4l?Quq1!_*VrrGj;#`_f=sIbb(WNN^ONqEs|kFx z(p22WoKgv{+^j%~)8Yvl@{BKM$_7^hoy-HlmT_q=;GphCc>!!HCY~>Up-ohc--Q5$ zPD7)|MMkTTQ_wfa;t24&TUbat0cx-*alWT@dUmq@+vNE>?1YInvu3O848UBET zH++6^SQk}W2SA4HvEBI~N=Ij4SncfNmi6&r&+9jqOR;hgRO8r=Z(;*>QfS8{5_@E< zz`0--gcALdKSklkG z)Si4oa=}qDl~I)$?QhJBY-Q_v^P2qxpnV!#UFYfhNiJqEJZ%an#jjTlqJaE)Hd5lm zI>oR4HF{r7SBj83B-Fe03)0#{HY5w7ZjkHo)>5L$3%|1kT2;~c;thSPv?aU;8$5@g zzf@xc^@HJNhR2uSUHMSr3*me)4H;AjSsLgfR*@m$brbTWC@}n1wAn$ZKxKL=^=8)Z z^3-Ia1$6WhehA32IicRbS!xPs)$PY08#-9@WkaUlw7y66Ph8uWwg9v9Iq4I(m{Z`# zo9$rEkkW}u&f63jb}o#1XEtdTC2qNnQPEa=KLXMFS^ukb)gu(tsEM$VkU<_kAR8?l zSqMn#B$PiWQ0%l z*O$R8SX2{T%~31^dR*CWK}W0Md@!s!Zi4x9i(YXmf*ll{5Mo0SxT_SXHss+CA_m;}{~ zP|?xACcmr6VsEAIsx#YfDoSUc)?4d&zOWn1*%8Jl&}VMVcQ<9GvPa^SV_Xf32x?;R z{S_K!GGl4apl6tW&N;-g5u*^W3E1CdcEOz` zI7IuP9at3@l~IAY-SLo)NwBgkC*}=Y@tysS8~`n{12WZrA*QmxSBh(lLUksYWd(os z7Exu_S=E2k_lT7-^S?u$9Y)$DhOVt>S-epA%lzTRwzy5c7|}Hy&uF@wOob>KW<+Xm z@%;#b92=l}K$!R*=MJ3$MZfXgOt5Ms0D0Kj0J1fwy`J;{m?>r1wBFU6H=Tkf(0%43 z{h-eU1O^TjW0uUMJ{XJ7j(3(mzBQ-kLWI!bCV9-wl7;>eKUv8>NIRE%gOp{#ikl(f zJ#40Q(lh6tV8kF`#9QQNZudQLHvpu+LO2XUDs$M4>0t&OfhLsKRoLArd_V^O~g9i_1J*2a|$I z@}@IhW$omH4atcB(1uIzA=|PGXxdO}w@Ue38dZr2^;>jbFZ?FIuFQKiFaBPF*;xcZ zjx*SpW)`wlgB0_y=j2jEEeExB`~6eR3qYH!F4rf~^C4nJh%NzUHDJ0SkhIHt3w|b? zm)RNkyp@2)c<1_cI)UD=wcy1E6qj<;C}NZEO%cxXE?XqDGQ}_t%bgc{FwnryM)8~a zl<|2X(}$#4dQmJrs+%u>^7uKRcJ^4GWQh6#0f3*+i|@W=9!gVUuu?@Tq6m*WxVxWK zQS-R(@3JGX&Vbv-3NT`HeeeZtCZfiTpxL^95Qg<>M#wyJR|sf_l(TUezAELii(|7x zbuK7)`74t$N-uMq8aEC{-ew}mq<^!x{z4q|qa1z|99(Sz4_BmR6vrpuL&o6Jh>d=r z=UFENxlVRT#Lxn3$euDPI{+Q1`54xI-69|S%sUvPyh7h zWA{Cf%pf(r8F!ASB@w5n<3*wk6_lWW>#xkON=#bQ;}tV9LR-qXCX_j5XGQLIiL{s^ zXnjK z{|9I-1Z7dyRQ?HUq0`Y^K(aQXi&9i&><`>{q>e4ZSa>&781Quq<NnMh%i|CdY zzWALNP}8@RUagWKZq$B$6aEatRr9Qa9S-9jVdLLRd5kqgZ=4{*(mH;nI1XjHVik$%dD)E?DbxsBBqUtY1mtiUC`<7CZZ_R zBtf1>Q3yv`FQhd_ZTb7{Kez#pX2SM5K|9oO-vNVcO!^(on+wemVTN% zj0Pyf!i}l#-*UNJsm7Ae@J(s;1Sd%~DGh}~B(mwoZf_OR@$lc>}OJ)l`5UoG0{^7q8qcQ%CayK;ANGO;tm&}PWgxbzZs zH%!w8Nf(WG4~b4^<&uz#)dT&Ol~gTvh84`eb1Y{!DCMwAV6(sZ+jRdc29E}4?SH4Y zS3x^eB>lg5`|dz0|G)1u^N>+QhwSa(C}lLvNC;VR>|NHeH`#?mAv?rT$lhe{ zy=8Bn&(-gDKhN*}-uK_nAN`keu5(@2=ks~LU+>rW4?y5wRX#KdgsS=f%K-*$f!u#z zLI3MVetRP;V`3CITw1Yw67WUU{A2V}o}FLcLRE;v*PIp0no-X9ma9wpk9pmw|M9)n ztlhO^&~pA;dM?$5VrTyLfO*%ib{zHTxJh@@odDgMar$z7g!`|9Wv#UCFx;~-K=f$7 zeUn9s_#Z&BFwhduaRW7*v>l|+vi$w|N#kMGYY?2H#Pmgr!+}10s(1M0%U3LYIxisC z{m(xyZebh)&M}ZCFAUqaETRc&ToD==%SKA9m-gkw zSeXwMei#K`_?LqtFXDCTGP>UycgtEl)whIvjkqm}bJ-|$?bb>C?yZ7~7x_$1>7cmb zw6luYd90~PnXdR);D5QLbJ3Lx9m(IpG2AG90W76#z_u@(3l4?QFB+KvkZ>?BjbTzn zVGRV>dU^p-%Yz@!K@C@~4}vMIM?f7b^KH<;UFRN0UD<57#7I@nEpV{IZIZ2ugZ}#A z6)XBhdM;1a)+P&@g}2Os?tC3IC-G4)gND`%>&fEZiUG5@1CV<=V!y_~h;F~bX$K`+ zsIb6Y!4WuID!L}IoNeWOetJ~S%paSv-Ce>827>>Amf7I4CA2#NBgX<9imyPXINWe^ zu7OHTh(e*z36eHosz3z&UZfZt3()|E<=3c!k}h+C5o^4|nf%(k~;NYnTK zeD%lhh{IGCT}qD1E08UmriQaE+B6vTLbhw^;zmLSWXEy!*11Oyv1C>#!xy=G+`3gZFFfN-S(e)ay5=s1j{Fb!m@M0k9n0 z_uLq(q`m=ZU_H6!sVaTd7oeD;9wdvDUa5JM1gIMM&M3EmZ)$vLtLWM$l)=0@YXdTv zpOSYUICI^^|6f*fWU0$B2cKdu3S$NYj2m^t{H6U0x;{vA7;`U0q7ps4*b&^AQNsl` zU1jA7FE6;KP}0n=SI-bo2$qgRc;mxJ#esFb7!P24#rrYFvFRl7J9ygG62J;6C}?i- zeE%Ct2&h{CM;EAMpMi*AL}NX$#O7UTt~BxIhaE|*Elin1hwrAV>j0s?>`@I1G`{v#^faZ9P$S@C3y}c$?K^@cRqqpuL8An z>8&11|2(qZX*B71(@**LB+qqPzc|Vfw@>eb7|ddWCIb+z^OGRHC7RsG@C(R4FLbYk zFAaW8Po)6Qz(_;REko;p{BWMfRCXqu4OA#RhjFqUvzn+ z{Gsa@)?>x$AT*WHtUnJepBLB2fJtfDPCB1v2RToc=1#F5iOcQ6vv@weMlQu}&D$p| zY6qPDNv0Ru3AIDJ!7JakAvdk{(Qn_ns^7)%s9$IO@`k0q6F8hg=ezFbv*X<|SK#b& z&BKPmz)frloZOsfZQ@ZGOh7l!2r$5x&lOv*%8e#XoFlakOHpCAg9 zxN+;sIy{dT3aYnTL+wsqE8`__J5uHv)?y{5{itR#+n6%i9QqVQ6pSpp;2avTwj-gG;A*3+y63yv}b}Mu6r=4b~-P~deWPH)H2Kui)CMcaPv8o7? z8JEeoeO*JcczB1((%ZcYpq05m@;Z%Li+mSGzCQH;_($tIej4Pjcj<&uFqOscUu)fg zl2|XK++#5?)ezXm4g82wD_i&ljw9!?bu@|B3A=K5=`u>T;sV%9+rO&6vmIBtG5%f8 zB*4**%;Mvq@}`Q2J3x`f0Io4j27sM|!`TSEhI0r3Xudj&Y29MKzBr~(UZ=v9YO>1l zd8UM3n`JQ};N2228uDrb5$jq?T6}DnoARFE%^ekU2c9w+7AC5&C&mn*7Jj94EZXz5 zDpqVYuf$5+Vij~9W$5O!AFdy^xc8Hd*&NB6&7XUtddx1Cydb_#nVsaa^hLpfpw(IjnGJ?xbQ*dww` zc5nxS*A$YvRxkDRKY;`|<(*!UTTk%bDd{x2?njQxDLm631f_*owC6zA1>F1u&L_v<-X@$C{%{K_Jl^?rF$j6d zN4H{o=V9}^fTgPC?sd6+l+md#bpZT05r*Z^>WoD$Hypz0Fpb?Gycg(9wHpf2A2{$g$$ln zN|QXwR&4=K|MYWLah5dh<<yXM4fToa>@=l?rm*?j$f9p`g_WSy2x?9lE3Hr z?&WZiv9caP@qSC!wiE~O5K^+uS;1flb-%dXSnb{+3nS~&Nv(Yt%3T0CejY9ZK)Z4{#-TqksY zp9)9$D#f)1-`E<^T~`7d;3QV`geYgj8&nU#re3|>2Hna)RVJHhx@*owyCb1#_|A`` z_Pu%_dQk}0CfMUYx?=+M$6l(#T>CLqBUnA=PJ#=qHG<#dL*xsYx|bFi!JZs_5^=V8 zx+9}FYb3PcABkr2NV?HhWPR>kY4|Svf~fq>94PF@krP@^0CIFX^}}(#De9*$fgY36 ze%J{qh)!ht&ZSL0m~{3+hu@toFXVVtIzQ2pCL(yp*uS>cZz!_mpHJC92q-*_EuUi& zY;+^%wY&|oAp7{_zyvwC9kS8G@68V5*YtYH(1O??5D?81`5C`cjAk0y*G`1#)M zlV~$bFT=puyniZ&ag{5WvQ8YvE4%QjKZoLh0_P9`Mud0Xl#FisS(nSoKz{PKcK?H` zQOa|c0DK|)uq{tM#)8ZpA~3;qo!9y4Av=f3iBAyo!jpBXKZ^i#rizU`;FpHOM1Pg| zV_?qp9?>CSF|m%_m9b&9*Vn=$UM6NBpFV%?Eqc-H4QA0Wck-~vL;UI)i+FmMXObP=ZZJ{ngKCT?hzJQUJv{C3RQJR2 zn@QVFFsKxLgz{(3Nd*`mvaXFW>KZx4djZA1`nD?DE23oblrkd7=ctdk0RNE;z{IK9 zcHKbNxF3|CaL3Ya_1RkY(!m}R(?rnHk^%NicYebkh_m3bxl7Xq09 z3LT4+6;rYnxkz)#TQrrxDV~0nl_~xtvTN&&kdo|UF|JVd7mXK8+YMgP(TSucod-cH zL2dd&=Cm5x#|nT!sH}UdnBnbI@ooBT`Gva1utRSXdYR`9(LgH0tFis{F_W%%wYg6PhN{ z>dK*}HF)_E?OVmI6_9;0JN3qtut_-I^^B(l%QT@$jhOK|l#s|SQeVyPF` z>)H^#>!#tQDr#Vr6)aH+S;eRA%9*6bwzvpIh+AQ&ubSM>Ym19$KWYw(@W65W1q!;V zxUIa1b~XT~7y6#7**$@a_F1n z=&f#_R#gV1i1@`Uu^qq`rSNpve^Df6I{uEVX!p;55TkqVGZ(10H=b4DU;QA>((`0P z&?MZ!1YFsy#NL(F-(SoQ%2{%pE6R6R8v^dJ%{wYW873SwvOP0yYQ=_pEU5XffU>{9V0!m z3SfzuUi7m=&KU~R=Udw?2d{pA9+m_LYpUk~f4xBkYScu0Z}TubufcVraxtSS;75o^ z^wcjuPg3^h%{NHpE|ESuT+#xLA0n%}O--(uWK8^1{>_X$HiQ%uwB(D?Rgr{{cV59gv!V&*+&Ir^Pv1F1Vbr4dcyKHMx6 z&XZM~dt$i^i(81M3yD?2?-Wzg8Mk?W)J{VAr0^%gBfHP8aO|%k6~mO;>Nh zJBVqQ}xm4kyzramTyWbCaVBsE$;%q z`LN2%i&Y*+8cxIF!s8E=EBSZA*bE{_VGQtFg!CsWj{_T7PD6zFi;*%YLyiaG_;Mb> z9GX9h35~eX{gx(7S$J?UA=z2~LRcd1N+cWo8Ves2;t!(JkxN{eiLd;pG<+T#-gn%} zc-fysW0I84cpUkrL}LP>?1{|C%F?l4kGcz25L&`*COW9HrHEcW6`-)~h(1YHQYm&c z4{!gqN!)3xZAew2rGn;YRs8}Gpq`WngN@YLBvbpAs!yw3}k-rOM}ClYek1aIsB+g`MF|BH8k#b!Y&rnmUk91q$f? z6xIo+xo_~aelJG8$(emWhkxooKeq(#r~pDDxUbje->!`hC8W7jr0qo33MhV2ZMod zAtQ3T3jSY1ZK#=@!*xumc)7)vx5NIK6FFZIUtP*hgLKac0j(Q9dUYj1jWCMj-wH7> z7JmyttPKIAdo?KE8z0GvGMV)X8j;AODG5?TEsjV3^Z))oI2I^#!3g{xNXNfs=KtvI z|Gf+ScYyxyRQ~VR|Ns8TJ$x=S71u+D&Dskuk5WCXM386|EVxU2n6Z{{#J~`Pri16wWjb zoV2J}*1`WbJJ|*%NR3=i#G9#3if>QnfO)F~h^PfE*7f~)(3Uv+5|D?h-Qz_GEZTyB z`j$##{do#NUSw{R8!TWQdC`*cIoL@3q69`vRW zYMl&T4O1x(5)r?!hQI_SZd>8ar+;1|U!vZFXrNiRsjvX0d@p{y*)mq8ZJ6i|fRXX^ z^W9HN?vy5E(<9)xo5>{Ryp0BiAqgf0sQ>=dpHd}=EkM2E7`V5_QMqc;M;u8Bm|?NS z6yrWmrjgXrsP^I8hFI@~nfiS(Xb77D_GJ04Tg=Y~3L=N3<-c zY?KD%kY$_pcX#%Wz%O?KhP4&e5$neoCd6M~F9NRW=pV_|7Z2pFrAz{rtV}7ZnDowe#_M#o6EX z!6*ru`vRxk@)FBS&5TWd7G*AmfiWc2>M6(uQP1x0kmqhJVa@&LV{ILSM($s|_HM=St&nPXTL6r< z-1TK=%CgghtJwj73r7z?;oo=$4Do~DLZ~i)8m^C&T9hc6_|ljf^hWVkoFA|9DMG$t z`)44E_cbumcUMZfv0VZN=EG(N*v;>o(#~r|O(Unxj5`42L+?`>mb`o*A-o^uc)Atg z4FVK}t&@moivIxq#%M8W4lE#>z1E>d08}kuK|V)+IDROL%tZOmtvj~sBW2^@;cQen zEWc>-_1S{Zx-G@^)4zD{c~dn22#Q;}0baywY6l>ZZ)noy27uUXD238a1Bl5?ViJ%L z9EoXe3$dAq@qbfgmv3})-(8vpxa*ym2*@lP@1|;rNzGb4fO{=Yd>Za_v@y29eVXap z>>dD^t@cO(GbJq>5GA@X@79=4A5soTOiQ$K*64DO}kR7x@Z+dcqCl-LX zRxBX4oxRQrAe$qezJ4XOYchkGfJFc-{Z3L-8TO-CXrN#r37dr*_95>tA6OmY;yP{* zk?o-r5{)JFAK}HgS0n!ShsVf2sb^K>uL7{V7^^B8fecMRe9^ARaR;mv$PNzRx|IOH zxM}Q0sKE&5sLo=??SHUMaTEFGjM$V+2XepXoe}mv_i#5lh+;Q^1_&Vo9rmaW01G}Z z_G9!9^C=|DxG$R(jEaufKAH`oQY%4f!>S?y#59=&CtD6BeANta{FjT@hiF)SBauPx zegcroqUR$l!^lg_}3;4vpww<+)k<&^nvb+0Ky5vmXM>Q5eMKaN6+Z*v93OU_6Km%bn(bU znf+2u@L;A5;W@0J{(CRfHuIl8F<^5Z1HNI_{H@aC-Sxz!5doKqe-I1KM)I2ALiyhe zG%Tn0r4d>n(#pKX4$zZqdJu3q483Z%9Bb-4j zU%(d;ARK@&$-DbeIK#fc#$QhtKD$4LR+G5RkHcn{$S$w+`1age;@jHnrj!`GfMQ%E zv+ehF;gj}C*56d3-pIE;Lam2hf`^1uh`>U(NU`*^s~_6g9-}M?dqhk+iB-$roNzo8 zP9)AuL|#OSvR)CwJ`Av0&dVzSb9uU1CjeJ{rwI~j9Q+C7n}nuhC}qgjetlxzfYrK> zI2+K7BLDjt#i&^)Jj=(lzcD`A7!yrsV1;^;Nk&D9Tw(0BAJ8%L4|yrH7~XCgqUky$ z&A-x&#}ka20}P;fAcGF$uA)g0+xNF4YzNT;w%;Jzy#@h2TyBGfp}}WP!#9j|E7Cm- zieC8tZj!HvB-a$318Q*rlKG)&0_}c%3gy`G#=m!gR`0DbBvjmq`_Wb8` z`M2*q?y4{2?4SW`2vm~w;VdqN$OZV*DwQb%_*)e>UP*BLN3}yn?@yb0>W`w@Z$$jZ zIC7QrA4V8~V-A)&7lX8g-C=#DIA^>zRJ6~uY(&?4je@+F<^-@jA1LH_Jj-F|6X44C+5WXFZ!w$fLCrJLV6h%*R1KAriMY$3E=B>XpJoJekn^(sXX(9rU8nq$&z zt?Q?yC*z{8l7=YPAHZ7B(X}j>p2(4K1ty~^g6D1DPIEN&x*oEGt;Xxr*XOvpxnQ{CjS zjHY-{Im`mj569xe2BTxMD2tGEG--Iy9_%N3H0l-C>I)rBg;}1r%y5mxbZ@L8Jc@iF z%y1RdIm1QAp7;${i%h)26X$akl-pv|G3_`SYIxzEQ<88UAPaecylS-IQc*CxQifyi zKSz~1Hw0-ZWo4ymAxc&F8)GAxlAq+4k?cAwgE9DOqLb3|2>}L&4Bb6cQDB zD}?piAcwgXr|nGt^oRY4;_)N^3bNdmiF~l2oradXX=SROXC_Ap-A*7Du>p#6AguSF z&R?xk?Bi@yUNqS+#C|-H5R@LFy>R@l8PysZuf+-cBkb8nuna7G;1-({V&@%QOXONp z0^KZ;LH2u#iq`^{hs8HJrJ^jPU(B;5#peI2gJlO=q+*?M=_BYjf zxSLz_D0lccQjx+H1@&22Bl2P_2o-N@r$Ese`g**Xwax7a?8U1ywC_a5Y!?*%B&Ov*>4X(X48Gm@RrcpCd7j`zBuUiI zL&vr&JDQ7Os|}~qcPLF2Tq>VVyJR7%fm<}(p}h@}7lNK|5a9JdE55w7P&>*c^Z_9Jv1i zUtpvRLw^)SfUFv_O?cBDSFvUItqjbj8XY)BQa+oB0l|kzmIbNEeh9TqxBJ%$|3{k7 ztXVDVb^Glhzc*6rr+p9Bf1B=Ar34KEFRyV(kzcPn5DqtM7p#6DHTZR-#0Hp7_MAed zORma}=2j;{SoBR(=cBikHfss__YNwn6l)KwpVx6GE0u;j-r-BT-MY<4+!lI#Sc8%u zZmf8ie?Q`DZfc+yJH838NX@2mfp^X0TNOu$GG`DQee!Ut2mCZ7zJKiC^`QSiB?XF~ zDTtVv+(ch00xBHm-RC03XYM^7sK^99Jj;op$EEJmb44}_?+x}{?IZZDFPRV(>6M9( z1hf~~utbGW6@cQ0gIK%ihZ27!@K96kQ+9NbF>A1z5lJ@zRUTVb0mqF@%xe3aTp>%7 zaO1+G#s~qrP=#v&ucyc?NDKnncMzdVcfxJoh z(qt@)gz{w2RZ2%ZlknMq8-kxk?Be`^gjxr$I4i4yv=C5BP}2Y7jvUsDjP;7;1|a1V zlSg(|Q}(d&9iI%$gMJq=0O@~n_nt9>%zj(E&3@tIXZN&$P2+Dn-{RJk2ZpH+iHsZs z02%Xe?SLZtte;Q3d^=u@_TUMF2s%=?7%=;boc@WL7`@sopf-ZMb%-Jo#ONtLkPWX* zpQ+lzuF(tQ(6c1&_la<#W3Xp=4wd`DX{cey7w(tfC+%@Tz?gEXG_h$}TjsP-NFFRb zw(!W-!!faG4z!Km7{m+7qM#$`W1x?#GN^*-77W3~VkW~#jKlJ>i2Us+TgTr|4BQCA46G?l*+i$4xbqG?W z69|MN$V)49K+QDNzvnwZu}pXh>hbVnn>Ix-*vlZR1P0aX_$19%Derl^`Fw4o>=Xjy zx$B?a{Q|FzHIs8yM@`F$vu@uhcy#NF1dUQ@PG-QAhO_m=I|rFa!rs`l)cma|3(qPu z6t#Tdp@wsK{7osKed^Q>4D46g7i83CK`6hP2flYY_vWH?`VjHPEHIUQiM(1G!vvac zU{>+Yq4;*gZ^6vT1C1n}6A9xV5j{fMqOSU#gr>K16huGh1s zTJ+4xjuFreoIo3?;SujBKWV=!=+tr}p#p$>zqn{fPIkANa{D>Nr?Vr9x2J%AaGBR6 zG{MX1s?zVSWs)b@MJIf@DBqg~C0|be!~7VM#Y*SR&#Bb=_g$%D2>?>lDlgeleDlq< z-Vw6`uRjoQ@-J^m0;qKc?#Y|KlxgrZggSpUN6q&I)2AkC`L#pIQ5#^O21w`k6kAhJ zCBLZkPzzpipo8NkMk|vS<>)-|?|+ct1}*U002;DYM=0;E?hP6`Lv&~;+7mKDe#sLp z`>A(O9~}k}ZpNVY4UB_6=Ln|B zB@$CUxCl)-vHdRvRjuJnM00M353?0S2|!!^9pXce{h~3nnuSQ>P~%+%z=H`Uufu7l z0!gqmfU(deUPHCcM z=^oMHw<8B!0qimCCHR``^lS$(riYFIa$vl6+8cGGW#~B%k-8674KGH*WA=_6nn4Uu z-ET032~XI8cn^A6I}j!0NKIm02t<))nU8+0-VPo&RyBrVMMn-9Y^!^$LA6>w&W}a? z-kGL<&G+u0U9hY4f^Nom#bLj6Q=5$Bl^8bXi z1AJ{EK9*8)kT+CjcesH0EtN62ah0W?ChZS!Vv;%pxoOQa`dOukPm`e)~5*5FF%q9u$bJ>I0V~^wI zPy2L5&t)cohttUfXeqhtnx(w~Ahl1YpHbEKqhh6)W_D2;Ue7ZOTBEV>MiedSKv-*$s6GkHN z$Iyf_i?0FQ)0s)!L4e2xnC?Eq9cXi!bX(>7PC#L_Fz;c%L1E;b?*1mz=7x;w>jIyh z4t2W6`z5R`|B2v$B_F8YpQj^u+(|5g@Ec>ZM0!Y$e|P?7ht!M|gWq7z@;Osln*#I{ zAv?fi!UV(exBkf2fF`bh4gI5B=Tk%llyq1`<3LWSoaLY3X%cQuayc%k<6qH%8MR<6H9XMAJ@netPs;Lb(nJR}^9UZMjI&ka|Mwki1D8(j-0u(;udav;IL zDI67~eYmfU`hfvhlv2i5GnZdhVIB<>^Pidd#EJ z9n6{k>ZPT1iMqLZK)kHyq&r&*zwSV&!lxzPS&6$e;J`Lgr<-?_wgNk<37%_6UzOwP zU6Uqa1`2MI&RT6;{%zGAi-<}SGPYL})vl$Cup2tSfU|4MK@~5cnG9H^@H;KeUD_5m6y{D;KvX;6^dcK(z%`2)5v~TYQB+SM$PvnJXa0VlxV4*tw2jhVVC_rB485Y)i z94QKzG+FYLM05Hs)h3a*gG(WVumGTL@!>>-S66S;&4G{5wiSpKTOigWm>(MQx}6wu zpP%O=K)wn;aztmK5(ts7X|M{~BE?p4+(ZwMGQ(ewb{0n~{&E}v!~mRDi67~JzPmZ| zYvwXr-4f9zPk2JrYc?+f@3gb?6N|BfES#NMSvMQWVy%Cz-Nz2oKBe6(4E9KxE5L4% zx&ko3E0Cwiw>rVPrae}FPU+uHQ1$A)n&kVoD_LYq zS8;-N1SXt)9vZqa5_F3g>W2eQf>ZnddJOFOVM0RbH=FMB!+lU}Leg1?ODNMIXb-I_XwB_Gl@Yx_8;@nGn5Aqys0JFI$VZ+0O%x+KPCvY-tdMoK~5#0Z4 z2Y#I^R&3wb&B!1Wb%Gr6*yRBwx+T)5ZuikjfQDL^FDqLCfAycYp0xl7;!WCL%8XFj z0RUbD<;wJ^r|YkbbVb{!z0L0lBQMGE7w2C<$4*O)`TvpB`j9yrk~f z?p4~gTzKDK5;cE<-HG)y5U?v@jO`Ls4HOVRZDD5I^;WOVb$?u~cfOP8rY|(G)D;z_lsDTsp9z`AX{w+NCJ^ZE^yGk@3js`61xS|XDTW_>|tBDS9APM`zIpd!sYyXoSb?H_`S5yRY&Vz$=%P1WwY0;)E#b(P$17JtH&p`N; zul4C6)9Uj@FjXlrP+((7RKOliXbOiDyUx-|mHt-vY(aicEGXVS?^N(D+ILD$f5C_B z#UU3?YPb5+a5F$oE)PYwJZ3g=<73UYo@vV0GLT$dXt+|!i`rh0ZLpC47QZ!&fBAZX zSnWo4wrg!n5X(1v5KLTF?qU=h+&qw8;$4Pfo>Ar?r^Q|p^L0Qh%C(*@wq8CL^Xab3 z$fbH3tUKWxCG6T)d(^=9PP8@LcQ)y6MY9A6mJk!8LMb@PC{Z%@)>yWTQ%1lR0(9Ucrk7kIXdB&so1|kO zB^HMJh|3LNBK>*NWOu`hPfE20<~=KzNB2jKYmFrMd+CE3a7I62a|H)JNsAKf9?}sc zD!kNAKxqw?lZZ|t*P)91Rwh49WC5+=})K7oj*Ue4)_=ou*VKm=k_skXW}Mhv6b6zXW?+){+k7$jLr%b!{9L6FBtJ6LP#1qu2(N1T3 zObi=zu}C<~+m!{yKUf_EhU0NusaZOd)_CEhMO2^)af<{O2b$CX*iohwZLVL|V${oJ zcBKpt))&qIFxNS`+j~c)ge3C`8wq`<80Ea03*Vph=>Q>DxZxN*O=$Cxg~#GcCyIPk zs;1cf4jd!)V5LBKNOt(eA7haf#>`1)eArVK=T^JdBcIM$-~*6LJ@c{`lvT1~w$m$9E}_ctw~Dpk@wo?B!xi@WlKO;ds$ zZH{y7Q%sd%Ae7D*RDbt*{^uvp5@;~h^JRg0eIkNEObf5|g?{cxHRxe?h?#u_(t!xM*(*nWQDuSjZluJsH=BVAs)nQk{$H$egP z!5$KvZV%h<(uPk#`Ca^2?R{gmJMql8dI|WTbd31DyqKP_)-=#d~rFff5# z5eoI8CTP?#mhc)AiIRA{Ybj@;$t*&E|0Dapr%Zuf_My#T+uL7)oTGOH&&1q+7m2nJ zx8A9AR$hIBUfx7!9+4yzdZ?Vc#4E}z-YQK7)9k>wCP67|g|<5Xt3cp1QYq&;_Ek_0 z{J?Or1=?E|BbHy+p)qvGDb%g)C;d#MV@(<)m;B=ciDSmxR`VD4M=bddfNZV;w1yql z71II2CUOzXQW@6!%Y99Ak?X~`Es~k>-Ms)=z$(Z0=9AAA&~)8#ZRn1!7u1%W(>@|q zieR?h1acf31`iJ)4k=x?!5%FLFFa!`S9`_r?6AZD z#i1bNAbhNn72RbY>zzu7oS5GZ4Y;2c0J6!@9Zi0yB_(a_5cRM+0i}CzuN)86>LXjI z7XJ=(-%3sPKth1T#R$GT=J}K|GhpcL`E5Yga+nro_&DKoQyh2dJKZBHG*62dn>=k zGb5zwNdvIp4h@UCAmI?N_ph4WX1r>6%eLqj^F=yWE(!Kp^&4zhus}*BizJOzI3|R7w3u2Y^Fe-em?1febpFqFu=?*W zT3txYL3MyYN3?axGrT=25_^|3?pZ^5=uj5al<=?#m4wrXF}#X#6kuK}kd&-b zbe3e4+EJ4tcWLl#Z&scy*?pRJN8^zi8{_g{1pA!FyMtqiJ%27U2V8lsyWjMA_B%yB ze7kgJa^7ZmMp1Zk($rh;;9S+aBQa5=LGH(72=&mA)vb7begPJ*vnu7Mh$ifiw}&Xs z+~U{C>{0BtS$-kgb#C(ct1=41bi5u`ft;>QC$(KgHV&uW3rvQDJ8QIB%pok^WS9+# zREE*%2Ml%ZFWqYUSx6Qu^(e9;D&GLp1qLutFjLRk&TB3DM5wrziT4(ufx2G6C00wx z(i5R}Ae|o_ki%nfouhDH&$J_?+N5iC1F9?Pe7359*h`2y`wSWNckOZ-7V!?cZ`CjJ z1j(EqW)d-u;usvPCtv(=29gdXUn{Dp6=0)K8tTxPVM6xd4Uh|toIq3Ai5;B@_8+iT z#vX11c5@U-RGGjTWe^f$Q?<-F2*RI2BHe&Smd{CGc>7qTWGDuNpqXu^&T zHB?R!0ebR_1w*gP(CP?;#&J^o=5Y&~)s*VOiYsXhHvhv1e39AA*Y)5!Ndx%Z;j zD6{e0PZ{rXqb8Z`XU4aj3FVbyV~nSVxc1Gd_;xaq?rG;MwSG7yyW++||U{N$7=|C)_ncoqgW& z7Fiq0AP=EH!!}^sVHWkUHZ+G`6Qljh^l$p(0jgvX{8^bRM42<$03@S`cz`^OE_5Uc zawP#8@xgZ65xG9H>z&WBB7(xcwd=rVPle%1dci8&eC)izgv!r3sdWm77PdrNZvj|E z5z>ZHIndhT$W6xe^}pzyt*I8d^|V4q#>2u}3Z(@aPFjAB(!0c_HoaWy8GB0KJo#RU z2wT3c<<=B2o-(^NxkxIy(W0~fD+e>35lehZu8$P7f5ynE!;#@`wNZ+fqbfhxN?liM z5N%wZ+-)6w*Cr9L#UdOr5m=aB(cV*XbNSPslM16NCIv!lXEB?&xCzjfN*Y}S>|Mbj zu6e-it$|P`k7hOr7dA~(U+~BxT$Z00!q=dKzm)7|za+WF&grAhs#j`mF&sFAat;`>d~!YTjN4fLn#Fyrj1hWwyH*ppR@^RI~ zxcaw@0e=nZj!Xj(9r?jaY>{Dk){{1IrwPYk!Q+}ptXS_OSD+wO8+G;%BD~r3?^OZa zYU^cC1zJ&XXBoAePG03zyMb0nmZl1#qbN{ckl&)6Eb}iD^Sx3VTI^)k%)Fe2Y>+RG zs${d3UPgTi6)bYM{ARv#xFn^~=$eTS%xf&uXgUHa*}Y%)VcSnWQGylHKUnzkXjE6! z)he-tv8Fuwh01q%Fe|E*(>z!ejjp8h5oLWOnHTf9Nx@mgBz&vi#S^sBx2sg3JXS%@hMQsA| zS{W(XlA7~~o;UuY6R|6bbxDyr7dTI^xWiBGgD~t5N&o{a~(1_(7?huc}EnhL$PxFkBJS z8;4v##q2V@Ro{>?yLk2W)9&)zLRjZ!nbV5{Va}+JJZOQu;Svp|xQ{?%((Pah+7^v- z4#(PX5FW<1o6>wopeG=o1IPkmP^7z~NF|TWUGx7 zm)-M_8y>b%Smq%XfB?Yw4Y^bu$Yu$+_^lHeAozg4A?$emZWF<9Gh??6fT~Ovzay{F zEX~Kdo_~*8eH;L4*r@)FpW+uwhuLA%O_n2Xb()xNJ=NxqDe+#hg*RHdx%(wfdK+al zxQ~on2TJEH^B5()lF24=XLh}srI#Mb31oEpFI5p+56 zo+sU9f$y)k>1Lf=o5#>1yA4zlN(=$6!Ws*;a%6EFXy+g%yiq`Y5 z-A0C$qYbV`J#yRHWqpKXliGdW;v^6Iad_^je2WmizOlq>I`AGlFnymB)}bKzXpbz3 zjO90&&qp!5mO+8r4GC{J!V9h(&9!#0QNhwdvWu=-2(oX_( zaXF3%ZuX{hE*)2m-Qu@Gzx`vBn#{n)jq=g2{8#gsX(=ZSb&b$O*Uf(33wRp;-|P9S zxL^L~cZlv@ZJGLw-HB2CBZZ2`cd(fWWXoAnJ=fFR zn(&wPGTvuKsT;A^JtA^W=I?L21yRdmX8!i3pv|>&;A`g6vLR#h?o6|(C+=>WPx&y} zNb~8+R`PiV*Vgc_nXi*CwMR>X$=0vZS*0-Fq3is>Ys6S9R^L|sh42|=jx2+6>%E!?aG;&!hnngVYE=I7>S0wEW`}PK-LSSbB6Y#@ZG4*h06C#fWE+`w zPc$LCyAtl!;BAQxC1Ajin73z!qFCQs`QOcl*9AM5SY>j>nBkFXNauH z-Uz^+m4+nf0iMwft&P9=XfsQ?k!l5FjPli&{`^>H7m(~1Tsp{7lP*M2`8o@-x};5Y zILuZFl`Ih`Q2VtrZTXVkmfi~?*YY~Q!jQ#Ci?((c)f$iO`ab017&?xRq8p{}J0}&% z9$%f#wh9%;$4fs})DkJ)yU)q>`+c#XAb@*j=+CmtH)>!B1PTeAZLXBVKj%!|#h z#%ZP?mhQ4+EvZ%_qfuovZ4v>;rAW1+XUIN@ZO;#mfaBt`uPGu0=)TLiF{8p-Uec-0 zDM38D&P`eu&s~DB^+ToVlj`-5HxptH8#^;os?)`CY=3rzF}?Dw-_aRJlyO46nYYU! zUh(sUr813vP!W1M87rM?#UN9A{*I}{Y&bpSXFx)db#b4?VKpc?xB zSUMlLU0$bk=YOnW9@(WkY16ix_C4I34akRc0$ht(g$8KnQsr+(;>$YFhD!J~Ysn?* z6=@34BcoX0o`hFf(Igxjbi>DrAr;s05sL&Q%BZtDTiu%kM1e(26Q$hO5rKKE3@AQz z>5PXYeLo^eUGoH{d12PPS0XD7wXS~sNLFx-OV&I{)D>3w7@;inE7NdUb|J?&BdDJ| zgI4BK{nLRb-00c}7Mp0(JZ+6B{o>n>_yF=UjT(pf@tu;fx%Lrw#UH$!FV8U!St*Ex zDjK@=1oT5sldIbjX4(rp^}vRd>mM&wFg&)>s3Wbc7MbgjMXK2{mR^#rI~T@H!sK&^ zB7#P(&bmj16GNKf#M%A%pi^jg4LJu{7}~}Kc#IRduzDe^m=FX z#dksMs&NlTtH^2UF(*}2`&mtc2}SiG>{+HYb(1+oYaHU6OXHmR=*Kq+Vw!r&-hX5g zEq97rK5?bCQ=GNOq85%1+G8r?w%0$70yRk|&xtJk^4bkmy^l;cw#ACvlVdf0R%#?Ib#ZGm#+ohx9A0YaSxSxwv4fR4f<+8O!pRhMqFkbO2smQ?xVfRGyE# z)4Pc|^eL;3>cH3C*?Mf}~FJ_u<-w{F3Lum*!(7lQNJ2V+x~_R^?(cJu3lWgw$dG)Ib z9Y;P{V)-_o6-dRU~{Mt^jDMR-DXX znIlTfOy!sRyG!#+Y3sZp zY<}(b2PtemI5tNR(h|;d&tvF0e)+1yiJ9RNlBMk8U#u)Y#^PM2EdN5xu1lEM(tgiK zR-2adjgY$Z{f3}foZbr$cY(P$C$u2`{=;F3m*PWMnv}ZtF?1^-X}o8DaBE5F%=Z-4 zqPAvtExyEtl)thQ4S4N2*%Bm^t@x->=R`Qe2HEJtt#z1K_{AG}TRh=nb^aO#+j)9U z{H3cDFa_sN7v{E;nVpbm5AdE53`YJJ zqWkYdIVY4=TpB+6$z`cY)q@M7&FKCp7u4<NGqbGAc)c;HMDex`+D$w_iw$&j$?n{U*C5ed;K?S%^IG(@9R3RGcd}tKk|SH zG;yr(&{r{XUr!IwWeq$#dt1dz zHz{iV?Q^ugsYH-d>d!KTT2@ajF$W^hs^>Tas0n&Z1 z6iCNjoGFZww$z9D1ZJtfjmqp<(;c{+ zp~-mQl4uaaNyVq60KDffp5q3k)Y(oUqOCbs2?KQh|BurQk`pb=Q{`>Kw1H zc!ahf9NABq$nA^T&Z$n}ZzeV|N8bn0VpK*jm|ccT^{&XeM-saV;_d5bb@oh0U{P6cG z%2}tn#@it-V!%1f-31#fRiYeagEA0bP)xgqVGiZY>)VYHWpc}(wk3wWN@^zG z2`I%0UYRTD{%|_o>$pR@jdQpoeu=Worpp?*S3wpk4qd* z4Rrb7HN4J_w@>j*_b_5ORl#H+4ln*<$IY;z;QQ&32x!WU4UBEvlcK-sEhwsbY5CB# z#J02P>q;w=9pym;_;X$H+|n29ez<_`O3_B9!}7gqi{|4Sz_zKn@Z|caYw(GJHXn$5MQ8a%fSaA#%Z!Pb;~Vh90Ar|kJ4e~r=)7eAY#i@pxQW&)Ca_eK7e5RzA`HQVU>hTy2&3AMr5edaau7M9dHhs8#-b(?o z^I6SHIZR{l8P`YE50b)q42NsI^V-!cpF9-=_Tf$6y|*>5*e3zEcL3Gi+O>gv<`#H& zKh^rBO1Tzqa0}h8(%dci1=_~opZW>G^uzb}oroYRnS^r-glvAzyv2rZt_r{T24=wh zl@dcPPrW&Ne;z$)Z{~23JI!jkV+XNW-f_H_A2kJf*XDSh(iEQdR-m%Zf}#9P<2q0z zmR0j#au&|EhsD`^dUtp*as6%s(i+mDlv>7oQpt1DTUtY6WZpCK;mjKzPJKj1(go2x zcx$ZKZiA8l`&F*Xu>rxyxh~7(B0hSZl`_4>)HHogpqly+Piotud;Qr7fUlK;Y3baz zVN@i1A}G-v2(zTpawL4z=pY7Ds0>Sl{251V zL(Hra$A66v97#Cwp=}`7lZFH=wuIddj4nfoYWR=W< zGa=at1=1)zmnlH^rg(!KxUO-GH?^`k`w0cQ1~y%Uhoo~m%>aGBQ<+)0HHSDJ_j4-S z8VIJMU#7Wzy+WDC2tSxaY|1W8bTV)C*(i139T@LI*pf0SNdK2v+9mgc3buQBXQxywU{WQ=I0|g)m_?~ynpx3 z*&WxHnLdJ|r~ke{0lH#%jNCJ2tiORgN^AtX;44!YbAm9!onB1$CAi??gT-GqvO4^@ z4AsaoH9B27fBz{Onq8+T43@`#1FK5Qzs{)W@&vurbc+nl>^9e#e?z()+#7pmZ%1H0 zXP)(8!wR`)s}e?A)y|NNbIQY7+TdoX^L-U*WW^qxhY-e`)Vs9fJ}dM znXoCc{A?<(ky3D2co9AMO|WK;&iu>Y&B@XmCr@DNFj+eR6K%!dHi7@Ra%@Rs=4+tR zjEpCu$--(zVdQ4bIcO@)@A?FjBWs9*DPeza<7SvlkqAv0V4z9r%^>yV_@f3Hc$p-0 zyvMqfcH~-OMS#WriN1yH7HiojViLde2K|>iKMTZ)j5kp7pfxbErNZMWS*Tb{L*QC{ z6Z3QwS;E~Q#>Z^|H2blnTPnQK6+kKzF;dw>-Fm_0*}OWzcPXSh%9-_2Z~{hj)~j9V zd~++CE0YSvhaN+?TFh<_kGGhBbOA-QOlwZnI6^0IQdu9GTl2avb+!ZbrQFyme4`(xm7c*57U%m-SuR< znIK0ls9jp2pkfhwPr^|2P>CATFa#pbGA+H$C>}kkk1ldF=*FU*vxjebEh#@W8@3XO z#mMP+{DRl#w&g9<@y``&Q6jDGzk0o-Wyl8F*g;$PLnUUOTP`>n&}*5OuS>vqO?6=T za!_~3g61o+Bqgjm>#4WQy`r|UIVhh~(U_U=ZJtw47f{h^Wgnf}=_iwWToykTBg*QZ zH(kG9DI2;>$i4{!%daUPk?Gq-mCeS-cbWN<&dC0=JeFG1cgN_)kiHvjVxt)<j1-_WS5{TxXkh3-75z+UCEZ#vR$7jN&omUg>0|8={dhx`i`~+QM2FC?I5O+ z`C8U&JxvtdWGWbi>0ffnwfFN_Otk}WxtDtW)0DvRY5eWDLT?VP3uKmR{J2tXrOaOO z0r~ikKZV9z;{_{$SNqxN+tnhmB;s0JicXovq$IP+J%tuu+E^^%;V{v1n+%_a##-Hl zeT@9J=&*ZT%JxRh+dwpFY`{YL&4leyX#xy!IQo9F0Ym7M@UyFnRe%R81{a?i*l{(C zMhZc-8KMXSj8vLhoJbNy*RSgruV4k(WrS8(hhJP$=W_k3ntSQ+EtMp&9FN>Y`R!#s zRbEeTF1oC`wATAlM?sSm9b|?Yj6JKbmY^wNf_-^!aP?hMD1JtWHyJnH=%1mVSRA-* zely2Ey2(s@SpUauZ@eo^40;}$@D3z@T&_##{WT1whd=+t;+mTYjBm2qLIyv!rd*dr zn)1;>HiRi~yAdf~@m~DxdzC^_Z6PTS!R&c=@#Cg_(X;2!qI{~rJb@hUjSc)2{R$wX zlIe;wO#0kl`tLmqd_j|QF(-LnOSIg63BQSgpHqw_`c!c<;RvD_J3!Bz9H{}RB&d}6 zG=Jet9^QJ2G(0U4qk{#lhyUH4zmh~6jO5CT){H-!qmVCLiv0TplP70yf5zVENnpeg z+KO&#_efib*PsZ;OFbz`Np$YB?d@ztejaIM@bJ!T5B(N4`s;(AgZw=+vQWrl`1GTR z!^2fb+wi&5*k?yD%v+3 zQ{s1Vt4LUf$Q2gJXJb}olaftG{ba9US;}+4>|^~IQGYr}j2@rarNRD&5TBOcUjE57|kAMYW5z%Lj!#DQMt#f_UVIckd_4bnw#gAVwu|&3ilzh}7yJ1qO z@;f@L=W%A!KB2JwnBCQmyz6NapVJR6Q`+1@kLAZZqPV1p3)i~+Jk19}A{VYCws`}~ z;0;yO4F;d*1Q&*@Ws*z9ffgm~M}KLb#^p3w4RB*6zOmP(bGDdBbvY1^x+<>5uO!S! z>-IWrdRw4yOWuJDWi%{uUhm>M=vz!)qdi0W9SvhB;ql>y$0wJw)>Y4pCcx_Nk|@67f8#+WB2I1f~A%9iVe~;vLXUYe@SjK6p>59PB)d4D6Q2n>*bU z)pihlxx-0K;0?UB8z{>Y-kB|^o0H`K!(?nfLM^i>57zHZy-ds5`mZ8pf7VnTSW`kh z_)C1qMIW)g|9q|FHsYEwzZS)a9vw~X{)fSYa`2U1 z=P<{>;8$yqNyKCdQFa{YW{MGWmWGb7UdS16(0fRg`4mIOgA*zMrmt*+=Q?=wYv`u{ z71m)4@*7GWx>SGzY=l%#WgG&L083QIQ3`k?b{HQ>IoTXek0aqPlPNfDUfp9S#Y;&& ze|^}8WRthq#|F5SmtMcgr?|*bgy0R->{7k6^(Y(?!66Mj=-e7~n1nQU0>Biq&K!E- z63i+e5x%SE7p}2xx>nj#*y9mWGyG>xuPL^0qX?GykeNF6zcn^ZL7R`py@nqyxwxApx0WznQh`aG}d@m z>$XI5{LhzKCp{xwwih^txv}Tsp1%qOTK&Exg1hW+5bcbnGn)R6(qGsA=`a@qGbq$Q zM@cnCEo`V#!ZW){@YQeF12df?@d4!J7wd;Q#3ciPNQd1ygp$YRMp1Em1!%+DIMTMa(7eot zn(V-r^ozr$-^AzPp%u?LH2#GDE4ZD{@M$K}`q(pu^5C#vqBQYJ!PZjXl>PaH z-F4Xq!GYXuSQSIjxkDuC8mDl~rVq>?m3i7Hx9drYV&y^{QMhi_dbjsPq`e+aNlHE- zGd%JA!tBc4En}=U1n$h(aN0*s83`sS?bf6KCeak})aKbj)GH8tF`17^#|U~%tDnN{ zr&E0`xOwr+IWbQ4HB0N!!K~2i_*3dPD4nDKNrf~Owxo^{@0wDxR7z7TUs5?&r_`#t9{6vX9n949L%ctxhMvm5Z(p~()I=l+YJ3^BprsZ@>Qz=AU^sX zMT=fJU0J>P`e}HAg%?@5q;TLO(!X@i3wu)iCds&;&2fQL`=`PBubWsIfRi8LteJTl zCEv{|5a$Hh4YB9OLDlkhRf~k8lk!D1Oz7Rg1WM)I9TN5|+GvZ5z%58uFOIYdur#cG zP*lUW%vfO8erlL>-xdZFVC#LUT@jqY#WAIprX z5IcqY_5M-k{UBdCdr%p^i5>FoXbIyjI8veV&tkS99;gXqFP00Y%Q$jQLgbuaG^UGQ zR>q#5wG}u56};@xQ`BEIES)T<5mjs09Je*`QK~}sCN@iIPC`gpw2``hP?_$FchSqL zE+SV>GrKe)7CovCCBcJ>?($_een+uy5MLJh6oUbQh_>h-stgp_z7cWa9!@YLZ)x%{ zw-A{-bSkz2jQGE`Ck092GiW0cn)ueHrG*t{qNT`MAI~kzKF_lx8~x>VFC;B~=05gI~xcP2wvyN#k`DZc_ed zA?ooq7Q<1k&b}((5KI@%&+%9(X$Q)xyl*u9G~8O5nYuqUEfBP^(@&gc4~d8IUI(y4 z)PMj_`Oy?dk%DG+)S63qMSi;m%Ae$A$J=vuXCj7Nz3%1bM? zbN}HFE>Ge~jqP{|X&WD5OVcqZ_tFWu+Vz5}@sZg&WD3MPapc_fZR5t`YQE~#)>}j@ zoE*qXS%i({8E-A9TsyZX6b`CFm>46=y&5z>1=lo^h&_D9AH@f`>-Fnp86FmJ%&d$K zRe8oUyIs^x@f6elhMR4*8%X=Jrv`qFRER-ql!`7IRJEa%?z-@i)LE24?PRLOJt0_x z@1Bpk5Y52{Q4+D>p6BfG?>Ra!PLX{68PpzzUro%?+o@j9!Emhk>Xy9Mf1p} zP~u(H_$Rp8=|fhgBfHOaUJ%`tH&$t<8Fd&j7WMnLM$c_Wu?Uot|-<1IYuGg`bB1RY8%cd>G zsAHO!?KzgcPu$|WXK#MT!dAW%eWS*oE0@if4WAwG{f5lK}UDPwAx#*hE!{?KZo8|9{&nFRuVrtl15X1a9EBU$IU zPAGK;iQ90$Xd~C{Y+kcdaF017aS)M^c`$OUKykS)0Q3BElIh59)#otOIPJ_+1ce?G7a9$_$@;$dMv zHWlzx-2a?aTX3Fk8X0H3hKW6cS|Ccs*@isdd@t za%a;&CN{`nAZc&Xu(*zu=+{5Ep~~r9isXHScm#QYF%SOihpD}ovn|B|OMOVV!{(gc zk?B=pvqoFsAbwuEY9yA=N?dB)3VXu=-tMW@v+b1tjC6M6H!cb;eUY48)$bq-X1L1a zQKf~K^ifJqv_-J%rqXHY31vf5O2HHVyo)!cEgWGuvo4X^rUmq7xmI?t-4n<#e?l4m z<@${mZNPi)Jen**MbeN^E*5;4kuPc0CP^f;-g>O_HN4**2Udk8lmSI^UB`MJu8Kt% zJDH`ttN-N*izUUIYf!UTf2|Lu)N-zaGh`I4ZIB%`yo>Ti_PHOrvf5U zWS@W>KZj&tl>?^yH(#yp&(C;W?G|dPJMCp)doGJiIVvDr?qiEzR19@XHNro00Gma} z@C!fgL261-$NSBtvH1sO;7~Bofx!O>>$(R=gkKr0XDLF*CJ)tufGwEPlezWThhvxDRQ!|0DBcNTyClPaP(v^hU?T> zZAfv-D26n+-_dPD&=k7;20t$L`%^E1D*H;T2e!Mnv?PWshKbt$fL{KJnfzuH*txZ& zx)YMF#v`u$jzEeJuN8gKhVbG|gYbc5@}BAyhYlIMQpYM7@HEI%Od;_eJL4u`YUEHR zZ031Tck`X_gs9S9IgC~N5+HV*4(GI?@^g^(x?cvvus4+QU24pP9mUj@4u436`Vp@i z)Q#kfI!@&1Wrc>{RO{RN8900`GrUeNAZ}j&RSNygJizhyb!3*X25DW-&lenFO#Np) zm46=H=vRK%@4RIT!&7ll9AZ`2+y)kEb9&+Hj0TZDiQ+nMuP{8vN@u)nx z2l#F{$L_gk48IUs)t$c};m~*hQ8Q%v5qNm9Ls5*_(CuY(<1E;K_Qcb9j}g@Y?RwoX zf_-ZR74n<|j2G9XQri?*l6W2mT&Loc8~jPnj*KJbYMAT5bE3Bxach_Nf|t7}z_hC0%ZZs3h?Plyt&~{i1c!0}*!xjiDW~e29 zJ>ig%Q~K0YFf`@pt5)Jw|m> zye+S8f4hu&@y5$suhX=E35`T90Z+OZ_ZSP4`4#AjOMS14P00*f_BRqW&XK;H+#y&x zjy8nw1;H>OM>xZQ2QQR#M*5#MOQjxwW;NKC4<2rGL$Mo!krL+?{79UeP8$f7O5gHj zf|}u~?E{(W6|Ttl57Y&YCBg3BG52T}a)RCltwdc$9M{bUmKNW0Bvgnwtb%r>*x@kE zYA^*}p*yBsxLO9N-SVq}V~-JaPz@0}Xf;r`(b%!#6J7@zo#JAoz0mdcg{})35ndBqa2UY$4PLTc|q zVg@}%#CpV2%YO-m+a_5u-TG`1#B@|6oQJ_PkzbE6bu30|Rq^D$pZVgi54M&O3pQla zPhIfzLFe`M&(bw={sA*Z%C^&Ao-T-^RoVS7|M(n!a$wd4{>(;ukrg=5hz0=GQ5x9CUe+{Z3<61H6b(Flx#@XrbW1A&=}ot5 zJk~UQ_+j>ej9}kJE=MiLhqTc}E2*4>SW4T7hhntTe)bmB>hkh(+fzImjNnB+Vvrd5T%~h1*KIpBrI_o9i{4wdR;=-@cC7Z2TZ6ghG_<( z8!_Xq?~XMjNm*c~E6m5^JVbNaWC7Lu4Uemc7!5ZMd*Z^&yUf!H4Sjc=EF*^L{U7&dAG9tPi@`f*GI`LVTBbN-rVl;VR(%-cE=2*|V-t--@u;l&VOi@g+n|L< zF%CRW)D-w}neXUydHd_#rXHZ^lQK5cEMSykD$Yp+PVygfWnhd@vqebeV=|A7ba|jS z$!ePNzC20k-XX*1JWO3|A*1t9x-uy!7AHmtW(qTYio>8RGbvCF%FS#JAi^>%vFh_g zm1BkV*X%=j@5u#c5>0TUG-ToG`1{|V@BjWI;|A-3cQU4yIrywz!+n|xxJaFDPn~xb zM09O=Pj;TZrBd2WDKR0x$Zri7X@Pw@JF~X6>^FEzs|$v=aZ6ykA55tXM!hbS(D?IEJM-}LBKv)LejHZMhB7d-^XC-eM%>7L zKjrNQV%|X0z22jEWnRI!Hf|HxU~lu@<8hV_EaYqe`wX z-K}h$O^8n)NkkKeVskC%h)G?X$2=7$3KqT`580?mM{~NfiJ3hVK9k=@lvBG~;y)%o zwNdWS%0J=~u^G1Ssa?a9`wmno7|CN2@L>qu;_+BD4qd>MG%xUz*TI=d@M1n*i}z$+Z>mN+6t&lmy>3d6|w z)qV9U1CoN$&bRUhMZPBzBm?BV|NH6x!If}UB;4uAcPIdh>QWDF6JofA$i?i7&TfN5 z>GvGJ&gcF7RymtLi>Lv2PTqWJyY}qezk=A?)C>sVOFlW%Q&899JAEO~^c#3~k0HZe z-?7&7d2;kUhx5q~eh+o-cpQfNIgn1k2NPj9!NA2L&_bIRiBv~E1kXjcg)|@}H26Rk zEgOT0mV{9Z@`1Y;QrM3pN$ki6>^j8Qk0PTSj{J($ff4GblD?m(1dbc$VCg0*oV+H9wz<1be{CjC>iDEFizhxklj_+=O z79d;pySEQ6tYYw?<`n+>eA+2fP|FpCz7GK7vpt4CiGObbN*?ak2s|>z%D;A95DzxS zGglifB2#_1Eo3mS!?M777-IaIELBek8C}7&?*!b&Ct&KG_prgeNIx{|?@uWs_p`GC zH+co`e5nY;6v%Bo2eB((XSXZ{yrsWCHT7&Pz{K3;r`>xx`dAO1z>(< z{rj86Somfm4J!ZN{{oF%ng93~u-*+;yRVq+ZLbae*&F_2`&#}RqN7Hv`K}P`T82V~ zS?eSY{%|x^oHpSgW^wq>j_)(UUW2SlaaRboEqfuu$p`157I^724omf*DfdRzx?nU3 ztnqQ}4GUqztOWQOXRhY*i}?co@i$QM&WJ4()a@4+GaMZ-_iRlN zjT9|LXZACTr59UJTJFLR%&$S5`ygI9?3SH@rsOaTMel=I{o4)5pFN;B?f{A7mfg!q z=-ym?!D8LZEe8!jn4k`<-<&(Hd$sP|-&=r*si5iurMZ38(lp}mGclWAmA?b#UANL( zB0z%p4l=nU7~9?_}qWpXcUeY z$NKmHZUjgPp%#YlXir;EyA6Ba?|~~d<&9*u1A;Vzbn;=pAJD#n{#3#vodV^IjjAq$ zn)8b{;!#(5-og=xb7lDn7~a@y4g)6elH%+sW31EfZhq-hJOo;!rK*rHG zn*=hP!hxnA2cC5jy0?ZiEuqlP_>By;IDIzFAGy-iRsF7Py#eXih$0 z8N9hUMvG!Qd?&LnuIn&FPI#4DwI$Ly1f9QH_Nn4|wXEm*lX&&N+mqmFcrFDl5g<_Q z_=kNO$zO-)$yyXv+g^1o71koI3x4;39V%4mHt5vYR}3Io#{$glJ3aBXkmTV8E!sU` zcRc!XQrayy&hLC9LL4ni^WAr+4}qof3#996^HG^Y9$Ezgc?|((#H8D5fUJwO*D_R& zJ*AJZgdxa%#M2@#=y|b7??#wOq;?OH~9fDg_XkIFB?WI!4Z~j%K}Mb$j~~~lJ1*iH)W%O_hkuW zlAJ0{_Dv|d6bXgxGL8NMs8n|L7)upD7g z|1b}c)WQjWYX$>tcz0r6e@XF841Cw-`g;qraG;s-<^rr>8>Iw$Q5AJvFx5`yu0 z6@+Je=OEidf}C4w4OW;+#2pfU@k_GA{nM!~F?o?(Tr?bb$=I+d^Xe}qPF+IL6#%oH zHi}?lfAH(kx>TA~Qcl|vE8gn;estC4=ZM#6m=rbOEf%LVMJa^lQIE`%jhXMQT`Ne+XjnX5g&#~5g7>*XWDQXolZUG1C zy7>v-==Vrs=BfaLE!V`;4jyx$V@pgcmS*eoMloErc;XuM1~M!Lu&4RjO|G;kr zvrqei!A4|d^Q1yrsXXr?!^Ou}VnH7+M44gwP)IC2n*~m5Jn|=-h7zHE4}}YU+6Y}; z>4V7B*f*Er1o<2u7IG&;m>ZW5z98YoGMzn{MBJ~e=h)6@ z`D@oN0n??p1s-_wRF)CvF9DvBQi8aCmhAzB!e~dqqc`&y>R;vS-}ON_>9%awoJ?s2 zs-GAd^Dba#t6tv`liFV7B5!2FJ&Eh2WVod~$;;8Nqbq{C2}=4~4DO)W7y)bXPnEf3Mq+W{pS$0--SZ)KZ~iFE+#ws`u=gXQMa*1R}2Pf6^NVTGBN zo{E1wYEfM=6^JQJ*Dp23@exjA@%inIOF_O@Zlxa zo1fpcaa*b37tZ?^ck&%0f1byw%Yj#aQ4PdnHF~;SupIfS$Dv_Nc-XEOj76cTK0SP} zHH8u~t?tEN$|sL{FKrhIS0`8YvD7Rgw3B^kJ)G@lc`;^&vbbz{B0_9G0|<7 zYC+WOx!*!uxIEOTI{7Wg%$L9ZZl&Q3FI~K>)3e@0%kEtb_BTHi$cGlc4f&YUe$Nm# zVQXQg7Sz7>2P(Rvy~TteUk}gBMh(1OEZqnZ%C@NmU@s2uGy`>BT3tNPu|RS%h1awf zI$%hoXSQgEGD;x^mNkRA7KwlB{e8N}*?KPv=TEqvi1?sVg&tOU(!{uPd+G>@K&&;5 zKyGbM6K#u9&px(kYOO?!_7rb8L(gR)fzuOf(UA6A4fb5Otl^=$$4X zFss5YOP(e>d)e3AaBMP)LC@n0_Nw~ZiK<`H{Ug;~w%WFO|0tj^+|GwQ`YoD5fw$J{ z$(wF|#%rL`MCosZ6+8}|Su_tV5$}!I^~lUy=$9td*E&rU{`p^(qF!s9$mV2|z1F#) zc~GglBMo`(|MJrtqE&nKyJ4%@>XAv{Ead4G=Nx1zNO^{|#x};0W!)-C*gpN|`EOc2 znzi=Nd%gg(wb7cH;-m1_59*eR|Mi#ij*9*0huC?$u~QwQn4^A9!!F;n4$OPR zBqjZ#c#b0e*vDeoDf&PGF@{8lAzQd{yGQ0#^kqrnEBc(fmS63T7Fa#B)q%O)5bU&O z#MC;5OO@h zEyGYwm(ta{&G%P8A=3)gnN#OJT^Ddw`m9;!l1r6!pt_!a2R>9*o~aQA=tizZs-x|0 zId?A>N{dBFM9ao6C6JwLutajfu3A5#ObA6b=A!|1AY01IS7hOmxz-qcCNy+k`k>Fw zrcxs~2ZK3E6|`6tQ1lNp_}gfw%Xw>tuEUfaF-+7@s0NnYAmSl}Oz6@Pw=feZG_`tx zb|>r^o`SsNWlG*$Dr83dxAkf~-TcfHGM=MKWi)`@z0QO@3eF%J} zXOPnwzl+!$!*IU9Zn(Ba8VLVGFp-)7`U9t3^5`?I^!fiUAtVL*SLRcHsC zwVa@yeUW_8w-yl;*?W3Hy;txS{f%&pUkUabO|_cfmnacj(+St><&HOcDqZcuNMfi% zqPj#JVGxHtJKtNBp-cgTSj$GbmO)U$+*%9xnspdsF(`?RcSX#a=p zbi$H6xv5Q(>b4@`qc0K4ZAJ&TS6`C}zYY?!Sp}LD{6=fMFb>HTb>NIvSlvC;t44Pm zCaMq1ys;l2db5GY`Vpx!3aj9k?gl@fHJ}Z;(rk;-&M1g={MBP$^O@i(&BF+qRMqgr9wYzmM%moUNKlN zI)bc;ty6|3Cl=-_RW-oo#6C~tTxU}6zX_8Ai^Vou$Z(6pF{sND^7R zIIE(Og%mlZWkhx_oc%R3%mB{}X_E=8$6&;wY(g*t1Mzj)ip|k5;pLF`?iHtMVz&EW zb|~}~2l;N|oJq#F!!Kx7BXrBdIhov8Wy7F#=Q+QS2%BBZn<<0t;UuID$66|)6L`L! zC7+<4IK<6$0^5=qx%j~5l^Ym|_uE;tmmB+u+^A#_z+ux9FFN#>PT`P}jVMVe7W@|i z(9C5uN(AV8IKqSi=^b{0Rou6h5tlgD=D`E5%nVs+50521KaZtw=({#uRiv0>I`9+hJI@4+K+?wM+G9$3V+V*SNUGI!jAH#ey-0P9VD#;Vu0 z37NPyn-rMV%)Ql_=Z#Sv7liSaEuvzB;Q{}`&f4tcQ5p{WQLN!Fq^niC4w{=S#16~O zb5dbEN{m0hjXMOmMwY7_IY_7HV2qvXC7o<20ZxwbYs+3M$IZo&^=G%A;1GYBlbGSK3_7jHqb+O> zec&e3uB?rjV3@VBK&POio z11~oPVMGYuiG%S_s>Lu&KQq~P5Q*Nz>aFVl-q&W^c?@|?#9g!3l%9!Q5A2pG4tda- zACb+Uo<%)YV<-oXZtOq>Suaim@ckCJ~RSJKLX# z%I{FUgJhzG=5r;WngW(G$HClN`O7u$RW~X@jIqz+k0g?IPsa-#^*r55Z zMC8YnD|vU!y`ML>fQ<@v_OKFJl%6_kbe5Q9tPR_8eKAPWnj+2#sggyD3~!NLb_+cB zs|1ux zq-b{mXEBk@&7jh(`gEF^r{~)NzWaPFht^>A-;caJy8MKaL6Zh)jj$;wB$ycK@%*cQ z7j89<=D|BuHKs8w>XG3ttvW{IV4XkqhP;Sk`|pk9jkIvQ5L7fgm34ORyIwH<>;Kud z{=eJu|NsBrt{NvLOFH3qU_1V%jmSuMK-f9P`R1~aVQ~X=>`hG1M}-;_DQK4`=MQ@zWu#R{`}JLs|Wg4u)ufd2U+jXGrN4& z8tWO@XaEQq8s*f81unyPmwnwD(JWZ{+*Rf&YSpR(k6A|4zIe;UrqK8dI|X8l^X; zHI>GNW{+wLfI2RXm_=RCl^QPqUBS8!qzF1b)e%zUIa-d7tlKX}iSSoT4F& z=-u3az@&5I6+3DxHIsID(e~B3bV=7J;o;a^3f<#ua}c`!inZ zo!6GLvAEk@uZ_3PpZ&cdBfGpST;9ddrNe#+ibZIQLOcRdV;A}W6PSJGav*u0 z1KOLI_4|Y*>;7Q@{g>EQ+Agq;?{n+GOtOU)77No%AjVXK5C!9)+jjYY>xmdv8X2Yo zKm5%#U7668zb`OtR+vS5R(u7lCj6I5u>Q0u$og6XJMC`-FF`h9X~2l)_E@b`MiA|+ z@dnUG%g=v7;!!OY;OV>%Pegb#Czl*R7HABD+X<{_u%*P*BZ?QmPGT%QU&RCNj_F4%y26+P| zFqF9?h$;iY^OD{zVSXSY?7Z3oA`vmyg;Eg9{06A1X!~{_u0z(km7f@RmT}t?yY5K{ zfHDA;_z>Vmlb}T((*^?3{SQZ&$Jv9Mo{jGQ-C42Is3aUXvY~!W1Y2Tjp~Rx`)KL{E zt?+|T!9ELHkcYaTG-?L^`fq^#1?Xcy+MFSOJ`bLMKD2$6SdyRSH=#edR0tkvZEVdBFOiyi^Y-~rX3D_sh zm1Kt3uTFn+@Wns)kGHB-li(GKq9sE06S(IK0LNH=7K_C@V885^0)%J8K-S4U!=U(@ zb3%FX5}5BBX!L)gdy#Q$5Z);}hvA3ww7OL0H&Eu8@m;kd{?4C{PzF=SD5|q=fRbM$ zYjyf10+k`0G>UFwR}~AoN2iV_QjkOy2g-oX0ve8DmkOhrkH)G-HYF&`#HB`)c}i9N5C4<{tF(o zlA<_{%%t;eh;qE2YkTT-Q^bEfF9)I z=4jr~sP3cPJy3q#7`?i)gb5n;?BfGV3X(NYcn?;brH^*bZ z{JUVsqZ*mGn%iVYLOP{@10c7A<6MY8oov6E-!W7Y4_;+bU^P%(CxOj+ZCaI5T0uQtb!8bajL6e}T6kZBMpqmgYja{vOK<|A z3eG}$UwxE5%AuP)=XEVHL!cHHT4g}WqX)}}(eBbVjO-}#ok=ZP^y;I0is|C(qt1Da zG0Y8Tmqm1T)MAqr} zOuyM#NJVkrov3_isadEqnNdYev=bp8<%08dMa_HuI3ao510&aS3hrGD7N$EJ|JL@~ zOZn2{ED;aW_+eet8i;80jo8zVG%rZ$mcB(`J$nmFRB>Cno4w}7_O_zeBO5mM!pj^a z{i?^5*Zsg3rF}Odu+Ru!xf=yYY~*LdRwj=Oi{M8s)N6zwW3m_4 zIv({Fy^ljFY9f80e_rZCaV7t|5;=L*F6lN^37{08t*ek}&u6nU)NpN{S3#!+BxF5k zh&Ny?)@VH`6Kn+UfJ1c^ZJ@bXo7Csz0T2Vvdn;$&tot+kGgW@TWZ@6z&EotRD>ID|IC_;rLMSPxA}0gaGph_1tT@ z*Ximu6F(2$BdJKi;6D3f_;%%xcOQt;7U{5|*rk7a{gZu`fq;(x$N#I4Xk20yu9f?x zp%=~w2dOq;TBzT9u+_NbBKbh!ENANxitAbP2=Xe#Lizh^@MEY1v+mwy*z7tcnx8hV zPoJ)_x&eKc{Qz>=;N866=`-pLh6x7)GytCp$t#k)JOR`xi?Dh;m+p#$MZ?p5_q>z% z1yMhs@ow#u|; zfE$S0UW%vW3rU4S<8ntgpTPkrdbo`mu`@iX5iZC`16(8YT`m?m4oU5p!n%|@Go9?Q z57iZts?BsBu>3oX7Wn0_Q0*-kl{-2NZ!oIdMPkmttEX(I+5h(lFCj-TdQuY$|HLSn zi};C2zzFt@*iz6wNca#hm|Q%8nD)cNuS>AIzk{-4V4@}N3IT-8$nOE4J{?L}h2d6a8-p?ayu|c0Gwp z>&p56I@L^$whwf_xGIfJ_2=$#srdw|mf${m_ z$JWc|+^@s@3%30RFdIHjy)#xu9Lj@lGd!wJTZgZI(Qaz z9*wu+EqUeI=#EY|GNB%H`k$30$p&&p1;``bKNivwAh#3>tD_+)2E^Q$jEc^rLe=)l zS@IH?ct+NnNFEEI!5Q$ewgt?jl|u=7k?J9gdD43?T+KJ>yON`K%Ib#TrEv^BoK5t& z+O(J|y~g&_fH8YZL=03|BfYQsUkLbeJI*@Vs*7BbztN zM?$jZsSkI5`@S-W`}Zyo-DMtOrlS1h;x@=HF1_idQzJXFT5;Gs;-0Dv!d434-~QJ5 z>KKwN?VaxGe^^jcu1%LHqYKLzzWCnbG1CnNT-zfbTnc65bG^^|-xLFi%|1L9=c4+eW_xw|%!~5@Lb`bWHH~q(LQWqV-#X0E zo-Y`j1B8r5uUYeE(-m)VOm=v`N;);%%HNiEv+iem5RvibJXsYSb=GaO6YI*uAAz{j z=wJ08mw?*fI*W;)Rp4s#t%xF8^9VXBaxQ}gmbYD`l#w5#Z4Rq3hQEJb#zl)J`2!+v z2Qh|-Pcja*#n`n_I?=t@!~W;%WUrLndmc&4C`79W&y(#H85J`N2F^G{^aDWp9mcfJeO87n;?e`TshGnw*(&6!G1@m%x0UkRlkSUB|j(qzZL*!EN; z%g=J!Iy(>%=D^zvCT3ro`5vq$QP8_E2ZK*~4+ahfGl=O#a{Qao`}zam;KY9Pv5 z8nE|yxWFK8>Ti9ZYT6Q1@nlo%zL5D(>6_7qUj&AtUI_EZwT0}8My&q*PKbVD>-!=W z0-3}4g3K+>ZxmmJqC?HC_}iMJ?`5X{eYsQWO~gOT3)VKjZ0d}?)R6?scT>?Nb8YPL zmj~M;@2o&uh+6&X!NP7)6H9~B)LBF<@3Lcd6FN9n63ZoWl#gok@ zSv9-yOMDlthuTx6=g$qGFO84f@(2W1tp?Hf+n4bNesnsQnX%KS`8g!j z&EGqFjL5H|sYvwS+c{6xM>hJqJI${@>^gys%9}R^IWgW=J|(aasnQ3Z*6=Wo$RT|f zpG%D+5mI#A^)~Br2r zK0brkx@d82%=L{SL#H>RMPHD9HRi6^#sEBoHvo8X*aI2X@pE0{P*L1~I?dq*;{ONr zPloGsKt-+hPXF6dyPo!E=bS|}&E|pj(F5b7Rz7AY+CYm(=u^I_M!OE`v>!1)*NPOpG9IvvlzaYo zrNddJBiF_xbp5MfHVBVh05>f0)ZvfI;Q8mng#e#%uMoCUErPxDKIA3)$o9y;*41E6 z=CCmf0ZE6kLH61VGsS=qc|uVnvS^>8fxEtG6%Y5z713$^ptq8wCUb@w81`ZQ4#*&p zzKTriV9T>m)b3S z6jMDCI~E97{wTCKRtw}f5=$a@I&Y;XIz@l}PE(TlnDyfLm9UGeRs_ z2sZnwQ<&64TxA`BF-*0c4rx;oVk zCd2IThaxXoe1-Ew@s85kZy4*8PnahnATa_z*K7n*v5xka-@OZ`AV)h2Sa7)Dix{sz zt^Zo_R9XTnAXfRE^F&ME;x_kT(ktg)3Xpvq45s7Boi+=;#~fGz!({Aiz1Rj|g+_~` zbtEE3x1Zlpxk8(C4EJ1p3jApDLU^=jWa|e3Kx6hMNMoGG3v-yV37z9HA57|dKKPMl z%zvW~#6)P&!nNJOQy6-fQ?Huy>>?w~9~NkP)TO2rS^-M&Mw#H=+(_P`IS7sq3{(0hK?L$j_^bq%| zC0`pdkh&VTBDeXAn9>Lk+2W4r08Bk?Bh92E(qNpqSzCSOb9TGCKjzs54`_{CVU;M^ zIR7Uz1YhukZglDu)77#rIOO)^*SDaW%&p+%Ok*zV5=w)ZUUR96`Sn9GdiD zzK3AxeG(jDO{+VS7}S6|A*I0mdd$nX-G(?L@Y>yI2Txj`)z+_RkBi;sx07`z=vA)< zB6aQ3o^0`YzusZ`IFY*Gr~5fAL*;TraG>sCSoopp9fTg3x8k{3mfTk!M*h$H^6Q9H z`~)A>RtTzmbw}sIk1h83NB5ML!vyc=sxDwUrKduAKUJ%_tQR78l~V9pIk*)@noXc`nU^WMNAg7i1jvWgfB%fqf-kAW zN9ERBO$er4w9cm|%Gqr%p>OL)=p<=crax}%eJTXB#NINWw6 zXVEa}g!Yp(Mxakyp~f7uOSAk)Z6R@0YzB}1y7~?Lx7IZ`-V)BHZ~dxHryL)NV|+(z z!3!PAFTy%p-r}))%__=9og zexY$$1?HyEhc&F2?7z;L_CBI!oJU8^eZ?ql(~3>Yar}?C_1Dnk?krpsN)wB=(QZ1C zxxp_@dGId;%sfCd7fsbH=kH~`+9{`SSfll?lI(8rKbL)Ba#Y~}AuEb85Su-rsPaTZ z+(}k*?{y2GS0=L}BU;n=)*mCE2lY<1OI7GM(VQ=btnI#fzqV>e_aPWmF0|Phy()71 z(nWL=i|YQlJKmC-j#3qGoxrMBcnW&!AH^1l+NU6m=(NMJb>aa!E=g(88LMa^TCGTX z2mrd7q1EsdI;_@;mFZa~>F6?HtGWvavDwHY;g%j&WA@LlkY&>@mBL{Drn*G&8?~=s z&i2)MW)QThi%ngM7V4Gee@;h-%qx;|%iW1a-yyG2CHQpurbU@}hvn6#s~2+m8&eF~ zA#!LU9uA&bi`t;l->q%hMOrC1u^lgSFFTr)hjL`m@^n8i^i!*_ZL{ftx`Cw-8`F-K z_w0ISZ$8s|&yxqd9_%%nz50+<Y3Pq?*1;_VI!RXyx+Kf$}##0-!<04yBjck}ZvuM2Vu^-PMJTX85+`asjC@thzufa{#9JY1e!(J1x7Hv47Q&UB9chL; z9Ik6i7(UMHyv{-N5`oi48)CRjfIZS1&rv=!8=~VVvgq8B3tsadqt%Go_>2$|qLp?` z<8!Tq2ZJJZ_iti%QpKED`_SWw8%VBv2c7R^QOTWTMIr#pkdCU z&=j^0FTO&ne77hXQIxQ%A|+66Aswv@nk2m~j$jUQLe3*uid51^Oam(5#6F6+)shGN zOz^r7^6b04rAQ8ga06c?0+g*_z`?y2CaJPkbvx$J*jtDfI*not2DhCV=z?{wSV4b^ zNR{b$&uedo++yQMv9l|aSEPnU)&*7072p_-7qJneepn-Mjxz5=;usm?I$H~gI_B_E zNfZU^`}DCxACyGN$-w#)_t)JR-BfWF{8#Q-Hf|O&g))&zSj= zd<~F~9o~Q&F7e7@fqz~0cnS7`)}?%nRZ`ZMd!l_7&RMB5G52A^s?hh-Wj;-OW|1`rnxN=&t(9_4!d(MS+IG{!JNlOXEU1s zB7TN>mIwYQ4$4V~kBn`yzs+|6>aFhzVQgNbEnn+2?1|6b9|+tvLs$I;NNpP{-6=T6 z&&kfaz&VBKx}5G=_%1z8q*h8DOkWTJfIfuDoPQR|aY{8>c0o2AuXc*p%tfO&n8i%s z7+D8@%XswQUw%s=yzrM)GHe%G_#(Hsr|UrvUllg~V05JuAddkuY0T%kZ+*qfD5GK4 z&A)r)RNQn3@e}~`)!3QcK`=y}8?v}iXaJ>XLBBChH9Cl4U$`?qJpBx|!m-$I1m+)} zmY*Gi0(c}lTDJA3s6O~51j)J_p%1{kCGCDQL8Jzq=Z!-K`wQFx@oJeDlS2R}(esRH zf-BY@etzn1*tTeu$e}xCkZ|{Q!=posMvH2;k7Mj4bc|^9tphf%)$KBECllo?lm+1t z>@w88jw9eE^hcC$JBkIRx2jd}Ln(il4-DRF_u@v|u8VQ@NlY=_iT=9dtIQWU5kx8} zjyFfN-jlyVj%ian3G+g-VQ-oDrPr_8!+n48`I(I-e}j5!8m9ucBB>vv;_>|pXYWHv z_RiPWT#Y(25Z$bMB~4^i{kO*wvxeV-X!M@l{Wlhf^4!Alx>Z>DO}A`lf&{xsBGpW4 z)s9eXz2?^|dn%sbn5Qi}Qo@R%RXK9Nm?~MWt#j4n;$t%?Y0v;at!e4o7RWsw_W!&%zd6sr&EdnglZqTZ9=1) zz4d9V$($Ev-29uP5)La~496#_?6(uV!+yAm?Ln=%VE9DYa%s7r14C{DTH-hvGCW=D*@Q6YLvF!ROvEOBV6reVvtCqUP0Ls>7Ph z+&iB7?T{e(w$s@}@4*`~+dh_01L@j&HJ#!bZ6^Pr1jo$p1UYwySGs9|^&D=lbK18W zJ537?ZvTSl#$f-1Uo8|oZ66xlXRYOMxUkHcoPFxdamLn=A^VK|ucshGC{)@`N=@H3 zfNzJ8Y~$AD`0>lCLgXkVQ?C0xMs^XGH_xxXMNng2CdKGB(hsj6&B(>H=r`a|@wg1>Hz{acwBC8?n*H!iWc zvOr#Zrj@Hh1$8H*hQcenuvYlbe4kE(wJT%&yDOC@V+A?2`7TLz4axYXq+{WA{Ac8= zT#i_-;XgLn3Zaz%?srp2+}i?1o(7*1 z5*2qLx<9qaO_Up5aou#V{D9N3ZF}Wbj!H9T;YraO=Q$>$&SCllDrQk&)al^w-M*?q z1YrphnS4Azi#sWQ(o1SlfRNAB^f)gaBGY}Hl)%v5v4mz0@B5!1(~dAa#+0_ipvGq3 z1}2Ur)=Lm{1Wo3~LE1^|aUclBuZzE#)Rl-yuX5m(E`=eoxam32w>pJF+%lImmT*>R~hALqS_r z^`1-9NG}^x66~bHQ#i6#<6{+Fb7;tE=C$V)p}@_3uv; z6=)t1$XuCE;Pie#GqWmDR_ThX*haPkfC|JbW*%>amsI<96qp3~=KzluPj_3>%qsiI4@DsWzmI$N4kVi`3<}Wc9}_Ad`3u(_hfSJ7zC9dyX;`| zA1QbD0r%^s(oLO)WTs*WEI~0ipJr!Nt{E^-FQ9P^->E7=E#pplZ6C}9BHPQ*5%~Ci zTgo0}>{zQqigMbr>J5x{7ik}RTLe;3DFpw2(#v*Jn0)Fk!7i#0SF!K~?&H}6m|r>- zg~-XhAd5KyC~*RTW+(tHfuR4ydCr0FlK7?Z=k{}Bu1{f*?Kjk^$Tieaw(UH!myRG2 z!TK^}qqND+0=OxdM%x1RT$9Kz_kve~*z9M9BY@GmK_T#{*LxW}f8h_nC?lY9K8H3n zi7eLM5%@*M9@-BAM5XKYyQDOkSYKI(fiF3HhS9Cg3$HHY8sz?*FC^PjY#mYgo#WzBX5B@ zWWqVAMeI#s?Rw_;oj22o0K;N(9uOXK$LKpVTMX>}p8?I_CD8Mt7(2RY#`>@!hrxzN6k zd;O|EZGSyX8>=sXsemQwNcQY z$WOLS-_CtS#2Ajncp!`mW@iB?oeTtIyLu$16+ni1u&;#L8AO%DK<$lu2mV)@9n-5w_d5W59mPJX`PleA`W^yQX* zi+>tk0rF{{`(S%#WNIyN;4aLwi$|*jI2J9LfSaeX9taRzCw?}0cpc7j-F2dYU`;>z zr2=HEz1#l4F~j2Xx~n5f%{7Z(b;zEg(K8h69z31%VJY2WN7?pnUv4(eFjZp4tJ^p1 zfN4h-S}fCEsN6D3N(g=@o|N_HD2fBlYozSV{XlP&vsBCo2Xq9KD2D8eRV@1#L0f=4 zzi!fJ5~#z~o0V5qW4rUAZ)Tm(`C)?$T7h+-wyE==X9IN}}pHDTDq2EeR`ltK}lXcDKAwZx< z(&17ne-8*5^kYK4yT~u$mNC9Uztr_c`=iYb!K|aaTh(?&T{218u6CSP^WCda7(#yj za;MZ`?QA`aR2A+`O=5BufxM@RaAeTqJK;61EU=?UrApp%Wzd2B@0d+1w&9$(rsZ}- z@zrkTT(;IhqD&o8xzPwrJEUsbaBHxx4eiep&MM41e@6dZ3Xj1`v-)W&oV zB(&CdCvR&K@lEO3v;xHow8KPD9NRI#Z~mXV7Jkx^i0H<^-uW!3LwW&+ND;}hTTUfg zZoDV6DJld^O+Au}8&phufDA5$Uhrsw&TDRRBaFPZvYSu929+f8``U5&Uld<|wc~tR zH*+oHRi}l=U1{Vy5m&W}a!J;(j&v6rVSdUZUa_=pQ0joD_1-4wEp~X(8QLLEn56U7 z!q{H(|9~mga3K#v-iK_EGxTLBq1tYoFRuZ zuT84$Hy~85?m=X3U}G@UE4JFf>;dTgzXU@Xz;pk>gIV`c3EX_Dy`}K3_OWZw*#{J5 zNkKoDe_|cZb*BZ*t!fM$e|VDL7%dx~4Fy54 z;xJZH%XtWF%HNhKlY55qV^`Kf(z!a+#|uFFc(=jDdC0?}5yl6PF3RY7SX z>oEe(jv`}E-S_Lt*&xeq(YweRis@o=E=&!#HD{hkh3KUs2&MbP$xBowqV3hbU=WEa z9EPe3_6hKR*yRah^+j{0`FyZ-ZnC_DO!5#JR2|mVP&bgNHd>QZm^Nh-`fmUj`HYHt zlfJ%=D2Dlld7`1v`rXR={`1#gTt-cg02|8l^jqbT3J6IGNUZNd8?XlA4MT#Pv+T7T zWM$dcBsPczN&1vcCD_e*tggkwtp6rbnf)WHySnOU0d5AsYo4zjhzb1Omv81os>0SA zmH~1!wkrdK{dfRA{+ca4hVjK<27j|Lu9xuJVSRU;T4}5gist_JX?Z|~A|fKHFj7*M z-LQRvNt+sqyHumg$GdKCkcFV4Cso$afCQhNx@^NW&1A@;_Q3N*&3MTWHH9oE9q3*l zn1DZh?_eB;txrgb3va@{yBP09$EN&h_$1gp%XiL#clk5$O*o+C|q#HgZkkRmq zw+jlPA8r=83Jw77(gh}5>s~_FdRX&u_&#khS+>5&T+gN=!Fi8_$%k>h2Y!11Yv_kj zfCCsKD=EZjaEEzcjud@W6K~sF1=ns71*6;~h`cTNW^3r~=@D-o09`wRvB_Ja28nPV zR@x4Dd<%qB28V)uAM=HHaaAgviiiH}yXhLAh+}}r(XDiDlbpb+8aOx7|(yNTm+t%p736O zRJH0mcRKs8J~hLHs96jAl54%3AS{ZHKZy0-l_iYO2Gk|cr4}XlA2I^ zUVyA{6Zd~=hXdNfivcCR?-&GsHM0qXNL}P6c2z;+HB$a7fU2d zJ$Z9llKo?}bM#G=^hAVNsPp-+{_ZZ@k8k%u%I3|@@Kfl=;g14Pyq3P6$is_5U$G}m sphHJrN^AGikO2sTsSW>s`)zX}Jas?wR3B)0a>1AB9xLNqBiGRX0;wzrmjD0& diff --git a/_images/docs/wait_until_task_B.png b/_images/docs/wait_until_task_B.png index 00b300eef2900f801c6f4dbe1be464bd524c1800..bbd2dfe6ade9df5e0d0ca6b08ac4312a5dcefecc 100644 GIT binary patch literal 132975 zcmeFZXHb;g_a%x671OJLC@P3#5D+Ct6(whAa!`?+b7-1YQ4k3&O_D4*gM=n0K|nx2 zvSbCC)C9?~VRpa2nOpyvx^utWPxsbXWzn`g;hblmwb$BbuO~oNS>^%-Ed?1F*#$Y- zC+cKmC$VH?Cz{TX!#5IN8^+~TmKY&{Nj&zNokdB*z;t$U-Fui2lcPm@pXPoBUe$90048`iYPt6(@+38ujKHWTO-zkh~ zzh-h0?gsvBG}`j~=M&jQzuRa3^D*Qfreptps=xe(=|5iyJ^uLLkB~V7qaywJedf`X z|9ra1Abb4ZPp=qH%KhgnhqwRdWdCQ*$jJWx9UAWkjUe1Zs%O@&ATN`V)xWwd+a4~- z)oT=V>^;Q)tCU4wLh_PdOD{b}=0L@J1=gFl*4x;HrKi_k zT?;))R?nI`w-&qj6i(VwQ}tj4%_~W2sYiql<>n*RWT&hjKZe?Xvg4%a8 zH8ZnX{8eaWX{jbgr)_1GEk=i_*>z0H%9<~)BPY8y_iwzIe+yHQ$Wq|0c;Y;8iW2n52kK*VNy0$suq%SKYA^Y7q8V*50Z56TAw>8lw+6IpA z>}q$-kgICj-zZhs9z4*9GV;o*S@^U)mx8hS{*gh1xY5i1yy0Zc=74^TkYh4j0QaJa z0=Yib{ILAL-20E{2mB_@=i@zRqPIBYdLp^>`CJz?@pybzQBjW(F-s`id2f=YE;CIb zYGFD|rBr)9+B`u`M#kR=O>{*O3C3mG^bgEBVqAZvcuB~icN*zkmT-esU*DWs^AP(W zof0E~s)QRh-fh#CSnZa@Qc=7MkB!aA&Ap54=UsVynogCEwjZHwnAWQ-s>B-af^~9o zq6(JA1g{Tvi@-gc}KasB%BwvLYe&Un%Ofq`^hlV%XlG%25v6 zj_=u88i`0q$d8M=sh@-S_JSAgvto??!p`!zOjnUCQ*uv_`UP4(SzTS-4^1zes>UFc zMW%utxC~on=-QeTeuCK3)7OWKrZ+S^PD@YM+pOVj&dkkKy{tnj-; zpa1M$rUjo@eR!jtwlT`Jfgn|5XA;zpu`APuu!QBHuBI01x+LnhDD>N_pmKr3&=VhV zc9t$!I*+(GTA|_T=}AHEtA#>~h=^$F=~->Y)~r;GEDqxo*xA`R*w|z<16!s(v`j%v zz_^AhoHNulH1f9n`dmX`frl}Td9Qbftp9j`U-j4+N3OJ9bABi}*w<$;J}V7 zDbI0M>D*;8335HCZHtYKMX0GUBz9%|Y4m4Rd`hre+4Q0gc%rGUo;*5gVEXc<>_SX~ zmYQ19Wk%_ne;;IJEF-P!Sjg%#z5~jnq+4!ZES}Lm>dM{iKYE~4<^C(@(!yZfAujag zOjn{k3?XQcz&~h&%;RnT6hO&J8`W+~d*enhZ}X_@pkedM_6<2{tem|3eaYQc6|dz^ z@68-z+yZlSmPQ6kUs*{BQ{VOh#EG26NMZ{e@`vnw5&$4dExPY8w*L6U+j!07$1u)1 zZ@ql-181%YGb?LsQy|R^lek29dh^FN1Fv!wEi7H-F|xT;B?*wiJ7|oqiH0RCr=ak_ zu584>sg+r4qHb>?M;e=zo6FaH&AIuy`6u*#8JbXW&Y8G57%S{Nqf?NG+R}aC@%P!( zrdM#w6z>Fa*bL z1-Lq2U4SNb4vzb9*&T0*2X>=E#a^3MIfta#YW@EGo>9S|?EQ>5rw{A^$qV9i7+1P6 z)ZRND@2_tgpBE#ymrv}CTr)ZT`jzgNXRl#4J;dy0I%3V?i&d{07A~%igIV-pM(E20 z0wHf|!{zHKnorjG6)+-?L1K>r&vm&OtO7T$@!?uja67(edA%)yv!gFdBX7NCv8Y{< zkCwmrTJf{5#~E8IW!fXT9$C&aM%}+gxc5S1Jy1@8BQQA@aWXcE%ZC{F>a%WFSvz$WZTSg>x{|I&lR(!C`G@ zCjem}jU6g74V+(G8xhg zP@MSr8tn&6Br&@+j8$Pl?}x`!b1(q#-rvScc}1`g*tocqj<(T98CA=b3PVFfUWdE0 zoA96QE8EuN)t-9rsBv}Yc&b&)#@u4Ls}}F)5+)oZb^W#g9# zW`4Wws3vbSwAgJ)@4CrG?8JfeY`l8{0MzD^Jz5{T?kumM&}&;ZmOf%vwe(T?hVbUj z6oxRMZ;z0Y^8FAPh_f3LLCuOz6bd@OT%YNvglKl{RT9jCG|tS-tXFCi9TO9?sKiyM zqll5%%N)qnP1)P?LM>Sv_hNiD7!jJ9zhdRF9Gsl|?#l)pG5iX_!NFEGHhu7nTz2tM zoOBohWZS{AI->2E`veNIhX!D|w?ra$`S0VdZf<(}(UR!e1n)IDTxsdTAAkCRs*e}34}(b3l0+TDddbmkWn+!peRg6wN`c(A)SaYQtRqZd}tM^$v5)0dIO61Nsy z-S*+~yOI%WBHXAp`k_Ii!5n=y#zPO&mnC|8r)piN?6k_-IdiKm9B$xb#aB zI}bAweJV-BfP_D_`^&xJ+oLI|sZ3)&`%9GvYwe^YW9YrwWMyw3#Wdzc$n*OB`t{ZlZt`)&p!= z@SAfD=XexpJdXOY53HennGtuS?ouVrxf(j0e7X)Ro2>=~AHmj3O3v+Wn zA?k7+r<&(!>UQ3dCM=j<(uf2PwQCUtB!I5ON9t1rHsvlc&2Np^4+1o}5(#yOIgk-+ zH}mW*N%QvS5<0WEOF|!3(%!OrUF;Vnl`s~i9*81h%Gx10*-aK?5%B7exW?>+ZruFKVg$YNhc-qn49n}B>38h-ChO2+<5-9&17dQ4>G zRiH4rKY*c4@bU9UM?Wx+Y3He{Zn@e_MMHB#ZiWZF8_1h({Y1U1o2~iU1MeLN=ayUU zIt9+o&K<<<3HzF5;X9ViLDy$;jEUI@^B~^sG55sKIE<`FA7Pm;6liKkEovX&=0~hx zm#krmL*@PfJUl-2K?`~lFZxiX)?9;%BJ0_UFls=_irIwXHoFS^Rnk>Ht*to~TMu$i zxm5vb%3ot}n@@|Pm79S_{h-;K@6LQtJ9qK$CDvr!F~JhQyqkC$S={^Fh!H5!z8EzLK2|ux9=rdlOT2;9zmYko#Y{y8o>4JY!1@Z zm^2IxZG(0#o~Uncs{=>mzrPSFL&pms?Sz+SbR8?R+p;Ee@P78B$NU^4lrV&vUz(X^ zfBB*c99^%>F1}Op$ouJ?%fu=AqmLWi@6&+kAhfj!059olYirZ%yBj|qbjdEzc01;- zd({l+af%P3=jZ0W91<-d=b1GSAO&X^7i$27oW(2K4424-v8pKRM41hjSP~^By*K8% z2kJD`)tOxLLY?oyiUE$G){wI3fALl}0F@HN%W$>l`mw-J%=HJ-5Jtm*+=zkoPwIn? zNYV5$SYN=7``#8^e_+N`?KY{JU#0*2c@j=qXIoDU0=j6g8mYGAAT)}5!~+ROSr|`+ zbSzi^V(PwPBqu*NF>$z6wzqP0XirT=WznCF07^tF?DVpsVcPg$l7?B1Q#-$;Efq69 ziw#dqE$|$Z1!p7t&LwDS(#bib%E3alMn%Movv-<`BWlNg_I$g-mwO2_6rI1H3H3LAPNk|;;KJG~? z?p1P?OYddBoMEp=e(jzWH4O~`@T?o+I(NNOv|!fmVjyp`k<0gxZxUW2J^RjWwbvZC z{ihEb679r&G0*OOx`$F+pg5?Me6`&?yFL`?wS+lL80a5ygPiw#L`pb)>}&qI!<#pa z!u|<^KX0j%AAfzKZ7(b#!H&l%cNVu*eKZ#MbfoLgvvWlX@;a|7_xJPa2rF5$j$VGn zW4()eJ=+=C+p+!*KX8V|6J=8ZisDC7(DKi--5rVTGWU2N!B5p@uu}<~xZ)FiqI9pp=KOV|A ztja~JBuW_OXcs8&+^+N9U6Z0Xy+UY`ZkLG2e@W1K-}?Cz!q35l7qR-08N zAva7}M9$RIbRb54(9k^|0m6D)VPSaXV0WG0dLZ|N^qpg5m9gg}$wx{r5c!#~ z!oEIJefsn%HZ_z{MjlJbgv2=+$({&pqbwl1%IcGuzNhIt9y-r<_CxyRlH*`!?*?WB z$$IqdC3K_zC2b?4goZy~Izv!wHpNQM4>w4l9F0ZP@#$PQPGoC+2!arpDN=>>0|9!{Rb z&|M&1vIaTL3xKZW(k*&I7%b2>H_xE+noD{+FJCt56bP9rzh+A>&!|REA@Xi_hv3BB z`R~C$%4cG%Nti=oG+bOei^q>_aBl>m$F<*~}u<{SJV z730x|yIW(oA|Vr7LJr+q#h`OH34_+4iTCh4X!iNopKqV%a z_U>&GsDq_ld*oOxzrDX)xsaXnGN>D%J?DmfwVHW?XF8xq9Xm7gQ^}pLmu!#+JBL$} zhf-J z=OYGtdR`FsWp#?pf+78t`q1c|Ci8Y8)s}_GT~EuU$Y8XjrTuWtid~yVwX4DQb1~NW z-QzXLO~7Xz2$61TZ36~5kkKZCAxwGtWy*mxJOjv;8df<{G{c(2d8|&pwM2l5RFNc> zfGSPy&(S7)Jx$-2Q&8(A%lLu(0&VK4b6445OdxxDu*?d4=tFPhgO)wfjIAvrNxx@UNPdxQlH&+V+brc5{;VajL%6tm}cEF!=|pFR*;}M ze@?fCMTCc^nkS;PNDm8<7#*F3K3q@C&dmG?6d=jod+NqOZ}vrjV1fhWp#_-fUSJpL z8yhYlAxUa~k6?VnfoVx06x10>66aMm$5wo_lT>A40fzBPL#)VslHYXvksz*5s>>vJ zEwBT}kUB@hEjBsmdAE|dHNtN{E+*Gwf)P(AK}~PEQZK-%O`a|eVwA*x)u8&(cu6uB z-yUTR#RM-J3yl zQVg|qbqxYZN(DBj40l(Y-oNGjVmkB-P)K6e(E$e5&Ju#`l}bSS&DPaE*zkDd>={s6 z_vIm0(`8plo@+72%83c6aCUyaGO3zyhfyMkcNoeiLA)@PU*6=v#AvCAZ-(c&Mv+QE zKtD^3WKz_YhKgk%?FWLgE?02ez1s)uE!lRYl%18eMelnBkEr`{_{h=# zR8A<{sxso@JthORhCm7OJ5D~SIXc`InNJP#DmnCkYZjXLL+YfUpjhl5c=HF!AuZ-X9*^0MRp2x+4pvj}IR{^g*$(Y{Ew$qR8tpis_0Plu)2p zMtQaU^xvV9rFW;S*m=~(Tb;wv3l&>d=kL)U35t@D{mp{wD0|2cw&0yAt~`Eaw{;0C zJ|uY$Su=j(O*kf{%z2Nge9R7jqSI(JXPMpKjo$n3Yf@UR0jU`yU>h?$GU5u#G4sop zdw2C;fQ^U=z6zU)wKcz0sCkJvD35s)* zYAd8u)(CwC&6B%Ncbn&2_{XkuR?aV0Y-`8e6leG&w`VkAK$iBlqZZ<6GQ>t?^U^~{fG zD0pd^n54k7ARWIU+A-(hL_(mN?QsnspW340VuXf9igTy13}~FsHS>;t`n8Swl?2CL z@+ki$DMeDeE;S`qk|+;}U_o$O#3!~)bq5QMXOiUqK&67KD-LI*0g+FK+ECL!M^4QW-maUKoh{I{OD#*Ss3ifm$wsFq0q;jw2!Op78OOeS!i`mZj;VSn6xJiDO zIaMemGv2(oz5lIVl`Z^>-_OEy$e9rl5o=yGv=7XJii(OBmF_|j7*azNgz2{c%1f1B z#K?Z};+BfvT_$a(oeqtRG~*Gu1J%j!urL!IItS^Hn?nS?x~YJP70Gm|JFJjz)6`Pp z-u?2aJ9?i#c#7v?N7oi9ce15dJ3AsbY5@Hc!dwE*~SiM;7g2(9}hI6r83%y?UC;(!Nws*s4_g zNCp=k^(&AX^OkzaqL_x>wJ=1WiSaqIFs<-qn7onKous>?eV=1+?TDHgE?cx?(q#8| z*=aJeox9JUz}DsoRitg&9j;*7ZM;6-2~~s^Y!fvNdE@K)(*5~pZT3@) z{d$E8ToGyVt@KHc!py8zstP#SIc1bgN5X~Oif9!C+Hc6KjsF<>Ad@m&wQ%9xjqTQJ zDQ(mR^4R+=idqg1K9k36vd57cz8M|Z5rW2MjA>i6Px@r&7b^*aq|va>NGAT}(d6`= zJf{l7wrdY`*`=g`ydOhU6cKc=)92FKC}n}hD&=~0+{YnS)XKArs8~GsEPFAgM|F zW*e=C0ap?~kQOd?R3M1Ez4NFss0VD(pAx#*Z*Q0r&m);PBhD<}_C0ch{v#8jz%V~# zk2cyvF|FW0w{^Esv+Q|9jQh&RcDxo_#>3Y^kDQRz6nHAOaE;q4>OV`jPw+>rs3Mn) zTm_bU6YxBoJ;SM6!}8WKdSmJR*&fIMb$@F1PvTFQ0~0l^O?3yGxm#)ELwUlJ_wwj7 zi<1V1?YBL5G z<~&S7=?}bL#_IMDB)|xud=0BU`HkDXiM!?rMsE-(`zX37ZDK626kmwa(uRFmvWPc zC{^2y%DUQzDKkbH5BF}%sVh9qifJ!p7e;?F;4b5L%@zGVKeM$Pp~fc{T59%Gbokbq&sLy{upUP`y@p6(Exym3M)CjE&zi;a>!d|T`*1Og6gIfvv z$4KU=7DjtE#HwrtJYYHX)C#rnhpJ8$RJPV?FpV!K14QS2dBU?h{q&;C*KL{DKZe>W ziJub`%r-H`Bc4#-X-r{71-LKy-&DvA;BqziQV>_ z5Td|S;RfAq)+k*8g}HI|MyO%$%pMka1c&ZHs?|U(BU;Z7TjaE;v=@$=WFM}bd(JOe zYq+YTI90G031dR!dm#F)$FaQ9EOdjF{>$N_A5$sq50W54vZm8mb3+vgG^3nRsfEUs zh_8!c))T>^0@=?;$S)*#XNP=0cnl*kiEF>sXt8o^F~4fL2c%fuP_a1y1Wt+eiEGaw ztg}hW9s3QlZ6ftQ6T+LO)~l`A2D{k{0@YEfGix3$4HqU<*a-1zC3!gOa4g~Pn=lLg zz)_>bO)3%A*_Vn2gegMkx}+GP*3X4#MW))$-n>s^06R~FpgQtoWUJJEj`OLC|fT}w+H3dEdw3{{K2 zx(&4dPu(pnnLH?QkIIth9o_rsnA>E*Ohw{Za{ zpnK=!KdjF-I{Mjf=>`?%ZG^y!xW~e$7Hl##$}1jWNdX$?{@bmkRH|IEzU617dzqe_ zeN_9D+Dy46K=W|yXBt}s{=+*_SQ&jTr|uU~E=+}fSqL0tcV49GrzzyaPo1J$jB1n^gWh*QqC)Ot8hCcvg5Rtiy&KC3FfPJ43{CQ?A}=o)>#*5 z!79@~+~9l{dt-WQkIL3Qf(d>Teg&WHF-yJVv;K5Mi{3aDr^`YInU&Yy2_5%drU4em zP@tqMwS8T3_IA{8pd>$WQzJD^E;jKX?Zuyq$bQGH=lkRl)f?qOydPSUKgcv}vB*3% zX=Q=0-qz^!bffKW1qHNFTiO=Uu>RUQpzrTtRE^N8{|yR5!(#l5(F7JSB00G>im8QnfyE%;=rdxxAy}^{cP4Y{|&Z-_DDu>KiIo zS;9rEoy3NRN2fsQq!ruMB%Dx&z~Cp0tL3IB&8H}@?;7$eM=4V^t?cHv4GMnUGY0?)2xP^v6}R0bj!Tee@c(YAi=9o+_mQ zi>eCeH7n|$P@mXt`Sv1vQ2*FyjY#tS@qj=qfg;N-k1p)yyl@L&4wt^@_$FIum;&ghqMN+U~J{%Q^f_8~2oBD%oQ!46TqiI-6 z=9P?5Hj|G1xk#BM95N!DU&mKP3}J`2X){Gj5Yr{d z`3WYu&`4=p;<^+pq;QcES?ZPQ_eKq99>?Lj)Q4O5#J@AEsH<`hCK0{V9R_BBl)m-r ztmS(i&!}=c6Yik8m3@s|g9;`I2qL%p(LP3|VR-L{)Q6{x^0%~7V{j`LE7^m2d$swj z9~08xfN3}2;@U}Z$4~Xd2Tx{>l;~00^QbL+xpS)6Kl9~km{s205#y0OAb3Sg@CIAVtXE!(~_(}Nyw=q zmC{OUzNj9S+$9m~S!@Pn`pVnb8=AYzgyGFDbD*59QE@C~Wk+=gt^XbCWdgae_D;R8 zvP_Yys%)e*Qg18Vs;j6eTW>S{z%qKxZ|`D$<>pvRPiIu3x`Jmwk4%WRxl}w{_hIw5 z{Uz3@7EWWfrwI>L5i2|q0Z;Q#@;wQ71#nyZJja!=>#FhtG zUSN4iAE=Lh)^b_r*(wH9LM#SaMTdD<6gJy>{OTh^0U4GLq+6zBjElKPG8Rexh+9; zGh%tMsn6VMVJSeNBzJ%L!t$jx11wMY9T@DUzND(TlojeIlWlS*r< zsO_=`Kktq@Zwln!oM&zcesONKOzf7b`5zLA@oUNny(^nz1GQziE8w75Y{ zwzOxdzz%nG@QN!j93aLJLpK7$kv+Oj`v+}oF{!fp#mTp9Pj6`8+t3{DGd8A)9v_(4 z>4LM(#zf`WZ<^wG3o{|hE`Oxa>4I5X>Zhg<6kIg6*^zpxS2>W>dQ(&vkd1lsN{mMs z7U429$gDm1{TA!q!c^%31x{-(~F{`{R~F1tYCt>5OZ!)QC4&BiIiN*fj9&~Nn|3T+BE)Yy-i?HIkkNCpTmm6aRk?G@(GzO=>7!Er z&={~swdVyT%js?ZM6-|fu%WH|dZdHGB>AO~+BH58CCd%$2(_E%kI0_gW`zFDXP*}i zfBc#%HUVvXzr_XhFsf4GE(e`8~XPo~FRulfzns?rz=T)$?fneE`2 zOb@0z_Udd&!92p7AElTSx@;Of>6o%O-+u9DB+lnxM7IzSk#-Flf29p}ObHYIImNZo zCcH5 z*NP_{DrzJ=k2Bzwxx#pal~ygDkVuc8I)2RqkEJ3k&e0;M1LZ!r2j|~+M8$+L8_*T- z)Arz<+LzYZ$EWC^meR9re-UKm!&R13lnHC3G7qL{T8W~SQno04_-0W1lyEL9a|O|- z72orT=P;K4f~@>`fe?N=Pm1svbn`lb{Oqty4L}zz6k{*G(SJ~@~AHS?AD4V z$TD3_#MbVW6NsU|T0p`YNElCsxBG5r7>mgeu%ci!yy(A^aJhWzb>yrpt_v7dpCl8iiCg=Y(DSc&BuYLp0|N7f}$o5Of{_G=6( zx8+);q%%`$^?+nD$#s|p5PDADFUreeS=H&&`=?B@7ATwZIg&6CJFGvPe{cgZO~t}| z(hpV>BBuMAvU@-X9i^J zZihe>LhO*qwGWXqf7|-%EuKBX6cipdYiMgZa%%*sYzkRx}$YI{jF2w*LvYSGlHBF2pl^gC3rG~#z zljpjb=4X3@s%?n^d&jl|^z^`+zA=sYABUUo1}jCY3^>1 zrBcnwS6%m|!7%anI#$^2!?5+X)jH)7W0~Y_dv(=Dp1GLHDJ2TaUv&ogx6mj>JM=?P z%M~^B!R4(9E=8~lqI!d#SOK*f?7D=PQ`EnzekHOG_iMQ`>WC?-J&mE5y9fBL<+s`V zfqb+?&IQbY!H1TJ@c4|4&;S*)z|yj8tB#}AD6CgKWo3vTR0p%YI`r>1fB!ZG*c9({ z8tXC{EU7vCx3DcYEnSeFj1Yr%30Gng~}#-}B5! z$mxkXN*%tCGYzW|3OpW1rw417G3`rQUvmR-Qw5kd$}??=F$@rjcRJ`%bHOrq3N(n_z1c+k)+rFn{2OuYR}wxB z=u7fP*=n>ZsOWT$?VZ|gW42t3vP0YxRUsWKZ|o_Ju#RLOA4-awFAmq+>1Hb!_XvAT zD=1Orw>;uX+$qPxNNkHbH#_4wI35#8@ zEL3RoOa7SPRznk8moBlnT7*J$LT#Ah<;(5e+C?{^l{`}E>-znkyVIH)_nyYGrKl z64%mI2(%q$6p4f{%HAEv7zGNMlD(}`TYS9b* z%qDrElyJ$CD|3m5TT{kx@_Q&?mCVbrr16_s5+S8!Z8VC)7BziH$xYUQp>fw0uOa)D zpyZ{zwUcj7CrYz3QUG<%3jvW5W3a%cR|4K~?2b&_W0k#iv}#wQOv$>Iq)=DiQiriy0au zI(mwseCk~*Mo|L_h8i9hoAFyW*J^kw7p0NiYVN6fzi8xfG^}&h`?Vg&A0b1f@_qIu zHUr+uVtXZ)N0P`L+_ttOTj(8JlxyDADx*f1jy=0AG~lCug5=ML1Xfnt=Yr&ge=v~f z0NJ(QBwn%NC<}$ZPLkc~)iEx*K>5}3X*YUbjahODlgazt`58?h5wcpsCgHeM|A}-` zsl1dxkJf5Wh?l1qe$?1mbEmN98cr*MGhF}k)`Iu|W7}$Ir=JK^ZJ^KSY(H@$FJYl9 zA9C*8g6Z6`|R&n1e6H0e>2&7q0lr^ zkhwriJ8KHLMiVj$$GGRystIr2r2LVDvM4BgSrE%I`ktG(G-%sL?NjQVp#`&$A;~^= z`w`q+HsCXy1$I*KaW0WHJLP@lCSg#tQELndmcJ#?Y(y;d_)jh7G^#-ljq)zB+3hXp zD=Zi`vT3E2RJ#5&>`FU};$UXQAm>rI@LBvAqyq?Q`~?=ytIL||GtZEe;L3S*4|f5k zzWM*A7NNJ~c_><1qbx#ySy8g^?!Bm22N1Y(jiqq*RFjh9{TO;q5g#8-FH*{uFO4OJk(#hVGzvW=$mrUzIYY-)YL~6P%4pISV#mh z!C}5|9bhaA^gWbelDCFyK-jA_f1=!9oPy$Wzpb9_Ek@U0*Q{;R5BJJ>U`QllaiGzK zYvUN-^>;G=0YN)gj3ER{YQp{iY3pd9mJ2G|a=OBX+eYe3{+!fy^R#lHD-2!-*$}P~ z1Na29|K?VFa4pG!A0QmISb&3({b$Ea5guJ;mP^ikX%%eyQuly4ItSJ?mg=0l1>wP^ zwr?i#Hzbr@Z%kIuX`g8zkZd1I_xv?#Wh5HA!lxJX602LBVh!qaxR6V;U zo$<4y7acOnUv(3;p*Bk^vafEvL=Sujku&}=NDUqyBHvpH+gIXTED~GUSy3S2=2;Db zdiv~1#O9%Tw9eq;UiBl?Xq1jjY__CMq^cHt+q6wzRv>XP)tntRnJUI0i;%Sa>y1YP zKEU>13?%&;IX05##QMf}o!??o4kRY*Y&O4#Vlw%s|D8Tt5U4Ex^+#c5$RtPFwP_kr zV3Ip5QG}fq(uOE#mD7rjq&*hMH&z^D$)(wAZ!4SQ^{EIpgMZfx!kN-Aai4)CDB2>b z@=oRY$2q=!Ec_0(;Cf!*w8A-{wjpaB_TrDSsfvg$Bq@NQY|rhB))QmoN-e{ zc2}LyH$%H;M<5>W${D6$Cs*H!z-~YSY2)+SGhlQe{mh?^=ubOUQQO*TiP45KLDf~= z!QplPKw?b(Wg4F$FI2h6!WKvP2=y~r*z-_hGk-r!$j-gpy0mM-7b^OX>fIiGEX&8x zyy~!7i}l`1Y(i`*P@J;<^ zBDZhRBO)Yx4jza{Q}rNU|8qQvCQDxJUR(bAJ8YRbw=1>o=G0Ns=xpT74L@q4KBcB( zhi+bt@wj`#vAC=FfhRP+jhVSp2{9t}?@;C*>PPH+QTl9Jya(46qR(owaZuZ$w z-3=KNak9u!#VvGsCf3jMsNDn``95|swl zX4T@950WX*62wmuLMc}4`XZ*)3ata(*RMYh3CduRJa<&i^dq#eFKYVvp(nF8(%JjI zPwUMa2gkcD`1lZXa;Oi^BspeIVwx2cmF&-!=M*NEeAioc|J+$zk=*eY~A-} z7YXBOesw$O*rQ(rt7CsL^RnMwU0y_)OL!Ga((*AGxy84LH+WrO*)C@8tBDV6pHCeL zzdnZ|3YD1h<0Vo4$!u)gG@>+}kF3{{2J?#Vk&}nro1t}*L{r9hpN?u&&M4IQ8UO7= z>P5M+Ovz6wGb3Fu?w$VqMc@j0)dL1KZTe!U&j0VY6j`wQPRadK?~=P0{$iHiN~bij z@=>gJHI2;x|K=So1 zji1qC+E^Ux!W%Uz^!{1@(!)!>=-Y-YqvZ967~_o9zsFpgH1NwSXBFksdVdjAb}G&> zy!~eqBa_0`)_Sz380SoCMxjG4@kiz|rq z9N)66Ei4|UbjOA6a^1a~nwuL0owg~1gw^%+Mu!*`WsxxhZW?GwJ$drv=id41#@Req z!hj<SyXEfd|MGnjptJ>O@x@!8(utY&!>m>75!fPfXLuP(FYC{#!UI{`c=^5{Ek`D|U5l zVDi}oCqYdtI%0D2#T#GWp(6Z-ov$#Z3H7An&p8)XMF$JlJ<4W&S}yXVdJW}avO2ba zlgkkjUdHH>4`IT-wP*>t{@@pw z2Hn?Jmdj`d!7;MaZhZKr-wIFibV7(;6STW|`r^&Mb`qTN3MSN#%bSdy_{Hs`H{7RDY z|K8czY-Nku>n=3l9^@VLnkc~Q=4x?*d1tIc?F5%g}@$77_8((Xr6|%&VChGw6cK%*tB5 zm<4@Ua5=N1L!!{lix?ebVq-wFSM{v*Ji$ezwYBxD-4PLUng&pXG*n~xD{_@sK1otxU7P1K%Z2|Jt7+X~Iz z;Oo;E(HC`@`^Tg?hyliP>;(D8PoHE5^9^AR)%Lyrem(uIxw$7r=F%NTM%|L{>r@<7 zW1WWXV^398{~_*eGBPv2d;k871aU(Hr-DqB(l@bP**yfC0S1N+Ue-r&ri!g$>;6w9 zoQFpdXU!DK+kHG{54tiyGGTY>WEABxq7${(5okHYrhJvu0k*oK(Ad^PL2uqIlZA%@UCGcmBV0F z#Zu{r$66~Z*ysQS&!f@k=HMIt?f4f>AE<+9`9IvSD}Q8&zwbPw*wEMr_KT#Xq}RLa zvk#D4HqeBrU$@D=4<@0G57eBQ`S~;8PniY#@pCXYjgOHH-=uly$r zR`wY@umfnIRvq~_>jI`4Fa|KKR)LlGn0p(VG5h6bGqC+33cHHzQLWZ)BqHuJZ2 zb&?Vi65s~HeEj$i|Jjp2i_KN&e0H9bjCzxklYLuPsi~=d*$Cj$mFj$m-@kuX4fN?s zluU#OST3Ks2xI&6=T9|QdlrX^{h=FuYHBLQZhmdudC)a8GxKw0r5?%;JOvRjjq2*^ zqxO5}pq1Gde9Xrjz)$B4p6<2g8_Qt{)i{3cS75s(8I7LZyEX@l6?}#!5ZLvtU6$v9 zrG4Q}X@kjAy5H9w6=p1!2%_~%ZJvX}p&EKfnOIno`>iUVvHp{g;~i*}KB?Mbe?R)~ zs^$JQf@N=dq078_a!SgvxnUe9INvoXpS4Hvu->`z23k~)hqXRYSHIE)?#>+1`kzTs zo?uwG&S&ut83O}@Vw}+GC#K;5iPI~E2|w0fBNaxW#k}qPWyWhl4xfj)zeP_M2~K?x z@Dj{f+{7&!9v<(Up|tNJat+;BP&H_=8zka#W!l*Fh?hN$tMSxoY)6(ShE{67)ovRl zISpzRl>fVO{tmc(rDX7V9l0lL+rN0sJ?~TGlA4s?`R9}00uD9{(0FKVe+h7)`03v3 z*03?w-o^2n8~%-7;WqRp-av>!r)l5dSf#5qwfF$6d~li`Hol`Vk_C)0X$dif4se(G zo>LBWm}E9cjNb_I-`m>MF>3aOPk#h#_wkW{2|qc?`pb1?d~8ab{QR}ghqs>n{QT(U%a`}eJ8y!2y#*|3-+%lN zGu!{2<$bZreT94&T?=>%DY}2~@xj&XtwY(d*9O?b1Dch8$bcjA(gZ&>w-J54kNocA zeymknrA6>ZJfFlZtF>aby@{458&&UrE+-h%WEc5-!&b$1PGuws-2ygu-q-l{EfM$a zIaUCxGYlcvCs-ld4KMM-!^0LX3qu5g1bk$Ad6AbS4?f0=y05`YBZ{p0IY_TW824UR z0{>-TJN^y}iyz6bN8n!O(&if0WA4>^`H~54+iYnVM;boq?_Ee4GW4kM3g_8Lr;2N0 z9``iT6<2G+Awzfy9=iwr-itSd>H&XtW@7DipqUMNwr@^&uU`On#MbgS%gUXu-w9y@ zi*8jiPLnU=GLKq2=d&#A58)Qh)k8}(QZcz>e=|TaUL=Bav(TR(0!xy#a!KZqe7@ci z$GDPiiwzGVoc}&*&xQ1CxvT#^hUY8)=+QA~?Nmdztm%(uQWenPj+VI0Zba1fC4i@S2CM;;!5Rb;_l8a1|TwiyfLTZ64cStY>9<^U*HB*uUM~CbgC+G1YMy zk+!5}zi?BWM~p2yBC34erFBgx*8BPF8AlaPm$bHGwkY}P>w z9u7ixLR3`7)hzNpy{C{_)4)mv?uuA2hd2V>fW=4I%8CO_a?>9;^Z)KJ9Dp~K>Hd9n z)K~(zgx~x5k&_|-Y?Y1RW3JyEH12}u-vve?IVGhua5fm8J++)?eeUXARqb>SR(6uj z6-+4&U=)cK^Slp9#12e6q_=cL%igCA=Huh@C;?RUtR@FMeFkf0fdFsy=*>_`)Djo- z#N>!)SS#yW+aJQa432HfXAN*BjeE}C!n~Pf^@;@RA}JsAq$xy;xMmMazzTBZS1T~8 z@c<~bfLBXU%7Q6EbN@}%+$Qwn{UG_dN=f~tulA{GB6&-;g-hrNtrCg<)G_BNV}$Qq zmC+Da)~B2~Wf67UOeXIog{hV||R{)d3I9-XJ_{?`93TeVE?iCFo`yCiZjg?*^@o%oVB{j;hFlk4pF@x)B7 zVU<}YEk1 z9*k$UaPf-axTLYwOYSYj7(mNM8{b+(kyBACjY^C;xO)+O#MOL}AWz8M#(RV5RWVi|c%|+r0bU3qu{Xy^ivBxy?vyWA63Di<%1A2{ta{W@?eF@nOh-y> zpGZqz0rCj%0B{tECmjpU)0-Dht4QoJ6`OZSm^FP506OWoQnOv;xo%dEYS04fgx7~* zXnpJe#pby;pHVnuqjUGFT^-Sll(Zq)lHH5#SR5(Cz`I4rNJJ4!NdZ0a@V*v4iXapt(k|r#(xP7c(;b~ z%6Lr$tovV8?mT2UT6vSDBX(f(eo})OvM~d;M3=FJJ9Ga0lbn8Re0*>+8!%}jpIy^| zJbf9Hl&Zsa7;6?#uq1!F!RO9ssT$_;p1osz`w#aMr3i%y zi|c1s^?PW8PBL$Q6BHu{jr*uo{H*+PmfiCQqWZ$EB8(pNE4-~M8v{TNwJIsXUc zcje=!$Id7&GXK(aN?`}8=QZS%SdmwmucK58dx@L4^xHQw@&dkg~%nSfp33i`C^}=i9e3_ zVMA_U!NPuhoAW&cPcVDCz0x4-O7U|3i=3xa?I!N`SQoYYJ|QzaHu6 zTr(?5DU-`|`%=dqBL z@ppTh6-fBvqK#I*K~~5niTk$Dqf?FRe8MCD8(aSYj%EMH591dyQX)htq|AiuJ(BFL zY!YQ=Z!#k*d#{j{?2K$uva*?K1 z=Chvx$M;S}7l`^>V6DA;`7#ys>X0K528k4Sp5W8UIUPN|qZzvQDn-HHRzCNscmB{7 zF4ZXIayN2~_K)|?Mr`j)mSZJm;-bt3Uj7c3z!!vVCGNhy@s|fGWA0|me&qEnPM`d= z17FzPyG;7xsku^!gxA*0x!War>KB6K?|A?CFj8OCyO)fKH>68uYPKP#Xd99wSiy5& zrrTlpecnb%Q&U<;hrFk!$JCtKl8Nri(w+;S!|EbAR%&W0Dz^QpzWyi8?&D_z0|VC3 z_=<{(`uqEDUNiVM*4ow8+|?C2JUndR9%c-!MrGy5EH5~wps1#1W)AU0Il2WCF)%Xz z&@T>4N_s2XL0+rd1r8{rE8?~KJ%Kl&rl!{8O04|>tHlR# zgG5$O*k7O+5D^o*L`7w8DQL}ehnSd{fQ)R^kg|G0UPKXnkhvq*)3q4>GS_?N~iI&~}+(Rny6j zIv=p{j&SKtvvqW+-M@Ld?iLvML5@T9&b_VPfLBZ&UU4sDuMq*fEbRQQhyvsC`l#Ak{c$jzWSuEr z-E?;Lu!G!VuFOQWaF=)0TuGlQhX1wQaT#YLf?|S~vQAuaVO?z3(NZqI?I=8Gubt1~Ez4}fQlGF$Wl-~DMqp>f!<+aMo@Rb|2W5Y4yeutr^0kSAcFX;()k{&B zmo6o3`f$JdE&{D+ZQ^sol7De?B2G>`(3DV^(-GdfHDbYZuVmzHqqUQnnKs?5-ER}K zwGPVC^OH52A27q^4{v$%U+=fM_d@F`)|2Y<+Q+cgUG%v=hxxaDuQ!ecwr7&moRxV; zRH+o(vU^?D=_dQYap%FWNp%Uu1&T|wS;&Gj_=WAQ==~fPrk{p6jlx;?QCX>v$l9eh zgQQa{3$RwgZMqU?g`_$)b==3rly#&i2Jg@N98fHio2rPsp}P~j*MDP!?rz$Zm?WK> z{63$X$}otky4BqY6h+Y5&vY(12%Ocs{kO>lP$T6{4e@X>BLJbzAGuRRbNh(6O$EsL z?9&UJg#W!@PJdlHy3YMK4NbYAx_WQkJdlj-eT4msuz!Q>iyvsamlxx>E~59hs}3?^KQ7pdR|uwApzHd~E+k;iONy_$_Z& zG*Bl7e1wCxVPyXyHq8zoR9)_2rxEVJOX3c3BA4cwQOy5$JN~2Y}z^CXh>B#zZx8@CTm8l*k=lEziu z`am8#Aw?mcUn8)6Z^!Ah=830kA|)A~=4opR4pQ~|r@t~AqioM{qoeiVxi9+UNp0fK z4G|%1Yau?R-oLTE#`eu}_t4B~!%-Y$=GC)3%Xr48p()+G1Js0`;<+H+X&Cw!$&A+ zdy!=pn)AWfr0d|~ybpicnr(LV>vWNcWu}4d1lsHHgoHK_A4q_I{PMMHhVX5Z6J56! zez5=Vf`4v22Gp#E69AE;gAM!!C<`jVFk6hc)jI`BMr5I-f&E}Itz;6409cY_n(O%krah)* zQPI&#T3RxYIdF6aL12eRM}$N~>AFbX7-FlpfB1*OvE2I zM0Vd6Sf*3y+gLX=l$5@M*IiOxUOaceWqeAjeWClPgkQJ1!w^cWOWA!=+S+#vcY5yC zF`e$Y2s%_JpPak}5bZK9F8a9EFyO6A5X%6|_OiXGe`Gp6E@0zXz*LMfMNBlBn2V+N zr5s@9t;lTi?w+0(4GsOdP4Q%PQ`q3DmB$(yRLjlN=4RHKw=YY|QW*}vwt0|*6u6yN zn$LXberlLPoiYw(?(zzN`!65eJOm^wznn?E$P@AnP)OPG_0{Fu+!n9;KP#cA>FC(O zD_(Zq=zHZdK7KX;kv_h@TM+K|nbq=z+ujYVcV2*KBtWnS0Xeyxv^4JN@xcPLH`!2^ zzz-AMzTFPS;r_V+FwsA{c@+Rhv?7SZyNZQD`r<8Xx_IzC28IB*SLN=xL`MKj`3D8v z=jDwD$FRP>em~ROKk_vKn++H~@82UhER5R4zHG2bo2wi@)GWn$_q}25+f*kwV*>&M zKLJ(&n`2mbxEIhLdXE&9mC+j@-{?2ssVKlQe(F6!-g@uUqGn4R?)K7P{%t@q1^&%N z-n@!cP_r$)C#Y2o9(LB7R|U3P?we`>bppLT{39UCC?~)p;TF)r)j^&HQtm@OR;n(N zWd@%HYNxwGLLZ@1L%=<_TS!eG;O~EzlQTLl?q=QTzSbTe)z5g9n!hSv*gOD>FC1Pm zYdJUN4JZBZX(h^)71LL#=IB1BMaeVes57dq^a5%ijjT906|4Rwsybc(Jv@$5_oR~8 zkxT9E>l+w?TGW_>3@YvPayI}swe1IRazLty~%0GHr$5hw*fRrpAU3&Q6Ct*>SPoSX+#^PsLD(CXX6#Rk~$JHO%Y z<`QUMpo|oSc>oRP0<<0g{68`u<#0dze)?_<>1SZRvyufPxYO&omT)kH2lb>&lmLwo zdR+VOZ{jmm)osYfK&nA64D2{gGZOLia3mi17c@c@LTmDg%X%{{;rs%14 zr35nT6m5VW9FB$Zem$Toqx38p`32a6mEPI{P@tRsX#K>mY~c@4dFS3oy`p8c#d$ux z9aG)Uo{P(U*Olh>_%Xd9NK|2uZNpo%ZhOsKN6uC!SYq`j@q>dm>F}yK<0Zj>h4e3Y z&4#w>zL5DB60E+>#&9;(9Ayr`#Y?qWre&EcBL|bBt9x|ZwAr=sacQyF{dWoB+j;v9Mr<@t%>L z%?=5iuwnxd3U&DoJTz8V$3s_2HS-e)SQ9&LUX}PpasnX}FgGuILSl+1VBe9EkxxWL zy+@l93kzA0ng9L!ci50NA>kteo+VWEfvUMkFN{F&5O=sCBS;@83PAWfZ2bLei$7|mPj(z?7 zkbFOQxDaOcx;H~=b)uTIWaKwwdPu-R3Rw7Dj|AmBL=Y$!nyrDYAM+1*_Vpk?)6+Ft zd4)Rs8)HF*_vWS*EcS;Gss`BWT}t;uDingzqXb>|U+paqKpnyUs)YdN38Xq84KVSI z8?46NclX@!1vXI-2KU3TWDDLVjUE?T>W7e-ai57PnCi*<(qm^FYoVO+O5cW`#8=PO z*Qz9J*t*HC0w&exbcph+JE!bDh^^2Ew>)fHA$zf@2{zK^la7(aiwysv?g6jhZ3o4gx z<2NzVHj^(TmxB+|cX+FG_MEO+XiJ$ZT?;>z(917KJ;}zS*5$iCwYf+X(h3#lQdYE& z1Er+MTcZb#9tx-5MfpNgmaRR4RsA|&p@&$M30_b6WA)bi2b!WbGoYqE9DL(VZraGDxbl6w#qRIbOBrSIfq)2=ZQ8e=yN1GIi?%+X zkzd9vGQmbV+0>$tv3Fc5-@wVqnd2e+5f~I?EfzZbg8`kYq=CWx+2&9HGk}R}K%$^P zIq?$mP{tt-qz1NMC~oKD7WjLNW+v2drggpg8oBSm(u~KPjRCEGN)bJ0!PZg2%iSv( zuYL@HY(zADpa<|~JF>H)vLdt;p+c>TK0Fy|F%6%@sD#c=U=qjY7go5eqoEGKTh}hl1I6D zIUu9`=hy(NvAj)FBy#tDj>xJ~2iUejG8Swjc(4tBpb#YUgru7&ND|rsgqQN$VE0Iz z>>-U*9*lAHb!wR)2v`a2?pFNhapruqzZN8(P9-dyLg{g$w6+7-E(Wp#m#x`t?(C?1 z!-CkwYCv3TAOJ1fo*ODnUteEXk8;dwT@MT!JkcP{FPGEyVcNIsv0XhfYgjAus^=O{4y-O({IbS5c{MeS->zFr(xV44x7Lgli zEB21pqsD(!UqMYS8Rz%lkm2djPRb9p9(3Dp3+~44JL)sPsovK#<4ea6oN2UAdhScd zpGCr)cq4gfPNDUUjIB8*p5OT1E(f3Bv>VG$O&zb=VhR+nC3P=*?CNYDxKOeKNUZtp zdj8fT%m4PK=Mj>G3sF${0rLjcs3V}dajXWC3JTePhzs88&}t9gLNc+w=_dz4^pKZo z?!55%KYU>IX5o{)f=IRg{(giA0W78kvSt*CeIan!3K&qNSg1RkxdLUopu7~n4#nHe z$0(>Cen4Oul;j`_NFS3%0WZANpF;#R&AzcELsc?tZ<3NYNP;z)*@)=@#1CwzoS*nD z^<_tfPfud0yx2H9HvVQ>bR946#n$b4G#Z52%eL7`ptAhtEIfZp%CVFfin#gFJF`uin~8Mu;#e`i|n!l?Z}dmFLj|bj_@cd zt1hQjb~dIl6_hA$?(y^F1*3pmNk79Qczfi-hvzWGd&{-c{W`5hiYW)B)dwCO>@7u36uT-1NWGYJgBErfc?mY)Z7ct`!8 z4f8D!7;MxXGeaIYl6!@^``|$!RFmOQ%b^!JZRrC_u3qEB3Ih;rd@mD8DcVkWV37|4N=SS2~(*!QQb==il(&m_aD+WR~(@r z!wZ%VWqlO)S2gCz!C;)5~Kg|B_F8J@wJ!4IQli;bkYzcC;_-#EHn8T?P{g zk?x*H%_K^N!T%l{)**C64-w)wp^MT7?r?HinE0s@f-Um!sOQtz6@XC%ScjJ!WC5X} z!dd&*E6hkBJ#ltnLE_DuJkSL>10MnFO}gX8r0Lc+B>x6_fCOONrk%-@Etd(>DxrZh zC>a?pH6emWvE$De*a(kVk+>=SQ58?!|B;4et8Pdq@%}%wVV$+)yRs_8q@A$-8g}uC z%?q2S7N6V=h}8)KCD-Io*ZphjW;*+ZcE8f?`$LqiIJhbb`8&&BKDC}U{w%R!CZ4`? z;Q}S(X8YfNy%1|oDa(j zA6U4`2G3)+p3j&gf~q@mdy8%%!iKSZUV~c-wrFY^)g0DU}swWxAukq7Tb-pAEe!ppTVBKMq2oL}O_tO)rX+ZqhEzg~$N#zcd zS68((H~T@)yz#eh9a6DoWz^$1|(u1;YHe8-2$@&^+6zZ;hH zK!IrxA^GR*H*{PziM|AMkJEc7BE?MQ;5TlxPd&z=ApGi1+N}FicjiQwYJw-BMp5oh zVZ+e#gn7?Gm3+LE5LAjH+Jt3Kk9&?2wt_59%hFC+%hZOCpG8Wd$kw(N2t?8c(%6$- z1O+azrjn5yk0ELwo;B4%-HCP8{MZ-n@viHY&DH-L0r>9lHVk8FRSU`iWWS?bNa zf`COj&q;Ocu8)1Ql*k?Et#x&jrR8mv^q)e|`{ox+L55LYfG2-5K-rTHpHS)jKB#L0;pkxX7po_6SB@Az{g`L5DOk~?LOqA5=;L@bKONY8hj$JsPh?&Q!(pvaOb-i=Tux5j>5TTx63QB`{| z=U(Ll7k25VW0uW<>NWFIlA*4$;D?pf3@3jD6^Tzi@hex&-wt_YR8eTh+xl;Fs^X3V z6xKaf6>;9t=jQesFT`{E3_|>yZg!(3w_<}@;IF?rki=N$A`f}_i{}i#oQA$S7lWw| zRSfK=(%ktO1;)Z?Tgf?0;}YN1Ha@#0KDbtV9@%sg5C38}$DkwDqJ(9(|KAb9`#2AnFmO?`e%84(O464r&QvYvX(67(;b0UGxZpqHP)c z-EdCB;y8xP`khdrv{ zHuZ-=J!&8^;bQL$iX$ZE&mYISV$gnE%H9Psyo>7-md>YN_Ovf%SSoQnq5E`TamLk> zyODJ*?apX|{9J<)Y+zSC+ox0Y7Yt8kLq3Y+uqQ~?EtBk(A>;2SWirS|VbJf$?*3sV z&OZyw`<8P5u26i~`Y9`>pQ|JP`wnGa1!JEoxxD;KVd5UUTG+`w86SUU4cxXG&6|6B zNEX<4xdM7cMeU?k%Hy@=OSDCI<#{Vj9Yq|(BMrpWjnfDBc zP|VfjwV@ho7qtjg2+e=Ygn+>+fh^pxBJO@AtVf&5t273iuSD@=Fdu26gEyGJ29U(i91>$68OXo#NY+iv*OXd6?+ z?9p{-rO;mp9m>5>9ISNeqbw zZBr$FkG#pOEGM%Hl~O{Q4>W?P{^Y>q#2(|)#ScR2xotUuVPi)&@c5r-sT!0#b1A)8 zrB0Mu121SAfyhTkWP!a?+4l_CVWs-Jc~i7%4;wV{2u-6xda(L`QL zRhC?|-?hA1m@gbg1l!aJDNu2qhp#xunD&pzWFNm=JwLQ3!>3dvdJHQB-6Mu*d4s}( zDwQ#GeuvDH?2X}_zbeou%!mhPKgqW6v*VmLmgH8MfV&cEoiI8>o@IHv8F4hB9iJxIE zvlu-2!645l#Y!i;BDpA*?V7w9QKuoJ>-o+-ml8^p)U3t+;%$%z zlx=d6;RTos&A{&erywQDX{jeeHrDLy%h|+OT7GWM=*~NdMDgtO=2E|bAN=%rY8+;HZc?3 zSeaUu<_4;5sIHz3b5kL^K%i#4bS^vHjPOWmceR3_d$m6KdBLYPB^s> z0lL*tD1-XH0>_fWCp}?r2kdt14By1y-ebA>biBoSGP(1?UMA*YlO6ThOm6Lyni;7_b)EgLX96=43BJWBI9Dq z)XQ)zL1w?t;SEqZ`4D(K8eGP8+@?1og%$=X=!>c0!^4bx+Mkr3eTJEQMs&!_GPWLE z``S|~Gj_-lupvLAW?YcJZ$W4zBIi!>Jbny- zkx0iywc??nh~p)Fpcbzr_cZgreNW#{-tq&wos*{7+IPrR5!5qYyt8wbrShHFJ%!f? zw-x>vn{HmiU|PE0e{Mc)!^c}=9xRbauz+5_`16I8w9fIap@%***>NIGxGC;e290w} z%~~|L0~d=Mj`iSw*J{MJEz{D%@^U|@P${`2@;)!WHRqVXkyBP^NUt#mOix$tpcmg? ze|uT-EX@hKQ<>S7Jvv@kFJIsT>s|jM-FH2Srvpwu((Z+|vy?i!jI3$nFXmin?BHyxIM@c4G^+gho|cAJC~m zV|RE-LQyN~iPHwv;rnLftJCl34Q|qj96c=AZpErBP*HqWMLgO{4o02 z>(kHsFk!q^7yg;|g|Cvs?Q8l&Dk)YU)W47i{IQ7{I;JV^zCP|%TG(Wa@xCTY<*HNTjj06ZftDpw?m4E%5X_-(24NH4g4u+uOxwXf+0|p@<(yazO0&Y9gaLJ%SgXT|>AP$o!XSmXL@o{>w#)DR8 z52_sQ$*J`RpMHHMe8BE;7bF9B)OQ%ZGr0A{zvU@fzoJY#;niu}sJEZJBzX(!Ur-qS zo;@NGR4^Dp+pgD^Uws;z-m}CoQiSf8AJDyy(Y?5P^Y>Xrl05A9)KJ!RKM1$8nw2J# zzJdb<6o|xDT{m7=>39eOEE4R8uUKb*@m=TmIzfsobn(Ncp<$1X5>)S-CGxUe^Mvw5 z_qqaK`UYzN6EaWyr@Y@{-|NJc&yK9B;@dEME+T^BOTHG=Nbw zxgp1I)Kpa70dg*Ga9qzMtObqk8?M_xSWZ&)yaxmkcJ%K({UUpH$Xp29HWEa06a zq}lT8Q`eP-mFbehswNMIb-*b# z!CSFq24&q-C2fSpc$#K6D-Aa-07?s#+;czPuPn21KNYloU$=($OnYL4BkX+3tz594L_7WmqFIWrOx*ps@e;^o zpm`_{xP=W&>S!?UQ^V?5kh%Wx=m$#YNg*54NOvceb71P1Txo@Z&&&}f~R=JI-% zjEJ8F&c9-E4as}m1@#GKV&<~(LS&E44;9I`9~YgytM{7vseFEOr$F&oJ^Y1nD|Btn z-p^p<3nKsrFE@n~TK0nin>Fq2m`jh+>vQ{V$$?yT+3aF0*~aHd5*kG#9Jy|-i!=AP z5eL3E6IIc`rKW7ncAe>G8QJ84m@o^hDPUUy!_O=LEya#Ig@^97j<(*uzmN?|NC|);h<%UM)z{|Udg4{>0q+ifY5uE=6m6@OTAR&F_gmNAwE$rPzq0V;!ZRYc z&2L5TA<5gbyG4#`5yz zOM&x~9n_ogig2ZLaWs&ntrnYqDT79x)$sRC5WL)aq=y0@l-=5BG~DH~F3{_Vfc8Sr zWfz&1Ac-!k`q4V^;}zQ$C^ZO(h<<=20?b7Qz*5r(+KhuGrz#r$3r|Xt1#yX#tSmyl zEeoFifB1sb&D`DHK?#2e@k#*({2g8je&E8~v^o;`=~Mci9g?RGlDnI5RiK^R-Iz+L zsS#*6y#s>)fo@}Buqqa+w7yxGP67XikjtFK+#qNW52ff}`Zg{KIux+?h)GD4fKH!N z2u^K+>~&y>kk1d4W&-e92cDjwM+^oh6TqQM1G%KYT`ezXzToo!-2Z2Db7Vq-G<*_J zh|Gf$LV0%KelW4j(UZR8IH{X%c%a;%I<994FI(kpbiw~lM~&_ocZH?dq$Hwp_ZHif z3s!RIh>p(@wcQ<8K|DYFqJ@s^k&;8HFSZV!4o>$NovxW{baeXKw!GM)On7ju#CH0Q z1B=7?ZOaX3X#TwW2E{;4hk%D)4mR$YZW^PO0}n2~srHNqRXr8g3_ol9Mc{*YI^rD# zCB5w6Hff9d0nNQ5T}csbqk~j;j2ryl6r-2qUtK70PO^xtbrazj26TFW6}PV?Kj(Tg zoQi4#aI4@gkf#(LU;@1HREfBHq5#$Aaen*)zMcnCRTbonuqk0l`g}Fim{7uh5sI(0vDg)NL$B0knMs{Bg@X?H(5pW0s2RC=_P?-aqpTtn> zvZo9x7gBUlz`vK5_o7}GInCq9Js;$P^FSmk!fV5L$p@*$JRBvW1V=YUF=>_417x*avp)7s z0WAv7W`Ns}`RS7=43Jnh(Apw@tgF-QS+Z+0gTou(G$sbFL^%+IC?Z~fOgPlhx>CCh zL=43Fs<}0AZb0BC`iq;4ybE|PR6!;h1;FELu)0XY8K0l%1AE8E^Wa=e2`NcQML4{N z819__oS7jFU@rXYSA*tjPtzgErtatqSVp2iMD`ly92~W#1hlvN)=AUPpY*VQsKO)A zFByqSw5-zz`0xRFA~xlk)eiaS^xN~Nt4gkS75kCdw^|F+!UY9va zCi!KENATndoE^?K=lRD8dk7`-yPm}iS$r#jtqx9NX#&C)4G{vJr_>%_3;iNZ$#a$* z6EDT`WWdJ43|*vunY5JB}Be@Q$6e5%G?l&Rrl~_zlPDH6yN#F5&av z;AZ7<+DzrJod^BPYp`{K4U!E`D=pPzLUnd_=C5Dk20aA`pmA_;P^rMIB8OVReu6`ZT3la5kbrF4z+Lf;OI&DDdeY7LZz9JcAR-kga9H6q6T^ig@Fc%1RzC!# zMTYic%i28>`0JN&OcSDjDq`wDj?&xO-u@~mg?*J$C<#tv!SV!N%?6Iov0m9WEEi^F9+ytUoK zT97bn*EogmEOfyUcLCMa{6Gn%f!DH9TlO!pg&kYe=-=}~&ahm*k14;EWSX%)BuO^3 z1cWrHDe)Id2-p@fCTz#;`s8{yy4@-9Km%oX-~=B$M-4Keft%yn%Yoy>7D;L={fz&L>u=Kg?_4q?d<790$v z)dpl06%|&9v;pc=tJPsva1l4d;fQb~X>ohn+{OkAW_ZJXlAc!Mu-zLiLNc;8MB)aj za5!n@s)>n75|1@{(Y&0gl#U$2<2RiC`o-$-^K<85<-L=OgKIkeu{!gXz?zB4+q_spx%PRR zx}#-A`6Qn2P|qXMF}NHYDAQko;pCdch_@?*S+RrnST;o{84>%#xh=?09Vs(g;!WFf z9H(UM97CJI0g+^Vl2ez20o=Z(E1=Y{v-is!WS>J zLT>!OKQs7tVLb(1(}Zjs=#U60DML$2*xinX9lAj9QJiT16;6s|pmLOXoSFq(qDHL? zCs<*?p(p;p0|a%MC<*Y8{{y*NPGMmzx+Gr7%Txn54oPY0uUCrh@H@!jM)7_$OA&G# zu5;r@xO$zUMR-`hy1ELb+H+Un!@n6T4@PnXfHyUTu?(7Bv0MiJnGW0>cX(~YaBD!AiyrJn-#j~ZyB_w1GdRnW z9mDjl7c_HJ@3i1sHm<^ zzc4k zP@oM4{SO>+_ZKE5WM?=Qag$a55-Tff4J?Ur)z}SVV~H@)QfOpi{>;z&W@pnu;fiP-VIhH~5}q0k z+#N#@m{n9)6OoXJ+u7M=9~mQBCD=OZa`{)L5MfP?O_ayG9E)fLW*N5p)KKX%Rd^ z84HW6hbA0k$PxhKVRLg6;zk}J;vaC)!9ik12PglHM)-gI4K_2Q!5EyOWaJq`=fG+) zUO}=mG>!wBEkv<>d@RGRe+T65N~)^jR#rtE?3rGWY60R}Cue6VF9HdW{{z82y|Oa4 zY#S#_3pVD>tu2#cIafFOXz3W17oFgIYiVx>g}eHwN#0|#g@ov6-zI%3YU+%EA*(Vl z(}c&y`YGo`#pH2j4y{<**hKuQE-j6Me2;4Ke!lisY`{*!(=jQ3)?r!}k&>bSLl6YB zOr332Nn0iA55YUm@=Q&Qh=O9$lsWrFkdMzLFmmDBJ*~ zkG-&1uIDn><3kX-%D!@|%o|l2fHg9}k3s8>ME| z-JW)yE~uc3%Qo!QAD-)&n_SOqZSKaq={uVKZweN8pW8i^g|SNUDFNr3^yuR9R(T{A zkIs`7lDw_(pdl`+?r(vmXrSgX?B?*Ccu2-TC6NYne@K%&r``V{2NL0LPm0lgJ1N3a(KcA0Gahoi$J!)R4|3OqO3zzdHOY3%V+J z9cH7GIUDEdQ(W(E>&aT|7m@iZI_RQ`5Nu3Oz_)>XDEefb%QdgJpX1*{I}G&~9i!O3%Zd%>R3%jUl?V#QnP<_`X53 z*H>FQw9iAaGd;B|uZqo6=S$~;73(|?TP1pm`;VUG6ST2adbcA6?P_sFmm?gu%m`)-@##5>_Jbjk zc3#P^0ptK%4H)=5Bv-ueYLo8X%4SdyemDBV zZiINs*yx(J#M8)kM`Rv8p zx0FrIMAlc90wSwP7tVGV%3jl;=#%uj zn={IfO2D{K4T@hSU$MT71E=p@zv_HTWNZjKb@dIQ##DaOrVK5a0=W%cnL(tXEN66* za1l}FulO&G0=W2Yp)w*kyw!D$`fT@9=#_Y@KPj3q@Wprzy!pysm%lRkSMWYYbO|He zqPEU6+2k|PNZm96M&G=Rx(3MIGA(4zu+)4!@b3=l!vGfUwY988b#&&(X>lv2Qd2dA zd_~WOTRSjfJqeoiFQ&}2-3ht>U7Vr*Xy#+WOOFp<*y6AGN;py1uO5dmV@SL#)BMc9 zi|?t{g@!8EU?Gv|`|(Kixn4oxlOanU>HI6qXcHMIY!Q1YG!W9y-s&Mmm1WB(u+I?^ zc*Cc-F_QC)bY7+z6=jsEUyw`ns`n~Npz+AcWq#^2bK8%RuJTs{bT;%lSQA%0i@zqd zom{PP#g92Mmig1s!*lF_nR<^u_>1?Oeu_!@Bn~mz;O`?{szy15=^XQPCl+K^N(JQ? z@YfnGhk5KyC5A&dfk)C@i=Qq)9)4KnA$(WV!AZc7+iEYvF;V&25eM?7y(vFqM zLBacxt(j({%6gk8X&aZxZ2fi<@>Q?+O6(I_J6_dG3?(5H#E6#-F*iT>Cb{wr&2FW*Cs6N*wEb!Yt)6%5Jv_-wb#q6x}>W?Ck@}ky=ymX99$NBe&Z^_zq zF7Vgfu}v9SNsmKb+dy#dT>9MF#3eS~zg1*WWMf}Br5IYH0lt^zlG2 zptw!sX{QF;w_n#?j%CNI#CdiN6w<7JX{#Bi8GgyHtMZB`iK3;17Fs^kHASSr=F`Kq z4C0%nq1u_WR(2c~6J#$E^U}j(Z_ADi)vm!6;+B!v>g4YZYir#nEJN8hVHc52FbvA@Ze3~-!T;kT5xl#H7Euj*f-4=P%FWCdM@lCl6wgdH#IhMr}yUv**uYGuJvXSxT5_8Leu*v*Fb~ zFldY8-Tig@_p^xE$seX%voPi@8YE3wMs221NjjwMzI}d5l@-%{3$&$GsAcB)Hj^M% zNreX#lWrA{ysf>Ey6)xixv9tk)Gdpr1DP6HTCTbn^5$QhWM{ z>x)Npzl4TwcWo>d=@US(CGkKQ@|YmwgBHSPcI}S2tJw{IH|RYI3k%aznc4mQE>gGyf>y$`F%}sS(Rg-x?7UjsjH-Yv5dgV> zd-#<$KVJ^8}sUWxjln|4q%f;Iy{Ief(9+b zue_xgzi7Tnv+gY~l%)H?nA6~OrQ5I>MKlUOjF1)8^ zws=0w$W!ThU0_Y*XK#*~|vEbaZx7zVprJb?{~mUKo#SeDJbUV<=Sp}uJ zQAYwN91|N669X7!Id>U&Mj?IRY&TnY3yM>jHLV>a!39i@NTdiP<*W+z4-F22=voVp z8jqZ>RK<(B`D|xrM+5FY5+XA>If(!&VsD?sS{p2-ZbtRSYJ(&yayQ`Ve3f4<7;G?Q9kXFH(IL-86(w}Q zqYUGu%s$TwOyaO{qiUcGi@4re#^nr%Gt7X1?AO^2} z;kV(=Yqy(Ri5>LBxW5hAp$~U*a*|{hCtJRKW>%)TG+M?8SyZL`DIrMk7694&(7T5U zpH&QqL_nHbYN{s;25lX4O5BGeL2I||a-Z`}VN<^OmpBEOHn5?9Hj50-J$dqD%ce33 zUdd{@5fk*;iaD!O#IDZH&~EWme~l@%cOwImO$G2WE2~HH^5xunc(W$O>P6}gd+jfc zMf?Pt7Ib!sxwpRsm22jMh?^J}6WVAn)WRqVhqEvWufJjUAjW+fG%wdx{PJO94CjXu z(X_=)K~)_cIeGbOuxvmpJ2t>MKP=I=W41PF20BgP2pT#%f>Tp}WfXdEYSBivYvCn% zGA;DXFUt~KzN;r`#CfeE0@S6wWg!3tzN8;3CmZcHwCgTf;Ki{)GkUh|1Tsf z-iA?(SY|vuQR|fp6p+ObbV|u*hZ8M5@Ww<}3ncWz^&Z0Y#}gZf$q`tl4nsFMBz_x^ zwVByj#Eh`Hy{!)+e}FsC$|Z<(U8=ix5u8TSobS{9AvzY8(9fUg!N zC*>R-$4((qf89dR<{}FGoHyXW`26evSlcd14PaXfpky75DiO@ zw7p!}Kr@V5Nn_*Bc7p45#}?H!QlN%zfM^VW#SmLBtXy&si1Uo)e^8b8rWpouNnHRu$jqr#ka1~$+QPk9I1B$>I zc-sUA{04wU0bL|T8FeO2H<9w!eMrrL=oKPTQUDNcz?JBMyAN2Sr7wH+HuKWx7#N5> z0pLQ!Y10wY$fR8n2CPaT3=KsUl^+mQ0*+w?^)k~N&;h@O{3YZ*Ma6P=C0p;WYJfYo z5rDs*mA$CgSOhD|l1uyrRAiE58=IGLj@jF94xm$8o-T=gHTF+5cP+I{DPeykV82+JlN}zZ++eV zM&>OFOmN8Oh2aCwehW!7fheb88kQFTZvv_J$*Ak2@-0sQo*>vUyntqST_Rpq9EKkX zuyJJ1K3R9Hj~o>lJ5blxzXx#lr}FX`U=`j&1kNi>ne&)Hc_CODF$oEJIn8rKE&?%^MnJHjkZtZQ zxU|7r4w`#KdSU>Lw6zmhJdjBb+aO?LGk^cS&&_27>f-y<)D*KGO=PQoa4?MQ>v!(_ zR#6aqDlHvYx{CY8E5wh|eRzE#C;MZ>@>sQyl#~>}!ygcs4{{M-vE70ZHVeQe)*E)W z1}=7~^qwN{WFx>o#DC)8;XTcH1_*5EBj5+%^h;@s+<`V^=Z8-RPx&txj(~BHVo&=Z zejlP+X2ISZ9%8Z#c%&f^&z|PrN@0q!!6wWQ78Mre3F?L!vEz9L^9c-( z0nR&r(aJ}RLPnQo0o(lxi^$V7MTCa9PD1hvh8P-R`$xck2rm;$Q|!)^Aw_CQ`4l0h z)B5}W|A{#ufEIYS)ByJS)v0>Qq7IY^4y}`m3mY8h4a*vYMIeV*<5J@R69p!IB+Clm z=yrGm0G(w^#yRp$TAcehczUCn^i4sOSgj4(|7_USAnoyQR|>v} zi3tM;_+g4}LM)LYggj_y+=6h`ul)N!IG4MQCxH6`9EJ4rROn+oNGel*|FfLm$de)% z2z!@9RY=ePw{UDcIlp!VidJ;J15J1qVAT(!;Es-n@D@)`12v7qJj6E`fy2e&HQ4K7 z+z;& zWzPt=FalkO{5m1wz0=7s%AE3Y)dws7S#F;BDer~kllhRuF!04Yn4^%TQ)~ojDldN3 zi{A^Qwi|`C1js;`g-C-WVULfCi^e(35C{bUZvZmN11}XN<}}|H4Qsg{l0XYAZah$L zfP89>d*#yrI;W<>37((&f z52~j)tIP3_Sg4^w%4&zT88GdNJ$=dwUUR_WrKF|x!3$n>~} zTRGw%LkJEeGzF1YK~@D)38l_^`pvFuqk!!Qi+RWy9UlG|HkfQ7pKtvh646mnMfNMI zFbcb>>{nLZfh3g$`#ek+a@aBt4-c)j=cKA+K&H+57Z0{t;|v-J;rlD z#+4^F*>aXTy1DEvV-7pan3)0;k3`yfo|*yeo&hm0uv$sIMggN?axk8ro(>`01`xu! zI$WGS@Y);?*(i~?Fi7-*Rti}J!JQ7(xJP(mVtcaVO00OD_JkCf>ExTT% zv!HO1%i;m_Eo4wkV`4jumR-MSL>6&?I^^q^m`H|DiDDQ+)gzL6T2&bXrbra_8oCtR zF-Yo^45)zMRt;D{^u|ml!b?ibbEiN#!?4f|Yh)9!Hw`d25Hbeh2M}cqj9enHdaK3? zmt|z0@jqZ@2GL~i%!degG=DZWx*%Wg(y+HU#L>J4{tfCQkczd#N(lloVmaQI zX@BW$#MSu()&$68Y=XQG7zDr%(m!~h-tPO;0;!Ex< zuDq+Q2FO8F5|2o7UDU}>raAZe>ju$}zi`iGM#gU90VI|+*ro>`x59?Y$dioAZz1qc}?w&Tk(4rW)bp#fzpJ-WX~Axu*F z3=DT!rf+W()n&2?_Z1XOrY^*~O@$wyinphRpSrW40kfX$ZZ{T9{y_ko5))F zYlPdsMZ-gE$iv6r#%mM0Eu2uXF&YBjNUZv_Z_0yqA22VtSw6{25kBo~kU#O|%a;Vq z2xui>bVG+}QM;#_bAm9Qz=OkRpN0Mr(lYPTe6ScsE65RYJ3^KY$b>a(z04&o+Uw0W6NTd7?Sb*vtkWI;@XN0qg+B z$lpWaP`*vNFapy7?E6ly42zU=1QH_RezZgfs}rCdUOG@R?de1LusU8zq@bW6ARquW z_-)|lvLJlX!MyO9L_rrM2)vJsBm&aRxJ(n8UqK`z5k?crKOlgLiz^0RJzY8H5VmVr zeIY$34Ghn)5FptW&VaCFE|_<~^r&>&x(74GDzW`13M#7ipw$4u0o)0UM^LUmB#|kZ z7)_{(a83O_zsm|!9O{HNm`CrRJb@Jn))QcJ_vI&kK<)g@vfK7-lfuTqTqJEU)y7)F z-6U%QfTz~;my8yVr(14F_YOAe7nHe$r|xgUgTtA#;h1#iImSxcH@=FlRjh3H(CdSx z@DFXZpivb+?KH9ZHwtXea4Ttq1#5j< z2WBSx{GEBWY~~=Q(bU~2Q>F)M3P9#`J6w)BGPxVcsQ7t6q}fQQ%5PUJ&4QOs+bxqK zx;^v%V(%^Es_MIL;f;tzsVGV-DN>Tsppue;Qc}_((jf>~lypdkv`B|^NNyVG25FE+ zI?r5q-RF6p``quB^X+|q@BVP%1#H&Z>mPH@F~)z)a&vu}=_M8av_fLYxBNA;A>)#aOv5bP27e>~+ImcEgZnb2;BY(S-oWz~m0eqTtnLf#`3~+8`vQCe z#zvGg!==Q)nI?T4os8SjI{(Op7MKgnF9!u^%SGaqpOXzQ8e48zFPiK(Fbb!c<&h-! zHaE!;cK)eM{kc2ver=GivX17~M`p}O?BTk9X#vdgi7{lEoPt+&S|6mFsk{9;)42bNDeGOl4UtX$Q@iiiC{6;u)u`8`@Kb-D zSsL>k8pZw|=2t_te%80-gO9lq>#wGMzH2rF2rOC%tPK%xHM{u!l-kp0(Iyk;y4U3d z-dngmy?Y&sbbH2EpQULNA$IuHH_mKuVUm&cs-5(|PfayUe@6+rfU+OnR1wmBX_jT` zWEFz%-nCWnnE&iDeVJZC1sVZSQ7l9bP&8^c%!x}`-CJ^=xd{LBW15-Rs~<_cn(NyH zJbKHJA_{N6V$g*drSaL~o6KyVv_78TbR#qDZzzqcMsrHz(x>$`*4ruECd zgdy+xUA#(B$0hP1k{$WsDn8C+QM>9pW?`rtm9N=96Ss5PTwY4mN;9I|g4NW9wyP+E z9~f^ufn~WFetecK!c3twgMdBuG$>ydMo|0R>%hcggWFL}cXu!ZTeQi8%UOz6baVkt z^Q=b~r)BJ3y|lD1l$A{iPLBr8xXCT}e2&_K``R3AuhB{?3_WVCw!S4H8HDV>QkFDd zOcwJlX%D@R_d_QGt;3brGjQgF&8>#{e)r7$v{VJ<-5d4*f!C}?W3dr!UDt1XCfgXp z%cc1A@0xpn9y11dH+OjKtx2-Ta0BEsViqE_PQJBluRG1`ieDRLMf=Ueb#2r6YYr?XHeX~AVxy`Ki)DtITB-Ph zx~6pjqC?%09r7@hzjNuk8BzFuSwXk(X%xy%WHf_Qa&%qew@HAMQ<_cdeP0A=G3)nnnqHi?W~g zUnxDNk{B;PQ#-ey(rVx+w3aa%^y7EJn@=u}f27Z$=(Br1Ti{-*E$h$*e&SJlUxI}K z0q@=ew87tsVfkuPp}9p>irz4Au}+kO+u0rF^n-TdDn464{~8>b6F zD|a5!>L4N4F!FBlN6Wq8`5BaSz9XX~Q3VATXX9uxDQJT*oY=`AMO zq(U{OaMN#3c!X5ccHmegcq1QOniV z>Z!UZWOdV^*{;#P_oaU^SH1bbQoz`}d~tD+o`uC8fJ8W#0~_uK`W9He`yn7u`}1vX07=LJQ}U~?;stFN9p-sFJpjc(A56}|!U851 zWKl=IzuzCzdb5rN5!kOjCMYTjp;^F>$|eJ581Ix2|D~#^21-RwRj$7yc7h8v-i2iq z@DT=oeoMyVXW$WQ2!#@YLm-VIK;#3)y?#YSMY`Qu6^k#*|E5hab6wI!Zb=qrL8=7d z2YU2C#4jxKY13oll;R%wDXs_tCioUe)G-JAOxM82Eu#9vdCbD;dfb+JX7yrWkZOSx z*km|#f8P;+2XRSBFDMe9huQ;Xg%pgR3(lrPe+a0k%lgf}t0gCE0sGz5wqyRQXolb0}94bZim~F+imSVqI+n zi8^801K|_cEhDwV?%p0NsJWY)n^8!o4?s>DdV4>E3;zT_xBxmbVi`aO0uMlh;eQa| z82S#tjX|pxE|h71Rxpepb1j0T1*Z44;8%Q;@%`4Y0>q zEUZpw)c}YwA~BBK1Y&q=>2P9no;{e%n=hH4J))I~i6xCwi6}=c^8621U$&yGl**dz zq8XEXHO8CicS*goJ#Vwb6yQ>D9^{4(oxD$}d@=b6 zZ7clHVSCUJ@ecY53?;zcfK4JK6$+`yf!dS+ND~lE#6x{|*CEzn@?si3xW<7%nA_!$ z8!pbjKc9#o6p*_i$QzRPqmZ@=Frvv*D3I8P1K0yxS8{RjO-K!Z9f8|`%&2QjrN6&F z-?X0@5HBwsLZ*Oc8u9pG(2)*ioPhkLE zGZa)mJWE#^)QAJatu^?xL*Ef^aeytM5jybtF`J7fPt3~; znx57xd^xDo?*R%rGiHq2yJH-Exi{bTu!Jf&SzHvr;>w7ZeN`xz$II!sBcVY4DA@~R^_ zO&zv+m5IP^2>2*CU6gAC4yfQQ{>hs}s2nkjOa`qyfL0rD5goP&2}#KZX-_AYmT2=+&5_>hIg@;cK4Ni3hrLL+2}T{3Q7 zr_x)@*cT8ct66hD8VF3s4@Xu7jvr$GoVO1?IC3qv*to1@J#}@eCeeviiL2e6Ucfm7 z^hsU1V5~KVzd~u>(GMk(Q^Fe|`)b=|hOBD1f78e^q|~7gZ>(RLktl zyz>Kp^o@h->{9cq(goUu9q1wfViZ+ij374-aS3HqefaliLQ+!FWzY;KH2KNO901+? zJMI2FkE;Vdq@th`l`ko#QXVo0Q|ERLKcpy}B)sOQ9#3uN%m`-#e{9DK{kx{FXZ4>d zJLzwg{WbTv=SB2LIh4`2oDRZnT6JK2>EM=my-(CbE~vM2x@lSR(m2lz4>VNAz9)M`fRxH6&aeKYEQ!>Ico8Yt|Y} z3sK4sv84*gRGAFAD)X3*HkQWXptj2^9Pa31lpOK^O_^14khPYxPg(<^u<>FvDnkXd zal#EnaWAscMVHfp4bB1af%=(*wSqkQ&M1_(2h}&mOMvNa>*=>ht3nm9ql|a|KDp z^7T(l(Hzv(b|4XMPX)+kc{fGP(f8-^;zvJU+eh-)YC;s=^_0G~KszFM6p|Ez%$n-{ z{V;?>z!M*6WOim4ecHYL@@DEk$1u{$A82c9mpOx|%vQCHwq`ZbO=0+^1==K8d)&@( zY$wF5;i9~vT4Q~_BSJcGowELRnZ$7N@ASc#r+r}4NN-EgUGh+h;sgYs??0r6F_9j^Vn zC{m<;3_Z;~fS8yBi@6|j3O>7x`djZ6(nOfU6rbrouR#HRqg!M;1jiLY*g=7?M9q*1 z&>gvOA}l-PJY~Ug3}?;z6`QGV1AM}{_89YVz&)MXdz!}%IQQ(Qy*FSAR(-=Ckk39 zy;r{ZqEB*W(8l4t3EMprLj0dXzDxbw-<`VBM-o@L%}zN?S;nz=Q5YU^oJ*-BQ+VAOD=a7*QWNRPGRJyKUnT{TjL|Cl9vBQ5@yH{&7rpnkX_2v z2z9@-=AZE*BdBVEl)$(gtor!TVyqqEe%G@g=Rx(-U_A}HCc)m#C`R?z*UYQsT@$3x(0a+!~{f*NUY04Har1&)1!aUBiP5(PRs4$QDQ!jKI@vgx|l zqQ!0d`x>|nOdaivpI3{;wdR4uh6i#uRUmvJL58EI(EX|oWJ~Lto6|_j1%i)BXtGjg z^4$tFYse4bt^P&!Q&9&kh+8%Ir=o!chmMhRFawazFCVIZu9z;hs$e1vU0xm=_%3^c zRtNGnAYh+7eOedIW1VD&cyt060&h(Lu18x+q!N6!k@jGNFOg7!crOS2<|M`iyY30F zXGRoskp6<1?(6A5ak!dzrVV5=aqxkR4&Yz-i6wY{+tJZFZRDdk!M_JR*1Yf;IW|ZY$N)a7WUV{v}Zlds+7W z-UNA#8C4G^xx$y96%y;!`-`oU>Q(&fUsg_PivndaQW15r!kMwcJxJ)^iYIv4#Kd*z_-f0t#Yy9yH{G zPGr9aaNYup9|rsn90Ku%qm}UETwN0TSt1b3AwJHK*W?I4!8~ZOa$$DYBz_5Yg zbO?;c#L|*9wBrHR4H2!NkdBtpksMwiO`DpYt^*ZE1T4O1qX|&&Z9$7CD_|L{0kya8 zmbnk4Tb!Miu3-c5%lvFEv!ObusbSXC)z*H1#x=PxoMq9{aC{y59$4H85DZvwVmUHOiWUgvA{ zz@ds}XMzWyk#0OI@RImPG#{QfWU*GzmLwY0M; z4OgO!=2KtHKI_)6zy5lmu<+S+IKeVyXUv$j86DD|74BFpwuhUeTrh6YhYJexlIOff~}~Tft2L4t`}~3T==% z-LSWtGBRm6ue`coUcP?Ln~+Hdq&8r^(4V_sn)viCqF01cZAY?g&n$0#wkgbL30;kLWRTF5~KP8O~lrlB?P9 zat;FTm%aOwb8~~Oak$K@QFS~2_(!NGA812=H?zF2e=jyCXSC@f)iRuMxG`m~&L8!$ zc@P&M5)Jei{mc}k#*YAq28D6-hyb+TnBT{%P4BUpo)g-^gWNBTnMba%ZXsHzIBIfA2vXQwHO9v4m!?f{k0_i(c~|rD zC8rzAAI?nrHTT8nFLth@!LI?@Jq$Ei?X)sEa4{Uom(WbKbaJh zYM=AbJ?|$BIzGB|M1I76w?Fjc+zj2TcsMWcv^~qgZWY|14!*o;9-=X-Kv3Ja8m~>8 zyJTSn#Kp1`+fTjxHeL4s0AR0&ne|O=1d1}BL-1Pyocvmu(sOlMT4)sS1pcGXjq^?u zQp|BZ|Jd+`&$DxH_VK7JdZT%Y**o~b!(`?IzMwW}0I6wcIBD}4)U)gw30WLcN)2y;-CJZ$W57+G^X!y7&Akh(LaYt{`^q=y_lmj zY@06C)DTX3X{f5k|WXp5fJa93LUyi13!pJ*FL8&ywGVeB8P_O!InGjDPAVg??3 zPt?0quYWEOrI$G-hhi&9XmdP871iv_#w;(^a6&(O|#3etDv964})&=G2( zZ@D3A2r&f#-dRFQ3iD-Ix-mzl>&>_6LVbS$U8I!Qk^@eA@sq#5zi#IPp| zo~kD52nc2|t*tV%dTi{}!A({y7YQy%NnCi2bDR8D#yJv_dioF_gwl`L?W9QNod;3Am2`{VdE{$Q3DxJQlsfYuq;hTn; z7OowE!!>k$TFrOk9J_;|2o`ClzDo_V;YL-{q~*&;TdP-b@pL0BXI;0m6{Dg<%`=&FV760PDbR!zAJw>i|UnnfnrK1M3f3}=E#a~iWkr(~#MhWK z{i=#d-;N0kTiiTX+lH&B+;^F1iH4U=WN(83Ks|iU-fq_~cwsEUoe47zRvSx4Dc#%q z*wd|Flg(H0aQrX+13F9!2tXZ~BI!B66#WL4?DE@FAa1iJ zJqwHb=i^*Fh4*aAv1odP)=kBR@GyS5YSUqE**g6BWb|fxhkI1B=4jN$%oX?TO3ZU3 z7h5u(&z#)2Hx9^4f*tM{37PZ840HXgoWaUtFua0|HFz-3;wfH}*4ALVwlK~%G9s+G z^`_=XU`fmAe&}cJSQ~zx*Lu%drEw|H7EYF>qiHXY5ulfHqlT}!SbWdvqpN(%e`7s$ z-V6@WaNsduyhJT_?wO_?6FmJddJB)6nbk!PNLYr4XWJviI}@-m?x>aqMMqeB;o!g5 z?<`#>`X+R&x-l31XwWSzSmT+@>e%vjVQ|`hBOQHsSqM?Oc|&lF9CTArj3T8Q7;KhU zy!|bEk96<5cSP-c z;+9>P)(Nu{#jz{nZq4|w4Xk_RE|U`hqg>>~^=nuSF9ifs(U^GWtp&HfCmCzw&E=ly z@bVNFTc4Jx6botzJ9NZomAL6K>{}cEU=W!Rt8T~FY2Ygg=7HVeFr`FC}Ne5(iclZg?TZ6RLqvzRs&`8=GAa9uWi zV-aNWpx~o~=k6Q)j@#wT5+>{ny!|OGI&4TP`x%q*4$~Ga zm?WEmu2Z)y5+I|W@KoX|e0@G~sDG_pC~RQ}Z=aaZ3KIE1Y^GeR-j_#D%^W4eDca@~oad=H$ zt}lpilgf^~i|)Di{k{ti=VmN-!?i+W+NJPj{@qav^8N@#b|#F$pQE(;y&z|Vd=+ER zauGF=IGvvazNb$E9>|qIpRWPPbx&VJojqLeJsyUF%56sXe(^!9bOlA@`bQ5)-AzZ_ zD&;(~?76zjoEQu^9vj1%G zZZ&%?joBK}#IZdSVXGtythZ@Uj)EWF>jKI_Ogp1)|ezc{YH zy;bzYxovLV#U2~;ydBx_JNSc*#wk~jb+u7>VQ1%_gAq#!`&{RDT>=9R>H6k$3&R=I zy`HCXC+~RGD^a4}p|GFl7vXN%cIN-VW$dP|vSY3GgF>SW=k1EUCLJ3;N?5608g`3q zI~3Kj$HMRqo)W*2GF5M(-Y)JsQ)R$d#qg3YGC6rhIVdGze8z4B#=8s^mN&x0u3y`S z4>oB-b8OICVU69Eokf+JcP@28XPnCZDn1s5ryow^oC z&MzWcHqkv9a$1`voMcJ+^^3hqx45Lb9lwa9EAIsvnR&SnT@gz8){_yUmcJYS#6_91 z-Mg1&V@!qc>^SHuQX1D#D;esjbHsL?l{2E0kD!Y%e4uHYZcijOydGCszsVVQNXhKl z7ydU?F>o;V!0jL2Arcg;(c&i0iav-`ty}vN5h=eVJ8`&AZPMUUpXEn(93n zKD>KFy?*zrJm0^bgUGylNy^JZ3WGrcOsZNPt=Axq+eGpkuQ< zAY%8-ceG)qC1JZ^xOyT-R~LEe3H3Kp+}YV|9E32>+q0kKyPBaH+5PlYk(p0LCIfR@ zMd1k&Fs5x3Z=a6J{gsU9Y09gY$>(XvFLvjwJm6OF_wqewxtC9{cT9dpS8Rqm+WqK2 z@6v2si^bxD-zya#GMZJd^~74MR~u1QXDPkc$V6f=ik-NA2Alf(`t{E;Dk8i@i5h04 zj>oJff`JM)n0Qrd+*sCO@=jCBI9yBBmX~6+kb9_5IK2m1`u`p$#IeO-jq+bDoT95S zE)L(zmD3fY#Q9E|S_|VpWcVT3S@uRhwKu8ip^w=x6?B|Wi6Ai@@vAL zd%VvJe*iVz9{p&%(%uux1LNi^0dBiL1!`P^GE@2fzcw9UCzsP~dstJUA!!Dor=}uC zlJ)Ijq#KOJ$J&XywcQI_Hf-T}=eqUWBk_N3wa@mfebh;$BHf*GmM+^gu`+0tlnLh3 z#j9>7{Bfow0q}~cLS!H3(fGSWWJ^?)$D3h&=+9NyzcrqOp2^vcp4^)w{Y}1m zh1r!bc1hRX8gt;pL+i>*^BUefL4}>N=Z%@F!dtyX3YCYKh~u2YOAl6lELeT$mW1!o znrT5c&?B^G>Q4R@?Sqau88rX3Vfds{2e)l8E@9=ELdT)}7f1M3t{j~iU&Ma}nSnps zUGokH*K05Z3d-~RLY4al*M~^V(aKN77G8&0LWoN%I}u0e$wi5-PtMr!Ay2ov?S*Qe zLt=&gr`@rgO0>|)A0fp14;quq^b~kXv%;~HIbhGv3y1Bn*UDRCZkev0`?8&q9l&mI zdk&w9ow%A!1}B?^hy3D)?u#js+I|Ij=N+xe$WPasx?A*r zzji(8rGgDN$h~`6688$x?^Ks%fskk?Ruw{!7Ch_~&z3R^4eg$B=McT&QR~I$bokw! zRCY?>M&R3>3eU4sJHg1V9U*Lbn#&u{KrG$f(xN2CgCsL;ukHqW<)29S4bL|@V<$rK zO+?0kZ)1P8DTYXzZ;;`lWn@R3B_+OMn5b$&!2SV+F}O2@VyDCW?;Uz81jKV+kC|4vz&tE?fGJ(-+byQ zxuAS&xZS^iEWv(9iB$GOLVe5njWEog5C|caC@y)o)J#nIp+ZF5{f?Fk7R+DNBblvD zim$aZ*zyHNJh9RIPF2ARLh|Te)uY9SgV&fUFPm##L4kSFul9B-ry)j^dnDdv|BsDv zF)DP7qw6;1-(%N=@eLTo7E^>U1C#~gGCoD1MBMk0BE;d2gk~G1)AUb?;oDFk`Pdb` zaB$we^q7dhz(0tFVJ%Erm(A@@*c0ciOwu>|MQQZI7N%58*~j-e<97L1mRb*xEphtk z-+euoQ}Dp){jv;1P6@_qdgHqGFCu7Bu&-LLEqGiAkwZV1e|SVtWdKDL>gc>3o4l6C z{cO($Ls$RqWtx$3nf~p5)cjb98^o_bMb!`87P+f|d|n>!xBsMcmzYtRMa5AWIx@Ml z{HPRnmDIb#8f5t8#r^7S+OlN{Q>qWXPRr;8KeU$myX+hs4+w+>L6Dv^yCyVVBO}*d zrLxy?crz`Xoow5k519%I3GIGGTDRrZB2#;P{6X_G^9F$TNk?JB5YdPA30V_KRCKznYrlUh(I9?Kk#c>9u z^@8YtyvjRBKMZyGPG*AkiURMLqucw}Qmp)f`-}E|qxF(acjIK2eYIq9Pct&R)7;Y2 ztRXVWNb`iwr$3I)uz?hrnzg|y_goTs-s1!aU}SwjIR<&t9H-NKQQ?ffUIwczd2@M zG?BH+ZrDk%yg3~d^?5rJC+PPqhq%mIsMqWs5wbzYRhibP>f)u6r_7rSq$iS7Pi? z=RH}Q-K*l6FBQvrXv|-i^a%Xjp?(=+eOn&swz=f!?LdtqJh$zur`(?Bt(vN)_cgAt ztwUFgDvka$7(9l)1kgAg6~^+zr}w_%NnN%jRvzSbPs;VMDr*!_DH zx8yZuWuz><_fJ{Uf0Lh8`T0?YKy$m(Dyq9qSzT6htGvfxD$;T$)#%OaZAW{vdLME6 z=%Ut2hUXA_da^4#PD9>yz%#+xu~&Ih7#4f^cU1F&G^&o|M&7;LFzt9T1m=hL?CBFn zmzR#){4E{Ji{H2yXl@ZXl_@gie%W!nG|QaZ|M@gyCE#XkAvP2)@{C>vW84SO_D$$$ zL2hsMepN&yVIY3ve-B)W&w{%qrS-0mkX5hkqhnkQ#HfB*{IVg7N(rS$!dY8Vpuj)X z6}sSz$BUf#!YZjx^m_64VmYt$gAK6nN&AQ)@Y|Kd(Ng5Z17q*k! z*|^3EuQOyN>C}Hto0v*+l3B0{Cd0os5yI)w{raIOb>pD}Z6YO7>PCAt9OTEqKTcnb zmVfI>7`%V4pr)PRdpwDCj~+a99@TqBT823+0^kYkyYK4urBr9S71g47bL9gZ?s!gY zUGe|8K6^cx>qSz9*F=gVsr!TKa{Xe=K^)He1Fu~z_bjpB#4SKtp_1a2{e_y7WV9%bea?SPdW6;T3?^=w(Qdc7Lakxu ztn#tQaOe$-(oqP0DK=M(%T4Q_gc|3quAk_9vBY;rOWD{MwT7mm(@NWMib#_VM*ElJ zD6M9@PB&&A)9cLK{xw*0tOLa!eQh1dDROC$n?21?c?38Q+tCJzLigs1OVq}UvV7j= zWRgQ0-O1Ir75L*3*Ib1*mt3OaQyfjQjvku)_W3>+ANK@O?_F;O1;x~7d!p%37D?g8 zad~JtzF#uV2S^~O=Nd}&Iy>u|cRg#W>4rN>vo60~f3Yyj$;j{!XfU9}%7#7h@b9g% zpHSeTBc4d}J?oDE#1Bx6ZMiEv)@i53HeIHD2N$V(wS_h2;Ac*eb535c)FC5v`mF?o zG!AF)RC{x>&0w;mVrh-DhE0FPMT?P;wC(#^DMr*(hyxEXY`KM zFlXK({(AHGQ(kWGA#e)k7=DOT1EASmn+T@F6=V z1aN~T=YPXj{bJ(cYY$kbETdoDcXle$b$Ihs(=IcHLe56dv+`&ab$Ma+cDCIWXD9mr z_QcTlJW@H*!G-;CMZ;y7JU2Dtj&8Oj*#5B&VJ-^+EQ5e(KG|s9DlfH-7rOKWZ><|C zGmP4rPyTq|vaFMrZi2dC#{uB3UuP`dKD=O-W%RZm;gRd06>NTr8()28kD(6 zmC1jNI@{pNYfkJX_2ESp`GWZ~j&_xjj2sWEN0PVqcuLIxHiB`!dM7iK)KLaw%@;y-iY0uK`smtmlm}-@px)FJI z9XCjcoO8@&^e$}k+R=wcPox1ogp*9swD2ckgygN-FCAD97MY)4S>ivau-g3dy1<`~ zcQr!YkoNafQ#;?=iLEDjOILY|UVYIU+{IG7!owa-q;H07dFfje15LutWMk!&#BtE_ zvM9{LwMYQ#oBkBLO;vuxNW`CSxu}udrO|p7qF7$qcb+E1JWE0 zFL}jRE0;ey@--BMt4zgFyvVV{hoX*kXtd#-&{){eS&!}?YmOMeKkML~2hqD9Lx9Y( zZxP+~RDK==#jq?DaInU{7@{=EaF-;1y-uubXrOAFoWI0vSL!bJZtH4Lin5Fizih4O zmx8NuvgA-de<|2#G_@EWPO;ui{*J()uG>10omcoDzlWgx19${H!K2HSHCJ)`JD7Jd zR1Bh>{g1A)6Vg;|lZp-DTdzfo5APlC+Z#JBTzrF7?~rH3v(|I8Z6j!|nP6_g3lH_m zolI#p!*5P=gppbr;pz8Px>^3}`Bf8X}wW@VMV#H z?~t^7Z%b~>JNwH=Vb$xtkR1GYr-3RyR7IZ8>!ad)g4N7is$?Ah8}_%NRE$2tY9F+G z3y`l9MF~Oe6q0IZM#UyuFP`HYFEPXP(Avcud#?jb3sRkbJn#6fZZp~0|M-kYizt-% z`}jSUyUDGo{@cr=?bWHSXn85j%0rzpPu9WjHCif>4qB+=$xl?Pi*KB&2rj~MTHj`X z8(DaB@XQ^rU)RAIh^$Kz<2PU={-iIWuu<%U$$Py*6YY<$Wz!v~rv$GIg{`PfSa1`> zc^y(7{2{xOS+_>Upq2`?#lLeC`e(e(DCJZ%z2fT{YSf<6ymjohyT_UOKqZGd6BGgfV6 z@6=@zk+HGRGqyX!`aG7@RTAqs=n^cPTk?V*AeB#(q3zk;w+_)L{xoULeCCHw{XEoV zOWz_T{pkR!?EG~(SAOkdEWsC}39Mc37S?hXs5}zwJCwxA)S4gxv>rBnno%4C_x-NU z^MeERy66C#OiFfXEF{?|;3RSv-%-4XNU2DXY08tLSGN#E<*wZsU3~?pB@#N$=s)AA zIHcxbHwjKHR3*$LiF>hpP7_KKLHoG&ZY?QkJmM3vi&8hEx_NwB9pm!>j``&*iFtFx?&yCuGe2_(|^h1MF3QUsl$(4kJ_i&op>QyimBn}?ryIR92mdZ zexXD4DA=!5+I|dh`k_VXQbG64ISr9^=F=*x@xZWkXAjD!gHlMbm(q*_?u>nO9Qp?< zR5`^8n{FC!T$!zwnYrVt2dxn-AFLyP!3{dGGb!;*@(tdbvD9R+Ppb*Ylj#@$! zT*TkJ>i^MLW#`M0*e3+B4EDZMnUF_tm(urhLGQ(t8ZC~!o`k0h``mz3FXTxr7nbDD zLg86?v|B;EyzoW4{pvw(Rni&h;6`nsvGRu~AUd9y%4UZ-aIijZj?$9e+vr_79+g|a z@i`b^h6K?YLuTxOcBAQ*S=U#i68T8;r<(SGt`$WpA$Zn~cIMx)Qv;6wK4?Xnp5b@d zUvWGvm-2Z}Ni-cDI_t6St=#3OvG!N?e*7&SQ$r@OwZ$H4t8RxKs~GhhQ_gPeFI{1t zvb@>gRGJ>vyy%;tB zx<7Bb?MPcjaVW=Un8YJAaZHX^bx8e3=l~a@NZtF|a;FY_g{Z;F3Hgo4N8-ul2LFY+ zF1%h<4qUg97)QG}l@d^=;Ha%bQHb`dwjAZ459@%F*(O3E6y>kX4Ca7Wf?CA8+*xf9`=Y&}jH@ zMAcH0b`d)jEp@z9cP$4nf7;R8O#k~q_Z6s$c${An9iaN)yi~qA?&VM0cay|PhI5Lw zj7-mNjIOj@x(`jsW@~iHc1A1Uc?ADXH&0$4^jH`u#b75**esW7N_%{0D`Y>b4yAMa z3hcQKZ_YLcn;)p>>fquok|&uS(DIk;0a>xE4v%?ZWdClcKEPvqD~EK^niO+y_9!f{ z^3qDS|B$*EGeItJ1>0AFdv#=r@QW;CS6S@)5-B##YX=p1ldNMUi*XqDrYwiQg#jnp}*U&~HBZj!Tb;~F?Gbqgo_VjEna26la}PZ{XdstFGDr;!xn6YVvcNe>$I|+ zaex5;M5~{$xJpL;BT5U0I%RtKcv%k6|E9>$T^(MfJ*;%@!%4LvO;-$vo7S)PFQNVe zIN_BkWs^Y5C$!qD=dA8{ENNg{{+D&AK_eU)o6xDQs(+c zH=3MTB;8d$*$Sc?fzpp+8oD5M8c*HsZN8(N7dk>1m<*gJbWe}vhXVm^Y06rNT zy7pgMrpx7QVw#d*4VqY}=$`0NQ!0XYB)gG`$z-a~5&ih#?0v;<$_)%6lUH9{mPb)N zW1H8lXjP+azj=Fz6WC7?8EQn;Y2=emjbXLqNlzwL6R0`ZXQo0G;FZjmL|VRB6$|b_A*<93s9#bI=W@$3ALumyN*F$FcX?SqRY!IEKxrfm zHmOOeO@}$=s|}Qv=W}z3k2g^zy?^MVUCBd<5Vf}cZLtT(1DlnNVi{0>8sM_2EI@~M)?sqRH-4@iuAzAf=Y@c zKPmr4B${W3;+G*^uwZO!(^ma@T#NL$`9hZSs^}5H&gI{djGgAm$5+~Ob~ z?L0Oxf6x7XK!M-jli(P8?qgoEnA_$5(gIlbG;QWaSNxwq4TMnXC-9$WqNfr;`1y%$ zNt5+nWg1?djXg;ZyF6OX|Cz%?z?Z$BO>y~WwH`>Cr~rW0uJae*Y@~m}?W%f8cDGxh zr4VeB7>e19tLq#P;2ZW@F|eUOb)F_jOWVoV=rTna0oWXF@R$$) zgC(a!=Fm6GWoc=_Y(I0nmzqt^5$^;jaypF+8@j4Qe-o5VJ!%VE7^=JoVh}Bbz(@n2 zUxiga|Mw5&$pj?l_bJYV+D8BcL`Ty88}oe*6(5V|xbw=exCDcp9KiKBj5}r8*WJHP=_uK-Z3>fhcD;Z3G?IF zvmFJY(g_|yxP&*N`XO2lq6++E_DXoNMK?TN{AzEOX;RxTH_ z5|Xu?edYHeCC~!vJPa1xF#tu)51-(n0*}czOm1`**`J48nLa$9dcD9H3K-Sh`l|TU zl}su{?BIyNd$6NQeNBx4-daWmp!P=kgfv8EX7#cD9o;I;K<7id8OGAWiqMe%M6qKa z@VC607Xt%Hm{1gu7w@_rleX6hapF}KgjP3HOm}Gd)EejPbZP;;LvXPCD!J-d}S<;?K0s-g}Bnp#FOxh8uvBqXRMxUrrEEVscwwY45a8=T_6ow<8`|TE zRn%-f_|jv*!qAyfJSPOI@-`%rnpPm`_?S$Db!||1N0d#+F2v zivPqdy%}EYcw#qk7hx};XiNkQ0}vZXih{Jt!nF;t*VpdseQ!#P08PqU5b(hhw(sM2 z+Akp6k8`FD~X-Cg(wBzy%`>ywrpJbjxCuOx6|LLm7beD)n4`PsMktHKir#(9g( zs9m=yo5SeDg!V4A4D9S`gfN06p?vn=OUGNz6se#fFn=956jdn=z=A|8bx-#@Iy#|} zW$rFAxl%!L?qUxIhmZ)018mgBw;MTs#$4$JIzQH0OkC1aPiil&Csa>@DK9p$KYIH4(C7{QE67(m)zh4HV ze8T1`2~o4r)8>e8lL?%NzQ9gkjRK*;EGAwfGT>N=8IYevwWlo1sj*H}_nyggyVlM}3z;E=^y8AHAgTOeX}{&|_MV6=9kBW6m;$j=X<7iM8DV^-ETV?IXHzUl zANTLMZB)>(51LITq58J^v4|z)=x_9vV@339l;vBEtloAS%1E+< zLH}3Qd8)Cqtd{}w<%nBA^RRw~TjLd<)_)Ks_z%|Z{>S9*&XW+RbtSh8Ou(!WGj-T{ zgqQ!|WQ_qR+ilOt75k!q=lO3TvBml^(~+Rp^w{obTgdW!UQ@P!hw%+9PP-cbZ~9c_ z_yDpHG`ZRf43#x#8bD0w1*JHU4Q_u3>_r%$!Umw*?qn7Xx2Y~D#Gbt`-AvxFqj_*s zyWw+O!g_?q{OI@V5G*Xl*qquDoA$X!*MHPGFTqv>gk;*uR0UKW5c;-y<3JUu?V#Pt z4g=cwbRvh*H2PgLrBz`R^jw0@I)~sYJrgy4XkelyB6#aj8!pgVByVBOJ#5$Wrj5g3 zY^n1RyT?D}|0TDTdwp%b*j`);{R!lQ#x_?NjdkjrK4 zO^3gU9Psk=cn`FqY!Mx&n|@??uGax;%=*5=+D}0|p_AQkrHe?yw2-Br+xY^=pTZ+h zWzi(#^m7RB3kr79n?;cO|7YUquM|$wPc}W$v(`A;;>yLV*sT7_Z@KRVr)e!D4ZD;l zG#^w;C~{kJckk%(PHkDPw3aX)Z`cRvOi7Nu%CK=hyWoGm%iNXnl$1i&UTeZ>G64S+ z5uv8~oA@B)l!Vy-6F2pD7dd?cTf*tWMSkB?Pvlg&dzv6Md7dUnF#kaIaphD~{r_L! z|K<^?r(wVY<>5q#`|bOh(x(KxXEf*O*zmYTGZ!5lSXkGF`@jG+_UJe`r`?Wt|IZKe znp5+C{TT;uH@?68Fnw+CbK%aKKZ><%Sf>n<)u+8nQh>P8{uRhr^>ykDpN`r8$A=Ah zsyqkaP?PNLDVB&TC@P`|(<(4}(xrPkd#?ma10kKK@PX3G4oD8LA3t~QoPr{Huid_~ z7T;yezo)lk}Ciy;ehoM`+|ICphm) z{vE-;b0Ls^@)JYWm%>6W&S;Uuz|$onGOY(l6`Pwh*ImhfEhru$SeMeb7cPlH_cg?l z<5VjT_ZsK}_hEUV+(tGGe9Y}9bzF-Eulm4}=8zn)7sP~B| zTiXWgFMiqlo?`wx-gM&QjG`&wU0n*ViYMHY1{~^X{&^Gx$q$1XuW{HpJ_nZ~ID|+Z z{7)J5+8pLt#QRqzGlUx(8%yJewh3Ni_{hCJ5f`WVOH#t$U%jDhBAgNnuCLwW<8j2H z^snHI5OUA4vE+T(T5*x^9q_n(s-%?S{`arQeyYu5WZ=A`hz8G>66i~%SWC%P&!kr1 z8N+A)U%!-6C}TbJkebpC34?!+#lgWD@F&AN4|2V@ zj{7OS3$}UAJ6bY?tp;-qeB>3tUFy-JM~_?bJN_4A?*Yzb|Gy8@*3wo&i4rohH!T@S*;_(Z zl)W-4MTD#*MaW*+J0ygVoxPJCve*B-?)&@w{h#A`{{Q26?&EOW_gy}p>$=|8`~8~d z>pXp(|I$I;fSB5bge5tcd{6``mNb2xM$jRrI?pG@_rD}q+d+6twyB=3CpmVGVd!do zcS(s@iG8g z?rG;>Fhd2tHVEHbN!=XSqrJ2RL(aUyob6l9vLE$aF_S)5< zBmW??hxRr#G+eT^e)h!J+|3y|~by1W=49mT-ye)qCcNSHF7 zKQGatEiJugeSMvT5T~hhisz9D0BvJulyhXmdC)b9-Ie+Qb-@ZA*~H@F@Yk=8f!mr8 zP$0p}rxJN|JiNXV%ZxRIn4~Kv_V3lbtHSKAp@|7G!wn&ets%uRhFr$7ss)qTow@j_ zSih^Pr1bjl+||GH^9`-7;x;x5xvSY1yg>Us_>k|7h?Bs6_pK5)+yz#e(l3CQcB#^3 zt#S~Qsh4R%+C`9#FE1}k=Gh7P=p4tHdARgP2fxL^By!{LTOS-yE*_qN#Z@R&cbM~+ zv3pbwVvh#|2Vb|h&wKA%es?c9c?Ray_m-6mTg-que6dnynUaPkCND1}gwp_@d{KV4 zl6v(v$Y@O(2M-HR1u-kfJSW~Xi0H4$-M6v|g#5bB@f{!_tt<+Q8aczjFp}#mssHv| zj1f(aZyGoTYQSnWQQ4+pxsRB72SNDSQl;oG$KKVj_gjI<{g{&zteSC;dXaxSu~48L z`Lg!o$ARSJWVjIj_wP+BeL)L!edntss+W_NHR)wd!QaC2FG` ztYJ}=yWZ2=E9>Yeh?}u1(h@XNJ@#6^-%4O~YAOaAA7RJ%LkPb*D!k<9`^XL6ks#yx zypWYj`eN~ASwG*D6Ff_->sk2@+u~KtJ)a10@!LawjK4vGl}#cI&~@dVCQ_5}`i-2d zd4tVP%KHMZ-qN(yyKGqQ`Q-dJ>Xd54t#1~28m$zc|Dd3I!30vFugm&BA>Kd$k~Hl! z?fANKFs;6zek5aKUVGDeVk(KvX;j*V=2M;UV%Ntts4mMnPq?(Vw@aEbSb|SV-8Bn@ z=7J00K2vkGF5OO{@>*XN#6LOOm5@!iFRF~alLf_#nsg2q8EgNtqIO+!w{7}0Y+hkGD-3n^zB=Bo>c6`#g z(rB^*Ev5&iJ%#OCl0f01j!S|?tQCX7)-~*Vp`ojaPpx!~h#2hKw@(#+3j(oEd&@pe z70%scKCny0b$G@u>C{@^&V@N&gUB|kW@3SuMMZnDG{^2}S~Xm2CA5ADb&j_duXh%! z;)pJc7sK2pNzmVgE-Q6gFTPYOwGE)e0v4=e6Ib%|qY=T^ZR1%QtieH{p(g8-y&K8f zRh*oh7Uo`BLzP`Me6?%jLXE?8rBidmcpvP@qze6^w9gb8API$s~_$ zm%01!;%YLc>}y7?)IhnB0m>6x#z)W=N>=&A*E5~gV$uGrK?*W{dDdYNO)I*tfMz^7sJyZ=@gSXev*B5{ zC2r~sy%!x>cVYyV2hS}snV;}~RdnF;u7>Y?b9o@D`sA|d3>ryrBm^iOgD81%u_&Qs zGS!s_F${uTjgSWhlXfW>N}zV!m~A`g%{vQ`15OYxCMTT(6*fV1O`L5K47A&Ulj5JB z@#LH?HEkjI3P9or{^fnVU1G4G1mDSzzfQA@iz73Yr-&cX)CTc=AuzrC{QOX~e&Xr5 zdq0hk1Vm22ye`ytoSNg&(!-U-Y1!Mi4_>==&1$sq8D_~rqHzk$e!EH_KNfOPSG-nc zD4n?YO-6OZ!_^;F!qEPtL5(> zvNsk~cE)47Mskln!%x79~Ku(sv~ePk4t1mu%)_+|u6A<%<|=kjSagHp-QNgJqY^V>`u zhZYUNw#c2WkOS{F3yRJ(u;mf*3ZHb!jze=AoU0kFzpzfa;L_)IAft85)$5{@9+;gq zc`3nk{`{?DUgbq9jL{02|RO*4~rHqU;l4wc4z=c40Z@ zRkKQQ>=;vG%UI9E6K)&R-Fx62vu(*%5GZeLD;sNDk`Lln}@QJUk={v zOHo2qo&Ht1J9j?t+&#m~tGqh#Yk1hmsa`+aVPPV^Z@^n(Wg?@#84NL+)r7(_H>m5P z1LZ(`kbrrv8zdSyM2|Ff$iN?fQigEtS9=7v_D;^&$g{R(*QTk*|!G-WS;*=um>n*BJC~8nfktpFDYf zoxW(cnz_SZ9l|(qS;bQP8*Jpq*~J*6n_&_@5bMIh!GYUbb%px_@hp>mM!UkTTd&^o zKG3S2GHyvwG=^r56l0~wM?zXBy2t6NfBStU5Z|a3%|V%W#06$p@&5fJC2h;AjW{hw zJ`nt!$y$uj5Oau20W)lLU{tYIs_incjZ`hR#eGS>FJCHvh!O`;3IQGC`#Ux8RBI*HW4Q$U!C9OJZ>S!Zj#d1q767Z>}gK4F_Q%p~P6y zz9v)~(qPyuZpmj!_ju4&+L9eM5&}K7y1v2{V6J!p8Y=LK{IDp;?LiXK6_gaM4Cl^0 z2ZdE(=_3&m2-c`1x2nA;b(|l2CMQ+1y6wQJQ>p8nA&V8pS;qR@+}W~FU&!jofczO) zb_vd_N{?31r2iWS7>(*UDdvgeMQjBdZO? zlGNMk>abs69QmP@W7M<*Y`3PTC}F3cfRh4n9`w0)!w z9a7U;2x+Kf-w&yo?nEL%=x_#uThbtuFGZKTEKL!qfuMND= zZPi8n8n+=?<#w3iW^U34XfhFkGLTd2@K&vDk$JcJA+Rxfub6V$QCbal^3itH% z^spwDfU^gRvYOTJZiWd-Ub;jI;SpAs8QX+up_X#~FQw~3EzN;JipCaNO>Zm53eA)A z)Lz!!D>LNEPvRKtIxI$-ar1W+8FfF6*hT5OB@< zgG_8Dr+D2PWIAuLF^#NUc{(0c2QsSN%Kv;YQl@`;nw(Eu8Z7AHO^tmw>%!@{E!)9o zY`7_+OraZIcOCWxbhUcRv%@#SgjAWsISqUkqH{oMoTQQ0s9y}8;X25(Rlt9t9N(@w$~h_j^BgN7qMOaX-(>YG(CSO5S?9 z=RG)y34Z0|3;g_f;$GUlAU7(*h9P3Y%ydF|%qP4G_ImT@C!MWC9HyCXrGucPaDAb( z3$+cf?eOe>=Yk$hf{}FD|c0M7d{+JzlDx_O?7)}z}WH96; z*Xt4pZ5Rm3oV)SHwft@bR8Srv9@{dl7!h3(a#8RVhTZwx$V&%dkV)21B%e<{|=- zN-(&C0UzF~ylAnfhR#=LpeLz{vNQJGJE}<)>>5&na{PqIBRbJ;3Dcqe5(1&t zx~ksZQ$;>R%$;0ht(~5{QiiFMvc? z81(Q3Yg9!C;3q(x{kbp1AWR2llTh|7L=+}gR_Y;*(whhNw9zITG9`OLLv&wgegA+bjECQ}WTH-}bNA%5X z&D*ylNam6F=PENs2aYvFxl?l9dx;Pibv8yZ)2`gxjKdO14ybv=gEyKfnyTi)&K*05 zNIB8p|Bxa+jjCh(_j?(ywh5#ka!R zGG??VK}8`hP>zU^EmSR(8Lx9(e_HyXh(^c`u{u7PlBAS~%^$8{WtHiGqIjU3!QsaX zqfOWGPHqq#EL1s}ka%;^SUPUmP_)PyE}7e?XRElJBW@#byJhPqiLFo0#0}{Y_)=_YDjwLel*)#0#FT_~?? zmT`-e<2s6IOo*?Y%mU?%p|Lx*xiP&ND3?-oNm^PusPxXQ2SxL*6XN1-N%8xCeeUKK z2dPN?EVUNA#-ksUQZ(XCQ$?)L8aiQ{1|o>JVU7;$$hS`1(u}%Eau$Tl<%rT0QYf{~i@Fu( z#SoynG2s`_&$&Rd=Xc=81yB{7OPb4{d^k_8r zyCXl?q)$TFDcHGg@q2Z(1>*z5a3nOw)B$rBQ7|<<3AK>LUy-Il$%Uai(()! ztSBbtIy*CS8!X@oD7wGn2(9hd>_@&C2O8Vxw(%gXRAp=yMVtdkiDXde0sHZ0(CcNjNikXv2Px;%_nDn<&zAGKT5sBsd7FlYCINK`Vr$BY6?vU) z4!Xap;oBLX5NyE8I^EnhOHk&%+q%bA&V_ z!j4;?62h4oLnyxm#xocMn#LWOMhW@(YK+4wr*%>Ds=mX1KA`F&REq#X3;MQlIF6)a9VV&PdG!K_^^F@MpKWR0dFoN0Mfit6IV3>|vf(1TZy~YX zzHM6^0$i;`TiMp+KslK6+pY_OUGL|5B7c?Pk*!A?uc3!3A>Eo9D2EzG$K`DZK*Q-f zH+20TPzLAyIwE0w|5~66BrK{SJF0Ju0~Q0O+7|R;c%uX9UNs{lO8(3WmR@C$I*+YR z7q?aKKP8gXoypDpYDj~z+z0^)aTFC56^(fF5G8vnZKBk~9M$mKf|KiEpO`f^%K2!G zt(;Q)J-Uq_C6Rf=kHFyl2q_VQz(MbV66 z!U6>itP@%|QAJ8p@hEq4=YR2$vvyfFydNDNqag@GM1(?d@W=5d&2ldV1qYj0Q-p3K ziYfc(-+SR+tS5e63}#cL_+plm2t`-xwI%c5I}5P&s^ik{k>rSuDQIdYU?$0>_L zQeL2}`3Y_A)|D&uk=MKevHPXlQnSA?Z|nHgRN+6oFIK*yv+)l9FTsMdr-o{ zz;K%hS5 zxyK(xk5&26vwCpKzT{N)7IgHc_u^K*YCn-yc^nerD2CmGJg%!Q>*p3@>nd^*DAx}8 zGeoB4E#Q?6gF$-atw~CRe$8t_&6;QfqR>}SWc0L4`3<4@j!Kulr@N&Z8Q=5#9K(h$ zXZbT?V`FPF{Z@|e-LV0cm_M5vy_>p_xIh`sx6`b^8&dOmyrzec?pF9v*PveV4R%pd zMrIgtNJK$OdaONgE)W$3TnOa25YRRm-Uo^3VCkEYM3jN5*R!!P<6xt6HxY3XnuXpc zc@G^q@)cD_f@c?{JY7Tph;)%}fB!8G0NA&1B{gj~+eJP`aFdYkoa^x-B)_(XT?-_g#Zw(!9&e z<>nmO;J3cMvQfphs5$X;|9}snyKv!q(a&q>Sw-=W)hS+C-R9FPTh}E-(FudrUTDur zh_XgRM7$HS_lFdY1)P2X@48~hjhG$vWPEkfx~8nrfByVY+YB~F4bbGzoYh4U>3!?P z+?3wdztofBKgUm8-bKrL%AZbB<3Ln{2Uw(0WkT@>Jxvo{uDYYQk*Sm++r0z(-MMobT;D{j&nhVrnt)0Kl7kr-0;o|`K?@iM z*h{)Ek#R&awkb`gYzGl}4OIn%9yww;qM7I~RHW$s2zrr!+cv?&15a##_Bn$@x*_XbT$jJhi;Mw-%E-_ECNuwt4vL)4_qo zUmL5_1~9JHB9wcwJw$yV;0$qASv@^^#PAyCD+G{ z47GBk{m4VM-XX|L5f!NKJIl`>0%@Osz`(1>(5VHiPBSpLqaLED9;AoU0_Ntn6Tjo@ z5f$4b?mNMuw+re{yP>5ugi6o|N?{azDwORZBpsvR%g-QF8rR(E?9#p^T5qxL) zaUs=txHgOmdjvrZjue16XNJ}zk!eAS;xCV1Lhb4#ubJMTzEW2@^AU*pEP*5H1i!^c zb>9qDdb_qGbwSP|n`@RtHyTB}8=!zDk%~X3U4Ss-A@pwuXak|z2}DMg0BYOs2)!6o zSm6u4L)D4T;qQ6Gw8jtVy_Zad(H?-nKxdK4E?T#^0Af`OkZlo)yLsr=wWHOKQrsOx zCS4BW$(e=?Pq5dv`uGX$OZMQfpVhn1bCSRdpu~ybn0O9$98R^UrOXp-bk1(oUk1NT3%r`#NxyO z2g@-UKPs7q2hnu+n3;Jb`Ur6j`&8r>HBg5qHB2mqRP;rNk|RscYZQDlTqu--#KYSE#?FA}?P;tB8ogb8C(q^2;MZ8U$=^hyf zFW`}twd|ioO9xwYTesyEnSeI`?`>?0Qsg~^;v3EbYDse|-PPZX+#UaOnYa&ZMRr{q3?Mi?q5-w;i?R@4U+prwQ=p}Tl& zZa0E4G;cg1v_wdl5k?Ho5m1WPj`H4BdIK?`W|4@i3R)q6U82W9lmvEI?nW#eLRe8y z+~+B49zmyo3DM}bojVW19T0V99NFz9xZ0oDS%Fv+3M#7a$X)8tYfwQG+%XH45?Z$d zm$^&?hTn~xVU-4(u|BYCL?InW6Tq)Q@Ex@4lrpULA_!3t z;5XI zAZ0y&ZnfxV+ted;xGthcQ*v?s=GuZ(dLw`O6g9~q@m??OzvUq`%y_JC|O6VA0q-gunQ~@5{~5jBQ&zTM!eIm|J!%zDa;W#!!`!p{7=x{HmN#Z(K%t(Gzp8j3dfBsjJ z{uTXy{tAEk_UabN|KES9*TO?fiF*Cx^1BUMC-?67evfm<(+KgzUZ3*2rFYX{-lw%% z=y^iDk>;+guQ!ad$=q)@%aPa6n2`H5Iq8i!L^|X@uh`?)WaA@~BLf_>NcIpcd=$nf zAc61^MPyWAT8oxbr;v6dfrSo?)e1cy`+kPjX_@AL)ztW9cn211!Xw3#P%6B=e zIiOSQ>+bIEXkLW0xB`y(i^oAa5)U6ALKE*CAK%a9;c{MsI;xc74TnIvz@VTRSm{4M zu8^Y`R0^BW9lD3uwz#U{JuL6l!?1Sjh`xi<$qt`mw-}Q6=fwNc$e_umq>R0b;v7yr z>+nq=Dr{YoLzFS8`p1ZrZ3G4{1eO`K}^Gv+k3?22oI=a)abMpZbPX@vxUm;7ECv=9nZ#bmr4Z#f)SHQdX2g}9P}<&JLKJoJ zKPTAlkihroqS*GI3Zv5aG@_IMSrJJT9SHR!L}Nnp&GP4?C2rnq-NKI?<9oPhIKEPc zBZSXlXcq~gkrysPt*xysU_EwKLSh#ou!%k>>+}q8cIZ_~qYC@tY3zQRzO})jU02#nx5gjaXUz%iZaVZD|0cuQmitlf^Ytrb< zQ1tjtq5TLul{DOG;RK=02Li-MNIb%09VGggoVpczbHe^lh=gz28?zL_Hf-R#Cq9#u z^b#&Qm?)=Vf97YJF9Of!4gi=J@e{1=9DL#zLS&N=KA-9*i&|yOQyD^$j1ip*tj=*(6sZ$K~e;~C8R0q!D45GCyf6(CBVM^|T+Zr0*k=E8D&_9ly;ZPI?kIVtF6{2KfVPTP(z1ZW(27$IO_jx$=tB;^I zp5?0MB(nZjo~R!E^8*zg_;3WzsacVs|6^VxVc0ZWk(VGXB-^`p=yyXDWPQ>fEnC2u zM+p-ZUX+22jEw$oy~ax<|GN*mK!d8c5TK=MVNrm9B|ABFZM}h7%P`b_SoN)uER`E) zH9})Ecova&MBo6ng_bPEtwKU=5-BZQPTputXq~;+}D|E*+>1cqwrxk_@j56stR__&tfvHIc$0NJrtNw5Dc{ zYrK5yY@;-rIdD##sPw@@5Q{^+Ihd25_j!PHl!jmric6wn@w`DF!8d}o ztOU-82w9{U341LhBxDFPP^)Q7AWDhU9Jst+5Ng!}-)YB2Xzjg{G=X=P#qZ&`2;gjp zsEY`a7D6%>@6Y@HS$hvpM18?{+9;>9y}*`@IL6TLjevn9A(~AS9a&ybU22a!O#a(_g3 zFWW&W%N{?ZmG&<^JqIBCc^9FpS}4E(Ge`xcPfPCNeI5BIu-ixZ)*Hv5rK9g8+n-fc zk{2^~}XF+{M4Cryoid9u3ItqnB`DYbSAYZ^;7q8kE&j|sh(4ewNiBV z{`_`W)P(O@qLbEK+#jtvdi5{m4ZU#Msg?l_`9)p{+OOLo7#;Obv_mN?Tfbv&->6mo zj`2{~y*5E=z&Q^dYyA`V92j(Tyt=)f9oQ27O=a)M!CO_b%cstUTsL&83GYrMVSnpn z)V>*W@95Pne3lP+{fbh9Px}+rW!oW%L-^O*WdHAUM`+r8-L*+3I={1N9{bzT|5??J@kKrh2n3W%_(Q|0P9pQU;f$9j>2P*V&hsbQr(WZI*0i znl5WL>?kUoKQ{cmv^!9brgUgf*2`@DqQfd*wY*I~HKpWeRg}WedkZRAcQe=VFI!G% zySOP!@Eugvo|fx5g8TkkQK8&&gz$t*bgvXU-EzO{85j_1Tm=++Xq^o_Irm%qts$S; zy}zul|60$+rm^+H7}I{I!ULgMl*P=4zID%SjkUesI%a8eHXy@<**VR0<`4Oq`GB(u z$A-4}kTgg5_Fio_U8>BcbJ=vMS}}Xtnv?MHm3$|!<^4h9ywi%- z;gyyCa&4<%mIz79@Y#238_ZHZ(E}8RWz8#Seax0fNQz25@~$1BaV9-3RK%X+@ulm` z?xLz~u61|5>MfM_jmj+4(FfM5SvI|s*zhb2cm67xO`p?}b8Q+S2Wu-*1Ni56`?l~&Ok53Q%9=j(-EJh0mGct&|k--+W1 z-t|?z#fPVV?226J-RsIP^gN)~WnMb@X}T(LL`<7~17!6si1?))F`)V=Bv=!@zXZ?l zecp%a=0=)n`{I%xeh)R)m$AM2l+t!5H6Kq6wv~?l{6VnY-*{(;7dI9z@kU=k+TExh^O2hETuA3hGV?;;!Ii-xlz| z^>sj%nwC^)zwlDdR9|blj=kuE*de`nM%{<+PK-+EX7U7%-+g+5Uy zMeg)AF8}rxFMLv#C9wH3+f7^eRaqj1?w{F;d+{Iii%({)Fz@i~|5@SUS1_{kzT&a( zIxJ*nz0@SVugx=mUvv#5*D5nyxaRKjQ)e*i^FIFh!E+WiPF`}m^>Z?8`>FnhX=zy3 z%lqtb5U%7&j>s=OqJHf}+Lg*kUV%f#TbC-c=nUF&)(R*1|L&k`*n0iIj|AbfmGY9C zkD_^0jCuv<8c0nmMO|$TwBq^J z6f7P?b-yP&OGKVFOgPqEqJNmQyX^-q!Fjx{;DO#W?GU)JX41;06p2G|z=e+^>z~Ap z;``9xb(I{GE-$t{VV86=!JVJCeNjcHx#yfn&hEcrNDmo?Y@CbJwDd z=*M#2uD)q+6XQ6kU#_KjZ3B*?p14KBjeoyd<9WLOhK!_=K;>c4=!v0=i(}%^&gpI_ z^ehfYM<(RH>JqLRnpk;F7tUI4CY+;jwc0E;Kj~-Dl7CI-rnVG^uVFofbk7F$(A07m z+_Hbpg91nEsGH84-0gw^cxsi~E2NF0+M`;JE+y1ReOp=BGpYK|LWe^{3~Nwx>vo4T zwt)Pjzo+4&x)M(wZE$4o(P8QKVk5KkdYwrl@BR4%-g(yo z2l<6iAT2x^OP*2vSE}a2RkLm9tSs0*-+>9oktr!!dZMsqG4<|04^9+? z+zt#_L>&=f8H8!;KiNY0G&V=tT2YdAS#&daEdB0xmdIUs=?nr-VOA`SJI^J*ubKc? zo>kS1!tSO8U5-^9ACC&NtV73L&bCCCBRX+^U?sFHIxS|vb*MFu4F;9ue5m(Y;QK%W z1D(GMXEWv5lBX`~P2cz;7wFqur$F0|k==&-z=MN|&#u zjw2*_wb;ayAmv4J{YNDyyTbUMd2QRB*Gl`H;F}_N?GJQ)7VOdSBRO(P@W$wiC|6x; z5tyRlzviFR6RW!CgoC!{y-~k<&_VH(l|yAOQ~k$@FM?eDjRDu=zX?8jP@}ZX_V&FT2 zZJARNIvvhF49+XkqU<3~7ekyF`7%#R>x8wEfB0><`+D)pfz-ZZ#|vwzI&+^7yu3o9 z5FGr_qVrt3?YaKLN8M}Xs{H0_#286@7*eA61`j-*dH-W{AC+3sF7=@3U%%?TYz^tP zO8Ze_$15iym*10nTyMr&hOkCY@Nfi(TzN1{cmWZP!=mNP=Z}z|a%tRHr_qn4Y9g6z zQKVY2qvbK-c2=f;1zUY{`e%}<^n=+C`n?eymfcpz3kw@Y>n3fOjZ2c3vR~5O>)Z9{ z%-zh{FPY(t0_msfT@P@4-q=-Cby!-5CeQKn&XPX;3cZEsiNEGj-7y{9cHNKPY2xg4 zcxvBQM*u3Zu1AKoCOIx7gjGmWdhO?OC$@DbNi<)&8Do%v#V*5^$Nq!YB{uH{DQW&2 zQcdhK6R$9zt$cvU+E?jRSA^iNV=P$)gz@2W;W#6SgSfOco|U;mNuL&5^kt98($$Jv z{vkWC1Pn>z+$5~p3-6&>F9rjLAZw?Xwd6qrHpyB$zwSTjj^9B5_Z0d$4m0VdExC* z!6!B;<=4OD&oks+AtyRj zz9!ej#(fY}`hQ||x?P=ec4fbD=ZTVwOjRs8_E*}dKOju{+(5RiLYvIh;LdM0-RD$M zp^wh!GS=})*xS5r-T4910ry|;zU%I@_4EhDoz7YdLc{GLZ_21IeL{?uRj+7mbP$OJ zvWghfD}>o9X8SiQ*$@-jdgaA$?l*)x7NmdTsx(QKH*36j&l+)B!H`Vj=ss@aO9t%5 zQ4g#HgdGCNR@tI__R?tSJz8f=IvV}^uS1gl*`LWR+y&ZJ0#6?!d4ONt>U@!GXuWVS z*!4N*)h9gL_mp&<@$3>7CGjbdf`#6x^m!;w0TJ_^#0!;u`mHN#=jx`MYh8Ha(#C1p z9e2Us_m_AEV^vS*>e>oD{bGDS!fa|e!fMA>y!QBS^{rbZ1qRzYWuCf^Ts!gN9ASQY zef~AWqDQXTEt(iLOj1^7WDqVM*3^je-do2qHQenWg`D#rBLtfsYu6on3z6#=7BB zzT>uS4K@=_3c*3Q9!(q=)lNDyRYA6Nt+K$hG6-=WT({i4N`6L4`^QXuJfZ4 zv0v9xjz*svDoF^w&2th~)6Hh;%J7NnP(ninL;IkY2U&W0=lPmCs|Run`Z@BNT2C4} z4{DsRuZu)h;}9h}^38CeT*)*dKl5kN?x(T5rPL0uW?HVhS&cpGF|>$J{U*GR?~wQi zj4>i-64DuJm>CL_Yy3ON*(O?Ah9L6RR7t|`v)b$%YCQaQg@wzeo7}1JRbhCJ?(7WR z$1CK>I?~qs>EdaTA}|X3UD9{vA&F+-{B-13o76WVmiMS}M?na_cSCH8T2AcWs{*Ua zg&tKC?pf*Y-dv(1xy8dQTEtCGQczpbz$SV%wy7a~vlgdLda30pUw;4A1(x@|4NWy^ zl<&0f)Yi61#Fn~F)p(My?D z+f+&po+c}HIPI>?R?#=?T`PB~#+f&N-t0|Q*Bz;XB}boDKD<9zOeCY(OnZKPdX1B`za;(?uV2QvdZ66-g7-yxMm{Y5 z9Y}Bt`%)(A!TkJX|2KmgDpFn(?qsw4^_=hx24d-?#bcYFaw02IUEEJX7ByYYmY=2W)%!fXGflM`Zth3(ZJuhgt=nx( zjygo`tmJihVsJ+y;P5Tx(0%HP!)(*-T)0O@W^Eg`b8BOlu=3+__c9bBC$iN#>)YSo zu&*ND7*P+`$lrdVYtO=GbG<{T7OCDu&|Z&>DyGrHY?bKw&=GM_NwW&bt|d* z)ZJ-T$`+*Hh(Ph+@EjG$U4O&D#KLZ;NO{h*c{#%>q*iQcp9PfD)!sy@N#vmm04x?`Q6m3RdJr1JV(Tzauf4X4Q_JUXEfJ6EM zCHro#dR3J2>}Sd;y1iUb3*4@^`GDD7#G$N6YM0Ed&brJA!6WdAxZ4idN4v;3PcPo9 z6-WMvMD|6o=^?FBmaasy`%Tbz33N<@l|VErHn+kVa-jGLs=7@@1$5I_EHh0zd1&m1 z4vN3z3oW?JB}*={bQeb-)p!5nQ&GalOVvz{z2&r#qFsUlK&aX5JEcrZr_6Tq32A|5YLT5 z{rJs|lqPb(6C8?qqQhH^%kQuo>Ps==55%MVF#33?NIlF85SZHv3Rg8WsI;`KhrhX^ zo2HwkHcoA>*n5$Wdsw){T&T_YqcDqFv&YMq^z47`4`>m?A-jQh3u27^)H$gZ zGRGO&G)i=;NJ&XE4f_RVOYFOVYC!K11xw|TX7LdNZXuyAebK%Np7acA=EFb?@gJ(+ zut+hP(v_4X1E3~f*TH1f0`X^7;0C$qPVi0Ek936fR;MdVjt|X=h1Y*%nAZFQ3QZbc^c`;DM zs4%Oe3XGoH_L9mLapCJ2Si-PtTtia}I&NqM zu{I3?%ZH0&26yWxKrSGfOaT4?U#4ebs@4xh-)%3oKp@^hzRjc*a20ID8iM_%GGLbS7N<%X@sx}vsBiISFN1Y zbNSA?4OYTyy5*{%kdmuMAc!!W`xA2=yj>5s;zVe;tj`NA4+Ri2y*N$gfO1?!2is<< z>jf(7X!pFN;`c|l@-PL(PQEQyP_Z5c#HXyYvvXd?m4FkXVJGWYgf|Ecb3BrobJV_* zJnR;FlcW34miW(vF7ol@5wQnw^`;n^lYoJJMIZhsEyE^}`&)&~-a7%KsUB(iNB2rPPxO}~7(7n^MfaJf886ycWRIX{36r~J)D-CXqN zerB0az->H2Z=(w{`&gI!xrsrK%R%lBgUI7KU-0ZA5d7})yF7+5YfZ1lZNAD7BM1-34VgqB@Jy@ z08@wuOjgSp=zLII4vY@qR5#!8MHE$*D=5lIltvUC`M7cQ+LUClK(tt_{BLK~tf~{& z(~*ZRjYVbbE8m`>6qrY`&V-VN_X8^vPhaXYpXP(?cDUv88r>RWkoK4m9#RgeP*T*8 zm?SHUR-dOw9h7dZ&L5>&4*AY9PBz|1uAgx?HN_%cba}lE1?^qa{6C@#FEV`I z^lZIkYgE7QY>9}nO=u8GBEz2J*Z-|4UDjYHqkkcNj*X4{;Y+vpl$3M8E1@+f75a7o z)B!p98sNeG;mA6_ktT7m8K zJq*|phyqFfxa8zv(amLYv~R6@0s(3Un(aI@b6I!ydyMe};${7ax=x-~i)lh43?sqb zyYY_C5ACcEma9KPMhrhHFb&@cxfy#Us)1lBAaw76lUk!nEn1)iu&NNC%tB0C)fW6d zf+>4I%+6o9@G(347<&IigBzE-#S}!KYB5nt5CEK^qa)450SytbX2O_@8TTtao=~D| zcS6*;u&}yY)3*B>Oe<`yk2f1L3k!CQAE;=6lK2gf1NykrvsS77W$rbPV`0aM?mMwL z$5VOF`fPOeZk&@%*2unpf?zSgX#d(mPVq2c`FB7lL+}6)lVr2#TF+sF&Wt6dR?80) zfJfm)uI@MS3QWz$+*4Ciz&0tRYSm(a--KOGc{+-NPqJ14hD1e&8u}ujtzM$79^67FVm9l=69uU>%6a^!8fYFv__?< z|Bja4{=)KVc2+1u982kyioRn%R;-3hWGIeHExzFV6mpVp<`>7vSa@@E^E4UFBW6-3 zcYbBk1tDqAd-CdnWk7y++_^mY%O|VUEm79hG9XbdH2iT#3$@eLn)(x$4s5%0z%B7C zpa;S6Eyn!5zMP@8=XQExI*wRz9Q$DmN!$fT!Hp1(XGTpiqz}iM88003dNkJqoU>`PD!;X3UTC@RDfw}r3<2TkGOwf-0+=OvM|+1QoCv?r6ygN;FsKh31_njt!m%CXG#A>oV({{~q(7g_Mj@4ir?0QAVG|)dTbh{iap59IsbH&KYK|!t3?-F+&McjA3r{b~KDX4sE@0JS2Q2gpJ zW@?h{KS*0ZB^L^1gS^*Il3d_1LAc&m?;wG%eFLowGMW?6K{A z|FZK;q2)J5XEx=uZ+o(`@7?UFI?p;%RS>wc)og>d`Iw&01?I1GT$H_T8?H|hzAKD* zT3ie~;(GaUUdoQFM4uAU1u^sXsxq!-CDJ~cLoZr8FP_qHy2dyh>wCKWzFp-xo%40U zIoxdu2Stp}v^voBN1cmo&ivl4r2eY5d~@Q%s+;={J3D^moSM6FSK6!UkN>-aQw}|* zkEnr<#>l1>>y8hFg&H?mlN6ZX#`ZAWe0Tcn*=GR10GzzH$7R#$^Tvt^qHqGX1%%Aa zA~6+}CX4ShG}Ppa;e6(2U=b_o>wTA&>>L)SWWq(9egXp#D;rLLN%oWaiDTx50K_0x zodb(gI=GUw0IL1GHY*Lnu&qCz?l&F%E@JhIzk@Ezudw1?M%G*Qe3m+UI|AGUvNr8B zq$b2~Z~So={R3RJzxY*RaFYrAOU%hvbsWoN;$ zlby0S!$2zuv|NVC-2E)FWn{eCequL85yj)J;)nR|&_DP0Qg|nNY4}+HSF=Lat}~2B z7k>K7CDV@CIDS&jj-aZX>t9n!h8lfhk=u0o^u{l zwx`aEMP+D@oUPp7N7J=Wxi@BLUQsoEXrkwa#4O*f^WWNwwx>?LSP=7%c>bhJyZ>mA zyYh`Q+aq2+JUz2si9dbn zxASuSiyS$-&BEO9VTnVd>b+OSC*747ud+sOh*{Tdzk9Cz>93&C*z+6Cq8pM=&B?&m`5t&V&iRFAI_e?4=x}42~LFMF)^W4g| z8r%QbmmOya!#WRc2;LsMr(pdkEPVU8&kBY^Z-etL{9%UR$3?D7lS`-d2mHvOJ= zFlqelSvtG_ORebfpw@l$aeS=rS4nk^NNIGGdC#OS{T6w$qvt~LxvbFrx~d1Y=;eZ} z_a|0K4B4$(X{7$%cC&a>d2hM>?BrVWO0_nlkV65?9-@=#XpdwfDq^|ko?Gl zKLLzrY-~&fs4p18K44;~J%jo>C70BV8vwdLBiO67wd;}k+GApU*ny3Wjes3C$%@K= zmDZo$ysw1Rz7t!f5tLe(IhTbmCMmF)yo(_&L<=?RTy1>opVFLAdqdDuZpd|)ovYiB zC)m%A;BmzC!UGaV*Kt%IXVXRz6=2xp(cgyacv|8aFn7^ZxTnPVWiLp=uol;SsB|!{ zhAw!Uj&%+yJ^mQw1&UQxWSJg(Yv14TA4Z@<LH;QbAv#9^-hF=f1D&yw3ADkK;J$*`3~NXpRPmQlc$crq)NP zB&zZbkGa#_-4-WzJN4~xHm%++h3PbZ%EB+&S{sAgacS$q%8$E_n>QHpon-zd?9+IJ z&p_#hzM;V#L0-Ky^#qMyt7L?pFpCB!hLxzR=U;to;8CnyrlIpNExdcu=(SF2&)5Pp zpC8lbgqQoX$Rgz2(5%)x+O(E>A!8DcBqk^42`S5Q{{CxLunuk$M&AxC94Gk+z53RWF+qh0yQ&p2C^~ukP*{1>ykOs_$yYCaC zJA{?K44+A0Vin+4e*ka!pWIwg2q_3N6S-bd&BY*C%fTz5b0oLp16~u}9fx2z;F1)Q zoXihxF|jEC@BioEV3m!>AJ!i?{wU(2QSyK;NW^BSsF5LJ-~Ij->p$`7$Y(LBuy!QS z1iXPW1T%19Fe_om@d+eg?7{o?_HWqRp5a7*#`=9@V=$l{NQLL%Jwo^Gv112tFp|<< z6=pH52`$HN7-`r<@CJn8E?fi2ossb1f^Dyo3_B(!2JoG6#X~k+&&RLy9nRgf#E3^A zx9yg%?T z@%)5^g}1P<_`u5pwD-xej*i6sA(=$A?yy5%Pb>Yu3_apO*jgPTm^RF_xQnueb_bog+cQ0kO07^aG zKHU0qC@w222tWI-tgLQmsw{-V;~o|?y3t43-dh{9d$u; zVKUUh1Z$RHI44@?vhNHf@0ET$nL4&=i=+wNyy-tto-~@z67`Pd-JV^~6x)!eav?ym z=^_1qRJ>Wk?i1h7B%>tVWYE67H{;gI==<{q=Vmt2uimzE<-3>fkFfhf>W6~#xQ$vR zTtA!Xa{cLP{ruH_@L1My>gUdX{3o9tUOy8czqx!)Z+4O`W(@qxk1rn`@k`E`dX~F6 z*w-jWHRVqZC!y|(3a$6Qp~%3O`jwl6k$$AW8G%5NKb)yREI*mzCH zQHdqr?f4##@246h=xIuqL>bL0C^u$BYjP|NjZRHQofORteNZUXd&OVPZdB~GdVz$9 z5~--uKHW_nL!C_-?-aVj?eCbz`j5d>TyWU*nwh$ zj!~bh;V!faarKu(vYH$wzk^fEw(3-P^w$C1HQy#(rT+OxQM4l!0zg~AZFh#=CA%HV zWUQgAo4t&)Z6{LusTYJ3Qw}cQJQdC9@IHLaB%8t)#oU1GZW*QG z++EpCjU_D4OS(ID-c_S~yI=V6TMivk8l=&Jt~Q@U8ok_k@^Fi9e0Vmq;-eOOa%j7J!^q6)&aMHO_ut$o9n;78n6)jLj?_6F^BQD% zAYU*(Ai2Y5B0#YJ44>qbKt%iY`z1yaILc-xf7LvrJs5l4z9P;yIgNUU&!7Fv9vsJ| z7CHx;mlq^<{rBCl1ZqJr4PP_`ip&#vLE?FgOQ2CN^U)JjQc`<)d{nz(J*7rvT5 z4p)8Vaj$-R2U5lj>Qg*PnP2aRnHpYC35hMnh0Hkljj3^nyK`;$3^X-Ahkd z%=suC^X$}1_il2lE-rbzvx(?wOOesuc6ycV6z%)mD~5-2ZMaSA&-I)C=jL8B@r=fy z-Nq?VW%5ERS@OBZ{tc)4XD5em%k`ghtaZ^yvwp8^_@IyGrPWe>{;%SHo*jGa^Jm{9 zORWNB=Wmy$@`ku98`d27AklyMKd-oV73FUp;1GJo+3A=^*PWlz>ve5BZ>{eb)VrbY z=r|ejH%mBmB}h{eL6~i5Xt!$n6=+%abaQP8*EBSEkR8o#7JeD?EE5%mOwLgBuJ+#({uq)p**3{4oMuN^6OITwrMkFw%yRF-jEyR)^)P&Fca zQ)G#Z)pGXA0p8g$K_CB7d%@-M#Nwy2Es13lpDp5+)i$;iF8>qVvs=6{*FpTDMzG5h z>|0!30mo30;n-4Q<>$_KO-|y4zZo-}mLA^=Rq&q2cQ)bayvyEujeBGBIcH}vG~Nq; zYE^`a*~OIkEq`tVyy^luHL{Ql`$orX$n}v&z;$qoMEFB^u*QDXFKrA+ivxJv3C*is z8xJgacB5SkM7befVT;F;%{+5d=ZE}wMFjJl=f$#rogWVn%3FI!0yBX+W|w(2`1-pH zccDlscw;-)pRE?`!sP$zYEs7MXnKF@yYKQTg>5psRrMQM=(1% zQ^=0$>*>3)mAzMHOkLYrCuKkRJN_UW>Zk5@f*7HaK|2l-*6l3c9b#bxRg20+HJR;T z^1s;keLp|hXqAhZEh_rUx4)QY$EYQunB5~P8iL0+=~`SiO@&@A+_E(I7|~r8h=>*N zQxCN~8der0+27lhs>M%pcU7Dk9M4atYLP=2dOXPbQrEFUjRZRFW8EP-gjY!FXK^44hp^~gK&%Wl;U4lj%H|11aE$s>PTp@EqDws9@eG?50 z7We!2@5LtfP__kfM{DrG>@60WJ0RY|EVLIrM?*tdpn1IM?Y*8a*av`8b*m_}<`5Kg z_xF3l075I75f^zX+E%Q|kL9zXkxsWb?C#ca!oJ@6f|}Yp;Pm%>eBL!?_g?FOK{tL; z((>yQJoh6Gzf|Vzx~HyY>r#}JD1R&sW^%a%Kl zfogGb9CfSj>fSE7@IcQxEjhaD9fgX8ull#oh^*}QjgwnnBh=qE&Qx`t<5dEbRw96e#y9v!FHUY{Fc+bAzjvKa4A`Pyqw$)J zNf~N&uJc>I*oZ0kElFu+=e#olx7U5Gikbe#U((M5Iq0^0@yyfvp*Nl8*)_;~dR#GF z`B$o4b8N#^)dY>JZDCqPDg2+_YB+8*(&6Gu=Ob=Sqx2JN7jO`FR~oeuj{M=Ia-Uhy+bKN%FcOn26u4M%C$R;H0x z?iLSB?#}XT4rpCB$*MH?GWeVK-Ik6ON&A0yjU4C8oQ?WKv-Wdns2W;AVr2(GJ?EZ1 zt6%v)t-C4=V~f===PYk`>VSBdv)FYi29P-HqoXMdB?7hEtiNym! zy%j8e_XtITP(4na5`(b6yuADYhjaw43{qBNb?&*)+7UXn3iiBv;g$`#=T@M|=&+8c zj18AF8-lH&=8@89K1W2cAOWD}LAT!)m~z&$+ZMRxq)iKh9EmkcFqGMO)N%(R7{bjL zs7Et0hD9;pQ6F}X`=GMK14YAbZZP>JtL@3z{rPL}Y!fo20Rr{wXo1<97v<;A{uDKg zx!$O%9dxGdr)M|&HcIWNz_$aYDqeE^H<3Qbeiu3yY=XyzeWNx}<}vw5%I^2%&v)@- zDu${w-)!bT1A#b|`XSkEcks?DAKP0ekEdU2jIMK0(GEIm6|r>WrK+YDpN`?;YJFQ# z)DbT{bDk8OT5wBlQIUE3GoAN%0sYJ?-jtWF_0pakFCO+g?DU!V*t)P2b-=H}a# zh{cr`AE)x&a@E4a?>U{@Mib|gRb%n$=u;|QagTs`A2sf<;9-3ZT=_|KO&WSyqz`76 zEw^?C`G#HrJ$4CtdcBdUz^TR8L`sy2UgAV!4v6*+po-V>qs1b-#%5wS zZI10(SW$T#_E2F+;YW!lb=0-Gm^zn>iRrP6!>TTYa}e}RT=-@t!ImG{<-kuRKa3P$LR83G&~lEy+Pf^hMt#?^NR=U zvwFT!Ut3w)ugl??Wl&;ldBHnzP%V>Ax1TNSG*aZAihEs))i)bn9^5MN-&-Bnb$qzA zX9T8Fy~4^fx3D0@v&*l?fiC>W-%kaXFXB7_Bcg4wbsymYc)rx5ScVmSUC?eo9pQlY z_(h;_2QK71z=$j=0>}Z;AvVW2G%+*=9kfsC%2K^wlrO+z8(=PJ55sUZ{0zIx9W+og z05#_;Dk#uEWDCu;psefKZg1lGFX5bmka;- z(2PF_1DMnL`fT2GY%#B11whZf_0{@M#3Gf{;Z;@dt_o+kPMO1BvWnO%01zQ2I#gF` zpI?F{c1__EMf6Mn+{1`NXvbz^mP4)$@BA^$WdIyiLhp*6(+l)Mf!YW`@C})-zzi{j zLWc=k5niubwr?+kTfoLQFjUMZy=>U~VkQM>DQZ9HhUaeKeE@~D2eip^t;P`+*kr|0J%}qG+AldbrI3(*y4B@EKTwEWsp-4b_v_bsrfG>O@(F&X#r>Q9o`FYK6tg& zsq&T2B$Gb||=I6Pqp`$o9NWJ-c`Fn?kpPdP}Q*5414ndZ~QM zZrq_DsOBc*n;^;l23^ptMq}j~s`p-}Sj>$Tw7ZI;6DH1VD5QT;j2www1HQ_7hBvzB zjnXnpoeI5A10)dp(cW6Sf1i$k1JpcRmE9Y5O0Wkv)#Ou>ze^~6S#}xw6^f20=`#Vw zM>!>rQt{jBh^$g+O`ZN%p$|?!Twz3+2;715Ue^s^{MW+1{LKBy+7bDNI@Xr{VN@Dt zVd8D2L(N)tzdPyP$+ZpW@eq(ydeiOzZUPyr5TJH>1{iQ9LZDTqvMFxUZhS!qJflMS@AvWXfQmMw>I>JXb_ zD#Gv}hbjnH2^xH4N(N?Vh`G-TFU*XEEZ81}pB$XOpe)z}Ln;`7UjvbVs$_nUUr;aa z4ffty4GjkK>`)l`976XB&K7so65rR#JSLW#ZT_dCFJjySP!~*QdrKV19)*VbG@8rCe~s2k zR!!8HXvpa!En(=iXW<|GKr5MN_wHNRd}3JxDHvCD4aeXiu(3*(rY{ic8O(o_a7HS` z1rmWd+GZqrP?2^TQW3I!P$W3OAsRcdC9(No4UFR9Hn%ohsR9!z02&5;etbk*TN~wq zdA4pz6P4Vg zFy{u*q?bYrwe;Va4jUhEyes~^eVoR{P5MlnqwLUjDzB#2$j-M$@=N0)_0kv4BC9Tn z+5X)1s{T^kWrvfBH`mQ{S~nP)(^Tr+j8&w4)N8vmN!71pzxu!diFjPqR)Ejfh*@%#|&)1;~}k>!mdC4EW} z&2lVGQs%iYXWj~$^@=&Zh_%>zd6;2hCO%-gj+NoYAD($@p#;59xraG%B}E(bRn$Fp z-&MFPc!rhE2DeCjAgO%TMB09sY2O5IJ{+8TZ9gmHk-y(<> zr74()L}wTu;p#(@D}-LOJp0;$5S*d6{{^o-nYpNwxAUBT$H?fMJEu;EQ4ns+t9;8> zeY<@S%%FZu2wRPwCZebvhGD!=I(POeu|R%Ds63#rC8nmDfTt`Vm(~W~!ig14K1L*J z&!ya$ys%feDBDmuUJH{Wgb?^s*$J-OHM4zq;d@>r95=5;CFjE$xq6SaME#B%79O7% zY1Wo5w2$@7lm2_pIkn`*%{vZxq19Ar^7idpx|5Ik`rnJ&_6&oP0%X5}Yef}luw+}B z2(qz>71q__sF|<*!o(wv$CbJ{CT-&fwknBqSTIyLdt)XuK1YKDgN-)71$ zzdmFh)GdDt2iF|S_B)2VnGbTf{t%_N*QZ4V0SNtc!^qcRO5~#rEQbQ$ESCu}^h5T( z1u508ZCi6?;~dM(GgdrqN>OH~9^#FRgaW;XSC~>jENqC=O0%J;;vTA=x+8v~ zbABu=p(Qm|4c~u-emGG_zKa`1&Qs9Eu7FEvY+~{njly^V2^*NE5El*7ntAu`6ynhi zQS0Y2to_DqrkOf)X(+hwZQl6~cFvt&)(xM0oRdWrB{T6~T!7q2zsk(;$5&e|bF^|T z6fG#(VHW(erkO3fa;%2tzJD(f7ZnxVyzaKlvqp0(rz#HNwRB+?n=hVJKRgQevRr3( zKmQA7wc6{1%>3+EzT~^xq!qt;R%5ycq(Io1wB;w2y%@PQZvSMu&V130{)4pH29J%a z6U98Ysmt!4AK#I5_%n(9T^#2hxXE(|azDzBHS4+RR#Z3>Gdb(|&n{1nK*gBJ_oB|S zxz95k1Sm&YO=W1!Mcr)Qsyz2}*+28JgMad;P>*}D-*?{@XW5E9I;lasq|rAq))2HR zbrR#3ToTY#Hk{ll^*nibUzStN`9a#}28FkP;dc+R%AY9R8nkQSAd`%hH#OJij}Z)u zPRvui<$3dKRZ%J@W)#Vu8WnuZol&~DLv-cht@ZwPX(J3qW?X^BjQj-~$x$V~Reqbq z2pnw4?FZMeF4xA8=qK*io_H_`WHrQ=y||V%EkEM9}h9G4ptAlJbZ98Rv$nuie9x4!hZfzBXRiwXBCNJ)!X-=$4WfsXJ%#wqSymLkhnNqWl}f~_qWpD zn6~1uqmtN#Ul#seDh?}AQE~*8Er*NQow8mq8u(Qtc2-`VI7FU%dgv|J`JBt;K1!*= z`!ZAtd^3FoB!zSrEY+N9{RQ6{kB zXGlYSDO=U&8{RebC*FUv`14GFq(Iu|wt3WnH?o(y9&0N+xnLN!McX)24T^OkhzP8^ z8icZ#2g(Hs_BioEUL(&es29LZ2_$(@WozpN(5W9gbiLm=09s=pRU*u+0=X&mfF`(4 zV1`s+WNcQJ#;O0U~oT%JC*=?WRyT|Ga$Kvxw*M(%kP@rkF43t(30Jth~SyPzW^k3$0{^NjTlSkG#0;D;gcV7JZ{L9F=p>Rk7g6m`6&2oKCxd5s8Iv-U;KHXYHN}9u zDlq1Z{5ms@7Td#T;7?^MlbCyAv64Do{dPT7Fi?bu_=<88=|3l&gd9F*)t3 zzvOstFidU>q_*VRa6rA`v>}ZQrrojm9#ds%tI<(1EcY#lB;(`!)tgk%Oat#jB7DjJ z6ebU0)evgCztr^8wowedCBhm+AROZ0s=}NqH}ua3%cGB1$$@2B+b9iL8|EgjhW@2i za|D0vooVLQojY4b=Z1a2u&mtJQQo@X7yW-FF^rEY3H;ko^!OoY=^pZZ@f=bbu0UjgLK^Htn3# z3wut;C&MxI>Iv9QM#3zpDwj{ejaX)MpBHw9cSSfO14DzgAXm1ofd88U&>Z!XPo_T9 z8xZ>M#^`L~{S$%Xu`akgLLGwBFAP3aFtQMqwta_I{c`2szaJ<%T2qw(h}Z(zHffV7 zOXTl{Sr=@?LIohV0q)*VH>IZC+e;4LzyB>3{e5Ag(*Y3o9O&Tp@4DzM*|oo9$>u>* z4~Y|617}a4zGE+fr344V<(~9E{R#jJFvo?QJg^ib8o}eomqV2zx3BqGp^e6?+?cG4 zB9E?e2Y;2cgFvIfr&G*3rXQC+j0~-5^FqUt{Zg~1aBO16W_1&BT^s3h!M)CM`U_k0 z|GlVVe=n;3s&MmxM}M-TRCr1CXaD+KsuuA}(>vgxit7C4&1sV-YfsL)JhD7`csV;_ zbUVl1ZbQ~z;!{F;9$i#QebauE&n4)!OLOA0ulE3Q-h%R)T}eENJB-%%HIrXqyv&^6 zM-5G-CT5O$w_3ISB#U>Z)^AL+vqFsvrY|#TKD+XJFhX9luO*p|yXAmseQrs=-exb) zNaGvb3zE#FiF(WSwu%Jv-#a;8TCEaD@0I=IzFPM!-*|s@-^ln*E+gAbSD#7OYN#p< zu1}X>UQy;#UWx!WL4tYp#RL4fCxR5H)8;K0*!En|uNwdIZbwyYel$R$y2g%HPzLGw5Y>N!oc4QelR`gEe{G`W>V=yH%&W|>XV}g2)bq+ zFEe(fe>2c{5q^SWtFN;Eab%!(y-NcZzWka@$V!{&?uuPFq#10Kd7gK+?<`eOOgG58 zZRUX?wQR9_53>0c?z_2kChEHV`luXE*5t|!+cZq#Vx}g!qB_Qvlxvc!B+fWqXQ7E( zHOB5fzQONWLVE4-GbZypksX8idrzTt@>y$>#j1qLVy_x=*~B`PN7r`+`|@AfGxko+ zCaTAKHIT)66@4xa0(ySQ8>0Td_W;|j*pu#ivf-AuqV0ovje)1Q{0}9k^UB8AnTdCu z3*;5c3VXA>hgZtw{=KBLvplpP_6R4bH=k29kU(LsQaCt1B(j5fDSKfT0}1mhCYMhK z+A6kVp2D%;@3+^MYxD5(-Y0z;<_;AEK613;;3tE@v<=;fZ*IS7vp#(45e!Dsjyv(d zT+-LypB_`!(6;x#jAIxlU`77yz1|zk>gwt)W5qA`?}F~oba`=Z!suk)BedlIyPe~j zVJ`wQRONh^jJcp`*WieMecb-1&zE{DG_FLJ9XSk6GZ#n+m5!h)zv%H^`nAUmU~1W2 z<&Nl*7zQdM9cnaUdveg<2)Qk%sNm1>UW$8LoNmos0h>!gO_zn5)Mjf!P)Rf}_NqF} zcI0`V4$O4hbkuhzLsXp${=>aTD0n6l3DHU3{JNIag*PvOzOPc~Xub8G?|LV->l0f* z9FjlEZ^lvluu+5FE1K88s5p`ouq77`G>Z3Et|{h#BznM7Aqz;%g9 zJEWbK+rXL^bbS>_+nafqE6@7Lp$31tuj}Rr1IHW-voc46gj;}oq8gewWwK*; z6^8gYHko9~ZaWoN5q-@r*fU42x2x%Zt@9K&H<%cEx($b3hYr@cE>tf$In-crKUrL{ zJj2n%7N<}%=dW#)D*AEiZ!pu#x0o?IxIsD)8Peg4UQ4VMtc@5$^RcF;7taTMH`|_% zk616ic&MAYmzQ@#_WbwdBsVuV_?0`fYZZrqlp({}CntLO{RZ!?4*!#Bk)^|ba&~UQ z=ixqwSvEQoC_V6QVw(4q%0z4YY?QirWUTc5>y!nZoRec;VN|X0q9Q~z4$%OePyPv zPd|&o%pf=O4}I)Zh9@;)6)KLdZIc<^bUHy;H|E0%4Fe5cUTo^ewFkYjSKFi{Zzxik zYdZmyqOD;%sba1-{!sCqWx`uEn_u;>uco!8I!Q9?Z|ABs`u$+|l+s>GOlPN(>yH`F z3Eq7m{D6bC{fpC6bt4i&w-gM1|DjJ)>dfT3Hd|K_nFe@P5U^&8_nr&nPSLXP<&-nx zs0n`Z1T%n7LO}_N2VAQa;#PHHF13_GoclOvoifoXIEV1m0LFbOE;Q91eL_ZpWu|zrDrE3+{fvR-geJ% z8;)4?~mD*h13`j@dVE z?6Ob(mwu9}MUup-DlmA8+V>lPI`WF6|HGe-#rdnonJod_8-o=Z2ZkDu2R?dq(;$5x z#+l^n_T5N(vs{4VMF!LoOOIt%L+$Rd+kb{e2OSS=5M3qexe%1q_aJWVc||$z8!}C< zt6wHvYg@d%ap&PD&(m{kub1(oJ=+x~MwP03B9r}l^Nkn2VV;L*8yUY?P964k%5UnB zOW%ou#9Y)#m|gL!cKhu@RYL=AX|1DfpEW>1f5zHVF=A&o!@cr`c}F#kDz7F;qMgka z0ea~wi9MVFYN>A{*N&~bN{LJd*|eVWJ8 z{7)z?F{$MyH-!qwr;v4<7_b9ksf$#zX#Cx#iD}fYSD@Y`{0k5QpxYtN0x${oau0>i z)~1BCG&$5=@zP8GpjdzO@#D)~tmu6b<^%Hi?QCo{DCx)~6&J86sIh|1fTsX8noC$8 z+QFcE+_`)AH$-ULwrn|Z>eMRGE)b))0@5Ih35j|L;i6U5;?`X+1%g(1YFwDoe>qd> z72Wvd(s9i7ocm^dTd`-YqND7;B?1|xW{{m?)uCXC9%nYh0b%`di= zp~oB#Y06MJ!*am|{}XNt$Bl7nVs#JlC^k)U%?V%34uNmA5nK+ywm7=8nKu8WyUG#qe6Gf8|bUWg352>gwbMdAwq4^FW zkh-A7m_$2Ne!$;|W(Z0Ej6{c5fD=cDeesIj;#_-N&C$Y)mQUq+Hnh<@_J!Vlq#Nk5 zb705a7>8&XW(if*hiOeGukC!aoyX_?*H5nl9zWFUcNM(%<-^g!We-o!8=sGlEWEA> z;hxOvurBOfa4nUN9OIcgUfhxHk6;lL5O6W&INuO#E1EFqE}_hO#9d(-(^->iX#Yr5PL5QSor8SD9^cogrm4t!H>-*YZ_~Utv!Qi1!R=b59!h zR6E8^Det!r%D>{fI4Jwf)Sw_{IP=<{$-o0ljFF#Jl|FD)PFF{sx7x@T^DkDOPpX&c>KudkCG%7mT2`0^*w_>_iOv}RejGb zEAbiewB+Hzr|n|wR8(UAsaAQ$HYIZ}-<6GosCZya31ip>n!RV>W$t5U+KaoBjIlE2 z0B|wTFOl2qOVmj+%^o+&G<3-qt_-aF=dq5U*NL)f^)SoRdD3X!h!*iA#7s%{W&OU$E$4}gPB zvw3ra)J$6}E^$8?dd`ccNI&cGmNha>6|H_0>7eqcs;pE+;LgG({R{A^@Q0g2 zeqp)(gY7NK-s((4-wI6lYCo%A><;t0SCcI{r8b}B?`U4_8qC1-vCuVdRoJ(M4o%wR zJ(1(`BTuE?{%SUQ5@shanR6qyYw-`wLos`z?rq0vZl=CCeI zr5To*bk7l^iR9Mv((WrZR*_SodV1{)Tbs+ytM)xmm$nShzL;>sLR6Su-;R0VQ$ulV zdcC$l!?ezJ?qp5PTNVkrJqO*NDA4?I9Iu`$Fnh!6GHZ}m%t}S2@qlwWAdrb%FMwZrf{#)Fg5L4J5!f# zC{3Au6|E4=Cl{cZg!u!ydE+4;5&+WLZlG3J9a|qE7Tl6=9}gNSn^uwr9-L^q#@zM0 zKEf7F=K_m=W*d7Rc=TxcI2TBifiK>@n{cxOg(cCZqhua~wnczr`+GbT6Q1GjGjF#YnlAu$>B1-cR|SXBW$zh(-Fr0$vwny_=!;Oui}; zpfSIT8zY;}VY;@8>Z3m^e8-@xD~5oSd>cDn1c5>dClK9|58uLbNaGZbhACqH`iJLg zPzw}s%3pJI)Wq4qcIyQcX$BZ&riu}fXlDR--wOb}@n>GuQ*A*AQ1`>DHkqHgIqBXE ztx(A3<6EZ~mO`#*JohvZv>v@?x6qqp_=D@G&)`gu!o=t5uED*`P8F$Uj)go)FE|aE zw6*i|@{{|l+WlUe$`}M1uS^`&>6tI(FLzn%J@Ary!MrMzZImzE`cue@zB0jO|6N;i z_wgRc@wIH)mhaNCk|JGVmtAY=q_^M9&aqK(wHzg5hQ)m1&33;1A2ZjBo6OS%7q2Nc z_I$3m-tURAp{#@R)ZGj3hT6lq#{z8U?lfzDD*K!`dn0Y>b&z>25<0=3nT zlFu;eR82li8Wy6coo^MS%dOFCYisEyLgGF}meo$!Y_UJN zg&WmBQ<-OrxwTfyl@DdjhO}<9PqGtKjwWlSMLg6F<*%xF;u}`jR(x=AJtq~Fiuf&V zy^IXQCLXu4t_-fTCROW>8yFY_4!6csCGoD=ulc>FU^1Aa_`kRSDfJ_=roAHP1*=Un zD=)v^u_A!cy=9$ z0*p-9q&@UVh}P8&g(G$h+LQyxlAG~RiBk_ey3PV=B?G(=vlB6%a6IW)oL^qejG@6} z^Gfy?!F;q`&s_x0wu6aMfOK30X~^8{>@Uo|`~troWpDAmg#!!Xa27EC`qB^7hwejX z0(G;lUJ|5a*x0aQ<}#T(ilDnR_t~=vSu4EwVlbMaF;V>tBpRX|TG7611Kv!fWRx6B z3-)_fG90Gq&@#vW_D090*ZK@h7hJ}7Q_>=)S3<hU=2O9kyqv)UMXp`~gXyw0zBK8-okF-rqUy_zFWgc-K!p3A& zY8I#u3dlrv`+lYHV=ijQS|5YC`&7qlHUqNZ-ku)$4ABjS+2+CA`nGEe&zjIBaGPQ7 zjBb(hYcdNO$)w)6hvu}npO25)_3Jqh>G(xrxRM!?L}oqJR~o3Wg7K$7bK^rbk78%A zKF$|RwPbK(j4Ox|F(dnY(Zv-P@3fUCDsAzL^ zrClOU9~Wn5UU6|9?ECMTSNsi}f37tmrz5Q2zQ7zV25#$SSV69R&#nM+zb;$qOl}(h z_<2azQI}_7%AR86aeWx%X~J8f;ngJ>TJ~e-L5o$hvwMx`6^nFbuSXEnlG@>6Q(<$hZui}=yj7>j)A-Xv7?a378DfHmX!Ty_v4H~v& zI*wR#bkJRq9W_97j{);;Sdouj^Q2^b4r&3JFdiXw5Zw+kuozsN81!?0k$)m#Dr>9} z1Ya?iXsbp#Y)aofHnw3|#?#~%7te3|Y-kes^-|eAGuRP?9=dc30%Qz=iGxJ@Dw-IK z(>KwDt|KOE1`)`5bVn6Z)qs4=|E}O*dnZ7Jk39CR+&=@eEnC!Z z!URV~MnaaKhM_m7zylOkR=2f%g@QbNro+<^al*VMBM!vn;a722AaiDc6$N-C(O3~6 z%*qTxI)3*;rCk{5lD2%h)oHn(dR#0hXjzuJgvQ|oo%k^jXpn49$>#1bfURmETKp*(*I1S?x3G|mgS)DxMj+Qo9d{pmWM!-_ zS4=GL!4U{-VdO{g1qjJiFr@O_m3di=g3?e?i9&Gt960<_&C)Uj6f6gf27P9_(sgq^ z`xm^EM$9-gF*bhcO^t`pS%65RV6;uo2}yG-n)65!lpqulqBji0NsKhifKY|VsP7|3 zkeIsE85{%=K*Du00e4`JjZMXm9Vl4HVk!%n!AU&?+md-;6IGuUr%?G3)(65}#jnpA zT8I!JbZdee;9Vk9s)ceLEb>HT<&u_RNvg5;mH`f!!^YIa)KCiiqIwWP8Q9qc!Cd(B z3X9DF9Z66rkmPp7jM*nbnZmbcj|>0{xj$q4T>SiJ0U6LmMx)eI0RxNezf1rK2Xv+CUHfWmt+CAJBKzyG}DD~*@y~Mq>KuJ0= zKK=z&JQnuhVwkS=C6V(hq0u(jT@T z934&j;OCjYYtja6n}u7PjI#o49j|mx3guoiv&Y-eQ(Z%u)&ILM$48LY20ub7*dp%zYqU0(ugmH!4Zf(8Rrj#3K`wId|9xlO-L{eRv8kuonDyQrZVv4 zaHoHYxwF;Cg5}GYd8z%r)pz;9;-m7aJ{hnkzWl=ntPOQ-he9<(W=D8{jG)O6)|UCV zS3eo0R+LE~%deoX zjyHYbvV%O518XR@pWS+(dcFxGI->-9dEBxt91u^%aI>}SYh z&v$lC;uUSxTZdm2WYxA>P1U)scTiQfscX0WPV#b=YbaDyZBeVj+EUb|Q?yaLQuNB{ z@tsokliSAmK}u3W6C5K#h3NGeafkvgRz%~3t?`0y7*A$eb!yXKm^w}m2rfR!Xx~M+ zMpc$Rt6Amox!(~p2uZ;N#}ty0V6i{AWgNjE zXX{;ey$k6j@Dr1zj_Jopx6Hv|&uH-&u*iTO1CeG&E>EIz|3>qUb8~Xfga!O7`waZ>3?gw(d~9#mN9aTtcoHgX z76YIZLuhs2@}z==k4=n7la^k({9P;!8O1dxCvD`6-20CoHvl!s74<43%2*h%{z5G* z+^20kH_=Oe2vt=hPFXCAL`=XXhZLc#1GqUw%Ob3TgVGT~IhIQ`I3{|rNnx%+nU1=G z0nfNxbr^eS#4EAg_4c-aYT$!AO6GHi4`%^Q zlYO+dza2LX%O79kCk9kWFdStOF@NFZMO6a}oTpAgIEK?<3lxofh$S2C1j@A6<~QXn zDLi~)ZgK{1FZFR@k#=Tm<)+??tgQj;nHMVyr7IB3K4SM=v{QU8rV32%78x>ZVrn{w zlkG6a^_!(|O+^nyO+zCHy5dh|jPnq>1V==qq2H;Aoa;M=h$GQV2E$JiMwx24 z5@`mPtv(r^ma+&aVUr=l3l+7AAm)?d;`VYt5gYKxxhY7jRLsqj$bfJJX^S^r)OeW? zBzkOGCxS(wJ|gK8DO4|Cjv@0IK?%pwr2wRGdRhpzlslYI=ixB<5>_^fh&ZkQ&=Kl? z9ZKH~Num}wQRMJGo00zhZ@xr9KE*G|cp~5O`^wy|wX(T^SF-sFM;LKmJS`{XSDlM+ z9o&!Rt`f+N^T3FZ(g{N?K)d763E&<+etwN0mVffrk3vT#xBdVW%J`3~{0$*UDraJtLUT`NOXL7|OnZ(T>!ohy1Pd8NyRJ+qyb6?T!(8MW1 z9vZNsB>lo1q0c+f3n1w*@D<0ErI}=;q<#CT1TU(ND9u!rHFq4td!}0COTn84EVGw_ z{0YO2Lu693qO*_iTL_vks_B6HL$hH+0QcNNYw4N~xU%x{<<_ao{#-&rsz90G+@g+n z(K|Lqygwx^E8HMQU=J>QA@YjEgvtU9^v zqS`c{NnEl$RvVkOWUTO-0*&By&lX)-f-#Mit{8wq^#Hp{Lr*USw{E|XP~BAxDVR>f zpH&WoEba5>pOQJEps68wAk*Jp9;w=Ji@RdsV5?=J@UOt(&(Xujw6zyZD)_%2)sDbv zNHAG%dJZj=n_6jliHIzr@g$|9O51&lyHiw+B|^^%jUdwSaljq7K){l4nRrpBeHHmA z>}KlGBFRSG1NUowBr@<|QX>~(Z$Aa&E+mWev#d@bGK={_+%eN=h1wR3!~mB#3AhrdVLZ2Olz8}r^m)?xsOP%{n%5%i~Z z&`PY<#lcJh5_CW0YUTk%Hvsiv6Tfy^dSx*)Nh>u8)mv!oRa6mw zj*kL*c`AVnEG$Xz?M}e4^0K8=$?OD={x|K)8?1ScT;|u4TG?a-)F>;7XC%q>O0K$_Q=Vf586lZV0pN~P4P|2(#7I@`<{{zXsj!Yk>MdC;Qe&RYCncqi zN!>}>=@BwE+>6U<>gpunr-U>;rYQ{{j$NN+^V@-WxPd2>C|TDoxhljlrIUp zzb|7obVnlAZQu0Lg1`x`J2-G{kv)B_t(5)mgxwakI{!Xj{Vm+o+HVoJHAWl1C?G}+ zK*iEGLHkehsyyN4so3lp@2RTqr7|AbtX1VpA^ei7@FcWZPj0hign~^Shq&I+#YZ{b zzjdiXK75rvUy?mI^sO|cGInA01fAa@WwM&nSg@G+c-Z~^&>4;uDvX7yC zB|T$H7GAK^=|hJ+HC5id-f#)Q^nlPi^7yU1z2muR_~lDSE&c(lS%Xp=KZxWI_v66I zCyI+Ey=Vw|G#zVCZlj`VPT0OeQKeieS;ZnMN>Bc5>84PmYPNnfKIU;Oxeh@Gn8?kf z8ZYFOUq#i)(mSeNqetG2hqfhtj(m8jZwUPR2~{V8dx$;|1* zA#J}?lv9hFnrfW&+SIs4_xlQhNuVZs@ALom4J79*okT5Db@}zvYVtOzsFaLk>uEuj ztkqjJzTTGP$Y;ry$CGuCt<~tg_XF}SfMoV?h~4cWIA3_o59~vddJct2q{|M`Jir8` zVCp+eeru7>(rRIK9st!Eo<(Yc_y#saom{Q;k~}M_v<*2qe?Osmv!A?s@?lFu9xVBI zehQEM??*h=>)%iQ{~!DR@C{+YNaQ2T)Ov=bEML#={3d$3V`W(z;VVf!{vj~;2d+rV zvM;{9b@<5Nrgu}6a?mm$mp?N>FtQBNVO+3<&77y_=K4x9Qp6AGTeGczQeW>VmGUFRf9ou&&Ooew(WfXy5&#?0Wly~0`TOI7jQIW4e1(2BFx0fN zB46|3zlH0i4%WZfQ0QcX_xxlhf(!z~1bK-l7+g3G)XQ#b{Z76}rAvc z{`wm!QGS-!=)LjlgZQxnITO7lRgTm5P|aYHs@ZNfeD6*02cH+x_mOQ7aINpK7weXvLioB@2hGWPj*pmu@QH^? z^eHg+e`9ayP7=S#$N!nVp7(6in_e-u=@bO7`~ws~(t+{u@ko|TUZ3w78L^7Erh^JJ z`0?Xd)Y0e{1WEP{4e_G|7Hgf^;xIj|15ff~e9Pov0Dc$jcOr=Kc6AY))MfooB_wafn;?GFQ+YN>b!7qo0w4^H2cr)gv(nj#z@bw06y!Um$(-aS><) z^Iu32#Wu()YOQhNgcnMqQI(JvK-djIYRJvkOUw8i2ht7dR|&hWJ3>FugI(%9=qY3! zLi|zCdHt-H)&SwgBxo6|xiT^`BCx-tsG;1MY*1I;X(XCKFma@hXn6tC`LH(kU}Ny| zIf-u21{zayf0+MW;BOpn;<7KVquZ4L5bcYema#Dk4T!b0t$NP@mjEwh3YlI4AW1oQ zlrbbH0zD)hZof&ug#)>h8_NXd_mMt<{1izU&2_gR@{Xq)l zAJiW4SVf7*O6j@-rG^2MU9+>R!+4{8m@&@8@Fb!X2nrNYDp#*2pgqddlG_OcBmvDz zET%(j`{83bfaTx=O*+;u_kx?Ynp)SmtA@sBARO?C06b{g)?W^DToT@X+9{M;YFqv& z%HPToTx{iW%mgKp9`3&;BBW-V0%NSfwEF?F>fzy>ghCT*n{*cJtdkr0e9L!(MF5Fz zGDI|OjV7o!0p)63x)g2RoaX-ar~=uYc?RM$iVS(HV1#LHIYSbAfE+I%%iz;gnYZP=27+hwDe)Y>F$G&vesC26C($n$0s!sb)!og= z!I4gGxIH>Eptf)lupb+R#3S4s0z?CElm}=)3gicKai4hv1Zp;XCb>TtMLX@E_o6Qc z^_RZmU;`mA5KIK@zNCbNk2?+mCPM0Kyhb1Ff<^!=)e$dGLFGe`Re~{#nAM-gD+BBa ze0lB}0ep~8pGOHxTEcdp0KYfJon^*8Ou&Ezz{~YuL+zzVTpxal8Zz5qK+ULxn>1Mp zFx!Q@MJ94zg!4ORMNC~lg>GEL+$#nF#bmItyq3de0;bU#U0E9Dry}1&xl-qgF}4Zmxo3Oi(2tFae)`{!s;O%&r#NT0U;>(|A1OfCAJoi5~inZt^^BrS{0bW6U(FpmPWGK__ie zwlNdCp~^ga5aC8aSy>xbNt#@&-6&xjVN(7A1rZVR!GFJrG{9hTA0mFX9F2<<*r1Uv zRA3gkhvY`#Mh||^PDTmjcd;91c5Z>gz;4KL;npGxu&@!0RA2`27~hkCgM~%t^68eZ zX9I!Y#N#(98PY4j$ew|V03skE0+3!EFn)6|%j9ewNsKNiFb8t1n`8NGK)$~Sy%y5C z!kTV?->u&cp;Mcf4t#;cH~7(`=vS`}`JtK%L@0j&qBftTj;2 z`zlzQq;K23i1km%EMC;Bxm$97xC5J*$9oON1rvM#O^n`>dvSzs0D$E*_CM%VDgXi1 z)YOC_gab`T9gPowuXPxnLG+v6t@wA}SEyVu-vo%gKG~N*hJU#9v-z=0>4J-JNLj>H zP~iNl6G(0dDujI6B;qA0YY|n^)@j6_BbsW(r-x1kW`Wm-DN`DR%tU%?xG*?p4`w$T zd<8bPOZjig(#%C-V&sj9e{cr%kN-j89vZ(Bqd~~K2F3@{`UU^v^9k2SzMEL~5~7dk z=ZI9?EQ%V;L>w{6UUKO!pkqBOo)6PGa3p5Aq-ypt3xrHcJ)Yl##^XSS{zrRn9@caI z_J3y?%h(2EB-yhSDXHu+W{j+%#ga8br6@%t%^*e#(kjG|HVR2ngeY1pX^|wPvXrH= zM9c4SmbtFqabLghKllC5eILi|xQ^>PGg>~M&-?W{m*?|&KF@3vH>Ze^)4ZBCYi7?X z51%cGv=YhLnRuP5nRc_&WcA;i6we;T<>jXd77}_msDUcqUiZ6wglg;Uc$@Pq~D z3!f9bM`jy|Y!+Zxf<{r}Z2%XwU{=rT1lh|H!1&G#Q{}M0eM&U5qvMu>SVti$97J?wvQZm%U8n ze#%|O`=#34zvko!c)M{JJipG14ly+~6@Ja9d)o`v1q)!z4}i!wYRr}UOcFjnA{qwp{ zXF{HlO+NP432v^>M* zm+svyYZ5B&jNw9QG>teXnmP=l`X#6lFf0L-LSnTJ%7p=wnoC~m(z)|-5#jKZx+c_l zokuNDz{Fqs7%W|GKD%I8y+y)10cHjxRff<=1ejH(ecsO*AKMTCPlsO|GxU9TwRdR= zE8ZFPLo}){VFZ7k)8u<<N%L0W_OwLt>sD>xm||#uAF*#0McNt??Pi>PQlW zH^CJ!;S}1Z^w{_kLn#A9F2sZ}4>~q{He35nxvu>R${eScNQn$5PN*EO<6syoj`ki1 zpb2I!2bL#jZgt>5*~CnOodkzn5ivqCye>>klm%DEbuhoyPuwwNWq{4JIUu|v&Do$vBYOCr47)SptSypIGYCJi_Ye_P#?K}j~_p-Li8LCm_B(c`g1AG2uG>u4o|48 zIBgM3UG*O@ARK59ZuLIuj?EMIWg%N(qGSyzc5;SOcA}djv9L?0PRqwy-+t0&dicm8 z(yq9?X}vIi-3&2%26l6J_he{b#z_uqZBeg!Atn&A!&*@9>xpEOPsumQLgn_AwIV18 z+Ey1gX&)8;(W8h%#X$uNe^4=BU%%rw);X|JsN)%{f0~|1NNCJXhkFqOS{p|YA%>)V$N4B=j zp)wbrg^%U=CX_#3WeZDX$AM7KLP>y{O3{jTRjq&joBk%g2rWn*A=Fp0zY@#PM`xC8 zmryADnuf+br`=Gqb4ECQS!dQIpKq1uSM=I;<+%EqO3BQNovT;MbEN*xCDio4UEMos zL;nSk`zo)nrW8^_#iu?`I(L^h?Iw1L)Q9EZ!-^H3gh6nh#Kfuk`u8cfPICKH2M$be znzB>M4IXTpzf|bisP^G=wu(ooYDS$>I&cEBuSv8yIXtDID01bI@GW0U_3B?~ zM4iIhK$t?BYHuauZgip>0E<>A&qS6qiVa?me zagv&>*(kEji3Gao-z-ssLi z{{r&F9R8il^-RNIFi63RXU}H8%{fyz^}i$=1-2%g7EOooC2syB*{Qb9C-Nm8=leKM zj$h8vHcXWt%kLnAW+Zu?K;Wh}Vno)nT4z%I2sEE7SFQ33m_LdOMYEzx%S^WMb4$z4 zc*ERd1Ey{jBJXWo@%?_SbI(&QkFF|?TOdVr*s#4fm(S*t$XKaAhk6++#QHAVBB?2&-q#M+-tx&xXn4~Aa9V0 zyb=1)-4XF^Rxx<44BRr_YrW{j`Hy7k!1^gK3Tmoxh!y6hIOh zgn60I@BFpGQo%Y`vJ``6JF^k@*?qbJ)8Tz}`Y%NEdXCQ1zSIlhRM^r1ao7nt@vr?h zY)nQWfEsZyBRQ4(WU=g{_>ECKnPU`Z2X_sdPx~f8NPW!vPoI1_ZEcH1B(r-xd}YE`cPc zE%qUBq(5lD?EGB1=uh|o=eTeY{&5K;a|m?ew|KJzgp#n_okTKej3xe1R%Rsm6%!${ zIL7Yz!f{fiRw0fk2&I#|@#SN7)vJ&oRiXfOJd%NfqwT{b8;bx++WlEA<-Lylvv=#< z7{+D52h(_690c7CYMeFLPX_;e5)%`X=F!Ik=}7lMbF9|4@2_|mc&TtMkrYi8{bnCx zkWlTMQ{TYABAY;=nYFa$!s+j$O3b$KiHL{*h(Z9S?!N?qLYBz>!6dkQEJ>Lqz=&oP zK!BL=p%JpkIkhHh8kLT`D##v`&n3%R^3W0Y8I!DsJuETGvo!oVZ`P5qgZ0IrK(Rxc zHg*?na0D;{YeyBBIQ?r7v=o%CH0B7=N|p(f0Jz8bjDNb`A7F3FoZ$Ry>9)9^im_t| zLo~go=binP1upwn=y8SO2E?ig4RSSRx6Q1J)}lP(_!&%}?halml^dEM{Y2X(>^EnA9Lt(UO%YJ9QR1_C`W?o4U2xw+`a z#_MOIUKB8P5Iw7I!G;68JV6+^ea2oV&|ECw^a!pswa4fUQ}|~vn*%D61Ei6Wa#!Fs zRG3~Pa6Z}T>KYDyDpyzDDot#+(!48MtJ~RA|v9n@M*F<64KYs_&=>JJ$YWozU+rKLH!yhPVqaPcWEvuBACjOnS08h&=@X z5oC_~~cnp^)24R|-o}NX5{fG_pU|Jtu z(W3;%Xq7cI^pfb;n}$&#ycTV;pj&j0blb16MbVfQ9}3U=lIxQLl*5%6CWnHODU;)4 zUsr>@zT+I>@25=Jmu+E$`~wG*p2$+(&>4NLE)9~a0!k1tYwg2J_7T*@!SQb|O{4p@ zD70MioHSF+D0OS zC8LPibm)>RrrbWA!!x80JmUOy%~rhasgp-^7~@Z=O3DwXP@Y8(JC{C0-UCAd1^$)v zF{r&3uk>tS_Y7Sb5mFb$tpMD=?j@FhkgO5i8fz>=cyX^lJLm9=RrHB)+0guwi7!)V zBs&VZED({`2sChL{*8o@#{lI1AGb){Jmh3eudUjd?B&vCqhW(aVZ`cty%AlU$ea)| zR#Q`xgYCWk+p%3eMS_0+r+7XofuBItPI2_YPn`ITfFK{m&p-dHa=YgzjBT?RTviLZ+R$m$nMl$Dr+AvcMselx=y?WUs9AV@p1RU0*i?Jl_i4*^nd`ux3 z2Ec^!Chdp(k5bkHR{biP0dcn8b+$sfuVi0z*EpyS{6ks?iuuA+(fEnb9C)@I(@5xyF;mZVkXXB~)mQFENacsBBqs)Q$VSmkVc)v}R0} zOwDw-<8KJRj^9K-Bad6pnsliQ($W4VhSz&-=04Zj)qHRgWmtR^MDyanYDhv)? z5EEYauD)(oudP-48&t>z@g~U8QILkLh*{7-Z#!7n%9cvUHLcF zAw#@Zylb+;`2L5LK9L4Atm{Jkj>PsY-f0-z#CS0Hw$L~H%J%lRpM2RuK~g+EIdyU8 z=n79i=<_$D8^ch5jdXXGpQQ9^`C@d;R#1$$D( zt=4CJ&JAe%q^Kk)RXMqHY7 zuf8{dv6-)^u6rcwu6-n>H2>}DG3QZAI#z>F6dYgU5OywhT9SX}fV*DaM~+z6Tw7pK?w`fVfPN;ss9=78W z&Os<8igz>@TS@8!yax^aSC22~UrCB$ zJ6lz%TGVQk@sEgEM;uGK(fvUTP4PmIS^VtTF&04*+bvP>ZGN`1>-1HZ?qNgSAlL_t z1FwS`7qhn!IGmE@-Y|?hSE?iuqhRo*cY|^np6d~L!9kO;@5E|L6@A(hy04D?x7dV% zE(;jWSNW+(|3RUVOBU;|k9I8!1XDDtd9&tBrbQV6gCi0%Y&bPLjF}f_8_XE+KTIr0 zmnRZ)bai4Q*WHfAkRQ`5_O+KnXPY6gk-A(_(Sy@-L4uuzzYr+8Ayv|k-%Lr7uq`YW z5l>p7%S>OK)LL{!;89#kq?zK79Vdy3Kr`7l0tC^cm)>FlND#J4&n$vF#_~>Tjk@&i z$~W&rhfd`#-ZF!1L7K|soyaD068Q|iX2GQma%Mm>M6-REjsRJ_Mo{=1lOk<$ivfL) zJ@dG#BS+3792yH-i9uxp!dykwBbRV#ffI5X$gX|zM|jf z{Tl&mc=*g*iKcZP{Umby;T=Ym$2xgT6@8;#ZPfw5%`Mluyq`)N^oG2{*yaeOtwou^ zCr^g+ki1mi?reC)es1RZ7b6`vZ#Ld+q)GjU5GgRtT1vq_yX()V2<5D9#i0AhL)5Cpmaq%~=hvg@r=r<>cfdZIaO(5>1-wcobi?0Kh2+qAITi}%LdNv(BG{JbhC z`tI2nr>MK7(U!k?sKD|x{0Zx*?Zvv5hCe4JXHDt!{lD*5n%z(T-@mZ<|I#;@DmUv( z0hDAOJ<4?kRw=ZJklATn*C6HTl^-9)eoOPZ*1$vM!ns;Z`tfKSJCfJ z>3lpiw3Q1qt|s6iV@JOcPZi$3e=mDE;NYH>mYRIXs-KEm;3|Hx=deyr5riLEk|&r{KZ{V3g<+Ve3OFJZ|<;xX5ll zzhO%Tu)B}3tCSJO5k7QDbi2Qkht!G>9XeFzo9ixV-e-^Vw(6iQ8aY+<=c0S;&2$Q`u`xWBL2r#Vxr~EtX#cUEjB)99X&#ysB zk6GhIikJ1=ydl-szRkvikHtPjUs;>(xrS&fo-l(3g=TtGSNdQP8YZU^IUKIS_Wl8v(cM zUm(w9I8mswd?j>U3%0&wS(Okj%wiU>xmdpX4ukIA z2li69^5uCOfaLN!ZXO=RZo{seaWksAJury1mQ%5==j20zg@o5tDx-~tJRz*HPKlwX@TkCDeU=gAvMo>R{UCH5?}xgV>11n6f|rfRes#+K_o? zT$qS6Ff_bDuZ5AN%(@hToIFR-Eql+!Af{xrxss62MaM{z-vX?_(?pO@JYT{&hWs8V*gx}KwE;gVkyADPI-+QiVKR_1f6ho1!k zXNmXuJu4lclqX~NE@mZkD8)3w8{Xu2@b~yDT?4rM^W5csR8{rVhYUIIHfesd(u(4= zLt{32!g0{b`Rm&BgioF~#8;_cFOChF=yj-QJu&qJLRt#nE$d-T;~hMBo?2W;R0q3n zElVHo0%**f(rruj|I@ZzDiCn20C&}?{>xsw%d{-ui( zHg$9%Fi|nKYSn5f+D_P|{EbIR+dzyt!^jPC3E6>~ z;VKhE1&+nhCsG4Vy6}}^R4WV!Qjb?zVV%*!>wX>>{;GCRVRV=&WU4$rA~(BS&u7*$ zuhh$J;L6hZjEiVyoP%ZmY9Vp~=lR3x@mx43k3qM+Mc7RI(CM;ncjde+dIH5~oi2 zWBtd${VIvOnKe~_6UX!1r5Z&M2cw+}?DdCYza_?FJ?I_m${%UNyZ-2{Ju21jpif$A z>bWtI;iGK((Lzx|PCGPy>mzp`J;%rzeM^4+>GNklVJyW)_vt>lj82(T9giF{=D@yv zR}maMjNd3DocR4`y>uq^*)n3iC&|m(`vw)^G!PczX4r;A$S)7_39ZQmHxq$QoIuhY z&N3?zxa~>wsty#|M*$tCv#EzTaE`$V3iLAHyKn-M^vm@ALn?Lff%#9}Yt=|{mGG+N1Z znIg{7nxxkiCPi=GS_^_SR$Z@@m(5>IMmThz9=;ir^W(PM12a0O$!pexIo`qKrY*!( z65X_dJ7dImag*L1pohR=J#}9m$Cq}&0Dr~XR<@5 zQai2}@*NHIJ!be?E4kcfZm!?3VRtp!CV{VMk(5_+M!UoMyF$Hw;KwQfr}D1o{Ku5N zP2?XybZiuoK}gaca{bzIQRV$Wgy_f%=eq-|DX0#gV$Al0Cl&Xbv-Cd zFt^({J#E;a{{43XFEula-{{+T%k~CmTqy3^_2-`r*KTi>dgPPwm0bq*s^c{yRjCm@ zk164R^rzXanIub_@cHa#VS$i++x)QG#NdA6@-=#2D}7Pvd}zuq)@pCXRH7!$Y(Roj-4g4c>VI6B%^SFB8V zzqUW`AN%|YBGA-KqE{xAXGN1=wyzMM<|%3#6J7+0Is z|7Wdj?anj$fMMM8ckgD=I7$gVe7F}Sqr%GEGYd}NNJ+tRu%)+lU+UIYKmPa+d4$$P z0|CySB;yKTqx%VtcJw^IQOCY~6r+ZBnu7E-201HGAzw{N*@eO)u)aE|UN&MT)|T6p zD3bPMFD0y&&>!%{ukIgjNw2MCNhEm1gp6a^YS1$Brhf_{9Hlc$xD-ZWL7<{Fw#7eo*Rgsk27lB8&6XncPCqg(kfM}FKkxEpZIEe)(t#=}>z-Zzf%s>3r-e+2 z`)yuyd2^Rlt5%8I1t@v*2_UO+{4ls$)XdSeHQc=$1Xs28Yngt0F7AOeC8ihG{YgBf zAiV|BlyQ)5?8(;8i%7o^k4-R5k)c`l?z)lJr$}qW<}R9#_DG|ap&lHIKG(bs6yO-} zWtTgl3t03^FM5pA!%6lFk(`@y3V{BivV(5D*ttYCC{f7_F;9Dqh zo2Gv9-~9DeNWdt&0rV8Iq_?>Eccxi0=KnVLC@RH?ovbC~#&z`6OEN7qXZb z6#&UxS`GiekrjcKOK1 zLl&G5b(%LOXzM5NiEatdV%(~y#l<&yUu8PANC11FG3&!IYH}4XRH%(d8IPJ=1Q@2n zzk2&NwO=cQsOj*dHsc-3P&Z5Eb!JS6Di3lwpC$+iv5-}zQ3~nnA^25&*&R2#ywep* zgr@rf0^}2=eYMIvw-Yw8sRk3@-0)41RO@JaWkDjKxD(1P^GXR^gke{HS1*_LJw{6_ z0x47tk}MDrj{swQWz@+OOE(bx`r}_$Js!Ab-ucxX1*Ra?(>d+)^>xj*kUm#xL+Qd{ z8H!%NPNlHR_}1<{DjqtX6*}p%4T&fE`GD@Gt_@w){-8TIHG4BT@+o>yq2I0j8Rkh$ z7pXfScX`w!R-7pA(9$L|(rV>rL-SIwo)4fJviT0=1?5*OKzSm|c0`(a**;=uYmjr* z*1S&@#$l|YkQ{pX(p$nL_`0gRvu3VxQiLZ7SY7QjxOKm z*%*duYOw+77IlMvyPg9F4vbfJVN|!^1Mf$cLC}q$ zTJ&TT_`P@y#k)s14bCB}t7*q5?@a?%iAWtV_hv?-3D?BQY3$yy6|EQ#=mk$$LLD~t zTUj(w<7;J8hZ(1PF@3#Sx9BA{2g?cbazDTanyrH$7j?=(pntm@-+pd4uT!l(Ox&i& zu+9p?Zd;`hyP0v2uz)u-)p0R?PWEGccq;Lk8=v3OXv>*PulKdH8e+V$zQ^5&(C0Bs z5lG(1zp%E5k7CTW`fr6SI37i)TE(yKa_4*I3<~tUpzk9p7o1soB#}Z6ag*2c4)Sk) zF3(@JF=5r+o+Ohd6L{j)q@3~!f{Skbp@4wf{Q7D18dMl7XabOv{>e|z&uAY0a0j`e zX>WEC^OXIEMPysVzOw(Ff)n7_1qd(MeNmk4POkKwv0||)d!6N-qS+U;sl@B-o_E3F zci#{l32BQGMsNF))Qi3+anY%o!4}2c=Wp4(xdN`l-;q^{peU^6KwE5UZSg3Ez%rFd)JqJ^==U+F=5LE8{y5~!YRc{fgsp}=K-xXSOBy`A&%i-?~5E=5;aGA{@y(rZF{pgpYssMk1oXoRRB6ccVcb~Fc9Q9wkY1{ifd zZg$LZu5#z@-P4eM=+k5JzRdBwcu`VvaE2;;tqkoA+<`%W7J*P9{dX^=FH>~g@8h#_!|SZu3T@HNOS~ted(U35z{2y*AXc1zc@R{$0>Osq~}f_tAy|IpG_3Ov7~z^N4g`Hz|lH&9oWSoyvx}Sm5Mp$ zh$t4RF2ndNX>4RFt-L#mk8bD{S}eVB^JX{fiOk2-TYRDRTdm-VHjP!|E39Dfueb6M zFBk^lJfE>>WZsZp`e6}EX4@4IB5gqtsa+0GJ?+FgRnFdrUFo8Qgo`AH}6K?X^11%{LpLMy_%N1Rh zK|lpMf)FI}ZW*~aupUYKo}{VT0&~=D?b2{d_{UQNBAYtR48f;GkVMdLKBDgmy{*Pj-ZRuWet8ur~mObd#0edLXmI z40s|gLGw-CqFe&X+CjWuhZ`BR0oA(wkcj;d!QWY<@Pt@{3$t*DQs=v}-|898uI_yI z-xi)`=~uWWL@+=nM^m@D!Rw6V_QVt#Roh_g|M<{O`)G=|8-T{EA75M_JT63mcZ_bO zE!U6;HTq<*5&?$sqi$!Gcw&XdA6vE6(QD)SxZRwyQY%=MurmPdsiqZ!HlNyk&ZO^6 zSk^Q2Tps1XZw3bY%r1KIY~Ci;I}^bqtZBC0PN`-4;rZ|6HS-*1unq<;Dg=&>dsce7 z^~Q~#d)1_q-H)T^@_c4N8&~+gHvZD3x~JbhefSVovDhzSN#Yf=mnVJR-8O{te_iwR za%05Z9|Y)J5!g{t@fMzNvM!Y5#e^}0+YN%4EMXYZSV?v4*b=ONmM;e$%NesTiJ7tt zmJ~mVDoH{3N&Xyrojjg^uIjhE5nuPP}$_P19jaIA4O_#=h?Av!vKYmBM!;l5Q?CVJ^lqfwOm?k~fV?LBE^ds$L}#2UQPM2YvQStl5b$FjvzG?TlFi&$;9=4XX!j9-oi>^d=h2?n2hT z0!vg_vh`yZLdl91D@GbVNmw|l5%$?#;}AwNdyRcQ{18al_&)UCR9ym9@Ir8vzcOFS zG-h5FJxgEm1l7(%#)0@`|6)fNMT=eAX5@!naKlzTckS3AyPs=nYE%ttN5)E zQy$}xZf*R_!@V2(NrOd|EZ$t|vP_gx|2GhX^m$XJw4yURYgtF)5;h0nzS`xMgBE_; zh^kVI(z`}k4EeHgtFT?lsgXadOzZj}Gt=28t@U?&DM#Mmhl&cJ8)aZ@j@=44bF2Id z8DpL41!VccpXba|d9$rswK__o5XP3@LU&-Hqe@>Q-5fx4KWZr&AE-hYgyAVpNMMOM zDl8_DR)S><{Dh1e4?^{R@;8N<8xMiS3O61+IDpRQVYW<62h-aD|Hx0pB>(>X`#?D3 z4|E33p$+iA8Ck_|@MEDj=oBoU$#mw&|pqf?SUGAlb zk`WZZ2xe}V@)~7MbcMP3qYj2UX;av*l~%M@?+#c9PwnacKYA`BdO3&>TTd)MoBuK` zZ^@sOA_DtM^d-VbLmpRpq}fw`O%00`LkJM2mpA(`vGakN?*WeGmE%ynYe83n2B!|2 zeY&ppo5_MFpYXP=Km-5irZP^7J0S5%KQ!?DX-W7O4!z(M*LSpLrN*C7gScM~W>IeD z34PBb1r1&RHR~+OK4{T0Hp-(&gC(@i;XKp3-=;fH0s@fZK-Cj5BLBN$#d!>IPZeIq z6aAnU441SXB<|K7I!G@Bf;`%{nRLSJjquCXzf)xZtQS3h{uhtZAjc(-IO13b5ju(n1`YA> zyBz5M+5X?<$vGnSI+JH5FajkJ>F^q!xqorSXiAzN1+tUq!DnfU<0d=1 z(s;*?FOTg?ueDP}j`$Orv-55;{OFJ(3oji~XnjjMT|&kn*bL`6qp{;2hXhU`_0#aL zn$9$Ntc$uqGtj|1V?4v$eaO?N);s-Z3hLL$H*BXdowH!URLD`}-F*P?=nw2ZzBVH0 zt=PDD2HZ7XcxLK0)22@S2jDp?+$at1pGr}1D;j|I+$qY_zmesTOnNBLzsr&p(5@tK zKT;yY;8g}-yQrt4Xg!uQq4QRrZcef z1vf&c2I?Kc!|w|gC}DJPCaoE-!i@qbexC5Znl99zX15-X+zdWP30Ogz`H2-hXk5Rb z&ruGy@q|^Bn}`bbnnjH8j(k+*7O8$0eVC4Il6og5&x*1>2xGiEZ}D{Wn)*5HWU60m zH`i+v<=fWH?|zjEmQcH#QA$p(2J9cPDGr?u5EyjeS%wZ|mk)H&U7`*v+3b{0rp~zZ ztk7dLRlAnM@pu19ptcC+5V`nrD$0S|9E?}~!@H{&N6%G7-_r$s$a%L>J?r-|{k5IU z2VwxpQX(=3(mUjU~#QnI0-(FXZ>h;uZS!x&|52x~B?g8&*<- zjAdneL*!$U%`-$+3!TI5TZWPm2i$^SmX6xM-Y!IyVuaGjzx(J_D^|!sI9jG}rac?I zA(Vzyt}?P=hBh^cHGdMAo)#6&eb#o$%$er=4x*ZTfTRckn`pTt#=y-WL%F!&RVUO9 zXm1Xn&GPq%p^tX$x_HyEOn&2~-BeYHGt*z}tgK;l$Tm96J-)qETISnv-a!_C9obHYpbzko9 zQPPFGlJ*|VZ@j#`lxH>Rt)t_MF^eBLh6wOkGFWu$s!1MRw)l^PFv`IM!EPL!w@c$M zm~H6ne!Tbcd5eP?nm$A+bC95!A9+?fZ}lZttYU9F#L@Z5Za~mkc!3a^Q9J%N>H2k{ zo%omjy?eWG`n9MH=^H1bsd712dkhqA?wU_`J*wUniiii4|EYiYjijXQ+=BgHUVp{L z>Jq<2a)dO`A7%sPOd44(0F@Abf!o|U1m0w!yqI`qn?$$m9vIl2*m;5!DB;^P z`1>a`VBqnSZ+5;gS%U&a@El$=?OBO`-9&O2Dujb5Ht4A~CAB-2SohVEY{}*;O*7D4 zb22r!hH+?uW|D>|;25tX`q$gc-aL=qRrIf=M@=;yKS&7ITZ)%jfYTHhfalkey z=WBjstoR<%oTDXa6S=4Sv3Olt?{}sq9F3aE=F|oDa;F(ZzXM|iWAzja0fc-vpz6c3 zRj$B#4RmUuHxEW6w+g6su1e6Ml)3|%R(^0w7aHvNfpHCmndh+}AL*(tuiv;aF>IVC z7=Y@~N*a6l6Lu$K*2ka1l7V$a%n4Z`wI6=*@KEzFt~+M->aGQK1M9({{qJzsxJIvXR%fT25@1a!$ZO>JpW8k~iS~7NT4}?( z{p~krOHTa4NRDXYmriH)kVSc$>)HmM*WK3$%1+5xt>oJHkGpqgLF9cu2Myhnet(1y z2M$b{Idf(V8!d+nQ5iUJ7l}Xt)dMsj&t(@%Ae3-~MdhT5&W}^ym6|_Jee)#sth0N? zn?`kLjW4Z?4^(3d@Gjb(YUGg5{97Ew#tUsv1wQ&s-vbfJc3bq>lZrF8Fa}TI8elfh z`LBi5wU6BwIu1w*TvpxMy7;r5mUXecP4PTkGk`g%3Z>}cFcAsh zJf1>H9EE%GEN=W@Vzo0UAI9*kVGOKwYr`5iv^Wm+w_tmb6#PZJ zFp2vul68Ng@}Y~0|H8~j3dyo;xq?usAt8ZjuT&8QDM+UZ=Lj6oL$$1%>oWEImo|Oq z3-stSepTFm6Uk(-C=l{#n>UZ^}isxw+oFy4`Df>V(547g)n&M3VQyX2!0HcymM zaxLEa(MT)tKXoNavLot8v@@biM1Rq-OPAjv#{h7(EvYS2cxAHPPP!kuIS^Cks+!h( zyTk`8{S7c4WUpv_n58^M9rc*v_A!sj^omoS@?S=GG2QY?E@fu5)6WKWNyVQZPLx0Xcji@L6=<`~B=`A$4AW?tw-Vpml*3DElbE zWr4^{*ye^T^`~CFW)U30H~5;4y?X717l|5yql3sUJ|x4n!$L zODe8acY5#f^faf*;t2%guHO)ydpZ?(Nq%b{h}Mju_hqAokT%jUBEo}A_JqyG^J^4R z9U?7QW5I_JPjf%ShvE``m^2Agp8k;1o59jC&04e#HE2ZID)Ns`_IhlP=v@1SzA&SB zD(Nv8*#o%1UCMCY2}1D_@+)--`lw{I-cx4GU=`^)&@~0fU7))@Byz6I8J_X3{ZDyE z#lXvgnG;ih359Nv-#Egp1oacTvk#^)y#-Zi zFLR9F8D9lBK*6Z3KmBwShE%?cwgB|F8RZs{7Gb-(@Km@)Xs*hZeu|_o6H@dMaYdeE z=3QLZhw1jA`LQ-Fzqe^=3D)-3C6|l_+svc1@IV)yvLQxvc8_9h_ENH-T+ZbpE4FlLlzyfGq`m+AIRwoG=>~M=jYcN~Cj!w5?fD#TTF#QgSrD1Z zyL4p=x{obo7?on@V2WqyhIda6ql(aCYbU1%A-wb*P~Q?=BF;bsaxROHCytR ztfv*l37EqXvjq*g_J!_5L>4l{UvY0z2Z7Bw4tcRQy%;ZY7!t7p#Rn=M^ompkPX2VR zAV4$?O}^8Od?Bf#lzMU%Cz#7Ss{Qt5icBvUJ@U>2QU#IfYB$#PTxG;uqj5Fg4xyc_ zl=Y&pI|yY`;6WAfznf%Vyk6!NJk=O|z?Z_cp~Zq*y+QbUInQ~Lu3bU6x2}=3Z;}16 zlH5A&8ujpV6t`kTj@4PJtkx*@Z;UpHKLDq8fXwYBY7toS5Mrs(ou9&>K>}sMqO5E> zcb>mo%25yzgqPQKRPUs=7Sz;BNrQrUFh?kV0rFRt%$U3oe9B`t-BZ6p&D(3-@sk7i zm}E($6#OvIQijtFtfTx4wEoo)h1~BT?OYg*CB*h;c!h8ZZ=S8WP+?iS=#*)k7m2JA zGRcP)u9@5K_4z-`@!MahUh6i+*#JIX6s9P;^e&!icQrph5ZGzJ%tJCA;JQrugrldL zAZ!=PjDDPg2Ju23{T0#_pPuDU{sYCefDpgTWQ!U-M^`k1Wa5T&D?KIy0Y4%y@hsNX z0fnJ-PR0ghGF2+Kx^1uVhh!F^X;XzSls%i6O0-DmQx$bH>cd88r{DQBxek3vPu#YL zPPLUm^&7qe=yBx~QF`F7ZhAG(I?xAkwBPzi{@>{YmaH-MjEGPZN}8#Yf4COX-eWVO zftp(ev*RBvBmm3g%5X?YDmI+(`-~bDfH=tqm}$SCU+Jc)9#!S}eoW0(qV#xPT)dO3 zOr?UX;|GMKN3Eh{6xZ!xZLjsUU+s}w z{JwPQ(%|`;dcUJKLFYnb$OI=)dZ)Qz%*7tgUF$PYGQWHrr?swf%fv=Bvu0oZmbt%F z|4unihVPLy03wUA?lQ$lSuWILQvG^3omi*4Jq88N?%a(%p>;FlCw;#vMiwf6w?gZL z9Ava>xzxHuxs>-&IW`}(zE{D9@+AO~_19J!#4emv9Q!4pu_bXs15#87-CsqJ{MaI9 zIAg0Q|3QR901ddx4Zd zWJNuhRc$3?y-Y+ww{URZxi_@-3dII{4Yphw{9{F z!wA1lrR?=cd*}RlOr_#dR51=)x`-arGG_<{B%;Q_R6+8LXlg9<^2xBy@BdyZ*brZv zfLh#hu;4(z9T{hjl{w2&sI>gX7VOB`e9NIb)AwxVs)Rl)#sji z!{TXbN+9}9N=m7Pb)R%a`olGP1u}_~VQYk!PK0ceNzHxG zJYy2A-~!<76%;fJR58O&^>snKE-ed!F`!LHIzmMR9n>^vZF@R@S$1U8^VZPI+X1r? z=AEFIl;H)M=P~U~PV<6hcCqfGlX+xBSBJTB{CvH5w?l+aG_ZX0vJ3opntG zrcjW70TwhFA6RK-<=N~W6J@fGK*vj@kC179!`aNAYt1JLc^ z=2YAYYlGGx30ia>8jiH>9nD3{0G`6zc3oQ3esJM(qcAe-J@5D0jvx&R;$S2E20y*`1^NT=bI4e01){;c&?$YD2F z1hZuKCaF5UEfkqmD6r}`DDc{be$;yoDSO9#5;2<@ACJsr2@ppY^(fmr;$iRbJw?fn zimi0=+uc1KKG86{G}O9g;W4PG33=yY_e7tCqTwFv>}?Fbzd2hoQeDzW+DENU8q5H9$b>8sC6XL-IfX-f!?*pzeN<2$x$dg^6QTk8*Bl?nNmfCZ}Kz49A#Bt-5Me z=U%-!cn@_O!yQ4z(u7A&JswS~wo9#Go>9*3)mRURF+Eto!S?E{?| zLx--~U{gHAa{ij6$vK9qy73Da_y>e7Rcbw_w~FnHlA5}urt8%w4Eymx(AZvq`EgHz z?%FRZ9X(QK@i(U@r8{JZwH9ssC1P1dqe0b|yFaNMo0PCPN}keIn#Iiw^Q?%?$2e!8 zUmD1u3eEtple^nw5og6nOn*j%uk0M8wr%c|zi?q>T#1q_s->qpy?Ic8`0Zg1yFaC9 z|ASXqK;|DYvs%pwk<}%D7$L+jWY1Hf+;acuwejbl9g6v%?zmWf8-AHdt ztoiG#4SokK-{k37KMqA};&1LCYJG3Ehtk9&hx%1E!ht#xk%v_pHq6`CY3bCzvikIw zmNk|ava4BqwrMo|ca1S(0*GJz;=?9)pV1jL&WSKQ+0e>Aw2Uo07;*OO?5?Kk{)DnR z%}7k(u6!&t{}CVUHy>M!sPR4cHXZ%ytYMDo<8%{s{RHg zw$Y+RL!)x@&7%ffWueN|FTN9AiORK}*Oom+=5t~0WHh-=9G>g~$f5r_|y}Q%+ zAYMcal29WfBUuxvJ8MnuZR1yz*towInzmne?(^E4VModfUt;ob|2^AG@f*-$nb)eF z=gtjx9NROm+~Kro+_`MsOAVF=E?Rr#?_lY~mIOq=H>F6kVGEmrOSHnoPIrF9_YO#* zah-+2NVoU@+OnP5@$Zfh-!n1o)`p)t)pq2CJS*GLhk2Z>L+edYCOmre`E#{XMYR(q z4uOs@Puc2Rz8fB{s;#4QFs(&=fwOVKEO~)fUtQaya(>Rjg%OY+&1>B7tiT2wN?-Pr zSJygMt_d-sm6TAgUauw&(Ii~=BJ?M8tzkFaqm$;&8W&9HKA3j+pW}BAd3$HQuAiK? zE#%GCrt#5Wr@ zmFyD>hw*>$1(8q!MkXexgq-<$uM@=gQHN)KL}xd$6u>$c{Hee8<(6Tuu6THOoPL`> zXVRqYAdbZwMsvEOjLoR>ELN|+$CJ&bS9aNQWIFzBa-1FFi*4i5le`X=WaZ?9qh2rR z!yUaXZZfg?r$OwFzy16z`{Bb-DkSk>0m#2{XlBTXtE)bJtK~;xyq%w@bWktK7ei|b zWOLqI?wQ8psA@?QQZGrZ)0ay~PxW4!Eg>7@(4s?Xeq7E4Ez& zk(c~X7DXXF?n={CQ?C#P@~| zQvJ%8sC=4$w>|*@YtrM{ zO@npWF-qj@tSr19j5e2@O{s$SnCd03*cZ>Pp|lQ`UF=j2#` z*dEkc?Bi(8fQFP}JhWHM(vhtPkX;rP=m=z<}zTpyfx z7@ud^Nr>+_kI0Bf0xtU!lu&!TUf7!c;(e*AreNA=mBzw6g&@}8sy1*+xUWH$NC-Bi@9ATgHOx40T!qtpD^SB z)2qk>M*n#D{54&90#6es@dSWvrjYIAbkhVzCf02($DT_htW5T(=u=P!%8Fevmm_kX z%P*JJBETu3P?P$Zs0&yqaIB)jRzH)J`VoATSSew$$l zOWj*yE(mcfF;^B9Gsa-(XKMSmc$$G04CVzp#E)Cre^xZ7PJf2lo=1;-2kL`XE9p5W zh>7XCkqsM=5e^Y9<}6-(L~|J5LuUwzGuPbwBxl=j-n@s;r*1>C@IXQ@^UShEo>T#< zi>3SJrpC`HQ(uZrKTdGe_~&Wu#L1lJ6&@a*38WJSrE5w%=v81Xu}r+?#ZQjMbRg?| zF?uFPRLr@!xaXH>F~DF+8^FoddRsfo|J}-))UpwPD=#^6MyNBHM*S!o*C@SZCBk?-o#itn%Tidy2li5tW3AW7rwLCR?6bR+nsjD#Ul*I)v zK5o|D^nPi<2TSorr89*tb;q*TuJG&AllqR+PzxB zxvcx%K)LKTG^yK3&Iq&+J;;aTxk7e$p%)%LGdu@99r|~s| z$`2?V#nnkn!I)aef{Bfk?cVawMkb58teY8q;jgZC&B~IKCm+|pQ1!WXfra&jf^G+6 z_Xm*8TR44NxbWTa%XSgr;Tx)p{UZMP=T|Wqhk2Cc)ZB<4(zW!q*iCxl>gwtcRZtVn zLDw9A7sAVT?#zg}1!*-})>c;HJ|?E{KVbOQx z)lIedS`q{O*s}R=TRxTTzgwy`{(x*mu(!9r^zt9K5$H(80F7cIllSFrcLidfdN6ET zeVsgQ_s!EnHkaJVR6ZY5GpZL|&ZeQ-r_Y5)M&^U~H&c0w zhL0aB*02@dYQM5gB80+6);Ne+mdY!_gKUTf>?N`g+GK*E$Jk8<4Sw(x=~6tmcX)yy zUW;Y=zfCmsI(Q)zKevc8XAH&%%_0h{)w!`4paeE5lFvuVb1KdUoSRigKJ6ubyrPC$ z8@*o^^fZ4_u{`&Q6IXvS1NCq48O84^N>8RgTwATh6IC#)`R-n!dS%X4|)Qk!b zp9)@ZhKNfG=grbU66hj_yoP8c#xb(>VTsd+os`?ayeGjz-{dT`k@ddoduUZ^ZKDwq zgI$X44)R^a&`nf=xvpVwg*jKQwHx6SZx{rm_5grBSvg zh7TX^Zu9dNv~53Q0LwFYja%dc^eL8B!Il_}Caqq6m<2P)^@u0d!)JX^*7tB>wZ+JM8 zE9W8_V+sy;OUlJ4$fa&-d&JIMmU~F3X5WU~=?v}Mm%)CEhezK3rBVwi>@?VWZKVwx zf1y`{Jb2CDc|CY#NM1rC`^!BOOVmMPxGL+1=$EBZ5gS5mFM-CNJhzan=Aw18#3t(6 zk9S(r3_n1lF3XhG=AFAa_Hh_FkZPjO-jw4ENLHSK4gQDB_3>@NLV{4qGPya{v1)z# zTpPOrUizXGtRFTtRkGaZo0>Y6>v_JqE|5nibtla=>9*wAwin>`2J`0!&~#FVIzD_) zbP7Lv_Wr{btBmK*4@1Vt&mVJi)aTpt982!ZS+wXhc>3TzeU24;V;*A-$k&e@I+!>) z)oi;^`_@z@ct;E<%^f4}K?vIIqdUn{FgNI==)2~H~YSQaf07(yR+7R-vW3vZB4hnXJax( ze_zOWFW7&QigEw>e|+Bvc&Y8LC${bS-hXXqUA}XQ)!JzFho)EK*cQ~dPf_9MG>w*j zti7BZ)=|a2BXOtkN4uzpU4FXzr?8@jj~qO^g8;=fKiWo7$I3rW95OfPm;dlbN$#2C zl7XAYl!7-;V~T^NWp;{vWS!x?(L+XOTOLyS?#Df{^nBM}Vm>S7{QFK1&3)9yZRRJX zoPXc2o$ILHuW#`kvdU5ZEN!j!ec9yF*8jSC5BaYZll}i)g80AnmfwGr!qrayE~lLL tUwaX!{kysH|NmhM3jgo>%<5a#{jsm3!P>8~FJ3|a_nE&%{<`$9{{@42jAj4; literal 77478 zcmeFZWmHsu`|nS83?QL&OQ&>5tCXO^AU#M)GYs90v>+V{qA1-%cMl-l4FiIJfOMTb z-|zSSt^2lC=9N;I8=&cE8Xn|-?l@(rkn*7SfO}qDMDm-93qslI>sC3qNJp*dexl_8E0Ua)F zu$o4*qNYqJ3}k!yUKtymOhqMGVnb#F_;+@2CR+EUA?=5VhPd(RnVhylw_%;*tD%yz zk@~IcTna@z=1`C#9+~v5K*K-(XI9>472-tw6!?{pGDPd|KVgPMc4htjL&Yvol;mI6 zF^5JnlSBXYAxdn>e=cJQe}cgO`!AG<64UXRZj&OS{WG2`1D-8wAF!PM_tBeSVsR`gONi-f|o!YUmQN&kN#*&E2kWcCRrC z|NgD*Kx~wM#%;#Mzpm9{*2)e620t;rtE4pr7|%#vP~ETsFf)B>Yg4A`z+fv=MH+4~ z0pq{H>attL4$K4#VOI$hHDgDK@RRAkziVwu5;dI{PZloiP;=Oa;j&8yTomcc=6F+s zn&3A{mWskirEnVquIj4B-3gVVE5M-|hUr(fR*(?T9IF{V3F7 z^=QYYh6CG1MZ7zhRPMaZ*lkqB@$%14u3c^EJ<+p(yR(3HQTv(lHkOTGB{HMcki6Nf0$ zkz6skGkm*j8u#z5MwRBv5=Ez~S?RZ|%phHq++n7F8 zLALZW+bcTQgpOl=te9(&UPCQR-Ix75GJCUs1EVb}{#cHK%#@WAJo2mf~`Y-?XIo zxKJ-0MRJ4+f0ILB0&{z<;LphVvn8LAMfZ7!{qyyB51;+|uk+TqenxeUi}r?K#Gwmn z(!ctC96yDB$H=?5J|6Kfw66%8cj={H47fdJ^jL7|ovqE0^=TN_mS04=w0Ax`8wt1_ zFV6dQ_h(!i*HU%W1XwUFj$gCgU44F4MA*&OmXw&b_|`8T@YOAhIW(V4P01}8li2Ni z`$N8jDB%5<>Woh^fI4NvVO zpuE3BLhH!Kt;$+1zdJaM=BYf#CEcYyu1WUIAr z`pN5n8Jtynz&PQXd?*wSGn;p)gI(>_<@$B`ov%jJ#**rgu9W~0hXX!CMFsUeKiyxP zH}=2StSxa|Y^cpD9RxQ(;z%JoJ!(QHi*Jic7Ah?VjdXMpv*RnAe?@>Hk}{=VwR7e4 z0_0q0t^K;_^tk1EE^4%kLEk%kiI2dCvM*U*nE3?);fPG2}QzNuQvr8 zr;R;o9E=;?VYqb8fkVgW+L9(j&hcO?BjbDfJbP>MQ?0j`b`;WhWxWhOh^{v6qjBh;U@>g0pGPC={TlvI+$F6dr8n#SbAYK`f3#E{@$o!-=8yd%VyQ2~z_YVMxMyTBc(| zKNf<&@fYNPWMt>ZCne1`<`i4%Q*+ZCzMTQ+i15j((LvL3TsAH9(|KKnyb^I(|GlWR((?3E)75^XKtXX~+PW<8#UVq4%mW;Yw^I5Ef8|LDj$6Nho z1MG1}J&;_jG;HV1ZuwiUFB<6(mdL1hdAZVjPeNlb!t48vReEWf(zR!4)6p}-2(zQl z>sCMc+;(}8x0lncUy7C3m}|!NZ%dv)mpds-fZ-?t1TiiI7u)=jt8 z-*|I#7#~m#3kwUY^_{g$ofXEY;}z;XP9&+OT;sXEK5k-Nx;R9$W7-^bWVlnpkbmGQ z6j3k=J?iJ2mpbV11y-h^p=Spq?ywLMk?S#+1S^P=+{aCM>J-(}G1#)$=s|kATCdz? zQJ`{uxrKM*ewH*E&pzO5<4wKhI14K1ATsDE&WZHD_9yH)`JU93TtQK$Sf5aj4bC&j3~SJx^;GS7gZk%NNpz{|)C%c%NZ z#(;$d`OfDNZryZe)16f(Ka@zrPPNv$7d}NWJSaZq5A;XeFAcx-0*12ru!pw&a8n_B zMxI+&)&w4wD=Y9ZL(Jhpq~wC4?1IPCh0TY}D9JmeK}=E^kUgg`=k7BK=t{0#j^qNn z3;W6XvU6kitFby}`3W;yECHmm2ets)jYw#B+NQ{e%yLh*VMk<$>^NzATiXHwqHB)2E$2!|cD!$~7udSfnZzl* z=v~_SYi9wXkXM`(5EAr_L&z{;id$D!ov%dQ1D*{(;B8!1ZW%8M%syiGrLSO*3f z1DNbWhOxaeDE8k;%7>qH*S$`eVh+3?v5%KN3>YThr3HTU{4=WNklx0?V1#zRHN?hz zey?uXad0(|^19(bUh#fzj~6$A=&I!TN=V2@j?Xl04l$M7tVoGCSR`neks)9cnop*Z z;OG3oBHbkvq^TJwXjxy~mxD*U@XD{8U@qqHWy}>pw4}g{jr95Hywi~1NPIeL8ZLjL z@-&+#wxcVs1D(IU@uj@GvJCcI@$bWxn&NOG2C}+OQSNdxMchcZNe`j078&82-Kmm2 zIb>d%Qsn1oZTi5z4sKPS@i;g=i>FOd^Xc5+z=q#y1Kx1waZ3v%&W^F;W$}nQ9%sx8MOb75XX!Rs5`GdAV!!`0qT!QVJJ? z<~LcmO`CU{uLKKA2lg)guD0anJz9Y-Va7#Jtkuu2hwHt#mb|a4`+D#%9PpBk#?V5U zopH$MCHF%qwD7uKTXxa0tjCB9;|-7C!m0U3ZBqP?PNF%8&nQ?p2|B__&q7F~`mhA_ zh6P&AJ8D&4P&6G4@L1h%Cm4WpVQ2s$0MyeFalU48)sD+pUHS1lgyj73mPK~FU$Kjv zH^=%a=uKAqv2(m%XwUa|k{=l+NZZ>y%$h{kSdft#Q9n*c&_^msaWEtG_M4aE zXbY&{0)rjM2=+|z!u9&vM9YamSN^+_uJ&>aS-gIOAMzm%T0zY7-Gicg(!;NtPQi_) z^ZTL$c8U@%+hxu5{RQ7uoIZK6|1l4|aTs`z=&?Pi8|4ss$lj94)-DM=x3?O8( zvgxh-NI&~ks{Qr#n7TkZY}T;$LMPCpM~#?|Sm3+~jkHsCWJ8)6xSyTRC6E z(AQg?qEcae^e!y+1+N*);m=7@bd4sT1Fc(^3Jua>qe%<^2mNiq0uS>)3hZ`FT`CrSqfR{g45<&bt6@s?dq$2UcDj>xuyyv(9lOQ?0j zqar<3eJ5u;QzsZNv%pY2a`)tRH zwR(3S^-b;M|IQqC>_>DY!@7&~*{3|78KmOB>mjZCCJL5c-&*3@rP9v*MMW704cU=7 zcsE`Abe047T;+b%0OM>_3X2+-0^#h=olW(j%No~yMRBJIvpU~fdkS@RYfUI2VQ)i0 z)mQeeiF^$7u8?FIL^=@te` zbVIG1ZyH;HX|$tFdWycqBvZ^t)mramBw3M22u^t zq5E^oL-(hamBBN*kG`qtYJ{5`nSc@KR5i>erdkI244YB)WPES2cU^uG9YlPz;3h6k z`v4?xfNYocuSopY!sZ^AWI}>8%%4$0WsCTc9A}q^uK8+4AGk|)W|~dM0PeW|_Nr=K z$rgwI$u}OG)3{7=SF?eNbSh}RTnTM)udCQ`s#Az1YTbg;KMUW$_)%)+Uwdo7jbs)G z3j{c6MeG)n9KNFiu@}V^Jp3jW>yxV0o&qzZyQZ%pj+4*C;U9bt9?h1e$HtIAuV;AK{dILqFJXO;6$^fJO!Q-2e zRp^B=c?T8dj(T5MAmiy%D&=_ngC?+B=ztr``;XBlo|H7JA<)LlElvc*j2@T0&WMTO zLaDzjwBK7xx&O8BqW()04*%bYsHGkx$}l2ME&*bU$n(b>>RW8kG0S(hH!ZF_)RgtJ zO8zm9l}tR!r*yLoak1@&VorL`%OpGf?*+mHG+hMM;8)=B{(Md^- zicK#zjNL*pMj&45t9TSr>6L+zDV$4*MsNCK`nd+N#E%YKMQ`vEJ)*#kHans3t2q?k z1R5Qb<^LN|P_+G4{XijfPNPG5fK;X6g}tqUF3TGKGu0#Z z6Z|s~BKiFo8=XP_^7KpNx?~5%mz?!WrfMkXw(nwU!PY$b3MjVDGSN+o}fP5KD1>9BD86vDsued zM-Pjr)5OO&e$h&LMO`wCd!K{SgjO=|3Dp6y+nA^RL}sF28LC*W!*GEW6uOnHnfaS} zQ0A15dfUDEz=ksi zJ#JOW98)>Zu*Q9fg^La&?5%8i%>gXXj#fDOp~;scap_`qzHxf3qcstm<(bo8BAROW0Tj zzTY;5J#DG=Ysoq${NvAgJNeoyzZFskqj9;6b4uS8+>yCnMn)TK%_V|?oXeZkl*cj} zFA;~IBErzodqgWIaTDV&*18(zPJ>$H%x2dX;NY=1oz#J`F1m~D9ygn0n+Oy48b7@-yb+uf6@^uc-@RPb@7PovZj-G0#G*6tJ42e%9lu?qd zWUh-(Q)lPmHVy+H(u}Ujif_)BidDpJ5mq4TJMnj$;Y&#Ok-KYvZh8kTWqofgOcLjh#ea zxvzH<*M8FNVEFmo7p1}m~Ua|)EbOt3D*@=31I)>dhJQpnHJ zq=XqMt98zW0?&FyP8tOe&j^gfMY#%0zVmuHCtULC>s6|{s?0iV~RoU5{Ac z3Q2i`ryV{~>Dl{iiovP!coRZiQal_1Bxu|OBqX1=c_pUZIM$K_9LitVqy&B~_7_u_ z!_`Crxb7<{8w^IjKT$xWGjVrc>OAmGv(W6Ygq? z=^2*M{O26@vsBVc=XurKWQxhE^!6>h#INhnczz#v5@PBy=VnmF;~)4={eLLd24CD4 z>WvVEgdWOgF%~iOLWDZFxAEiC4TYia40L)t?98cHdN6{b>bs=kYwqUatsZJ3gu;ml zbsrd$a!hy{4L|Ht|irE;V3)bc7-vN&TA2@O7V? zl>t(vcZa3Y*$mKi99f@yh(mrMN9HCVKq@K%ODI9Kg z>D5Mc{9aqkw2)!LCNFAFIT>;&OWc3Ql;wDNC%hyvwxnqCflZKOa(kRb^n`y zYQrE~Ob0G1s6paxbAI=|IF9jrsOyPZM zQ{zd&!y*7_gbCUECP0LaAswA?(YQ_TJannNA75gsAViEX8t_$p+g_|?5AP7ebqKyR zAoN|VGtACZDEoL#i+0g5wpPnpBotcADE6I*a3t;??x*5`PL+6Ft%z~<|zYzt|g);^h^HH3&-SU5CMz-}pk7U?)T7de_keWfn+Ofm# zuID#VMb1``$9t~>VP56hzQ3n{{2nD`z3uq3yeO{}0n>dBjkJ|_or(R*=|AE`tiMo~ z@Y9Er(C>Jk?e7r~5;_d9r|=tRKw+;P~;rPF`Woj+b*A5*K@2q6#`BgJS}Y>3F? zz__Z+`Mp6E=DG*x9$2%8HoGs!!dTA8=)c+@jkEC0`DQJIkIr&51jcn)VMrO75CJ0W z#D!FwnA;KTb;2N@@RVdP%+#1Jgmf8FwutteFnSEbK^}6rR21lHGLZ~jqz>H?71U_H zo-Y`CD9KMomNDlt#J*viV$sdua(jBu9An-t9DQ7VBA?b9y^}Jyye5pKb6})d*$@gMD*Ms$E zM%txu8%%}O)VqjfudT74roCJx^8`L0{;70S>{vdADa}`qVP|()A2^#1sO5=PIQDw^ zU5!WG+fO8jM$%=~?RML5B6F7O(5LD*mcv%L0;oIAa$LTes|!E3-lsk}a?rZJ>WxkI zm}11Jdf5ETnz>Se<7!ufNhozCR(#31m)^t3t!8(=t}NSQw(^gWL*-B)I_AP|+1Fc) z6bBQ(lUL%N&Xp9U2321gua5>UuldV+Ue(gF>&dG_av)Gh4py(eaHGusxxG!Qv){P zGyf0W&A%_Ua_bxfTCXcJ#ml;e@OCHT>8x@2 zW_ZzSD|>(1G=R9vsL_3I!J%%^3f8VUSq0cdJeilWe|{)Ub5n1bA$j#O5)%$HIVB_Z0kUBigbpMs+X8juO z{HgI|%5X8o(9sqKx$k|lvk5r4Cer$F5`ZgkEqPs2dF2QAkh79SN&lJ^pgjGD4%!-{ zfZ~2&MuWVY)7 zS1BM$Iv#EGJ4VpEJ3F=B)P8^>)2$nL%9?~XjTqwArDPTxU{JswEE@_q?51{X+^dCh zX1l%Lo%ojI1I*}RY2*IeX_~M-lnp&eNEVsasq4{AsSgJbEjZxj&Cq+U1huDiqCg3h zVDDUFSXb*;@x-ghgof8}R)_j^_Y?#V#Y%k67=dAUv88rk( zu@4><@0%cm+~Zs;l3jnX#>+tX^Gxh-R!IW{qnU#5e;V-Jo2$`$4h-e^l+{GkX1v^G z-(KY)KgWvv#Ri2(A9Dm;-{fgH%yF*z+q~b|;@%R|gRdG->Fp|7{uzaiU?(*=`Dq7 zh$L@pVJ5p`v>n>c<16#oU4UPy>CBR3*ZEein6jA?m2k|$!HX=<5{l!eOAfEKmJKFR zXV!bJ4R8gT8VX*HDR``1OFKViu;%aynSRJcs*!FTLr8dR;j%#vk@hRs)v*yLks77U zzpVO?fC;w>9#NWiteMn1C1OHe`*QUC@ku!Vq}_)mRo>Z;S?kes(EHV?G@lKFS;-YC zezDP2lzj(DguEoF$0H-}Tu%el%7Ilx&#@9b>BuzTXM#XU^}0)i#g2eE^vPd<96$OL zZo8RCvu7gUi#DoFU!wZsVFmH{`oIwo{^oPY^d3BLO6}?ZATE zM&SToi;tDN=`4Lfsz%elS38ID!a(?@gR2pY`+#-UYIY|G7^wj_yQUnW9h>FE>h$~{ zvJOxdQ|+i;ac5YCj1Vp!?7+(F`mi?>7Hdsn$7C65tXiLIF0O85G<%j|SL&k1;Pn~* z4+;*cWkz;5mcTc38O}I?St+f&?V`{o+8L3xTx<)%)I`t&c#eYPq~@39Dql`&Xo=we8;J3H(UPv1&++W5XGf@8Ls1@mHa|iV3@IA101FN#(I1 zB!t|Gl+1B~7Kn9pT)O99(mDyAc!9~)DWG7q{F5y?7UZ)kCVlF3|B<6?4G)sgG0vBO zHZuzPxs=V%>x##xbq;eKAyZu3vcy!JRh#zmr8zICdM|H<-hm<1?u9qM-}%+&`oizw zu^=I5{L`lUg2RM4KF?+dg3*zk$J6g|^-^9)We8i-@2nllqN>0!=@V@^{zJss>M*@$e6E z@!mUO*nN%EYy1%fctUu9a9v^1+wekL_E9&CWRPYpB9IpD9vn5#u8tV_Sg`beX=`Eda9C@3mujW$}H$I z@&!bqz-Z>EU~8gn3&vx_l{0c9;lbpW(wq1nhxP4!hhYWbZ^kF0Nc~6tXGS@hKs#~xPj|conr@eiSE<~ zH3LYg=o4p+H&2c#5`7;O5?<^(kAIf!8w#7}fZ>J;?kQ+V*5a})X-`EY-B&Y~&3{gX z-zICsbFmm`P(UczNXtSg#O#K|5IHEW-wO+>ll zbjiRv*7_bXq1B5kUu|4+;S%ybL3C$oxRZcAeK9O~r6W0dp0opcP;h7q7->b!TR|=| z_13NNJtJvH0+R$ck|3kWa*B68=OKko&?KP{wR=C^_@~6!UJPYI{EtCKR^~k5SA{WY zO7^SXksp;;#;UYCOf2qX_J4}D56 zJDgYIA0{h#(WzgoRyg9ZV3d@{9vZE>7=q(LL|LRD%*gwv-Ip&+{F{JGckC2k<`VH~ z84=itK@u#tE@-NXj3@yM5!n#v3JYGbomwSyCTWjFCW66 zUB21Cn-p`H!&-Oy?T`Y^a@*FSmW?(kc zejo9s8*HoAJbj&z52zL(8Sr$VaD=F5caQf6PGn)G$Az+evD5Pp1Cf$#&msdYis`1` z8M4M4OtF;5lo(Yr`3a?h)FUgaAM%^<1SXAoShMZq)TXKPMzHFIqYQ;eL}LG~6vY!n z)IB!jcg845bf8*yu6UF6fbp23vCbt#&Q}PpDd_j(A7&pq2qNG|f~CamJubhtx;)%yp zY(vWH9%Fn=g#grvxo|IxWKSv$n$_@tBgZ^qe=V{e%l1dq{^R|nw7YKr^3g~2BV}>m zQq3b7tI~39>PDQ$o|QQjzF^w)GsikgW>o*cxBt|~+_qNoH6RYG!Jnwn0?Vsx-b1G} z_19RXAO(PAYNAaq$e?XS+FTbb*_e#dp{3y{o zl+}*~0TSU!<*mMpdh?VGv3;U;yyxOKH6`*MJsWRl?YQZp-*DI&rt+9NmakkWdI^$Y zpHEKhHq03A;#RCANWOyOD~&TgXAzljzoaTY!+;Exgd{%ua<#jIf{Xvf54cixEhJnD zG}_81E0-+(SaE&lNuVt!tH`fpMq^}&>b=Md{RiSexxfEu!ig~{XA*506Ds{t&z<|& z@X07oh@4VbpLvdrOgxI<>6qh=;cKh`Ba5}JC@MdZxNE)TDkJ9q03PN8{{YD8Q5U)` zPM^>gHl5^VpLGiUe(RmT-H4pu`*uRtSO8BoSQ6Xmn`rU#xmxCYGGh6JEdXEy)%1IV zmv?+pc>a@apar>(ntNfmCb`5eT_!&jQZo^mBj*A3x2yde#%PpETTa!KwE z->1XN(a|fsf-B@X>2iiLd*Y8Wr~7hakp}7Gu~ok9&r3e}{FVs~?`dZk(0wxV;|6A# zm^O$O8RuNN6-O`KU^SG1J-FkGjh598HmKm)_?#H0JStQH1a*{ z)^mDqtJY1&at;vIwNas)2d#H4MaDjhSFdA3sfD9sYp(vjRkpE-tU(I*XYuxM;ikGU3sA~&0 z%}P_rQlt!LSaIRt6$%4v!~JFf!0umD61&{pQHJniPLvo}3A?(1}1M&ELJT!2^4n1@93EiCyQ>sq399Y`hq((N z5LEHK_{viX?;vK7nMrBRWM{Dlx*lqTZIVzb!Z2+6Qv?p|4^xxalBb0Szk(xQRByI*&TP z7er$wZk#b!%Tb9At22lzQylY9rCgU|g2(y_Qb@8=FIhAIwDae$pN`6dXTh5~xl@`G zWk1F+h#X$Bg52riXE2Wr6LrxFtzBD}!#8ySNMrIJom}{_x%sDg`>G+tgGUZ?qIJ_I zJ_aoN%u3DOQ8}eg_N2P(xe%%0nxBCtvB$Rx(1vU*Q8( zD=+K&G5m&L_V}BMQuLHkR9VCehR3lel1Ug*n9;wvL*d{lWD2}K>a=U|n_Ics977I( zKE-F@5K@?SoFdH|^P@;#z>r@P(GDn6)_H{LYM$Z#8xOx8>Wc)lbZcICQ+Ku~4eQf}Z@hdCz zn3Rw!)FJpxQtcRD7wv>B5hfA|LDtt?~DCu8kTf-*&lTiGwIq!aSvHWnDj z->o-1(RCeAHcCXxys#;4GzhsgFsU67JS@_F(Y3HcIk-?Bzg(V-wo#Wq3}#Lp%KQNG z>ThK=!aQc1!r6(h0imO;O2?I}k_?FlsrT3nvPlahtR(_A zr&kRA3p_mvGBOqOwCO21|Hra_Z{GCpgofU+^=Yw zq@E)ng4hi%`<-R;rE((6B?<;>rcE+kWu`jNF>&DR>M2+qWQRM4Ftx5AYN$UQy~Qn9 zOCLe+(nVG)0|?TFCe=2H^|}Ch4Y(0+A(YJSsLHGbPvf_qLa|?rg)hKL+u!G5WkQlj ztOS1K#p0T;*Lz%81*|%57TWAi@2Gl(<;*lCHe%cJ@A$&XpT8wB%f>br=&b1I7olp?s6A zET~rb?Ep_%wM8?{F^t#{$%a&hCBzP+udY3F=?({oc#Bn#q=MvitNT);u;Pqxo!Qz$ zLgBST$Uw-COnL7o^f#ngPo(&mjPaHM!Ho9zRjWpAdEbU@)5X3EvcuJs@o0Y0^uDp!0Z7D2m~#KgQnp`1$U zzQ&A4G~IDpYTWn*%h7y+Y3nOdn`^&tX~yH{o5y(!^uJYy?7FB4z!JH^8xWrV(A@61cF3h4$F2N>a71QKa zfX&P7`bIQ^eI?Ik*IKKlFD3at&My7DpCBb^X+n$EPsIz9VlTY&;I>W-@Kk-i#aasW zP{j$LJZTyT{M#amf-zxm*6%;dY%*I&0E+mnRe;le6r{l~k#f+mTe@A!u~t6erLVzj zo9Fib1$2u$fleJdIGZY`E7HLRl)SV!svU4KXd3(nUB}tfG8fRnD-nL7OH~^G4i&2- zqGp1N*rya1o(y7AKWA*#O^*HF#N5^!#HwT*E^vP0>G7K+H1Lm-eCA_HAX2bI5p|^h zfpP&*+-GiZ759DfTA4_irvt%or8k2pdIsy~cmTm-(i#L6QPtB0_j(x|ftr(w>je-> z{S$U?VE6t9{{>3N%Ib1w`*Mv!KPLx8U%p)NLDx>coSY1;wlY&GySIQ0Q04t0Q~YhY z1EFEblVMGa-xb+%wF$SMrG7i}Zm~QH){cHoroN@&0VVLSb;Dh4a*5;|?yh~M{!BOO zUM%Bk%1Exo34v)@L^U2>wHwn3MvC~p8W_QsA-n`&nl9xs_4;b!9?HV;pMgNPEcf5Y z29rh)%=Q6q5}xnshLBkNrY%6}q`)(~mQ>c?U(k|02ZSp?1KF{T>cRE@t)Yvcq;5e3OfjMI<*@iWbI)b?c0A1yo-+9lSBxW_T@GyGqhx`4>$dui{75}DYC|-VA zRm(u#OUAbZ6~X!AB7*C0y=7V>%C%iMJ)@;b4k-;}mlw$MMe7v{7$+2BexTKU)Kw<;i08GJ#;+x@H;3F>k-&iyCj}JrHd6}2 z@}kq-^dxbcuvgj-) z(SNEfr6c6Bm-Rxh4N2y_G$icJ2f(vA+{mfdNE*hiFx#{N9G<9ml067!QCYarnl3jG z2ju@zrv3*2K~L=p=5R`vX5tTyi6xA#$6tKi0L1ysN`J3WBU%yhl4X6A-iZ(nPcv+W z)bB;q5EIh(jxZcqIG3V$^|&J2{Rk5x@)kz(?pu+7yJrl$w~7z(Cr-NY?p8v7Aml<3&o^Jwq()Hk5%IqVG?CFR^9JSaER`yI!;#Ve z@4Fo2fPq2KL*SlU{&Sq%wjNKY_0*bIusquYV0s5xi2cR&td;R=F>BQUAuO?q6M*(- z7vaDSQUbk94*L+}2l6+67_pv$ct|v59@`ll{`&}B9i(7Bt^VcPa=?8$rTP|=NWqZ- zcES?6oh~^!G(w2u=mdVP!{HxtYE9A;6Twf{72Y}z=Ti@Ka!~JNFcn@j)ffL4k~sT3 zTgek)#2@sK6;8l~k0%;DZ>bX63n2dhl5M7RGW|*gB~83Mm1XtBF12Y5!y214Q-YDe z*{I5%F7F9unq72$Amaf`l_o;NPsMjLQSXu95_=h73~)!GAXTY@bZY0AZ)>E+S+_F| zHvioUp)=*9mk~&)?Q&sJ_vt^C4B+B(*`g6qRoDDR(L1FChRRVw+5_epTjQU1nQPk=bW_cba>ijcJRiCtyltY|O_* zuFsoh?X})Vn98rbM5I=C54c`TlpJ~=(BL8wtb;~YUo{Moc%S4wy2?^0`03sTw0G%H z-R5#-2*f6%RpIz=p*khr^-#gr9u<{jg(ayPHUt}lT+LR2!avV#yg$C!>EKNh6m}3& zYyRRtJrrwmkuw>4jJXL2Y~;T~(YT(A`iDAXrWcC9h(ewhWJzMn8&TT|X=LzjqZ>Ethn zd^x~I9}G;g4nz80SrKDYJ@*)(bWAsT9KgQlO1WMy{dZ*-QOw03DH}D4lFqz@^`ia{onRY|JHbTT-|5 zuC!ECJ%!f=m6$ICV?T}V0e}l6iaSv|eVq#AclD_DWzCG_oj59S?yDTG5u?pMx2eN2w}Z6zJL=FC)@0 zc^$zxE=5^CN-WEP=cGed&o*}*88K3*@(5<))zA^wK*199|7`JBSVCvOqp9iRzD#wV z14{2j@#W7A!mmE;d>;p%=4XS)0RsTT{MD-b)(?Jx%+&l-DiA4@BO-uABGT6Z;fZ?I z&X|hd$fj2_OG2oDOK)S%=hP4-bWA<$84Rkw=YB0gV~qp?wGmx&CPeX~zWv1H`*TFB zy|Falmkq7~U}Ld0cr;J2w(MhnW-XtLm4H3KS5^sDTn7z}02NgIJMXDt6H0_nvOTIQ zl=>%JzWNNz?Vu*WgP;J94OGkY8Nl0o{WV`^D(`V~GTjJJCezJ-#?&2wZvEQZ%~Vr& z6lXz?@)43P0$uHvST1daTX=)4WT#`WQ#WnXz`M~174KiKpPyt z2|z&;0Q3<6-J7qgJ29f3Y6f!8v1R}zsU?~2L#Zj*ey6kh0C52Ymd*9i9q^V3xJk43 zUv1SpSHQasaDw-MHujpW7#|@k1kE&1Hctbu8kw)P8hT)eT%c1kCIqm%d6ZPyYd%RU z<5^zPS#ScR$W=a5OkmW44k>->U)D* zR89tZk=!jg6K=?M3_j!z{>ZKuanJ&$ovf6Y>1hD;E56xTcEABZaqm$t1kAW_Q`LFh z;9)FMoomD{y=iS;thhM4K;{)W_Ro3$9S^YcG|~i_)2@4EL>6R#0!iK)t9S*Z=a{ zyhXe$O8Bs+-G2uN9wqonShT?_0F&U{-Q8V#hkDCIN64X}4uj_kx(7;2M0LBucBh7r zWeq#r^F6o8(Fu=basYMHaXt2bvGgHy~i|abCGmiKj-$NL8)e*#d zYf+>V=e`Q)L=AWo9RWWi-z`G;2c`Jss;fihyt&~rzz zHV(W(B(>*u6N~1vJRRf1jZxF6@{JHUo3U_@fy>knYWL+&n;?IGkDwgfY4sh!SECgm z#yNvdzYiTN$ppXKP-S9Bt*Su9*!GwETNG9S{Kcd8)~dWNWFDoY>y~9Q(aq3bg#m$4 zQpgQ-;r(Ca3ihMDyI^q$H+4$NwlXZkuN8ONqXbKmH-`LA=*zCC4cp0NAfEhs1W0Bu zCbod?t#t1vTJ=%tc^ue_WWM1!bP*^sNf_F!#nwinQ{LyhqQAQ?^=-FehwG>3D_CG;KeE z1qVklDxYqB0RRCo4e4{oA}~Z|EOB+q9LU}haMYNS?A^1So?N{N;p2T|)E-V@1Eev< z4#m#(U?XGa2?!Brl$KlOeRHf*ghNmX-V8=uRZ-HfDVLdz3!r(qb&56;^bM50>-9fm z1YxgxZ1xlBG&;?*0Mz5?GVPYFSL67F+q7v9ddImmSXSSe=_SNMfcW7Z z9S3;P6Z*WO24gR=^`e$X6{ZnjyGi}FljzAVKV?Gxk+taI_J29n@*LUL+_B`6Q z(_#lcM;sR(PfS&aT$+@ZssyySjno;6Ln(xdEg>TM#Ky=-nrRobWxSX%Ot5h?z1O%*-j+uc zkM&zc7x~z*tufnB{dKCM@fe$HubJBnFJ`;`GHTn^oQR_yImj2${2{;_|U&Hj* z3wz{E3f^XLE{eHqTJIUVs7hZSu0yF8OL2U!fjYu=JNjGX@7lSxSz0K+L&KVRxgp$w_+|J)PF zK}G@#x7Z74qcWn;;Lf4l@Y^Q<2#gI#1DT;~lRkg36hmrVIW8YrgYC*&(MfvyrHqJR z97^+N-6gG5X!YLbCu?P)joC6uU_ZcE^bQNlCCmD|%l_iV_gW^f%MO4d9=d^=<-%p*RnLyY@qxvJEM)Ld7`GxqIdLkqVZ+!f)qCFFhf1u zYeh8`b6LrCL)Uy~@{+QMAA(GS^xex5276Hx|oOteV*=Tsi^p{$8FvFwA6 zKB_BZDToljTf%736UbyC_w<YJ0R&ZiBu zSuiMS$ho(%M*N-?>Ds%%ZPMI5DXcw?Tj}ox{7(zBF zH{2!%LX{JE_Byb8DYVsr`IXLfB^`cB;P=d^iycdDkc{NRPe+DbM$-a#-OUdFQ)(?9 ziiIFWEc@96A!y=FB20{#?OEJTp>}_IDSUgK9nWc@R^lcld|sUqZ*UfUR7bzPvoC8+ z-(B|$GsgD_tYTV3tio*MUG&FRK!Hhl*T{z(Mw4egly+I)LpLJp<@r5!;Nvtfgeu%( zKYQeo-!0&^cKhiGF-=zsnuy-3v>I&Je{TH!qpVO|bOk*J^N5t45kHgYMDrm|82QM` zoRmEk&%3Guh6bP4GMc74zZt0G)wg0peHKJ`^>w$lzC>lLG@ZP~&&nHkq;Ac2wYd>g z_W8;%Wr*d_yyeEDLeoNRWoB375bCrI%67<5Mf3$uxH{d+rgtqykv9GBcWe%3Y4vx; zUrxY+FHMNpucdP(@QwAJWoirzRIscV;)FDUkn2^AE-E9&_V}K+t0v9Ljb^SCfvMg3 zUP?i>5dCWR<42W6c6pgJvl3z18tS6AI=woML25W;m1X2)4JATa1M2oPRBe9suqbxH zWeH{#h#Ay?a!r)e126Jlk=}QF+_+|rS>J-M=I|t`Ca%xuQB+0fmy~>^3{dmd(R=52 zeW)m5@F~i*y09Ekr4f(y@W8ijk#-wVn9eAisNG3pHRyVfa2E(h;^3Zr-!DSN>ddu- zTcYcdpn zA8?DZ=xb0#^F2C~&CNJLLSJJ_Y^*z?CYv94gI$@^@+2;kSq2fK(I)^Z)8kyOPLErE zPLIFf0f&584hSdtV7jeT ze~1R_mPbUKl-U%emY83}Qe}g%i`>gZ{k1|)x&M(UfMI;1h~TS$9-qDZmTtCZUTsWU zZ?l(YN_jWZ29PG{bM<0#;FKT&r1A_mJpOauhp@K;fD?0TB#(Lqh5iKPtKf`Nm<|zT zfE;X02%Ay&lZGlQGd15;aA(>zb;IW?DLb?MRvm&M5Bz>eqUgefm99%TMwpWnbxrpU zu=GmyqVLvz#io_=Ovy=l>We-x#4L8a9NT!a+k@0np5f)Qn+$G*{Q`PVIy_jqSw_Ty zcTs|!iE7LjWezC70gJQk>tPYP<<1b&t?CtNuawd00kze!>EQ))(R4*_%AR%|;r8Zy z{gUq$YNwxqKgjB$>cCI0rRReh&CrdhDLC>@c3z<}%FXFWH$}zvf2bAgkC4O&o7e!> zSX^>K(FqOu&9%-Q(nY`)Dyf71YQhk6Vwe+}^xW%Z(fQM=u??J_c z&Dz1to6Gm?$tr~$ba7px@mO@8)rC^_Vr~n{1Gq@Z!{lF?Di{My`XGhc#4mc#Ssu^* zbwQHI?A_~>8#XcDL@Ix9#?=Bt4_%8b)F!m&b6Q+qDh*YKltQ&WKkQWzF1dWAQ8NVO zf|M)Gf4w!5)M9Tjqo-}rX}1ceLU7II`j3mNhJF851hlz-5%a3P(h-QcGH_~`*;VSfR5~qfmRj^r1re^ z{_|{gV_fvHI}M>iQdlI34WW!8<-E*qCE7xyFQ#O zq~r?oKsjKwUpxPn6LFK@fDgrC)RVL6&h+Fm20{e^dZ&xyrCO9X*yl?*1F8W`cs^;S z!WoN&I$}aRLAgUk>kng6Uc+@DZDe)9Y97tatM}>-}-Xu(CTr6lfd4(!=c|K*i zXUE`(x8Wm#ssPF7DtK4Hq}B@DBiq^wAg>U}gyKho+Jt!M0(n|d-Pb209xM-8|3gsJ z$H|9sPhG$rj(Y-59ZIR8T1O8#(!3SW2|_6^_o_I7XXcBlwmA3{bypM^J=S`oy|Gcw ziv&23V#l^g8jtlkT*=>>hk#OK3;XCRi7XY=CCc{%21-~<4!<}0VyQ#Iw~cyhOW(F|%F z?SU{QB{UvD_H@sSdDN2Oj&td~Hg!AqiD>39uVX^WQPf1It?8+}7*vr5^^NsP@G5G_ zUU>Eg5EbO-xoo>Fpoy{Qz)MiN~YDdt5*0LKbS zsW}ZscN2tO2=n}r(wCFypO+8<$a{xRZQB%O>OpZ8yG>k(TPxL4mVPT$hs4S9XJ=jl z7$60{usf%TgaRq$Mvr%Rt^xwZW!wZ#P5HqmsHKI>`UY_GH-WIGviKw9NoxGE;FF+L zccj9~Kh_2FBK~6t4wr#WiaJ0_=|%bM&~E6A)iGn*`~B)(kRGBJGmkv(uF+*!T>X(t zX024F4|KXhv`(d}N(g#10&Yq7-$iD9@?Jm~N5=ugRGGRP5)cTw)==+2m}mf#Nkqjq zF)3-{O{<@sF)WL00#rkRYjW3aG>1EUen+ODBh^C6954)CCv-1adi`P7esSbU@Dx|E z4#UHGN)9`NEB+wkBECD#f$1f!_fbA5urcS zyNkkIbt_mG+m1FbviJ7J)_7R1NghrPE)v9m;eTF)!&Ch;cHdp;>zX7{=6`1QmOj95 z1mMTvafw$^qVd>Nu`qDptD#t{`<{rA0)vS>O`QPeX*Y{pjAtKq0r(}!^GJ!lg#PrH zEhdCUA!!N7l7w93!6Dn?gir6A%k+$qg-cu~S{A*sWdsK1te$jhW;HP5l1cmEVic}^fg+bmFZlTkjxX zK+aaDBP@+56kKW+_8xu~n-M7H0d%6TXiZv>)JN3O-XAUXe=sy%3?~S?7wMI9)bD(M z8u(FQPQq`kC6T1Z{~mEdfY8nt0btO61zhMpaXu81a~y-ez{WG$gQwxh1f`@yU+BFS zUxAWDwX5$m^>sLlncxyJHLkxH7wbrHhP4rVsW>~ni0t!BbCRZJXDM*H%Uw)A(_Vb_jNP~45}RBKJfSz`$@QDEH9T=If@;2D zna=yT(G?bc+d%s^CfW3Z$n)HOOW`M-vyX)D+yO>=&hdMq%uvySl$~fu zc@d}Sd%*gH-wZE~h1?s*XhI4y7692!&gVvyZ23LX>1f9hR6g9oxigAKcoBTPueY>C zr1Rgyq@{eM#$dPGALC~Pq#wc{MN$!gzJRjc2gQbyTlc~Pp(h%WQ+}aeVm#w}Q>;XP zn&X{+QAlPwI5Z=PFc{(QsJ3dc)9qR6bpXlb%6k}qX`T}2WDfFGaR)vyB-N3@TM;== zP2SzLV@I5jp1?p;sN{%<$2K1OzNt90g;+fjmq~=RgJwjJ03{AkHC-3O?*M_y+m8gk zUo=3QS7@#E(rq$c!-38#DOKdwYaQL_w|)mnpeUU4jYY`IX_pxas#)lapz=AUjw&3SEWDDP`D#P^{=NTF9*!$Vd*I-u3c~RU5 z4#Y0vXJ8A}$E-q_7}o;VTlFJ-Kz$V_;4DC!B)PboJjlmGck4RmMZbMrYSVjyAkhB> zu)U=riC_vql+cR5)4bPBg)d;-91mNi`2@?fA{^SVqdPqvYfohB6EFhQW#{Yi zl!{Q4te)WDP6j@)k=}hIwbVBp=vg9WBXBM93SdF!)=mt??)LU2w$~;v+nsDo7%~~! zonM(i+b{KV%V)H^Xi4hfl;c%ddWQFee^uEVBvu3WC*eor0T&X7s91%M8XQbq`@qrS0FXpCzx2$1K+Wp79ey7L{V+ z^!Mm;iVdN$gdGSPCs(D(Qx4yapKz4%{Ld-l<9IF8OO;5OQ9=ki44?LA73WFWHL4z| zs*^eO75bu^r^a);v*{r@rjiTG&Av)LCC#)mI;qXW%mK6=Fe)@GEev#%&`9GJ!Y9uz z#29EFY4Zw=#)}c4v#j5Kc<0*W?a<~B__paOohNsQE*=`wdcp0v6XTm)yf3A`5QfA) zsMZ&UZhjU;b26{HGttsy>C^e4ESF4Ir(!f}w;8HdOBeZBvmi?SInCr?QQNzc=AM2F z-!hUi#*Y3V$Q!(omWJ>_E*yQQB*E9_8{PW>Q+fnb{X(-H*9s_h^q(cHJet}{PzK;U zd17$jNq{1t*rUo(wWIV8p;UOoi8=5V20_zr!sZX;h~3tRhx0)a0Eg>ET&w3sEw)bY zqc;8Glo7q}Y@E7L8F0=smSg!l;ji{S=}Acb5R|wL6la~jU4gA`1eVGEKbL?2{~qVa z{K~t$$e|BwKi$Jd@`Q>ZWf&X$g7kD*zc=Dk?NZ?==omkm}xgN&?g2&ORS)iOf_tuGE@jD3&t$(CQ=z&_VVMpx)=Q&(5|u zD-phyf-QGTXJgoYiu(o-4=Fg|Uv(Y$NnORcD-kopb0>o(t^W_dP~pp0xcvL09fR=V zr0@Bey?ef!+&m%Zr8R+*E9rnYx%WG+?w2C$BCUS!T50ar@ojl6t@jM1?>TOhDrm_l zo)J9B`xug*LkCG8#n;qCS9mVROCN|%NC?5i`~vNeCxEK91yl~DwXl!uB2kj+B~6j@V{4SCn(Fl1Yuh%P#H1dPteO(OV=1Afen`E^g# zLOm4b-aB8GBEwVA9_;6VjinXDsk@L{Q$1g)xdluz2^=D~XXq(EO}#Vkz;?pUW(145d7XSKK)783+VrzSW6b^av&3xHWDM7NIFdZqdWn`JcLS?vRjD|!6kv{IGN z3>UtjO`EdTL_hx(UrI5R6B-o%Ra3XtIbW~3ghSCiq;*n!L6Y;{fcaIw6cZ-s!E->| zDX2eqE^PUo𝔖tOk|vmb^Gx=r7Sk5X2n;X1`JozNNOleIN<)*6k;yo51&9uxU6p zKSb#kyw6J#8fe^?>BVnNI*k}SlQ}`v|L30uOP_tZUyKHj-NMM}%Eoi(6{n;5Cc#zO z=D;^QB7KskuheC0x_|e@#cq5-22)b^iN>3gcUKh~hYg34Sfx}T!)~^WlYL5$#1(6u}widx@C} zCpOJh32rkT_}1%=9nG9m@tNaDaZs{pkgcBL&`Op58>EtQH_}dzK>}Q1q8PWsc#Jt- ze;zO~K&97itk4480S*&2=DW%xx0hZocLU2o;CG$!YI+dPGtwT1fGqvOj5O;8(Y2@G?sE0&3AiHsBUT) zf{*3E(Crt=VJ5FvmjQ5u`@Q9X6njbPVkasIa!1m=>~x;2aT&!2sq{FsacQTpfZvrX zk^qsJP2jB9X-MwBhX%_?04>0V7^rmE1d*jmhDi{ocLudY8pP&f<*&65 zKjC?GqW=Vp`zchL1yo|K^5uj5^coM5(!;FXOvG~ZQeodEqktTy=UW@Qe)Xn1iD!rtFK z`kgHeWpDtEgPfB=dkRDZwfJzwuT;-DtQSQGGWY|x0CtHMY$R%!6ih9MFsm$+@gugU zm(wyq4l9N+^U7<`lwP z_5!vsMFDf=6)|jm#NQ>4MQbMk>B+J*$)b^Jy@p4@-x}~x#~;VOQ$$1taSr4(k#RtF z(yu_lfL~>SXYyYFhY0a`02<9gWidpzj6+6}4bmfB0Wu_gG02%fv+2{M}cY3|F z+afOLB z5~`qxQovlb44ck8kzkXVu3xD$uU=2MM7cy^Ye4yRv zzNly8993b{-$}LsgC|Pqjab)1m2d=BQ?w4~^w8)4(n0&VOEcTR1k74NbGbKN^_tUi zTmvrqBvS{=n6YuMv zlk{p*4h1Yc{}M*}w%TdW9NxL7BUvZ`^Z%rrIl50g|3HUnskugp z+UY%|5SN}Q2Qdt+q*It2E2h&v7-QzS&%h`4yf>GBwj1AQJ(qTo>b~9j5E1H`(JM04 z`kr;u4t6SGg@zu3K4jG5U-oKTBuV&l&y8nGIJ`vVZ8~qpj^@S^%_vKZzsuOK#BN3< zE#cA!8KsYkta-30)H@=gmoGgvEo|;DoldRl+9oYo-;c*&v?W!{X8&35-Nd!$n*Ty% zVlf_X>$M+t4uO)^YneJVk6oHd&t?cGhg804SWW}gQdG1&d{>l)<^i+@NR~A85%kva z;oU*V!bGv*+X0VdfHtYMf&R~~j4$-5Q)ZNap-ZQ#3SPVVH8*`~8rtwYL z6p$FbB7s4Q@Glzo`otOew4Xn}!@V#m_X!fPXB(gT&OS7wnzc$~@cb-0}t2g_7r z@GgpM>RP0jP1oDaPXf%#t2J)DIPPVvaFX|MqGNEXMvR1A1`PdbW zz(q3&o-|RrT3hC+^Fo`?OYXPyeC!&OV;*4cWx05$CR^ghb}Jnk7f@4C>F-p;w*jHa z?a5t4rLN=Jnq0=x-G*T%Y9}n&J^=5ngWQaHtXp&4H zsC_I3VWe)0w4p$=^3ZBL?`?mZ{nZ}_(uVwU(i9W%8i@W|$??JC9{M*H4tz}cX*QE) z&dmGvh~A1y_{P8Rb}I{qZJTU@1`)zd%1{}+!$_vP+ha)Y;r1=Js$oq8{h7$tz3BEs zE;ZB~1T>8uqLQPCc!RDzC>PUrjQ|4oS41$qXFL%|p{SvBf^(?#cr(4^LRfC`%b{<{ z(Hh90UAF>9nWxIf!-AYsc{cg$uzZsO7yn*>vb{{OeBdWEpF2hc-Zz5I|m$qTq-e(Ac4L7(W>VRlue`LGR<@gG~9S{Z_n@A zL}oBDz1rzOur9JOeiI83lzUW7+MXYH23if3*{Mo9SFH**qKjyZA7BuHm^-nuu#(chIwXivZ@tc)J!c;q#T# z^gU+m!6+s9Yx6g6^i?*1`o?8?4>`Hq7Iyie*#`ARD7CqSRVnB( zhv`d4{|RF3Jw$`G)-?A^Hoz6+S*#QAAFTVbS^-u7DQ=b3Aj?E#QDY3F()gw856^@f z3KTs)e0BlnZqM?c|7wrOUG-`G#3h4FmE<0LIVm5c%t-$b=v*9PKh18WKk*ATyU_Oy zPimNy(bd&uG9-XPC?BHTy%n`)L1kEFi)Vt{)M_shj7jvhIf?wReW$`^>W=kXo&mmU z9_?*O4Mjyo^;klg(HQPQf6WX@I7IxH2))z;><(i$Na!<5rPzX5t)F6&>)92A1c3^7 zW=ikH2rXz59fPui`w%sS0J_+RskSKsLN*)8Ur5D5wR27GKRt3&Gr^6Ebo{MX_lNgDbsEt9i5 zh7t<;iQlk7N3ii|%IB5S2{p>*cTCjRJ^uCTWf0NW8Dbw;qC3$a%)b)}f5B+g*_Z#+ zxC2t1IIziRKL06U4@1ggzFot3SP31OWoDKD%h~KQJ)`c3q{V8o+7mE|h8m9?tx(i#wpkUJCu`y59fX_oClj#S*=~ z&9ULSC%|!NZMZVEud45_9Kc01+p%u;&-rD(z^^DSe2`R+>WBz9%dyPRc2rM9w)_8A z?#CbezAmug6R~1HL>rXwMZe5^POys>sQQ6Pi~XLn&9vqIVYAi5_|u&q4jIfd{ip9MSa_w?J*aI=Y;A2x1_ z`r7K=0=AezBJVjriima`{KC67*LGq3BBAlU()M?6D)H&KJpU!Exgfjr2p?x|+Tjtk zt)YQPqQW;FqKLH_P(6puCtPXUab(>RDeV+aZF=53w$tX;MwLlp$ys4MLw|izr!GCtui``j!(Y(l_5P^pCWc8BA0xCo@Vb>^oCPpP?|Ngt5K1dYm- z+4KBrIW<$5!0MO!!l}f@XoicQI5uuqEx0gG=Q(QI_8U{{h|YvSMCw#2)bHi zspq==JNsBF)*ie@1TbPXCE{Xapufkcr@~Hn-(iyGLZXP&h(%9@wZprKDVt{NA4A2% z0CQp0_IqbhYvImhzm{L!|?|Df{hMjlDaBlGlSNB5u$*b(r^s!8cWP_q3u!_L5JsVN#g@tG%Q=@Rk z&{iPkk!=#Gp;pv-Kdph+(W`hB&-qvIL(mt_=*SmJ!^Zovn1W~jBCXs7wZVgUlhH6~oL%nhm1TQmr zox2ENbMWewluf~=+LuEgEvY|7SaQlB=!R^7UpizV?kfXIFQ$V0(GzKv>O3L?6XZ*%9ZXtT(5 zjU`}sh>wSVe<7C>x#i0@dk3mkpja0lHkex1anPZ|5kPI)0F0@1EP~)eyq(siyRsN2miO<6&}VrL zL?_Y_V4SvnekN2_>4v$(BL^PkG@ZLj3Y}qTaZ4J!@5&B+aL_qNNM%YxyL3wOM!sgd z33%z4K>-P-+561-BKf*jSE+Vd369{~YHaytNa&eo`@TJQm?5Q655YMoV}WG!8vgD4(ggwvnncFVZ6X0De5qgg<9@|J zx0_q*dC#KozX>e0(Keec#YK$Sn{!Q+@*Z?~ZZ8xZr5)!jbgUg?UMFv^;_B=5z$B3H z)`zDxhsVCGSC9$PCGE=TsuGfsI4<@NFl#^jrHHkr#cw<@ep|f4_Qr+7G}R5hM3u~m zI?ot2(dn}8?wpj}rsF|#*OmEb*S0hdsE)X8Uj@vmWU1|9BX#2e!p|fOLP&zceSk&ox)nbELWjq|!^j9nVp96qu@=MJ4 z|9m-|!1ciLAEGE_?tsjH{G~ukDmLb#mqT=w^Z6r_JeQr;3@cO@;U2DXh88 z-6B5A`gl)p0pAy8i|l>jydSg4zF|{orrMCDyAo!=zlK}p_k$T(8TvMe@k~TWa18$) zaRx4y`(ydY^eMp+3Dol?rplF$IHA}=pfw4z$|s6oKp(5I>bbZJRFYTe#1jxC58AAG9h1+j08$ zbti+r!oaRamhHw(A2)3bRuD()&)cYGb(1a!N*BBI#9f}>lTL$A)YVP4CUzW5G1uB& zH8%-V{xr5$^B=>}QerPZHNYpIeu)|Q67ig=n}ZYTeZ1`*(`mvrwMe3}E?_#AQ?$)s=yfb;tl)rppi&7tXs}Kd4pnvy5Sy4WBUXu=KR^(9xCpHau62NRZ`rQm5KsG z<2`&Is$eLjTA@nTz{IAfJ9F4Dd;>MW2PA>!g=>EWhAMG#_i)2KCd%?A+bi1Qbh3J& zYtJS`#8~jgc!YUUZO2#^iW+-+$f~(XdK?xP+9s-A%Boj9Ov`ithDd?KVF8dPE>dBD z=*s&&urwes_W~^oU(5g7wnBBAPA3P3o%#p3H~=H8mjWPbqWAoHEL)>D?m)PH`eSMOf_8dM(%YWQU}r_{wOO%FM$)mhZprmvvF(z@h~Y^~zH zE(4|dgXMR5;)`qL)^WhX`hpK*@S?-UhnCMt& zMANeszwy-EtVpNQ8p$|T(GR0!SKC3T0+>_`@xaAn(s|6^^#N~-GA)Hnj1O2qY*Muk zKEY~@`z6+v+Y?5%tSSo}?|W9rS`@RtnnhVhVm4|x<>&JWvXp3JitMue$=15%i1BRE zk5%WB)5mX=W$tmM-SyMhQM{?rwUa}Q`U$9ce zu0vvp!myH0_4%m=;Oyy_$aRaaR)R3R+TIx(Y2W(^0s|v?Wv@H-LddtjQ|Jjgg{KIN ztm}%pmAMf-l{oHn`t^SilfW>}ZWqv*C zwBI!Sm8!nbu9*2u)%($!-bNj~E^!3M zA+>^d)VFtv6CF!#+q(l7liD+J5-k#iAV*fb^yYk+WkmbhHJ@t_6l9+?$6B6S>#3I= zy9VzZ{kSn$^H8n8ymHju|77zMeWuF@Vn z=iU|h24<(Sv)c{36ui_$hDSU*l26I%RPG`!lnK4YKmHY=6Y z1y1>Y&uS4!B1OtpWn}kHRi!j_=C*GuL;d~DwTjsxeL`zm@2MVQI2QNuH5>O~X(*UP z_EA&6z&pk6VqILeERhy_6mUN%u+O)~amNh@Wf4?dQY4rTjx7qv2{G|3R(bb1fel<$ z$srxOCcd!XbCYN$};8FY}gYN|z#$LpkWv7z!4@c{T{#%C*F1 zDJp@%p_jI|q;yjz`V<+m%f9jT8G z;1Q}L^Rb9mY<~`Zzg2(PEf1%a%7nNC8QXI^_Zuwa2!!C4HAlz_ZrI*tNP{gN?;8?{ zAzdNYw=~#PcUby$3qy}e#XuZ4w_Vd*fouNuCs{rEMafAIUgGVHom6YR%5epGuXa~m zHe+il_AN{#hn<=});zxNy0N#{0p5kT-E>mihl!{gu0zM4+QXiFdmXTSee=U*c#d2h z8jZlE|8>wyU~=LP#tvyvfJ0-;&X>uS@1M6m8Jvp_-E5Bb_$hBjustoVT?)@Fqg6e+ zm@}A7!K_EB-2dgBcHJ*xO9C%de3RZJ(&_lqx5_WJE?VUO{T4t*9{s_n)!ZG-mW;<# z&JDR?)z+5Ot>T@>K-J%2TZ}uqDlqVtwep?@G@A3S=0abv|Y*aUaG^|%iTJhEjOMBoS^ zOQ|g4*V@Y^Q`=T5!|W3|3lC>x#UgjhJG0b&Nf7q_!oFq<{FOs;-j5y9;vu4SiZq)E zc-g;ZPDV;@^xzc_a3+gqId1mv2TC3Ku@Q* zRln&fYR5__3%CXPAmlU;9Q9?mD=)#U=-CGoi-qKfqN0@9qEB!{3M zaE&|n=z=YEykO`)!{c$)u7@vBV7{r7fd@|8#qHd97E<1Sw0`t(nmK?Y)Qf5Hb{a}2 zAQ}S!{EMH!-NVlo;tN(brl4UETR|Ke(zFxJ{rYICE|N$Fn;3pNO3otY<9I}#dn1HE zZ0hVJ;^V9U^$R0?+yxtQfj}dsC)@#=qGIEMZu)oRr1&~^L}(RAdY}>-S+IxM?~o9T zf|QDFOyzAUhWFbK156iv)H$Fs6GI(6Ax8HRI=2sO^3x;f=wA%C-zeSC&`Y%7Vf-ed zF;3RxD{}DQ^-lUEg+O7@gZUi7AML>{X&5t zt$w8P6X?xttS?}SHWn4wwJ{bSVbMKFhJFo7JWW<~I+k`i)~g`;y#ZmN%J2sB9r}3i zfyIlA_CvpFA&^VDdlBZ*?F9+EUi2n)FB-f99}C?6E;oCG-5E8s^+-uBOtP+LQu~r> zM?F~j+Rqz!cMk(A%&^UuyMnUtVc$x7#9tnA?YT^(?%lUGYm7H6syLYI@XX$p-V#}A z_rfKTB$|=hHs=?}hG&@NB-GrhvvrnAMk6x*@Je@94h# zZ6O~b`51!ROaQeWY+sim@O9K|VLvlV^_tb{8WA;<4r$HuQP0*mo1+(fcs41A&u}c^ zuP?Ba%-h1ax9)zR&q(bo);LFOE}P+1eZLONxC4Gkz!q?7*4B|4-8EI)yVrhUWt#?X z57v#vXMTfGI}jI`0yCm@PS#<-*;JBXWbBA|fn|E2gPdvnY7x5OGEQu3O51FS>`Jw` zi(dHhOhoHeAL3%!vJ_8(&schxz2*33JK}*JWO=kS;8K*IGREWSv|6E4$sO%N=9a1 zE;WoE5<)4xc+KX#W<7XjL`OXu^0>0=Ewhhctq$!|W@%CD=f5|2Zu|dpNzhG?wO;XG zI{yR<{as?Ydr~(Y`SJgVE&S{2tA2bO$L&5Skc<_}RnUPxW=At?YRVjjCZHWSZ_(SR!eR%rc$SrQk*2qZG6@TD=J7GhgjFIr{i=xvhaL+ z+m8k<>8l<$bQvF%$Yd#j%c*I6nphJ7$^-(SdFssk9&zJKaSOJqpzHwlD@Q?+jMKxF zU3q0+8sy{%IeyYm$2@t%;$ts5fiw-q#>(hpo>Y_i;%GElzL98R5CNiJ{paQIBU);X z1wgEw7aq?=49n@0E`|HSzUBy1T#uhN;}gDS7gf=JrbLJf(6? z6Q4XthYnq=Cq1_sGMk6#ATe`BNN8$>lz$<;w@dPqgj*Kr3v%|#tS2=&Nqe2NX5*i% zmtF68`PKvbL4Kb%8@X!#rsi4fMe6TOD$YC&3x?S9jW0h)(P(GfbMr+&yF(p>5wR95GYYmfC-R2{ee`~Uhkv%_X zZKK-HA3ZE%-LikZq*jR(bxPvb>~uA-dIlG~)qX-xO7NBVB(q3VF;>*&Rgb;u>L)FP zD7x|6qjYMvkNQ$|X}zpW@BD_WJ47e;wXfyCDVMZI`CyK@AUp6Ec9HNDM000z5GUH9JB`%4(<#g5>dr)eMf#d&9vn67M88iXmJH@$Y)f=qvI7d$0`5#1lH5^v2V z(VBV8M1iC?!SzLyKjRfK)Kxjp20kk>Njffd`6m*u(B0R3gKbu-d2$#iSP_?D~LiVNZW!Oo?idC~{2a z4(B3-Z-3#saG?$rvmZTnxrzIaiqe|$k{#ctPsm_Ea`Az{hWUU(gCytHO=tQRFiwAD}jEfg!Zg0sch4#jRp`PT;0pC?LfUQI>M-@XA$Q2g8 z$3TBOx-G`5D15<{Pl=zfeVYCZ-_z5aD-mNZAU>?9{kuN|a#z|gpAVH$C``tZvvIgT zyPI%uP2#=lcT2K3fni)rm39gq^3mRa(a8pCHTd<*QoMGi-T0r}GU;UFZ|0&?hldS| z9snJ_!rr5QOcVM$80Z)@Y^}YK5o-xV+%1$AJtpN#_@2iPZx!LS#}-TVwD`?W2}_%BFmlUe=Js7bs+e-FuRwNpzgi+O)UyNLl{h?#=)E2LBoT z{@)|`53Bfp?KwCf(ULq(eHFF6XEl)VWt(Na49K|MQO1DTaR7li73$Z3QLh##ZCp9% z)0+He!HtzWl~M#9@%kkG`8=yRv1nv;;~p?#P%9U;K;=SSf+h&4r2~Ej`H~WVSVu)d z!OuX|sQdR=LVXdO2!9O_)E5JkN&lX_S65*Q`};Sqt`Z9fdRN=P)m6F}{(t^+YWIQM zR;`XN1$3NYSv*=>;seE_UOT;4_Zom70YG^7C_pCr=Lqo22h;%Z1zrkDd75^HUtCU`;!x z7P8jybh;WxdId%>NZ$uUbz7rQw<$myqmHVe-sh2~3JE3(y9Zt{1?m_0uf8zM{kdxBFO702r%5) ziLA0N-QG*5fqD=i(x$zoMo+nBN?;m>v;R>Noyk9!reKr@hx_{%7J7tNxkx zSNSZg#^1(Ni@!HDH^^jA{}e2p$HuCoR_lUksI~Ja3rrq(@85}${||x~)JXh25m9|E zP)eKsJgolT>TCWNzFcC9$nTAbk@JJfMkmf^c_F+HZ-VmfI#jz%l*ZFx5oqnCU9J?d zy$J%W7H*G=0hoDt52*W>?nm4q;o{bJ-kRPRue9B|0NN#P8C>U0DU>d5NH^$#wnI&n<6 zS64K>{3NJ;AWBP#N0EtQwik3S2jUxu^-Q;pccR{`OP!7(pVywPTS&uZj@pGMYp3^l zP`x@@wMo*Kt#Cc+h5si78yjFhT5PK1`3x5Tq?`t`)WVQL1=Wj*b#h<6pyc_UakAO5 z3mS>{*c;f;Y!#t$8?h=p4^$B-v{C(**H#!({U$(P1=j*b!9wYwD2n-T`lHYrs2iJj_u=(uxC=~!H7=L2UD4(>eDNbJQ!VL zLUrZ2N_IE2&rQr+REPrJxlMaf~I|P(Y=%JjM-x_P5wf6s z&2PSQzR&vdE!X%bKnH$k(23 zIo~gJl6!lxEFA2?jvMQm(uD0&V<(R9-a84* z?fu;m*M6Zy!tD0rBW(YsvtpwT7Sms85Bwp%I^$Dj`uz`vlY&Oh0FTx4&6_uPs}!lE zGmlLWuTa?n+#o98z~;g0@J(qz2j2Vtck2bh(f z#3TX%|6v>Z`A`lbku;oyvU(+yT?Dq5OF3S-8L=Er33KY2_cdEt>Q32c_9Z4~oEwl? zB&Ri(XFuKIoH|N(%qe$#6S&PXx)j>akC7?8-{*0j^^vMWFL1*v7k^**hnf(W&;~fq zZs=oBQA*ejm>(a#GUnqP!f-04*jH8L=;W;H=_ z^#ZRJDV(Aui46NbJpzAJl12azmdU0Sg{^Wu@f@{ID-U^eqw!$UtRIj)<(&<;uADYm zO#?m>c7z&`hDR#_^}y&9un2GotFdee+623!)U?bhlvG7_ z^>8-0Wg|sTVsx+q#5RnHsmX9Wp$R8I^2X(3QwE49wr{1fRCke7Y>$05Uy#4>}yx>_J8th^oy|utky~ z2BC^M1eAl6y%7T5f1OLouKfE(@Yk6IxZ>Fzh9+{q50BBij$P&9!mNJa)?*x0i+b$^ z1GT%;hu&`$Ao)*S((FOVLJkilDqS<`ry)v2dn*^v%(_IIG|8NVtChz%UMK>gld0oW z+Ywql?)oFL$~~Jz3hB#Ez#?|I!oK&di6iT9LRwx5YuKf^S`S9cgY2yUen*Ro^E2I$ z@}wLEe+?|PaCAH@@WeRNU{84?g|qrZQIM!W!&sV&|WYE+}jklzMziEqt`xtQHT)Gz(3=N_tz1O zl0i)I;h|`E1};X1i7?CX!|TN6wCF46MiY@kUreRtQZx91rd%xq0%BfLVD$&#Y1 z7n_gEQai&!_bn(?UZ6jaAfH88D@!U17&I!NV=Nt+ug)8sW@OQ6H92x=2PP1*I&2bh z8qA(zq&Mn1f1>5t1-rz1g!hnl=iy3bFP*sb5V3V45928muqp&qrR`I|Tejac)F<&^ z!5;;uvWjL_VZj=tq;ZocZY<_-A|W=J1ClczsTyIo;~GUD&rx%?OSfSPPss# zF9eSmO?E_yC@J-ov(2`El&$AHySw0H^K>C=L`ZsEoPM+7H%m3x7CqOvf5OgH7&yF! zVX9OJ>*|5pw7A2Y=ir`X!mI)~?$+10^0r$jq00>f!nq`+;tTTZ$LQO~!RUr=Ai80W_8kWgIJ2o}ZgUqGb8gR6vgTUnbVfr}h|;BlPLG@{vcUMmS803o$cu`{ zMOB8KNrBprv(YhtWP}G(t5Hp9ctCsJrJx$XiCGwjID;wRDgxBb6>w?}MMl5!z5YPu zq~3dD!b!BtxXd?FJ*PB~7qhLxb^jDGhq7;HncF7{8hTfJdA{z{HzW=B*Qn*0RK(CE z5Le9(!xjMy2vOgRIpm=UV$qiggYO?<=YnV)v`o3xz=iYl855NHSrt$$Y@zstFzCZ8 zP7G)X{PJR14}+e=nsuoW7Tb8jB}ZaY)O|>De)B>7{g-Kus^F8qJ4ucR#@T}Q zd2h!G50|xt&hxk|fwEOC{FGdorJ5JUs=5yhj5M&K9J%v{wl^XB+cp%o-<5p$4i;Of zs2;bEQ68+xJ!8~-Hj1=7wdnJ3^(=<`e4ls8Q^3-9{>oY-RqVr5{us+cXldEoWOkAr za3eCtMcf>sHbst=U4Xc=F<<)VIH*c)?LokTB->FWDgXR#(=D~=Z z+_e5G(3;$^Vc9lw7rtBlO@cqPG}Wj6Tm(yV1x>EZif;?pf! z*Q0U;&ux><**sqbS&r@q_BG=3+ARJYQX;}GLbWR!-+ivk0@KgKhCKFsv?#(eL`!C2 z{^-=I?eK|eI}4U-p_$?a$Xz!(rZ@ptsHZ9;WZuoCPKf47fbEVcUj8*nuueGIQrgZk z8xEtR3m_t7bEFBK8{Ql3^$}&0eH%e~pXy?Yq1_v%A{uoK&F5Yc;PbqNKsi!CP2jRr zj`v3ee4Y^Llhew`X|#6FSH$Mnr508T(M}m)Bw#=s;&>I()gk_;X#pZKqY3F?ncW&= z51u()4!$T^Pe@yA2x%spWo^D__4|dn$?)FTDY{9BhzIi*6j`x*6$E1G)PIq=@3<++ zWii?ewjIyOrQTnm5U=!g}W{K z%H5E}tfB*hqnFo*)E)X9PLB5dUrU| zb7t4;9+bjDY|fa`ty9VOyR7C)Pn5}z@jP)I$GDdw2T7bCE2H?ss%_XIf5BZ5D$75m zc%W=deHe+;j|%b5Q(c_Q89co~o|~3e*>yzO=_Nt`PX$+vC)^S}3}a9Fp7?#`zWlb3 zcv6gG+)9+=Fd5EQN?S3aBjwm){%p5*btFnraD><{REElsRSRh(ng17lPJOgrQW^av$id7Mon-A1eE z!VDkfq-1{DVwCQtco?Ca`U3_RK}A6>p(CLWcg}o;W@mPO5REwnZGUHQ?LJ34UgnHc zXt(gEdKS?2bA}}jek63zyS;R>V?Snek^P<0*^F|dixHN?{3=Ds+=gPln3UEg<12Crc10{( zX`nZJo-|1{ii!XNNc$pvuPog}Z=a89%9^_vnU2|+^_5eipQ_l#m0_>kd&Ko4KT9uzDv?rF5goB}XW&|^N# z8MIjS^_4pEK(b$g9NV&P{hE^tzgRS!Y8$9-bPn+GD`gEnF6V>|b5hKwH68{CZ#SNt zRqDf{tfQmLwom1Y^^uoo=QG)YwxdyUDHm*u6N|lR&rTB2m4motg@e;;lPO!Qvco%< z|H59gB=_wjC*8BNq|t&bid|AWcP}?jKGR+t^l|YG;+(QY+N_4I$S&rtuD7As58KEr zQ6f=@_DElY#ile!>X7MmwD**Fj%o`f<)ATRMjGYsmK$DGHi74c*)r?NN0PH(6E{PK>oCrI!7C#_@V6ftmJN%d*VFyn-?<2?Y(egNT)^0 z(^uFIT&f$YitG^Or7}z|ug@af%sL5pFpb$Nr#?tjV*;u5#c_@@XKX^`*qX|_!VZ>} zm&keRlnHXado&wAhs=+meD3Cu#G#ymj{u(RXC#A z7ZFL(8frvJg@ABV;wU-OyBU9YRrECc|N42@2-v0r@J4iCc51Ud2^*fktmf=rH z;oms>y4p&8kSp`Ql#AzY?r2?FJ)$k3)jNF>nTEAMWz3B_HmXBth#=wb{=DPHpfe0k zE0`D%xm|Gt*l2bo#v^xXr9Qt_Vn`a0fRqKJHL1d)WmU+qXD|MM3vv*vJ+q2FRcbU1 zS}kCVd^F}h-$OdidyJ$r1i}~yj&ohWvOrp29@*6B#}9HA$Kt+;>vmn8-)d`q_RPPXMUlf@2kjhi*Ud0_#GenZP>c5A zQ;XQnj;MKq5QZ`(kv{C}qMSLArG8-J4_|y(y5O>6U4TSc*pe@m0>%$z6Pu?|LF7p2OGkMq@AJ;Logg>Vq_ z;EkFab#7yAE5K{z*|*cl$p@iaGLm~>C(al8;TCe*!-e=WEyX=YMLIf3qr?~N*F&3P1o05aBh7qQG`#CXqHyQwL|D!;` zFDI1%gj|e_#=9FVDd&u|ERIKAnLJ{#i;-62;|`J$QAhiib&%uz$m-o z{{|ZVpbx|?IBzWQUv&vyzGWHnU}{UdFhQdZS#Jz1Y4Ya}?+4$p91m^E1;7n-L!}?~ z7kCLzA$A_Ahx`xE9lG$eJdNqFD`YP3XU4$avc1xY^24Mb{f$vEZ!FWZ(EY~;MceY^ z!Jguk+MChSuQ@OR=#9zz4zp37G7g{a%ym=gbTDzE7>BS+00RZXTlWLbgc*mR?r{VWb=OC6A z-aGSR?G9}*-SgQ-KSY&0h|>WeGzV-l8-Ux@+251?=XW*)k^+`t3kb&%fG5`z70-SD z0la&K8v0lR_lA>0PC)L<+JNlZZRbhU`QFD(VBwpfHmNH;y_6{XSKtspm6K=q2?6S; zo!?AdJtC$Vxc7HwyQ4`rL1+geKR+L8{nq!JaS+HV0Zy+C1Ncl4*Y&Y-z5y9x6<{5) zRpr$tqOGcw(PnNT@2}o{zxzi&Sau3dWFtgpN5z1EsDQhp?LW{Y3UuWVk;V|t z_3$-gdaSR8i?Avo|^7m4g2sA;lIRv zX0d>ERP8pqIiPT8=F@tGVeEpCn7r(Mk8Y-v`r4cqH-U&1lP7JTYKhGmg)e|N{0g}n>RfF?Jl z&_n_)M;*dbH$P@Ayx3cv$2%`2$}B)etKp`mzwZOXv<8u?*P{OM1WQNXyxif()xwYQ zGQIyeZMFOI)0D%BO)`_2UW zpMYz2)cpkBf_6`fJ&a*NwWcs@wE*vh^|9K4e!uycqxBn~rkZ;1ppKpd9Iy#a1L1^M zgO5v+@R;N68^`ZW#Z70m!Fl}bWBEaS9bh= zb=|T3@h{)UgVkR@PrZGlEslQXGjIyzHVwMk4E5%dHOm9Djl%~u@abnYPfbj!rVp+; z_lHNkBWrD__8-+V^}$6J+50vD`QLnjyhjw=ai$bJKdH>$Mwu(+f%XG&i+(bwY*VSa zX*r)Uk6qGl*X$9+@Ehp$oDDH}~3l(v@r6u8Rvr6`a@;g^hcb>+8USV-W+qOQ`+FsW$M+lpS$k669o__Ol_} zZ|ypTU+dd1+2X%2rP*@*iE^Lzzf{MQiW1wmy_ob)c{2NoI`9$a93YR^G7ZYx^#ZYU zY~zdQ;q>%lv%xT<9G{)4~ai=30SXrn;_-w^s)eU6=9dGeAY9gl7$5JlxfMHD_*B z#elSq=#X2P&!CP4@yZGnCN9>%2gbF-bX=z{A#})4KI9e}fy-Dg@=NRWE@Wa{he)Q>O2C!{6 zf!bHah{I?L0QIr6vs_pO#?W&9V8A;|wIiO?I|!m3s(<~cbpE4wir%3Y7p8rqSQp01w@68guD1o+Or7H6G0y#D%%Jd^$>zuFoHOWPVj z3ICd3u_Dr=^N<@nw)Ut0LjL|qWyKpZe%BmGt9xDUIzx`-i_FczU;DHE;h1wGb3v&C zVwK%c>7lm7L2G6Fc<3U4T9FbKP8!ss=ZWA{ zCXX>WxQ^DTDK`5nfP1N(-#^=IZSK+xK1w3Fs>$`)zgRWEK5|0lb0~B}&d;j$io(e6BH2rK!-hKk?T^cn*?&fhoX9`RP6&~|yhykfz zSSA)tTjJs*JUJ6r=anz6b6bc>@_YaKNwlfBV{HFNV`xV^|JPf*ZC$K8{bDyoIun-os7^#jIVV9I@!NQ-Uz0s ziS{hYxOS{0kla5GhXZ#Vrr~`ho*fe|ghDG5ZpQgU{s<7lO z4z3(cBYww(kExoy7-U0(+ybIk!WxM$vG1>m8o}P90x^x$3BL3xHmb*F(hZuEg-$QV zhh|)Xco#3Qzuoud^0F?}6$Bl%H|N!@d)fYb#q;apRpB_=u2 zisY4356b(HvFzd+)E;>1v`7}v-&eEIb_uW!@j7P9_#XFIY|x)2t@Op=&)xKpr6c?i zcF(f!#RwH5Zq^q%!MB$oDTy>)cvH3gOX2mkwd|)WZw=%)#YTmJ-y3+hf0!NAm;bNw zVAe?>oXNnphUqUf=%XHp9))9f)%oh>LDAfMrN$Lf)`RDC82eg7xSl_YYPbWv7udQO zWwi%<7L%smKI*MlyCe9;pf4HOj&d}t2yA;I{dq0VbuHr!6q}mpC&_PEz|e_*;s5sq zAwknIfMO`G9L@ai-0A4$^KK78hbB)ygLvQNGF3>*GVxLd8yIwpTE5arA(+2 zLB$cLe5ZdOy~9Ah?vNV;#M(Z$W?m>bX38M7#Mly%yuN=5fTWKHgV_(B716Q7C|5lYw}Pb|~6baYLfHPU!J z?-xrZuGasfymX=(Rz>Tfu|R_{>Purx5YKyk8BVPSbLM4JNi2W6;Mt8W#vSd;Sn8Wvgs_qq*Q1plPnU^&Og%2O??&1h}HD9g}1leCL@(c zis$$VXx;{Q3IVgL{T8DU07?(o|7_`n=ZFn@<0D~kfIvfsn!Y_1gxlC;XgN|3@Ro!f zlqb~zwwWZ*_uss8$7^HaQ9_LtAsCZq<3N@zI|?2T%t4z#E@l!ir2+vU?zDV%ZEZQe z3#5k$ZUNlY8rH)@hb}*Vh^;BnKIZ#d0L(dZxK!B5sO3ZLKJt7>UMUu$3Vf|3@Nhd3 z1O?qC`In-igyIJW25=UaG!j{uz{U^c#NeqYhrO2PVz7pHOwz7dz?9Xc_HkAdHKL0J z5zj2)^fEB$V>DEFZu{-FdTN1i1BUOvthxTa1BP;drn*_uu=yOH|t2}0?>#M zhtoc&?2Bk>?)S%W48q_~qWR9q7n z+BHoA>d0VXhv-V*Cqc8gG=DJ2)io~58swy>r{4rgCSUCp{12)E{jT3Op2O$aIE@RT zb8XzS@!W}Nqvl7^lFE^-qQiy#K8F(WNg z)~jebNt4a5{TiFRjAoyQ{6R-`lHz%7wkGT!?^?j{8k%-*yM|8=N>1|!$wDr(RUNy_ zbzWt)sPpE2l%k^Jc=Nl0!`rA3vX4~(lMB07d<`qXdQhMfz2*{qWuq_?~7?owJn#L!(a})*BJE&pUBv-)5$yySVZd}p!KF{ zq_OR|TM(9c^6gsl(Lx;D#Luq|pAtF+xMsq%BKYPV&hA0=4{zchG+?yg+W1t~KkQ3> z*bb?4+vk${9@gjIIr##x9(XEZQqW!=UyqE>043-5uN9Q&>k3(2fNk{@g$mf!qSdP+ z>^dHbf-Su`+=Ta1Y2e9fa{D8O(>~2u)*8ER8vnP=pgFC_Lpk1GtO2&+hG(|nK)Y?4aqny=%sEC6VW|PxX;pHk-iz*9YX&WGHk28n-;lZ4A9zxsc*Pfb~{u9N8-ZqRPL{@}q;4k1;(tFlme`!@-V z|N2ylpBO3QAZF6)uw)%;A@Fi4A_gfqDLtb2^d5|nRx>O$LHoM#cx3%pnUlqc(8$(j zVNhB7;ig8`9aDG(i$Z`f|I^aU8!>gVV2FkTG{d*FPoj;8g~^8ex=fc^4fi&ES|%H< zqU%6QK8Sn>ll5Gk8vqfWxOgiyHO})(`Xk^Md(g_}rpYbFi}&R%DHp$aZ5KDn^}A69 ziO*K#bD9Ie!+lIXH6Du^wE1q0JCUT^YO9$3aSC=EmPUjNox#jqxhfv_qdCyO#%t{{t!{2=IpAt~H;2fm zOu;ALvR0x`@|AJ84P>EQ#v&!IpBd31?@NV=M!dGfSNXlWeY{Et;2Nu#dujI+RNJKXD>)3Zr@l|Y zd!?wp_=Aed^9MeXxZzewEmsD`ch59@(kK`&>g#fZ&0up5jnn3VTQ>t%W4>HjXZSh` znTjYLAd%zaqDiKXWZ_b4ti7bhJ|n0kz-5QVo^D4ey4W}XOVv$7)X8hVmLPCG)B!5- zZ#4tJ7U((-0<5fF6FrEajg;PObD-`ilH+;p7T`0NZR<>giD=0uYyl%%9V+VT@3N_8 z&$T>f7|cDB``c_I({O;%!@2=tdsNsJEc$?)?wuWqtsQ`VNFA<%HYxPtA>cenKT!l$ z84K`G$nv-!$W!~Gi#~g9Y1}MKI$H@k;wK8_-Eh~>G+bYb$Y}ZeFn^_aH_}a|g3^9D zsOkXA0>Da5)MeJex5%)JsQW7SMIJGjyy0WKTcZ!X%r{o<7w&iI=503NSl!?;H-ry1o8j3$14qWRa=ShpvS9hgKH*F4UOX;p?j zDxRGzEOIuJ6LytQ0x6(K(&}se%W`j^l!>|x<2zWh;PD{~U_!{{`?F%V@HOH61~-cq zm-KMoe`x)>gx<1R{?j9O`+kAKyG@9->Np0#FLQ+aWiCQDN)_T<<-440ECbA?G}b=z z?Zz_gQ+U$J`d3*<$oU!0RDh2waY&PhnN3FJGG|Wzt8yPo*wH&bZ>q$Zxa;~M=pzsk zuP48wMk}#{ZATD63>(Ao#OHqQ=%dNzrjt?(xZ@S?6;}@Qm?Zl8fwjsMr+l&hm)`HE zJfLs?4)PTZMJ!La0e{}Y4N~!r2Cd1iK~`Z#kRvs@+A%d%_s9ge3~Tx~f$csl*7@5{ zG>YVUlGUlqR98TIhnYOVRhw%baWWb*U5AtT+NoLlDSWg38b_>N4Xe@qJ5rw{a~hTu zbhjijdS!~!6~-H(+M1N*=-+fx#7KsY3T@z$BRQwCy=m~0S=mj!jo-eDz)+wOSQ(PF zs!Iqlr#4;xTeNerFlzan%)$@GEhAf3<|H*@)JOgNE;DDW3fAWT ziFfK>&wwbDiQq2tAp23)8>hLMWrw!n<1A1Q*A@EhOPS-qy@`VbpO01p%*CD9Vq_9w zCr-4gN);3;IQak#83L}Dokwhq@MzXXU2r(AXYP2;I4`RcaK5zA@e|ej&dVjf*U720 z{ZJVW=9hO1^P|eme53jFvYc#Qd2in~uOHcrqMRi^2ADrHsdgtB7ZMF1zTyRf`0!el zyAd&pRN__QqgQy?j(^uQFXKs@PZnst$whSyTu{b$V;72nh80f^)jXu9dScPX$w-|w zU-|7EWTO9By?6;SxrAt50P~DSq?vyj3kJZM-=AUwmEl`V`z-=f@}DPdf5{`B9#=TK zf@R_;c|6#2uGH!)8|xKyA1OzN@U_2#bQ|=qIr>TfwQ)TI`4MIZ%c^GrKN42D+fHkp zK9#0nIR>_!BJLMm+Tx~S``eYkIYy(kS=S(J&zBL{XC~-K!VNw3-t#@}RN9MPe#O6Vz==D5%UKH_?B#Ws?gR@Y9O! zq~O0JpHloDQxSL`X(=tJa{PH6JV(f0hB)jMYTQ;aeatQ@ZQDuS;Ekl`P&q=mYwEA2 zH=O+atQ+u(4k_vgk=dFDNgJG(wDeSD_$_i#r%U|a3Gpemw;5(M&{8G`fagB(D(h&8 zl@nr=s0!idS_j1~hm@!DVmJuG-ARX8^l8CmM<5mgRol6Yp*bYf{k7tq!+xP8zA#dw z<+PF7Jl!U$XN75tIYSij2)kgGUf^r3zwjC#*{}&+yr`|QHg&7l0M1-TR^4 zkLx+6o#^qp9_A>-&g1$GJKyyyf4R4$4s_#6737`v{hPyl+&sjYnzuluq;mF+kbi6@ zPlagSWVSF>;Up-xgcX-Y+^QH@s=nxtZYtKC{z(U1Np@5a4x^gu!O;xYx+-f+JR>6n z7nl~a(i{$5oO=)Gqk(;81)M0$@bt(-wB}h)TG*YC^NaOq5?{JsxPu)dIsX=5D7NrYEz@YaKcSDbgS(M_1!>2qim+bcNgg zP!?J>0fpD_AQ6j($5LgyfR-gRsZ4X#n(5b9UTv|hIsI?Tl|-yaoGMB@@@(+x8wo*c z34`ST(R?MAvtDqMV-1GNULeH^Jh!cr%GA^cxkGmS>DZX(#aNUguxO|3y|@qE_A-|! zX8nQiYu%TTh`(Vmx2PLx8_ZM|d5Lks-)@d!8;AB$_IkZ_=kvGB4^tM7&6cdzN>asT zt`vKm+%Cf_@qCryC+DNFmv%%nEo-&RE#ra)w9;(pG*x1x=g(55Wcw1FXZyaG99Xg| zy1hUhPGx<~eO(Y|A>XIFc~HN>|4SJ?0wi{$Tg4n5ZBwP(Egmi8oAiygXCj)xwIbWY zZXz=z57g9N85$q1H9knArOsQsZ4%*yNQ1unyx;VmX{lJ5UBf!8=(?^Wsn5?BP0oX( z3FxEJebG$Zh7vPpibzGSi00R~1qnzR75X#5z}c$&pIwvne+at@({~(lOwwl>@+5c6 zWZ?l1LkTAxW8>{BFPvZLrZJD6UsiiVfEu*OVF*4S^|%{B5a#$7Uz#U*TbWum-MWs zOR@K?_0-}^D(&ch_lMqB{ch8+$7DOAbtJ+7JAHZ5r=Z!9=(kqLa{P(RDXd$}bZa)) z9^!D@miaVwPEAqvNMwcmTpTG#Y(>gG@021zlHbDktG%p8^J{{#vI-J<`PLg@7;WMU ztw)a3A-BhG_KBbnNw_7dkN8Ni0U;l{IRxqqzY7*q!y8bRs2ZZ6XMYo%DeU6<_d%c=0M$kaxb50h88JxlV z);jsP`Kn4rX{E&76U;Xyex1Uzl~I>Oe7hKzv>3M=AJfi|bisLE5gknz_F-%ESl3#}TBm2@(0?8s z!GwvsrBg?WKn0)IHKjsV@6kj+yY;nZSr|XXT^(JN^`=nmB(_e!EQ!Q*3)RB&*^N6Q)15z<$g)EAwb7n2YOy@2h6Z z73qk&Z&^@8@e2*7ofLO}%b?@@rt@}MeY>&SRW>!W_=}Lbl!=1yRvwfq?X!$I)27MIl;6}>x zpDaVd?6RJP{vc`|F18DDnBCCkd`p|)q}t$4F%lDIriYwa(L#(uxIiatK_rkkSoP;G0o!?D`V^o z1z-lLsGlwSYo@JSw9Z@Rra#Nta^nn$vGHb0+hb)RTM5CQPay`!{T#!#sb1@IjElrVpyeSjDUpQLYL|9nJMdjTSX<}eS&3U`|0u_+V968t#LIOk9-M)pFt zV%$;L+>!Uu59uhsS;~r@sdh>W6Sr4Si}aDiiu;!!l0kIc+g_Cihi^jlAvQXqb03+E z>)cClD_botCDMGA1KY`8OT`Z->-|=Lv!5&0q(qAQL2=hhF~_z$IHY86a1G}v)D_p4 z@#{bq*E1;PIBgWTUWck2DDC=9uVa6yz|HCg0dbghcJuS@W}UO64X>Xf#R{_?@k4b^ zeZhxOS;l2jI);+qY-Jn1(|E&1>CNdcj&Cc`^R=3`~s?_yo{9&QrDJ_^i>} zmn58qzP-6+G;o<3P&}UM3h2xJ;Q{Oc)qg^X9Z8w--RNhtx(YeKak(R~zdFo)l>~_b zGN57e;IsYfGDQzREmV&?FnhAAkRW9ohn4V0s6jtfmXV;HX6TOv0sW zfJSK&$|P!|Ru!BJM9@7mra&I)e*rRB>=mV-jeLJgyL;pZ(5s|_CLkH8j=$eMm}OYq z8jf!29O@{TLJJONX%9q<2z*4Z9B72$D11th^JVRA zw5eN@{Yn(a-NI#gJ9-Rc)jEF{P-zfA&+~QVp(QjC)1L{Z!~-{5ecfGo4wk-ww>sAEufqccGH%X7u3o;kwsy$nDnQTi9O_pTR0&pvXFUI^K zb}mVaIb(HSGk<>$SKyDHKV+hX%N0kF0vJ8tmdmZkzRz45^QChbI!TprPj7Ya-s!T7 zXp)6P>wPt~tD65hhBkvCBt+08tLH$zHt~)()2+GgieRbpXvskoEchWU#(Ug8b(M1c z3fc9s<_89?KzYP+r9h<5K(Zcey3sH0cLeqG@4cBQ6shUBZdyx9%V(Uw0-%qoQOIi` z%c%U4Nu~Z3A7)Yl`myS)z{RtNfjNN(CZ>l#GP!X^#EDlA&#bkPwML+Tjw1lK{`#ij zItyO%I(+U2qTjUK^U-&|H-RgpI1*ZfOoE*heu)d@-rE5B+3LQiI)DpKlvlt8I7>Z> zJ%}pGRHVGujs3TPKIl&0PF7Jym*3pjr!0I*bcz4r=CByr#RARJLfggW@3JSS%$r(t z3xp-pkUgJy#j8E_*cATeDV2jIB%F<2;{X+sjSQffq%e(U5n8j_cu(NGtm$KJ__rIn$*g=8@IQM`?>m zXWNusRMk>^ec3=GJN!JudUpb-SvK)KvBF{Djh&2HX%(8*q*&%R8gC6+Rpk4IiIP!C zfRRPkDqlFT0Z_c*6NRFOjj5MbhLLYZ13<>>@atF4Sm^J)r7oUpn*y2fOo2IbUCvuA zKs)v%x*$d3tnnC=d57o(yVPbT6Sjiqn$SPW7^`pr8Fj-IK;9^!Z=GnMLVEOY<%onJ z!<*(otA|0;{z?MLoAzSjRBO72&9^Sk;WN8%s~5Q(E%fbPk6+=hN875wqL(S&lpI;{ zgUjXevlp`$C3lM4tR1(t++Lx+h&OHAi85SQ z`CxtJcig^(5F9)K=j#^~^I%&nm37qUm~@8C54DuV58d4JNth@X!X1$=Q7i(4oUP04 zP|m&ZQX=uSX$>hku=jwI1yN1h5PifmF#bLq|bR1YbyaErVbimfR$& zj^-ci8*#$T(E}-zh~_^xK|=My?KYNKb#Lp$b9c5gzQ8m>f;U^Z-==O~7jv0}eDyA* z(auMJfEBQ3lH~9nX?OD50RBOk16L@Lst0b;@1Amj_M>vHtMxZhjE)jBd` z&GM@fMY10aQ?`|Fs(0ryi$ z=igN*QkLc|ky+~c7|T*feE0_y3F zt3_{4*FVE0?&O;|I{e~QxrV!EDXDT(7iJ=i;_n+aN?su^xlBwmFSBY&!j6GVN?h0l zHmgW_EVR2DMp7|ul7uI1Tfj2S)AG`JC++;%<|V+22g|WpfV{jsk*)(vUu$!$_|e}b zaHD%VTc?<0W$E-H-6X|85Y_yGR4~zm)h9?Gdaan}R&gd_Kc$}t8vjn3dQp%QsbIBF zA`R*m>)gzMpGEj|p2dY?jr(5B zb)m|y2T!s__9dl*j~E{3XKtTs57%R^;igX3heuLifqT-b7U-!Sb*xKELBQVI{p`hK z%Uh`?mU4*^aO#ReF^ojtuw&x+i@Nf;E>73Ynza+Q*yy|Sw~BFI7B~COC_`hKpO6Q% zexs8ZT!b=)ggGF<$gHeY6!IMQZdtN#I5^&2T?w>s84NUR;$#SkVOt!`N;D+W?J83w z^kj!R!>Olh5NN0G)0q{%*twy5vf847k_d8`U1j(#O8tbXID+5-#H#rdckA232Vc1F zh92(RSc$o$ZcHA2Ke|;;hQARNRVqmH5b`!4=%=o<7XW0d;VE08L3S)Pl!%9ujO6W< z11gB2KB@soQG9^byZ4_2CJRs|-qsZO%zCWquUE+e&=nK#9DOU2SO{BE@%l7645UH+ zBPG|P8ju?Q>x3c9s>|cPXugU`p2oGc%p))ljQA{lx_Egd6>iY6Y&_;5Q}i@Q@Sl~d z%50l(R|~OeKyniwg-{~q+oI}PjJ{O8R8F&2qE=xnd~)oN@$dv~)p_@=%VLsc!ILo? zPtdgCyRqWQLB$pJpk`^o7#;p^u%lsqh2LG?L8zTs#SoFL$=Kt{_o#7LYhRw*jlgvk zSYHI?1(QZi)&@x`0s%Syly3deSAsI5%e-x*{ z2QwsZT}2Ra6HD*lP$oyMz|z8DYdNqOg|d9{hnMU_7Ugf|MB?rf5=u6fGaaf$d2qBD z2(@k9O61FZxH85zt31~C8s-Tu?xp*ai|ix;DCm&Rt6&Z*_T$ZTF-~!$-bwEcOoh9} z@Znj7+$eM2J8=IJ1kI+P-^0lu6m*!FDTbuzRB3z1knpIhWn2gP;C`A_R!qm!&2Fc3 z+gaCz^K)!V@TDHNi(-pqK5tk1Nm}Y;bm~8y=vC6-tf+ojQtF4l&~@|A1<4WW$)&s0 zR8P59H7o5xlCSMp3%R%obPFVoni#w)$RvCtlwm9O%02*A_bOzVH~6^XBiPrLWZ7DI z>{bD;O4QUhS)SHgs#=%4yq{q6jW%ONREAiWOq@A{mp}GJn*Z7UDE#l`gJH#z`oBdk z{JjTsn5%jojRUc-s-{`g)YR_1ubM8U$6TfEKXVGY`$&jINU?^I`c>!?bTVVy4Z%e6 zDi!g22a+G(3R}7YgrSJ%bFGD=y83^0#s75Up9N-E7(cWV^QOy6-4GSK837fQ!u}pM zd;WWcy@O$SxMhtvj`ZY_I0remlh{{)PJA#jXtZ?H{5Lw$kx8g}Ae=6PP6)*LF-LPl zFD9lubWXDk_r|e#rmn@JZc^U8n7%Ttek>t3eAoQsY_Ww_w#g>%f!^A9D<2^Pb+V^m z?BUwFKwmypKSdig6C&(*5SF8(dXI*gRTHWK8Zw;*NP-jaE zkCSl=wl!Amqt1tJXE%w{?uBkFjbzwsPk#{lGQCWgWm&&Xl55!=ai;a}1jk1(FH5p~Wr ziU_6Aqh6B?&`3yrWI5Bw6X+|4w+L(VC3tdA%G)ERW1{b#eE1V|Euv0k=%YTnQQh-p z@N?g$ifCT4E~)3SXTYSj2xZ0Q7TR)QiwpEPUW@^e!tW+$5ulgz`PMls_kNc7U#7lcuY3Hoh!?)%lYG zHg>Fi8fb$AEdiIo$GpKif$w5-x}oOE%_P3iplk_4TNM|+LBI-cfd5#1`m;cND-gJK zO#>EzQ;JOG4A5k&^(u*Lpvh_FTXuVHF=>3X6Z=EWtx*e7cH0DDqh^SNN$*KGd@@Mv zPif2f#591vrK~0MOe4pVh_Brk;~6;}&M{B3ec;Ns!zUjI0xgHv0P5ip>5j%3v#;4- z_E4Oc4BY~PI`=${gbLChev~Wiwo5t#H*wuO3p%j_&ff+54CZAqX|_{uL$NbuOs2{ZGLu3=GG`u&WZLG;bJ&!5+Gfsmd!FC(d*1b)v(~%LTJJjR zto8cCT8Vvs@B97^*Y){)uFsWcS}>gPYSnZ0QQ@FN!SME|$JYbo#;gR$wM@crNcqhd zo58+W=qIb*@gqB$Z@Kq;)``(qDb7||;Gb4t1<8U#94J|m5si(tv_!;4#eMrfKW&xR zZM|nj4;X>{Nl-;(oG(UN2NG>_%%mr-NsL;!d?mEsw)VuJ#m9Kl120w=iz|0G8;2T+ zm`L_97`9QuEAo@UxQ4Z_j>?{i7QB^=EElb!4qx=bOsC)d9MjaHgl@Es8e?B9rz=3U zTbYe~eMWSz(&#A*C!~P8PtN4_7|HOVegY>0DjZ)sc}Rfk&3qV6uGJ_Z_XrLvdL!uh z@U4PDXlq?ch8kiEjh((}C#)jw2N>M?mr;v}tm(CWT`^NFjhute8P+ajB9)it4B zYm`(Sxc%eHBSP0XowYr+M|hpUJS*wwCs8`mYi6IMH_4k6Et)sh(!*_r)}9ZPVV@_i zss3r_Uu?T_Re_fkj?|G^S$Ffn#VzmApiyV_i{$rP|0j?@gSpLW0^!mDFssZP4KHB5I+7QY$FV}p)p`SXWpypfHX9w^4;2N=pT z`N-7W0>;_Wo%I*(I=Be6zhxvuq5CPT*;Uwk$#+>kzTl^ouC)})k^+FQi%r5?W(hJ8 z_CuP2a#Wo%F-)5&&!zG7m$V#N{LPQC_+rwn-^W_amVXvz zak|-@5U|nMdfkDpb(Eh#f0sE)=TEW9b_5q|U7(#$b>ZR9>>~+#wTJhD8Qz^SQLT=X zNf?npjsLS8$jR7Wh`X$$rZ(xYB~S4XTMYIB({H?smf5CcQx4sAsPHO$vgt%=yt~*x zz87Q7*uGB16)5e*MW(r7KQ4Z3rK(Mg;srFQWyF!x5VBeVqzQsK52 zITO>yC{D#0wou@<&(Eq~IICBZzbe>x4zGTAsgu4cE=!J!3RgkPzI7wvNqML8Hpnz$w4@Qoz)-#X-=h{u` zc2EWz)bLp;tQC!4tZ0Sa@DH&;4^Ir=>FEyqW2_4E!>}A*(SaW)UJ4sf?r-7}HCP)(s^7NrKvrRZADs!`5du?xx9<<=jdX$=IyM(u=%H|DLM z%8--rdny1S6c^1auB`?)Pa%H1oiy)N_Rf-`FL%P5=}#fr*R3eg$b$$(a6K1;-8YU_99Iuze2$oS<_;#>`| zb&1h@;l1uVo4qZrGP};YEQHi5dPTQ94Y7wmPp3~Y7y_XG!<<#+G>(Cgnwl#!Dtmq= zt4jCjhgrgF9gU(Xaivb1rlkP4LC7rHxvkfxA21VAf70D#`S4mME{%JGq?YrCMh6Ss z7^oQwuYgi4sDaTVql4w*_YA+gu!aqC`=HI|Ms87YosQ>q&Iw~?0*j~j*pW(kA}&nj zVou1p%RvdtS7pbYKHbZ*8T}r7?Rv-cDvm=g*+N7~_AjDu^rFVLMs#h@d7nx-{%)T0 z3OmxJU2^d|qqRm;5gPvtSLZ1-BRQI|x=D!F=s-PMG2?w=mubg9_&P5<8T(94OSs8^ ziO_!5TAZ97*!x@4*+K(yS_O@^M9Rp zF-=uq=tIS?EH01oN?$n8DVToWn_7QuXPjk#m+Iij{LO`Hd1{-D>Ju})c^_xl-UnP~ zXgV=gz2`!z6O+i`RQ6up@4gmAEJJP_8o!%M9dmcn-Q(m>^_ubZo?t*Olp24n(^Lx# z0sog+;qfl*jHZ}7CkyZQTR9{_VPi|rC%seEZg;M(vrhsT+%>5ryPCR?6R>R7J!3;j};X?}x-nSOR>~;J`~Bd<{9b z@>v1ZQS%7Wq{m{-UUHpitCAy}gyfNZK$p)AXQ&T&qQf173-F8sU$5+3ssu3Vmhust zhOK#5{fN*?0z%;qCMzEn|0WoIDkiPn^{2SeDx}D_uIQTaXv!ardwjxC!meM6tEeg7zmoku=KcJkd+g_Q3h*(;?N*|nNMeu1l#4vRW;z-6?3($@ z(}%P6$(xflG*n|UYq5AGEE9}{`m8@NZ2!>~9Ja+7-uLX4?^1CU27bEu9^KmXb~5@D zw_>+;?vY=F?9Jd0HgX>$Kkvo)1F5fnWgu%gtV;I)_PczH?PeQaSXG(*C@RSLs_0Fb z5J&ZIQ(*x;b?&x8;sws988h2(uY&g}kCzv+zAXZ>TVD=qhA zL|4OzHU!Vi#j9}j&_jo9E1Pc}!BISTM=OI7cbk(SOF>_22Vu7rO=;jNvHy`0qXF~b zo5w4Dr^NOd3gVZ46zhI@sJU%j-2UmFu+FXRZ(q?!|Ma!>7Za?DqGw4B2nURtr7CGs zbWtCLuRYJ#H?vTu6Zhi_Q|$APKrSi%&n0cn%UC$}Rk3e1mYH5XjBDPgA5KeEKhWRP z5J!upX_c|?USf3Z&eZF-pYCen*IVOyNiXSUFV^gbk)F)4 z5wOy+{t~`Z_I^Jr(P`fGQ8Dl3--;bv)B2gbcV$+_+g zWvmd_SZ%N)a!`CyPxAFS$w{D*7$J$h5xAf*;fp3Y*jUhSGksj##)|9DYk8WS);G~W zws*uV(#w@N&d;ezZy4{FMCYRM)F9*!7dDXIPSt!rWNn zmqJ$9cM)*9NB0VC^mO1wClsG>==pZ=F+du+@t5oe;Enxu-{Iu zmZ2+6*cvYbpyuxvSKbv07G{9O%6@&*J%0Eof#Hp|=na8~94Z@c-8U^P%WP1M!VFeUC&05S9uFtB^GRNxzrH zv4eL&Ie-W%_w^d6v=kasf6$vpXUC!M0VPgVTMA>>`9RH%0|0i$nT3Gz@#A!N(ik1P zK)fIoslA9r;;dr_DIyUPwVb#<7ToUwv3u&n+_;e#2aEFNcJAM?)d;jS{7F2MGtJ-s znsVe{`yb!wJT$YazZ>Fm;K%W_?z2`-RSc0nAH}qLrHE_%JH3@_&w_cok{UuPvOf6T z{y}s_avElF1U3^=i?%IU6lJXCQ&RDuGePLuMbQVw{v=oLCxPuLYCqaS z*#a1)c`slTZ%m?i#=Rj!0juE7r%m##a|vT3ENMS{1ny;8_4DD?xhN-i@oiv&8~cbx zhR_Vjo32lBcC^WWZ&jRuJGeU-JMBQlK)z>G%1gcbS$X-_`kMd>NanrXzjGfebcK{; z_|&;lG`ZZd=PpiEXgT{J{yAm>$7x*p!nM|fJiow!XVEC~?Clxrq zAb8Jo@u)8wXw?vR0@f6xFJ!8Xvr zxwwYFxxsr{d~G^W7KR-#RmZt`OL}9RtXdbWMD==eP4s|5)B~5@K|m}bP3lhew2HmH zBE#bJ{D7?M#Azy=_X#oq?8#%BgcINm-<8ou>nTU~AQq`jxsa3`s*tLn55#3)@d%7V zsyp#2rDcf|XwUma6r*{25EJ}kx)^b)vEVXaOpK^V-Suz*%?!C(XQRvRq>TeKo(z-K zx~9R+@sj;6EMh*^KO%?0Qak4hllA_5C`675B_s=cS$PgNaf*i7os#S`cs~DhY9{V< zb$p;=Sn1=$X_!Y1F_KTIPRo(-Znp)W`{aI)lr83wNG?y(84+twCESn4xqpgrllMo) z1_C)Q_qo9cSz|7#MvK%CEdd(2czhgC4(9TqQpZOw(l!GUYar=SOgPYAm+{aaL`Z{V z{Mh`PT_=K`VodQYY&l^jqlV}iGgp>9c$U0<_fnp&6JqVF$Uxu%-yt9qCjZ3hU*Gd;82S(SmPS4*Yjh{{~H-%_Ew<-R0oepI-uX#OBD?f>YS(fN7vBE;nGl=u^xP zM0h4f5hrS<>Z+dJI=%>-Q+9|b-y=knCoJyQYp`nD@zmk5WrXF)qsVQ%j)dFzPq*_{d%-rGW3p`mcd4vqGvDo_@;47KK_p~9*gYp+?9%_&k^OF9D2p<-D$bup&#b;- zwh8-tWzmN4kyXhFiKL7ti0*nl{}K4vfJQU~!FxY7zkn_8TYb|`$!WE}C7i{@nC=`xM>Ap92Pl%`>CtlXH4C3&*Ay9%tDzr3R%;d4UvXfuW3PT@taT)P@&*`EAjCnODq#=AH2lo9!HqA(NIX7N`|Cg7~o znhYzaOK1%y)Gu7nqsSbx%J3dW0$-u$d@#!1 za1Y3ka*q;t>0v0ySN-j%Fa>0Y@Wp%M|NO!Kc}o9FQ=?woy1(Gd!VlQBj~^qfXL$rF zfeLVp6Pc{^AyR5lVXnBnoi!cL#yNHH##*n1up2T*T9|pmuE6@Y=67yxtzc`UkgpY)I>Kd+hrx6m7nqi^+x$6wc;fBDcln5j!-2S}( zvs`+(gn>!t&s>0;77Je@^SVwE84vTLhs9tERNDFJUhOcl9J#sKu3%M{^vcpq;5L3e z`s+f0$cGA9J=9LQ$%>TguIua%-I(VLUYXnVP9tbDe=zSamuu4Su?np}Z-;rm+Fw4W z{<}u^OAA-7)sMm1=>Rd<%G0cA^?XiUGu=nXg>SEX;KoDOcjNN+bE~cL!Nwf_`nme~ zkzoAs3lB5yDI+`3(&V?*8v7qOWO%U1nFuRNDc9_t#P9DSum0MWkk9;I*>wIl{5l`h z8L*tM>P%JV>8OP;Zx9s06HpgjvR-R9I}vH%fE0yS&VbPBgk$XqM`I^MLX|!10SaMO zeGfp5^+4_;T6U~E&+L{XFfWQSYxBc0Pj><(_@7z}*KI}|iEHt(F_5H;h z6s*0hjLW*4p@p5?24PB|a6?{lrYQ1kl@(vm;7A#}5dBs$akk&giB1hMZG+cxIj|pM$|RGFHE8GY!kswevFBC@)3Mf|`De#1nOTq}2)Hy$FS?z(pI-;H(!E7ma);hQRYV{s{3n!8C*tzU(M1}$y-(hWg0kKCzQlFk6(cdw_LmIv+#TGu~dei8!^?e8H(whx=RGmwJjHW%$iTF@BG?fKRZoP zd23;inp1k9V)`+_jr$84D-?@Xx>Jjk8^68tSrXb;4DN2tKk}Gi^jwG3ZP&6f7E)A) zK8sV1zduBlASj7|jaY}mT`Uc}_9ucm1^JVJe%LVyXk^QbSoDb-*U`DeH_)lG4c$D!QV-@$;_vA@ ze>kz_JQ;7cWe=h*?IKrr!%6d1k~=FMdN9NpOp}^p50)J9=_`VaqI;K(wx6R(CGANr zb=5Mso;?`#w+1&gY2t}>=(XGp%=ZaRDS3@sv{DPQjv$=rmmaoj6eMmUc6fj^ShVyy zHcNJPA+=}e?%OnrTckn1t0;w^Abc+{^9$l3B|x2(1gC8+>+u#2F;W$p2I< zMnWQ_sjP5C!{5JZpl@}l*0skV6B5`0DGtKAeE+>y>pUeIX}4|0>q739b5E(cEw0N~ z>X$zyN|mC!i)@W3J)Pi%oWqZRG1?QvfZ(#3o^(DtsO2-EN_$$m?ASMdwL_c)SvtJ6 z=#47&$s{-lh@zt}$3D)pymeiwPmMOQsbW76B)~i+S?9dmnFp1xUo|td+TM124?$n8 zq1MPoT>&vwLA;R{Ka;##8+YApK3;Q%W>?KuFHdou%_C9#Dx_185i8}KyK~d$HO>J} zy8afxPjE=x#fp2-*}UtV{btcwJ+`hIg1rtb1c}ORn{^}bmrWQjjkS*8!t1%McDBhJ zLF_S(iCn2W_2#L!TS2|8z+Zt_)xe%kWea=Lae7+Z;uSRN2DEbta!(1B3zHJC(0H3F zz*UM?V!Xj=np#4qD~o!^O&YNW*hiaLYFW-8>}rGQ=BM5|C6*&vhz&?~h5_(m}1CC@HaBL`;oJpX~9zr@fSuZ0xRvd-Ed+8^L z&cdOhdVV25wAo*pIZ;4KQ}p}Vd}TjSp)rwjkcJiLHQ!OP^%H$_!< z*`#B{A8}+h&}E>s-h*sK2X|v!4F7D*x+nX6{4yA5{**iJ_6t6t;?8Ai+c<0#rIOIZ z*23_qXYqts2-Z_IAF?uq?~J-286JE=N`b;54uvV+qlWBa@nf`)fnSlm`f`Gt)Ag}$ zcbYl9RAxEx{#LKw=j`i<#^LG#Au62MDXMCACK-Xp8c*fCuMB5oWmmJiH6txc%vq<- zDw?mFODkU+8`v@$UE>}gi%P*xwZ3Q7KlE(MpC<^wpoBFQP26z;i>%McgnIagVgaU3 zH2yL$GMR8Dwr!-Ie;3AGI z$9a@&@|rFZx4!vDSUrEHxw$&cTwcrbSoAAJ=bfO)KOEuB&^@X(Vp0s>1VvTE=VL|& zy~o@ZCFbGk9&F+F$jnDCgGE3aI3OZqyj8PI(zDyee2;G*NKQ!kEAe?Vg`PY`-SY5f z_2c%(2X9HeUi7=@q4oU0_0;2tOYE@*)KQJe*PY3u9B%J=f}QwY>^><|^leheq(NVWC8 zhCU$GcS+yNG??RZq6t;qFQsnM{$E9+@=j}8Ppc?SDLg|mT zzO$6{)@#1?-q?EiJ5Ii7GnuHjp7X)zOyz2zYZQ_d{4gQO>VZ6X7d+E7rncY)?Ke}G zkSVIn?1Kp*ZBqy{O}>c%MsDY1n$6|`>z53AX8(yOL(wre+L?og4N_R@(zPF9JM90b zO!ogdsQjP-vHt+L?U?fLR6sq+#d985BYzK>1I}Q=(P(w#FhLoKEL?4a&L2J?ziPHR zHCXDn&4Z~@_=R^a@KWPluSNrkTyaU!-`;EpVE&gkId=2O$ur<7=`*^^Z4 zcBAMn12nBL!$k<{Hx5%tq-frd_N8JC9ldPvnmBzEnHtIJQ8!qyzYvEVNTQ06n)X3p zJuFAbNm*l*0jVyY11Z}R2Py%JrrAQEg@J`kce$Bl+o0)Bbc+x=R5+}Lv z^^hPhePUE475rbU^)&eJIxy=yy+;T}J)a{?=UC`xB!Z>O-mAu6nuCBVxXT50=Kcbx zU!)ZNAU9mL7i;xuUNQ|L4a;hCCn9tdxjsQGWfQ6AU@Jc4loYRX za1jy+t7uvrDJCdGnV=Y5J}uUx~>=vV)M&Yfx$`=2JG}MVTSs zOLO8<5mKn;b#T;|;K%U|oQi1jCcP0>hU*AQV=Q%dJ%K{STf!TQI5*iNl#J%2tj|ka zBoxUwjk|dt7qIna5HK0JAV>3ztPE^sy4pnetDDb3yKl##oK`Y{dmu;hVM80r=5NFM z$a_a##r`b<_hvB83hG$45VDMFryKPOahtj<cOq`qpAgPd>*h@GJNr0~uHdl#DtBWJA|fOPt( zAWt%#E*LgE|8|$9&fDI{ZE%w~8w&*|xO8K#bdQYS*6UH9Ad>W*h<@RRA^Pwqh&7E5 z*wR=e{;6iytbopP!+MYs!md`3XBt=Whz%RG;M%2aR*bZ=?Nih>Z94ajsP!o3!@nPG zo`Qe^hbB+V6%j*<@Y4t5ltg7V^$|ny7VI486mbZ-w}SEFY7(WuWklLT-%S4d?nvbm zD`Cn=(d4Xx;q-82C8Dpp5Y8^`>XaXFh5=L*C^e1Ts+52gPF`=WENt`I72T327AqVv z+FhUSwZs%7-d{0JUZ$yW!yq~BawobGQYG3sLkMZn^#XW$?wyi$fu{Y8@tSfnIuaej zA;K&3+*7S7adS-m`1^gwEScT)q{9?m9Y{fQPI|Im&@0JBuc$4P9QvVsF zm)lZj8D(^mVKa~ZB`fuE4YNUh0xQ*FDt|kO2K!Uv<8bNErOo}4v_&G>zll)wabRr{ z+=wq?;wy-KmUrtB1=SX)eP%9;72@l6nJ-vWG$YyFb#9;HgI}k71K!rvg(4J@*mdqC zvD;Ta-T#uV>4M@Ml|4g!T+F}g%AODz3M=7(b|U9OZHrUUdQ(I&ib(HmU%&pL$ETQ4RpQ$$q%6_W zaFk6#x=Pax!N_{;kxr;iX7f061EdvpaB7#GXaV?Y&a^p>Rd5SX$w7bs2uPte&84Z6 zh$}Z~!jrk>7MWmaq`0IMEYwZ3-W~(TqX;-Hr+*1IDmFCjzbS5?EVwKrlwEG1HzrCT zZgS8afo(?$>Snv4o1crmMgTje9dzQRi;9(cZT%i)T0!9(v~BtU9i zI}+Bs0}CKiDVU?csxRMyHR9RH`dnlY@4z!?o38ey#sR|Q@BUWQEQsy=1Ml)lpp2h@ zTqNx z*!_aXqjLQ=TD_EjclGbfOAQm`K#y+^a$I|;MtcGt1UGz5){*5e1s;V`)zbjml=}RJ z!&$3n1j_rE;s^3HkkyPZ`)N9>jqpeuuj;01w*)&Obi z7m@1?zo-9uU)=#X3{oe3-zVU)7qnjO@$#*mR0UIj!iSv#h-jn;Anx8tLUX+3GZV_cnP51XN0A5G*Y~FKOwe^r1+nsPfhx-b^|sU0Rz27#K=V%Ou`{x+K9?UHiYHx zYdDxKrGNzv%JHBAg$e_Jvg}`s$uI(NB#f@z+$h3hE&M#J&?^ z@_}og4%NDXJ*9$7UL_<7g_9ZwcWmE-TSfsb=^eRlfZD8?6kCtJ*)fr!DAYK1`5^mf zv;berhPxYI@UoID5APB}JvbsZnkKH|5R^TH%Eduot&Q{b(;cKeZ_JIa?uSDmRqDU0 z2LQEV6XeMl1Q(397Ak(brVHIYI00qX2)Bh`!NP%dV4NGt?k>J>;n6^|P}(sPa`Wsa zu2a4MMZ4c@_W^Qt!)a_Kh}B6|7cd6OD<~Xn0S><1vK`lB3~!rQcBBOQh|r0N_Zl(#YHLz4s3n%!9t@iY)!V9btsY4}md{b6G{r5JL^xY3b#<++whN#eBMKpm=Oud+Az?h7Efr@cutWW}?DVu^RFbyY6w=TF zy#@hzDQvN(T8f9!Gonf|mxwPOHx^rgo@>FTKJA|wb(CO7N03!Bhs+{Bz|<#zqh6K^ z7*accvL579L5Lja+wzf?qx!dtnD`1d=!zET%UQH|GkDuca}XJjuWUkjh1-^5BN(_E zHqm{XoMN7$-|exHK)r6B@06GGLk9cBd#Jv6#bvT%OXF3?q-5Q z%&m5-cJWS9x2@FUxgcn%_2l=i2k(!ojj2(aPzV2dW7zKYj)iMb1wjuGMx*AL$i5Q;|!cP zYm#oUFaOM`WT$nba6`KR`gTrCM1XIazYK96C4`psa zrs3>7!zu{nj04?wcEXAY*hvUmd$I&obBZ&mHw!M$tJg?wjE9L@|2e}J(Y+r9fN4bz z4GyxVCN=7VD(umg)ZUpOi@w^3vJ%@`UbpIL2_TV|5s^dfj92Yyhn>1r(E39pM%uTN zJN+IhRRsM{lrT0-N#MTs+08dlvG#QdPNSZ#tEX3S_-EHy+*VQ7Zz{{OP`2#_&~t8_ z>o-pK!PBYr%5WC_>c}il+vB6 z!m^6Bhg0B{YtUnrldiB|Td`gVS<4N0rk)yVYOfnw{?GJ!X&=QH68B#W0jbvff5V~O z$f3mHYYHacx|CpWgzwC~uEwyV1XRZHAVEVDu7HawspTlSg$SJPu_B(%BgA13k61FW zSt;?X8Q|={LM9utUW+z6L5uMv-*hRG4E{Vur4Y3!&ZXl;F z01XU+Ms5iHIT0`ESWsVAj?78mTOQqYHg|#c`+I;%40|Zu^<;^lT$Rc}j z{HM*lY=dXtz{w_OXetpLJ()RaLT7s5HKi~#3WOsC^KkSQ8jTgXnq)%^ z=b(xp&ys#pYbqui73(ygG}0bS#_qMh=@O?$%$pG4WL9!~Am@=Z{({XwPenJtLp^{^ zI1?+JzMixA@APQ{E#Ktc!l@_pM^k6=q3#Ya5Ny{TwT3+k?Tr!80<>;j4M0FYDXNEn8y_%jj9Z4k!BT=qcx zqFK%2Mt67C47QvBCr5a+9JTUl8p$HaxP>>_cjzfxG|o`qW*Vz}D6Ltscyg6Z)d(TI zK7^Z#_^eyp-W)=U^JBO3*W8pMa_Pql{_EDk_d{mLc^)4vI`--uOY1f*+^_O`Bv?W; zcmlE-R&pA)Ri+VQhm-3^kihr-i$63~Xr*Nt;s@A73+AP!Vt-h|rWw@b1FT@*^qr5Y zf%=G-_)&sv5tb9N)&6wR`b+2CyTu2u_`NflIrc>+yOOPFP^1GXW{7wST=GHXzxR$ey(9SNQ|>{gh?ehA8bF* zX5wD|E!I%gbm~lBNr@%9fV)KKnzQt%mFhpB5xtMOo&UBs_vf6P^&lEjDf|D!# z6Z@e9fvdhOO(MW{gIZd(^(^Hn#DvL`K;|Wyh_x-d5w@SA0y*5iZf^m>wJeveRWX0Ohel;ngl#C{%H66I z|3?)Yrbh`qzO(@&%QJThZ3bt|z{3R{Y~9X&K93M*yJ9=GET$4r3bBE8aqU#Zitw@u zx4al-yoBw8717Q@gh}-h0Kf>s#=JG)%+>G08bu0d_H)f-RG3B% z%9pCF?ZXXbO0AW%%RAG*dhU_ku;|NA3p}lSnwQG!fFuzBEF{p=d51uxR(o#tA!x-q zZYq%;6mE87*U|gTCb{pGMx%VCX2Iu~-b|tbIwMZzPwRDYVq?Y?#h~vvUl3uBGP$WI zJCf9JRkRk;*r5npn~jaJU>OI5P?EN!`gt(O&#(bw@j4X1R}6BRJdERT;GA+ z&G*q1Fo@!yov&$B^8%Ukc}wJB;;gp+Bk=z=Bl~)Rv)*F>lxC z2p+%Y6S&4GB;mWhu)%eZlS$C)bO)mqVBW+_n$qdY?6la|U%$Jbf60%+k$wbE?JBR= z9w%1FdFnQIDCje^j(O0zOC3Bm`Dzsbvc7#31>d-6pKioIMNY%18B^#jd+_M)_r0w&6gyCGs21&r^cqpFTW4w z-XUoHcRpXPr3jOaR&yBT;Qz*HU?K2V zRf=@A5eRPbF!(Z{E_+|EC_k{tgF^ZXySZ3yOBoqmEVlWQhkF!ru=DSzvn{kmRoT1e zj5ta%5DCp7C>Aa(0E&YK;UI!tAoE8 ze;pBogeA|Jpz+~G!oL?FkJ^I1%fUr##N6f5os!BZeV2hV$_(E{EW-S(!{J2 z)EXdV8?iK4K$lqcC%3cbUND|Ab<%rT@$bQdH(+s7rvoTPv`#ON3LJ%+V*$;a2Ui^- zU?~A^R)-Ebh>@t!r%dHy?|1&W3IM%kfF67EqN@8;g6jj^x5Z+p-e~E9L+yl4gk}`% zL!tYXft-Mm-KBhG6}&^-W_R+wJhacDA%!w|&6gS>0J?C*96~2M0KW282O#^lfvi1P zAP9+LaYWc-l%}Z>-zwww@g)d%1`MN;4z2-9_1z%iXyd;iHw*%*bwY8sR}V-TW|3|J z-Cr!b&7qEDYRn!mJ0--b*Sa6do+iP(nd=A;hcAMC79oLT*-Sp=dnx#?1CM;8z8%V4edHJrgqR z#Yn!I|3YJ+K{BXxXBDs*f-)P{!=KUk^X+_0U+A8DdIJMssSgu639aOr6g@#LKCs{9 z6v3{gd@!4X^cPu&68`jn;K4A9kuash{1j5OjCMdBW%?@Gezy5x_6*Zsuj)lO2 z_r9XQBAX28Z`aCeYx)4V_`57N6$uI{D?d+#uiQ7`Sd!kH;-PdCOIwj&cl`6SUiyY+ zBTp)Ta1CA@hho)yj9xPeIKOM*SguyDhXSKur0+@ML)NY4^P3ijegVj#WuUbR30AbA zS!Gt)(sj0XKBkH6GEGvy=K<(zsp;akcnxk42snSl0FqOr&FDV5M17Dt>GEcM_9BEp zz2+f9MYdyzji3dOBEwwIF{paQhDzH7EKSj)+(fT=wIdyS`wjIa$po=tHwZRtk`5V2 zADE;TA5@%1cNIlJ^pR&T?`l!-;ORG0z1o5^Z3atN1@uV;$hfd?RATfQ^0ze(Xe?{( zfuCgJnqTV3`B2ll5`M1IyC+wkS|#9Yp;cus#_)T~fkR}ZmLX#G|5^jZ1BR`%1oLGS zkH()Uqs)`5Grb)tCr}&cQ@80t%lQ>bF^H8Nc2*jg9ew;{{T9M?ehoe$&cPb>$AbZxw@XwLhO?RM$0B z^`G>VsUN)t%T?!UAo;fp@H0V7R`b@t&g1+`V@Nx7A=4d%>>8VO{){8+=Yp+#fkt)p zuGaXiAKyon|A5yH!t_IxJu#SG7L$cns+Dqw42(*e&*II0=Lj`!@j5-D@$zQk)mIl; z2mn+QkY26pjhUe8zKC%&MH$>|Z8Dx1EV0k)hHROWQhvq}DnSz|%F7|v{c!;dh0}Gt zn*nX>n+AtS^M`GTJ}!XY4npqrAPX?21_AJR={W0jGiV5e!ANOe5wN&dvq0NBjG#$h z9(Fb$Yz46oFb2yk6O(UVhmp-^4tNzj9RW!fW6up5-Cjl3wMzV@3r|(rPyMqL8NjmQ zsUhr_j-WZfU&PZ#tZxJV&us8UFy<=9lh!LpC*3CyK~|_-YPLkASuW6bb^zpeb3qsa zOFts?vQZIF%Yc)+QI4@w-n;3X0VG?6Fx^XmIWK~}_x{xYBjeCTBqu-Ny72AT%C3it zBcq5B^N#~%J=a2W7sL6q{R6-MInzsVR{Pq|rZ&fa%)l;;%Agk+r2(bhi0aF(s! zi@TvpE^TYpL(Fk4V6jZanaylyI7_uj)NF1;?c;W7bMagc2%nv2p#f8)+w#&nl zJbak$S_!Z1jo`DGvKfg-au!D>WsK?V{CGe_wQi!F7BeBa_5(uA*xCLs*5I42fd1EMcWh zh^u9(cd?R?jEU!9Z63#(bU(og6>=k@9+%9FvsWI1j-&|)67rAN*RP|ddvlDGERKZ! zF?8guo3PRq@X>ReA3AZIz&$y()DJ9OH}v~TqP{(dj{F=4vu=B0d2YDUfWSz|)GO_( zn0!KnnSD;TC|fryMDPtrfrK@ydZ4Gb!Q((U8^UqUKP}(blaYK~r@+Z4k1C~`Q#j~R z+@iQyP32o`6^M8Eo{5)nUC*`}y?J9VQrMsXhnc^44nMKo4^71Sx=%o$HOpQM9>MJa zyzPd_YWYxVeCyyZ-~t-P)T?v_a2Cn!Y+J_lT^VbfIxFNRE@qxz-XHlK_Px*w;)B}lso z=rDDxo)0gA@HdjcmzG-tp<=@}2)JW_eu=b>{H@9g&qJUWHjwKd&}(l%pK#U1cWz;{ z+C+${Xnwdd@^etJP?LK57ZIi(`hIvU)&@2(w|KON8N82OH@o=?jYD?=8w(o2)aps* zJH@07Q4*3LkA79@dMWC6m&y#FG0fsD<0V+3_AVI}jdlgzEBvFM96J`Vw+}adCMy}L z^cZG`b4nw}&UX%CY`5j!gV8N2W3S`PZWO&NyEP=9wY5{n0f-gP@O{J^%ul>3^@Nch1UUh*UXk12aHq+4L6 zoi_fh=;p6Whe)D~s|Hvud+e53dALH4j9yiWF|jmQ!G^afaI)C=10+AMMjbi=KX@lp z#jd6Wug#vG;8_KKnfeM%eiS}kR?i#rE*qBFA8z~sADC2X%vhS!@Z>y8P=9~Khjg^~ zg$tS-Y`%+=N?nm?auT&*fvN$ZY#Kd8sH@lKmAcqSNIWXxXOk@nvCvC==e9DMYOEzF zBQHaogk;xU(;GuVLb6GLgYQfX1o$q%i$6d@qH!(i5D7`@YxqbKH7+a-3CTOTDs~bQ kSs&yNJdgZ;_Xn*qyGe|h961egFjx}htEvi_a)w_27hSqV{r~^~ diff --git a/_images/docs/wait_until_task_C.png b/_images/docs/wait_until_task_C.png index 0ce279aa17bce0049287620f9fbd85a9cc1d594c..6fa395a7df901219a02d6bd7bcc05ab91acfe10f 100644 GIT binary patch literal 114917 zcmeFZXHb-B6fTHkPM`v!M3oGZ6eNR*oO1>dCFcxHP(hI_O_D4*Ho3_`K|r#^mL}&6 zl9~*AdZzB~y;WQLXMgS1ohrwkp6>7a-uFG{InN1C`zy*zT)#qog@AzIx|HNgWdee8 zp#%hH8!ladcQzvSMBuN>wvt*71O$XX@qf-lvJz4d5Zoh>dihM%RexpF%_CwU`E+A_ zC8qTak(T72Mwa5s`B|=ZxwlbRi(GXS%H3cP=Ul0O$U302I>6qmW0gDlT@QhBN{$Rb zQD`XMIR6aC=6mB-ahO$cr?Z#0uaGhISGs#lKf4ci+GOV9w=Cyde|GTB$F~>;as302 z1OE^PF2$MH)1_Wj5pa*D0PXOa*d84JYg^cOLJK7oc>?wF?3R z19uu}P6{OgUyuchlV1545f*meuhFnTD_1&0uXc8JwjA>ie1F>X3vU%?6FoMi^z2*dV}%iAwbIHOwncB- zZ^QRT^>?!QBOC;FM;vxOa(Fxo6+Nk_mG(Xy9^XD3KOH-8U#py7ks};J(#u3dMyA6< zA_ferPfrec3>(fNHn>d2YTU@VUi-=m@2IkA7CznI-*=z#XI$w#SPfv!|J}(uZpk6C zl;}Ej`R&`ci@h=&Xbq|@YR_$@>(oM;nMqz%&7m{}grKZ90t}lUL$ud zVIUHc(n1K?yY`jK=u?J5QvTy^p+0?jDQt~fNrr4p%7+jCsHv$9<%*K}*~=RoO_8DB zwBAba*lfkI2yb;fURqfAy%kw>69V(Fs4h}}9wNN8unVFd{?`*j0#yznr7THOueGY0S|o!)V&2GzuGFz;rX<~KIf?4YPZW-g*Lh7BekT{VcXuo7*?9k) zwv$3OPX5NN4o8NCCD+sl>Ewp~e9gsANywi-bA4%TOrpD3k}jpV_|fdl43nUsPLZap ze5MMa-wTs?yHE0htK7L(4{wLJ&niE>UDB2O?c4Vph2}e{o16AI5d8cKJ)o%5q@2O-)VGGBPrzec@cqOA?uV*$SUyL0lKN9jvTSuxFV_ z*5x{3k}uQK)A6qYgcn(YH1F1z~UKVj?0)w!)K+(&pDX zH0lr3a`llhkKRf@_hcfG&RX9my>@{Zi<>QKp?-|)sGLuC$ z1qELD%syQ}8ujt|gQZ+?WOh!@qvksf&38?{dLNd1FIQf5INrg;4V9Sa6eM}#v>u!O zzBlb$9o#L~5E1E&X=`X@0lG0m&a6jE~$D)L-9<<{sWgy7uTXf@G- zjZx6XzK8M2(SGwCBY?{oL6>}Z13n$Mz3sS_bh@7;jx;khEez@FJ5Q$jD!+0LwwFsL znw+x$FP;iFo9j-pq0`zmUF=O4NAfS{m2?c5Bw5kL+~v0Wd_TlV5806>72Z+3UT1;c?~Sg5qfI(Jnm68@X;rU|d2AA!k-^aS z`}eCzCvUk#p`klQd5AK{Mdf8zjIKlQ01Y4oFW`G<*c!EDi9J7OsG6I>!p*@yL!t8@C^`{#%nKG?TN>pZF*+r^6AO?sUt?ug_)OEqg(W} zhT3b-(5+U#GeJ-T&b)l5t>Phg$PVG`6uyvu42Z}+8!isTIBYUCy-KQlPQVzyIhjwJzS za2c23R`q6>e7&mqL_|b%bS96*;6iDieBbZn7dr;0I|iHk9`4|JJDB>DfjYAf=`ztv zK13qF7c-OcIXot>;+A}>*6R)(yM=d|=;_7E$GxiA>yPZMMk*KStpj)CedrJk!ES7q+9*P3!l2f(RBvPzP_LS#5>39-lthL^=AnD zekC%TA$UhSZ7WW_I$YjOe)sP$+R!_|=m2qfmZpK<@BnlocCELt76ma*%Y$0O`c4CC z;!EV{HyBJ-+}h1&=g*(V<#-83gh>EUF;It67zM%Eqs2M<2L`l;soVJFl0-%&C7fq^ z?wZ7hDdNDad-gm;h_8Gkberh`OEne`p)>;)s#b45D@~h?36l_(cn82=XxP|64X2w8rMe8jX)xRO5vT~^7D_5hg*Z!<<8K?2`AW9s$51{orXmOltYikS7 zT5W3A_%}@twioAe4UTivOoF&}M_rP_4n#L4ky)|&SMI&W^tq&P|3Vv9qY;_Jl18T zq%^Ex(d~Q*^3%3_x5Pi_xi11XR>DCCanS?|Rjm}a=RLujQ`j5pipdMP9U{-?U%efj z-#*&v*0F-vE=@~M<3>X0*ZJ+4PY_)RYzAO;w1HP;*c)n(zt7-5NJ&ZOn#c^e1zpy- zoA0RT=~>0gXNJ8oH#h(H7E34kKoSeZp9*jOq6Lsv&(kza%Re0K^tw(ELKGx)VEJkW zvbB~kd3g^>$;fi^@?`OVus@$v07m0|G);pPA&*hj)y<2ICHDk)QGNF8JrMLnx4FAg zdbGSDPS)ka+Jfox?(6{NgY}|TkBvJdU4`GakvKU!=aiOmC)bERu^!2i3TL3td;HjG zsb7RfLd3j3%NO(Gm12)6cXHlvhFqMgvNH1TpZ)tUJ}m%Psc37*KC!|&e*Z9)DiNv< zMB<6fm}MkY8`moSTFfdLbP-@e!jn$k+d_V?IGM67P)TDXWMn!PUQPw5$97XMbGxg_ znhE_H^(g2jcMqM~m^1$bhUXMO&QXh?XHNFU)BmOV)5Cf-Rn@deRt*;FP>Y|RZ(a@z z^xgt6kr{(VyAFzU{%{xN4(4K9*-LXEm;p*7QgOOY!_v{}W z%+Szx6NALY;AAtJUJ4>Q5bT4YZm*2ia7K&26F&wI^l=U=b%aUXCc#ll?91!N1O${6 z`1%oFvurH46r5i_7H#1)<~DEEpQWT-VVkVR=p@%u2?PV}w5&er&@Jq~KO2qzz|Kgg zAy@OCK*FK0KN1QO?%v054HPR5ee4Y0E0iZ1`i-wEd?jaa`sguAQx(49Duhc(JMO`# zlp(FiLR*N-gd>cwR4W2RjFf!w4hwGAM}MSs&kKIbvq`MiP!S-0bR8oihj$gV6e9|BCzmQ2_7JrJg} zt!_~RJbhY=K0a`-X2g{dyfdP}7sy(^f*IhW0IPc5?^3fqZlmUFwXi_-1iIRdW(s6l zf#<446}-Z)l37@I6x))#G*$*EZ)IgwhCNxNUhQ$Piv9HI!t%J^l4N{eOObJBtS@H0 z{qx)oX-ICtwY(;*mTOWDl4@BSY?<*bs=f$gD>7{TPX;2I=+6f8ZraT zRG%sgMPSP`SZM4gLaH2mW~Y)N8`e0fXl9m;=V(@k;J-4;4Jx=0-~N8pU`l>vB=Edr zDJ0%d@EM`WW3f~v2w3zU1@dtCj0uj&w)S=u4>G@cO(6FKur0bDJ?^$OXExUnb1{hT zAA)N__;MnpQPtU$kPt$-1OYYRuo@5<0imR&rRk(-#e=@k;l2EzC)6vAwV*~BVpx3I z&z|!{LVw@EWm17#=^$0LwR89#=1jZd`7hJ#eY#GO0Xf6RM#BWBL9K(q^15{VHz9{n zkE`p5=T`wAg*>enSV%^kb=6`a+1IE8kxamXW$iMnVFoFDnB_Lf}v$IXj#;4m4HNR;-%mDXVVieu?x31ft^X+*!iqCAD0?8~!tDK-d(Eox+ID(UO zF-pf;iSAYp8l#`9maA^IG1XMHKNm+&ReAFcp5p=N;3*9_VK(F)-xugEuw=<1G!F3q#BaQCzgMHqiLn^_?;paxIKngmqNzI#i7Ab z*|bZU4BI057W?}YL{UF{E?NxasJR1y-C4>lpzi&Z93M}KuNA;?h$bJSYn@b8}=rkANwpNS7`49vajMnbG`_xVpn_G5GL!GrC??S~@^p^w<$-w}j|^ ztHMerofQ6zQ~_PV=b3>^b&DM4S=a8U=Zdhh$^f+&RnyYSe%!_PVtlWeH!o9`$}(VZ z@>g41FCbkeMjs&uaMae((H}x3xD9Mg4RTU^3g>m$Xzpew_c$`*+}eEJi`MIrQT> z<(8(u@>oRSt1!Yl{VK5{o>gEFwm%EDG#w9D%PoM5{a1d#+hvA)LJmaHA#ES?A0N&i zbh*@}nsWb3YulsP`XFE5Ian^R*k0%nc5!(L`#t^}&$7T#@TCgK1qXqH+|OP|*zF8x z=-gk7uG>!cT{NlR@3c|X)Xa+3cb5Wcp8!v1E*G=9pVmTa2!L_`xfjhqfB&Cc0)iw? zKYrwNI`FLY^c2-$gRdM?ER{zL>7*`lwERe@iK!VF6hJVf3=5-bzJo8HG~ay3~mjipq!_=)VEGW9URYD1m z$lW_6!X(j69CCtKZZqW0@m^ojiK@eV*8rvt$0L07x3P>(L|I8G8Hx))7nWAb#|ME7 zCo0nTzf^^KA-;HYe*KKc6Dx#a-E-1(7CyJKD+BhKA>}b8|UmW$N?s4k37|i0GScfMw?Z zinr>=Pw>|72iJkUVgp5;@K99hwq*>){X;-Bx;>r3rbY=5xhSV-KzfVgbg+EkgN4+x z+XU~rSu#*(2y7!fZuJe?I&$;!wl6xe+_{F$6^Vk+u8vfyEG{mR^IDJGj4^k8h^=(U z#I23yg26zA?5Dox$R)oDqOYG=>-zmJ*Xx(P%pNVo1sH_v#TUn1 z_A`>fltc9s*ySDSo}F?iv9|OW*xmZCJy4d#EU)F-1D&R@8$ z-kfzA#~}Ft+mnIAvMf6ln)*`8pNv62Rit`P4jL_Intx7X4@PMERm-&43lzd|w-Mo~ z#=~3Qs#z)h`gyK&d8QI^wR>5CPNmG$mxlw{DAIR6rh#jyoI}E%^ z63Q@64Rwr?cVWOhu5qq9sRj7Pa^u>|+a~wkoXV@(wps39yk16@>($4CUKz^|BQvll z5Xfm8cUAiFqmjq7?JkZ*O4)ppvr_q=%WvP;{2=F_cW-TY-dchK5efX4|6UkC zAvAuZ+%!jxq${e$eE8TH`Pl9guI{i(xp=Ezw@yyWh#@=MF?{6xw=2dS%0lD=W05vY zBc)J%Rb%s3Lq_npBaeKp5EH#pIUb86=XT17w+=N|=TI9feM}nat9CePKbz!OMwe|i zZ_E>I71p?@IJY2mg^-#(+agV6ARymJ3d#6|A(}%>8ADPSJ0LTlULr9$cR{Ugi%6>X zTWe-}c&xEic*of8m}=Kv_{`-D8RQbCKJ%$p5!@DS(`UZ#aFsM?BpX-7a{gkdB5p4m zNok&&uQ(lY-MpYcJ+DMBtn5oXd-)al7&a;MF|=B;upqruVn6q?HlbMO#deY$rh#Al zm>~!Z1Q#L{aNS{hKNB3f`0e>9JvN#!CJW1-D69)lnZDa)8Mc$JdhDB_SD4kLjq~I6 zljyRIJ0Cf5_qY8tVnNJyOS4ht9PF?T6eIj72{Zq36We?{_iNFf^@~Q@Q~fYqX0PEf zqJHI~7pqQ)fuT|bL{x2_q(upKIVX?VbcaGCdvmo(nnL@5_u8vSc6Viz+N>UhAf3WJ zCWU)hpV(-!N{YI$HoI=FeUD}~(>3R3wq5g{)Mo2c>xPwuW{j>5SBX;{=Fm$84`Z@d zXu2hvnb5WsEYYVg4xbc+(N!L2Uzs6oUEOLY?oho~z-0I`qJ24>@rG(?s@e|4czGMq z$M)&vT_@ND%I-UE-0w!`{Yql~$1H#oMo+u=jeqT(?*zN}Qdo}!4VrA4FM{iJ{Dq_q zene4mi-HP5F1>**xQ+a=)^#0GRl5F%e(mWUNPm0x8uO7l{TO=U)i?&yUoovT?FBQ;FgG2`b(*vR|#K1aFxuXTA0-Zjp=R6_y#>e#m2~m;3!&!`YBHZ9duTkB$Ah zWm;APq?etJ@kVXW&{arw7QBhiS0d>QM1kHR6Bjvt0?xuw&)ren1Im`8%34_-2fF=T zL+MVMl)2Gi5+WD#-!pwx;*|UeZFfZEku!2~8cn^?yBB5IKgLl+I5ap8>x;M%?n>0R zRn&+yH6#d|Lle)I?gq7|_z3J8v{27>09UvaYWwG(^G!MW$5B%~g`c|Wp6g&v<>f;) zK4!+VO66!CxWECC@6Ost6Z$#VSN<;Z^WwyPsN>gVk8$nL_mCupP+B z#Q^8h*62hwzjk_;dvY6+nIk8vQp#!RQr1ZZ_IxB(SD96{7-C$f+PG%`(5%S0MoIz(9?``mIIuMW+zk93^YFm1l3KGv?itS)Lnb^-JS2 zs8Tx_`Nv{hPVh;V-LU)hSjU`@Un9?8w~Qhh?=+gOomqnPu6NXB9Hmuaya>IPQjN2B zUPV3BN&#n=K>iHH8NHAZ%Pyqi^!Rn8DbGaTT}^Np!OO*Loo3;ngW+fF#Ql)b1B{oeAs%BB2yb$R=wJ+sA%s+)4(irkl%I!+&7Ps&RndD&jnb&U8P zK#2Qy3C#w4m)MrTD5$Ky;%QNrGh*OOkbkao=OcW~OYruV zMyXY=$c4mKU1wFRp0gT2>E%~Btz&aZt*w90i5^Q&Mv3!}Qi~1i&`ZH5RjZ9-SjOGN zs>eNg$_84<%&fxvTUMGRI+90{PCiRCfOiZ5w~Dl>Pg&ZH{u3z5sPx}(O=v<)=@f#0I@#f#UeFB$3;Ged&N>7zijdf1`I&QD!aT z=|mK$W-5w^Cyu4H+5pb1DA$O9?t_}mjD+lMLnAt=q3KMsnfPTj*EY-H+Y-(AilycSkXi$b`(fO)H3! zQgZ2WGlb{VIE|v{{FX#?lWnu4lr_G*BBIx6D`%z-Y+c;IGmgp{W)^|1Dc>ip+k-6( z)EaQbe*JO{<{=;Mg`X<3+Xn|LnO)5S12(#ER~fAqO!@Wv>y6ikkKSuL+e9<+=((ww zXsZbBT4}R+TPHt{6dcgkK%bt-M$UZc=fP%MHzJm@hFNX2Gwc&(bsX0pM?;9k&~=8mBxEhO*Kwy;8!0gLbdaNitTq?A~C z?fhl{iIt7oXq5}8^;l-aipQ+HkXG06dh48?4k@-o1vw)nCsV;oGhaIZSRz1Sj#@vo zb?_lCFVMjA#mhXoc83Dz10}M(j-~lWtO3PicTTdsy!{2@mPkXzQHP1ZIFzsYwf>yO z1G5vQ!aX^5gHxYI*9sM}#~kVs$NHq5E91Ky1RmOV++b{iphsOVc}eXw69|~OdTn~t z=BoX^aw(#9oK7lCF}&<(|2}N6G=*|Xn~T0u=TiD%`4eo>-^LY-S#K3YfT^ytg$i?YXdzapoi8|_T%V@VQr z+|FMl!hF$+X2{c-+1w}n#flWVUWkRj|kX#A-`_@3dn*>6m z&U#?iS-399684fVQ-yhGAJ5yOd+K}0|8F_sp#`E|bk?Tk+gveQ8zqktVWx~u;xP(6 zC_OwjirrZ^I4Df0qUZyDL`UvY_S zr{A8h>K-{Z^vB!Eq~?ry>Q$fY=jqmw0NBqu?jD!7#`3iH_b9Rwhi0!tin5|@vz9Og zs_ko3NIDJar-@G$QHXX@Z0%?nngpwoAuL0d?LHf~nPJjOwIH0gG>D*)5j60UP7Y9h z8*~TE)*WA42=d<@QXq`hfp4=X84Rp*g!zl1Jf(XR-v+AfPTB*0!tKo3AJ;48l~|bT zOyitb4qF~0xqxoxx6PjZuIseOvufAhH$bnBqJor&Nmfn!2J4UX8K}#b5aD@A2M1b{ za_uADp8ET})peOF_M3>cgKtwsUzY}*Xi?l)Nx4V=#@WbppN!$Dc#|yR}mst zGH&%ZAJxfE2t37L$7Xk0i7&BWdvXqrhn)}k)={`BX&!3>lUhQ+Lu*eAH%3w?kVT^= z2LcWg+Oz_AEwGuJt#_o5qUDNkiolEpJzWlW{ags)N^QiKatzxqLZDq1d0GD^G%4fh z*sJAw0^5hnho@_h_*LBe#i|aNmg9AL8o}dStUE>mw}YqLe--mcBH`PI@KZ5l1Tvuj z)qSk*laZJV_K6Rc3mjt)!6k!~7)@7SxZp;1Cb`5T+izQR)Q`RP+_Nkg&-K(9G{s|= zG32N8279qP2h*G9`XaR+DdC}Q*-|tuTfu30EK;=msgHu70o)`UZgL`jp0Rsv%l)7I zrYkdK7Q1m*cQ2BB6m}WSed-k^-c{Lk@RaiZB<^Y!YHkI)j3y0^keq?-<7oxXN*{&8 zN}mrDmqY?GDvg!qn>~dzEV8~xai1}PKC>kkl7)a$G!wSR`KhQHYAXf*>5khoGcU+itw^^!{qTc^<<^q627^ThofPzhBIuax zGShNqiVI{y@^1elxNpECzY zG~{?7?4IkDrplo$#(OSfPBVpmIKB;zNdsdA>YIIZtWsjnAdC6NY$CaI#q9;DVBSq0 zE1pPlfkUuVn%tn9(`urog;PC}_2R#!S`V|!lSogVecU8sQ3Z5?R7ZHiJ^bPsSaa3^Wu=^8g`Hl&f2rTqqc>w43@?Rml zch|JpZJCu*8e;WUFBPWq>&rH^2%PHqtTtYoK)1gYKysM}q8v3Rx-B17rfh|d%+c%P z>1C$&|CMk{(sWu%PH<-8SMTHQ1@8-V*{rUG7aw>oqCy36YOM5(qLYhGjT}eCJL`=D zLyD~BqH2k+s??&iIbTxkAW)bP>QuC@eiDzlEb>z#qLL-5h7J>;5eWqY6|T`v~*#Pzqg#+J;*%{&P!7~YGZMr z^pBWS>D8fesTI9-$Va^v(Ksy?FYornYbltO{+nw>ss(xf$qhzqkJr;n(X!azJ+ZdO zR!e_0Qi1%J&c)APyC@zkSn0TST*J3Mp@xzQkvS84=D;26K-(Ka#r)l;bU} zlr7Ea>Kb}AnTBwKnlFCMOJPT5=|<>fg0r2OWE+ryD5y67x{PN=JUPiwBsm}WseM*P zX=!3|$uvvJVt`#rS;lQj;Bj4tt_8W2&~5Z>^lBjEmyG_S*N_n~L}SXm%{wkYihT$kG$-*~TdVA^0yE*tN z1Ij)^Az@hb!He248sbpa-oXdu^{ld{P#FSVCoH-O3u3ABrb?_Lie}|YdnxP}>-vvg zpvbW3E0d7;Z&>vDuSwfBFkcDJ;8>#K3q2bt1tKB7v3cvOVBv$J2alVuqS{HUTB1A6 z(J{0NoQ>Lzj6fP22YIB|i!?nS^@Kb@9j|)hQ*B6axlP+-VIe(biqETo3#rvl*7_DJ z$e5qp;EA+WEi_H*4Uouzy!HHMbwesd5*Xk_XF2Y2^OtygCZF)d@2X3y=VO<5wNp1B z^&QgQ?xMQHa(l5fL+zjMCO7{bV-5NRl@};2p%?v6!}^xP1)B;C$sFa{?K01CZyT^< zLh3~rGBJ$a*6-ujLd6GXfSC;&XnwmMdZG(;i0tz;!glRHQx5*_y2vbPbGpp8d*dfI zCt}F(Oqct}LBj$gnlx}A;l4MO<*{$}tC}!ZT z57=lte+NrE(7TFo0ngYlhg2$0KuVfML>&qTz3{v&neC`4t!NgbpM0e8?)fZHM{*R@ z)ddzg5q;^C^QRUKWfF~L^QT#OhW91IdbC=ahF_mn#08C-O$Nl#8zTv>SRh|Lm`|GB z-XjV1<(Y|Zzm;eim6!BCst^^{qeqC@FWhr7S@U^d4Xx@!^ zY{?;b-kmXSMbZmEY4BLfXFmKbiIqhp>+A$(cz)+4EhLRD!ewKV zid*?87VjN?#N*(anOxz-(tan|a?ydFI$_nXw5$(DMwXQ-V&^Ma=sI&#OM)qecA%vPr|x$2!)H(iVlPKg z7cL(W{ieS4E*R?U=01^#n6fy-Z3WGOMbkwCnq77PNhOTx??yv!8z|mkw|}1giDUL| z<|pUg=U#ToD|tZ}&3gZiC`nNlVT@}YX7|Qlty_oi7hgLlqu1v^*gWY-wOPwixgw6}QF2K;_)~HkhHKp}^R&?wsjtmSqV(LZ zpC-N>l6Hc#TPNgkEGelk*VQ+u?_$>aJ#0YZf*{~aq_U`o9w))XB`^&Z1?^9@cL)f+ zjsGi}x=;w5V#%`xrb3>sv=YXOp<>VoWhAWAW6X{nM9i;39iJ zY?KHHUVX>zgo@(JwvWVvFuxrNB=fk%Q3IsF2(xRALwES>Jko$nK(R(j&qByalqWay z6PrcElhT)Lv%`^3O6d%(5`V8zv3O650kk{84iF(w_h9E11^)Kjhub`69qh?)rL*KH z;|5qJIRQbs#e_)MNlyq^hQWi2xv2U>^Sp_ zCO5^OA^6_&3}3=|2&q)o!S(f_KsG2KN4WHA;ijgQ`$B@HX`W~Y3qE0j6dP_mMR<1+QWg{^adTrxxjCuQI(ER)P7#BJ4Lf>@HPE^Vs{Y7a-U zBl4c%7+^CAUg3o^XFvNlsn#!gqSZ8htrD@gOtnI~q_qQPJm66%+k^Y^!AF7#F{0W! zsR*Suau-WQgeMy8KcE!+p;E0-l-u-wYHC2rS&n0t!iQ~(F?ER-D9AM1gf~?AN_ROgk|p=`L+02C#l7}7@R`MSV!WJojfAUHSA zDD66x6$;%CA{GYhSPqQisX^^mU29hGRPkh6%ihhi7H8KuNCez59SVn79-DS5Nfl{l zeN1h%>h9!~k1zCSKjHIzs9aN}a)d=OkS6g+6ookB|B?^IjKPUrBfwXzUlA~SPoIYl zlhRz4zdfHGc5}ss^s0+A^7SO4mD}927*|syRZFzZe$YIlk_ zXm#G#JZN21m3FTCx7#$Md1#k@Zszj20bsPrqr<4plfRI7boqwoo&H1c?!EuN&BS~B z#2M{LI``lX+ml9Un=NxRMx8~I`}q#VSTtmP;BQDeC=6#oKMF|)h5njFEqn{~{j-l3 zWexttd4K`+wY;kZE(pD09?9Xzu8Q z4H^T?wk5b0Lv0^AJW5bG7_6(Fm5oo1_kRo(-1x>tBnPWTg4_<2$=jgN+>6b_9n``% z0@B6~|HMUQKU3*a6uMP*P^M$xd1ObwJPn;dNJ_ECbI;SSvxSM4a~f8IInrfYY%2*R zD#Dn;J-qOf^IHWJ(x6F)4^_4Tq*hi+LgZm|PAj=l-il!ZgK<&GlVn~)?w%C_OS>#z z#!0m$k&Uy;_iPHW%ekn(zZMTn`@i(ft32%Gc@2aw_d~deMPDD$uOyXkkn%wzsE5ek zofzNU!m^+-t7^Eft$4=>If%{g5nQSb6_sl}005qt#!FPeSoOAj1G?*8LJ>^{`9yeM zCbw&LYdG=bEx-hIVOEKh>i{nlR3Lu&7DLB)g!#R1vCreSB0h{HppU-Xa9{d48YUX1~V{-b&R-L6U#x`LTj{%)?XXA2W1Ugnpb zW5`hS{&vGc?JmJi`o}*H)mlgftYzf9o@livO4tc(1j^Ip?cT`qW38!H(m+Zyb#;z) zn)vcRN{l^vcr=aVlxS8qK>F?f3P9oJ_TC&J`Je2aPw6o=%@I2HRBuD1fO@qr?zl)j z343_uzVD6a@A8ChJ->9ni-H^#^(XK|c8pBscZ>(ug>#12E;ZYhj9*w)*_TeY+Lx=4Jwjf+m z890dB>qdQdssAypY0QjdW+Dkz_w%-7T(SxW?dCmIvUNS9N84TcJkga z#+HKMP{hrr`NiQtq+DdR*F8?=NO_|I(aCvs*p<(sguy9HjHkJe?Bw0HdnDXeidydQ zn3Grx=4}urIo}REUosTb3l!Gr{5x;&bJNg%KA5l94g=KJ-g%gb3ie0NgdZ-(5zr}A z1i!1GE1)*{H03yDSw_u!f6`vSmS;GGLW6`X}!*DG&8s zmEqR=O^bZ98zdfE?C<@VebaCfsluKHMA*1#Tq#dWWfEJ1_H5;&U!v@-sqB&Mh7xvv z6j-=0x1$?F`mnw~I0(3{y0^^InV8ra1@#d@iG9@1ZE(A5U?WqM@U0CeAw&26jI9_zczT zZ(G~(6C06E$^Kq&WRx{Gbvht!<{@XhaQaWASxn{JHljASIs1e}@sLKcFLY*;-#KC&w(0$VuA&k6D0%`YxEWCd*T2^*%iu zuWih1s<4~>Q}12xvZb}COP+h9f$apDyXe*~dy6AshU!-R`|m$V+{Ye;Czf{{skJ`A zJKa$oog1AOuX=7|En-($TYHI0nUsX&OI#eH<2GexpMMHdKL!(?l(c?x%eYAMPl*Z9 z?Z76%bMHp283hI7&R!&REv?pNcL}~I_G8h}{U;%{kfgKo6LpJamB0{?`-M~v9(u8L zzea1fc6DXs=jW@f8zq?PPUt&1r10~P#k)K3QNj&ih?mAufXdx-xPC))>~io+CF>U2x_1Bm{cCqP-|g+W9_+3wzz7xj zc=6k-Fo;Xb&mRK=&^i1eR>3f zw&yQiRN}BO87kl&zYP+g=@xE-d84PvY@dKZ>yxNRUkuNdS2Qx)$wok?4_e#~oPDUCvho z{{H@stJp{wh(&jU&`HwL@}aQ%_Ps}skQjqqA>lUbat9dhyh%dxvfk@hQcCLng9jgA zv{iPsZ*2bepyn{54nzf~v}|m_H)+Lxqb)S>I$RzG{5im3%wLhB_8-@UVeVNBp&B^_1v4vaf32d`}lDg%dM$Gg*HE9@zLdfI*hk(=_f>* z+O5lpZ{KbP40N51)F5!_ZJD*-fHC0d_4UxuP@=85PFgy;mvTo0+bcuie$?)t+u5sw zDk}KUwIKF5|0GThrPNnoAo}RhqyC1`t@&<7umHiein9sw60WX%1vQ&js$JHN!PEBk z_Ogc2M@J)01cHywybih7O?U{fl6;J(P$_-|+vdFjEIS&3c1n$jIfAk2< z8e$|~?Fp*vUkx9xp6TC+lV$Mmz>3(rV@u5*Y8Cq~ESM5hIj^?;3ZorJ!+`MN^XJbK zFqHcJ&7-i0h@U0hBEw6Bc$XB}n>c&nI{CS$l9HE*8Rdl-?3`1&e<1Q0w>&1s)^ISO z`snq~OBVdj@hp-_hsYx z!s<_U3h)OWL@gY9nV5mot@!X|j9#@f_|zSk4qet!R8e^W`nrQEP|BiGT3|L@;B>#+ zy8^~;VOtEr;bdbTePq|GB3Rp1BKZh&*RFb(;YSCS!sbz(;13(qEq#DE08u|kHFSUU zXRCx(qn6*eF_IqOR@>VmS%tA!0M3OC0ZvXu)DMSZ2X_{1TzwRO442Ubfzh7nA{lAv z!XeA0Wn2&iZ-`CZ{-=x7uI~V10Na0ccbm-o3VU}rQwjKssA+k3=4^lc*=yw7pM!#~ zfo`J_6iY*J${?j{vAix6*=-2&#;1qfWOwgM+1eH!Xn!7mK9HD{HJl{Vn{+xw_0Llq z93#-Lg&-?ND{rEqb+&u^ON)D-Dv6siU&wjg7CSxk{p>|{6Fa)K{9J8NLDSx)$L)xl zB-7`pAnNtst7$Lh*Qk&Ga}m1GpJpkT<&E84QER28oE(-9A3hNLHb;8^AA@c4DX2RL z0Ck7`RwwTk*f6MZ$aUGtxVX4RT*f{1UF>W!&3gvTzYad2r5!?BkO6g@jI*i3|1ku8 zhY-vZcO(dsMYlIi{P4l+iFebtmoeSdm)`+)7J8q0!A~W0!PGQ<)ZG=Nb$hsBo4dm9 zr7pWq+{nx??8cWGmk$fyy2UvC@>s!HUO^18RSu6pum*8GYOS2=3FfO1n=QSrO*?#Oh{x~hm@ z6v}N?*Z^^wbj419KQB1qv?j56^DH+;U8QPKhoIr`TH^%SyG~^(*h=%$cfRbVp_HWF zd!0vi-_Sq4MpJ&yoy?;{P^|Nv19^e-=%MtqAJ|-*HEWSNQ;PL#y zrNy~@rwWh53rjM9^z-_{Sn8(P*Qc@Fi;nwm{<$?$&uxkl5PXq9_U?D$S^gTAYP!&W z4;Fi`mDUcsy*3&LD%!^`Yr3I0(BGnebAKD8jumua_dM7(1W7^7$-y!nZa_#I9vh42 zhZR!+tU_LYy+Gvx@m|%Se11AqG$T3rJsc@mdo#Echb?H|w|-ot;e_jg3LrZ-S4BhU zJwgZj;r!KpQl>F~e-O1sftTSY=HaIsf;x>;!874kEf}pBLW9IVY5bl*QQ9auj;9Ki2n z;HUe`x{q z+>5&zf7(dp_8EnIZt77D?HlyvZ%CjVq?R%@cXYpI>tY-3j|WoXmF#i7_k=L=T$)<5TvP zh1w{~(W=N_za*bOfBsd#iA6p$9KNfhruMOMa-x+n=?xf4OWrm9Ft8wSJbe&uo~ux3 zZtLn&R}if}T&sp*$Lk8B$J|fit_Lgb31_ns*3{OJab0Bg4YZd!WJYoE=2zkYZ9HoOX~>xOsV61j#axYoxnSP0ziZ84NPkMrh~Y`zwnuG%SoJXo z3D>Pz*6q;qj=%*W^!=S|TpX?D1-B=IOz6z3*|x|L=V7aeh={CRuDDLi;j+%@(%Rea z-@k{jSX@$~L~`D*@kcvHeFvy8%`6=;4l%G+5IEw027sG~M@d<^0fgcUc1e&h1%PBd ztqUGGM$}v6ojZ-`se`HTV7RBqeJ>eppRjK;iF=<~Ui~GaW2$6))+#)(YS#SjUc;fj zr0cp-dE7teoL8hxiCi{?YPuEwxus&7UvPe6BFgc>#gGSim{-r0FW%t!dyB=nqP}jB z+l zlnM$c4JuM9B`J*vNSB1PfPf&~jRH~l zX9GLU2Ry1^=%spldoN>PY=e^=jRmZ_;M1yClH>QOs}oF0N-{7qD$;AgvCHNfvqTp> z+a)+V-b*Pi4u`!ex{i(xK0f~6y}j4)el$JK_Qu>#)^jG+_Z9^&qT$W5g6;Sk20EB! zuCf_*?QXP!Z?QGue3#DE)wLWfQEK_RXyDULb>NCPC?Bz@TqrKtUy#chK;HSy+qcCI zHpW?_r8S-ABak+eGCdf4mJvQzi5`O+O2xt9DmFI6GH4@h@?}g+0z$%OxCD^=2ym?> z*Ve{2H$M}&IJFTtS!26|j=tQVNr0qdw7F@!Zi&K8A_Cn~Lqh}7s#L?q2?e*6^7;_$ z8l1D~PF$bH+Nd*Pyscr%FGvnAG&5~iKPG=El`z{gH~;_?N-YcbRWP5k8G$`2oy1X}Y2coSW0>I>b4MW6T=8l5IKvZ=<}5>Hd8 ze%KnY(+b%MKlMZSTLCNRKW3}D64fF4<_!bVvWtsnl>}Fp#CoRq78Ils6cp6c*AF?GPAVw)w6I_pvY3&Pkyu#x z8Jgoum&W!U%YMtwz82W>)Y^KRmBV(|nIGB7Kz6|Ei}N!Rz3=>HL8}I_!B5O`YL3tk zc2reW!$Lznhu`kw>KCZ7kOrBxqDV=mcP?AT~OYTrFSG~*pn-`z~!XsP(L**^@2q7|xy z>nFQ1jn3EZmz(O8T;y^k+&TIV%~(SG`(chN!{O%Y5-Zm?)GY#L^x7WUELn9(Uvo#B zbKNBsj;kW*ovc|eey~bsvTg6e=Y{N9M*eRUs5$SVT>*<(J*Tvjs;eein)Y*8SWOJS z?Mi=p)pGci%a>#S8gP0w2tm_W6QgWcbo9kr2sR|s)6Zu^i=kc;LjcXVpRTp)_CkY}N`evI)-iJ9Pzcyz6 z1azd{&N(l6|G84BK%d|pwpI`6M|Sc@trKeE@{5!Rlv-&;Gx+_n>r?7XX2xd2%tpa9 zYE)Vx3u%Ys-$2R4id+oX0CdO93ZQkVYq^ijDQHPh4mQmL{J274q9pW|jy!0u|JEk; zousRgv2nz_-WgX4(FrPh)Z9_>LTDYeahL7+&g>VHvd@mL57uG;B-Flc zk5D}>zFc8;xhIp%4zQ*R69&fB-}W_6@UDkikB{dtTPXF1vW91$eg0LJAZ*0`PDQ+} zSOP_i?j=ENbG<^R+NW#DtK(IA-yeo0*D>skrMvn+bZS2ae3XHQ{KbA^f6KW4N(usa z;hG;&VO$7RN|$$1YllVoznTVx7!K+Y-YMxFljpam74?nafbj}KaQ>znc=b(aK$Y&TVLC8 zG1D-eHqI8$;!5O*uf52-6-AJqgI%-P8%CyKqej+CB|%z}M$Z&06SUN6rh~b`BPwee z=3*yLrlET)9li5Y-?VJxj5P&GUV;ObrNy*Jig1?TQP>z#DXhZZYMkhEmu%L1-$>Uo zHqLMeJEZurc&AI8PO|@0ku+zc+@CtJv-zf{Sc;hgpLz{i&c#+3cluZEOFhOVZ8GHV zPP}>k!=3cf({H^0Z?FAtrD2xXejXczfDPv6`{o$+%eHz2YL*q66G?r!6%`~gF@Q)=so>Xo?2TE zmZ#UG#8^G97P3KlmTgU9lIbBR1j-|x;3t=K^t!8FuY<+e*3R%K)9iHV*W z8T77hZUc@kP|P8y1X`Y%+1cLJkTavVCF%?h9y9_x^yiOS$d`j6==J;h`=9CQC6BaC zTUs9eeT6!Q$f?H=Tm(R+;Q1kSKr;DGJh+j`1zf+(%^4J{=d_*Gl(^#N2v*IOjK1ZB zI0C@enp;|4aZ)ihkN(!l8`3WuZSU@;0}w4S@lJgWe-13@(1pXBNYSSA=6({89C|W* z&v~3DYy9aDW9*<9JI|Suj(274{RA(;Q#=>9>$TIY&A1nAt*C<`O3#tx8uF1!jP#OE zp3Q_%l4;W`kehxc)_zUS{%Nca1|H=vz?d>?wX5tIF}&U(D6z>Xbd7-5q1AVHhd}y3 z(W@p5u^`ebLe|!g0o+kKVb&}U1t<)5`NGhf%JFS^lkV(;@mHUPxEwMnV0(%Kjmx)h z-+JmiJlqebF~Pkn4u4!wP#_Hf5;AIx+SSBRXaR6Uk#WAQ*JZJUpdmJse)`X!KNCN( zHdrm=NrH153hN@&XbDNld$hD-mpK#Ir`0=A&uRxcDn4W3s6eSO1XW2Ira zz=n1Qk|Dk&{}4U&xFoa1iH z{9@2PBTUEAZB^QigwI@Sfb>#*Ui(twe8Wfelp*h#NL>#s6edwy)1Tez*yLD+CWSh6sa$qW~74WOXsiFfgnNB z)rf<{{@oT}H-_N7c7V$PqsePKn{ZxbgycP^)2%iMX=wv!aejT}xSG=Y17OYc+z+Ju z&g@8jPg@Bi5}`BUcAy2t38A-01YEgo7JhAQEW83Z&Xf1%px)8;yjqS50Bz6UYz&uM zQR4|5-hmSV8>+3pO?b1`6<-8BYQ^teo1(fn!~`nA==V2?KkN2}zrHj8Sl5yLvIwrb z`vU_5loE7zyBvJoHN9$TRot{nPQ<@Hz`Z1|qwYuJz%@V0C4V|jM?SGrG=f(@{C2h{ zBx|^C;pz$=p<^@31g8-BMsm6~1_EXz)=$Ze&z*TadZDpQ1KeX%j|b9!xkWv70t%^)u?6|jm&PSJ!Hn*={gb6V!} zv$k#n#k%I^ad-bXj4Z5gLi$%v2bMHYhU_=LjwF02JTs~0F`}dRTsccd>D9F)GIxbK zvuk2v1s7RSZY;*@A5>vk-6j=u=Yw1U8ZNFVxZZ#F^+8hKB}l>$RUlkhT|I)!I2uwx z+w9bHRAk;#0GPWDZkF6R7H z=SmXSHvUn^_L8%X;IEqn{ZVuJfAJd0Zw88GDdpviouS|2UhQ_BW~a^ktr z-MBWnz4AJ-ED@u}XyRqP@qTia+yV{LD0(I$Wf%8W!L%?^i`+8Zzc$@9C6(`!BdDhG zIcKc@yk7l^EZ1Ex3!!BpfVeObJ-vHSksxjq+2cZ_Ob0~63>WBQ!Vh6LOUc#V8#&0~ z4m@Is>I+^tXK?YLN=jwBk^Vq#*(iO6A*-ejN&M%iypT%Y>HeFQ-=t&pSl z0|3zBO1p<}vB<{pWcpKk`V-Jy+Gw24v0ELKkx3I37f07EqdL(zn$671Q71?UujA8OWRL9jIxkL{9>tu1?k$N3WoNTj=e-`i}o6s;|| zz+rO&^+lSNL*dVF`@#g@8y@$8u70*lC2Sn>?!Kn=EjadQJ(l@j7Dh~X&X%3uD;@W2 z$ql(^8U=r(c{3(+*=_?Kd3C9WA)<1|4QZ9JB{%#V1aH_lvLir6X!uI4yaN4r{(IRd zxw{!s%=a+0KYD1=;cj*s+Z~iLFcC%Ya`u6W0ZU?C?pJ;Xi#U1CLx*Hmv?b}WvJZ}Ld~Tfm*KInq|D?9+0{D;|PLTD4iRX)G&W-BjyYXyJO1ryELJ&vX&qUY_$79bn( z6U$1eDE-<)N#wZuCNO7#rOS})s3R&f(1jd2e78~NMl*{HQLBo-*8>$t)kErPSl_UV zCkQX{Rs0^g1!^%)808BB|$l;lKScXpUJ&Y$fQxOUz3QUHPRTpo81Ay-&>76N^~i{guL3g}C0! zWBw7hkx(_P>(}Q2kxRFjtTkpQ-QL+bf<%{ofdtoWY!r0o%A>NFfEd_~PC`xzX1QFR z3&ihfI5feQUQO+}g2JbfK{!Vk*NBCztP0erGhcU*mIpd>ad05eeSzba9z-y;URB!+ z_#Z7mn4~23U7?h|xZMXt>74;8>Ec;^No+?`#S|WUuiKCFdQZMCa~@GvYC90YrCD8t znu>crNE(#b+w*#6-8Rk@Pm69+B;?J-orT6y)69}Iw&O&4Ce5~&{EmhCCewv4d!uE~ zZ97T<@9(qh(V~(|=_8mpc$z(M>kru~8q4988M50lix1P24_E=IOX48zB@H=G7Dm>l z8BJSUo2a5NcH!${-T9575#8UE5F4SzSWDS!+JdV;3_}VchzW1lsa*=uTM7 z$GDN8DQ%B4JJ>4$hjkeOe+_A1Jbz>}8}z`S|z%4&V=|KQ6^(gk4>*zCjHDqT^{$$=eh-0SAZO9_LK}thfKL zw6My|bGY!duQV_)_&eo=_dUG>+bWmsichcF!udtTf7|qs@=nEf9m}Xh>qW!U*)X*0 z?yM9ADp7D~;+AqA?q}aJ%*ztC*uD~kA+BFj#a%L^J^ZIp7q@<4&mF@C<^IX)g~3}P zBlaY=W8L=7Zxy8@DLNXqv{b)7ZLJLQxad=GcJ!JVtp~Lazg3=W`&>mPx~182xkuAz zdTK$re9eq5qncyrCH>)o7WtqU3P_LMlVknAHhJH0o-e)Mv-EMUTd5(rOlzxWE^-yz}5e0AzoD0_5vbKBV=)|I~_&Zw3-EV~p)3PdLtAue5z~CRmMREvP-Z zjRdDdXNvS65Jk2KnWbCwvJ;We%Etrghl=TJg~u%xoV^7UHCv}H9xCz{gpv8c(_6z! z7FkX|MI=cOf;qS%TPF*e63B<;gG5zYCZ;alN6k;@oPQ8+M=__|(vJykN1OYJY@P$zDSfCTyoN>4jMFWQQWw(_3(Ce!0UZXUp|StakfAQLPQSO=htKvUAz|M-%_^-~^&Wz}?*)h%OCAp>v2^+k!wW%MQk}4D9Su-~vKpV}X6rhjgxMWSqaKbLnwT z4mQOV2t#HTW)A;H85XO4_P}c4|050KK2YgqlTpy*jv?)h;a|mx_>UC4uWipLYf1pe zFoe52&u%!Tmn39RlvlE$_s>-A2DirhTP;2*Nt88tBtcy}t2rGLA7`wS*eGfa8W^)O zM$YuJv^R1b_|y0=du9!PfHT+I@7dKBm0gxV!@8~x$B|-reE$n+2VUsKJnwGx-c53u zy(PC`LBpuNcY~(c>k67ov8APpH^#0MYS~w{6(Qon#T2)MS_wA^0R=BH0)B&!4r;M< zvg^Dwce@lwgFgJVJm~#t6ay(=5b(b-zLo?69@~|Eph?(V=-U9A zZy`)h0Q%#1NGd2hJ3B)4p;%yh+ubF;Hc=BZ-x0L~rCzUScxfPOh}ECk(!&t;TN9m6 z{lXG^jYA~JOVZ#!F}pp+#ciPbGM07JvDERX4(llXkn-@F#xuN%@TI#^&RkizZ#Ca_ zyrR3qj-OV!0CD`ItBaP6O^G5wHhmU&>Uj{q{9RcGu~qJ%4m81fU^vm{ z_r75i0R89(PaXG>+0DD=a}jF$>)#5J2`~Q0-v3z9I@??_%X)a_#>D2+O+#dj#M-+0 zeEYfI8Gl5atwLhQW-UsnmH|z|69I;*g?E`YB&D`&SOqG6c$0rS# zEKk(%(uTzf-EX#NVdnWXn->A}Zn66Ns(l)OiZ^?(Nlq{MlTYP_(EY=^+$jLq+~Q>; z4WevG?iQ7hkho71r^!eJJ4+A@RLA%rhXEcLn+p49Wc_CQUXXp+sOUOMUkFoL_!aW; z;1SKkYk%~=BLB3~E*cstG#b9j9g{PW#Fp$lDGN|{zQr!vppWX!$Q6Wd1ysSSJbXX_@`vY*Z8hh${QgODx%Ck*0>H zz?OM;8PEKUPuRL1m{wctnfB8QK+=2nOQ;gj>U;Zz=5whKVqNa}{a5^$NgU^u?+o}Y?^{H8@#ZsG$|vVcAb`KXCQQMwFP%WmvEDOE(Y`|EiUns8`oQ^At;O)7=+0+D?5ts!o`mG7y0S+Rrq2 zV`y7(nPVkBUK+JccHdM!(KrzKOxEHByw|Z6m*n#3m|nYf5Wz(EgzAhes!3Mfnwb>$ zmQwyqUCzc?hq0YA?30Mmd7%1&RGPe=52wI4Y z%76Izr`7;PkTPShjG?2H<(E^BAWZAIGgchH@R zEK;gjFTyTt-5qV(jrnrDwvLFK1m)fFVXM>5s{G z7CWr@|CcUBY2sqSc4eB%VR!C%T<^1O<+6;te|N)q#{atd#FH^Yl8gt$4Qh7C(YD&X zZ8t+0xW}qSS>HxJfVb4osB1>!#(tbK$+`5AcJDGr&V*;5AB7bA<@@m;SA(;>Q_^c)E8v{@*mA|czwz3 zmx;%}I$;(5Pj}(B<5wWU!VtDmKOrw})~k)I;P;{$+gq?jx4DntL@Vk(e6 z8csrt{@#*(u*kHR55&2_Gvia*(S(C8SP{HjN%S`cUDRSE@@_N5+=^=_Lgh3(gKZR+ zpCAu2sa;Uyzgl3temME+KUlQr;LPX6#yOgo4hmEyut{jO|F+QUf7o(gFDEy#w)lqU z2lS1L_-oLBkp^MJwYxdT04{_I_$}7DNW=oF_?HjHv!biL4@e|s&M8f<7GbYG>7ibD zTl!m5<9d19H+m-5reqWlXRY{ND`C;Rn%AEXSnVb*`9kANEOYp{*aLM$7A(!z? zvv(9#isw5AYwoKI#XS60DXo1;N?i4EYB+v!VvD9Ks<$$W)j@^kT~k15q=fGOCak}2 zF!{sBB!l%RgW9ueJSo`4JUnSK+vQ_We1^MMSq?FEad3A0kR$x`^b;%uQ1ZA#zEJBu zui0|{2VwK8dnp86xo?})JswiFvYsi@mV0?z05iP=K5qp7h11QNVLZ=oR$MN-*Ed~~ z)cMGQJ~S7bT5*iZTMmgxR__|$OY7k9P`=n$pNdp|v3}m0B9qeBt3M*LVwy7{^s~g_ ze;A;z{a=8fsx1y>A~07TRbSc_tJK_4{ns6w3fb6dd{s%Od$oHx98!y6k8-eQVV4@y z!0b8Uz!#uG_rLG_TC#sG1d&Q5rt|E4keg#kuYCaLz|V2P8-q6a>Ov<5#j-20*|13C z1LeHAz`5KRj~x$H$usP*pqcZq}bw z)AqBsHyMV;fjFF{5D+0;*xz4?f8CUA#r|^VIlvqHTvFr%ga%558&bv2=x`vA z_XtmweYc$&x%>>~qC!9EG_Dcp%vyHgK02`nV*;SdGZWwKuLWV)s1-Y89p2KkC*zb- z9^G-fZ9N>5`Rnwi>HOV~Xu{rmq#q|-cZp9vc!>fS%to3M+!OBw)#B2W<-R>T55*qM z(P0~HuciyJiwK2+7nAVjDyGo*xh4R*Q0u(+iM?49y__d!-*BsW14bbef!Q1F`WHJG zf$RQGi2S`Ck_7)cM!({DV#{&yC75!k?1axZAhT=Of5!I4m(Zs`yZ`ULfGD)*N>0~~ zMq1PGXy#}_U;}d~s1`H3U+SnYopYrN$uv+(ziaS5sJW5Tuw>EzRwTFE&vs=t7m8HiNs>9fU~P=}R?cWz3pfY$*PT)XsYt<#@8_MzE+s|H6pq5# zW|dGK^V6}t7g;@ST;dGU9KzgFW-IEvW8}?;o?Wm0 za+W1X&7I236NYy(wjn+0E;CIt7bny|zS^V1qoY?W#MM=?%0Mgv6}eL0Z4ds0!{cK;_RUO3TLnNa*dt}sS7UxS)qkktUJy4!z z1&@-g7y)M4X~>^x4_c%j2$-4a8RW2~6uedMCIhOuw}&783Wz8W63N`c6#j=bhD$iW z8OIh<8n_EUBRB1E-));`lhvgo? zG=FTGz5}KmIf0|*lWm<})0X+V4VQ2!c;+aMl_9lxz$$^s$RryD1Ri)N`m2tJGz#>t zApDxcPM)HcRwtl`{X@*Phxf*-s>-5bKe9dXSj4Z%qk?Os_w@|Lw+TxsxIG&P2^Yp? zPT$ddj23FI%=>e4{t%ktNYBGAXme0d4Z)}O-R&%Srhsz)m}}qx!SJ@KM(3;8PEKe{ zs7;q`3>e*lVFw1ERGc^AV)mOnVd@_5NRRJ7i~ z2H)$VcdkU|1>fNJ6q}?0sEswz55`(8ol zHli2)Nae9lbe}&=KaSsp^X%l{!2GY$kd`UUP4Fzq-w zJpt2>T8_BK654@%MdZbUpIhJS%RyHKeg;thJRPt+K|y70ZJm*sxrLi4Ya0^D3KSsd z6GMhu9g+)f|L0JWuIiX?1c#6<4^UPO=4CF;8i-*Aw9|N&I(^m&fPnz;s^OsgGDijC zm!)7Xfw)Ttx5h+O$?xBafKFv*XYU%T5{j;CynHDELy+3kG}gsCF*~P0DObGU7MS*5`DxC3_wul5-osCEv$ zpWT2i9$I{HeSVa%1b@blKUiRBBSP+;B&CywsOt-;(|fb4rMNI*UB&OJ-E8UB2Y4V1 z+A;qpaOKvAcE3vk*Vn5K<^+IA={NB7ASgj}oH8=vauGnwBDNe*vVv@13OIfQSVO3K zU4WNRfSS6z^*31uA_kmiA9{M^5fBeM4}5F@JN<)$4M7TP;tF~Agtu-% z@dmvBI-<@6jo$_u8jQFi1@X$aw6xzKnFeZlKv}ZR_8j1U|Bw(m4vq+5P6)`zIv|NZ zr?p!yJ)i1%ti!H=A*>!E8%BZc=bKVU)yRj{9@`%Un0klRNVWl!(+5ObwWx1T^jQF# zqD@<_Dd`M4@i+F&&YxFeDVE$k&Lrc!VpI$Cr^&aYE_~AhMAp=}eYFC|E?P%j;z2(> z1v1!*xi|ZdT;8p?@%oeUk$M94gghwDf)BSomunIE+piDsl6sAo+4r3R%lHI(y~0Ts zf4^EH{2N2V{27x%Ey0~HURQ>x{%Z*8utj6bkl7HZpP+@T7BPz0TOE4nxeW~HLn^o3 zPi+Y>QxFK`7V|RrDU1?RRUi~a6bIoz?ac#a3OA4f2n)hN_c;&FwHKSb20w1hzrV^P z4?d?`Ftg7UQ~&`mQvvbIv_MWe@K89328MwVyD~@mAKr_qq9b2C$&Xqh5nhfzA#O9vUZ`4xHlyWc(q#2N>#;w6y0u z50aNRHrX(JPf}h!^s(K_i`3j)S(x0QXxJ5-38Z&wVxo`&;lW~F-*PyNrFn>qxhORs z|6Z$ON*gBO1ZwzOq6*=?DdG=FgTz1ts~QfIR$hZRM)LV{KOSIeHk45`{QO#Q7&0?5 zptlkMu zrVsdckl|G-V8lm6Kmbl^M#ggzprSv2{ra6gAQ^Jy9|D`909u#u%1R#O*vawlg~RQa z1-}Kch89c?`ibP(muoVm!oZejh>rn>bvXD_boe|#1@&`nxCl7~f8KJ=15>U74ix0u z*c_OYmNF$E-N}33ov!3$Cp>}Z*9&)T7NyMbghdJgsR}|D{W!qFtI-4CZ59ouaj%lH=jDdt^7_MCnpAV{G!*Tz~=BG$pxQbE30NS*iTs zi_!Sr0$*ypUVGtuEY?PNc@uNpo`jZt;-ZFYKQLg`=B3ixX9!t*n~ z+h83_w=wFTTo_rmzs;oi0}*im*@FU0#x#%#(=gU!9uXm*?5`t|G#F`@_3*|2;p@6U zobr_5l(#(PWn>G}rlnBKOrq8jW_hmEEBfrk?e~6H6g;vYRR(0OsoN9Ty&9sIRJw%o z0|)1MSm<+RJ!1*1W&gWAp%Tn}?jF}F3~1vDA36$jhqe8BvKU`svk~#D+NR6p3y7gW zf`$?oZ!>hT1j!982jQ@H(-ex89gVl&@yU<3{g4Yd!Mgi(b?Oggo{KvxELM*YA*1dUXryrSZJ zO(xp6IAy#fl4i3PLo4mdX5Czdd71iWzG^lW<9s>Ql&Lu3G8fm4gPxk5m8IrrdR6u8 zWDczbj>_0yU7KUTdVdG2ab5Ish&KegxExr6J!6=N3k(y&;5h_Qlp(ZEicbH@0KwiQ z(GUzPIGU&z*KkEe1=!prLo{|^w(DPzk?epZ1*RZA{ZGa)=2m8xDW<5155=Cd8!SE! z&+9~1-TKM6EfYIuYu!#HrOMXgp4eajzU+5%&@5>+A~F(IBzpe+y*)G4DJ)~cY#V#~ zNbBn`*TEZ#$qtx3k(VGKA!&z+FJKh;-pRTb8yo95_euN^e(}U=<}wkJ<`j^Pu<#7e zJ%bJyn`}Ol+*|Ha8Q=A$bKEB74lk6EvvUkam@Nd_*%zU0P@8+S^OVVh)~ z4+=fTK7$ex(UBqJd4X|lf@w#MFpx0iYu3tFSQwxj^^f)+{y-&Syg_j#S23 zE*QWAgOVB%`x~?gV14C68iaJYgx0pUuWX_>E(`zrnl2N9%R@sJ%mskm<*1ml&CY}Q z1;nB=OH0oWHU_mUU>P?vjLOz1la>5F{$eUU3C8w98EgXgf`353XBgNpdz~Sp7Z&_T zMh!77tvEvV?+JUC%vMvhpFVvrBR>z^hN9)Kb4{@3bb)NM{Nnt??9wxspu$vJTYFu7 zLXA!~7AZ*8P|e}|`a-L|4OGxJ%o$WvQ}YA=Y-fc#EHAPAE|Fkr1S1h@Rn`pVC0FBWi~<6b<)p5Kg0&@E59#TrVCCh4E8;awN`e*97Ybxwjt1Av z%*NEcGiS1T$j??rV;$jY{Y;F6v6=%DUG zMpKg z)WS-hFnBePb`3;*$iXA0pa7lo0>}?Rw>#SJV?jx8!?H%tAaw=c4I6W zn&H7b9Xz!tRTyJ+3mnbh6f-IL3OC?3!l{m!4jQBa;bjDK?m(ov1#X;*R|hCZXXkC` zj1emyA0MBkg99BWXC!#MLZDv)=Q9>AE>gbUPE?bC=K~sb5?=eaRmT}zFw=`x`U|Mb zUqO=!8{lw63Ki7N0Xt@xIKBV@{6Ua%y z6Bif%aE+u9?rF0XFeeGg%ijQFlB0_Y8|baH9jC9rn@wFb-aLH6PKp!&xD+jIY(!Fe zSv<~NkuVMC{k1ncr~kVwmGMTW@|%i#Yy8x(sA++93{eAz9T}Tr!r;oexjArB(RI2O zsDh_OLIPV@Sors~aOc~BKA>xdR{ri4!8K(S6_5;jg@nizb-!XKZ3q2tM@LpWXU<;I ziw7?O900-UT{=2nP*=b4&3EpMGZhoVfK_yAYRXWjDF~*jOF@N`OjT459t?#vl!gXj z(oNVULZ518FJQ`?((4C5g{SO&%nmAib8{v@aX<;o_2gtly|w!-=ME66^2*AhYHDgl z718dD@R5-$mYz~qg~m?R_!!w0t`4*%_BWhN6pd@@r=@cgWByNb8XW4MpL}0c{2Kp! ztAfCrpJlvO(%3h~&P`n}gPz)M2d9#c2h+!^wf4AD^RV0K5RWow$7AcF>g&v<00Ozh zRer(}joG>bIFMy2S0^8(-{YdF6aI9FM`EVKI7WNUo4|f$n%2t7>Wv-Ar@TCiA}3FS z$0QRI6Z^Q<{zR-!jjae_OS{|C9UgrsV$D8 z*YYjyA*)px`%ON4q=ZjbYRaCIL_ZZ4HRtJi_o_cat5yDG@MNNkyh&WS?J<_!tyE8r zo)r7C>z9WjRv83b$VFb01Pi=#+#~jsR=Bv`@>Jp{$ph=Y&@A%5YlBodWrC>JFBx8( zen#{B*?wiwGxTAbT67Rb06wmwlA?Et+?`5okx;GZXvZhZ_toPBZ#j{?(5dvZ5u%SD zKSArHTgr3T`hf>eF0?f~OKkdJYw0)UVtv-TrIi_1Cc3!h7aCqRy7ci{C-0>PSGdvo zBMB8^9WMp8d%G-7a35hxoDFu29o-^j);YzP(AOFGcADbS>v$|5>4p}g?08~3%wCl$tizM77f(ML2pn2AZVC^wDY zj~&uglR2Q1%)LdIStBKHH20gsH!_!(-J@IWmmw47Fm;L2lgdQ-QH-<)%!XF*(H>V^ z%8U2vSvf_mKB9M9A&KSnR&w1Zew>QGIU!Mxy}*yML&xsA8bPiHZrdKFGf zBV*py2(Ivr^Hm%i97jkTS_`})e8U|3xVR`hEnZ}OL3E)jFEp#ae}!2g-0}v>r}bt; z3R}d{@Qb-`Bjl!>{htcA^bI6w%wOGH>g)PMQT6gWGoO=ZW7t;tWrv1_0k5kUM<2g_ zzK0^jHF*)-1qYZxmhUbFx@XJN6|RRF6`Fn;#tuJ=lq4o^Q!B43b%$1%@~b`KKJpE9 za3qQfBOtZyscuX-2s>-?kat;3!84>o2714E-8=cfuAblG!Z z!UTRXCt1>-?L9R5CkaBW2dnfKG!#KqxD{R_wGz~=D>zJ)BR-0=&tJRa9*Mixw+nvB z9@o+5Bn@Q<&mfOe$S5I<^=s05JVHMC+siS;T2yA8`32l-^^cLF;l}>o0|C$=8^AKfOL3c zoFnI5A~(Ea7M!DOvESc0&8zre+rs$hy$-Hxh(kh>+9N~IS6rIvP37{mvkx2|`^$1I z;`NsmliodYZ^c#bFb{Et3^aM=a9c|ll+b!^*aF6rBh1-3D(RPokCm@f{ANX^ zlC*y@$-<^&yMij~*@)HJ*B)%6w?CCJci^lRIT=7%P2PguHRE*f=Hjjb@ zC{Xkr(n*h*2})w%w_DzAW1?CQ2s;bTud)wQ+X!l=l@Gdr9^ zrR-Ce_`-B6pxjHxee6R)B|avRL-omo|FFFHL<7aXZ>i(BMx~L#;|g1u7#s|3zHRh( zO`BobMJ;-?7k>mAsXkuH-syVZCM!%EHan3?m!5nfttHBU%T(G?02lh@=`yj)A^$qd za#qspLld{HsE83Q-^s-1p9dL*SLb~-jJc|vHMQ{P1s&O6y42Ec1s+%}|H1C|JI~-J zU1Tm&Rf=W4Vu>=qxe_dZ_JWA$c?0!Julq+hm>g-9>dRK9a{*b{yYnU-v|f8^5k*&9 z{M*`x%Sa5YrAr3rIRb{*HKHBwKOH)S0dd>$ghF>r6V61j|v-~Dj9Uo3IPxl9|@o;Ide0393PvBeCS zkOh;L{fmdDmIE*x7?nLtB(>}8RHCr!F_GmM4oNdn(k1~{Q5iovzNzSp z(P!=l8D`Ln=2{EozIeqN4VQfD?+>w0P#dpq62|d(!!e&uOiC*cEu^)+p~d48zP)yJ zzojf9GS|iQKw4_7$ypP7;bs1pPUOKF#vN6qIRAPiLrQG3aM+pxvU&(u&Efc_J6#0T z6Kij9TpWt^12%ytBR2uJWr=JowxZWh_J@^%fb)!M4ZHBO?e# zJAy?59N>Vsag4;*a)8Q;oX;^7=56A5LKYM;2RlDIn z%XGTP_I=wXUlY4Wo5zN5D1XB{*n_+*-yBx(t_tScDb}_PYD%JQ3V4!j7@`8wgB#Zg zX~-L2s0OAupyEL=VY&5}5=ZXbuSM_r<=6ms^a^#6ymak0SZWe`@xqSR9}wb_{t`n^ znx(2*E|Rw8$5i<09?bS|Qj|7omi$J*^iNsCoGr4)U&qQfxety6<+(G2bMF}ZqTcVM z=dmNsNoQsfj$6;lm5>@*G-T+m6*?Z|==UAydgOsg(lg(?*t>G7UcJFM&UQQOQ(wnz zG+oZK79{aO>f5ZItld&%RFb*%*ayGjXG86G<#nxG`>h|8 z0o{~k3}Fm}yI+n1WL`>r9EhMN@BcAU@KBvUaM++T;+tJ*-lclI$9Kazga;jC&trZT zD*l-0JG8L)(@an9c4;jz4^CT6iAx%dp$NqfgC7y9HmW7fFI1&|e{J=Ua>ER6gcEe4 z2b;gi@c+BN9=Qk>JM0VquA}}PIwvwwdj{e@5E~Til_(VdF2PnGU}u0)s7rEkb7>zw zyb3rUcpiRY_)A{E!0WqF8mbC|%t36?(nGswe+(Wc$g#pN2uPlZiW1k=z0=h-hwwTZA#dQ!$yVL^sjKzxnqT97lgl*+b-k7#wp`Psf9N`A0OI?ZajpPj57`2V116t3 z<~j3jX0y2x;)sULU+*q(e?%5J5K{Cs$#{of1$IU%DoB_}d1d8DKZn7jc+-yQ#zdA8 z3o(S?HMO+()YoVEYh0NwlctU0B71~piko6O5MO`O^CHw`i^@9B&8kWbopeZyR<)S> z_G6#M+9i)hj`FMg2_|P(lUIA8m0FK~Bcarg5eb(7*I5ZtI2-e#k(Fc^F2^TM+uy?R zmLNclT+lrha(GxE(9V9XymG)Cw!v_pz)eBr)leV%#0K`^={j}pAW6MKMMVW<^rI37 zYim6qg~+)rg>Y<^pE+O0~7Mw*Cg(7~tCHi0u?`0l<};$ENl`FF zzu*L8o?&(8Z93M0l81(dhH!)KXUE`*+7#;;L)Zr3^*SMMEHgLPaI)6T^>{fQ zhLV2;#WGTvk%&J@DYC^zZjW<50$OQZuu?z)kd%^&=C-;Akn0SPE{atUF8Rxl4UC8e zuV2IR-9>f&*B68TrO{Qhk>d6RBVe5r-86E$0VSqqWJF@`AXf}|Z2rmvWG-WxM9av^(uc?v#1~IM&;;uAb^uFF!#rI( zzj7cEije5`{51-o`)gDJnw62dHB_%3lfdPN0%Uv}z@ookDUvWtoOgL7AP^6MF_072 z1n5#X%s&JK3y;ndpN zFLXRU%klO~q>cXfWquo)&XGrV?sx)eDkU|9T)J2MR?wvY>GZVQ7d?9v4yCUUeCSA) zo@aVG9k@KqtxJ70nZ&aOE=?^h{V~Q?(LfUD6jH>dmzI9OM}){X7T`H5?w&z>E zgI7k#ZAe%v1Sovv<)hn(T^d~YEpV+n&G^$nGxz%=9TY0?)LEtZ34+rY z=;;%IF#rZ;gq+uGggvIM6DlmiWhiRj%?}oV0s~-lA>i##F&aEW_-8EyTKV^N`qgjhQx8*$cnBhx z0N~APYep2Nvp*aN0*4kHm>Uqo^z4~;IF=){0$`mFM6Ah3W*HDSz_ouJdy>N-nTiir z>#lQ++b!MeW93yi+0q$socBFJ(N)j6?)rM;a zERF_HYhndG;z3CPmn;&R1e6sL9Kbc{+IOCRdjNARS6s>s8V4kQ0wR_SbwnW}b}jJo zG*=5?dWx%l(i5i_B4vS*_BX014O7tER$hKoooCCHF&-qRmTEs81VTBFaFaT zn*eEpdTc|R+*KJpp{7f9d?JNXO-)Cau0>THvr?A>&KIP{!bNBV$^uS7;Ad%p(gf2K zB{MTKD1Eryj*C0D5TO|&mFd}bLed^WLv_Q9hjm&0La7}6HCS;IE<4c3T*>BL;$V0D zt6O_GbG3fI1Rg36QZ-;qzdiPZhOxwX1OC4Sob}hqIP+nN0!C`U1+sb(-V88Y$V&mX zLjtbvqoKNUQSiMTOnTIv-4*K4pHvz8Ee;2tftlF|@*IE5L015GteLd~ukazG#JM#C zN7U8zKntnif*1w?hq2nj$~mgZwu*s^I~PmZ4|Z(cu9)ma{TMmppb(e+){$bvqN4iQ z!8l5W>|dSsj{J8`LPj%U-34p>@GqWAtA+P-R62liG$P>J{`>dN!-rCmX%wJ*fhbDU zYU$EGIYrLsHc)X=PrTz@HlDbjZiyo`7}OI;?gP}xF^`Kg=pEUsiZdBx_9j(8l<=i< zfz~J(`W`f}z#>FJJt@6c~DDZ+JRBc#vw12Ph95~OBWsS2U@@uj@J+hWSHdkY3XO2ScJr^hf2G9fmf%&{D zVW2yh3}gtzAtusFv=^3u%?_brkVg;6A>L z&w7Tp7Q)bxgC6ME502UF6u>R4}QM8-|Q5itQ{Y%Z=*a(h^Asa2TFamZC zQUIIM*7r<0_Kr?>x~(iN@4(&(ZVbRbkTn{K2S+I=C_r0=JUevHlO7lRkE1^VV_2-t z$Xv6FkMu~8p%fWk_5_OS9BfgfV>okKXmnAqNe7Chx6DEZx)8K-=x~8<53+x0y5zj^ z&Uxr}8yMza!rg(Gal8H>_TD@%KtSn61%XXBNGd7aT_y-f>`h5` zmvn>5jj%~+Y3Xh@NT0d5-}>I?`NlYZoB1z@;yg4P=L^(nFlA0KIjNh<5 zP$!u=ykWPCP$Pwx0(`gwYss62YtUWAqIg$`Qe(#c3i$ryom8VNtXb4J_OPoULYDl8 zyaVS$M_$@DQ7z~2l&5EdZ&XFX64K&xOnSidVVE+PUyHFs7S>UcvY7&J)#TibkA3`) z7t-UT^ByOvp0S7@pCcJQ_n~s0%*uhtRasVTqde>;y2S3xk0{1gv3J^1|HP~`>;sux z((9I&t!i+$;HK4s8N!I|pmwjW`Ncz+>iIz|83ESYy#dga43#i|WS=%$3Q)lTG(#K# zw+?qSVLE3U&Wjz2cu>0mcv*&4S7c@RRaRCS>H0M2-2+o0Kza#@CQjxsQ~y$(c<_V* z?tr{!a`P87HbTWE!EXC?uoi~pK!anCsl&UzHYphy0O2e!j;OSD={_jQVc)EcQhAw{g)P_daL5L!I=-V@zpmDENc0`x{~tdl>) z=x$pznsfZL3FW+?t!}(NixE^=^4?w{e{tM5@q4TF`7{K@#+QN3~ALHdw1sE>nEi9e7s@AFyb; zZ0wSMG;IiWZF{?vRg5K~?9TA3?3ukfVyIE039j<;@eQ8UT*4X@ItC1tm@eWjUU+pt z;8K&Oqc63*Jdbll#^mFA)heL2w>15I!Ln7*I@cpZnUNtP^zN{%vMfvK8|sA8EjHln zyUH3QZkT-PRk>eMdT~=T8COWac*^Kkj$C!{#!iI>pqZAzh+oNBz8&4p?v7urrbYx0G@@3CUg$ z$omW!Jk2aPzi)WygG^qkS!a8MtG2Ri-YbWr_anmO25bw>k|3%E^A}r)Wt>!EPlrZd zg6=eI061+15DP5m?kcB6DcQ46$~iO0w5>OmA1i!61>X$<$5!TS1`|_(NxHp#T3X6s zRjvzk&zZPhH;ly2xn3>Kw+z=*cY<)`*I<7Bcf{dPDukBrRG=-q$;`X;`uqDcuqYGc zH6xreM;w%ircTSN=?t!DPbden^psjlBeBnCXZQ=T6wtGo66Xd z#pjd^2>)H6lnTzaPjt|X^X#IJwY7uz&p zJty2S-kDk!O26QW+<*f$l)jHB6XeYlcrq>$AD4Tu|MN|ZeBTe073eB`H-{@Pgnqc+ zKU)_1u!_0Wo9}^95y!j6xPez+m6ZaTu?))a`|4K9&7$NIx67m6QFtl`6RU$3ce zN;CAxOhuh6{U@&)0=$f=E*w*X3j=0VXlZFJW#>HyU570)r-8iFlUX)iDB#uG6gqst!IEafAR1YDW;K54=)`g(g6w6z0Z=#Ym>bYzN|YPI*9HOrP7m;nN;*20V}E;hzA_KxD6b9j25*sstZZ6kCCL{GwNp-hI_KiYHnmdwS^!1RGy!Kd(?SZyu#{VmpN83r+hFIyj_hvELQ>mSfp`B}`JRP= z0XyTM`QR3yrc+2;2Y3*n`X~hcDf%}WvLh3dKah}LEA6w7N;pzW3V=24a!E~3S5i=T zsRRQV#Z67K+SH?gU;gY(5`H`{=amG^D;Ey3FH+rCR?d{=u&}byGcaUg*Uv2eNry^X zpB4{2w~7wb`%S@N$WcnHPNId2cWHY6v2v&i~4L-sL5PZwu|cd9k9`e zH?Tf{=Yg{-?^I+5hbvHJ?}4g@o+I!;`2*9y@YjVeHj`q=6z9%le5kAuCX~Px^l??k z^*M^IdEf1ZWyIFB*OwO2Lc-Wm@R=09#w(z!EH^Q)b+2q%tmt#w9mW<=V5D4R85u~0 zO}6y8N{>>dwIkz_-k-S{cYy9`V|qyHMf&6<%>B{5{*8J(945`he}TblaAuLc4t5)b zkDf?NfAT2eLQGzO&u0MJCzY0lFAtR!0oSo_#09+|P&NZ$0X5$sC!gVun=qVX z4XonePz1W@Ds&wovewCfNAtmAUpRBHxeRiVfXzZ0OB5;TLVRH_0K1JTpqnI-k#|Tx z05}Qt0dXGyV#Fikv;PPLjYQ)qpikLgZZ|Sr4CdRp*2IDB3=YF$kP~i#y#Gncioh_; z{~J*ZtpgX~vH&G@A7?ZE{ahf0Aky)WTIdSK=F$owfF#rKZ3|5h!WWoMWTz8gfMWz) zkjc`>m>slWs%?hMCiMA3Z{YL2z*E-i7a0(NH4_Ieq%Vdj9TiODgyTidm1^ zGMO2uOqPY0{qy|`DlZik1ST}0xP&bR4BI>DUw^?j`ipP;;y&X^tg*ZfZM@Va+GvKDyhizhjCxjgnnnCJJ z6$0C=2uLviJ3lI`S^*P>w3l_^V9SRos2M{R2+p5@w|D>pcfr1V<|k}oh3u{Xtn)Jv z;DP7>-eV2cZ?bCk#mkrV!E>)j3Auo$WKR$3@FZ1TY0CpufamWMHx@Ac8!^g&-lr$f zf<0kFES%X){dS;f7kd36jF6@LrdL_%&U5@n=n9dVaSgbWWF0!6%@<^*`T6@eh1Bej zg65gB(Sj9LvK{B(-7l5L*ham*VKeo^szF`*;^XJ4mk>-3**MF8BV`g#Qc*U<>D6tJ zL!Vv52hzbGUO7~3f`WPqTtsr)gwgk90fEf%uJ%&wWvG6c)~qF1_oa! z5WsDEH;f@n64_b|2IJx(cpvHjur7o22fHt6hZF^V9n^)LoGhAG$|tYR?|>N`vbB1R zE2oI}6|^S^5Kk>En4t#_=n?2lc$4%^R+?ZR!tReuWL3=R6gpaoCiW%R+CIxGZl|h% zGgTpMSx@`$N(I;;ybvbrs?~PT_eBK9^MLNOat!vYS@g zhY+RiY0&{*yNwcu=Miq{I?6M~AqDl0Tt)yJVh-M+nZmUGxDx*`HT#*8YIpj}3*^-% zV;+H-rRPhkWTQ@{^zH(O0rdVj&<5b;l+4Ag%8OjWw}>_(C{b}-;tn;8YZR=eXRCO- zNhdU(g zI(Cgc^o5Sr*1_%RnX?uvf4rky1Agu;zAp`M@VI+9N|>@};6Xq=H0!{s!AFMHfp|;< zJTv(EcO1plv3c(M!}9g(Ih5%j?sP&d$*k6S{P=OU2b9|S&!xq_Q+y6obmMFaYOwH5X&;D-gA3eJ|q9=`FZG4w`Eadue2K5~-ZHb?X}|er+QdA0FH);xNNvh3|lkx0x*@ld&lb>@-`;uam9tZMQAH z(PrGxh^>?Hkh%n$e7HFi9-JRJ^ZG}31aJXsD^B!yYQn0U$b})Ib>lqmE&=mWlHr#O|Ini|B zBnGFJNMhdvNmp14mOhiExt{l-vgue%)^~xoRP@jDy;Ue>iTqULByvEjo%8QE_$iG*7QbS%PEck9%Y(A2Mg%>cvYOh^ zl4BpV(_SUx`3hsSQwo8*lc*cJ0KES+xInlJbv=9SP&Px03}@7Qw+>WT5w@prU`BWi`?^5IXS^9BW3s5;@Bi`RT@Zwz*N@>b4BY+$ z%yOiFOJR>CG9~YMkvEh+unC9y>C>lED!oC@qMf$Oa$4wNnBM`~2?l_|fJIOhC8xo0 zMF;I2;NXWRHGqh0-k$jq$vx_f^tXq;UX#~!C05dAo*&Z7LEp&PwOlaH2lDR^fgg>@ z$n|0!&+-qB_1Qklt&QPLd99YG!9V;nJDXbA2U)+mqARu9Tjc(~ETlen$UbP4vCNd6#mEqR~m8T=M0t*VOWw6Dk-ipalaa%I^ zQM*}RT=)bq8mI-lEWeEm#^w;Cgh+z(p(KkNRwwmJ6n%K^#j;Q!-fZW7-jk-g0a+O7 z4}^ZOZ?(iP+Psi*5d3WMm|4+}nDm`^^!iY zk;tA}P-g;S`T;wpfp%ks<197KIRy>;Fuv>}C_t&e8ba?U$kyV3`-+U(FoQDDTmjG? z0*d?45{B~&-3?@WN^lI+8?f2HD0*aKGYSWT>yQ!HFx0t7zws(~4WMBL(UsxTdQ3Ti zj)n~tA3-YyFqPQ0Hba=pN)XpTLK6*}^;A@pvJ(Pb^Jwbo)w>~`z&hE-@GJ3ZI&D!qE+)4bxq1_Iu6$3PKHAeqUuhEpkb z!|({zor1b?B+~tvcJpk8SFh$#5Cob>LXe^|YNdB>y*VXGJKOK|e!ZCuRUs+kQ$;Vi zqX$!}lYs^u#QmcS3Z7J`AgURH>kX!m}uGH3OZlnVSdR!1$3E5lWH*^E( z!3hSL`4T=pzSyTbh_l8`q%33%n#UneBYPwvJKOQEl)nSDqHK?3h`sMctYHc4#NfC* z_@Szb-_p_&kxH30OMgwNZ@>;daLgIXS-1A11zgyW`TQ=hz2whV9G@tKYdf!(f%X?K zPU(TP{y^qIWCpNi!MIF{*U)=iYCiBC7LARA1A-L6A2PUwCaFUnbbcM=jTMuf**5(`7()Op`>En@#gLHg8Wb~=$~&6GG4QE`4{d#Jo$gM10{%6`47O*K=9lpb{KZ{>@e%p~aONIl>K%|>GE);o}A-evQ{R?*r) zZ=CIyrS`V(01XUk@gvd&i0v1uy!e03lXlf;nl-e-&Cgg0qtR&yMj& z0?R7zyde(t@U0@^il=Y1aufTN@}*|AZH3+}{c6jI(E<^t%caXaGmjRKh7IpJ{nS-c zhz;NL(~}%GQ?k}>chzdk`7tjL=I1S50a8H(b3z2v`g9@PtJ~VKH;mbuq$-5KqQUsO{{RDt>vDTJYXol5YMO6 zbDyA+JbR^x;BWd|&9{Bs5y9(01EJjMAWs6wnP;0`V2L6iisfr5RU2&1czE;mMfa?J*ax>m;pOa6{+S<_ zL(U&x8YZ1s{sSziIRpC_AA|8!o%MvE&5hoamHNvP_>0rgx#Rf}u&a!C5CttY^}B-u zcZBn43@jTf##PwOUMC`Y2JX)nBSbRECP!!RhW`}Y`iG{4|FzUc%1Sn11eg3RKY|_% z2?abFOn^SOR*#RDMqHe=rag9!JC>3=Yo)@?v4z!Ezg|Dmd?(*L)mJ1Tqw;!Awrbr#W!a!_>0Kg!Y3;teyF2f{d!sjW2o6DG$W+}{%&_rH!tO%tYLS3oOy|IY86G^oe( z;uPNN%Zdg+y_RmRU~!?g*=eIa`gnM+H%~QC>zO>_jjnz#lY>2?l^V`febhe8uj1|dn zRf(kftKLt~k;L@WIaQfo^${D?3{&e)n6s|aOFpHNTi#yT>-t-w=)7js)YhJIr8OuK zANo9t=7%@lZWwczz8I6`9kvW()?sjZV&ht56X~5e8XFB;V_?csw5I*lWSz6!7+gqq z1_?*9h8Osj57vcK(wPN^xJ^@PR0t@m=mpQ=;XO?K@`4KwFPNqz*X`-IJZi?6lE>@T z^7~$gHzK|7p-A}3#qr}kv}&{FH*Q8`??%R(6>kR9n0zse@Q#X}VtAl3R7r2(~>HA|^wE(S#8T3lY3&9Wa) z#iVScMljV`1}0J0V@$I2C+(tk(H$ADw)IqWTyr-}jkCPQu9^+`_IS?eGsYDuv*#VB z47)rd5m>Wy4GB5x#>X*eBf)O9o8w1v+vEq%sYyvW?a!;bHS;D++V+_X!W)rW4`K0z z))#Za!b3&b)RUWzt-0}*3gjOU7pau~VdD*y*}Syl)S~uWzoacUDsOZ-|9KECsx-vw z(-j=kwSWwVw( zcB-O{mMId(%`zxe!$&-eRYHICo??k{Zlg};#^EF}*8-YmY_UfAzu|j)&HP%8`4`Xu24_}-H^^D+hQ0_|ujmrwR+qHr#Lu|_3cbju_R8|86 zY|900%WFu?EfwvZ@79=zeXEs4!H8O8>CXG6ArT=ryky{v#w??R~{3yh9?(>rCe|iBtXJ&2pY>7w-GR(1(E>es% zsP4Rjk5_YbbJKjh?sjv8sj(}CMQDYTMy&UaxtAe-&?fZIWxL|ilBLXJXX#q>>0q@s zF)x>uk&7*5!%z*Yroe<+7(S?WEv;efmcCW&D73ay=vJ+9(6HJxzHK_g9N(LWlf$lT zG<|%=c{n(vv_i3?Lr}tDvi6lFjP-eDD6bn_7NsjlXt|4Gj4YF;-DFV|;9&Hjr#Cc> zte;e=Z(KoN^Oxj`UTVLg^pnK$P-$`2(Cd&DR;PbnvEIr7Rol^2gyG*wYy=`#gZi5t zEM0Vtw5>FPXt6Wauf}iJz7&k}T(+>?+c31_Gjxji)0?`tL6{ByX$Eyq_j0}ZHhV0) z{xd_1*9EgI`X+rh5}#;$=aWgSd3-HPS6AJi^w38AUY$*wUM&az`(zLtGXp2C;o;q> z4|jNER@D+q5mmfinya(>QYF7t3y;sz{M)?pFLTEV_ucuIoTEn#TR%+-0vL?ol1QuM zxSYkqYu60Bt;?SIp#pwoy}dTe2LFs^Y1nAHLd3*dWk0!m@Y7vtlO&?7lQ2(y( zU*F^770^-9DP$B3Q=uXYZ5tN;-lDuthaj=S+xg09ytZG_ZC?s@9kJd zv{@oyR=L!`uz4HaZ1yyD5Uf*|e1lOoB2E@bLb_;8+DA@f@`o}` zS?f1;7=Jm4j#ycK**F@pGW)Wt-B!7LIm)HQxOZnom7ruvsNf7F2D|rYIL_aK{#W)m z-CxCDTA0alnx!Ky_?X37hsqmvM=AbGL@phFqqFN&bFcfMa!*W+&bmxww zH%}ZaJrsQU^26&V!Eu>NMVfk97z<&$DIOv&9>)Zm+xY*332*>AzrNzX~cipze}TeO$?^m(-?2DJ0G zti`(X%25q=tc4W#RYOWTO7;d4dBdksUGj^T4i+8?onI5e@bU0?)b5-t%?s?;)Q~%l zo!&|Mr*h+uS&rFmuX|P|sWc2ztBS|9Q};=aSIWZFh7zK(EzzM5_KNE^_{}yac%^7) zFEg=SVPZigjUOyjPr|Ey8Co5y^PD^aG_3EM4sZn zL<w-N< z(5-!xY-R4~gWDAKo7GN12fj0Po!f8D%~Z3QoCxs~jXdkde{*SB{vme z>Y|V0LO;_GaXye=ZI>w=Sb~IfY2S?_rZlZf^z<_Gf`_r4D^IfXD`n<75B2W6%ICZ6 zM(OD)5A{pm3X0Q4VoXfezVc6&LR@gJd$a)oEk*^$J(er7sAkqLG8S<~WVDbGDiK!OwX(fe#rKGm^MR zDjZw5Eb6Th#o_!SqB$Zbl#`y-f2B-U!JsKWIX|bjQ>{;9{m0O1SXr?mQA>VbA}+gk z%b!vbvys-DZQgk)n;ZgWg&w<%U3KU1=hH{)l*bCkTXM%KV3MAP-Ogm?&V1GbOGpBU z>Z+K(Qx6aRdS#`u85NJhkgWc}Y&1Ujaqz_8KT;GoCq;mSW0k=j5}vg@h%fz1{I#K7 zbfi#_5eH$>rAD1LX(soD_^6Bn<+#Kb#@eK*6GdqZa=+PUwTd33c+{$iJzyL#$G*J- zvAp7pnI}>VLg}m1%cPVZsK3BdRJROE(cpzsMYo9G`SZQiGf%>F?LQbqEqLw|K_*+@ zGI~A`%fcX)*kDxD62^Tr_=Kx!viPz%rrmj5f}}1UUfoXHhZIV)pZMz}iY)i5ucN*p9fJAE4`R)jB{2;prLDDojv+!lnN$@U1DC!5s9``FnVj zc+mJFO$f;j@2iRaROii7U|=m^bltmm@8%h#ZJ^06-PP4~OU(Q*_kfz?Z*XOq_ zBhoXpJ`ikncf%`Z$Hhy~+#%Z@qxEm{oF_foudbBwcWzUySf%+SscD7>VKf9wV+?9KiLkb$FsH>e zLO*(|a4=P@sFhC6dz!tY67eKnFX!VrRKP&V6=$2hNP~hP?doKyNJXanvi_;r`=767 z?>+P0BU)Gtg&b5?{J`oyPmT{^ zvf4O=5NTcd5VwJ(3_X;_zMkZR{Olnvd9#QkH5P#+;E=xD=)ZQ>E{ zFa?y0PdL@avXBghN;Am-0K~ai+99QA8|{6LuX6o)7;B9d+>bp&43TMkTtex*@kf_k zq?l+?_q-zZc9xM+Ay63iM_LJ@x$-2rZfJhejC!m5uQ6sPPX*H<8w370_)Oc`+kmZZ ztMruLH>`?VCRO1uOUzQ$qDO6nE1Mp73oGmv!duq*X%KZh&sr(dQCJ^NJ;4H_oQ}6w zQI@^-C#58Umv}`GWG#U)8n*Tsp1L;aLE_O$rw z_S7q~md|h48vhqy(nxkM^bNQQ5bAz<^`IXVlnbKoF2bRjKRvP}>X5yKrJ;=UhpfI#GUH0K4MPi=+z(9BxN=)$!B z`y)+e#>?>n&QH?+fO@!jo-D}z7~hy?Dl1g2;pb`|-zJNm=uMehd+gdB@=M!ty1!j< zl|LHl530N~a>vRdjeVR@c0z$^IV~1QQCu23=S+j0Z&9MUrC@IG%MYdavi>xbn5m*1 zRH%i40tFXNoa(7XbAO1j6}v9P1+QE$!BNJ%Kq|%H?#1p;i^7>R#-1$ctZD_Fubabj zLd#N~VmOwYgXVtj^+GbkheF1MlU>CH%W2|9tb5qzvO* zUvM1U5|N(tqan(%K?Z^6iM1@tE>mNMPHt0MGZ`ysRXNM;rBg}6q{;%uz9q6ZkrZbD zDK6&J5FU$xgM$N~`=2i>b;q6~(ET%Sg0~v-*eyG%|3DhkRVyvTm!N6X$dmn*Zi9~K80Qrh}DdX@am7&*FbUkh+M8)3kX#g;Gpv1Hy-8> zYY?Hfb#^ZtXe5=7J#?mFxOTCH<2vN;w7+HQgRccOkH;N+OvX}lh<*~)a>VzVJcAc= zd^Kk`5-1;)k_lIp{OWsx0Ss@)B;mmCl;-$9AJSgg`k4|?W`S!a%yymj>8_{8ZbubP z)A3QDh|`k?mbR4`$xtD}alZ0ANNx*RKN5w~7kNk|A;lv+UO%{xfMf~mt<^CrygaS%C0dG7l(X2YV8duif&Bfycovk7ek zv;$FxHeCd(+?#Dxrg$Y)hc2p-*{Y^s-L#iYnp$yjr`zu;i7>kX_Y}%buLiW1f%;!w zrabc+=xD3yPwL8N_MI3>?qKrWqb?aU-zl2zxdwcZ!B18>g-ohe`8Fy`?m0fcwN@_1PY8io%)wkEotjlRBu*$BqJ%6Q1-a)uaeyP4q@39omk157 zW2wkA2I^~aqbBVfJyrV2u1@AX--HFyI@?3a+*siV)~z23x{KjfN7F{h^V5CgG|f5g zc1xuAbX1%<-c$=4<`XCB6QNw}w+TV3-siR`uol1D#k+-QbaFMRSgash7nk zwV49h2}JhekB&KdO4T4n70AD64WIonP}%;8OfaL?sZ9O&G|%x#R{B@M(70D#DkMv7 zG+~>du6N5!7#*j299IS_fDa-w747I+fp7@TvfIX+&_9vC$2Ln(i%0cZFUF^(w`;ml z9cnw$h^iqRAQ}cgP1qRPF@|R&C&Db&-OkCx}JVo-DkNt*4LYa2yw9%x3xOL z5?!ANh1hg2$9=xx{9msgLorm8W{6uI$@_{ns<6GRT(FcC3YYhd4vw>i0Yxw4v*5aE z7}j2=o>zSug@M~-L#2-~-TivQ`R-7!ogtECp$AqrACRyyg5JySkPwd!tlh)sbl(DG zNR&3k#wG)FP(=N*ijK@XvN$p(&Ynu~WNja!rTJiUt_HC)wyqvo>YljIp zG}&%kBx=*a@OiM-um4^D1ZVCh^DQpf?!8w{L3h!gnCx;s#RoK6M=59xVll%2<^q5&23)S&E{eziQLUwghHx$2^27|M44Y zW=YX{#<&_$h;6he1bSrTD*-nF%cy0(1zz!#b~F6>{#7!Qz86vuW7Jq`$0+Jyj;*I5?SS@JG=!&+rc!&9yS#c<_e_Co41*MKp0-f&4vc zx(cqs@pX+L!>EN{)jC8ic}QF*B41FOPa=Zr?3E;Q{szt_qfEp@#;Tbv8u&R)8ffs zF}|TtHSPSaXA!c_xpM>Sm3q`7Y)RL4qetQUqVo$?pB3Fo6Mp6gC8r;dn?3yuK8;Lp z{k;j7)pjvqs@EPW>0T*Y4l$uo{$;Jlrw&UMk`-fFrEJ&P_?C+XmD`3@s(02uSB^TP zIuku3(=yxJuseq9OSB=C+y9&A)`)L;a|o&-Q}HNMqi}rVK2Ntxe5(VU5~ZB|C@pq; zJoLeZp z)`=@S!7>lfiig}0B`wuU6qa>sU-eiWGsP621~pIap`_widz;@mIqBZHu{x3Qqm@U@ zY-anDN{Bk}wzA?9&LL~Mj4+)W-L?{3KZ!Pwk~1_a$^?i#y)}*eqjX6T_&%r-fzz30 zxR1_H5*zJmene_~>tA>g2Bma1@}QA%D96NB4xR#Q1}_V&IUiAC!R4c?kvv}N!5CE{ z0g3_~q6AO{7>?mmHH5bx#n|!=>tr|4qtehnk93dK#RSqIjgl<$<-F?U?2-F3~z};@dSxOp+Ed~sHS$h$f6fBz(I3NO9VY+kTd(GOl-d*3TqgYMyxF4 zTUI>*5I&Go7(g{NNf+YQU(LScJf6Ad;@>izoue|e*GpnLz>I=a+N`EPolY;FS3Tus zw)FA7&k!}d+xl7t5KM&=n46@;UA5^H!4N@?wodXzoJIcgU638-*DfDZ%h^N2FaP{z?3MbpQ`N=4Ip=$WXun?!#&2r> zsiN$2T)~b5x@1iH?Z`3$J>dfMY;I>?BC`bQtQSpC7ZO^-N=A`CsH@F{4W%Jo|2(LB zSff>eeTx%~Z!s^_-Y?W2gNUs7K28xTBK&*gL6ap~^cu8`XUGC=i&d+=n zZ5+J?>%48dTe|AHX(C4~xYZ#vTS?=5o66+!j$|qJ_EAi&Kv=70+KUbaUO`@vjS2#5 zD^-CzAKrb|SN!FuhQF&+AklT2fH8x=q`|!iXS1V8s_e4P*;l}8=MHywru^k8miysV z3F=VY0O9G;RneB4r)236>pis1_-iB%vp7(z0D&;ew7~(s04jA``0z#;YgJd&Y0l;5 zXnS|RpVmX30glC3CH16Vb6>7^er&##8w>?hMQ=9|PnX`Z8`~x0_U>XPD_KJ0YE=nE zI1_9)Y*32ht-Bxr{IHA)%TH1T;x21HS4~;KDHCYn^U+SI=F!_gI@^{DkeCQ(R1cm9 ziGraltDS^6eAzCtO|-w(y#Ep;_@p1t3af@m%tsx%Tsr6gQg#N4XxOioQo^{%+al`=g@H|TrEE>(e&U&=(jjb2^MUk5^Rw!p!>eP*3!SO>&M$@QNf z%^j;IlHW{8kkPK@&1By>KKK>O0Tm;$pZ)0MLiTsr`Qlc1t)xW$GpfdRdKt+kn4u_etWpJS6Ovx zSRt>hyXvB_ZU5(6ku?#Uak)Xv#+%h=covZ={dLigaUAxeH*I%u?ObF1y~UP@?#U9d z!cUDe)-in}!!mVN z&CF!q9*rBtAtBRjldUI|*yNtO+#qk~H-ixEY%RJf^rvRaC|r~#rqcVTjY;TZ07fgir|_cyPQmEMO(fED4|wtH6P8VSVjeRM<)Y)C&;CzK$|Xun zX7jXKw%$P4CC9RCr&%L{QVx@C`ns6WwYLuybVFOU)7n8_TUu2$NZ_94S|1RK7?8GK z=GVkDM(ss%CS4oQVi_>szL=L8BCtAHO-#R_k9S+>gsn3UNY7BttA1)G7!C&vw^+vS zUlDT$mAoXs>Xg=he@vO8!s@&DHRsIpbbbx~ekjPWE4^W6%)mC+-_*$kNpFCh1y@t0 zA|}8~J5vrgCpJ31!?1A;otM-xs{Q2LDbb zFf_n}UlrOfH|L5@({}JjWc{o#?hKFm)gBgQk-{*tR*2yruQAo^|K2fh z;+tmX?G$%`Gn)~eoaS?+;#ejQbf00-01+uM2KZn_+sY9LW@-XFNy8>s)?|GZ?LtW( zU9IGHW>y%&moVVuj>0H=ZI192dzLr~Zh2rIPBCXgtX9%Ao>P{w_mu4y_0Y0e_pzT! zHO3sy*@(PcFMoQ_V; zHQk#goQ73Pan*FMq%5`A_nddn;WiWE(=cd_oop8mnfEWGjlhm=rAgjSk?n5Yu4pw% zG8-G1uy*6z4DVR@xt9(q4N&<}p3BR9dkO%3GF;j~MFL@>YPdO<&t|q98?z(bABo+1 z^!jpi8`=KsJv^nSu$jPBN}(L+Ak~GrP`a)pU-xN#j%Lkp0(j*dU8kLv`|@=`IpX7c zj8iAEactDoNS^uRXiYN*0qxUoN*V%AInF%ytGYoJ&DZ}V>OMRxsCFU?*msc#Hv;do z{#%00Yw4=mKZJ{KRSF6_{~8Dvg2jSJiTl?GG|Sp#BR-~UYW>$-fcGJ~F^&9AogbxX zR}VN<7gxP9-$rgKvsqP0Q=iT8E%?}C1T_6jdb zVg8W$N#E+STAp1y-hmy>QnRu7SDrIZJ{)FJcW#)HD)w=)$%yjfP}G@10pWuTXgB> zzrXS?j1(w{>u4m`I+doR8&HR;jPZC9+PaOZtdy}=#cbAhlf#}sTl+X zt9Yv8_?{px4p@0roi=HLl4TXo4`9<41+uNbQ)NA0!?}x#cqD5Vm3j__sc4h_}8A7l7ECBvb;Xp{85t*k+0Myc% zulf-6eOdF6nl=eN<+;zt@#`QDCjjeh&(WfU!Z<`pl^M!wNE5i2_L%A|BinL21E-k5 zu@=c0-5l_JA+jfod_+S18a-(H?sYmf737{CDJAt!hj>Vbp#fQ4Vh zvhbu38iLZLE_u5Ufe)#snmg~I;G%lxu`q&OS~T|%KqGfhg-gvwI(PFp&g6K3l8NL_ zD2ENDF@Ic+hj|o2XG2kf$TM&1+Yqr1&4vwh$dBiI7~K6j zrn%eByr|+bξn7=ynj5pKt&ga8420J}iN4*U3Cx#u&VX{P-*+Gd7qOnpc)C^!pa zRWgaASEqYhrA?f&pcY2z!aQyrfqCA>D9;i4E|FCfRO&7z0l+H&b;Q8fy^gW~>tNQa zzNad=5`nh=Q|h7BwS$6%eB@6Kq-d6Ij++b1p`kTFMQk#NDI>tiU7^-5O8=3_ORq8j zSD6-#Ad3Lf|M{&3TrXKw>vA+G5C=d~KhAowb8Uc3me<1taZdrCXX|RKT=`p%+`}Ok z0t>1JBEI!e0>W?KB;IP#RHX%Z4AqyBIQh1Q{L;3gda}VMb!pjr)>Ij~t7U573IO{R zRrE;SpI0vwljYjgz@CsG(s8U&<+W?o96y?YIoC4Hz!E_N4jhK=LfhtS+Io3=9^Ok5 zn4D(mg`o72#)8h5u_%V&2}DtvE`~#n&G+pG9I(DEBk8YyB?s` zW8j$+#zppfDz_DSy{1?|*1>c~huHe?fg*vHkj}bbU+EDOGiuoUQEYn6nU=Pn3Tn_o z-k2NPHl>pVpSl~b=C7tytvA$vLy?YL>NXk{q*ZY&7FGc@ zm(w=wzs(va%u|*-c6#vemsitti;}{mo=nw5T0s?9O4^zkGL-?7Gpu)WPVUJe^%Q6i zA%NrEr@NKeSY7Cgpri$5yDLuoNE_-&S*ySW%St8-!b$!Sq3{%9%A?T1I5(}ssxqv^ z-^y%GktN=pqW^IsmRRoheIgagoEa0M@fiY#D+uAj)IR<60apTCz)fJCSQMGY+y2-9 z?{*<{*pUmlt0S}ZU@BPc7RT!yR6>nPo0%sa%Cve?syY7E_~hnm6B0H(1>WJwpwLGF z@2{hOmOF8_{E(&r%|2JND_u(Tdm%3w!?|p5guXW<@wM5pqPvdej4{6%cAZ9UOG)YtVAKA8ax>k^1|HO>8hgVj+%4gj4Qg@zLKt^S`lDwjN{M=)Tx9d#Mouxd;}ViAX#zT(gzb-LQCLH!1&9RHn zVYB!r01`@{$6`ocM;^h~5N!i_7@T;yk)Mc9iYEBs|9={CI{y6$L9+|OU)rl7IVks& zvZf)X+}E2F$k}YaUe#@QD9|;^M+e#dVF{1G=+<9pe<4247}^SzZq8%7IN9C#1UNvAp6?@mXU!Ni66mnXk3 zgtH)h3Z54W(_3RHWWQycEbg!KkQt?~-3Snhx)13H5|T5VOC{0LiJul_BWW;{0s#x~ zxPiR>8Vs20f?F2Nn@bIc{-wb-qV6-%s{Nsn1w$q4%ej)N}y#I%} zH;>A(?Z1bwP$-pBq>&~~nn*M#%|#kiG*2Rpib#{Fh$cx=p-E{TXdXnP5|t(zRfaT| zCXK&+-p~DffA4zNde?gY{I2ypYq`p!7+h|NQP0 zTP>FbrPT3d+j5Bq|NPET#!qvk6hboA7Lv%a!Te4zd@w4$oUpvSoDbs&v`58XUti2f zN#T{nq!=8<+6yr$(d;$txzNNh^_(cc3Z3bN?m+=AL;mO6KHZ&?rD+*_lQ$R$eH(A6SbbL~ai_bx!{j}Dl^XHXnYipMwBo*^qD#x+E+z|f> zy2@pbQQ5!W56Gp7-2D6D;X~!3jpdvTU0m8U%4qnD>)n~SWSO~9(bZ*cXqcwTeuG=~ zY2?6Em+WG1((J4&?&O|2`B+Hj#*LCUe?K}4gsZ)flsgC+E@-R-b#!+NsCU1<7{=~3 zeL`@fnqyrXe>aa^3$~u@$I_-gZ+ODwxJ^=;$GVva|0I(@FsjRGk1v)q8**vks%|1= zpR|hlt{D>#^XdAVBoUvPpw3}}GHSm3IqE8KA>%wqz>ob}tbY5}SGZzMx1`TWc5SY$ zba^y`F|2;RW|!88z4=Pa^2$oH+Wx%4LW7NI+KqT92&jKPTe+;?(b<_YSD#iq-)TG# zr%~gusj{i#_>8r0Tjg@C;9vaOhe#a0w4C=<-Ob&uU9+>bRhyrmpY_0<9P&+M1w};} zrKLuQx%?&WGQzM4o}6@2Z)g>ZKJW1yzj3#EKSaE0>F@cEU-Q&BrE$7!Y;^Q9WC^~z zmSh%NG7)9B>9GyK7&n9e_Usx8^1 zuByTNG6q6f9mo5i87^^ief7~f7_CDDSy7R&P_(Q~%84A5PIP zmNzBeyj{M(rz5r%bQ`;B_n2qmRe4W&4!oY7aW}d7NAhM89Ip?WzcGQ&(K4(*bF}%+ z7r2y|EH4yQW_5QP>7PAo4+{u`$zq4*U19Y! z1s~(&%%MYJ;Np_^=FhXKbAO>UW)Ic07`dBoprjTL5%je|+M7(T@9y&O^ek|nu`<2# zQG#;Irr(!v!f`+&N};z|$2Kz;nd7A_eSNYW>iBJEmT{)`y=;TH)KuwM_DTNd2rXFV z(Y$*0HW(9OkG1#qX2O#|2XeX(*>8NOyCK7#;Vr}7g-iGuSOr)>YvF}?Kus!hHI4Yb zxH^0BSrm@8_jfK1oujOe9|qoAIVQM%mU2s!l|Q|wV{+{6jYz;=Lk zhq@M#o8R8JH$>OJhuB>DW@a!-+#eDeIx4sEM{XVlAZKCl{qV(<&tjR!T&wE*P>_fK z1LdWjLdWi0OTTrznIkrGa?7n@`5yCjS!NYRP!P~;P~Roje7<6#+rGQB(9p{B_5u%$II+h6fVDgR(O)o1TX5JnOsbvmzV1 z8>`J5nQGjSxqeZ(QdZekx%#0pH7iT=;aq@-*9piO7 zN^{BH%YKa?KFnj|xbz03(y~dt7#y@Tz4q1SH@~{BlT$XNwq+&*lUbaKPaKbH9*t;i z)gdBtMMVXqw4z>oKU|5k;ystd!B&z=uWJZ*i}`cv5X+5;oxzZep{0oL0hYlyFRArSy$a%q2S;qm&`}4*^_l zIZ1O-7m_!n1jMk|Y-?0W39ddqyu9WjrSWq2{o@z78QVK0(21Jc!Fs&GzwuN)A#kR5b`s9WgOFNbTb0^wkldk}(S z+jsGPgU?1a5#7r1vM%%;y@u(tMttBEDV?H;IcYx6M>PY}2b%8<~YD84?$ zKG|Opgv;4Xd-v{#;x#lbD7p@dh|og!#{c!}Lq5yD55NjlulvIQgp*rpX|M*k({1?Z4E-aFdL^AG|2Rgj^4{nza4J0n~=>d_X$f&vp`BgO<_8l!YyKC#~t3Q08n&>X5hN#cJNR0$-KFIs~;(J4R{_Vhk`4VL26;Kzv8#Z=h z6v=j!qi#(;xo6O`#3Z!Pv4@kFSH%_~IeNO{6tAB`0+d1Twxrw)PCveRH+B}2tjA$E zSZ~7j3uY4A1OboSf&#|tS$kkEu!CKON$_lT4J@x`;7vklXtcbnK)h&psFC3Z<|caf zAf)&qLA<*LH9UW40#w)hp>)zEh+CbGX2js7h52s`@3~P!MA65N~yv=$3eT)MXRwfwpbi_7 zABNq#6OD_U2s85FkPt#t&_5tx?+$h;X=yHTaeA!fTgW!vhvvH#6lTtqUQKJMhrbL& zMDY)^BQ+h!KSaa}vAQpnWVGygD)xP)5)7095BBRu`z-%~R1_JBkSWCW_y%V;MHrjI z`?xj#(itdFZZo_2G4O(&-Tf{zPtB#-xw#sMT?X(^jwKbYL5LBGrwn`cP_3Ojc{2Rj zGt)~{QZVDITEvkF3=UR8Ng+6ID>JjNtu|;+9t1+6V`?>66>!vZLFkBMw?AZ3{oXxY zHiAA53ir#*M>JH><2ce}??D~UJ{LmrT90@yI zY){o;g5d(;X+vn-caLou`E(J&kzZb4q=ndCjU~iSX(~6?%T8P{un7$fB_uEi&p@nZ z!p)6!a0BHYY4AK2HoXtgq^h>IGv&;_>0PrYR-kkQr$TDjr|*VBF5xycI580d@w}aM zq;DuR39V3KL&K|y8M;sI5P7Ahe7y*f*S=D>>U8}KLd?`}tm)s75GKtoV-<42$te`d zkW>gWZ&4J$$M7C%9&0#(JUMic1{Nkl?aY+a)U`M?{-vUlPQCJo>D`5nR0wpZo*tzm zB)=eJL4!REUG6Ou6r6_-w_EULm9`gh$e%rV39J47(pNkfOU!j7XX79acS)hlgX z-P@2LN_g>N3k=hSoI(;gc1U|KABMY2e5-9P+`=7ti|L?aY-3|XsPjI3_AI0QZyK$! zvGMm`zqn*&*+`dvePSbaJPDt*$==?c_yM?>sOsp@1#W{o5*Y~^RVrUX`_XXi3s)nA zQ12<;Cd6o=K0)N4H!G9Uki>y0I5VMIMrd(1J(Di#{@OWrhnnS1PUSi?s&rpJzs;Fh zS*`FUgRfRuXC~L7Lx-S>H3Y|np_a`F&Dm|u!3NsezVN1uhiw%P4-d%~#tGK2#DmAU z9Ek+sESSKj74BPrAIr|2JAIKjSxY8XxhWD|FZkg$-W_qYbYu z4%9+^*!u7svp`fLG`L74;w=!S4m((m>_|yTv29Hx$Cti? z_^`bvHEenOfUq#l>C>k#ySm=KcW*nYRj%&)li>$pc74v+co-q62Js21Uc!@|e9(y+ z>93Hk3*!hQ)(Tc+_4uZQlGc+aPu}+SvcA-ct9$3SHK0_NdIr7{Z>y^}!)nVfDT&Kt zaWVv%zi1 zc+P~HRd^6d+_pQPzdQeuANq%Hgsk))bFckowQmu^bj-{`Q9+-!Wq}P-zL8^=pDN5t zs-bz-l6K~RW$yS1W~r-ua1#oG_t4vS@5o>U3ejuANR1GfCB22tl)3oJ(C@hAKvGva zp|^wMI4dIZ9jr{u;Y*tY1qJa~r}HJAp`^yU-o@cHee39d6KNRF_TO<87FthvPCh1d zvY-eZH_i05T31Ks7W9juumvZgu5%X0kfV`$;Io&b8^4!?6RoSO`)z3Gb803_MfUu6PbkCg8 zF)*NTcAgTDcuF#5dkLYXM~@zTi@x|gtuXYA^`odLE?70FsHh-)d5(lVj(qeeJ~2@t zHD_KFMo64+W<<=F=d$L?b!dq&op-aSc&aF#Z=S}alsx|42Fc}#?0)9woo~-c1P2FCHyv`TnlW^NE|_^3Bmb^61G_5-32Fmv-+Vb z6o9Z4h=+%!9ty9lnGD#04Cyn!NXRigapKmybw>vWgcHht%TH|CA$|6eJ7$02@gaoX z{hS#T`8GE&HxEJX@044qXYT8;T3K3RE z#G&*R?zsdEdr`l6%4O!GO4on(2Lo!(<>5v8K8|+E(4z`j^ zDm)lbcBnw4RM+0KT;n#awIS$Bp@V&8cB;Nn}B=d+qNpW4?m8L4MG%G;0%w4W+q;T#1}JYV-w8- zN&4D&>a2=UMhDW7(fdiAG(DneBJ~X)r@mqRI4&*>r~OH6ELFfpqy`U4AxkT(P0r5F z5IGz~`;?oTOIQa&X^U8BR5X+kOzn$L^aLWOk9H&Lh+0-{fh@Ru6B@H`19#AyRU@#& zEl+2n@E+0dC}bU5<0fMcQCW%#L?Q?cpxR?_<3)C6<_;8;s1vhwm&}t|<#{6#U{r^{ z-*I}A&a;?Mb*-dUC~ngs>0EYm%c75HIFHr|Tly}(9A3MBu~C)^5;8mjAYg~4X9gP8 z1~;B&q^53zUgPxKoIg?;9AhG{bg@WZ%Y5gm*jxsosUco?dA=JM7>Lh8O2s2QXgF_+ z`Z;pAwQ~34$B*^1gPs^<1Q=vwy$WeWXL%0>mfJrN9%VRMElH}hnMMVafGFv#NQ4Ux zO7eFfK4dgD^OJfjJof-_m8ioqer{_U{P~lDii#@1^yUQ8I@yR1jez+T&fECxQ@n(3 zIeJF;5(TWNaO9L{L9*V!v+vKJKRAT9fG)j*)}-wL&Yg59)?Hm)A4EiO$;_UMfKMVJ zp9sjY8YPwgHApTKuAYcAgac#l#b$O=sWnzgfATu9g|_7#=!8S(b`k&$Emo^}_{>5l zQ){WQx%nj!GMA#8dN8Gh2W}9Kab{*Py0My%w3^DwP zon0AD68&++)J!@~IOmyG0Dn>KpdCVCD5(YRg0P|r{_c9L;_uH`C8hQhO_qmh+*QpJ z5CDf&l$v{==BZO72rfD0$C%}O%6D#+$7tnnAP~U4HG(${p}0Sn^#OJ1HWK8d#cLuVOi6+f`SaYk#^*QJZ!k+bvC>Jbm(R~tZsp?S^e+Um5+mg% zuy^m??K#O=SqHs0))p1wus?5~($s9|?R|E+kZ7jdERh=KPS+CWPd z4@fR<@kOn~O+!c5`e45zu^?5h5KN?oI~|F5l<3&lHmJk%)F6qcLH`rW@xG}k7@z+e zZil;u&@|6|lAd~?kgyN6`oj-D4kN4%ej&9$-c=2207L;)7O_>l|jeX=FW`55JM9VzW6$1 z`;bGVd{&EFR2}}#{@@N*88AMKq2nAMAgf@u=DE z5-5A3_$QsU#FAvYkge^rdm|&Z4t=Hi=X~@esG#FY_~XG&xvIW?D?(-fYH^h?_JdyZ zjZAH=T^AulS%c?HFvxI0WKZ}A90TbchJ}YABEAXL711mb2m%H;gv|wdJ4;W$t+aK} zA{4W#*_MzcZf$K%H1}~{v)f5;QKljezr_Zh2AB}!A$Jtm3OSu6+94)Xo7i|_SAL!% z&C9{&S`fX$9_ZIP>KW)brfA0A0U{2ObHce6X%8S2o%lWiKZ5^OB0hzWk53-@wg`k` zFwuqY)-YUl$w|HCH+CUVWRzbby+wm`7Y~OHiU9=$(T_qcZwBvhn>WOb;hcK;@2m}6 z=?CG?Qiq5U{`|SwrIR-^CZ51$4ZgDXV6!-cVp$2oy2uc~ai(F{Miu5wRvM#1xcj=e zh~drNfmrV_Hi0h;-cXmK$(;r|FQ2Ao&|UTkXCe=BzvF#ndx&R%aC4#afbgV2#+~Qa zP2tiIh_^6^EdkSBWi)j#4!v{i%1;u>sjoBu8nQ$;%qJkAfEJl}d8^Zkt&e>Hmk&X0 zxc(9UnOyum6`K+S_x%uP7Ko%IO=DKW1xyVF#aOdjJKgV0QTvQ4xhSHKTXel{qL^?h+ZRWBlJSG)EdaZ zmsd7HEmKgqhK&-An3Aq8eR)O2%)rKa(dWlIlvPx!dU}lCt1i813pm!29*RSi3o&;0>_@m01Rt0WOY%}roB7R z=(c^^ws;ssSpLOg=i7CpS4zup6V8r^!7X(mEc{Sn#LHuo^>~EpBo#$nn5jxvCF4bQ zSs&(z8&{|LWjDz~PCo(2NQ4sSel9Mq!HD_6>btwbCnFYMU8Q^e{EOVlv7E}&zQXqE znc0~v-YO4*f`X3fIa4>tyvoa?6XyaD6yPa&;DGA6qW$&l!2C9`oBV7=t2lz)N8yOJ zD+##LF1l7Uo9{n=eh6i0e|Kp9XPJ~d#McQJPxANQ!YSTl20vROZa~6$S0@i=clnJ& zsQVk6nix8BobozjaBGBJ|Q&rfi` zu$CC_=Z=q$J3JWFIrb+NlZC@@9o(;?G>77uUVEb{347J1!-oBt+)cChc5OWnkH$a8 z$+?VfdOHcQJQ3sr1NkH*B9SKUjZAepVY{8Tw?7FN;PBjMqwSG5h`Gg}*#`RebXJk@ z$%`cb6_u0@!>?xab21ft5a{W`;jM>iP8W&z(qZOT1qI3IK@H5FU7PCHgf|-}r|HjD zygcfmp(X+{Ksw(uw7jBl^CPr(&j7Sy7>Ya;hEStI8UY5Z@HEgCfv6o|I_Kvskw^{d z$&XMq-z0BWU}T#yjuXm_I>P0U^|)9~w5rzDPcl}SG|MsM2u;;6@C?LR8AkqsQOphu z5P2p;5sqqVYT`39PqA)_UpZe~Sgf0-dviKS6aGc-#0W6o;1@9moyh9 z`+|s&g7@?UIS)lIHux!-!k;_|1lfWprM1)amhjR@ ztIwjpqv*sVV-C1+D=3Hx3c@IBw|<-QkPbUkVj_IrQSXyb>hJ5rNk`y}g2ZkCzab_x z`Z$SssHg_7TU@<*7<+^U#fRlH#A7QkK?*v5k@>2(>e`wZyrSU{L%y)Ez$9k11@Swhoz@f4DLgLj z=0ID`uOB~7U@+0xNQn}XInoWB*-J2 z&d$!JoBWaNci-GByZAJ>7m-(^HJuo$0Q#~lQ4ZQIDk-@qG~oy=SwzLePN1`*?#4I1 zgBsQHD;NUb`ZLGe+%8|12W(y(jld-5zcq}>-XAWZR@2|!Rk29OOQs$Izzi3sB-9g^ z(G@Y7XsD~7z-Dd%@OpK!cQ5R#DcbrUqv?PyMgY2cscYlgfXSi9GF}=sNYJ);cbgnh zRuw+*mwz-eqGPc}{w4X^e0ZFIEXZ`smD?!a_7=8i0??@{4j(@XYQmKpkPr_;-YVvZ z-+up21A7yL0^5#sM$E_W<1fE!Yukl*xoZgJoT9uuso!VC5zkqTvOqKD@H-e23(e8> zz(bgrw*Z_9Qk-5~tOvk5(`oE{Pcc}wgFw^}jZDg}Q4`}Em_Ol4ick%yZ|)DiY%L1p z>8}^#24BYcRAD0vI;ZH=_|=8X>?_py>ep}P4MlQxAbRi6*otC}#(PV4q4T`6vobC^ z#ZHQ2?XBJq$Fpa(i&N&uq*7u!+w2NL`d>ali}Q}_GD#a&V7Vq7i&u770T@)pdS0F% z)khMvM4<$N@9Xo2^mLcFsPDpeAY>tD1`w|IRk|OWU z5&~K48*fiO2FgK+I5BGq^ddZ7-him9xMIAQ=T1P6mpGMpwVd4CTZqvPa^<1%0}*hFU52%_wfC7Z0>5ydsog{PbpV!4ijOA|;}{eH1X7(~Zf&<4naH$P zXr#B~^}Ar9V6i@u4yqGm`K^d%$dQbg6zsI}b;{lI&pRdTporIlA$@MhozFS3QBil% zKI`QB%+0F`RDOlK+^#pysasu6g%Du`#fT-c5K{j;r03R*vm(HADV?txV>p79W??;x zY(yZTForU+AIx|7O7B|23X^t8+e!eGuxUcXaB49#cVjyfd&Dt){1B>=fPetE3n}eU zad8}fSbDEDEjWL5QWJV;;gN|4aU*U4S>j zBO`enE+U{W0RtW!9la0Cx2*0&ST}ew9NVa<6fG?Fkxcv8Noav7ckX~@j6d>TB91f)qAzc}rD1t}57W)f zB-m{PpdPOt%lVy6)^}hKEyY{RH!{35wvq4v+h}O+pmPxt63X>i^FRor0+tLI?Vf0s z>yLbw3d~~PefmTL54YU>e9V)`AwLbw)Ji+vfHQpG(W6W>G&IxG({C|Sqhn(;9kvz+ zgJyC5&f~n7;Xb~p04ttJxhX^mo1!(NK`UcvkpRqwbk&d%C1{;sPWf$=*PB{2)wA~i z;K7<&0l_8t0!6bJX-PmfNrhfJzB=KNh^!8r+z%0Y7@WsT+IN&;OJ{+^h6aTgWTJ$s z1No<>Z!|008ca$0Pds=RzQQb)_^2->S6=2mL(kamP7T;Lz{dk^2^JJ%06KBe&K&bF zq7$*WfUyw3$0x_G@FFY2Y=x*P_W-~pB41Ne6KRB^7b9W;XLkHJp#`4n@KyZju`3ix z{(*tpgiK2ra^5TppcLA%+;!HpehzzLkQnm8D;2l}jxjL~cK7r=+wkgACZ6US-o+Bc z{)s6M8e0p%T_igWU-u^tj*j7v9&xXl_}{t1iAncABNgDQ1jvo^h1X251F*wk7H0CJ z0Quz|8U@U|La{mb*3=--{L@w7A728YoB;5)Y}pczkyh2)({OrfO;Fs5VHh=X6Ui5d z#a^u5?#YiBjKff3Ge18+iI^?!J8)ntwg7oN3!f22m_8e8*LTuYRaNEMeAo>O>do`X zdICiMMS$Kgm>`Oc(yPBY9jcp}cA&UFiV;Pm!f%8RB`{S*Z5kN>@hW5)SfjZn=AQ61 zvui2Z4^%4Gs+JNI05T-0sz|}J51u~{MGn}%Zy$;No)TZWIfglaA%{@BC1#1%F?njI zzgamS-0>me+-p!4y7rNq2}e~oH#f)crsxu~7$0n-WxwI+Sq%zn>fW|&Q)$a@?wDOL z0Te(pJqxcQSyzlR4H!gIzg%g3K6+B!YX8ofva>!}kpi3D*yCKOjKi7hHfBKlP5F;u2W1@q3Yp77c$x8^kgWtXpkjmRHUzmt2g#mxA#k)E699Y>h%jWR#h#i$FKj*gy@A4;#SS3`vEqQw%7i2Vcmh2}Cl`R~65HPY z#MNZod%%4Lkzo=K5*yJXP&UuKuwdm(mjge_K-Ry@%k*@uD0a7zkmQ4q^X;eIroWxA zWJ}gn#{(wg6#^dG)o@;1>c%WLCQCa>Qm)?vTh8tvP4rjv#AnU!kVMCMDbi3K7{Xo_ zmNTgO==7gCX3aYA6YV2vDJroFFsWOqM9Srr^e-Ck=afRFLYC@MmoH{rr;UQF_Tz2r z=QG%4#nBR*nhO_}E;TvWQ|s&L0f|trYO+~8nbDz(nuO=Tfe4i(y6yqE9}KS3--NH+ z+3ro@8p(-hI&{_JqN zDkf$x;7;I@+G;1w%bED5^Q3;;?;fGD zI-6}scq1kZ06z9V{1*YI3N?S~MI@SGq8-Qw`@J~Rb<>ElI+$J7sJ(2x-|LSi>(R@kyEJU{uQ=z>ZMdM4w+p&- zsBW~rx3|1oRfpvyXZYK`KGWXdi*eotz1)EEkDPn_;Ri+S($rba`ng=dh+WY${NZYL znL5DizKx9VIUTXEw&rTT@1c#AC1KLFdwsy8g}|TSwMC>Kq+$3>s$#2{dCe%hbg6T^rWXs-TF4HjTXhudx@$Xw{W2<{X6*F1= z!ffs4{@HH#zvJ{oiCdTgaRRFWG4Lkxp^ly&F^56>{O8SuLzs&5sf4oLLv1;TmRH`( zO9t?A9_)n(N>7EyJiYE1P<=Qc1%YxJR9MBd@>27e6eFOo?1hYMvfT@F=kjgo0MN9& zP~Ua<(&sHee{4U$*p5iMZ?f^9F(=(WeYN?`wE}Gx;&`JPSc2s(GFqm91QkK*0I7fi zDS96#;bco8K}F2nFXA9&f)6EO~|Jxl33b> zh{Qk`fDqg*3}Pw9pb1MUw>rJK-+R&2p{J0V^lfnP7Fuem%_boQ&d?z+D`z4s^Uwv* z%1b8CVW5+XaBEpufZ~XlbO;LzkD%WDp@|@|vIpDp(OG;{1PRG#$r(>VVmSlgNCg=ias==Yc!OCs9#nv%*Rx z9;qa~Ls%z<*dii1c2wc7>ZoXGRe`;bjhLw}5Krkn?nLx6ZD{?|@=&@zmNaEmKwi$?q#G;K0B1n zHPz|H7cq=GQe4(LBLA+{@H?!UXF3CS%|4Mysaa>!t(PSJho_?dj`*?*{(_%QomkHr zdmmIrqpy>2v}v8Zk;?Ui(ZN#=Y_#%g+K9wzM+*{-mjn~Jdvy1|2hCKzZ+bpV^8VNbsJ@V9vN)Q%QX`}dh2JlHMbW`FmW^xu7U^-)99=6)*lez&+b8y&<_1R3u=WYJ%<>lHJF zuU!O-_x8p|?lOnIYr1SB?UQ`%YoD`+J>wP^sda?Mh?v%~Rw{$Z}Q`J#KW9^Za~ zoad)p313NcOPy{_5H@d}0{s>KVrj=zohHQtvo-b-xnc_0vM(bY|x5~}H+TAI&f zc=nTmsnHgyt_!*Led;%_#LLL-2~f|=oplHpx4$W$A)p$;-mGZpbg$}#F`vds5{a+r zpyl8wkHZ;#y}urBuEq#bu64h(CD8 z1yuFY|M+|CeMl*{!-vmFT+vuv1voCmg)0{@OYDL#X9E7SSm)1QqCQaBe|dH+ zA%$eO~=w|2mQ^jVZ7^`!Ql#b z5o5iUCAFzVcAc?Igz3n^?&{A;$6g7?ow(scFjGh*{93s`E93IyGOM04d7yOu-h<}P zD0UgE+6px8EOXxMV3glQz0-7!jpys{%Ts^oN%0ENVP(Ix_KPeq3(3YPUO2xa&1CWA z?WXrkl!vGu^?y*Z)D^;_bg&7L^zYICuH?Au9h;r&FdFjo{U0o{|Kjw_gU0WoS6ux{ z^S8y!>OMIJXNwn<W0D^{DWzsySy_D3PUN zYRpc*vem})FPrA-)~eQ`t)#yA(3Hd-qzAihu&2-nU!D-#MzXM)3N~Jm-0r7}<;}h9 zOv5r&NFrIYY_)tKy7*K1iB$31tgavu3Cg}|8*5AEI&7a)XPR1y{Kwg4|L{H+bsoA` zRm1e?{OGH%0ug&-6MtVRjX7oT{2*P4<1vI7O9w~V*q;;e0y+w&2Af!PuEmBYQ?p7h z_#5c!{5VJK<~IvlyD8q#1_UrV7+;gW;UnzoWa4|}*KrbQ<%sDw?0S;CzMe0RmOe$; zTz$vR^dW`sDyIHby_6}T+5d@iU(O^?UjGo>kq9`Uu(0q;`Hj~{w~)Z|;^_CtuvFIP zNS51J-Gx6XzVa*dsNO+fGG4%chko7_K;c4+n=3K0rSy6=IEG5nJ@+LM#L$* z0~YgJ%+1XShD=w^z|B660wZdmro0 zj&!Ah#)#$nU`>nFE+I#oMRCi~)DNpuMsDAY9H#yll>3&#@;VH*`oJI?h$84 z_pCS;0WI#6QQkvheuasr%qQ4L@xp@M+_f2OQcKn8hW1J~%P8=3AuDc(Io&=taI33VC0y4N=d&P?GuKy7;ogk zsNU}#7pgtL%|uhJ)KS^i3Q|l+NS0X8i^40U(IQ&;>*L_I%6I(vjEe@|D@Q)JQNOgz z30?ORHE&Ckesm#wq=JY_QMep_;dBi~~} zZfNJq-4RLyRo{H02P%GvS4|V_NVyA6e&t{6wWA)(UpT)hOCz8+c27c%1rc?RNq$0- z+3p$lNz~2u_G~%E_09Pwd`!68d6Y@Mt4pzg($gV6ZHvlhbne`*k|D|atWxj1WI6hc zvxf0P>ChMMWp8a3YZgyFq0Dd=H#*;J(hWrHT#q`{_Se^l507R&;FKMKqy3#Xg>PkS z`JYNmHjB7eB94)9PQ?N<$b`PA%fzF+{bSbUnBIXRJeDA=iju;xCG~EqkQ9%Z% z&Y72|0|59FqoQjQM*As7C{jR^$U|kF;0Oc|5FE_U>AQ*E0(i(U$N|J}g@tV;tuBw{ z5L8se$QF=gic3n6I<2cbV9n69*ZszgcmEC`0DMtX2#reJT^?6-{`$&>;KhUN9k0!I zd12g;^cK}Mfj-~>RHMhowTQr=jK3kR#ASd&N4I&cIgIbOTU(o^Y$6f-G;lK&fm#uC zcfbN5cvVuZJ(s>tgY%>Uwg5VQ78Kz_HTQNYm^1;-AR3PYr!g-m?G}2wW-cejS%teC z=;Z=2S0QF6#MKpV3_FPn1pjxw^A@CV5{YnYF1uFBECh^3S>9JTb{HU(ZC`1@<%6tj zY+~-y7M9=Aj(6!z;kSt}NQ%dxf1|s8=hvj+-eeKAq!ZseZHi0&oKzEF^emip*#0Yf z?Xvv_uhN8B$dih(9pYXxn^g9%jB*67U!!*N_aaL>MN`)4Ln2X~6*=lQ={F*KBCvm# zfAF7|-~O&(L1%(Gke?}B!g6nw4_isbxVLq>e+qZW>D$1Wd! zFto;A^9~60RRm0QsxA}+R#JRnKFxW?*N%zd0#UPi+U@kTI%rn@grr^R zvsRO^H6=g)5vc|5u@*S_D6D8hm?iE91|D(lKLtAZqo+?#DJj80h8L4wN*Wpf5`b0i zfn(#?oqrEh2ps8F%$3rx#xGiJ0|Qf?2i}0OV_SQlaSnW|Ga4HAom3;|rUv48Pd(Wu zv^di0$4!6laxi}Gypz*u0CNd|d^gFvxVR`OeIFgwfUO93h>9Xe8VpQKYIuaIbsO=$ zUweAaxVs-s>#)NWJ2^6fW=N;A_9-FT8!Q!_6Tn3|0dwgJMB*WAF;GLtZ;K73hd%?U zuN?yvyUxtLn7-VTJfWn7aX4LpT}Na5L2hn;3`^+fYU}FgNz35I+zSM|Cl=E-ElkDs zb0*HsT?J<#fxw$|(_Wy&zY2BsA#FPh*bDa~1A$9(}61^lfx zaH+K5<$U_Nj5>&YRV8$Ee^*w{04L-V6AMR3Ws`A#fNAjB)Xfd9NDTr&ErH!wB24sT6;0YEDzFr!9{0O^gOeF9b40zSwVa&m0tDhu91zyk@`kH9gR4qezm z%*!w|Cb`8adM_rt)aJ7|e}2n7rA?qof(uP>Vrl~Ep1`mfZ-t1oV3=_2-%lpDzLey? zYd-NNw;JM}1b00$d@H5Hz8&{{b- z?AR4iIhNMjJfHCi(|<9$c0K~r1v2>lbQ{d!k+6OdlOx1F;3`(cO&gGjZ~OTH6Ap;( zKujlaTwF2)#%6_+C3@(PpAzRg(C5C5jvCqT*3$$}?Ubfl^nRe!w8<&-p5hI`n*K&| z`szfR_abJ1%{SZZfu7D<(;eOD)r5}e@K~dE*CyZIrcIwKM-NH(H+{+Poaj{HjF9l? z*+BpFHX^th{(%lXZt1B@`;4~ZorW{ckS8?rf>QB z@))t|SVrLd_fPmyY;v8aB9_~+l&)lrCvmDbBMHx3MNB&mkgfuAJ`fCQ5p3plsCPe}9$odQik zJELQyO;u8&(2O9A5Btu$RCZ|z;nIxAo7C8ACOP21RW1IP&Y;M<;#rrD3hzL+?qdv>~`e+YVcQcan;(k0D8m_ z+OJ$MwG}KC;*q7I3epHqCw4S(6%XM@84MVLB8*7}0|Uc1@VyC+8>&_zGis8k=Ym7| zY@^^&*YDeW{{GlQ5X6Z4i6G_$E>xe0!kR4N-r`> z%87C7rU_I1v-igNYyDKm-?+i18_WrPit|nbZ$c1J1~oST;p>=~1cOYrgGrQxc@XiT zGnE@_w3v$C!K~+zM)HG+O(X1X#%MuGuT2Q#chsYxnL%FS;^$X)F9&sr7ThgG4Aad# ze)G%-fCX2BR5%m2vAVS_MY9^1=uQ@vAe1*;h&Varv-jO21yBvujVsC={fuhmsoc%} z_=Eo$u1j370WTIj@-OiR@$pORAd^+a$DnQly)O_~dMU77gh8|YHazTyS=VrKl$khF z`3jbFaC}@yDCk~Tg|M4xGn$l!F7nm6AbH<@K zT925C5fKTT8d7QW2s$kPcV(s7Y3CGk$p6`C0HTG{MIOC9xA_#XV&dW~GO#Z$l5q(L zP!c0DqG>yD;6V9ux)X2Q|MOzk2nB8xTlw$Jz}!_9J~eavbR7_i+*!yRXyRl;i&_ z;r|_P%AoEi{w>zyUQC#+252NJV5)*Ut6LBs{0u(|jN!5c=FLQ9o7!QAVJ@M2pF*nL<@RdqATXZ`O*;ubS_FA9~7m@1Qv zu;1H!HSCurI8jLaV0e;gFG?`Bb?Hm}=dz!YPTiMbrHpiW9i!XDB|3*~c=+DL3jLET znO3g#S!o zHy$ErstZIu1Yy|F*cf{|)_+|*Iv8on--eSDy?e}|i=nwDUB}uBX!DRILHp+<<%596 z$!U~lMGki60~6r`q;`aRFti@qeyl_-#(d~P@N_q_)@Q^U>I>Y)6&@0XMn(@o%}&$P zz`cO0=qC2FL+S~?-r|eAiaM?h^^w238v?@#QYz?OMA2mKhC8w9pkH%GeQ4C&7DL4s1{tW(q@-dsP53pavWaWu3r z^iIa5<()cxUHP*P_DZGE+X;yok}al_bE4A@_F-`=7zO6#+cEO2&&qLfHkQw^F!ptP zbp5OKS?^Iqdj7dyuYr7KYJCRAz}Tsi>er-9S3K_FJyJ#t^V@X^xcrezR4|m+DKiK! zHIdwWK~ax^@u5M|$}_`f##<}*|KKXGCk8>sG1GkM=bw6KlK}2W{l5khOSeF#!no-! z=!+QG`x~iR{m%uqjKaDwjpV9l($_7VoM}~N~0U!zn@C|%k{%T_btAT-d;JgGjHF02VuE)_jNP1i*%zj7zGmd33uEM z>rfzL(#@)L+6YZ~;VgPD;nDJN6!WG4t!BZ1AucvYI|Gm>d z89HGRGc(NhLHfmT&w7@>j&=UjGaij%tEc0)-u;C1%RM$@JullzDM%sS7}?4%7yUB$ zx|v=xf7p||ZzM1JWG}2uoxJ${Y3*H_k?Fd{jvt-TKNDVmnsEKC_sOh4BeU<5r_?oJ z?^6w31Hv1Dwr~JXTbd>#&%c)-$v|4&G2wYVO@roQy5p#*GA)x6dmZ^u)6K=(aR)Ox z(s8J+l-vU4D5v7ai*DXJPM)sOwTV)N%uRPD>?jft{8spxf%$e(PF%+I~x z^q_grQJ<3j*@|(zXTN&7kW89EL!Vym^|IT;4;deSKBLd`QV)i^UW!#$1?h^wnqPsk7}xv-WJsfs<*kmZgG+ zPlmDSov5QJu}^2D@6yS7$UJb|#PzUovg&KbuT$cNLj6UfooReW6IM+(V7y0VzjX1< zQi~5G`xl;AbKk16~?TVfs!($nN?3=%{=$3gG z?X$l7^lyo)zW!)UVe@&aZI8{z)CwkhRh^wz9g5T%}&{SCYP~{@Jwj%yX)8#u-CTy(yjIUYz;r89Co9$)j$-5xa@g`a4Un z#&H@sa-}-Hec~zxWu~vr=^2`&4x4u^_(X93YOt1Cs68-C?R4CIAuJGIlFv|R_i*`< zjqa3nr?VmA25ZXMqXGfEi`u{Q{2Gl`9=kXg_V2gJ_Aw=MOk`w;NUe_Ta^E84hI1jX z;#VoaSEv|tI|&t(*8-GUb^~Q6e_ZS8*U^1Qx!`oBbE|Xul3L2D0#~p_!;p1^>^`;Q zG&g^Em*_aPT^wBMigg)HJ3oOgS=;+_ekLitat-4s)WzWazxWK$pZ{^#^r_bwl) z*&K=VYn}aWE%k#r3zfyEA2QGn=t!I2&}CFU@WYldyXE_2x`3d8+l^?2h%%ODe)Vwg zt%BA+%-fw>M1BlUw>3Byrn^P?%+A>R*k4jpIPjO^?&z0JEtaQU6Rv4%E%uD8QJgq9 zVY1)Cnnx6eNL(JEyrP*y7FVu z>&dr!4)Fi{44cd2K4iqB7Wg?8g{EZb*Kb7gR!(;_27QXCpPT4+v}?21j>t(HU($(W z|EROr^XvW4a1tK9(QL6W{bZ00?XuGk-He(~cGnvi>#WshscH0M`=j3L>!&5fWz92X z?DG6-`!_(9Khs)d!rL>Pa&bb>y(oxbCu4?h>N&RV>F0=3vV~cOLIwrDz3*}V?vd>Y z_ITFYET_}-ErX#m?`RK}s4j z^kK>nRenoe6&;t+IK-(R`CRvsQ|Nv1HXB+yo?rKpK01+Id44oKhVtdL%9#U624~C` z21uy|I)6sw4W>@4=^w)~%u;VZqipHu-p;TwT}T-m+SM>8!q}Qr`KIr+CfiMkk1`Ya z2%H^yj|8ndf?T`W)m$4UT-BYTxHGDx77ZF&g^0~?OKdyk$;m-F`I7YXM--1nXe~qI&|`LBG)w&T(wE@o zkXozA4yUNGO2OyQ%qj_(-bV7JQc@mNPl`I-(8?Og+MsLedOdQ_Q`;jlue!Z|>|sy- zKIXib*)uM%u~4j<#bd(wW7g#f^GDCG;S3$ub7>siwQw-W3q$PlwX`Fck2&MB*m|d* zOAUAxdHE^on;IlO6OnTYHuiS7&+%8zRo?*T`f;fD%)O@rKlw{$q_w!Xoh;^*hm8G)7HLcr2A#C+L&XFLuu%RWJ zXL?_}&a3W;`)uMy_^;@fM|QHt60bnu*u#Sy=5mJK`?pF7SYx zadJb&spx}ks8EMfS_WTJj_H~;Jq}q$-&rCGzdv5k6K~YGd*_RobV~imr?aVNBN;zf z;2GB17+m^^chWUKCZ%1Co#g&#T9n1QOCB_Kh|CsG)|thXPKgyj&ONe*%->9j{v2= zd(U%&DJDFHl!=7d)~?D7uGp^B(%!VrXC9uJ4=z3INPikeBsC?8Pr9{Xs~m=o18gi0 zTh!|-m!sYoF1$egsHLee$fB<-Q?ybFTbIi74r)zGO?FtnW!H8k{_}vl0m>61WtE*s zVqjp)d9W1PT`*3IdV`_&xZ&;~eSIEfSAUgM$5D|-6_bt=MsMO5+>Ej`%B`OMokJ>2 zt`V&J{q|;2F1gZ?ira$RZ;})uJZ-xWKe67vh0m|=*F?$bdfX_@`SC$CPJfm2^)qU^ z%T6AdkMZ(ad*uG(VB_Br=U3fqC?C?-esq1fL}NEc$C1t&wt#CDr{3}e3r9a*{2%h( zJgn#Z{re6xm_Zn0OUk~>k|N5!WnWq;p%L1|N61pl7>zZuw3j8?R7jE{qfwR?RFWi# zq9i0rsrzxp_xfGe_4{7G`?&tN@B29Jt7GPS_>NDX&-?R!zh39-JfF|!`8==nx^1}d z6o=M;y*E#8@K_R}eYI(5Uhf2hv}psQZK~B@ZitgJIe71`O};YlL4DBME9!q2{H{rB zpI87wXJ%m%lag3`go@b=(Qzh%FYl{{wO$L%%?HQjMc}G4(=u86O_#OZX?Tl*TnfR9 z57uCY{4Q$B<0!m*g6duX{~q=93d@a{F+N*c|P}9H9cb%n~HaqL(iVKh5s1?jz z$V!=CG|nivrmMoBY|x?9A@eS5T0d>LfydEI|G1}vi+cB0q}o^?y*H&GZ^)G+Kk`7>l^JhKLN%}X-7z%pZ93?}ml1V}(Z+_SpJ*8Wu{d|; z?1Vlsxu>mHhP&JB-(=wgjm|ytuhr7$8oLo|~3`6^Gyrb4>>!S3s(9pA2 zI}EPXZKRYoq~@u4sC%N9wa@5T_nVYlaw(jcQI(*)J!+7)wvn6ehrbrZ)J60km=@oD zpi#f>-6x=co9?9VKr<{=<7@L1Qxy|-XTAN(eAgw13E_I(9+{2p z8E>9A+Q`TJ;qfF3fknniZaubJqM-Xz;uEp8Iplj+G`{ zolKP%4e-EkbuM(wjYsbaqS=d;H&Y{avRD}on-;n)57;Av-V+;DcE>R6(X-NJ zMkDi~Lq}{p0A^&v#S9p-CVrU4JH_(WEscCK-WVDrSKIkheY&sl9kkb@{gA4)Q!2YW zcr~CermLfOP8(%YSCu?26bliW#sgrEBH1t{V5aWYG2L>?Hk9S#KY9_jXR)aU8P9^> zb$s(^J~jUWD7aqwNF^!p7R7HmFMmsy=#vTxhRlp_B&UcdgL#+6q+;IK;kHa;CzBzjvAo`nk*K-Icmgtym!K$D2{ ztJ4`V6J8@53g(EPpPg#9CwmtysUa=}C3$f%$g|hyZ~NSN$8;m3V|W&xKss6Z>i#7D zdh>_defJltyVS15&uNxiy@A0I`V>y0GlsvN1%}ezhk`-aKZq&7!+t>JQpu%6fbP40V zx8e7NUF$>f1EsqJG|ZT*@gBAIr0<-dwNLPVXy2~gDIm!H0|v~%8iVE^%es_(syYjp za2?ZBSv8pZhIv&8y74==Zx8EgY6AU>Vn$u*`uUX|al^1@R`8vdNW@PPsqm1KDb_-qZ zFO5^jFMAtnVjx>#1gQH}_=^Gk`$L2IhlYh!-ka3gD`Drf)fp{__-__rY3-La~*ys^__bfi%pT;u(<%RJWe?8f$1ZZ(XMg{+piv1P3ZE95}6ESab3G z@Ze$a99aK*wF^%cGB7fcJ%?sn^yzCCCvzx zBO$YY`j}49|A3K4)0Z#n2BGrd(-lC#x(V9ffn^& zvTuG+8Nbj+&GH` zcI{qpKiHeAxSN}4nwX_&W876P94vaFo0=XoL`FD$_|4qu<bwa1Gv<58nLTEo!B|(^TH}aF%sePdD9$EoE~4MkiW~;&8SP zpMPp{#H zJa`<-GZP7!v|JpevBW3!3{I!gn4M(ZSO0^vU586$ER#8b&oVBt(uSh6w@B z5rH$GDO*8qE;KXqRonJ)zK*Ii=!uV!nqrYPY~U4mJjaaLBSX%dnJSL@O!t(a2G3XNm%$do_6jP z(Tf~e_$6n2>>sdb_bHTCPOM8yH}uY}x}zh{)%IkpQraGzsb0xT2%8}^vaE)jyi%~M zi^|ozrc%)B;`$K!4QB zE2R6RIcscg-t6eIv6zcicce)aUzn-kisEv6t-<T^d&oD`Epb2M?;r8xiJ6<> z0J`@c(s~N`dGDE?oBFsV3+%SPEG`bh3vbiDpfhJS`-YK9t4)~x)n>W!-V{D73mo1p z_vvTa_;LzW7S?MNBjorq|%(;G}Ph-~7b(F(+pl>63v-JGK?Dsx@9bE5p z&>D$e@rlzVYYGns(u;p8a=v*RN3?!h;vaI{jC?iW$J%*+mmPL|ramyUpk(pO?9mT& zWy*lBmV~ymMqzX=pOyf|aU%BA5KG7Dnp{ojP*Z&U`n7k+-y;i)tg;r^xpa-XqBa3~ zB9jO+!YZW`Et?B)v3dxxxgP(~jJC7G)Xz+hZgsj#i&Z78-pcZPi;?+Tqo$dMwz90N z2&nhGoBH&9O4$Y}km|z=*Tw2aOt8$JWSwJ|%O_zaT{J%oVf(r;zmMi7#ui^~7Hq6- zHS)=E7GCGd(d?;;O>-T+OYXNWE>EJPm@`3XYMYp6_~Q3c0#QrOmO)>c;i5$)ZKr#s zdJda}R^%Q6Fl0R^aIu4Yn+Q>16JFA@kZF^3|`e=&G z?Vu(xG&c_?^IrAx&QVkz-qi;AccFO=3=L1?HEbviIu{|P^PGzP+^@AT#riRvJyD90 zfsvzQG%c=?9!oZd)U8%|S5c9{e~qBCei6*v(Yr4n)P1ed!jMdEud?eTS@lF}`Oue8h`F$9Ey_z>sn=zY~7yi6>oE(P&P@xqZgmxyG2oSGS3jm4v+W&z(D8!GQ;H%7#Nq zR*XoTJu)wlC00VyCt>O!o#2wAhnvR{3ZjS49Vtc$xYmYqp!IM~JTWlh@fMc*p{fPaWady%on3&^0&l?&eGNWOt5;@AuQ1jarP|2@RRmA~1 z9H9W^@bpSsSCqHz?%*%!E_J7120LwhZL^277TU6X+qNgj2<{X(yz;h*xZic-lM^&+ zdImKaXR>O6aeMXA$8R)=dl71V*^zQtX;ha%Z!_`||ENepr8I)B$yQxQUz}iZB47p} zhjQ1^4AVWs{i`@9?fWGeL2lC?4d+5hy8Ipveu8l?LWb_7z}hASnZ7vRwZgL)h73)S z5%m*a!spHIg%*Z}V&DRv5{xxzhe&V9?l39GLSv1sdRRHNnqV&|&^SY#s}A73JO@74HWeRZTN^el(_E zw*e33oOpNm@#nV-HU@Z?nsPi2!1)=W;c=AvFve{nf4=F?bCsQo_EKELY|ek zuiKh$qvU&l2W;T{!Sl+Ts{Mn`6n*6}U(X@!Q#`P!`_PdaFbCfksPqLqAsoL?vb#Kk zp0|u8Q5ZqKZNByWO$3v8VH`rcT#2yl(x$j>+cobx^)RkGH0+0IykC`mTeSk;5lBuc zhzIoSIf;4%2NE5dT+b53E8{VX7*(2Hv+(?)a6v=Fj(@%^i=Td)k6dA=AH^ZMd|#H9 z+Ng~VGB7Y$Mbb!8HgDa!3xwnL*yQ^+eKum}#@9iYI+|;ocl?#N88^&GtnvD(O;0Z&FAh8GqM`h5suOYX`gf?2$dCRVg@wW_@h#3+ zD0Jn0xOWE2m!A|U!J_tgM<%eG8P-gmq{G`Dx{c=~Qoc*xET=iS6+ttDLo_vG(Qk-7 z9$(uQM-J4Tl!s>7(kx>Ot+^EwGd)Ow zJK0gJ@wCtm7LE$Jbm)^-w%I8#vaaKt&A3hcmFQ@6iyF!INi*L$?fPnQk2cfo|3$YwJ+tFekQeZ*ZSv1wJHE zOwH((W#6Bw*6Z!n&r9T>a9>X`SAuG60il0vU6my%_*}k(A^%t2kSv^2!Ww6{B&R_g zsKFKmqOF!H4N1UbpfGD|>lY5A_SxC9x?5d(zYRnOv$9Nbaa<^I0PZ$;(Z%V2D{2+; zjg*QtZuERM!i@NqRK9KN)=WlGfca(n+#e1EMb2hKd8${^(R}@(WXmX4nOidN%YXkA zoOS!|-G%(0KZ=<=5zj;5Bsr5?ucH+)t~1Y{SDUR+eu@OLA(}wiPQ* z)1(kWy^!TIKTP9t|G|T`tSh@L4hjtHH)_HcTTd?&lM$bUls$Jpi1{9Zq12OuxY@!2fWs?|9`sFuRY483zs> zI?sjDtr7<`6$Np9ARCzK`Zd|`m6Fh~_2i>2<#91uRsbWTH@!P9Ib&GX079p$+UDt? zupYg(k=z1tTOP1TV$2PnNJCE2JT0; zCjRzg@`jPkn|12u{-OlFvY9cf)Q0t=pKGf^SX3fHQ=&gS5sn3w5xDngFtUu-S z5hd)JaMP%%n7N%^UDUdxib^P9Wu%I#{sQtRDNQu_bM&?oOhY(}BhK{DRwKmpm8!x9 z3Hq5Fxp&(YZF3)P54iPTq(c5N;MUQg%&F7>t;f}#Gt=-O{48;EPVLK6`Cv3^Fb%@{Ual`S5z4d{?DiQNC*O^XZv+LG}W^E>RlDIdVkstyC)G?r4Ua22&J*TV~#$%ETo zp89-4TwYNR4OPyJh0B(mh~3xXiRUm&L2?Bd7@4>Juv4dwmyw3w{O2FfyYgP|uAZ|i zYn%;)r}$}H6V{P?;ENZ(869tU*v@S(h5sM%)c+4z-2V@K&Aqv08+`UErKv-*TzPqH zv97gvsNl0oF&+tsf65C%z7 z`BcNpMz|5ef0RKdMGKl>fpg{UmC^=~hj*B~=?60+t+pw+1M>Tib z-eUaHrAwm<<|zulz0a<9%`cB1(Oy|dIxHuLdo--+RTPL0J1&!jWRZ+2Oc!MQjV6ts z+1+&;Yjk_6va;Q`kaukeiBRJQCeugQJ{n4~s_Z#WYo^2>8p7s78XEglw z#b4!ZLlPWQt)qYW_6E*v%8zfqA0GE>e4RO|Cvs~*e5>xn!{<{a;$nS4gKfu*0 z?e99qNDgSmAKA#HS5l*kk5Ya#8$~X!#nDC8v z_0;|1<%!#F><`ZxN70w?E!eMAZ58z`5d6P*T->qJPzqvLz;yeVT(nDc2Hq`j2!_Q1 zB?Fl)>YqOov=Oa0xcNY`*{R9YmoEzoEi?1%V~_+d7|vaHZ1G`cfJa7Vr1r5tTa&u;vEr>AdQK?=iTo?2_rus7d*gmZ0G)TJAzcxUVE2tUb_&0W4$PTfWc zOWpqm)5wlfpZ5nLc4r*rkz>cs$ZW`@CucHUhT!QJTbEy7<07f%?5H$f48gYS>`AU~ zn15|sX=;^|30$fD)k-6o*2#z=I%uPk3o{(G#~tQ^lpMzP)V{i((^n^yUq_|2n*(5f;EA_IXw!)pNw)O_0%V9*sO&SrT`Rl zx~Hy8ekAkM!gJj+BIC8eoH+-e>3}=?`INmbNfgNa0slc#0XG zW%&sfAhruQMfH+SKi+;9Xv8|Yd}rYd z5vODvTENi@CUFL1GZ;YqXp1=B)UC82d5JYqaSZdD`IBPKtf)j(ysgh8f<~T0KGp1WcoN|NcE3;$cYoeLAx{(_$*DJLJ0l10*G3^)(6g8F2q{b3wQt zdd7hf;OQo{9sB120CjtkX{iV3Gy!qT1isv8>72Jkf96ch#!)00dUaKWNxsL>bqG;^ zT$CGcpO|73DJ&^f?23KanVGKutViAm|Bl;K&MiC&WdiKJvUjgu!7MR(XW@6T`xVlZ zhJgjPwr8a+vd|NAg#Dd{O$3<~I02Nj693B??gvzL1b(OYINx)Kervst2ay2u3DJHP z3njeYMnz36f^t*EVs8=yR#tI%7qZHErxAE%T5jdyWh#SwW9my9xbR7xjzD zq_Ok9KYXrU<&h;WUmd~YN?3UJg>T(yNP`<7>V5p%g3&B^9u!jE}1cDN2yRBz0x|X2`+J!5H0mQS&Bq67Q7AP*KqQi4+JK) z8h{y#=}sX#>3sEi_rPZATjxO{v1bk;$E*ZWSdGcJ40v@4y+7$Su@p1-KkJ~ztnq*- zS}k`BW+#$%c)OenQwUj$&Mn>1Yc)YdSS*nTfOp-3^xDx(?H({<2+U}DJ2_>qJMDbe zeC0nNho@L?TWY^R@!I-Zo%?qRge2|oT>H4$GOHMgQ!fhEIUMQJ_a^+bhCq(=Xt}L9 zPuQ<*o2(yaB7ku3#Usoy$esE?_$EzT-sAH2M;ZddEpd9;9vj@*ygyU}A12ZT$jaF(CH8Kw zXa))K7u@({(h9YNx-Z!Y-a(xip;&sq#TgBy;E0H02D!byaMaVLd`#pLK!noS$X-qw zmMT$K&SF$BZjAHl9rDSimd#^QnjL8jVgi1@Z09ukEm^krF&aE;@wLPl#Ki-*+W|4T zcD^w>+CHhx|4uPOta%XV;CA6!c*(V0({^4t^U{5vQmAu%KWGEn!=eGCB{GxYNtR}z zS2d7<9qnblG0#z`NY-Ib{mm%MB-T?n;*>cPIz$-!rY$=yt(CFUu+7VM8lXFikwMf` zmm2qFtg3xX+|9-9Q)QzvKx`nO7zPBQT9fR{%tc?wi-z3!8$25FI#N(t=jyu_C8Sah zctBcMmK3Hr2UWyM>atz2|FcHab+_R2Yo48c{8ZC@#Mbx;!f?a2D!hFYO{Tt zHcK;0)+6}jbrxIS|H-ed$&7*2LLWrMmF<(aPEHh-TLXGeNyrVF$0t@MkchOpaY{f} z+?iVIzS}-uGe101$K^{#z^|Pg9CBm^$G~)$_d!ryA~NIBh}Mv3^9vuZ8OM@0z=z{XBB`u;qx1C7d0o zDRlIsH~yd*)?yMmzd#Zl{m`;(iGYw63uK@OuDoG$$5v0yHdE{eh@4~7{;)xfDt?|T zPA$HccJaSdT?~t~NN^Sbm)ho6-GyRBFR`HP(q*ia%{kOAvXZe@Ja4RC`yr8 zE+2)VLW7lw3QnXDGpwC98OJ<-L&$Rv1c(&&(p{zg4Y!lr^7nVmi+$0vl%gof0%Z?E z3oCLy1_g)~_9*f#6wVdhmxzuXI;z!;o;*?!$0FsF+H-z=MnGL4aUqN|NYWgU!{D$# zBh>sS%ZCtYB6bp$h)7`d7eKM{X+gZFh%OQNJY=Mg955mx4Z6C2H6lAn4k9i;|GDB` z=an#Sj48df{5*y-^VwHdNbxHFX*XB8oYfR-;>xt;khgU7>?K=J?omW+kqV{YKuR5| zsLf2;)ho*Se51vXRVZSw)PA@N?;D2bXBKYL_h5xm7A}6n8R4FgkbpBZv$P_yT(QR7 z-Fx_oJx-y*9kB9e3o#)AaJ74LK+se*}e%<*~gdC9g9+iG1ty&V%DIv}sGYGiR> z-@wC-Lw;zvd;RGFZJO@yxnca|$yfTF=yz-04-v4%Pxol9WeQ*MynIw!@Y_ARs{TWeduZmhz^YTWS^sRB%R|CbcJo^VxU3|zN%ZTA5K?&u6^_|$dg zHBR+0m;bsoguy8pD4-Y$_d6UTW!CP${#wdbOq)$Xz>l-y;)m&zoht|`M8jsFXTGBy z_dr{Rcl!nS9y27D0cyMds!d>u4QtCcvEluDB&>dXsn54R_UPfb;QjQ5H{*Xw0_|*i zIF7dEziGn==JmY+Job$9R^jTDvCSn(N1PuSTWQ7TD28XvDCM23B~3dOaR-v zz}@@BZR<;+7XS5AZd$=WF$E;gI?iOri}rcmu(UXFZNuzhXR4LLUgO)BH$HK6S`QDI zScaxVf9~Am+*}`$NQ;<(!udeQH$nJj#cWWV+jK@&FF}`b3I_w<0eaa?AWJ+LebR#N{Qt(nW#y) zk?Zf%_usiQ1E7F$r9&ZtdBLC#EwFRu4-6_$MXp=6K}pld(D2W&uz|o(<0}XFs4z97 zhzk9aHD0URBxkH_*iHy?f&VUx9o~ zC)i9nOD)x_Z{IQhyxA~@MaMhHgj2?vPI_t;#nkludGxjv@4_{nSu)UciFbD4w0$5*` z<2ZzaR$~Vb-jDhV=w$lz>D~JDp^-}4vl_@L_AS>*X-#A7 zyV~2^Z)HRq(;)splk929NwJIHc0Y1N{H}OVJ^S_hE7~Tzu?(VxO-%iygo{1OotyC+ z6pBJdC3h#LuoJ1Ar!a_~2ZnLWeZWI7S())}v%fKY8D{{Lo&e(UckhdQ){K5(vxTL* z8f!EqR>)~mT|Aee8AXkDNi=OPwKL!4MrZzm-mowJap(mkwH~+ zRv)3Q1mT+gj2S0+cjeFXbNRwdLDnHPJRKZ-OGhSpG68!mi~jPPJ#zPDu$7FYHb~#k zNC5Q78?5_(Tldi+n|fvYk-aQ1F}Vd7O;^D(keZfix}Frmf<Q`x%>0q# zP;q+=UDjA;ywVTSWGVd;xFQ`P4G?oVeSMj`QgkOsg^aN9Qm*|e;>K3e5Bw8#UNj<` zmx<)mCL8B8!dGY#y$Gr8XOezfk}VjUU+vv+Uq37kdVa{vnD(ty=;qs$DNJnn`{vC* zxy8c)CX_f`WDX(f9T845XLmSl9vom!i0D(+vSVdf6UifPIGV@`z)ZKNS|#S@cESD$ zNmQ&|_$8D!?YeeN#pB?zwD>(Yu~h~j2x z5qbV=ho$DvY}yC@0&eVvOt0;^_71-;9arvS{R}s?}YN) znAY0~Ut{(iJ$!f)?n?8%Zbf~hT6!NgX| zF?^D^HJ_BSin{>`fK=U7uY1=_EOh9uy-XU|d6dKP#8Kd8r%s;y9dxG+bbzaw9S@K= z+q>cXZCm|5n7wxNZr6S0KFd0#bw7T^WPV&^MM1h&Nr?sXsX9^zD-ZKY-EiAz;7Y)X zwC=8kBecFI@9V6%{WZ(X;_bm#VX3>LuK3?~I#9BxKoQQxiMi)$P64pHzVa`tfMEc) zZ8gC{!0Qr$l#m0+|QiIBU(?E<8ITkvc-*ZY&h-n(Pi;y38b8(ml~q zWyCF=R1{!N&vrEP1YdIcbol#e<##FkwqtKh`hv%L1YbhI9>s|XLip(FmXXNNts*X5 za3>7uoc&PUojf#=a%~E-_|5=TK9lAr<>mQtjCyC!+tw%jXl8uuAVRk22*v>|=*|_W z=S^-*dO@|dQH5DpfaL+Dx{pEQ7{PJ}oXCj|piQq%xTd6!X!!>%P~Z|MihHxK3De%L zyKqarsTw4ahZu#%b35K~G{RUGSu57AEjTnyO(xAdyH$(&riofGSv2B_V3EC!jp!9(QU#mC3XG3SKX zUKSufwIIAN!5+JJ>!w7Ji(TV&R8;@aittJ|^YbsAI^BY2lFU8k$+{K*O;+;*t+wPK zC&r?%J9prEM#f=Dxz4|8M7m?bA9+0LPhnUq&5i}29tBXO+PQD@69QP?N2Oa( z1&>qt@r~`|*mZl4?5ng12{6p?+#FiA6<@A+`1s7^DH2yaRE_L9H3f&i38&ko%a)v| z->*fI5rf7|l*7a%b;3hx`qPPx9+FR)4C+7)m+~l@N$WkwjSJw;SJ!rQ6`LHl;eyhZxJjxTy<%a!mos?wrsB8nM9!-`%QQuy95g$|@79a0R{mWeTIkaoI zxEI%)248N$S=yvzZ0?MP@9-k-!H%4DdDi!i?@-)&L489qN&+b~PDvEbLPC zSY2J+Rhhwu6ebOyH~Cu6_HL7}og%Av!25$|&YV77RI!u+A3PFjUrt-BMb#reA7-9- ze(2UlTtqgNhR1ArdDK|^1Jl#p2=H}%E={2%;^)>Hw>{H($l~bC zxsfyul-|YFXHwrn-hkgH9 z(3fxW{U>malw1Fwf519N8mY?dtm{f2?QF>Q60O_UhR) zF}7w%8Yx)L#np!uRpe58Ugal@qhqZn$tz1zz-L!&IvRUo0t~c7Ka45p%A~sN=WOqu zNI$<9y*(1TFLLUoOnZVH(@JD-R)BP*EZg~DC4BXE@7wnRjHq|Ne!&~EEdqg`Tp@2p zyG91P)Yp+OYzNEvrE}-oFaWP}qWXR>V1d?=G|qiTV(mb?%XzfR)E-l|Zq+4uPfPs% zu*|Yq49(DauU8g#Y;+~h+W0UaE+Qh!Wh*s~Bs`Zd6LfcwbWv{naGWC#D2v?feMLo> z-VaLuLs9kGH_0k$Ej1PKa@D=#fA`iQjd2ZEXf1wAHpUUNkGhOMZHVidIJD%6)g?0Z zx?-0)SH8jnjt?aO@0oMvC?f#g>FP?qud0ZXIgx&rd5F-Tg>wn+?e|X8_Sp~T!v(U} zZ;*S%-Zm_jWCY$4L1nN-!Zn3A@CNxS@JHNlaekze*3s+UKc7Ou%nc1B4OO-~zWJpg z5t{g!*8f?4z^9z%X5}N%A@C zdunSRqb{QqQoXbRw&IYxyOd(&c#ILf*z4V_-CMNd%onmo!D>j({@YCRwQ@J?43#}7PXgZx}Z9RapnsZ?vk|N;a zxzrp=e67U9#6Q?dzfhKO8gM#c#ClgXe`rg8r=rf75zM7Gl{~+@o?af`kJbR3k=N3p zE5`?T&nTp-le&DrnU3?{Pj~*6fNx3t0ec^XRG8MTDUhaBcP;85n!96N(VR1Cq;Zox zm-??*P42#%Aq4I=OKA2g`f@Zk?mSWKS$10Wln z$fN$Tk%EwiAcxfa`E9vZluVgs{T-vL1smb`DxxRo1!7hf|Fi&+mYT-Ej`Rj(ne7TN@(xB&QWgtt%Q} zudl7u$EHBynBpwU>ZUfCZ)kXvS>LJJ--7Rl(o@e5)%L>j`wME zgMhCFi&Gt81tzJ6?$u^=Y%y0)`*-2nw`s_61an$`-YjG5Akzyw1yrI9q!4>{&S_I- z07zmgg(q!?%2H;aJ|;C_X!0#amI<~*)X^?~$wa`u-MjCgv4MWr>4t{w8E>z&l;OZ1 zOS1MhQ`@Ap_vS>@2c)b!b3S9kuf+U}eE>)7)JM3w0t}DL{dQ*EisTgia4LA)*aKPC zpq=~4JT!|63K|&%?7%N~?C~#Wk3)TVjuY|5U3y3w$=qSue>H2GFcEDhmw=Y!Rh#-@ zR7^+-Ou0sZVx~^LKtl=AnN6ggDLv)`6i!O;&YGw7W7y-fMg!SF&q*?Sj2h($6?6gG zq$2)=jh~yhrl++Opd@2!@nrx|)9{J}djT{?Hm+?6_)t{Nrd5L8ZFGw%|%st{Sh6 z6?UC=O^V-@XP=yxm#1SJ+JEO(3-&IyCj+sJ(5x-3IDa94-1ewC3TjalXl}E}s*gd^W66 z4DQf^^m7@Din+Q6U|l?cO)jwZAYaVFJia}bTJKda57oW_0BS_25x4asw^XY_+8C6` zm4O!yJkA@n{#6^`#N!wXjCWji%BqX$e!`?{>D~5|BZOG;9kcO(udk}6QAN^a?~#E_ zhO2W=JfBeYyamUdLryxwku3p%z!gEhWXG|j@sV~Tb!LI~>ecHUU*mD&1x`>&*GLf8 zIyzqc?HX+zyR)oMqq$Oke+BKoFH>djbeAKo;`5M%T6akAd!V*dZg&6@WP~2I{Mtt< zeZOtt1PyA8^azAF7gyc?o${?B-cRlVx{j1Vk1-f=XAa}Cbk?@*B+uO^ z12*xdWF9eV)Cn|_DFD#;1T=Y8Rwnq%>T7LnL1=gesV8RJ!9+`wp%sBkZUjyHb?;oq z&0DnS4ziPIW*ePQ8$jBkt7iJC zz6s3r0i~6{LM!PNlVdw8V5}eK%<`CArc}z*S#oOgik06trsJ)H7U3L%50&;Id@9b= zk`kkl6zhVcknABj28E%o|>;N*A#Gx&F4jg#*6=Yze zPE6$6<>TWc&yrM7o1QZY>z@YhoyDovLvO$7|x$C2~k z6e<1KpFStl=dqH9C4c<_mn&o*wl$^xbx54yEfa^*Pg63qe%G>2j3*qXWXZa;vIQi;np`GlTeDHS zz@G*#i(Zsk3nZ7a1r^Lx#8T%0BQ=NAn`+gkm5eKESd1Sm*A3e@T6xx?(x<4;VjcIAdRKZ-I*Jb)N9w$$B=PMKz9)rVTjLofKs@#EVutsu7| zy;RJxIQ;FDmt%`1g=SQPVrw+#&R?Mx9r<+8*97j*{ z*|d{w3=&R<7tK0;CDS=0_azSfqg*5OIb-}LDN_<$Teu@>`S~_9@v3fc7+f)5QIsLC z*;-y4UQkxH?PfYH%$JK4N4~|*7hi%j|M%-1jrsHDjTd^T({`W~(iz{xe0>mWD!#OW z{6LPNg@%SNRkbN`*VffK6~Bw5arY-o|JN%sxq+WsLw4?&_WU??E?3%?wL+j$=F$eaH*nEFfJp(i=J9l zIeqr*m)C0ED*pRVTW5Zm7Bq%XTvk+FxoDTGjmyC;vXR^A=>kL#T6}3ACI!H5)cmyY zr%H+{K*!U~17WyFvK&LSAPX9|Lj^e&&VhVrWPNib@q+NlUI=hhbqRX zjt6Z5!t6U{Om27ks2n9~H)?s;C!h*Co8EOpmPvf=v}*#EQKo-gdEyBduF7x|hIN=- zIDPia)n%Pjb=K_!m>Bco#2073o`Xf z6@d)gZkebQ+Tv&6`<5iGLG-dQF^lQiZ-*u^S1GpaQf_l)TUoFJMOtdMqdbtkYyrFf!{=7jgor>VUUI-@bP?aMLCdS8OANK`$1`Rk`w z#|Tr!P#Pq|#Ih<9$y9B2m*Aq*kcT1eq}ZZ`+AH$x*+4P~a+(a<7Ervi!dkPMto~J{ zIDv+YdxW8n6j;^O)o0D)j!CH@)Pd4jlk>kzPD2_%f`@;{MiSAZlj=FS=LC#RMfaLw zI1W&|NIQadW0E^`3r&%mHG5W9Q{I=fpXUu%e1n!`VgI1ZBJ?hXkn{`5#0}(4W>1*V z2uxe3Ix8QJ#1ANVqlnf7QypkslB+^al?bh0qz0tz5-MX zSMxBYUclpO21=k?si|N`OB%_X`0IoEWU()U6{S!4MXyn7dm!eL!V-v?EK`=|ylqyQ zmTr1Upof60-5IEXG8>(mnj-oh5CiL?71iBI<~qUDRY3Dypq8UyF_t=vlc|TM=3#`J zG*iexaZ}{$PU=EV5%&2E3UUU7johnHqKLwJO7BfxoCh&pbUI_JU$oP#f4F$fc|2r< z+a*NE_+DIDmNJ#*e|k#b0d#z}Qxg3Z&(Y0vp2@YXIuJh3Q9NF!#(@*1Eqs357`CSs zzt2im${M(lK^@i+dq|`jg&KEr+PvBQzbKBZcR9Y}!1kl4k(tqy4eu%|R{(4)H`}=J z&7(um3ERoa8_9tP+0fOfSm_BiAnYta*oi{*+JR~PbU?< z%hys1tG`!L^XNi-5cN857kmPWxm}kocZtkNtP`3DegcbSkj`-GLrhri()wWa)OGLP z7Ep5CsEH|exLJP_vd-n$nlT1kz8b+NBi>0twIGw-b@G*n>?h*mpA2$G^zM!DsQ%fc z$KQDC7c~lj-h9GrD%E#;D|Y#U^YDAB%fT%iFWb}U9&7lThzJ9n*xiLfMaL{3%~LHh zT3OOXs2<*cFmt1MJ|*`ek{}Vbmz+GBWvx{R7vSNWxX_Z+lGB;7K9)(KVzE%hsioZg z^IJaKgNPQw11PKvQkb` zkNt>N!>WdO9(AxtOiVt$>VvRD8^so52#={OOH8tm}>v9nF@1PyvprJnQen$GHat z%%x~oU5AFO*)zNYZf0auxEHgV{1UAr!C73le5|beG1S6cH@HK=zA&N<0t z&U@-q+|@qzWd}hbum`)1231TCRlj^cH`Axx?75clOM4j+;Yj4sq{JVIDU`}?6eRv6iM&ivUlEn5prPGhl2 z=(g>j(KyOba5=1nod7A2T?=!bRkF6a_(#>BO^p}ge0A;uiR?06iS@9mR2)rYk~yvM zsoF>?ib@8p?6CJw)ad6Zc_<8$K~z$B#-{8;hEyim$7EdFwnfdkYFTjv%8D=U<^Oms z>%?Vy)}Jjfn|0Qv&aWoRs3s~A4G*OZzfy!yzl%#vZobJS+s+*5#lW87Su?-at{P}} zJXQh1(o~(cjAP^uRncmU9w%+3$XCvmSiynvgUs0zYD&49!^$&3otmH1L*l7KDwM*h zl-!IwIFPs};PIcXoEu7z4h#a1thS8GQB{tJ2q%$3+WvuoZ9eB~Yq!e$t%@(`7A%p( zNVTeexDVWFYsDCovMsSsD!zRA@{789d7H?)2!C%*YOVL8O_)=SY3i~}T6Ux#!Ro1f zOw_iT4Imh+lB{cRypbH6i~WtlQ;;Hx4T*Yk1|Wd|hf=P{V)aQI0lEAP4#dCz{+n2t zz3d5T+)&iSgo1up2^eq761Im6cKj;~wTv1g!UxtlRiR#$BkD5AgQw<7Wl3aE=V%+R z`d2nWUKUG(LeHxF`mYvrN~aKUA2Iw+DnMBnkO>~Yj+Mp*>APAQl~aY3K1C=lB5$Kk zI_rALm^&FcL~2PPCN<2b%8H7_<>wvVJ)6)n@px$H9%177mL&VjFI9Z{RD}QT3w~Xa zGislM-rjeJI7)J6JJE)fl6b}sAD-RRdB|1AgQFp)loK0eh1Z`URVWDkRA zS8|nx7)w;~)RP3%+niXP#%>)&wWSpQ@xjb^RPa_?Rw7ulH?Najsvn&42l zJwmD9MxirACoxomFx0a1@SPm5?{Sf8hq3?_Y1gN^8$Z69Pq${`xVrbPk8h67B7^RF zsUwa+{M<@U`5%j8!@(x!t^>U9XyiGLL`>4{u8%>aP9cZgh0L;{F08KZOj4*=rHSS{ zF*!Ne!O>BRO}$^LTq;c~XPPs1xw^VaZCh1U)roGOg!kx5RhY8FnS6-CbQq>nO@^Ye zk;)ryz|PQRT1ry-N(svrvjY_HDjZGCrm42|-GoF?B5BB0Kc1VzRF;D`XHAKBl#2-cLbDqy2>Q-;w&s_6nIcZ##3=~8D8 z`D`y2GPeEVWcGMyOG~hqrb`JQDwO8rgGt~l)&dNm?nk#ZR8pN&NTK-KsT77@pWnS3 ziUMXI0H6wGal+Cn~Yr06jI zji`Zyb@a%%J^~e3Ss`Y1&WZiAMB%olCgjKKN=oWA`jaOZaK#MjtLFk6Qcu z2TBa29;1U!D}%9}0DanCXf(5ddpM*%v6Bo)VF5qv)6vvdvo2* z;;Sei)r_|laoWR&`6W7j055p{H7+*Ryz*L;#*H<`WNUH0KU4jZW}RjdI+NryV)V%G z0Di?h7?F0cf=(Zf)8 zcA3?!(bH-mi1m&{6YQ9(P_`Sf$wsCLqRa?6TWWXF;FB6EFjAA zK^E7Z*yh5{)23Lr=qe-kJf*~6wCLyYSm${~<(3uQISuQ>Vofo#V-r%#tV2i-@$t%c z14pH>&jmAm8H*;rMK_VV9f3dHMf7SMBwH*=X%%o8WVNpFeKAl8`E5JeGp78P; zLtApp-AYT_(24cn^VyI%IdeIOEMOZ+&t`p>#Gx9w#X;VCuNW8^eE`*X0G$K+Snk{5 z+lsFr+TQJ-9SjC!dD_yYa^hW+bGVCg6xlA33AtcLN?CvIMPZ4CTT~c7wQjwVJ_w|3 zUQ_-8Ng#mFMoUK+M3(E10PN7wqbm+n|67fw(@JU-n4b(CTlytOp~2}xMUTpCH-=9# zXsu}Gj2WOzH?y-ncqhi2&mxhh$F1p79{;9Io6eDxRb1nV(b$o=Yr+!dz!KAoUx z0pr#jh$C;pNpl8e5F${4K+?z7q@-Bv#f#Usi~Z#t^5V;DE#U~Nk?}ODimd-K#6JH0 zRM$^3gc24rzK&#`ecgk}xNz$5ueXp^ZZ9eCfuNRCIrmM)!ql5ttZoM&I5LUqs5O6J zS;fzxu!ZlZt8xksr709+Wf78~e(MHa)OX;(y?jMr1iv_?bL(F(pqx#`hE}vsyh=Ij zh&2+$gK$L(XlL+lkqN>J3>S+3e<{#ZsJ^NfFCrMMyE?Xy1*R9zCC;XL3!9D zE6n$8e8n76(&@l95Gc);AH_Rq@(#UW(OG*UX!mI%Hf(B6FWL%+1;Q-QBB1eld$DGeu*_b^-*<;xBAtYy^fMhcKH?ye}o zfTvIK$pVq7>TUjYJ6G6(E&*C;ceC-R=2Lui4zoOr&YCPc;M7}v>$^ruq?XCq*&Pu} z)*;{>Zk-t%X8-b!k{;>*PD6U$WDtiejRTNP^sX28^=Z+tBHPB+fl_&7U9wvYb~$Uq z25r$M(1ElJ6J}9yCcN0Ex}B;t13iW7Bf6B{IJ9a*b>dKl>!Q8e-u?Suf@$c9K=R)4 z3Fs$xqt0!dwesUubq?E?poH=y*sAZD1Bf(@jINNyMnZQV)Xa4(C={HE7|14pa-`(z z>FNE{suksL#y+P_o93CC{&bz27?)9 zNmDRFKYuzOvaFq)pzkFC1_P2f!51>UWNYfT%_TIp&A07X8u0W|A7v7`bkucsIHOZc zfLTD+P-*VK*=a9F#gYp*k&o>ah}MJzD^Y7Zl#k+;?ky+qCMi8=hH#)ZTF1Y?bnQAD zB*1sGSsZ$F2Y4TOZ!+N<5c5?uuHE9#zmqvD6wmVi9I$cY#){6q<++ey1y{7=^5$?> zrNlhQdU$Txq~d!kV(IyCjkr_2PkhcE1kF{a&+M+e8KO9N!PbH!1>--9#U8MytK6R$PSw0&Vj(YdRA0s)xMtV(qqJkBZy^0#r#g} z{(sziWltAlN##YF4^m-Dw@pq?4%_}cm0kW5hs0LkK1)8FrIz}~I{E>T(zPlY-^3TB zi6UG7SeBbzd;8X{%YoMydQcj1#y~;r?tC{btq-U%D+$it`Sz#i$IaZZeI14y8sH|P z6+uVI`ww||B(s8)l24}3)#~^yn^^Z%!lrK3vp=LA;0a!8DSl%-cs3Vk7Cxq7euoWs znKp8?l)DupMNcBP9Y83Vr6Xt+>$y?HwiPq}lkjs#$;fr)Y0Q@WhtLFXBDEmJ$N}|n z%GVR>Du+m>h6eL51Q1;LN=8B0=3Qx@IFw14D=DLN@#sXRqO*U49Uu@bF``EiUX*G~ zgw7;Asg0jx>0++PY4{#7F;*F~03unhlsA6dAK2F^NR*`I0Mdpz89J&9%Ki;c+GzTW z8I7;gSVL?Bqk0=)tMNSoe%WZ}a`S zIdh7zfi40gDj;H6k=|PsBs=*mH2*KepFs-6@h^kdNEfBz(M3Wj(9d574kWQFh`FLW ztZ22IXw;WB49K$r1d`C4muVn!LjLVH^~we)J;6D6ylsE^g)XR(5@7i3_4wSzRNqp=gqpUNyOudnd<$&0Wyu1l9VEz<9i8Y9@&(*d z2+KKR2HMX1z5m34;uri7nm2Dg)N)*w*{!*2Q2t>r)~c#*vEDa`)OXwGgw#80C?b=4 zubCEhmjLtV;_7zPD)@2iq>ckJACG^fug{W00J8+fv;y_Bz`SUC^L1=-$#v*=yw=1z z!Rt*8>gL$zPLuwd{>0Sk`7XS(B5UxJ>@5Y&pCRfFa;dLNTh=Ts%>Vn6_W;hUo=@2P`Ye1=!Un*s zv=bJ+1*`Hu{JsAn+f}`I#PV-v9P&HE2X}ggWFRw-^j`w|TN}^N z4kL{xbn#UHZ&SKWn>w{A8I1VO#^d#46-Qo}!5O?ruf9ScNfaW!iS=tCogiF~NrY#A z3BMza2}}y0=}DQkS%v3^NK*jsND7 z{z^18t}L=ag>{&okXf@@f;n-l7nCgenw-*5dj8JBnl>;nJ^(hCX&a-cJoqnG+312%94=AU)KF$`kvQ<=Db#=GB zd-ryZ)LUZC!TXQoIV4(G6#RLHkg#pK(|IQlboKO{^q-iI-!-QYw5pv|L)yV zYHYrn&I_!2Zva@PmQqg*U3y*V_?7L$;bGYw(pko}&GH=D2oe)yPe~AUXbW2G@mcCb z!>n{p0D%;F3c&~90ig8&ngoro7k$fK33S!{itcI?kATm7Mh?!Bl!VrGgG+6pI)x^6 z9m0kiL`Hn{JCn|9vNWH7x|&^f_}ez&-xoY0oZ(CoxZE1;EADS6 zz@_DZ5_Qq^JiFJ2>WzidIP0b_=jtz{RHV;v$pq7}08|%9EJ)ZJt$K3#d`{ng(_EO@ zaxU3DM_(Zs8Q`)%p^`O}%wh$Ok(3KzvxrzeecQH&@|#NKiDHl-`x~4TkLBQZRhLL{ zfBreNLaTzba0T(=?4syB}30eIx+a~_LN)Tim}Z`6Sz7mTOjTSmV7K(UH*D6}g= z{1sHH@t6#Np{A@oepjekpiVilf9=rW|7!0_qnfpVBp z&N)42{!D)le}Dr?zVCkbzW06KXSrV}qCUQjy8Y@z$FqUPsaYf8A=~zQ{LQpqEz$PL zQ}&)WE@w@A4`{t=xbgD~hsMr0<8``qm3~IMcA44<)yjG_PEQ|dNS)r%opa`^i@~-2 zalAvPuVp_ulan`VWJ2|QWS{vPjqJO954~5g<3DmoqW3In3*|er!8~v8Q%%j z&&4_OmJ)=4#$YgznOs17#{l*HEp8@dkB~{nD?cT&BPr;C3frUSf$1oy^a~S5v?k$k zU;pvPRe^zlLiFtGkS|fphw5FSkNglhT#)62_zGk)F(Dyg{`~oir{9!)=;?vMb5e72 zvt(BZu9c2rnVji*sfNGUQSAlHRB)@bz95rtZ8cr*1 z#%tM<*RL;P>?47pios_igGK>k%k$wt{1GH}yur&c%RR$RJSdLDX+cI)Q&aF)ndVT^ zty$q{rf{8EA6#?u@@lAhmy;=ehYmdloFc$=BTv!AK}=pWAlk+zCNeCZ>Xz2w;z>WaNKM@>&+UNKO|QPuMd5BvL9VXZj?tK`hqo^coLWhGzMMWs3zk^_Pr&fm9u>;*FoSdA2UPSvXq`Y;78%n0MzSNnq$^GK{uVvdEbOLl8H0Itm7= z0(cSwTG}xHS6pC(@_9a^TL43p#WfwF;WNqFB=iuJqfy8>(=fLL=CQ^3%b9Bv>g(&J zz%auALT18O@LI1Jd<~8J&fCbOmdRw3KZlgwdXP*B!?mI6>Lmq5N}B!LESpy#)gn)s z{NPbq3CySfJ?s}5rkmg#TbJ!TnQuE%B0(sujFz}WnLfLhq7F}$4hPFCju_L2BceV! z!Ytk>k$z)|K1}aPhpO`F`Zk^F5Rjq&vHWWjkS;1w&2xccrp|WTp^|It);kKp;AIq; zhFGjkzzdh^@7*0NQe^i4r!$U^j|XvcXAP7n5R|M=+smX{1ItUBMnyDq=d&m0u~qOy zA}esnjx=?&$AaMUXOQr>dwO}fdU<8Q7mtV*cs)e(QUIE&WFl))s)wlJgsn3Ta}kSp zP1fjRJ^R=IkJgx=8go5hxccYAW>D0i9gtK|W8wdj_?DV+L${{0S-l6bLE2l7mT4%L z1c(e^re|UwSnsj-*fyCsE6Yf1S)e#5#K#5!29o>xOn8PzL=YkEbqHW9IyPT@j_RlY zg$4oms2p?~eL?l4a!^{TXL{a1AOVZYanBzudTtj;8X8j3e37&D4ZB5ka!ayKGhR8d=s?bfKQ9yfACYlt#%Z*X&~fSl)^eJ zi2_=bJr)8785+erRD&ah!0!a{oID;JEW_b45!Rp_A)Z@}LFt_c_iQN`JX9>T?g-eN z?OXe9AsupqbnNm5I-`$NnV|MF040<4l?M~_y`ddvNbv5o<52MAs-XqFjM__z*jI%X zrF{qE#zz-hArjHL=H^St{bhx9v?^pOL9g6B=->}P)#TbaxT**{(%ok(s?aK^I#7ec zN>Nfe#qZ7TwS`cJgroY#Mh28iBy=OoR8T538Qes849daJr6NpgX=zD7)`X^^lhqgD z!-j#NlhA~+0yDv(`&& zXM^~WvjU{`uFlo#u5&q12&}Z3XcF6(kt3(#+!ko}oLo8GLs}L>Sh}GUdSf}+U!Ic2 zzKQ)1ty3`~qNKUmGd!-*Wkp2qT@pr7#PaUyOt!0%(ZrQxerv=IKolbXj)p|O<0a$n zJD<)bJV9vxL_!tcz*7`{0uAb?5BmQ}l%eb5A=2Fhz)lQ^X@{B#&;)&NonD9=#0VJ7 zr<#nM;^Jb3Vsj6=3_z7HV(0KhsI|>|fv&$#CTq9}r#q&ozsW1a$CK0u%yUObU%Y|? zaUm#;52M2H9`{y7)ea;EXW{8C(sf*>kSp2(N$xN+(Uv8BT@nsAEbVHq86AW2zj}MW z-S2F-f$WGd&0kAQ9%E`se95 z7I6)TbM!rCTDR}ryVv`9fUV}Fv0!E^qI~N>LWrAsS}vb&^&xC4f)}%ci?p8`-0T+{ zFZy)3Z{wFRoH~Vrzp5GYm`L22Or&8h)n z@_uT|JEal)na8Wi|EQf)dcZIKLTT;3mZG#W{`G|}ft@PlVr0?a{koeI=isAmyH+eX zh-J#xo=sB$Wh_@4Pa?GH=3IQOSJkv8xdzfTclFQ8U&D$c9k+#_;X1$OmyZqb!fz_S z|C)aH&HUztX8UnR?&>?fRgMr1dK`C6oH3<+Em}EN+@q(j9@JBggHn^K8QKr33$dkK2pqT)EPyovyru`Co4Pp=*1-xuNo@EnB+&>dTBU zr@J?2g^&PnYBtUp!uMaF)NgL?e|g0Jf8l?d|6Nfk9{df5Mt^v(Jo1COjkYy!%f9G; E0qo|46951J literal 75676 zcmeFZWmr^g`}PfjlEMHI3esT^4oFH!NC+s1z|b&A2@EmPB}fd7G*SYJ0z-Fq2m?rW z%M9I}@0#nn?*Dt=_xt7j_B`9OJ>S?Cvu4h9=5g%%?^wZVuM}<*-y_Ds!MUxZDE9^j z2M>;eb7PtC7H|cI+Zcs|^ASf$PWr8@;YKP!3iZfg=Qa3VZ3m@C_&pCw>#%yRd#03B zrcVdj#s!PN(bX1zoPprnl*6@ReZZXQ_Y>jA{L;YP$lbtw?%Zc?zshc#zM{^+nbFR( zaT_D>kxnH;$l?!@A^a?I#aHvs-z;(qY+x?zRp4Jla?n?Qe}sh+ z(U$V}MHzNbu;^d+vG^-8Q^NoCCC}N>|J=svtB4}{`xA0EJ}3V3GYEXv|3kmH3(s1c z8(!LQG2VNzD69JAsny^&B@Nuy2V)0QO3$%fxQBDUb*z8xyHX4%_TMj?vsLORU^vvn z*z+6XfgVPPN0s$S17r0-K6=zh8R&jFMnzo=GcY1|*p$`_IsW=B_Ix;Y3`0JDI~>Cf z+-HL5QBmvww<`{wSz|}F3r}gC0k{bPWw*L4#}4@)-)~N2z)f=C=&~!_zaHlK;QwvT z|LvXswR6WNq;DZk+t2}%?$eOWZ}#$o2CM6CJMB!r&lOx4jz%F5f26tRo;O~fH=>?G z+Yrdj>Jryo=<(e3)fkUagLqAjR@hyE4vFJw_`pbVm}Z_w%5RY_4}63^?CaG;P=px zq{9HzM_fE)+NWE$LtvCLZ(Flh3Waa|y|R)s;Z;{>>oexbwrI)gi~SYOPIK{+fq;;#Vh2&Q}gg9WR8TT~1KYw&T|=vs`F6uHUXU@BLEEA{z*K)}JK6RihW4;xwuQYw;%< z7&# zNWIEFVDrk6@Ai37Gv~wRZT91zJO;^M7`v?c3x+C%*>wBm!zo=B0Qii@l z)Tqy0I!$9w9XZCXa`?$azc>15+>|`IGj*r?ap6g}6Y$JHrj#_0M?+vQ@nv$pmuZKJe3$Ln zt+Jt4rEdB=MT3`D$Bn{y56uz1SSuv%1?&>0n%=wYx7;=8xcx}7vb3QdEl+Znrr(MgH?m6gnTsv28T9tN_gl7EO zkh}i!Xlj(qrgPB$r}tXU5B@``Z|`$Rj_0v-?&AAR5a zNo8BK6!EM^$abquE z5}%7DrhJ~CQ_=+Y|45##WTB1>>)orFu6BYdYlwv5`1;S|9D5Om&O6=^eGB1)bagCPn$C?NmkYaC2+*1dXovYq3>!kDzJ{ z2M0$|&Doyh$voavq|l%7Tet6x3zl5AQN1q1^fSR%GJhpQcxz_Hmw?f7-?K?0f);O@E&i@HZNT}<+LOpba;b~o zZDcL$z>EzFej#O8WYQYQId3JU&-F0IA^?M{tvQ*z>(C^qp>6DQlq%+wJ44^6K#zl2 z_9RT|evV*)xSBt}`y5`>IvLvaQw5(DJ)W={NDnJ2_D873^VRLhP|+Y%N7XBTCUZ>b zpwk>0a@T15qLvc#3TnFXQ3bVI@3+bN*LD_KRhwAit!R%-jM8}4y5ar&hYR}s;`?E# z^ejqKZx}cGo&{U;EeF8j5$bIsou#Ql3y_M&i@lzKT=UtnPDT$@{AJ{0pR=KKnDOFOCY7WUR}6udqcNH8s3W!LI%=zL$h0mvii@ zMlI^^;K&-YbGBYMMKBI5M{6yRWJRs>=KJ-c_iov$$>ywx;7BRSf-F}Og9m7FC#O=B zCW^&dyz#Wx&gQ<~ub9x}@0Gu8k%{N+eBPhS$v*p!cLN^~JAshrrvq#FRU9-T@*E`D zK;fibG_P;pd{bxrq^gs$_I#^0IgSq>cdo(fJS>r9M!T8`!jka_+*$5Qk{RTo9cLU8 zQoUoyVo69$*&Zs|7UOb$-c0Uoy#7*I+4eM{@!~rVn|&T7T%4);xgJYH3nm?Nf447^ z0D|{0(s}=ciSlHiDO8j@JT3j|;73JY?Gq-4Hi}W2G&K~MG46E7?T3Vpc2eS!w{g-z zyd`(t##E_AKT1+O0pW@)BQ&~BaRa-I8MsW8TxT>%&0VM(Pw35M0s-D<`s$;x0KdP3 zKmBI}l4++nvWQfVt!lJZKmcCPM;GgT8B*M41@T6d2bki`11MRg>}Wu<*4{%jta>>f z>4YHCA919HSLGLnlRNZ}8TlA|Pdp!p^p2e%w@+?gqq(WvT|Q<=Z(wVh@yMFqpU&?# zIH-!W`R1^~F!Ckpa^2{f|F|Et7L}K{bmi_^0job8HQs(|h`R4QZj$6Qd-HdsXzR#t zDRRx=YOXX_R=B5=8rM-|$lFL-*g`4h=G#22e14!&YUIbMPLjH2PSC#V-+PsfmprAZ zT`9;s6_l?}fg9RBp)GDW(x-KkMq6nv@Ivj=cZ#~i)*0%$sDpkGjcI(p$P%d@5L{=% z{%en@YQNWc@=#LjbjNH~&%=Iy5s!z|-Z#|1wmrq=SBscBeUZOC11yknyF`Z`+$kb7 zs>#KO(crG0CNkNm**vuL?^}=HYRJv(FsuB z0uS7Y0)F8$a*is0M@b);zu_=HW~w7p zbn7N?a;i)H+f%+D5Yp^%K$1J$bLBO4Y6ygZ8f>5wq*~1<~ zl)4o6hGaTRC$r>4XC>Z_jfpQtr)96Fw9|R(nGG^=C{dKfF-z#uiG}&EJnXAbDjqKB z38Cy$V+mu)Fa*NB*}d~D=C$NR2T3tXL0B$J=gexcEjWoko?8dHSj)^z-(xX*XM3h!R}SNM>*#(O=XdtT? zpk8eX0w%aw304BSJC%F(6_2_nLBYX~Z!X{^R=?D81I(ZO)Lq?T!#pzm+H6 z>V)bN<*S7xxPJ$`K)`6M*`?{J8C0p}2BNsi5>BC;qH0m7BDX9C8>{AVcS5`t0&Z^x zOc^|-)xJ~EShC(y4=%IepM9kAqX_&vewc@$5W`ZALz8`mld(C(?^<+4F>sKK0}XUW z5>I~iTBAa?V}o;@gnF}Nrkk!7p2NSpcl`QEc0gNhDceA{?7mjp7(xF}R=dhTSl$<8 z^?{h@z7lKM8(UI{{sRK#hXwB;-Grv;>_yBA-iXJnW71Dmk$!Q(V=}nwPn#Wczt{)O z#2VYSZPJ-IA5B6E?ELS`+uOLLvuHRHYP zCob3W3Nw=fKsTTNZy_c66VtXp#pgouEQ5#q2YvE)T{`1;@UfK)>8@wjPZ zHIR2*4*@C&Bj>EJ`t`pH55XWfg!H6Kd>BYb$H2eP5`1 zkhf*BeMVbVw@$NF3+lwJlL6U7-cJ+6G z?D4C-1YZ7T{<;^kmG;y2$v?t!n{q3lv)su>Izs*V%5k>KKe`3GduA3NnrbXszKwtI zjWO1CxeyYs6Depj@COWAQ6@L97-LV-itlyFOW^M2=1US9xH77Aj~lT)9BePJ@eI~0 zuR=o8S7WAQ$)8QMiE42tny!x(=zkV1G@>J5yEpr8bAj#X;cA%NPSGwF%Bo zm)d)r*N@OVeRdBbN zNPximPlpo>MumBhtOi}Du-}lX&=@LvX2$WB18sh=o+OrS`k@?<&{)6!>zw#&z-`3{ z+NOUB^?z^coJ5JWO|KmBje9EfaLv?cK34TKsoyJN4AtTdbIaOwS3k}S&UR}hsBvSv z^@WgxM^nT7d;2@Wr9Bxi0c1E(&`ZSH!09a)TE5(ix0ErV&t3}uzJ{4`J2L+-u~p{% zkP+<-Y)&J)ty4Fg4S$YeNtAg+4X(co&qyqVt#a35#jhgQvRuf-TX-~;mKJ8*oF zoZQ=3Wm3k5`+ts(jAL#?ApH0vi=r@YXB96nSVEI-Vmh2*=IcZ@{1gP&oo~uG(yTcC74A9}) zPm~`6_Fs8chSQI1xg{Sro1jTgr{f8PYsR=E^sNbLl(=JnC51nn-N^fwJR3M$>YAg9 zna|P)obOnX-D88&y{`Pw@s7%kanu6i^SJ*HWM6~xgO6MF{Syf7S+^?Qo-}fWS2rSYUaZb!E3+W%N0B{^aQNUa6`onQ11o9QI3 zzbvnIC1N)OmXe&a^_u_LX#Q<;#%jlZ&Bgz}*D_qlK4 zAbFp(#rBiV|v?Y1NZ&&XlyzU6HR5)1vUEj+yJztcHrn3DsZzF1mW> zcEpN;>LcVtG`>z=ZDZ`uhqb62a*iV`%N?Y@O|D)_A_^)F80CJ3Q_ZS-KgdmSR3?e0 zrf^Xbi{{IDU6syqQ6-SO2|xPOd(iLx&Xy`u^5MaiSjfLtii0y*52mkd=Zd6*to#DT z-cKe)M)4exsTtbimo=D!4|)CQ1|Pb6tf1Wfk}>pSHT!v0cXXiX2wR&}4$dPg>5J%B z_u;-`aoPUU{#*H_Z=UX`znrZG4v^Br9`o1a5xHVkB38s8>4A0TAB=}D#N9o05gB}! zV+Eg2^(D)S33=!Q*bV0Pn%>8K!DOXA1(n|NisnEAJ9niuM`c=&Sd!%{BB5@!bmpj? zloBf{$#+SZS=TBT!n?J6&8K5(vwot^+dO8nw`smC!_6TcpC9>E6j@kZb_#9wx+P_5 z=@+o=IU3@skIXHV0B2@cy z#(YV+WJ~JZB)`+u7w`F?>{kInp9O`^Bt+afK9 z;A83sb5hCT0wyoXc5G>Q(uK@sP6`Sq&foRFiCX-|U&WO{9d0pJDcDbXI6qm8bj#y8 zHx6e!+w*yxmb~Xw5q=a|KqBoa-_EcpR`^HRTDU+PQH3aNjKIT2iP)WIaf6|wex^nB zw5YWDe)NS0@bjn=d;x-^3MWsTgfe&c%g*>x@{0wYdy@)Ojeg|byN2f{OL+OfIh0iL z!{@4j14JGiA}V=M^n|%7QNGd#yazT)(;e%Q{4IQoTQ7y4R(TS<_C_Zuk&OvBkPMZ| zTNRuy4S%vSD@sOGec5@H7k2nDQl*@qxGA#S`U<;!TlJ{shUbtRC+;N~0Y`pBhIiJaxCIm1 z`6_mPKUS5&Y)rI5L&G}x%e44}-I{`(9{s-l!l)2%a8}sPB7B_<{b5hr+p79{HTs`Z zQE?4taDo+hWeT2c@=tYr7H0(A%$k(k&i0y|;jGy8WQiAbNi3QTC82C9MG1&lD86{( z>d&wkxxOIEnDkz`jpw(azTR0CXVMYoV!G$`SBe%KO!H+(*w_GKmWij# zX?zH6v`0njJc1W>;cC&^@%U!&Nxj3gl?X15bn?d&;D4fpBdqukiA*C~H#^@-K0l|l1tI-NG{8$Li<9c(`uu&sC}d?6=uKZ(v4oI2aBrPw@nyz`u^L-XNc+z zL5NE3o$T!I477Dp?PLTir*zipjJ`naQuGEfGUa-=`~Jt6GNyF{$d5aQV^JiPzCjU)D3w#=JQn6 z3>pEpfkd@f>qv5K`i0On>&8B&XG3Q;bLX1w4)5MoX0*lRtKv80Y_Un6Z3M`*GmNhM z&KJDg_)y~3mf|wf`m$$#URs0&VHx^`+nljYe>i+BRCG2S&>n^zUKYMOGK8xVT3j>k zH0*P$t_|?oR&S~8_Q^^DJ?py9yW{D~j+Ubg{;wS+mlAHCY!ejOfx|(e~ z=&B#+j$d@OZ<7$h(}unk$MN8f(PeJ5yUQ$dlbYsyTFBw#ClZ@iP~JmEaSVjQ?2=ZiS*)+sxsXmdd3HOk^lV_JD z5a*pZB~v!xZON^YPx-M^h5O$6!yRhCZV4iE0+VR3Wu>@XOZP$8{BJPjLs&r%o%~v(EWpcH9EyR$ITXI5z-!Z#mNAooVNr z&1Hij5Zv=(@F+|=Ga@4(YTZJGb!=&dkAfMH=l^)`Wo&Pod4*KlqZnF(o%e^eP+;#c z_W|Cpnan=p{x@r&H+L27w?;lQauIp{C_n=Q0b?k*nD=-PFV- zLp45s7AUWZOOvQ=%Gg=4OWH}h{+YxN!wV7F`yklICW{nyslMO0#6v+5NlOyul4TwH z!nh>gB$PD?|A4#+ODa@m@Xl+aJ|*JO_y5|D%{^Z;3$-;6G4Gr9AG;1;xC@o&$J=J# zpEZLZJSi-E?h^nrp}V_#I_xg>K%4ku?Sc;gRp7X6@{V7fqiktoqWVQ%PryQJP%YN7 zh>MS(e5=T9)KE9SR#x10nMVB#h*Uhk?mDby>F!Af&?gi48neuN`Wf8RfaDUdevzRs zRS;5gGR_JKjO-%V=nOIvaU1yfjJm+cvnW8FMgo$M$yDp)OXx;e43Y$89TMk1EF&Ka z4q)|n-)oL|zGwPPoV%Z1@;821B`M36CmA>AjR;qe1cGTYgxr)5=VT{aGVC$?T6!Zv znV{{fXXigN=Xv0WCzJf|ah10PCJVUkyoP*6Hsp{WsChEyJ|=-le~jGGtuu?;H~svr zK&XIEv%pTc&2zj1A|t^-+q)~T=Z`7E;avZ0tx-O41eU~Ep&{5G3J~XUM zf3GL~5J2N@!CHd@BL#MI4bHRFj~(IVzk~sg*)dWo?UDr2;C3*eF!MWO^;H#M^=vJM z@X{qgL8!Ta76QTQ}Zy z9fPxVjF`KHM6PS5{V;^Psw{uO5y}OLwSf3MjWs7$*6KHC?VR zFjBUR3vZdA1=@v%u)_MIkb(lLLk{%W!RnIptQ!UpQ)H&Mb&9dFkj*{Bv|@xXz^Wt% z{zb3wx`2hDZG^{#K9@b0%X~f#uO&~v>6QIl)Yh3M*>1e{o;uoTC9l0n@@P7&$j}R5 z1Gc_c7dY5Xz9qFeMx}@jNgVu^b>0A6)TL|{rN~2^zRPKN|AbJVgo(`L%yM2~gX3QW z0bpUT732Q=+zJYW1qIPOSAzjZ=JLvWP<_)@Rs&Abrw( z3@N;}PBH0~M;Sa;L%arqTPmTne9qcNUgcBn>-qVwxLXyNy#ByyRym((LxKRFpz3II zYU;89Ko~Yt4we2jF#j)eR6X6s;Aj0K)w#rL&U0VYWvd!f1Gw6liaFrfrW?+;tZ$&h zg=dS%4_e8dakFJtOum0i#f2c5CXl6z>}&uain)A!$$1K*urb+-6u=bUN`dzkJ2JV> z<5u?Y)>eT{I}&lQ9^Aq!$l0tI4r`xav;{ zfKhO^1uVn}TLpjbZI3xPU&BeJ_3y8~BQv3*9ewJ&@oyrq4t?*7;m~|wGM$@K$UR|u zn`Afq^D|L5FqTu3VPeG>fNET0;4(9Uf3aTJxJ4#$pmyBFwp!GeuUqcuu~8f}Loc^f zW;J2TBNSgXR|@5_N|nuM8E5MlIQdADxdnR4B@vP9eH{;I2ho2KW*A2*cvb6e^VTQB zCs)J+_=JRQ8eQN{hM3|+7W9SZ9l4ImhC`m?UtHmjK>>+TJ_G~yD)k|8Ec~1#P&=vH5vTS#R+*KD=_NN)c8TLJDEg1vw73(0k{YRN^ zOahSIJX9>07b*|XMJeD2UecGcQ>Bd3LEk}-fBpaljWheJ7;q~E)Xw&akgs#g4Z+h8QXVPYP z&P?9E5q{@}+)Z{qou>~)O~VxlRf}StK#dGo>~G~T5L2+S2QDRoDkLEu%=mjOw2TyLQ68SHj>vXbF^vaGlewq{PQ|J?NxWk z&5+1r0PqnI*j10nV_=4Y1T=jQL-&pAWz|UO;~DvUNfsiWZ6#{*LW$OC{Gnvc!PItu zlP!F#j8urz8T!fzK3-zF7Ad{W=(!_(JT-SEWSz?O2>oE{)04#-`3MFp8XkW|R~`ih z2mdLb>q~+2AV7o!s0yh>5OI$QeY}|dBhk6lAL(fm@_NN&v>j`049vsz$;-Q)Om?G! zX`)EqSc;l3M=4ohWqtjLSfYclC(5_m*q}UYnFzYVS19#P z;5_T|XMlYLm=kn%NYo2L$NN>$?q|o_>A+5+Mv+VCfX`scNG`t9^r)Rd>v?x;G$bjp z^#)zO)G-BEJLzV11L9obvGd{<1L61AKV2m!vseb}pBX%GB;ofe?}DJ6>Z;= zLPebVd-H1Af9m*G(=VeJ^+g}tiWD6;RfcQ*9QA^tWd49(7e&8+$k$&2qlBh8-JO}@cSM&{0Kp^T@us<4WngdAlzBl-Aaah$h_EcX)K**XY8nZF~eQ2 z8EL&RS%lQQh5MpT&(sMDn{V<(-v~C|eZotM`}Qu7Xmq5SG|Q#95kB(!-Rvi?$2KWW zs98WOd9fo~x~ADt+Ap~t0l20pe$y4uJHq!(lN}Pf%z^cZ=lki`Hpf$++G*5Rx22$D zzMCfEOk+3*@eb$>+g>Mtae7+Hw|D_?dVN(oFHsx`BF_l)NtN!1TdOghCtAz~32+4s zCq}4l`1nWk-&<6%y=V#{>Ws`s{v0IxGj|1O1MiAnlXI$VXp9V@T7 z@_llMQS`+E&$= zBW7V*Sn}|FP)iws=<;|P%b|CPq>4F%(_xs54m-}Vef}R8JjY+3FTTjlQO#P}DwW~x zDolJbs_VS6VBNmQEUv>ix}jd0E1#o+8u7=juy<5{Ck*S&BNQx6L5(h@Y@h&I*)SHi z6MU9^2lcv@%uw!V_RJf_FLp>X`6xy3dT6(zBp)a^LCJ6xpOfgbJxq8Il0rMsD%2+n zBJDOqGQbib1h~HKiDLK^H~f}B)Ulre$SG(daQBUa+oI(@sARITGRlG#yeRmp-lqYf ziTQFK_Zi#8Jb~1cN_l*3;EM@KTiqTU+xeU)>l|J{njZjt@m)DV*UK9Kfpn9Ln3^pv zAkvwxgYx(^CfscMk}IU66}>`JsL2QSaAVFt;VjW*esGkks-TBeHCJd5aJwLk)2Itt zLq#Wt2-2nRypgIZ^>p3KLs_U z9t6)&Mg!Vj@h;?}B@6D;s2=Vzzmb4RglHR0K@j0feBMoedQM|az4{NuI#r5+hJ$N4 zNYmmJv*7AOmFtVkFhqXvmo^5iw@vOM2g@7BFvYC%l6cuF8mvf(2ogD87l}$FX<8;H zA;z$92^;aU8e``hZ;{d4(sEy^E5K=w z87cz~37eZvaljuFO^lFIBg>s0*O$k(jX((5?jKH$_Un4iK=Cqt6B3+D>G<(^W-mxK z>~MXi*2SDYo-^}ld|aH_sEO@2egE;F>RJ5jS@VxpV?MLJedfH8I1#9M2ls`j|79ex z0P;H_ONXF*=Oao_{5;(Qx*aX83b?^=zd|Ygs5F$El7 zFr$EByFH&Ek8g8f`y9Z>Y?JotR`C3dAn9kEM!*?E2@Hs3Q;lGTo-&Ca7}WP`BqBP%~NoL1)MVS-{7lQQeELcNG5SFiFz%mzSR$_;+7Z>9~Tq*2vpZB5icK zRwP2Po4_VjWZi)b}>ZOm433o-va74+k?k zIW-t=^qU@&w(h@bE)bFbYLFsoM2ZrA1CXoji{GW(W7?1LaQ+}`=>CMt6>q`!YxAQ3 zYBGmq6McHW@TKwoPy#7)m}M@*+WJjqGiH1HWQM8gr0{`HK%>;}QrI(uEx8gY9TBaMeaK2)2=q&ULEQ^@-LmyL%h}b9#9g#g=!+n9FGgCy=-TczXFFI6z5uvKn zfMbuH3jdg9K{7YN!pPNDnEZ9f&+_DZ`mZQnFZ>x|yTgwk*sQ6AJsKY={#~N+|FzjF ziC8AzCA#qVuOvv8OMA&y%bBu2dY2(nro;-Pq>lbJGhA6h7#q;>=T{8RnK|WYc7sKL z%zqell|-i}OOZUU8KTTTGQbU+K5ImHnmgD7`3uD3Xf=k+P|Z>$iNAfXLR}#nsPmb+ zmXvm9k!3w)ix6S05u@tmF{v(- z?rqZmn(uN9Xcsk&7t4GVl3&`UTdOUTi%mNxy*FM{T2E6k0Wq*1=fi3s0KWIs()dOQ z{^G_n5-Hns;aNpY z*F6#YujhbhU}fvje3KSZuateC8jhI99vPgJ@r^)aS)iVE8!qE@IHK*m5yYfb7v((z z(9_VK;Z*CdjKXuCrR!6bcIHOWo|RTZ9fxZpJqGYzLFd;+41@A1$=2+@Dixrw-oBUy z427%KWZ|MF`VkJ|ND|gJ(FI@mo8=>fqmB8#Y{>3nXy1_gKfFs!G{_L;_mv+}@Jk@Z zI@)nw(mpJ*>>&U#Ik(LijR{l2!N0#LQMq(K{P8Y6Qu53az_M$W@99Kx5Q8g$oGaNW*Q_Ug>rc#UXNxp9^K4WUwpJlx#xzo5qi)KsvHpCtvSFD_ z^28Vms!vr<%oZ3to03{HuLe%is#KTRi3k&~w}~%I#OH7c7>v);?OTXo0R8u2?zGQ^ zpA}(kOn)e{^7RuEB}*pS7V$~rwZw>R`G^(_0KOe8QXB$P)4k}}jsfJh77Oae=L{8k zA3hfTu%f1S1mM0!y~16&!x;mMcu*ep+YwpF#XQ3Z@=|7Oj4f%AQRuFkXFAWC@VBVb2V z+)@2`KCo$2bOFnH_S88q0rntQMp2`Pm7^rSH!Y3Ktg&j5fEItD#i4b`u4*4hO{{EEWQ9}y^96iKGy z<THxO*dCE#GYkwxnetS_kH(L1mZnIYmmRqj*Cq4tK z>FTawrMy!4-b8TgCLra-BRs~7OlS`9o1f3esG&5`=BK6Um)shhEqI?7Zkixy;SF9z z{>7fZI1X7so?g2yz^zHg)(?W#*@)~ zC8Of@z|q0b>)Ow33X}Y!^4)v!GHnbuY$waCD#8$E=YU3H+=DIF;Yo=77DKFz3eH88 z!kJl|l-4b#0UOJOBR|cN&CsKzP1#As^+z22)yq$@IGzLCZn8#Kg~2lVtP15G%`Mj& zG(=rqu(I6w3%03?{sKD`y(&sZ;YuX&z|cdvp;su~)1$Y9qe6w!_Ugx$QKNk&5rsb} zxG;y@ELvr1T3!Qnl9@n%u_%#qCSiBO7TxrLe`htl(T?Q^H{(STJc#^>udG3X_Z3Wg za8D_@@S(yCfHPzt|G2NQ`RnwuoVgA;Ynxtq9rV<#>GO`q1oBNXM(pSD%2Buqhz&W> zk2$8FI}{Y&+N2SBeOdJyh`q-s^E^PFvPNfx93nr+G7@E{T(Q@L12UMAh%*<`p<<>pKJh+%-l&l2O8jewZDNMWI#Ps?sKEPDsP^2PlFvS-c13;J*hfDPGL@fj-1Kk z0S-E6SF?+Epa=kh%u&fUopBm{SxsmGAZ9vW01G)zl-6&!wFWDDakh+i_y>SMaD)SS zykZ5L?gCIuQ?^{#_=;;gE|E%;!Ugjr%jdPQ3&ckla2jKo@6yfG;UcOB?hh9HLNHS4 zJyieb6y%0{0qFt}#>^_~9p>SM-s#j7(jpP=0Rkk}+Z6tY$5w}B$$~#4b=G8Xp90Rb zFktId!bV;SR}IwP#qB&~EgStVr=bb$Gi|X@o6N7_9E5K1!fC&A`;Q#-55o2hQN<{s zHa=j|loN>~KMW^(DY8d=r%;!N)qS|!o@$yY1)_5uXvF$bjpCgMj-gP|zJQ&q@Q>F) z+5SQpy1DZ2MD}RaaV2c=Q0hO4Ep%}qh)HO-ty6Mo09#hY+i(JEJ7+@p$QZMyzvl^rcfp zl52rK_n<8TyE8&Cl}^s2<=k-ySh(a+fV0Z;SpXGAL0|VS)zH}T3{j2;1C%V`<@0Z< zTN4B5`oz{tFg}am>8CP5rlPdZQS<=QW|f(A1}&HM43ul19*(R@ED8XOvC&4$+HdRC z;_Dap1c1FxqdM*2R%0QiO>5D?L!#<3SfWFBAL9 zi(I|-Ig1(jq4DEY#YOGhB`;e_#f-DwaXYP1qFzp=p_}pomMe}eQlSs01GgaGb9;al z&i9ZY|9080lt{PXb!0EYZ4|XwNb@?UHkbG z#X~1CzF?kcmgLbW`)B30wD=c9Vtt0Pxow;NB)@B=4vBBECE?R)sa}3z<9f3Kqe*^+ z`}H{OFJi!U>flZxJA=I7Ff(3FGF!wU$zx_fUjx;t_b@Ed&}9XY`~f%#)t@f_nxDo!5J9dG~FNzuYvDiK=nWR#n0!2VH0Rab5$2cFDr31xSoSB|_ zE-SyAM}rDttNhO{i(}ot2-&`0uObi2lC>$FE;5mwY5+qcyv9fK^_D-c5r=+>~c3u|lZex1u2#Wte0QRN+b!g@a{d)3DU=B<0jO zf(JP-QD%`z9uEY}`(hX?gPI=oB1t+?105(Tn_Co0cUz6DESDYXlfdwt_3sP?Ov-=S zwpN)^X%ZqTkG|dp(zrydJYj?HaD=5ZXxZ@Z>@IBM?$YRnf;cv(DuKRJ#IKa{r_VSh z8rs$=v;6#`T)&d{z9cewS`x) zND@)DNJxJ;HRfXUYqICD*`BTU(3+>|xb5iOjl-S5y_8FY&tWn_z@bxQ?8|dr(dzz7 zuA2a#dwE`LwUae^@8czfZyMn8BwCua@Cf*yslV2Ltb}PQmW;zSWh@pCJTLLuJhODF ziYwW`>tw#8M1s4~D&#lA?)%Ru;Nr?hQF24nGt{XeQStps+o3yMAwo&+&R%65UoxSA zMSSt)H%)`gyNR=O_*pDHpDN2e_{=szyX*V&=^GzDLPi-Kb(ZQ6=-7iZ1Y~!BtJs)g zf*&c2DP3og`BS&is0kbm`|1L+l><+{nB56APkLYY%hH$Tqy0(>9LtbA)7$YnK>Qx}PxJxBLo_KB)OK_7(Ft?l2QIi( z0kV(^a|}tuGGI4I*5n0?a68RXQz?J>$pE0c(Pe!Zkl=_UpzL2=|L^j2`kkTltEWrR zbg5lQl{wOC?k);amw&jVetjcH_?h`O_p3ght;A)%#}d^4ksJL_j`kmg@_%Jv0L18D8F_2#!7aiFnLEFb zPV0D0psp9ba=@`$_2Azry?|L!&|2EhL_z6$zE3uM-mo~L%Nn+I9|a`g`FXrCggvCk za!c=w@d~>Bj%Y%I!McHGe$zD9sXEhqXm*ruL(WLJI}r?S!*xT5Jf*Z-+%cAlm2Wd z;*dE_gm$V+3G*;nq&r_#5k(beEm`18al{Aqy1X&oRbcln`Fg~1nJto@r~pH@ zzMXyGK6D%Qp)kL*-Qn#NW(FzkHNDZCK5;t6{hCBFNb_xGP6vCtr`Gs3cFZd zqrk0SByDbxf&*?wUMo3EtkyeoE{YS@tpd=X&MklFYNvrfPmGjnE7EcVT#ZTgZO;?u zKyQ_bt`*rh=jafKUi-s%G|ax=d;o>DUwk;wrA%Wx6N>+t*t!-Z2$OG2L&u{x^G%R%a(8_TN_N#Mc6pF+X6!h62e3|CrKi071HZsVlJw zAj|Pd-JG%SHmS@2qHSjIF7-p%KqM`Ed3hZbjX)%iRtD+Jd+KnaX;8&(Yauu@kW469 z&vXqK2qVyI8 zHYdwiZC<8Kc!PZzg!JDB)!!sOR&-N_D)sz8-3QT1cXR|mVQ(UxVMp5O=J`OSz+4Ba zcjeeO83?~i!&uOx1-e$}Cbq3IoxAWLug{`md({GOIt8B|%kteKnu{!gUQZYuJN=cG z(Il8fw7*#RBrF%7 zXlFwEGIao2-QXJKTi+X3T5&@i*e4wSvzxXU5NBQELfl$%Ir_DZ)%glx!15VGDnCZ| zc8dizaaMQ(uFVUy^)4@x{sDUVl9BfJ|v;) zeEke-mY84#L)8&ce^WFuk=)&8O+}^WUn!<}tyvkcQIkwtbM{){`d^^%&rJ{c9b)}~ z1|p(w`@m%ednIn8gxV<+$>zPF$81_f`uc2`+f0_DSPX)dS4h*xKpVT%<$1T0Xzjyt z7Re2wuf}cP|MyEh)JHtDl0K6B_;yh|HT>_TI9QR3&9nbKrTxOw0u6!lPd{?bf}JO0 zQ}Kve;YxSaXbFoJ@lrs`Zvc~D@zKFha!F$W5B8={$JTQOE{;r+@cvtVsv4K7$+>W5 z+os95$C-KSH{}*{UyyLyF}N)_26QExd{73O3)Nr))8Ya5wncKocV9W^p$Rjje1^y3 zsd!1t8!h+fNUrKgR&tx=MXBt+K|!`|HIMC`F)NR>}Is?IhP2Xv$wgR=GF!SSZ(`5e}=llf(2b&?dP8#V?Em^;lN8PDtv%iv;rh@u{8(upiKX7_R$gQApS?6q&VL@u0`r`)dZF-X7yHf5+`uNHhgOFl;u9ZVe#_I@ z6-P+$p~uHs>8h~1{^|0*xh}t>{-fgf@bzi&Ql?>fRP*BCE=;D9c;VJJ_2*%4$hqI6 zf|OdTg_^npKL$(~9fF15thGM{l3t)V$zLT2TZ2&WPda;FbP>Te-S=#JgG^-pBXTv( zW2<=c*=AYHIiMA=DU75&+pZh(0^XW1FyfTiu=W9X%|ViVJ~>vI8UtLPl{MYw-PaO_ zZ$CKY>r~hzodd83hKA>*-cu|$Q{!{BpZ>XC=w0s@!7XgMtdae$Hj5*CvcaNTK>Hcs ztOB(^P?`6D{6Br*&14f*$@2(3F8o2W?H&fOWO>O)C5$=s2wj43Wt~@2^g@U> zEe4u_D!Y{=Ce22H=cFhazMFmIJr!5x%}M1S@Ng{<(B)+Q$o#DhYb$`@*pm1UPJw5X zuWC0+LeKxi*l1_hyfJc`v@WdI?@yD+%3E(Mvl>#7vn9p0SoHwLjR2a~3v1!+MTKtZG%r394jMoLsldPpS%Mx;B3lm;n9K$H$?kQhKIal{TyVMpS4Uff>gH z*3hLcccrt*b4*XI(LN8<1?H|Df!piC60Fv-LVMulFrR*oCEED|D&0EpFsMGB0eWY; z4lFZZ3f9wlRm>&ZaU?(7@q1gVGXN-Z_+c*bugePy3+vX3vRtYcDwi(-1B>ywQJ?NB zhF@j;7ZcS`qlH(Plg5s)v}!$I;ZjW1k}gzp^SFC zu))RLCrz&eWqxq&JFFB1q|}Ag_hdlhm~Zk_eAPE_bZg4~S9#>{l^V>7_|%__`WwFS(USQmbmP*3WWmCf$E?5njEzRC2NPe2 zN9?^?VZVRt3U2U2i1E+r8wdvLW8w&^kc_T-^{%ToNoT3%EApDk%-&mFB)m|r{Mz&) znC^P>>lG{XU>6C=c&#&63*L%-9Y6uYF(%)S4bn(wz$%3XoI| zMQTm+r}`MXBLMkj=p%vc5q$|Q3!+6m*to{75tQer3AROX`K2Rh6ozXcd zA=avTndmf4f7p3nL{e&71*a2`VG!{6ns{j0J25`;+luc z(e_eZEWuFyqaSt>{>Qtq;e(;B*yX~RNiSUgQ|QeCa)?I_SvSKxz2+ODV680qu}@Tq zk%v2X?Za+&X7~mUD-hZ4F9nttf(`LtHB0%G2Uc%&(^Ct9TFhnq^umC+RD(osl+*Hv z{puZcaXaj&j|x>>sc=+;md7tH+rbI!z=#?$a?hxIz*<__X5}yWYqP7S&N|K)EC6NM zpj2v53|6@w#N{-RQU#+r9I=nR%z@I5=Xey-H`%G)=;S;O!K*?XRUzh%iK2=@y@g+T zOc`^2mj0~uVmAuFUH5s#O6Ago5UI2)JS2#lDGN8O#&p#?DtE+Z& z1V%4C1R|1l&ZpU&6$yb93YTD|%6b-;p@C+MR4@+?Lm@2DGK*qb=oH^*=bD&HONS`_1ptCw z?FzqYsYPRra`jvtex;;}1eCo=b1-r9zQBc?iQ~b#JlP6-inzF3m%xi#PhtgQ#a-1h z0$`29Sn4nR7_hK9q620(PG9tv@}cotP5=zUrBR#=IUW%(VrIPzb5h%s*=)x{C&Bk9 zw-(Dhq8c~bmTsV3BM~{tqD(^2FyrgM9))-pn7FtMbDia0aNY)+(Tfv)fpYT2q!9DeT}CvBEh`66$zO$9S(7ocq!r^q$siI&^?o@J=9IYu znV$v8!nSi<(J@@mH?rLf9f~u6mx~nbnVs_?iMl7)~y2%)~U6fOmvH2TK_^3uo)T~^tz2{GNt-0rl{!m{_!tK zyeVTJFm`b9Z_t_XT8N|BOY|0u;L^&lEDthDfDq$Tko3N!9K&aA_iErV@_<;?lCCEi z#S^QB1X*X(^yYfa!|gg0vsq<}sS~eL>foa{=ZO^1Dv%483^foeBTR3ZJ$5V$^K)a* z6%Q?0Z7lXX!c%-$mI00X_M=gRDLvK=z+{%ToS=lw^^(!DkuH^c*o`!m@&z@y<3s`p z)+SCMRfagD=*xrM6$cnxiU5r|Va>GR;V5Cl(0l;Ana=|w-2fNXp<3a@Mv zlA7emEG^EMlJ;j%XhpxFHVu%$u|P=Pk}pTP58y@0Uk35^#mwKFcqm>=26cBhKz^>* z4&rLkJt9NL9ggw?S^g)+$?vHZx^*&vi-w|!7g+kMjqgvdRvZ`bJFkqce+fFwlJX16 z5~zF(n#|9@B~0f5dR1)fv{4pA9jdg`0_Zud1)FDOAS!of=bn-s8lS&2?~2;Bx6`J&~`43%jzR&R+ZEM{|DG<>}B0_*yO#p4QxB_pjqF;$&& zKXtT)H&8-FhzuG|p^svsCH6Cc+&zs62RAa6yt0V3$pD#UJ79!ToFfF_^z-*v5hAcY z2#|Je1O=*;LQZ*PqVAvwP)VkFVmFVEMB(EW6Id4AZ`+0NafvY%BxQS8%Tw#`e&32X z3#o;t(grhDv5}nWd+)(dKPHlMLfOSG!&d97OWC4%Ns!kmgv8KsT$y_*w@*rT#r45( zW^?)LN&ZozUMzzZ$7EPLP4$QW3{v5xLAtS<`=ijty`q*3)4((ILW#+X;*6}XryiOH zdTtDvv}-un`0HzL+E92n}3aoud=NCPQ^pB^hPRpR`JKli+m{qfDgl+NX9;?1(n8fYNmblR?jdq1VrOTg|Saf@*&R4R5^Z6 z`<`6*B12lsN-4Z@AyFFsBU5mBL55oYzC(@@;AZwm=Aa6Ii5qL&hG(*G+oN%DmLDIB z>xP;$@np4}pJ0l1*PT|}Y8bxkOVAJW7>V_CmYLUmt^4%j`#}H8QjHDIN`IUYgVE)m zWBa)-s44#H@d*yJDo~h@2m#{tUvHS_nh=&wpgE{zJ68Er&S8QDWdiz^(%*fo3_Fd?4b4sYCDz5vb4hK1vFrk^ZRzeyI0 z=U8(Ed8@H`lPQaKCy-R+8FTeAHSTY#__x^SKL#(couBF|rtaC7JM}(&`C6Cn63pi!j_dm246#gB?4DRT$IoE zOFqF{m_dOz?*5xLY?AGN-{I6l`*K`H*Ts4eJe$ni)&(h)c5R}~B!(0(Nhx`tR1zWs z!66R!=*+5(XNvVhv;>PZq~F5IL)plWM2>+UYI?TqXB5~*TDJ62T2?5rZ zkSn0&qf)yca36d|%~e3OpG)NR&O(1wx&JHA|>{!1Xueg zn6BqntH?&61p0!Yn_mGggEtj=d(W}Hei*YFJMBT2G-7ULQWS8cTraH|?4KMI&MyI` zmF15<7lHRzClWIc>Ow9aC!oryeH9!W1fj)W%77`?xGXWqgjzsU=n~2J?B>?!Yc+}z zx$(lj!VKgY{>JVy8t5kjD=13$*S8UzIr|qpZdup3BqkuE`6rNm~V~Fs3^)tWvX zQ4wVZPJ}8*piJU#_1UYo9aQpfy`9K%11wnYjn|}!iShNuK8?mmgmFOQ>NZo-(q0e% zDZ~gDnn#3exzmF+2-ixraiouwjW6$&3dyUzF6Oggv_#;KJAHdq@yC%aX-0gMg)^6~ zG?arBW*AKgBbK2!sR}$lJ9VZTiEoeVJo=ijzi<_wO^%Sop>ZSXdJj~!7YXS2y5e&H z=8NLrzr^p9+mGUV+ZB zD--0u)l3(t%S|{^jk}h4Ug2(u-MN%Pf_#L9oF!0i*4v9|)AT*t8Av$A+dYh4seS5K>f(U|R;=6T*gCtQJ)CSv18n z**X{{EJ_8n1PNtTwp>*Do}Q4gV{i))J$k)F5k%txazcb_fL&2;%uctnL=Z(}sEV(z z4<#q1T6xX7-AVuvqU9Gc6pB0qOz=dbZAg5Bua8iqWE zq#FgqpWIoB6Z%{zKd@T0*+Z4UYBd&)rAfEU;bDQ%<-!>Lvf!`Jf9CB~K83hpO>+RB zXwuip+PKCKo;6Z2A31Prx76vK#$^pcN^6+}NWM5A*_u6t#>;bq6uia%@=3yz_Tvy= zX6p)R;kp8-bpX8sn*daa_i0zw)kxHzhhqtXLG-+RBl+y5utUD2%5b`wbx?K#U)y*!hGi zI5{EyGXBmT!bYrDjWfqptYuY}XeGKJ*PhQwglP9!441vywwX|1-O_Uq!^?+@YpiVy z+@SyP$~GSMIl{`Amlo+ZfcaE=iwMwl#koQ0@n}2bNl`=Sx8NDfTd&U^GV2mf%Utst0)PE}MC$p2u zJC_2-3^C}-tV~HlMkcSvEiYoyKTZ+({)G7=r1*A-skspo1)uf2px2LZejA26X?CRKTW zin`Io5W;%33u!lpGH!jnDirDP$~;zSVMf>`E-E3)0YTCUU*Vd)xMxeoKqK7VAN7*M zopV+=CVZ`j{>iQ22+00?xv&sXEx|!$HU0)`E%lOjVmB;Ee<-FN05lE#fLZ23dE1d4 z4T;BxzLMdokre8sxL8X&#JHZ1uQqq~L@WRBf5w1p6J>?03o}~j+O)j^eNrfUeoF@X z)&atE%7#%4lqRPEytQT>V2VM%T^MDeB&Ls73mV~iJtcOBxzZfDWhDz3UkVz7VV^)P zDpQ`mzZ+EJhIwa@cbMrAXvBe;M zn2Jrv1un9PwRBr^{W1`|Ueh#4zg74Jj#yq=`q_r-dY(00RtQgdfu+&Cr#pw0jR!Cn z1U}e>x&YkT#rE5;(gjcon~ZzBlWn}_Ftm)iN!grYbx^%^I&R0H86YQ!F52@K)3+-r zUEss@dnfQr@c!D6Tbp!qx^<-S{1K?^4KY|B2y>=sJ~a5nLR|A<+1l1suu+F<1kZV} zjVt#40Ss8Qpxv`bqn-eH45H`H+R5;o{AG2*qYID1th*|Sw-n-=^L0tvt5!oxnAcO7 zE|^p@(+E%qL`O-EivXdi^o5iw0e;rr7t1t><>E2o_%!+C#0VN&VR?Y-pODOQ*lw5!9xu>2x_O`5pvrAwut@> zwD81zyr>Ex#;mWuHVv;$-ezy8O7Vuo>j{Y!PMp_x(#*PF{`Ng!xORXu+3Og_1rMQG<;auJlLqh7Fp-Iu33o5uxW(clFouwlyn`0`nr06>&A(hQMS z`g9X(n$#*vlcJ*O>J$bN2+}kL!Y#KXpokkOQOLyL@A~a*-D9o(ia=#NnN(XL3OqDW zWiSYWHwN3vQS>8)$(9IRy>@l$tP=|H{d`+N~6dJf6^*{-L7PVmS>yTFk#R1 zp5b7@@EMk>1w#>&-TGgSY2D__5WNw>z!Y}1khhEZ47tHipU?(&?<)*Pea$AY5+4*Zy(K> z5W4$F0;%{_%K2L56V zp~xT0pMki~%tsbM))^-Oy#kjoC9hI<(?RhQwOI&i4p*HXNK!14T}Ucm6Y7-~DG%0< zIi~wk<+T1(8!mx9|5n4-%C*;S&sQ82!#M;$?oCaxSTuWz?W!MQXTZnSCHT?ON>8OBXx&S&v~L`Pjm+px;clO|pb7N%@L zQ0Jwml6VP!?H}-lbM^V#p)P8srKWG5F67IzM@bJVc)Oiyb^emde`r96YwIeu_=0b2 zt)*{4Wa`caZ;1=kR#Y!DDj%-txP1oi%=Av96T541Fh-PLQ*9526r5GX_Pj!l)Wm-B z*UIHRF&^YO=hN(dDt+zxUWb1b#|E&?zrgy!uNNSyO<{i;$dJ9Sc}ntk!v9;Q*h z9XQEXyO;0_DhFzD?U<)R6slEXXlTq5iPL1^KCJVfH5b|Fa;haEB)gbAN3KWP{pf`8 z!HaRjfAxzY!8WTgA&@?t4PBQzKhkygc+bks*!c4z!FGP4ZUW-_;))dDQztiHCR<#> zR_2mR;%sIbmgOJfyB~yqWG>6Oat+KwEcPKpg?$(G7mKe8sjb&%ir8}*RtT$yoc(;0 z8RfF5+;vC4SSwF+tN zO)8cnPV7xik262|q`<4I*Rkvh-=N9&jwaAeaZpxEZ&U~X0v zsagH>v#b+Pw_4i(kLi&j(Y#CAZ_5HurPW%+*7??h@W@@$&7K)Qoe_W1vK4_%v$gS0 z0fMj&uBzD=bZ!8}bj@kjNCs#pamQ$>u}D3@n3};W9Eew9acSA=dBzM{8MtGK2#lnw zAAS~PJ)~L>#v^KalNTWAUgI>=(l`aWNodIj0Q>}-*?WR&+Y5TBI=_3{c3Y@c(*`2=t@v{P6w1pBIv$(tfs%a_N?=ot?{W;`W>riNi{LwMog zb*dSnkH>)Z=1eLzw)l(M-D4#_?? z+aGXgIQTS5EpACIoM|^4zda3r;e7`#%j?@!{_&ATLyNbw9`z=6#roM7$b2lo`Ply6 zj;u`D^77nTqbM7X%O^H%9Pb}J=ezH-q}-m?=0c7WRZ4fyKh@$+ud)BUs2-yI(Jxm& zlbFA1JDJGk5VP^ke!HW4E+f$*)m!8NzQkOE;dXv^H!7CZUwhG;k9p>0wVxMQYQW9~ z`d$feLPY(KQ#hj-LD_K{kCM3r6mO3?${Y>NJoL?lFw^9?ywv&pB%O|Nx5sZPq~dpU zd(T_ODOR%D0l#acbc4~oag`Wh@3d{W1pW{Z5K=StHr}9uHSqQ{f-$BYMQES- z9QH;F__NZ9Ij}VD2BlSGE|IfFSh9T+Kk-#pmMNb~A2~36ZePA3HPra_G*E27_&b-N z@;G0TPVz@z^yZn})(Z*f%QEIKKiR2m-4zrLnxwkbF_gLj# z-3Thkl9LIpXXZ#&4p-Y)7+5ASS71gX(nkn}*`BDCH}?Ch-|TX_a;VZf#G|qSMl&JH zj?N(c@%CK?*1`y^OKbTHpf+p(WLH7mb0^fg(vZ7JQvFIjJAVT)&ZIa zD$I}_nhy;buTcT(tk2gwVkF9a0a+;1L$K}cK5$_A7O>E3Pj!3&M!@-J-fjnH?4*fN zT)?MP>a#Y&*Ne2flb+cz2J|tt$ zb)T%}!hYaEs)J0LJc9872b!?{`iX_)y9G6uJ9!rQ8&R6;^+oE@pe;j{_3EZI={4pXOsw@KN`4wy@EI5K;-Pb6th4Z53uqwTCZ6^p6DR~f~ zL5e}HjQHH0gD|k}ncSr|G8c+8TB@N~?yQSOps>BDiU4)tdsWihaUZJ96dEu2(v-=4 z!;Jztg;(C^hb0#XtenEZoDK$RG?m&oVK1SBwfgTbEIGtpM%t@Eu71Tre`mRozHtDH zWL_coenx!&eVKq;mW=XZWpb6E#1_a=Iuz%)HhTurA6Hx z7lGcd<&4#)vNAQQm)w-5(i>BT@*~I<9mQV`>oEEnEkv$>fCHr%t zG){CBWg``cuUWl#u+BIxun!PTqw=6%uEaf>f~{luuI?0|>RazTz>AK02Y>GbcBLwb zpauml{)bFqmoZi|3<_$*WAhc6n#e@eAb*HsLxH;>(j*23HqtDqqC6=gH=#&UzK+KY z-?1)I*alFE8F=Lh?aG@upww=_&43prv%CUO@EV64Biz=Eo%Mn;&|Ay2wwfIL>w)KV{2Ms%12gv`7upq!kpd?^7sSNp}%Ef2~W!XV3mYz|p>e^F^xb zIN1bd&HnZFe8f-8YgU}95ZtA*cNz2tUFid+iUVEQAC^_~w4!hGr7BH{#kJk9F#ihd zyw&r5$8{<4&mnj5#pK)*x_3IPmK4IgdSdCU6Cot4!JKaacMeT1Za>H%MPC0wz^v)3 zXX#_vPq_K9&g~51s59wgZrx{crw>GNG!!2O8I(OVF6b)=Creb7PXT18o4i*qjtku5 z^!kb(xTuWU{YeN)iF9y7W%|yD6dYv7!dYe{tz12kP^9I&WXfE+ML#Ml?(fguZewf@4H`>y)z5?}9 z)V3q;#)U1h$}jYG&h+1^;^>dJqzY}3_;!kXZcOFQ>sg2sq`m9vSw@hms`eu+pz^}2T zdnm`B29s9BIfa@IfAzQgcQRt64=D}%ku-p(V9?LWDtI^Qfd(X1(RvH@EiF*6jW0u1 zqS1t=AcsYmXJ9e+TViN9gzeUUUq%#%#OCQla!Cmy+l_r1LiP-nY21dStjc%)eL)|45#QUY?jDm(a`S68T{3$5 zF}>$FyhiwlD>(Zp@r8BYNtV%fHf#@|3RzOD$=uXE=h+%d^W6+2Z4!3t2%)-wk=0DD zG4-!9)(&!FZ+j^UF`pJo*<0jJsu7>*_+Cg2j3-*SAkxdK2Ms9;*k&bBq>qTD@$HOn zTEEM>`*2)Crfn!Qgp~w@H#&pw{g3hFz1(D_41ZdTvU?TFmFJXd?ssg5yDEw6smZs- zFCQkZfZW-PJM%nVnC#JkPO35;)MZmGE~(^Fb3ld5v$#xlLM}1PWmtjF%X0AuSnr(F zinm-!hyt-5&wt%FkwzEYs))Qjgj^FnF0 zg(36KQiJ1x6CL=OZ`7tE*94*EzSEIfIEhXzp06ieI%+iv6&+GmCU#ZC{MDH!PTv!) z39?DuvIq84=ud7kGhWEB zZ;R$~4;gXR3&FvhXl}0yJqqU#=D{S8e)a?VR7BkqXuj`waYtcDv-wkhT>&AnVh?}n z(`V-?PgY$`hI|$Cy_?TRtK*K=KbI~5iGx1nzwrU)sKx>oXr)fl6J?5lO>+MHU|B_5 z(|SQol~HNUtMNdR56Ei-Lx*{7qAORRE#}7d!t@+n zk+B3R$!%q>5hfX>M4HBUv{1Lwf9aP5gcpM=|DLcQ{^{}%CJ#Nv-S{$Kl##}7G>^0L zHO!(pBis(4X)ZGyCXH-q&7Z!s$?NMSQ0Nt#9%FJ=GW4(=(J@yF;H?2JgTYR6UQr@|&gMFjR&6 zvc;Y^zBZo5DbYTdV5%O9k}wsOG3v{>U&jWG|B*3s(SXkAvK#mA*S&Q3;BvGCx_Qoh zxnug40NQl{pD(BNn)Fh!h$(N?toPySv@tIT;vdeBW+ueO*rGEZD4Poz-h*C<{m`D> z3ATy(TkFx$JSt!DY~$2+cG+~nlf3<3Pcl&xIkzuX;Jh%pp?>mXgrK{zVeJU_mF{N zIQZ(a$qfYLzN~|~EHR?PyQ(1sde=*=%=)n1v=jbeFi;^ol-9 zkS&n&=rgU3{qio=Sftg&797#O)BBfO8#1VPak}KrWJC+J{PMc>X5^Dhdj1KvJ3Ovr z9`W+@!`1Qrxnhs9o$1evHK{)nOT=%jWKQ(9#-0_mI;-u1^^z6xUvpyXN3@3Pp0%vL z23tRSuVuK#LyNEp1s^2Mjj@#(%%E|IOVByU|4_VnZx!cY!}BEcoaz>^`8)r!`2yXn`<-IQSn&2>&Ya{Ens5#1IPXJ8qhMBc5EQExJyZK-}DS2MKl&3$gu^ zq3MEkv)6ZbRz>zB1^M3II_RChe{nON;W0->?(N5}PnqKFPZ6UZI8M0co=RuSupai^ z#(ai=Q$ct`6;~^G6|u54>?RC?s71Y%sYL=YYvAzEc%WMzxMP^MB$V~@xNXO;Hjmat z9@HrBB#V$!ikEgZ*X6cAIexAm^;p-%bz^SPAG;-w`b!ygE`v29CMkmbSA(d;H%Kx^ zK|J>^S0sZ*^A1KDsDxP`=YpH(Rr<$SUpM=i-k1-FZDaqTUTc<^ku`c^FIMY+zuxlL zMziQs8&m1i)@39|aPf7Lr40Ot$; z7Q})$(jxJTnFD*cfCoGSNQW+x)0q{`jZzo`~q5A&y0&sS4lQ9oW z(H&{xBtIT$hX3@>~JC@H@d;PzzP`*7Gmw%-}FK6oE%S55? z0aVUik9(Wu7$2sr-xmX?@m-ntWlL%&3^pTDA1WeRE%aF2VRdSjoJW3{5{^4#JP>lu z5vIZ$y_0*4{e|kmniFPZd>NF?>9F^NjkqpW!7OK{vbSD4xtKs>RGLgdJn`wZ^%i8! zeLusB##xvI10F?fmYA*IxKF89O)vRSw878U4+KC&lFDax&nNE4cp|uwTFu^{7CfcV zBFM=~^l#GTWBZ>}fA<{+lSTpFh?S7Y0_990nszcBVd?{7LF`cLRtMxY2(%oiF+@L( z<*R5OldfrxNrNHx_Y`3a%g6%FNlQR)W(m!Zv`({@RJHN3N}5T!zrM(Z2g46PWZzWt zN#B_!-Eq%s=0!w<^#=TqdM@~;JaWsBn9>~coKPfU*JFW-@@De$`IkdeLzBXXT@ihs zZeLu=MAc-`A9*;|yN>UcI>UMrYK0-r$?DlR-z`MyeenbBqXN$1zW%BsUrK__n`LW0R_t zYtCK(2@XyWj)tlN(y3u`SF>8nKi;qJ)pxTS=S+WHQmr#$dxu0;dhZ+#& z$0UV7^@X2odzIwr1I4f`5f^25kLMuJZ3Hv|HTU;f z5>U$-`#Ry-oQ%nh`o-m?kg=O6-MpTmhC)pmZn2nD`QL>cbpo)6RfBqfdbQUKgIM8) zAeU^>{>c~Z!}kNiq$-5&-H9dfD3}{B?fTt?!1W*4bY1(f@jeH-k_MS`^TuR?G|UZ) zeU1MRSVIA@bE;i(uv9NpM58aAQ@SEH(W1V}?-{#P9emt)uzA!zjD?MeInUok8XI;6 zPI5GR@+Cy!QiN9ZfkZB|(SE3aNiKuaN`7Es^_o5%@w}qw*1-mnEsYsN{DpUQ66m%pC8B5maTHZZrOLUYDyX5tZ^@8pRb3=!mT zu4Q)ic%_QmdaHzNJzO$Vs5J2Bd)aE-^CW_uvR`1|AJtwzO->y_*gc|u>904F`{ZnB zIcO-=*yrQk#~MqE<@Eh^vukh9-KN{BJ$o>L1t{u(Q?7uEVpY2gXGc39f?#^*DIadQ zT7VGx{lRFSeaCL!GbViUwbUV_pFyYd&hYd5sR}0ZvfhRZa+7!K+nje|g*#>Nz~{E( zX?LdJ-y-J;yr^p8857p1w z&&8`A&q_p$Spa9J2Vf;&%L3GE4&oPW8`Ac8sZ51<{)DL3V~^;K9%?u4!V&Z}|8q-@u=j$hZs z5oj{rJhZW5>|MBs?zqu;a`P>Qg6qZ&sxcUM{QK&=GwUAA)jnNRAEi{yd^^N{?Hp9c zzmA7+vA222QF&ZZSXcD5k36U+V4dBeXZr}j0k-r7fls{B#tid%-isVCH}~u+w5~Q0 zPm7}j4b1m3($d^72Yqk*_0N#xN?~@_8>2!JE&T893kbrN%7`b;D~@%)io9f4e7fkp z=kkE}v%q&RB>s)g5YG_iE8>A5AT;q^5}B`HE4EmEXHk>BYPLYPX^lT0>5=Sv?l9#Y zV9HDwc$fyKksqe;s>tPyK$%$ zf9ItPi{$INTCGKW1c9>sQ(8gg2i#$jYD}ejGgBd~o?W%eq~oG&H{BCZ02)R)A|Z4c^0X ze*457j&24#H^g&VIVXFT-gZ$cf0|0l=)chiqis3N46@$6t!(c2^?E_Y-Tvq zDGh`MSm!}HVJ&Z_-#}4%J<6{id9qT*MV4CyxiFsBaI^ab!cvC0&-49xb4ALhSA18h zqIkmyJ;E~%HdkBkwkN4dVN-T^#5?4cuwf@c`rahT#tm0p6zM!9c-6{Ze~{wL`|i5L zg4(wPJfpFrS3NNg+8>8);^wBF#}+HLT%Zv-55*q&o@MX`?=O@L>Xd_M0XEA1m!zUVp`OI_q(0&ySQr zQe*9VKP_99hxrHg8SSK9s$GDRS0au&oCQEFUmn@L!O4Uq6iRn|o)dEgIA`a)yBN9_ zTxKrjNSDS}6DvRsLus}ZM}D~ileR7mVme<3-n}&5UUoA%Y4%+;?W3p&&3gQq(^WoWw-M1JMIvBi>b!}#_$zrmp@row$iu8YN*nq|m9}EZ0md5c2 zeaW`3{x}XUpk-~xNjwq@+LSNu?gJR}dJoPw>bxvMGB$XK5%mK#q)-Ky?DO5F&KqGd zST&!Xjrv+i)YH_3-b5n6p*Dbd;|0P z_vU@Zd^t2%SvD(YRPfeD{ab8FFX|!Z1fp*vLcjFJNGSJYyU|U^m!^M%y|&YL*wc=d zSRRdelq*=CD*YxJVQOdoz|Q4*{x#Y~aVO1-mHOAwu5WF0UU=qpU!Xm==&=uQup)oS z&2EsT`hCs+ZTl&WmzqDLo8bOAI~r|D4O$fUG_Ou^ZsgE!^sLGoBa+j*j>)b1cd3_AG*Xn1*lGx6TtYA0Hy-D?$o7-V9D8=>F@Gm zD`g-c~i$=n6S@2}h%Q(<51+fnS>^z6acG`^et`>T<7VA|v{g}`a2D~*t zn)K!8nn*X9{?KA*^C!%8#%$pqiz1!DzHbElaHvWXh&fBCwm^G7mQ=}?F7KeWpkIO= zAHHvlJ!TzSUs zJkqZ_PQ5!$R{0FY7ULq^i60s?F6=3t!UPl-d^=1NGhQL{Us#@As$+VGrdq-a47XYm5*&7trnTXH*8(j_otgFMqkZH7vB zH$rTeRGn%ex;(c34?89mL$R1nSsoMuE_HxZ^?VpS3@e@!~UMp?BytA!T5 zT9p?VV7o!pD_F;A+&dFKGLvk(VaZUM)VHEcDXuxxE1w0kgu|PaswrsRm_A}C7MuBW zD1v5;OCN}lj+z-bY>wu9X8z5$-xm@{RIF4oV3f7Fsg=~BSbEA4vUOMI{FktEF$XNi zmd5mh>_Gp+V+msmSsblx@2^tSB_iutb=d=*X(uxM4Y#)ij)V`H<>q7R`S6D5STk3Q zYXpvRaWS#yPjHnzwk5ZsidKh2bRy0%jbG0>mqm|1qy+D`pEsJ?Rz8yrurcu0)9pKm zT0=Guv@mC4ey*5Z{;%j?;a8Q$Al54@k@erJag>~BL-JC!I&dYd`mc%f5BT9fi}wRU z*aP=ZxY%@Bk?S8v0?jhz$KKnp1fd|^)!`~I_Q;8CLI&1j2EBbFb@^;ACAmkBJ2aAB zt@DPo6Ky%f@m|=wru(jq4RSk)g;d!Ghzs?0F8c)LDF3}tU=Qf9>V@Cp2e}o>V0N2e z?##d8mw1@GuIjo86C`V~cmA3z=Dt3Qa2^HwhkVG903Fodn-yOcS}w_Y3=-Z4If@$< z$?AWHiHfTXc4R9U)quTVmlSOcE3lpFhf}lHXhp<(Or{?DFO%)lMtuem=aM9U0cau@)a=(Fxr0a~!*OK4(TP`VF{ybhGLSdB6SI zYobD{l?U|*dtPv6Pd>!)no#kJ?s8_I?iJlie!!DL^B~Te*Z_^=PaFdh*BVvw>aczQ z#fVxdve{5`b8@DkXoEu?SVrn;$vIY3Ql3{l+W+w??KLS{H^<>Zg0u-o8rRQqT5g%| ze$rGj9C!BNX)+o@Y5}~1)6H|AU5=m2?o04KxqqEQI9KQvJ2H(3eauQj`Hth5vr0lE z>AFqkpb|M>KLjQJCxYf zWT1mQ9sP!$W;N%BA6Ikq8Ic2tiOu?Zzs{{BcPP1MAAv}bz?3QU0(t#Cd{m|G3zd_& z!+C!(XUm}4+osUMLgoBQ9yDC4 z95ULjMCy5B(U_{o|F^r0!3^E*K$wA3+aiP0f}}Z;GB&KylUNR)IWIE?tsri-)LACvqJWQ|kylYCjoo}J zQV3WlUO$-K&OFB9OEDTQrmYj1ATQQL(~$#4XxP`;glm~M@!DYIXpZglS$_GKw9A2@ z_*7cnYWdrbSYPwsPpb+h?`j#Wh~j%8lYDzbwA8JRKhc-GBc0b42V*HfcTyvhd)IHS zln$sn@6B1C2%1{5-Du;u&wld_9~0f@F3=C$${S9=AB_A}SNQD1v%#b!_oe9Xf=jAV z-DRmv>v^XOUt4)rR^X z5ZM2@z&~}}|7=zN=LrIAGv0voBj$Net(h8?5_v)A9FF3S$1c zp8u~-H+FSzWkPJL#~nECXJsr@SoCfK?lBhyHe>_W#0MI8=JzxJZLD^?eywTX>0V#g z?@JAX41jLB#X>-`YoOE8oeu20r!QT-$>N>y`z|3+39xtHR@KmePXTwN0l4@FthBXH z>F*!I!H@Oa8y}W~etY}%*1hq4(;y1No^#;$pIS;d1ybD<>Vd5hx962V7gLG@E=IKv z^Y~kVM)G3$pAVz1$OG4DaSg)(VBgfkZ`yFP5o;C$4g@8@UV@JByCtlDI7;RB4G~v` zfH!rGd;M|apyW!!_4`E}o|Jzbo(21!T1pC&!btzTICAUnJ<15VpIY zVTl1huoXMi)npj}%?r@v5{u8>SKeRVSCo3)3K&dabaZkP3mF2cpZlwIFu;-q6@C9a z(QsV|FyzJ!MS=oETQ;Wx7__%*hT9zMv2+*k%W&PhP@PaM)={N3Y?%$h#`mX6l!?73 zWg`Giv68(P`F)B?aC?eZAKU-_ofWo`3AS`++xM%{1z_vbhs+=TGbuI|1GPUeUiiDv z^5bei;9dZjE!d&2i9>q&jQG!iYo5-f%SuKnIA2RSA-MZ{LOG1wyGnX`>-2V>5_r(R zD{!Pait7JMA`JE#|6i6CvGs|VeecJ1Qh5r=TKs@*ibE5k8|Oh&MsgVcn{4+x?guwUY9HPA1ZIichL|P5bN0lFM_ZZs zu*PM+3vpse&H6E*$K+QTWTpscM|u47jmyX9tox1Ttv>5O7!bFSn+*8mX(h>rzzU{h zkyU>lsD#}t0&@oC{x8hz=TL`BSva%_XP|Dt9JCjXDMnVZ$Q8cW~ z%Mi|_`ZMd&*%5Y_jddJbN%tYt~but`Fg#c$MHBG$NlkEY&4md zbR}NH!Wvh$fEci3 z0#AH1GqtFB6TXDszN_Ks(d1b*Hjkli4$91~-w*KR;lG2qG&3G_pv%=Fw#qp2!rB9AD4LJA&(Hp~P zNOB;5=pX}$P@W!(0|;|5%hs26{`CPTnm<_uArX+H!m1-~M28-H_75IZI2#W``lq^H zBdkx@%`}VpY}*Z&+G-yyw-~|F^zsNP(~YDkHUZ=60gqMm?`~L_?F@OZ;Ogeo*&xfx zDFaqL?F?s&S?m%3Hos;3y+Vj1!%jZ{&ZP=>fw$ZG~AQZl2m=^x9H>Y0SeTFI5wij`n~&P5Hk6T=0D3cba%RqdfGnU#} zz5;}}5`PE*y|V{tsclBbu9KnIY*Fyo1~|iA^Ax)&LHt!R;v?AU`>?6CtAJ#C0v6xb zk$h8EfHV=k>kkfpjtZ4#^pK&8lVaEsL`I}@3z9#HxUd?zq?4W%bK^hOHBh3xV#6)q zgYI*xUikd_E*cV5v`EAr5487q?@x!PrgGrg0tU?!n~zE?(|JGH&i=Y7#5ELmSjiRomqXOEmw@Z+sYYnb+rs~eLJ+g z73g$an9<6`Gi)!WU=5RG0F3Ke!T)n6Nts1zM@s%U4=xO`l+Cn}fuHWip~dO|?mem98HW7GNo* zbZZ#@f4%(Ie_K%w19kG~C96`Ba8YY#Y3mh-q~|CkJp3sUc&E&;-Z7_~Hjhn-g*(A- z`vf=!uJXt0A^ruLC`4u3;(3Egav4)t`{BgYM6qQezm^S&+@`)uqihHV(DHX$B)Mm) zazpcTdUiZEJqqx;>n}h^>dU&lwaLlO>u{cx_OAd!9f2|Rh` z_2XWf2YE~7Zy$2x^7qlldHNkEWj8+d^(fQ-ON(dx&4Tnn{l|42<@1UJUF1`B`vC1p zz0HJYkI%T3OfF|&2Rc-XVG=oV!b6zF;G?T38nRWjM%ZX@z*5>CGAJmBiR)v=VqYma zVLL%jHloTazB4yM>gG>YKI|e{sf{tb&il%ZI9t$g0i0%tg1WrPJxowI>?9Z26{(7! zz=B8WCsIVX_&1F=+}wZTaNBvO8Um(qM5Ybx$= z%>_SS6+ODonGd?xd}!CzA&q8EBqcHHYzw2=rs?NXjlpM+>&UY4~DF76NLdzWDrupMMryTLyypomQhRyR8tSLFWRGzx zUEH0`OlTE!WGY?YM#S?Y3-QK0IJn6O7I{~vZR`2bfKwV)0gC(7;DJW}0G=$ZzgpVe z>-p|RTTrb=mm_*#IaSuR&Z7|Fml|j1dAVWX4vFdy^AI52Lb-1W}3 zdb19MsV|RoHm8y02cLhn#rE@KA0s@I`#0^(Ta@YU#i9_(Mdq)SQD(${4kx-_RavO1+z-*l3BjrfGoQcyo3sVic{U@?H!L2$F0A6orRA3DkeM7y^F2R zK@n9fG@NHzUpGj$Mr^$s96cp&u$n{|>B`|nLZQIM+#Oec{C`d^n-crhJ8qP_$BGS!8j&SOdB2j?$}6L;_@u5)pQhb_yhHe`Qe5Ul>-zvDQc? z5+wsQx8Big%@}5F?=Far&NH>16 zKGE6)Vp@6m;ibLFzzV6yCSt74RXnTFKCy;8NChfXWdh|z#>^y>+f->6aj<JD?Mu>wuQxy1m=-hTuOGA|foMU8Ul%qh7jHj{)E=^DrHJw*sHnLe9d5L29 z^xdCYR;I9UPdk-2AAS2BZP{!7qpg31Tmgh-IVYN*vS0kwSw7z@+@S3X>##riTlQn)NU`NObVDv(JZj_l za2Bq<;4g@9Z;RagAAk9I62*w-F<@4DDut00hEK%TIJ#03)ctV`->kP>RiS zv`eVoF{2|~t*0U-OvVk~Rke{)m!p)RHWQ$b_C8T|{6K;rP?q@+VKKoGQ8911`tEL5(S8?!ekrHMFpg6jv&fEM*fb zu!vkY&NdS`wVj{{O-)#dyDeD!XBzZxcc;t9tu!f?Nm*F94B}Gbp^)C&fcijnEDjAZ zIlz*+{8SqdQCwDVZ=Kq7<=V7lAccbdzMCE!`8V!7u0Ot8Vi#= z1f#>d+lXX)*yuzKKi|`0%_Q`gD79}xt4qb&D2hztXV9(F}vo#z- zdZV2Q3JhmhS}XU*X6X?!d%Xwz`4$>B*KD2NMEo>zt?!lD(sVD&#{VC?*Uvh5FhHSm z!fw5e&BHreysOL=sIgCth6{|xp_6fB?=WnDb@NiK~^vNQrwz@G)O4yBii zerP^n!}P#b>fbaCLScP#d)KRGWHnMUxjX` zqPJ3dlj&{qet)g6=a?KoT`A@8Fa8EVYIg#Kf+rjds`sloBdTB*Q}i&M3Q1HhiOqGa zQdNW!CgGB2kEFpI)B#mK=|DmgFHDk#+j|^-bDWXW{Z=>|1gbq>NB_re%l~=AjT-)3 zM&dI+gwuZ7kB82k@miU-EGd4vZSl~-;Ajct*jF!?9pPKCv*ZpdMZg)Th-Hpwx{0i&pGy?eM z;pd&;ge~Vy1O%$E!Zy&aA9dmhSeeM^b7O`KEH5Eb9f5lO9d=X4fzEaLyvTq>$o>ieAW&TV+j zmXr@uiQ1qdGkM z?+=KL{`eR4cV>e(c1YaRcSSsvrLJUQvc5hK64l&2Opd=_w`eBveQK{DX3MU&L(h`CD|odIix$K*Kzn}BcWnq=Zxx~9CYK9-q~I&4gR9qp=g`|E6>#(RNacPt&D!&vvZ_jt{u zevnMQ$^Hoh-6pbJzeMhWZA*;TB6-qXvBiKuQ)z6#wb1q=zQZMItU&yaPyGr6;Z=BV zVYnWs34knFs2|f_EaO5DYcFEmNp(>@zWHMJi%mH}gQ5l?F@k~;e4Jz-Sp~15j!eAp zcF+e`u`k9yiwUGUp|e+=6W_wpMPXrxbiwMUU~3MTSfS<xf7Fls zK(qR886(vyS6JF}gJzmWT_djM`fc=;pcdA;Yf|TS^nem*w^lhzdRxD#4ts`UBP26d zlxIJs4?l9ac6+SF0>|I=6_<;Lya>3nm~kY zdGt0vbyfFk_qq2Wq$MTT?bXB!1nq;7;=~unpx<}K3vf~4;u9|TtSoH9dgldwx>RPe zgPT^T>TeAt$_muRs#g^EeSQ{WN!ke!HBL)8T^B5`aBvU~?s*I<`Hc)`)W@XRaKd|2 zuG&T{U0*yiI6sl-ysQ{~%>UhV!u||BYY|iZMR4=s0W873XL{$2N$&GR3whJ>wgKZa zMO^lodYepOIa9#?^ut8+iCC!Z2N$Pcz4zN5VK&*RCl&=UbbThV3Md-}zEiRv`~XRr z`V}wVx`tEmL`-}rAJf+RqN)joSV-CSVJC7(+pr9%X>*IDDFov7tGJsPOrA? zfj}mCg9XpHGq%z^1DtRlh1qz2f&9KK9ZWJTLQoh%L9l`<1ts}4K-MQwm!fez`bE?_ zsWM2PSIYs6W7&lKHp!nVmYZqo$0h)*l<-_N!scsGK6fi#X>6hDYeB2tBy!h+o!ItC zsNa`=>)!9LaRfBSeVhDbqmX!hnb^s|v+OA8Z*pu8pz-}^^{ZVJYK-O?6kQM?Ey~ZDc?p|#xYH($15)U>`Q`b%mTSmLWnCK9 zLGqnn5M_MSBPG@Ig>}aNy_}a?wyxa#WyglIm)u$@oDbfH_%w+>_+P%&rm*>SP?bg+ zE=?woD_|@_qYJCAE1EBw>yG9)^cfPYc_Yr zX5rcs=n7p$cN8zUJwJz`6VNA#q2O|(i$H41A=+43+*H#wV@=zp7!hw}coIvzobQlH zNxxYQF%3K^8$_`GGIV)1AJYzG9J2hL%5bk|H2Lo*GUK#SY}`d&Em9!g<_TbG_HpuK z4P>xay6DPAz`4x$quH7?7K+fH&7057l#P4=HPJ|}`PRfICoSADDbb<3K6{77~y2pkYKR?(PNU#XtJhgmEk~AqBz%6nI#Lcuq={9}8Z9}7reANR; zE+UAxBxXSl>|=53Bwnf-MRo3%)|%!&Fco9a**l!sp5dOju{K>`i6Q;4B+6_Ue%VXMJr9@(tKQpX?Y9yF)b*L#`KVB)6>)TQz`Fst=v0iHm}u>Ja@KluC` z+s>LiNs@Lq3L_JQ+ClMDOQZD@sMgTj-Vctwi>%yDAe*_nSGsu-^}V-7tTPrCD%mAn znd+cp%0hC3fz^(ua(O2ALO7$lx|B|sIL$?d)ovnxIuWagDz+_4;;|h5I^QDly3@lY z49#ud^({rVtC*xont3QbUo6VP9kd$f;RmNs3N}92U|kk4T>*@@g3b?7x&|^nwaJxJm*g^`k|IS(RlY?EB{mKViE+(wRSI z=SR&EW>c`O__6FNivhxQ?D0VM>q|Cnv9m^l6iAeW1=FgHk-YPuSr6%)^*NLr{^67~ zo>PN<+!~6)LVD<8o#?uD6DzYrSU8Ss+ub|(^nxA})s62NAE;ug*pkR8PgB4?YT!_m zczDQeMxYqg=*f%)CF|7#y^32AMRY`L5cPN;5(N{Oc0)Ld+y~NDaBOQMeeMJhg{5|c%B+YzmKmI9LNc)SeqS~1;&g) zNqvn(E(30|N}9}eQx=_B!sHIS#DI;EzgGRO^_=6EKS1qu{mU!MY<`S4f^`=+#x95? z{pv+Lr1BL!LxR5~iBdu#$I$ja>-DF+8-gR<)L{Dkh6O44lF_i~WE9gPp@d;)`DDOR z6?U+kA68TY|BfC_+h)09!I~i?!r3<8%WRR< zj#-L`h1}|+WsiS?mj3m&qzu&T`>@RV|ltg>Jbw6-l|3Sz)QRQ-0 z<8@u`uO=ilUhkCMn#EPno1x&KaF0)TN=1uwg_t9Q=6e%3i($TdVBE&pQi!zbJR@cK z`i4b!pW?@l@2FTFDEbB$3NPaP*Jh{qxYSe%CPX8jC=Kr-!Rosy!qpBgdb9J>EpGfb zh6!-mz3G&{oDU{&pxsNnnD0W=z5kvjn{q8Z`C_x1ibikV1&@v$WCEE(|1%uC5?nU{ zp#hKnIhtX$VE=r9qHh}lHLlvhWmMDp4@W~%8s2g-tG6oE>c&)xkA?iic-bb6yq&qe z;hgqSvB86kpY{ILs=-fDv_L@=Ci+yr`(IBdmI4>3nMBrZbW3rL((hB|Ik8Ne2I_vb z0xCr+xqk+P|F?3BSRMD^@&44)#sxw)6)_~i`8aI?QioWA%tX4p~<+jTx{|0 zx-QG=r@6g(qCE<9x&h2 zDk!+_hVUFV_N+QPsz1B^zy9pJ;3Oq=amSIL1(Q(hOZe_C+f71%LnRi8Hy?H=^)wM5a5`5#pOktwX%eDQ7`s=SJo^eW`M>dqw0=PSS{ zVQ0wLqjtbc<{WK;Iyl1e+E$F17h`T%8A4rvh9o@;+pe(9b-$6fM}SFM4Dqq{g#ebU zop^hgPs1|%VfGQ!*N#kU%@>7g%#P}?*=0bqDNnaWot`E)!3Qv3yWoY8Fl#vHIcoo< z3R88!gAQC;b|$P@D3=d8#?t?pyrzQgYpXGN#5?UZO@Y?w0Ww|)c5uzq>s@1@vdsuR z(9<5c2U|O-X?>ZM8LiC&@mtpF&sMQw@*X5_4HrZ*OvANEmqAS#EOv@wF+RfpaYV;o z)y2+=SDfn(Z1{g*Qw<6#XD*D9eJF+R|2sCqVKM1YezkJe{Q?%CH`=3Ne9tr<*>$Z# zj6(SUo*5x&vh`!^GzF&AN58$Rn0MavKHtVdjoh(1@G7<;JKVBZ1yMn4iJ_P7b*uFH zh-K{Wa`+$6FgAUJwN!|khZRBY8jQZNJ|E8p9KwI*A-kXMTn#*)xFa=3<-67Zn=NeC zQw9M>*;o4?+p;VD`%t}z&btpMf?WAWjrSHRw-h@{_07P_X0Bv%`|tf#QEV~pLG3dJ z%1p;AE`i9vlO(br2f}z`MKr_@pI{CTzyERGSIptw zn#=uqtl?^Rk5&0}r!Ww5H^(5C(2jwo)u5&d( zEg(?aTl5$%7=$OC&wm-gBtJ~D@g3$a)rr>(Rp&SVxR)wN99e#c9EP1|28YL6y;>2i zU)^YppS&g>=VYvy4r8cZ`1NIM526!O%-}+TPTf<|e~D4@CqCm2&Oiq!>{b~|!-XzG zlG+fI@D(-S1XXZ*w}{NY7xVPnVO*$nJ}x zFTKHfk==-H2}Bu4xP96VruI~XOxO|*J7i>m5ezxKTx+eQGfBGWEp7yu2oww`Tn@D^ zaW1Sod`#&Y;U3D+D-$4S#9zzcWQ4-OjX_R;iDC7X5^1rB4tVGSv8zT{Ulkr9zfgosz}=Pk=jOi~WwD%0#ITCM4U}&+bf;+06@X7Y(*-yB<2Kj}yLZqa65-1+ zB#EX>UMmOF&7-21U_Kk#)le-}zFP)ZW`O{ZJEO;-i$>jx=Rfy?mcn3vMB-r&=;$g( zB0?9VI4nra+iJ?NWBRFOFe44g#Rp0GYrsUgg(8Us)57SQG0=8)6nNGfdTmGop9PnI zw$18yAb2qT8l}TEU_RFZK6f{)x#HnU-25jJ4RYOq+l=gbFnFZeB*pqB=6Y24a3i9m z7U?Kn-oCnZj>69bW!^U{+WSk%{}$>5LG*vvtxK6SNK_lU)iH!`#+Rjg8yYx~yH#El z;X(Dv&I%0`!zCJ1?!P0w5^t?xKDF}I4dm!xx2d}D?;OD~NEawmx&PF#zKE&XIdLtx81-K@nk4>>9Go`k9=sQj7b8$;^GB z&bbyw92IC(PVE>J$rL)!!kEPA9(uwkUgtOsa%FvLB>r24DfYXv`0C~wn}8=B@o&MK zG}GBCNT_UY{rcMAZjP?}ny?@SN=08vH|G2w@sYl&#~Z(Ut2l)(9nD`x4&e0WaBJkf zizNBiY5#x)sVmZ|$RE-OM-J#&&la=;MT!Y3kEVy(rqb+Uh*$-XBsITP&s_?3XB{o- zaV%;iz>E^XC6I&xS9eLs&u4Iq{9N?_yyvd0AVjU|3_)VZNN4a=(|L-eyTCLStenCv zopCcIQdw;@#3b>DNlr_9{~^cnLKTknD9|hg?Q znlLP~g(q1~*WlYv*AdYKo2lBFGkuaVdQ)vR25ul*$`XxA7`zlX(B#SaAL{X9iUM>9 z&^%Qx%2)S-%dQh=GJ9$_^9sI?x6X>b{-T*tp5ShPk)9Oo(KPcyq$^!>VCxg(U( zQ|~~pQ?T6#Z?wkZVHv4|JkB}5Q4Dey)2fWp&Gu;qKCine2i~i!R)AclDsfbz>6ruZ))b&0r^0@ zICC{i7n{ezSGP*Hd&6n86>36F$VNnfDL(c6{(V0M_DAld<)x-F=M|5ogeNc4YVRr? zZ@fG4Kg0>(Y`D_lcdJ0b=c4JbflDp##|cR?#p=)5x1_gl3$$l#msyO}&z6DL^M9BW zV0aD{-YhFM!WFCw-RyM+B=o=f8C#W|F}%;OdY-! zhdFGal|G#{cScQ|lqof<`sbT)_dCg<{9LZvG`3$&#eBn30ia+gQ|~CqBaklr z{mCSk^JzS>Gk`-r1q)Et*iGjzI8USOpBkm9AZ>r|6jQYp)>}2oNCYk_4{vq1tw_=c z_&!CYCC?3cFB^TDdtrF)YVVA9=}Ovtj5pFk%_<3~7OA3gZ*F|fC2`!T#zIKk%b;O+ zeg5Q$$KjHGG}gGytSTAztc`Ha6KU?iTr|NeQ@yQ&^?NiN&io(vB*sN zaP{Z|*5`_do1Hirc-ndyFGlHyE)%St7}h-M5uxpr|E{m4FHMMMI1(#xa*ldtw*l&b zxTS&o(My9Z3x|anm4XK$JRB0OK%-Di6zwT42Zg$%lS5hXXDpmysaw+yH&MCZ`5YO7R$gfJ^&4Ls_G&@0G={xSEVd>t zZqr^Dd;Uu5uM}QJ5AZDUjMFM{175ALEXe*)i*NSL}N_*powhW2&UB~&sO%3pEHD@a%O@tmBP;$N|T{) zNq7S8@#4eB(pVS#9sQ#v#c48rOlu621D;ik(oa8_Hze*SH;-}>hl5%@SjX|A$W9j0 zak(SZ2eg81>U{Ik32ECNl|6oV*&)u1r}3U@ze6IRLY0@Kc!pnO#9IB#|6$SY;W_3c z!7tR&sus;BUllk~WWL%Pc#5=2zy|D&+kbhNSk?>Ys@;%u=n@Q?RtdJsZm7~dT5 zR!OYWPir4|-ML7c7~4DyQ|H@ys~_rWD+wmPf<7#Nc;_;*M=jI4UsacIx%)FWoF#7BOom-ycq{wHGT=aZSjMU+))kLz@lf|e(BW)0H%I;*ZHVdRrm+j3O-y02I}LaZF4sR3|u z0nPi9A=nw5e8HvTbQZ%TT@A+4HYcc(oUzn%r+{;$&?BUNHH7J*)3oT)Iog|bvjl&u zpzC&G!XsSR2yeC$h0VhV;7~CrC#RDJ%v_F4S;s{370+@L}W!&+D z{xQiQ({JFa1s%3`AG;FGcToX)fVWPRTDsY7nH#BsL#*7W0=kJl5?C%QQU&$IaVOP1uktaP1Z&nLd z7jqYLbp7YOt)Xj-eI`C^g!}}TjK7J|+y+cCcd+*5YOrGT-{Suo4<6R4(K<5_k+h&? zcp5T)<=1!5HL>YX%FpmA<#(fnHO|Q&goay0Z`X-?VHId}HwTpfvxO zT|9r2E4H^gfic$*U-*=Zm)t1oWS@wKQM!ql?d7W^ooQ^e-0a9;eJpnY%owAN@V{6H zTOT2Ra#CGpEj>Ls`l6#s&lSU=r7nfhGij{b^w#@S0z>@VzA63KSErENkhPoin7b{g zK||jI5(~fX)Mwqh)l$OT_Uy6!DJgNw7D`mR`cK^L8N_5CEGeXbb&GP$IKP!*V!!8S zns8g)X0^p&d>g*{dX=otcJ{T|wbQQ^Vb?7gUJs?)K2FayX1wyNsMn~>Z^yZQd&udn zxZUDajeE7Z#)X%V_40MlBg`PWXT3B<#eb5#X#+EwaVP@!{2*0%2t!cF9Jp#;+9aUA zlqBd#%}51&l%T=<9UF`jR=fNDw}t9m1FP36j|U}ixkEmX->?f%qq~|J$zxuK0BU~# zzW#2ct8&8+NEe_Aie^o8(HoNt6H~JC&G|TJ$x3^;Ox=fmm3xH<*<$7c(wCY(2|gpP zF~x@j_)K87>(qJ8uK7#s+v(Qtz}&oUh4#z^Uj0(PW4KQT_v=QqbBjVBoQAz%%Z)fA zd0*YWVa7rfp~q-{Dh1k;YU$l3ri6(Zw~x8%^KeWP2N-MVE_N|tiotMW>is65`oKh$~2ah!vBqdTL*dq=bIByurR zE_(Sj5%V<9g8AVC4QAiG$3KONCh!%~ce8^hE19h;N7!1=$_xA2DSR#!U}p<)lDbh% zXjrYG^+$=6NA(J2-cqCcBt+|vd2v!h^tMI#A=aW2u_sv6fZL}W%SYF(Y;VyXK<%xdY1WIph)5~a^$;^BOxT3z_8^m-dPelY(bO_1=9MOO;%t+rVnpU|!N3RL zGO?%$`y4CtAdnGxR*eajI-D%N6nYbP7G5zK;6@pHl!TWcnVZXK$`{nKF3Rs?Aq^Bl z@*;cFc#}LQti&}tbOzydo_ZG+l-kSt(h}B0*Ji;a#^5iqHA(8_RB-b;4{GD^(57VD z`eT(~ThKbX!ew$){5-W0K_(a+@V< zw8btG_H?YAjE}wM%Ufs+n~}#w^R525F7(vY>8Z#bsjT0ujd^sKeMFCCiu?8ZIv*aj z*jnLp9d2yQX8dfa7rTVQd4UPT=Ob8WZKm*fVb0F+l6+#{Z%8RS$tq5xALeefU3Q%s z>Yw6T5Lu7giW{-P9ZR3=xd++#-jYl-UBCO4{paNyIm~^W!esl18ez30>+klt>MBv4 ztldn+$ZdzLrWVhp@_v%|ApPt|)|ag;ct^1)huP&iFmN8zImOK;DcQku$oA%D`%Ou`ll?kL zn**2N*_OTDjn50bZO@VKs~-8L=XiJ4NgnSm6(ZhV(IT$*%hNuY;YR3qCM)fd{q+d+ z*{friY27~0K}qmvy4CK3x5ds-<^g8DP=+!DrT58{Eh{5HdTN|5VSD(j`vI@UJLBKO zOXWjwe-2&<80e>Zed}_FTM?;hApS|GS6UvuSm`X{7u~Y}OPQW-;SE@;X(q$!@mvI{ ztjkmzv&p9qNK)?kv1Cv6y^S=xDKAZ+Wq#t_tk6W6Aa`gsSEQ$WKDtx0c!9H9J}0a= zc3XjCnX34bBfpkxREWy}$KT5|56KFzk)}1eWp(g%5ot4iVGpL$m)QMoP?f2eJgIg* zfB!%)na)kra-AC2ymfay9V|)Wii}!3TSvr?1T1UyreA0YNHOF0$>j2II9$$TP!hIW z#2Hc&f5qB5sWCyAl6=|Z;hkrXb1g2UjMC(N&d-vpys+v)L;bXo#bWCxu$UU`vx%iM>fLF&%tUpRp$NDzR6=>B0J#i%v0H#L0H|TQ@vp!^vS+Z@rMOOVT2x z?nS??>9OLM3*?J~+E*sxGwNANj0=st6t8S!^4v1+w$*rC`eHMG zDQ4{Mr2l3BV=rTgmsUFeEANBFdI|2Z`6?N2nSJRg@q^NblRt6H0&csY-Q5^}?J-y8 z>@sUCE_c?MREYmDYPs8(nW48j`T0Y(CZa*J`07>t-owS5EA!s>3wEm|f5yjXR2~>{ zGurk@k^9&kj;xI$`=5PTby;WTp0hD2Cu6RXt@T;x(5c1Kr4+7_r~W#8<{zN>_mbje z%4ec|QiJId&K5s&!h#B_%wwc>M(!(83`(t1wh}oBoh?;9qGKa!nPnkVvwpo|<(up$ zqkS{xtZv)Nk^jvX(HyCuZ&F_4d2iFU!}A;&$4(`VMg6z`)Gn0qpX#KFuD$auh$_0U zyOI!fC%-m)C2%c>;a7P5ns&zI)WYrb`lUwoH{SQ$%hKSxA6=TcX=hgA zOv1eFeGO%;DP}@~)XUwU*7hJ}k@Hat5#HPJJ(-nTT0|baT2RSG>zs5DvF@;CSD6cP zr1fPK{tY=p(@@5R@Nte2G%yPL1LziK_NnuNVng*O8VE;VrkfruxE)G7TU=DrluE2VGGh8<7#)}m*%=VFE1 z92RKR+ik`f$u#c$8eQ@ke-tLA(YTdwwBq6R{;?8Lkn%Q!wuXB+h- z%Sn;)=`M*QWl_`w?Xjt&gaqFcfuqu&%WraxEK@EZSsQe;J~cgLL0`FuJaJj>d;i

VH?I|of@!xc_UV*(!F7ieb$a;Ds+84Q==dxRgE zFJ&Inus#u@bY#3!yNHr!#2gwuy>+;d8iscx2*>2F=ol>{^O!m;i?u|i7AWsf-Vsz-DGJvbwnrp-rL_u^*-a5vr|ty(H!&)>fhO}5DQ*ddN+SbW$Oa|@`(bc~GoI!8? z_jxI)i*Tmps%Tq8I-bust^Rk$DI&xg+Fwg^_+}}p*N2Qr#nbDrsM@)&E`p=?^rRM! zRCU{i3+31L*38xAC4w0hR-%UO550A-S-BY<89jZ>cstht-;&Rde){E}o6%-9QGr;r zHB0gZ3w7~zi63d4Ws1JWg@$>$;Zk86^012Q5Sy%=;@z$KR5NY7_UILh&Pt?rAAlC} z4!?|1A!`t(#+Gy>pCy?Z+F#gHB~cb2@WoEc)u;xNJYx>#JN1UVKeLUl%)slB;{Co+ zlLGSsBD`wmTDVloNuNaYl+w@klVZEzhYUd*Z!;M1MOAP85v7X{>Ac6hC?8(s*R^Io z?tNP2#~-t+P8}QIrbqdE=%o`U6*UEh4jpo8S5v2;+dsLNQRnV`mdY=8w&x-4Db@uO zncps$68;!5;uPJ0W0aEp`upB1jJL}({B6a$5BHi+kD2j*v&49-df6B=M#;*3Y@d~~58Z*C!ZpHe ze^xaIg-aMrl8zu}XJ+kHV0fGG1AqN$$-5m{qpB+5FCHK?%MxUa0yk9W?7WEFx4ZJl ztarKvxHKMrBE$+cOXX~ z?6+WrljV(t#B=jaVs_05zjn6pkFeQNQ2w%`^#Fzb789A_eGCKWmf6M-!ZwHfG+2b^ zF$Tx=Ld99M0Cx1;T$}`>bm-mQ=^668@!RqOAJEIltf(yGk^<ZrfhgP>vFr*JSb$QD7Uv2sTu{z%Qq}Dk$mr9PueO!!{5R*`v!t-Kh>p< zKBHF-+hvyRO~a5lX0PM~e^CbEqiY^RAqykeIZ0AY%>Y=#_>9d;YjnU)eV)M2ZF5NG zP1mTFO4r25x|;p)u1wnZgY>#s;$Oad&J$-wq8ieaQMT9xNlp9=#DT<{$aIgxoL z{Xw*hxVBYBz0m2zh;5Acl5M8|@9`EA#6vd?CUNPTxT#?VzgEUIZhA8DNe#*xP-90#XgQk|OcPye3Pw z1GftW#-NQaFaPqA0c`I40#AkESYr9zR`1Ura-X`r;>;1v9o?z^6(%J%gmRCS-OZN$ z+*Aeu@vZ)HsdM!5HN=nbzx#v|mV1Jz5;d$-n+&RE)`hU?=TauxysS@jIx;V)8hmia zPoFKT>KGTQKaTqhs}N$a=rfob2r)m7H8x;1if#*)Vun5JuNz*2`VXSpYDo3iy!~K? z+C0lHm%68Gj+dd}s)#^cgYSPKUiVH;ZR`tU1j_BKg*N;pnxKh9|L)x#-`(FIl$>-a zxb{Ef2!~sU-o_Q1&av%H->3vKfc=ZBpCc?$dkQ}V?#~+VOur^?+2HxDV08~Mq>_{hH<3fa z3|66?7&bWP0+BhQmvqXaLO3jJp@F?!cJaDuaqf5CNBZWySE)@I1m3BvbP_N9Uw5nP?DeJ}CjT2Xy zzeocp!a|5gquEf{MX$0pM}{?rE{*=K8@*!6p#8m^Xt#@z51jv79mjc+{K&nQnVt?4 zCVK7y4oA3D6QTUJxAw-+NbCY5=I>G>H9xNuYK}Vv%u{YMJ?1f=gR8FEI$!U28UPR1 zkI*V`d0m%A&B+CbA^*4)sA3T(T47S;6WOggjai3fpnSD%NuhKU*axVNqI5iR$&f0J zE~H4v=+goL)l|&w4>J2@88^yJz|Q$rpctRg_B5Wka|`u@{94j&=`42*Q|XjvLxF|p z7t^Iz^WO%9iY@$cF$c@d9hhd@h%KPHA1@K!wC6(=pY50nx+tBT;|;4?v|nfmqPWO3 zpcMB}{=x0S;gzp&auYPaziM(F&Zh>tZC$=hVn)1s1E4}Kn6|~bDH5FY+r1zf`mu?& zeVKcg6p2r9cnhIUM09KWouw3B68SlIFH3s)#T@DLtOeyu+}yp%pmw^q_6ScWN{ zI%1`o$3*E}rZq4N8mR#P8gCuLEj zPH}vYDu&WGy)8sK8E_onGmE*nl#$4(!S#4yr@Gc-5yXH@DJJSGd>TJ4B40ALKVu6e zR6NHP))w7Orn;rUcimA`ei5GbWg-%g?+pcdkCb*IUXY&Tco|Ki;%+KZzvMG47!kH3 zY>b|x)DqJPRUtTN??wD1JS&-y(b-`kMrzA!D3ioA@y6?2%*mX?1i+pBD$TWtIO{66 z`3ua4{5L@gVW8S@F}7VRA7Kw33nFBu!|Nu$3qnQPUc)K#(-HHsdAg6!*Ww#BMVc5V zaXuv3d}A~{Y@WkpiuHb+Y5)6L%!Bi8pXuf8Ez6sUpScBl6Yk}fxBLI5v*L1aPU5f< zaU~t=nAe@ls_sPm=e0ly?H<;LUq6B?G3W4~SAvj$#k}^I2#kJi7jOc2MX429&s_<{ z52)Ol_3={rp_^dtuh*6>M$IpeFHCS?MxVeKFi?8Q`!Q}4tN*XRNR{Ui!!&C49}k%Q zcd!rKBi0YvObL9!R6(Bt9s~XR=r6@RZ%zFRVzGbRbd@$sSHzgCeTnaS8!mp~-UkWM z(r^K<-PgTdH2Btur<$wPNC0^Rk<~K)B%$ujb)Qo%O>yx(mZLjwRAZFVtAiG~PWE1~ zr3$MBs^w;rxWeH#KcHHI%5Lr3jx#JC?Ud`YD#;Nh#5F6fXT@uzBGmiPVN-m@IjJ;J zf0#ooS-vcEaHrq&y^}f$5x>{sZ=kQ z#=WXXKDEv+@8nQ9PQvTzi2ciUFSMA>1YZ8^VC7ShLX{B&Mcp!Cjx6EWlHq^gAV`Xr zUL#cNwxxo2Sk9@zXX;QeywV~3<$9wGQtaxd-Yebg^obc#L#G0I_wD&KbhR<>`42hF zV{SbxFnjtW-FEKrLd$epA>pUt0y+`(SDYG$$Zy*|;}ayv$D-RESsmQS);aEXfixiK zS4E5aeyvJ#J~I{XHC`syJ3pIzeB^z75e$)u*V%O({EV_ zrT@ZjTY3M_MB~dPB>45{+VvvEkXZ&PT-^N2CDO@?lwjj+cY;-RL=0kU$T*b zrvtrQ!$zSEGn3O7`18qiZ+{CHf%8iLU(c({^q5Dn9qq|mm-HmJ82wi4z06|{R+2*N zK4B3ENiuSxC=a855pZ*Upkc1gK>Z$jB4T)sz*FkbmHZ^7sy~S}?QUc2s(?0g&(R1s zccQZ5KPjAdL!)+NV(mm|Ttq7l=Ql@76ae??dmi$7=C-O(VRJby|A7@`)=m;Iv`!V7f(*?t>`v$W` zc2~TxYWv5T9m+IO^Xu@BhkNflCm#Bqf;Ba!mzxzKb%;aANIpgsL##{uWMx!*_l-Sa zwdb0NuMmf>JNke$`Q|&~c2n=U1cO}|wQz8=_3lp?uq1h52bM2}8Qt62`UVm$JB#P& zwwPQ|QC{+GEAZfH!#+3ijd_72Vjnh4nY#a<_TD_6>b7kcuc#==s>qZ%m8i8?nJOYf zGDXXf$~=!r%9spMEK3oY3YivBks&2QtgvLBl?tm&Av0m0m)`fe@ArA$-*3O4{l|Xy z{(ScRPj^}i>-)XF*Lj@Bc^t=eI&PQ$tZt#h82i=4MJ`UbALf1w&lub^f^LF}i8A%w zh3s)+v3J1m#Tew=geUjv*GV_x3GGLiBZb^m^xhcX7{N+a(C=2-OjeEHvHN;^uNJ~| zqJmd6VL&hyk4)hK%$loUkK0#|h7t@mq63r#kn}zTrEbW#5jy$z6fT$20vHOW19dC} z$7tKzrQBxAUXixhhbBZmtFX*?Svf0rF!0ca2u7R`2eD3Z-boJ#BeT#dR%W{(q_|hX zj*6pbz!{~_eXpxbTJ$b*7d^aEe=e@S6 z;VqU?nrvSOE4K1#sEg()^_T|k5IDtp*nCEPz!%(|?%Yyk+vNneN|qIa{`Kh3z+11u z7ew(@6sw0LW2<8g6Ax`i_6~f%&vf-`!;d%a1>(LE8~2~cBd$1#P+1c$?0PYcORuZB zLAlwn3?VPA{i}1u3tV3fr(>~{)fdd9dL{|#xu@rL$=SqN#k9d`sU9c&Ai-q0neAWi zkm}F@Z|EReKrqV_opp0%DIFvu1(PEW*r2>J9H!5M%!XqkN0alX;fUHZ2NOK7-JajHwukvcSDt}^_I z>=E8h9Q<}fT+JQRGqGHLzo#4&f;@-G=P>3Kb3+JohqP; z*SE#^e`&bU@t<9$>2jhe;dg~5FS%9gxY$iYIFSAuMiBuSLzQU_V|6QH-C5t(QX;k( z=510Qq|hetU}BQO1Cv5}1EKt?**>L)}c^_fxL~ z(Dgf7_#Iht865ejI;>Rk3mt!vn@2X@sq2O|h^1lqS9k`}8r$RNpHgsN*>#2w3wU5e z8QsQAn&BCI#N%Q5;chD-7FOA;eWMM1A}zQC`u)rz;zZPdVV^<#4Fr5K){NsNoZIJ$ zfj-T4s9}iZ4y%b*l4PUVn#VQcqw5ZK043j5{%uZo97P5=JYN(1*L7pSy&;_))&b$} zk9rk9(QI3K+4$pZCfemCaJsTgWeen*UAP#7p@r%lW%=2)Q{)I?m_f4o;?D%t56O&H zD_1jQ`KaN?f4H7?4_ zF8X`f2YNMGA7G22e`EXH4kH}ad#eu0cni_s67QcS@Hy@Eaa7D%i85`K`ka1)Ef@KJ z@1lW;zPe|0IJK(}`!M1ClXTePHk`##r{1Dewkk)LpAHME(XNl}$S^h*QX3&=UwwO2wx;nFFx0tq!CC3ec zmHe{z$p+~~$0kZPyU~xsDp!OO3-Q!Elaix6UGtY@0LIhb?Y2(Htw`o#(o)=?hXYWr z{=s*~He0q$$t7xj=@FqwoCx0 z0!)tkb5E)k9+Ar1|88%@js}iiSt^jxnT}BO%KcV57^*pZCBf8k!TY!Bga7QKA?F0{ z;O33typuD20uONJg7Rq`gMqxCf(`^QD?IP=6BDF1Ti&0fn6j0+K;&GGUTxQw4s}!0 zPIfp_WH`O2EMZl@q%GR=#9E@R+Sda* z5Bukb%vXY5fVf0Ferx_C!uY#93*H~glst=DQLtEKVhSaxQ!6a_T`KYK@=bzLxM}Ph zQIl2u+vtL*pjt!iQ84+VtK%>DSw<;+Vd~Za}QSayu6}L&5KDw($#+PjNM(3*>Fi(+8zYW-VcxR8_F0kP&IYVRj?}8#i@2=|0~gclPzgw@iGB z(~SbbeVLs4M?+-hqF+=lG3@9@!W`4=O-&k+3YQly8JlpYrQ--Y7|Xz1YZ_Ew9;KCW z(zKr}&h|7gsA?&6*XhNbkXHLs;+=-`w=;%jZ#nc%mnFdj`NW({#|4|*9R-y*b3S&` zp^XuZX4f>D2zb8`j{c3K=6rjLqB7Eyxw)34Tjog}39)GCH&9`HSf2as zhRJ(Bp2^~ddBygkg_BpurXOtOWBFA~=@;Hukfoz?F_k#2aawQu8=so44WV$<9q`#B zWoEbV@S+RKgyUHSLm9#Jrtud@2d~(_2fF<~fG_4}skdclMiyG9;`btot9dLhH<> z_Ajp^S*L2eJm+u-SdeO8noFu;XWI#9d!B#( z33R3cj=~AnPbT(V@8W-SweC=%4o{dFsrKz?1b@_py{9>M6F|uIaTxq?nn&Nx=*l7q zji>M_c?fs=Cb!$t1YC2&fJoIrd!*h2SWp+@PV7g?lmZ5gvX4bmF0S$P!WQ3GMBe~A zV6VAfe(6W*H3Y;Y$3PWn2U|kKyDf4zZnNs2nQoN#8{4UQYEf!y2PBJRfK*hnqt{1y4B_bz9qkI>hB#{D#K~Kpqbq z12LLA3V~=<+%C2!B^PKdJBW6Um?%WxuxybQHe}kfk#_GQY}Tn9LjY@d8$=kR>EFSl zc2umeO&6oWm{k%t1g<>x(F<^`EI8J*uod*fkc5-fE8dRUt^aWIHdOX)+Aex-yB#D_ zo(_5niEJ;r%}6Xt96~hvy4|wq!*w`s68I^rN7#MoXrIw_d zIsfbPnVg4Jl~7kSf}-|3e3|exe<5FUno{;gq)fI_QkRaaS%y|1VYZ_eUwZO(vU2;5N^VUyw;vnnLNvg1hoO->8l(q^h1NtqzSU;z4ajh;UcUO0 z0;W7UxhMqf2?(4 z>irMFB7khw`R1{LFB(ALW(T17u7w((pzYAcbL<#5fLrPbj`?c%)`@Kr)>4cICs+|~W?x_8r#QVoYWd~TnLui_4T zac-sc#Xs$5CCq$Vxm5B8*-_Cgyy;35R(q)&e=Hz-pYJe(lm-qt{gnMm#-LJYLkFNt zc(o1z{X9UkDA43D9ESk#_{mqac!&7Jf`n75)e%k>Oa9+{uH=lu){k%7y&C#~?! zue!qy5ei*nAj9p;9Eq(G9JS$HluEsOu<@7wV=Yhj5#%Z>InXm(~yT$dq@ zXw*bfH+54LLj)XhrDHB+fT2oZSb1@^KO-AT%8Wjdi6}#iytsB z+12YWRf`nT3p3NwojegGq?XNAm6-O$Q&=sMAQrt1(Zk`(pG!R*mbtz^G}DR{%90hq z(101>kr#jKIjz4MKCKxkq$XH?HmC&E1xPk_jXfJse1AUX=?VSwPu&Mj4EVseZTawg zmzh@kX)GUg>N))Av?80>^M{z+;Jv!Ar-|G~-&;)tendK!3crxrkT^AK4=4oSCteDc ziLS&Rfd7rI$7brX)6n~`a?l9dU>*#==aH(!vu3gILn7;}{@*wKzwnycOMv3`&SXul zL+3LLZ9xjiBiMwV`6Zwmt&gQ|!TM4LnxcqQkeo&eQ- z;jI;V3qm9yW}^hVbdIY2xyqH;GUe1<#8_e2;^tt`MH1 z&5aUph3#?c6fV4^-Tc40HLPoQ;PYo0!Fmh$Z~2Dl=R?rR0O@ho@mbBi4$t4lphV2J zLWjGawuP!=wyltw^@%y(7PLX z`@j&t<0r3sn~vT3RQIFv+u4o+An1TjCPNGZ|H;XBbgpY)EWbOBqIFsTQnSr(W#%@V zCykhy=o^~d#;-06WWo_5M^S7Vf~(pvKd@O*PiRAa1MnyyW*VSrf;0`H9?2$c_EwK< z;L3}rW-`0&l>dDtXC6pC;&OE_EZ+nGaS0#6l7T)D{1F8?s`E>ktw>K?1LQB@3i2iRE!SIh7A26|frwZQxOXr545R^2`~)^3!?hM+ zV8K-dnLhiq0TO4W{D$A_`Cp$X#O&w%>?-)`XTvH%^kA@zY23LCrg^*~Ps#}3UM`w% zX^a)2)5EEQ5W7w~0%&=JoMb(2(8jsZ=ie2MCl{@Pt@#jeCWcep$(zsxNQZ&27&=;@ za2_R748uJnWp|gatxVwIgJ$0N?0JAk3UtMuL3GAzfEy@fFZ#dqm;W9*Y6rJ7?8T-I zO_qJeu@(vB>pM8{2S34?EqO;x`!B2^ercZc0F)rnWcE4m{?BnQUn*aPhwn*+8?e3F zNW@>)b*B_o&M@ex)xg;6I9>wtdvO$orxR|~|0>UfVB5V~QwqRk>g0=tZj|`(#k&I9 zC*I{o$?4+z5r_RGN+0`LodhIi95_Gq2q{vA;ht!q$gx#A1$I$!yj7o09PWjcT zh*xk!%57UzW8B5lomyvWnT>?hoE zZCH37NS$GBlBL80(*e7R&3lOypU<$kxu5T6*S((zBllL2uk4|CfQjj@g%4;P($|Ts z*D}Hf9$nMzlmBvyu4T`8jr&E=3oVF}c2e?ic+d2fTALSIWk)M96jx}YG?Cnd8;&5^ z+naRwu`;*zoCSyq&OmON zZ=a7%kn9y0aKspU4KKX;=56Fu*lr%Tjz)q@`a9J*IvbJvZ4GCWFPlhU)t z{=D7vVIbo<+yHuY%m*Yw+quS_K`yxLHJt9c7Vq#ZYllYV)%a;ELeCEu)dl`LyMX(` zs-8*Sr5Ewyeieavd$sUw{L{3NI~~C#%6l&t%*E282n*ts9ACEur7ZcIGoP4zM?ULs zapt@>i*uH(8SLZg+rE=XZP!!7ayi;zsTMhizrOv|yR+J2SbU|5|K; zU8gs>#2QC+0uHe-IaaJ>FcSL5e)pQGC*Kkf#9?|JxE+>-=pUGn?Ai zq0+fw!vS?QB?W?9i_kCmwMFgHq%WsD1P%_q1N+d!tx^ao2yPf0*`;?##DC_Y0ClKL zH;7Aw08P8K?2qKY7D(=G$-&;}G7C{Q%$W!4<;$W7P-Jx1*>WzZR&i@eN-P!VR8vFE zNY)P_b@8eb$HK?%EltJuG9LIyejP=YtnV@(2`r1n9u@^nUi9*t^f4>Vza)=IQT-># z-t#~6{Co_8^aHNosCnZhmGR9d3fO6((fVZ(zkPqrt2JfRiuOye>K27e)UKoHs!Lo! zGTE+Ro}l=u{4kT<$aIwIPm6%{NnMcX)WiKexxh~&oR4k2QDR7=cUMB0$IbRy(uLB(^p_X*0$-KN|S|BqZdJwQB@fY zwQ`Rdxm9uVht}EFluh?c;VCTx*gX~4JQGZSUeM!y@7!czG)ty#v2}e}n#F$qu=%eXEu_wG@ zpG?cr*_q`$l+B(h)3H@NK#RvdiRDzQyof5^ZZO3AnYqr6IzfHO;4hWe+YBOY&1!@CL#`(lv%mZ9WE4!1EY`klr} zhmB2dMW5i?mU4TZ<+`+WX^gvgpWOU3AFpyy8q8vf=VA}-M1t8Kiy|k;17c{ zkylTKq=4ZMZOqiK)xa|B%NaOZrrx?Q5;-BA zL$fSb!ZeLMslWa4Z-)$b-C5+GoUiV`P;=wV!q%jE(}Ouljb@c|5P*FsL)x^5N$zFd zhEGO+13B*ae_f<#W`vY3Kfy9*~NzQHHL3;T5+HfQ)f-?Z=s#h<8CK0D56P0Zc_wTrS zl^$Tih1Wp9wZI+iG*xuQx-P<}lcbhf1ib{{CX1LdOh>FCH}$*<>yeNWgu{fX8AcCq zwF^+)*`w}B+`nNw58-#_zRHAjLz}Y3Q5Pr-3}Sp9Q!+@Dml|aQh@&32Q8KBU5IZ2j z5t&q56_(U^J#T_LP(Zl(V{dbpjWv;_)+?;bcrIZU%EsFrqSrGABy^O?sczABpcSv^e0rEAs1Cme^bQT66BoGCzywIr%+Aibm=TTc}i-095Uhqvg10}e(yBniIjZC^Z8D05y^9&EizU>d1%a2W>J zsfYHDT5%+m0K-gKhK;R`x1O_iX8?bL5@XyfL#T2pQT#0Zh)C8i^fa__aL~@ak5~gm zNkK(~-zKh#usY1ffDN0nEoR=z&bFN&z@Z7bPP@Pc|Lk29!Fn^&DTNKM7ruqT*dQY# zvMmyO<2^?8y>CY$KoXUERE2bt@|$)!c{QOKw*ks}#M?f(`$QlF7O0e>r3F6&eIqm< zQa`6Tiw+sk%WUBe3p?`qAkS_ZgD-ifn)0mKPbm0mT+Xk|#;3rpV4g(Ya+M3T5ccgw zDAGSbV6@TfC*%wfPk8}8Z0pc@FL$*sONGQh`2pVJr+!{(`t9q_)Jt({^bbHcch72B z_y?WcyD|3%ko0#a=_}FM4F(q>LF{`vtG*%sPbpTK$K%i@Xr<0wtPyG#V|2soP`iSW zh&{ljOy}-EKRUy0se%vn0rW$@k%>Z&@}vvZ!F!$cv=EJ z-SW|x2}(Ao73tMVCzT79B@i3GNibduKbAtZ&8Tw)*~jAgOElt3^;c9 ze#yUNXAcZ5WenP@=O;6|X`swbM2A#BfwWFh&Upjw7~ekY1Sd{W$g7wgh)pguBe|bb zqk_UAOnQ~THN4%xQLeVERrG;^Zm2H}BzB2-NYGZ<-B8n{eNQfIHZT=62+e6l_L_&o zvb|6taMuqmiELISWq8kYgEarmx2&{$nu6tG?70xdJL@KQGvozDXcs=8wi2 z+!qf&h(iIy(k_+#P;*Bq^!`cj--(n4Tfac968<|kOoUoN$#B7Y-^xDJ)>R%?y{RX+ zzGehrt79JwWKl8^Q_&T&v?4UICtJdr)?A+=L{VdJya zm;?b;1Ty&==2@tJNJb2j2F;XPT+@&XNv4aJ@6g`-&NgvoK=4vaPNc#)aYan3PQFW! ztniGpJ-up-#L3e&8$_7&E6XG}tzEq~DO$U2;V1#!kl;Hje5$3NHTXK%MS}s^)$)f4 zX9Aa{GPYf>)W>Jo!oX3y2b{XnWty7K9}gzMDyPLY-Lm5u;s?JOil0=7CM+U8 zd4$O1wvVcR(Mc~MiaCh6G8iwgzUY8z8Z~9#A64c^WGg|#lntVK4nH&JzW!TPFJTV0 zjzQB!?!)l}@urYA?tgz9a%TNk3OwTO|9cs#|BPObVctsvHYE;h91_R85TDrs)#8yB zD2#yRNq`ZF7;2SfwWWs9@CFshvBrSyM`FZVjvx^>7%^eUOQjkSBrcupEYICRuD0 zo?s*JVcSQHPQ^J+z^@i}6ZY>d^$c;MZ=mHBRANJ{&}D!F!^kQ#F7}Q6ms~&>Jn$yo zj|V>9{65Q8ynAdnWgMOSVzZh^u7l4>66Ia772qo#J9VGjyqqqx7N&YNEFJ*98$MWZvEsfa025~pL6V7bd zThG9S_qAMvOBRU)bOrBssi#2{qex66z?@;&3Ayq&mM?#oUyDPv1rK1T0Ip#s64{M| zn#Jzjt&JGN8n{9|4q?nd8Wf0 z=pMkaBmp5>qq7J#r7Ug;E>9Ffp*;fv@x+#E51LM2F~68)iupnQh}jm#U>ttzYg&sW z_(91SW?d=Uc!|qg}M%5c{u$ z^O}0w#R&yJPR}D5?n$^6VEsU6IBn9mkd_4X=v~umkP+J!u;(lBd)RWVtAO+_-9;kU z+tQt#PR~hAoUhp+j9;NQBUN0;hqz5yB$#tevM7d5r#;4h8@CyWmP(Mx1aQp|4%;sU z+aT9236TO&fU|tBEn!h!Z##(aZ0jCQ8ABr;a26B&+Wf;;72Z5Z@;nkR#Mb;UoMlrb zcQlzui_2wnBfc;B>@|AKgXCoWKug4cI~B%+9Wl*&o#AdBE%iFMsaen9GV8Jws2MY} zG9Sxk+mG!|HS3u84wzs!>nXWZL*IHh(J_eZ$hHED{H}E@A9Wwd2@0)1@>G@FZT0N8 z72dZ2#3J!{`Tf+E-;uN&;Ofl+J4YiN#!)p%n=^}bP>H2u#ctA6c_$5VXXe=(0+_z0 z-U;2yzZt=KrfZQpDRpp7^ugZ2&TR?eO-E*#jSFVaOJR($h97*l}0^2Xgd{&Q6Z9Q3|g(>Qba{G$~xeit3o#6dA@YutA zOtnVVHlS7(`0Gzy5k%pXnQB4Nr~gGk7{%6ZjFOnWY( zu5r8ef3-)l0>n9&-hk7~G!W_a8lGi=pmSmXnDAN>YzJJ*l zIwy*^Hk|auaGqYaDEdk*IWETy+MB!cxU)3afw@Pi6To&_EHk>$YmoYZ3XiJ+bi?2V zV9#CjIKW5qqX9Cji3vB&0>F{2#CuxIAW^*_Kl1gq&5aD zku5}tvL-LU5l{9Ly;rJsSl}CojMT8{8r+g_dwq`I+Nw_N;9JzL6OMBbH#6Ode28J= zg__&5+;;sRPr?uEfvm;uUZMei9wb*0BYV@4uw3|^b2uau$iqqEtAef`m8^^fbzw_J;h265eQ@qpzs z_4F^SgRth(NhImC!V6xy)~wtLuGF~o)*qsY(*eMgv(dVkD?hEbm4I&WP;ph87GOHk z3drg{8ch_y;iF0(0!pYp+MzK>C|go1oCV$^$%>Ado{|BW<~ zf1p}CfCd`;y%dxg7Pjo^%}~g_`*Zy-u+knDg9-X@r-@(q5IVO64V}InA6$f+RK`Xl zL8ZY%_EIJ~!ORY&<&IeRz8iBiy1HImR=_b=jC>gg0`thj#lq|%k0kwJ*}cef5&d#3 z(e2~im1+|>kd>jrvmbF;1#P-qN*2ubVgxD9EQ z)zdOQw=xoCsQy>npi-nE2r&*T6*B=Wd z=%0BJTG3{XMm}jUwk(%q*x^r_)zzU=%#a`di}EZ4ZLHkbNSXrp-I1(zAcZ)OdBNz0 zn$NHMP6r5UDm(|!M($xn0JjjUs!R$MX*lBzSR9IJ)RyPt#DCoJS6Ef|;LZ*yy0l0b z@LHs!Q5LXAKSK1Bszb0v2r0u_&8`s7J`+@eTAy54WX+ZlXW99KOj`^=eU~SOpReZ^ z?q|5DjGubCGsSm#E*Bi0GkL!FmzKVG`9v7Qa|M-{zk4z)F#2>Y@hfrwv_;vQs|-bA zs~xzeK_IDgUM*fumm_u8S*wVQxLL|AE;EvjN|sQEg&#wRvQGs4i2$&T@EIzlgVcDY z;Ue4yE>R17y?K(1qR7Sw-$9qa6gN|^cy(qp*Z->Ahttg^gGQr8<5QG!am}R(w6t3gA zK(|4xs)qm|4C?ev#84qU z*#HqUlD&~iluEp0O94c*7ZY#Z1Yx(PfSq{#4PEZU;B2mq6QBdQI z6+rFezCD2wD|@<0A9K?G^mGOxOm48hTqhVURA})YUUJ5^Tm*4F}!h zF^H|qBhv0OH7UG2rSfL55ML`u#Q{qZaPtZw1OX}bAAuFePnpPy=;l1+Q!wREYn}+3 zZ{15Qa|t(luO5HwF>LNgdwUmKBl!fzS-4jWblK;I1%xn{uDajHQbsRq)q8^)q(?WG zhVzJ6Wn~y{-z;pj*RU`nH6P;8xP5kS^xC6H!%#1iVC{ck>5~?S%iIeUj%NK^7 zGpAD-tyJ`E;Ta@iPnillXb#!IB&*172&}hY&N(Y{ai@;P@bR>|DAlV%=XRADcB1B^ zPp#N4L+t~<4~r>7baI_)^}Q8-rWSdUoOceaWT=hDmX`CJW?)|txGGAPW8Qh5aq{(& z-Bw%DnSSw(6h)6Fb#j>|bD;IyoquoD(<^?%pyJm0Z6A5(4#R5-!5*d*F@P>!6R%j{R8- z+7KKmsEGYg)gK{hJ7U1SKQj3hOb7QEH{&ZWfx$N`9lSlj1Q2+t`pyK|F|vmyoud%8 z5{5=HH`|7qY55Vrz6t+c*9!R}sh1@s_g?l!ityB7A>T10@!Sn7?~Q(WWf}kVs>HP5 ze}-D>AEyX*1TZ3mNkBg>kVIV7eO zIWSdyLtE*r_S$glt%QMl5v?G2;hCnb=x8*)w3~*lJ{BOhoeT)1F1%QY;I?EMX}J?`f!LR>Kf8s0^t~gd43b)r6DE zK!9OBvf=Z^_ey;lq=qF3dzrJ%zXLjLm=;GO3LFouH-)~#aRSUdpS~O;+IqrIt#)t$ zX$S&cnLxEj2yZ%&!#1_3Q3DL5jq05`hCIh*C|X7yv**IZiVS<8VTOqeTICu`;Y$Pb z9Wu5}$*;5x2MjT*9+w|e6GRU7Z)`8=qehQ^k#=Q*i@(^jSZPl7#;?0B-A^ z&3KfPviupDBR>IFe1!BDZBGrJlNS&bWCze$8_8qE3}5jG z1Ka<58=XV-#8opC$OEY5P*4&~ zgi_{smPnY4P_t)UKKHkMf^buUw?=w+hClrq)B_>HZpsHH>?CMA3P7+&@r^(D3`RDt zNm!{WCW$uV^~uH%Y22b06+h`CePpjG?&#vL{KTo(uo~XLJ%ZkwunSOb2OgTB^!0Z5 zY>OysHC75pGKMr@B%NRIWQPZ7S8`L1r*u6ZGwn)*@_@$o2;S zx9SaQLr<8_=RPSJMyzJTQP3DPQC7fK+ujifT<6j3`$01Crq&P+Vx1XWBCq}L9Sac6 z>>q;UuAuEP@H^u<)NS@14K4|n>^Uf6#8EXneL)aLA=Rl_U!a0txLC7+H;5A?AedJp zsxL1=&`Jx!ydHkeDAD9e>{jjy_}H9!rvi3uym!-|qgNxH)O1V$FLoI@V3VT90Snt9 zl7N;31r=cU_;G0yZZr_xYVN&#}W3GBCO|A5;Uqg}G|^v8IUd#>@zwcEv5u zW-#Ouj%VsqOtx4si z6K_PBy~goVxA-Ub9KNYcuN5FX`Vrt<{+aX$#zu*vxU-*NmLChFfkzDKvnj#WB*I=s z^O@rM^MXw#_h!ohPwy}`Q5qszCm^iCwCnWC=B1n0f|OLI(hlwKtsy`1#O~Un%injE z$f5c2l@oq#aM}%P*|SBZWbkF|W4;LSx;dP^RSh0f8eu_i45`luuh+JJdIpg&-+fdM{wo)LIh@I`V_t zb-PndAtg0yM<|oql0@`huiYB2+F}!a(VJ?cBA;(QT}RA_4A)!|i%uC^-z1&t|Nkuv z{|D%l|C$1+r&l7!+dvsuIeJ!W79nL23>PG@PQa9w5}^Tl?P$Nh>=Mpj-uVwhf5M#+ z2@a3qqPMP(UCV$=vl}$HyDs2Tv;XktPgYCxog&k=iLZMnbT>m@AR=r7*3AHs1ch}Y zg<3WrQkJ%?xs)@X*#Q61ulRi;oibs-3c11GPK$5du;G8-|8C6nzf`}&A?5@6P1KaN Kl%6S?2K*1~*GB~a diff --git a/_images/docs/wait_until_task_D.png b/_images/docs/wait_until_task_D.png index 24aa29345a299e62e938b9732adee99491dcd5f5..02698ec4442ac1f8d719a6b791d6a798024786a1 100644 GIT binary patch literal 117110 zcmeFZXH=6>w>64gQNel8p-C4Ay-61^pd!6V z34ze0O9@B`op4ut@4083@Av(2?-+-n!x)k$``LT#x#pUC&AijnP(Dq~NKHjWbsC|f zs6$0{7)?cWsQ&m-ct-a7j}iFigtLl~D-{*ZPs-l|QT#NQsi>|{Ar$ZEd73Q@d-+D; zp6@R&4ZAuy>dVugJFaGU_tpV1J;^U_cG*a&^0}-s z@%gMl<+l*oN3kmQ5veKqK0-$?DZxJY%f?r|pyYFwis~D}X@AauE{Ct;qQx0@%9|9T zwS@_0@Fr)S!P@N$K4*{eW|aT$*7<*FPrMs6qpVh;r*y$ga)8-HV;KI+(}@Kf4>nQC z!>%Voy=rs({ggY;ew=Hk%!bX*IcJ51%BKzE* zKOY(=w7tEnu-mT;%*_kogZX%PlqVWObg$Csu!n0YDZROWJqEjlNGU5LVQP<3F|;v+ zAEx@&*klnVlhNrrEfOc@l!R5)@pxP0FnEhNRM}%j3YS2;O78Ejk_I~c^~0oB-eOe) zwpz{C;zxHIwwJOqlZwS89<@db=xS($+S%I^k;=p*pT#Z=B4VMQC*k$Ui*~(P+L9B& zBBh?ok1o*B{pnI>h0za8#h4ewJ61KD`3}i!|4D0UZtmiWx&H`mS7z;(0^_YGA3G%H zuc;@9YZum%tGLzUFbN4v`S&ZkM|Lqn3%PbF#CG3<5YqClh2hDm!fliY?=0e9Ez^n$pX!evExK^P0Ng2e(pgkbGmh zE!MR+&0F?f?H#+=}NupQh7h9{!yHe#T%?q3z=lTPf}nF;Y2*Yef!9fBQ5Ri zWd@0V7qJ^=uz03kQ&EzuZ6YXwZ6>droOzMq0%nutAXP%baY(7+2XK9TIVmZ3>g(%U zIy(Bw9R?#46Z2oZI7l49nlLjnGfKJVkscNm6=}!cazNLO{hDl!h>D1aD6RF|S_g4Og*&>F&!)wz-)DH;OD0B=lE%)yBogmpP5fre|i_Pd0_4 zG3DjAkox+30s`s~JKEw*eFdh~bf=CYjg52KPHIQazNtoVFUd9k(-M)fa zvbSl#9*I%t(W?b&YHBoD{Vsd>2Tlnl8VCnnBO{}h&d!Q5Z*ysun7XkKJzL~YOG$of z*WW9pAU$?A!DR|;we&3uW4z+zW?*Xz~0LH*WsD@s*@*A=5HtQ`oUnM zTBp#1#J+$%d;phe8Yk=-BodijTB_$?OPTWzyn!+WRdYEQyt4Oj14AxrqDCeJC5}MI zDJ~YCCwLGEs3sCDd{otV5I?#@hW@?L&H&b@g8Jmisg0fd?dPxR9>Nd|_pFw7l5Y8| zFKFLj(0lsysg5b^AD9UEcvzjq;p(XH@P}A2%%ZEb^Y3Szvl;P@-4Zhi95Jow6{G$p z4IdS@D{E@Zj?pk_85zYUXjto*55T=#vdEj*Fc|6U%b1(9^O9zXijL-1zdLWc4(0lX?{3|GRulcc14npeJwZDH)UX9&n9wEOV>-*FYb5d?bYv# z~92waF#fa$)BeQ3>hTe!ryld5o-8|h~T~ySohG_*f?0IVaR`n*f39G zL@1#VYHA{KyJNIIOC7$;@6Ai+xMFR4GPrPo@+p|@k^LhtzhlY|d2NmbhH$!)w`NQ% z)uOKnq1)PGMc}G=CKVl$VXcC-Lz4P{H%3)%*+SeTSBL;{jDItlOCLMjovxN|LHl^* ztJieZe1S*=x4Lj_Y;41+1c4b4Gga91J>~YI~4)**psfqD15Bf z>ay+^5?zEV?l~slpycmYC`$t($7`9UbgGIEUxg+3OeG;u4jo=J7X@HGF$5I?&VLbhn3J0 zduu)I>%_r)@0eE0L}krn|Mik&(QuWY3&YhLAIP^F7?L}!=>?1*2MckBt9(3ilAiL! zkYh!2Tieb3t>k@M&e)6$?s;*nsax0G>ABp(TMbOZD7lRxS0(gTo3*S(&EMC846q8r zGss+h$~+s*_{^rq#2H?*3Kp^gq)|en!YH@F84K9~pWrd#rG$CR*)&RC~_ok4vg6O(vKoS@tK@=eqsB~?zx*$1~y6?d?SiQ%Qmn-hJvG85h7!XHym zP*+Rq0q3Q#MvKMjCE3*p*8ToXUs;ak$;ru&G3NdQgbx4HVKVC0Y8OP>q~+Xp1?PV%5&GUmF~1j|~ySGRn)22_8YTG&G+R;2r1R>P6?vEAGw$X0A;?vjps`D*MM-X zBK4V2F2>Sjlcp!L(!^0U6>ZWxG?YgitgzqPCT%x})jV{HMhlpf|H;WM=nfGZ$;5e+J%*>Oa>#&3=Uo>?K2X2tJckTWc zEy|1%1_w#s4$<1c#`A{FfxLe|4}gDaW@es8ZtER^K=5Y94vyEqF9UGc8{OYahIg;w zYspAj+09Q_quS85Dj&H2fUYDNAGeuA4?f6WFfBc?)=AlCIh6j??(fu2t!}L?lyuH@ z29QhqdN^BS1o72NHMu1nl4{9&3)VzjAZlaSW4=RbNzd3g&as+!%hY|qlJM25wi>t zR8PIPUQrtbt2-mN?`0p^3$I*j*7O&)9c1ws^{epT-x=ixfRU3t z{G}|BbJ%^*VS6Q}HZNc+CP4cpBMx7)E-C;MJ-XH5K^Zb27J>pr5#_TEE0fLJFhalk zBcoK$(jI6=1MMzC-Q+;iFo{11VetI>{a8rd*bTEnJmYDXX08~hUk9o^3ca?bV%p!F zzMSV!_;p2<0~KafeA(uvMyE>3k00_r$d=H@iaLNz2+nf=ZgcbV`QfMGr>|VuMMK28 z<7RgebGRF~7z{wTz`wxYj30=B$iJOkv$P#j~)!2{M8D(X-wm8w&`>l;__NKo*KLocxf6ed#W>H&Q#*YlE*R3*~<`+Ec14ApZ!{sa{W@df<{7XexQ-&0Y zbYE>3`-gTJIXNv010{{(i5e5m;%KF}rZ9m@=*o41eTdLfm`W9-kNjH|LoV;bA5%C> zZkw#jjI*W83R)Yad0yutl_<@SUQ@({BUi`Hi1kE(0wU;r-t;|{Lr(ALmX&X z*?;8u#8n7EE-o$#{n;kXqsCrey#SB~hMHW#&GV@I; zj4iQYyeQU+LJNWeTo8&8HNJQWSF7%MJ*H;V##LV4qQ2wvM(?d5p!JhCuH`VlQ>+sE z^Kx_vKbx8CD7dI=VUf1JG%AQd?Cs>5@2T#u%I&9(k3Y&c!y3O+luuI%Q8oU!>zcfi zz-f!iLF&h@k$3K+gMxxMQH6z3Ia*gAC-z*jPIwr#QP%HI3v&Ru$5>}03lkbjgN3?i z#Z!9w$Hkf}2)^sr^{<@y1t4#so+yc|dvm&^?@&pyMJEb!i9H=s(-(vS^@ypnhVnOvnrck0Gg}0MO>PW|Ao{_~j#}T+d)3DEX-I z5i6E?elNYHhT&;v;N8Hw6&wjH~sF-(d>H5KHI3DSnhwny%6?1sSk&Df2YW9 zJIEoCF+5hVYV+bnnnd6T{?~b(ZQmM&mZRvXC`&3q z&W*v__)(Lki8UH)pNs)g=Ehoix>`(5TAD)gc5mj*$4zGt!@ASgtNySHm{#dsH1kY} zzGn1jSa63#^3YsxI6%cC`+}2-N<#~xKwDWkP(R-|{gQ~4O<$goH!z4iNrX2EXTXIp z-|miat2-_B=f%nETELRZ!Z>gx4v=spB_*GfWzSwZ((NMzHC0pLIj?&W}P0_I-JX?JKp9>Vr6_j~x{T?nES%@n;tT zV;8mSy-JBBV0GOlPFS4%N!!742RjD`+^ZAk(Jf(p!Iwk;zk@KsJM-sFbM8D0V^erz znD)lIk4KI39HpRA3T8;bn+KReEJoCgX?b~7!W~&S?7;3-)9LQn4t>40<`%*tV~k!4 zl-s?7?(OPI8QmvuVB>k|-)E<$vd{XUS|WKRiKRVyMn<;z*>1!#yfFzVR~Tk-?>Yds z>vWsMW6pC_51jw0ABS=0>0j49R8N*Q1rXH(GPCPn+tSj)iGb)ubINS~ez{HFs4e6# z_##h%BFv=rF(4j=K!*yY7QZN<^?;mjtwem0-=fP6~eg1aCle7hR5h3c=AjvHXuk$ftY&F0hvGnMefV~X4w7*PD<+T0lbH5)e5WW4T6Uas0M+r(qz)mQd_6_w>B5;1mJ|@Lvi% z%cmsrw3|j^Vqza~x>A)n7SU3-*=~$zfPTUK0c+NN<+G$)9*g()c4y=afG|;{j`n0Z zb4o=w;-SVX^IRUc@K5AP9dxW#KS_V>1E-g5nF9B&TqaIv{*HN{Q^BbMFXSAOEo*g zOR9{UX7^Dzr2d2LtnId@5yDWA>(Ld!T3ED}V-iXN5La(l7SxfnofmEolXA?a}x@Se$-^uQto`|Gw(j5t=P|TT6fqO3>JFU~UIacg^xH9$f&wPUHDUD2B0E&u>8`;(^ zDZ>=TpIcC+>VzdlXJ{rDz_5qCW)eZpL3qpKi+($c=kb0BoLJqu`E*>-XIW_Zmjdl< zlz~~-%2aDqOiU(d9>W3qdyx2KEuFk|`b(_CD7B!^Q*^d&rt!w`(gtmRg{`eEqnKj? zcJrgpTy`df&e{Kbd$x*LKG-`l;;1f?Am!ocGV$`3<4_i4(m5znv;oXDWJtYrH5)Q4 zolh^_Jwhd3bQaX`XOY9ctL;@=)A7W5l`hK|(+tY!K>^SK$qN(_Sc_Cpr>wr&D)B@t z0R~ZaJ}d<0>sM(U9zTCRdGi&enDyz2_yM~ebJ^)@ms!GOOzm!Z%{H!(@LtYEZf{nz z3=~HPLTR(49H>8+9lzW$F!w9VM^#i+N!nvGfYVb1&2oCGXJH}~!QDB*k3o0P*|)U3 z9AJfy;S?cP_5-|@!epT4jJxshhfr*&Cp!UTDIi^ipc0>El^rtk>wc@qen?j6#+l=s z`D|{fyn=!T>gpk&Lo|dk=K@0doQLGv1rRmqCMjy$jj6kSjh4#&p2N=O14RJD+pJJO z6Yn-E`uo?ctgaI4Uv^|^r)?)pdk8OkV|mlMuwVPrEB~Yr?{g17e~{|b^~QiG z)qh7ORHvx_e|Ek$UVahevhN&cL$Yjlyzdf>=@=yM8Ch@-#DAhKat@T7x6i|WAJ=vf z-@431MYZWUQNacZK5vAI&5mv@QmtOU@~iA!slf&H(0FFeeT|eH7oVbYU2h+a(fBMs zy-4eE^=wH0djWx|cqDl!4PhDHXN4;?NvSF;w4W(?AN7`mm4SM&@dyV9zzi74%XW09 z%WQTpI)>LRkCBO4f7iTLXql}9^(Uf5?FOrL(*$c8%ux4{HQRYF>XhvMl$H>YXv|uw zPG$E&gyr+yhm11&l3b~0^Y=*`5p%F4vIYO7<>#VLJk{Vf>c;y-~ zVE#h-)O2o{OQ1`Gy0+RDedVD$7dql{6|ZIN<(eZgQ_q5ha*VdnoV?ZxbX$S+T&&+R z)`|F=Zre-}!z{Rb(}LYgGjNAlWNZ|lI8hp*)4G^%m*3AF*psqQq)W$iOGjtpcvc*8 zxDm~%c}3y6c^qcZ_7TcHCO6G7nLS@U$A8rcjY-k%MDxhh5i$gKM*Y1#Le= ziS*otQOqY1sfmLEh!u>rA>M^^Zp1W23t6euS=$G>f$GMeGn{^>dV72SP%;n5;Y1|W z(V~G8>wi)RmVqZW!(m>pmaM)NNE0C^X0B1FiPo!de7%yH%n|W6cf4LMXY#9N?smw< zC^PZ<-yf#YH3>$8&RtR^|9tlm0?pq(>Vpr&>6fW}AG37X=_zxnUv0T0hYauIex1{T zbS8M&4SiKY*_#`5#a`rNS=8I=ZoFwlMyU!ivPr-+T}9;hcvN2 z&lACT8f2n0G{PDs-2)i=3iYgJ#rahvKl>#nu!QX@yzl+$`qB=+tKb!3&5yOg4`c7 zXm)AkGF^`;Zsl&BUC!~EQL>CtFLxqj-u|AzG1B>8y#UUzcuiw&d=4tl<#*iqM=t1p za^C#D{U{_UAm7(WffJE3M_qKiB^}e?HGo72Pv|bRT$pSBgM)(u1i> zBK=VlCbq9AErtGdjytc%4>vCn*U9!a?VfcK^(g_#$uF~a(^UoekoNWZs9t?8T)JJ; zq!FXAS2UJ^it2$DyUI30tdvJVhg6}D@xf=`iJ?-9pD&JaPIt~*OU9*z6^7|}e|Iih z98OWhsKML}U>}tCWaovS=R}OG-9rilkRS9<>R`$c3L3GtgROy`WB&UFj4}93PfV_X z08C)$1(?9tL8sbbv%?QQfVh0=&bd(IPoEXbV8z+#yWV=m*zYu$Q)cSV+A0?U*}BhH zA!mBN<}b2&?AHiB^wH1UqKl{6#$1{?$JfU>T<8KJXrHwQ?i>fGa+Y7kSo6^@eh?Hf zpovjiy#3}}*Y(Q1Sv1DR)Ii90iDOp9^rTc~PIniMYg-hSRR- z%;A@w@I^}R9}|6YUm&nm08X3PQ}hw&ca3W!PF2cvT;orP{$yGgaVExFGrEkDq89lzlbxztvYQ+drjAis?2s$=AYnIWX+louFyw!r0t3Q*(JTHMDHs1>t44V z!WQ({S@5s;Yq?=UMET8ih6#Af;BW+IDVe;~Jge4|E#?cGUP=$Jv`;1D^!r7$Lid-> zQT70{l(MC0)A-)67HMxZBorDS`vXjWJJI$q_#tNFiU*|Zd06LP6b4JMFC54{a7q{| zuO1%RMTQxN8q{bs=HUPnSUbpOo2%!`8Qc{z$n~%S6Sl*K_TK_Oae#TT_u~TvLd>Hep z-$5#8;eq8gcFOh__el!s_>*)l?EAY>Psk`Ac_k+f0_l2=1=1QS**5!dR5r@hMLZ$! zi3cYWO{Vnsd%%+JP!95CuN!ilfK`GYUN#UnC_lGVDF9FT`EZVV?GV*7e}*!mfPr(r zip2fvK9<53z4}N;?Apu)cfqE;hc}dnWk_l|y4(`SOZroP~~?Pnr!3L|^wJ0P6J|1%?Q% zy{Zd2<`weQ``cd#_UrxeOk$_w^>h7)FWVW`>YTnjQf$EAO~B*_Y`$i9Xm_cS2||^t zq2ZNT{=?MB+O5>}n)N(~T-xh|5$=e$gYUy)IV$C{RiM;*Ewxb3S~(|Xrbm=&g@>`v zw|N=uaM6wa1)iKw3MF|(mxi)dW>~_7l-_yXduQ`=Wb%s*?`R%8Rd!KLlDw2(C-m-B zDlvb3oKq@^oG6byh(g#AmXqf2`M*XClC|r6a?x{`Mf+@Tzig5qRl*<20(=u1bFRAS zO-4Ziu2LY6`+qH4Amp`m7uk)JAue$=5OQ%}U7`GF$eJ9|>2n3T-nYqLGSC>W(_YWMwl*SEf`5(7`A*kq{>SVYKu6>~5b)V!hg{UHYz z!okObm*oV1br`LRJ3P+u!gE*l9AtE9dEzBfjGmha|LiWi`YfnJ+B`OWB4TbkB3eXm zB#%w?vd$GJs{$m8V;=6g!#p&n7_hS-N$~*@oEO>>_+#+aW%Fv%=k)8gqk;g-424xC zCNj8j8z>p|!BJgng%Dt0b9gM9#}x(J%B_~f8#1;#HKhw9IekG6F5=8BEK>DzPTBiA z7UNGv9ley9%aATRFI(cJO-9<75ES4n3jF{f2kU@z?!P*vk-&z4n9{3ouY_(J-fqHU zQqQk!Ya`u{RdI8;FI&v9p7#eVGOuE76gTd0!S2aHb>6a!4mH@@7K?i8p8coo{m}$+ z>3+UJWORICUkh`~C9%5#Qznx%hmqp;1)PD5BPQu8S$B0jvL4W09pnST7zU{!%XUz* z@~bVM?94dkmfvh)m^ypPHpwZcIp)ArLqCK?Eu4R4EFs?Y($ zvY$z&WyE1#P4A4A%+8{W0G9q@eezd;9*^9TlM|-WIQ9!VDV48i z$e1qP{)|uB=`)Z!y;hQ%?)#pwVUUwnVC*7J=in3}CGZJ&UO#O(Ce6JtmB?lpl9Z)| zdd;K}10*Ha5^v=tTnrpYKd;0TcCHSF^sL+EWTco^dBU;Lh8uSVN}^ozO(O* zHe`T)q+g6`;XIdPL_(vO{?W-fwnyyU>EjX?`G>xk*SqTMkdHhI`Qzs( zQcqsYb!?xv%N^p45mfhy*}IFTaO^?WrI^&Qmkf44%-*4??A~<| z4_z>b9Cww=|NS|fQFa53L51Fztv$F^?~-|JYW*06$6cv4q?!4)qp8S2SpT^f)R@}B zpq;Uea$|>qh2)HS-nqolGTC`KVa*r6!<|z6PJZJQF$f~c`7fT%kUauoUK?%fUYuby$jZ5Il*XNvTd6ITWW;H4?$CNf-BdKsnaI`|1HkLY z<3jey=u)TplXjj?>B4G_@NqCtf)|$NlE{6)aQVpVuO0_?zgNofo*H#~FfVC87<6%8 zlX+)@&%TYb{s%LGoH^RWc~0LiV0$j}xxc=rNHMKhvO!JT;?is>+YzjXpW!>t`=>8g zWjc#G-p@Z2KN`-7b28+LP-%jXB4?WOpM4MQae8G-g}sXx$(@9eDN^(K<9zgv1{2>M ze0)D_=vyn4#d$b>Hd7|V;XW7n@I5I_Q^)0+>A?6S&7^gf3qAvx(GpfdPj>R_7&|_P z{wvhzF!|-3B!!j3FW`?IVZER#?y@&cIC|)v2wfAa)!s=eo~q~jw6vh&OFrK{Hx(S8 zL+~J{BrNMrtz={aqekcqSMx{8Ow(QHAoCz7mo1kgT|S-YUoN@6gakTjA?FbRJF>VT zA(gZdP`FVL7Alluw)~=DueH7JSQh}j ztT9)eyuD*I#%j#D|BIbcDBm7?t58rO2pjM%q&Cb-AEk1&n~+y9t&~1> zp=E5r|DYishlfrVB!0-~EitlIiE4Qz6MMCPlAlS=<>Ej?Z4V=tR)14jF3_m2V}^_v zHc0a95kZ#idi|%YgVcy&%WRA6m3f_4yE6e%3xzUY-z9Y2tX>{g{heWN&eDJedUvZn z=#6pY+eVsLe@nc!d4A}&9j0(;vOOzrI-EUU~ zb#cWrlg1>puu?E`Bs(*ci5x8?s?0!AC64h<&*%!AO-X=rce;I%MQPQUct3edd#wdC%_H&C#e5f10-o2Kh zJu$hB7J8J&ZR(Nx{DnqIAc`U|eKsJC~K`y;CM1X}~w zG(K~a)Ds5&>LbBV>Luj~pEs`$vgkO!+W0o+mMP8rSyS2b9u-5dY*iC0NXDGSN}4(o z(;j(UG$49jHI$~Lk?z0{y)W4sz%Drv4pGhX-J8X$dD-0WJll-VcwB*6wELv0UajNn z`(~rxXGP-aY#mhXtk0dm<@wIO#WP5-6gS+{=_w}#q1>CM)OFbzkrNpnoDw=UEFM>~ zoO{A$jQ9wB>=m7Y5==p;S9CcA;^I0Adn2q7Dpv_z+!eJ_hJUj1bs)20<+j{K@%&Gn zhm+oH=<|txy@w6_{%+Ts+8;1sC0z7>Lmt15VA$t6;!95q^q+` zsvc9j55EA9W@5-rzP2}1zE1?UXJ`&z2y-{m6+G~JB8XC3`L<0$y6AYbM_BpOIk~ny zsj-^7mb#cNwOIO0X}8CcK$;1hf~PzABYXD9Z{xo))Ur#X#xp|GTS6aR0Ftf z_`3!|LzTOS-2O4>)Ytn%(v_X>5CDBo7|lcElHT)|$T z^!H$eq+clM-aKCfNLn#MO5EYUws&fIG6mH$NB%Mc71sTpS4kjG7EVcu2if-YcOa+uJF~2Ctt*E`MAwTiN6gV?{snDdd6%{K^V2fei@+X&n09{?M)#hIC-Nn^ z7P;?ju~qu|1BIDtZ_+O%?$Ki3*_8Td|1J2Oz*0!j_i`dIZQ&EhiglEO?_Xt?sv*8u zpLfMd>RMx$W^(NY%u8p-s;e_~B}^H;#%ehoe54mVw>>BfkNOGYt*_~AUFSvTk_(H= zq=olLMZgcWldFt<$Yf;+8Cj53Pw)RsM`)_d=Oz>QJhFBxmGl2N)}>ZYez>`~TG5nj zkfpuv8^velD_>?G!{2p5pByaFa@8v!(!hMk_CUx-k4kshoo7SO-R=$!Mv6_H0_~Nj z%$`6_BIJ75H}RIBTjZ#pzZi27H(i;z;C4)r`(cO*HGLFciCe-gnN14`tgPiJK{yH5 zyV=Wb?rv7Q)XJi~IzrL9pi-HiiSf%%d;Vo_mcpGK{C8)7X|!CILe_Ou*?dd(Yn?fLoI%pplMH(GAP8Z$6*=2T`2*b&u{#E@&~ua0mJpnJ^$n2%v(Tf zS6leqt8+zf?~f?3>N?z$fA?o>o|6|4zV)K`)`P4YN6GY2hXLa~8}pTGpAQ_DWN%T^nXHB5$cd`EXRJ|0e~ zVak;aMU}Ts(6W@9LGnF%ZfS0z#=~!+0wkLb_ex)Kon~5O_&XkSpNFKG&in+Ki``Us zF6p}W&4s0WPmG!g%U&!tmfFfs9yC8&Y$!mjb0u1Sh2!iJHIUG~n!smaY0RD1bb!IW zE}6*&6^n>tP}IPTc0=_a*fh3~l;I{Wqx*5&h4apf#GZ+=i(C>#@|*}4&Jd-d%YVIx zSR`I91w3fK#+=zKcI^*t+<9BhDqy2=%!Rab06*ruZX$@%9Ft%Q>_Pq9s9ET~yl}U1 zxMD@Rt~p)y;=W zd?3-LHXA$}zr|HRQPx!YCw%^X`_J3tdkO@Coc*UNAQ&CuplC=h&DdEY&YftUl|GQ! zaoWFu^YNo$&G)X}(mI7a^>92Eak3Tx|J-rv93^M{su`y69FC4!>B??~GQ2*omR4Rz zm0ur6%W@5{iMxb2E>z(O-0E8XNL+coZo^w)P;~Vg-WFrZeC2&SvY}kLVC&GAEp|z*nN0*<0a=YH6$S_J?BG+xh0W62%1pEul;!axPn78`iOMJAr$Ew94AMxB(Hr5QU(}NB<^nwv zh*h`C8$vvVH@x_#wa9a`7)(Ta^lF>H@3R1wr`p?K#S@93|G$2e$aW+!L}&5UEV?cw zl)xvtM8I@37}r-zULYQCo^{Fn`{3EHD(h;H($&x)$WhZ=wk7JK&lP2X`jO(Si-oeY zMT&GvB4Ie70!rrMHwnVJA(uz>uMHI>Jk`B$jm6U8GN^wO4HXw0oRCnLf}qVC=pd6; z~aj&`*nAS z69v;pMIFs7m^mzd8rnN#Jm3BzM@bch=Gmzt9ThD(qr36oRElbypRWjuFR#t)c*6+D z3Tm(d5HQG>)k|0mWMf7> zeyB30Q9*;?R4%v0FEQi@!U$&CG#jCHNiL9VOl;xU71#80@ z6=hX8vr!xLs519t*8sl-=gO%Qho@Gykf3|SdTz+~bbs?3N`{RA&HS2txqjBM=Z=L9 znzQZ{yMUGuouH9EMSt~!`8D&tGxl-?rO%|Fe*)o#uhb(GnM4hR$LUzNIFKl*7{2~z zqHaR{0@WRSLX?EdSDGiLxgFbfpmt88k6b2lK*j zzfu)4#6f-GgN>1Y!33vm5~YVP_Q?e~mk;}w8llsd^^UOlI}E2?jW_=0-9K=V_k%e* z0v4rUeU5qyh6~Xm-JMQ}@%2nNpZY>rUo2i9w)n53naz)`koBe}vvbq6;S3eD>$`&{ zxPdR`UJ;rxy#cH~BE>+Y20*9QA6;k23X{vK*%tqQDpJLN!U(@A;X2f7h&h%hXpF`I z0Kn;WyvBzBfiEh+rU=&;AD$kby!(Q*ZS(r_2EW!X z<_9Y1x+$G20UsqV+vi_tp7jp68QwFaD@~9=H^d}n{uo#-o!Z!Fk;7<#lws4v+bDNq zPV>`)FK|}eJMh`Oaw3Bd1g{?CNi2!9Fv@77 zOQ(vGO;Fd9N7w0u(mXNqAC9D`cjrEb)7&5r6n7L9qb`|8&@D8bSr0%mPKIJ1L@nUw zaO~OL-|AE>w)+cnF*2*tx5U?|lA1sJl+>&y0Blyf>Lidl-UY>bsgI^m`p{khMF@k3~M>2_#s-o|2M2|4cB za3;JyKEbYa<35~zU$}ND|Ms0Cd1N)6xH#JWldML4*IE&ej4n-}LgMKiP>U(t_UJTl zTSv*_3CK%p|N0SL21EI{obbMEzLU0jY88rH0Z=Sc9rDo_(AZk!i1!_~_OLF;$Z|d# z%&f>LS^r%TnOM4RpXX;(<&Qmorb8Dz9(0xcMHO|beLW608g%fz{{>U2tk3LMsOJd$ z)Ni8Lk%}j{&d9599PU=pv=W{olNnr_Pn|e$;E3-?;l=7UuMQd4MdoIHFP9Ei->y$= z#l0t(g=K6a6U72V}0!JG%|8`(z)YHie&mo0nM zCy22JZKUh0BYCedgy;u4xgER7C}8&e?8g9shT%Su0^WYj4!jz!w7cMSNf%Y3(^uN1 z563@|tbN%T6GOAql#2Ev#D4kgjE~lcNJi|a7MCmDznSo2Np9kA^!~%Yq|BavsRRA{ zv+=#G5?KYFe1jwo@(F|+1FGkQoCn*hGxEEYHgtC-w#*aXt#+T+l>Q!}DccO~Qby39 zWW5=jo0s?V$t{bUECFjy4h{mw`Sc}~L{`3^*}1v73Ta&lQ8V!|G0IP$3NcH$D;DA> zCMI5vok~t{%aBOa08hj6>Z(F!kJlSPLukpH0uRQK+ciIvFWXVOHj$sOQN6QR`YFi$ zJ*{ydMVv{TQ6Qh2CxJ$)L&-k(>D{M~3Ulu+IVi2pcaeDJCo4)TbrUq0`nJtydR2*v#D*SwQRxu-Z z?bQ2|Z=X1vw~nlT#CGGx2XF@Th#dX~^HT}k)iUv&UOpR(mf+Y)Y7Y?a^nzZ=H(+U~ zFbWfyfX2*E3V}2j4Ce22ywf=bhNjG9|G5ETX`W%xi>2EAk&>-aIy$;D@QdkoYxm1- z10QqGSie-tlzR9=A-5;_MnRX2(B^isOZU-Dbp)q#{#uvMPPg&76ZcUsG@?dY+s0UH zGk@=NN-Jch=UWd&M<+cUM|u3(3vC=Gd(tc5=T6s3ygOVlf4YWTt9kB3*7bhP1}VX+ zB;3+klKgSDSK?Bf;haAaA0<(Imv24!`-EJ#XSQnm`N4sJy?OA?UE2lA&finXXVa9! zrhk8bnbbamS+y;YKOWQHT9CFw?0H+ed$jYzCi7;aM+W@&kN-|-kLuSG5K`k|V@!%r zt^VhG0eIeVE(ewvURxNf2!lr5&JTQIVlfK~3lrtD;!HGjcT>vCqru8q@iDWdMRk2~ zSk2Nh-TF9He7lmB6?Y&Fvx~ilWMV_PVYD=nXk+%ou8j>P-ynYO>%8J+TdX6`feOQ zFR$&gmuUOwtlRjLiJPfGLDcID0}6NUJhwjntf4`vxVShgCuikUHX|b=T=?-md9R=7 zUSVjGT=#C8K-d!{p~RUUTUtIW*;{UWd6Ke^jyi-EL40X810%F{A*Eg|q!d9Ii7RNDK8Rw=SRO zzIR1j{NsT`N6#=ZwQVj>*xHD@E0VyrbApyO6Yd5sE$sRC0r&!_RMgcip*8rLX%$^W zGiq}6`^#gqJ(;v%A6=Wrhkg2V#i}zYKXhgmoJ<#ot5B}?KF|c;yG(Ttuv})HL0en< z6ywdeA3mIcCcY87)Xa3R=lqqTaB)I~lO|@D}Tsn5Y3txmPDPviO{G=AuywVXXgj=OwIiYE@NSyi-lAeId3_08wPq#ZF!h z3;66ZrAl#}har3!v$faqpI88#+VMjx}3WsHj$OaU4H=Iz1;R2s-<~-Bkx2@l8!lHsrp{1-bn# zS};&$rl!6StldS!O(t2kMtiv*vUzGo1?`VR-t+l}`TD}b!r;sp0|&-Y4RY+QccGyW z?QcGRz5x!N$_f3M+k>67zoFwH9j*fni(nLjUQ7>9@HcJ398kfH%4ha0H(Yl5?7Oux zU6)Jo=s{bnxZ9r(RjFApd`crR6=j#2I99%f9`~07f-!80I_S$M-fGz0S_NMxFL*05 zQ&OITrS0e`hHrJWatnP+ipdIUt`76$Z%8Vs>(@h3^L@*k6Jfc;|G608wmVSJ^9>f3 zjg5_hfpA@BXRc=n8a&WZ{0)!4C@3fhk*cnx^&#%?!9OEdsW92?s|NR<9uX1}vh#`P z?$*iE&o%CWD3!%zX6D|looS0zu(RU>`;M4oV(715T4n)zD6sFeSE1(ruB_-(xNU8I znUe&sl8&}^%19lv$Iu-mrK4bkcgM~;-9*jl9i?SC^$l85n_-6;effpzj>wFjK5_$m z7!;G;siTLQo124KWa7YfeSl~GUcAjsMp)u5o0|+FO1^$!a+aC-GZkK|R?ztS1L8*s zqS`n=dcLqW>FGp+kkg1X6^hIqaYC>#I;<#3+DjN*vuwh`=bl|Rt-A4~|Ay!Rc%$%- zA3r>|XETLj?{RW+{sn*5&C3Ulo@V?B-o&P72M$pkr>1^1^yO(ISC__`gl7lo@gnVg zlW}khbW%cpw6>OT{pY}BspzAMUY}dJPs(r$rt89?4djq5BoyFuU9q&Q;&G$ca_vhuEse7hYE~^)Cbda zbaWWR9GSoXI_e45$xA|y4nsS)<&VSo=9|^-#2=0o;L80qt)PWO)`MfP7jIha?m#ay z63MIU2_C>o@bkP23VH9xOINj z`1!!nHQ)@)+u;iXjEA>T#nR_b0jO9_wM02OIJ^rB^Y9@qEfw}HNDNqe^AWuL)jJ=9 zMe>hZW9ZQJYuA3-mE{x;3VW~F)a2^KuY*D?T==@B2~Wn{dlAB zE6NP1Q#489Vy)YIxw)r z9)BIIGj*W)wNm~_7y- zvoe}Ln(a%YKDa@ssx2o=T^PStY%<3S0ZQTuw8<;@WYgn8^=h3l_8#xOf&~2Nk4gnHJDp% zE41Tk&Z^zzo&Ibi?~VDiMH=l5PwqRD(A$Yxkk+c%;b|Ka@(fhc2``IyQ(PzR5E7Z; zr0BF>$A2~WQ^BHnpjx@pr}7(tueu75=?>Zn8Z-r4FK7%jz6o}aPQIGv6Yjyy96U3G zl~dkuh*3mSHk2YiWo5s>t|;~<*;%#6P4)Tz{&t{DMf6i2A1oq0)|>RGA^6fY!_Uv4 znLZv`yU}R0VbP-_l$P;9+ObaQ)l*|*V{`N6zAMc<(AWQT(4j)eWm3h=f6LObYL;7e z_pbt6_pXl4Ij|1Tsa|z@9rXs+y|m!TbE_afPqE zm#`Z{)Je&I%z$?oLOK9Ed)SRZ*zJHx1cy_U@m~84A@B*lxI+C3vA;-xc(NcBUoq@{ z*{OD~oUlF_p?R=CcP(!ESKrJp-vS<=0QuddQb`$Dl7-V{;(4b(*4=;ih*;RH9-K}rPM{Bv!e6$Nnxi|}&FgB;DfOnVNPxrOlSM3oyCvi3EO?MsB=9~lj z(fe=o3wb>1eM&X4XGcFC)}kwxGkL{(<)izFW~Sktlen#&SUYlTrli%%?8&H((39plzaY73JiH$f0= z!tHkGeYGj*nnYfgHno?|FGi0BHeR z!W;1UF;zU8R0K8&b`R-q8S3#=_!AV5z#Oj~AT2BG$uTg@)Y+Bk7#TI2dJNY?(mrwG z!~saUCGb5UfOH28vEHJz(tn>-F}U;K@++7m zl7>G@d0YoC)Q>Ue&yc2SHpfqbp=WMDeM+LRJRuv%ph>4w(+9S-g@FjDdSU>l4^n8; z;@4FT_yP^w(>5y+@Bz9?l@-3Lt(Aks2+W=C?svzERp2Q_?nL9cc~g=(V22_KB?{jq z0~F~r9X&l5>%+c;oM&KA0c%3sZzC8oxc3fdH9{jq;IymEz|Q&c4U8zm36+IV4;#9p z<^c!KRiFRRZ#w+LYVG8e(vA98>(c&ee9r=Qt{?VrjoXx-k#Ig7Qihz&-z{V`NTAd;HWR9<{_4?* zA&lz(n9#+b(e;S5Gd#|%0u?ua8gzGetNdSVy#-iRZMQDG2)h9(K@^aXl#ov8ZjnY1 zkVd*uRHUV)yF@yrB_x!R?(Xh}Gp6ou|NB2@U)LKVu-062J~75!kGOcEda3z{W&I5y zA)!3;QBJ5cFV%ui8Zm`OJ~boM($YFOI6%I`dpLu=7QnD(cZmnAJN8DZQ& z6($(F48`p44!(1#cwSek$B(Dr%ZB0M=&~~Q%Bm^?7Ngs2qc+%(pYeRVROJ+60Vct^ zr!&>yjeq^3dCjREjKaA=f3Qiu12fH4DB;#>&fVtPV}G&sYfS(DhKej~XuJK|*jQMC zZ{9Fbgm{BP@gvlk^{YDtV46azB`C^!O>H8eWkD7=sFR=R=sbWP;G0%elwrJUIG9o8 zppb_uOWS4hLcIGK2Yf!LKHkFn*O|qD)$9WdLM$8{A^1Irbzrop+`Nc_JFI+MyvxB7 zzuYnwe|tXGz!x(*7w;PbU6RAF+8(WI5RatxOmknaD$Osnyik%KL~bjc82&O|9JD?k zw_X;n?#~qsZ(Ip{#5DWHg>>4xVn^-kcHziXKfIH5Z2pIv<<$7U-6%C4QX{+hreV4~ zch+y8YwiC7OzCxEt+|xmEiNyA2bO6e5s|OOLENmd8EO5?ug9ya4Dmg{uLFfJJX~Xe zbwx;qs0W)m)P1D1w7;4C+6>4jDKC+bkR&B12ObL~L9q@!YUwd}0aL$y^ZW7z|Kvnt zmsKXEtn3Rk(OB5nfmz>^`YF6^(dtw@+*Gh*5<@uw4D(spsn1S~VMHk!KdT{hZENy=^ zmc*8b*qs>S@~p?D=BTtD8W5me88zyE5*cg3EgpXOHH#<&~Z)R@}JB!`xVs^@f>xs3)J9ZJOTfp7h-gopnh7^r#ie1}Sirbx}qmoLMa35sLDil51);gMba(Ia4VBXC`+>t~p1tMBI3o9QJ~P%Cj%%des_UU)C3 zt?@}#h{&H+Sv4TM>{h@sIftaMc$RlcR2>HV&FvxU&xRSoZe7HA{rw7xc_cMuGD-%k z4FmLIbUCXe{oY5x&pgntDy@xsyC3(Rul_|lP6owE#bLiI<3B827i?kR%RA0C>{{As zxK8q{;-+TiKh*NIT5gHSq$vyk{JnJ(H%DJm1rdd^JsPGlxBIbOm}k<=&O+y!R$VkIZTU}lKMT!DJwKOlsdzzYY?Vrf24@V6wn{+MRF!DECt1)R@tkpH+Uw2)> zY@S;QciO3;_#CB(LmBYVX=g4x7vs4mnOEwMV&jYtW(7X=0dxI|b28ymHfNmLBptUW zhUUCPJXPGcDC_>>WcY(ad-GPt;~%a(Y>xt5q=RDf(&r8VjZZS6MTgleYMNQ%i-@``UnOtxIExPrbvvf4?1KoY4C7Hvp!ZZ4M$sK^{e9Z7o0eSfjMxr~m*J3SU7% zJ59hjPxqqWeMSZqbl6f*o${S*AiXr^#ft^dE_bZW`(K;9|F`=Ayl|hwo7_qu`ib5} z=(8{AfL((d{P(J~xPe-R@q?xm+}ts+C3JLhShUA*z!Zgevu3cxOVqfXUcPpXjGLP% zS>D*^vel$w28RPmSY;i#yMmWf21?jF;G-9*(M1`gAHXl#aK;X$QC+?1g;Ax|0U>uE zRhC;Lo|@@`ouw&OUs+pQ*3FH#tE=na__(4m%7joot2e3Fn3|qG4KSjH2BF>4TSV+0 zrKN0unJw93Q_AR{9BeLW)UvLpS;0c-{pnNf@UXgnY2%_zaCEexBzwlxQ(5!z7XX;1Tb3`8s?}=! zg_>F`xG(`U6w2x?_g~Lkv^F{$EbcQeR-=Y)chd4UHn!)W%ePM!itf-r{@p0NHa0BL z(a}-;xFvwM0)`hD5fR}OdwXhz%13Z--gm*OY3Hf0KAV;5QrE%`o(tOYP#w|D^8-H9 zVrA%m?(obo;Gb$}JEOjC?_23F6B30xolJ3IvmRXKxchgw%~wskmt#*6J+++RN6OsY zU8q`~;9m#x`nmit?ERAS?XhSZo140jBw#v__ja=03*+;bFU{cS?>*a|Ya?S}2{j)r zzk`KU2Ol*1C$}r)yg)sXQ?bSg&sGfT7QkrIEXJ!(07yarK)Cm?_YpuWUR0%8rNa|g zXM1{-P)|(00#5)v0Z=7x&carZ#C7KmphmDn2Y>#|ucQ=O{^6E}cLXFa zeS&#bZnr8SC3PL?z987hI36OrbQtl=mUAi)q~p$=J4F`baZmt3!JG;FhYq8hs_Nz1 z)CetP#GyU~1~%z1=0UWEKp~unH>XN zQ3k;}z5OW9OSe>Ve>FEx079#*2lq-35Nw#2hzr`FJ!a5gG$ptC$OlGtoZHcBz_E}< zvNJ)Tp|No@*ZuTbNJ|62ne7lku;`c>4S5QMuE%z;BDjpis29HOra&GxOa#D)Cjm=H zC@2VS38CEXmdzm&fUiw2^ARkl+-9-vr~f@bwngE|K}Gx*El%%liQ%vw34V!!JT*RuSG&qKVu|rI z+8=D{ThL=OLIwiZtVO_PuZ}M9>Dnm33OZTYD%uh2XWr17qIz&=W16@9Fuj>`8eFfg(xs|6i_7)oL&2yzHN0x8oyDxtoZYTl!Y;?4aTfJp_1jhq z0-Td|MW52_#@D5pn-s;ujw{DH_e+LCqC@KY#Cj5FplI-GHzH-vWUy_#)axMJCo}Yj ze43c>L;Hg8fpC3B^T?PfCbE`(+V0+T)_u?Jg)m$|4F<)=O22$b3h1;SF;_U$fJszW zi;IgP6yg?SY}BuEW~*dT2tjvpu|7Zh0tB_xh>MA#CKA2wzl0?maQQoUc!a$6dj=Q-qDT*KQ6Y(7b!!^3|ia;DREJA8!TC=l-uz^P?qM3tqI zU8lp?nJS5g#G3%)#B{qz-64(#_!rLpq3-4x}sraRtE7pSk&m4IffWn+#5-x%4({&H8zw z!UFnqYPnc~kH{`@oJ^m8B4S66|HSU|G+j3<_fh4z9RFl3o<$ne4PTW@xoVnz~9Su?f7!hA&yGvJ`*dz<0r5^b$_)TIwlc% zCfh>V%q-gp3m6igAzq*ZcGu}(hZ}+X2oDow1y@%d7@Dv#KsW;?3U)tH_(h~8h3)$x z71bwz(a@SY@(nxUP*6{@z8>hYD~R{H?M`vF8GB`!D|EvA)VpFuO~T$3Jz>of&A<1q zP1zC!I@f;EsWRJlO~adk6uLXvm^LdSmZiQ%{SUpP-kqZGPcab0<3~SD~42nQca(q{UOGUpVO@1;o*>-5dQeAMHLe-njdvKA<;| zt1AX&Lt*ifp&}eQCGoPO+#a0!wQ9;aKha!BUy4_*-DKUgE4bS4));X98~QHXmmklB z&7Kpk9|7uOlQ$Q4ve=nQY*Fo`u0eN(4oO zo38-@I{?nRVT^?Jj#{W-CQ-Qp&3IQhe?#*@ow=le09-HVtS zS%pz1S{~(#FC1{m_=4uvySdT&J3AB3s#syghHZz#Wv5GYXMH^W=*S6*&1V2+OniL{ z`7zHEyNnQ|6VM90?fDKvC^ec!$Gv&6JE{dQ_g{^n7}M>7trBtKM?cgn_vP zA|&ot``sm<4eGL}5yPXvw6AE+mX-XbENaD~*7BlSN^?igB13e2)DF!;U6a+P+uL63 z{ZOCFnOU27GKbwQP6lQ`3;_uGGW5N=FDBs2WdCiRna2`;*n$gP2*gXdF$r%F-UwYk zypo$>$?0Dq8S6Pm{+#=7jT)2n@9x2>+MD$}1eQ41xKL$~LiD28`0lvdu~}B}$M#13 zIt%faw(DcSm%WHOIbCSq%6S(RfKppj5O=8BndVY|4v^klyU zp#kp%=LNuR$4tgD6*zNq9842qi8q;0Bh_k?tDvl0{30Dfjm(|3rZX&M!) zAt^H=f%n@W@Tv}?wtyOaxzL%26n);GIygEij}5j<25WF>7B@@7n49_&o3_ zuOPH1CB35LM^9h5n<|$gl$J=9(WAKZo_#zLT`+^e?sR`dRq?~Dk+=GY+6$j<-Af6k z^9C+@*l0I+Ij<`K~;H)Rb(1h{KZ z?mGP|4Z=VmGf(XKqZaaG5Uv>?o&`cJHR>>aj*9x)*R&ZL8rlGRcO=VeEF|b`xHV$C z1wbjs^V5AtNX2|n?ZSbAvKv{UVP2DXK!DaAsC^+wOBIU!iLVU1P?P@2?2bGan1fO- z6$(Yz+Wr0fu0z(1B%q0au$QUpZikQ9bW0@yuM@vk}C%|(`t z{(R<-59( zDVb=0*do8HkP-Ni``Nil_c%v-SD4aXs&=`T-Sr+81$C>1PoY6GuE)HuDoT^O7M~nl z`ZKU%!|w6ZEyrtV@10BkanVM!ZiF6>tMkGH3K*acYB>3rGi#E+g`%Pxs1(L?^z! zP?D4L2n@Uhy>i?nGg3X(HZ^$x$MLoCSG?=qi~H^;RtP%G8rd5RiAR7)=Bs6!j+6y~ zHl?ERuJ9y0eJY~X((diI^hMIl4Zr+brhSybbviiKJ^tB#`-d{;dRyL|eL>c-@}+J8m!Sk&;l zEIGI&bDa!T%yRU?`^;zAFSs>L58N~EaxUgIOs@~<)5}4qKcc?y_=jaaCR}DuOP%im zU`Q`?%%?5}Q{@hZ$n8j`Kg_iB57PHWgKy7s_=`L<%2+O&vz7*IVYt*{-_))<>p26b zjpb=)O0V&-h9;~a!qD4*nyd_x-QLUcorXg5c?MBv3eTT6L9F(5L~u6Bb#4qBD#F!v z@E%{!>Xm?S*HiC+>KaV}KmlFI`_!3e*&CGj|Lc9!Owt1q@Eg7m0NP$uS{yby5d(mdZ zs)-n>mhM++g2<%DNgAd%?TdnjWUt#(rkmb=^%MKUvi>Jz4c99^ww`ijGSJnrm19_u z<=S(7&t|RD(Y=xuNbC{iX1++`}mx4QA>~4 z{^*UDFR}JDER&W|C$p2RGA#W2!Ux1HKIF)rCM#jF_h>0to{~Lw^|w#;%wyC|vjf~1 znLwlA*8MXnXacd$ww`x<{`Xt4V*jAn2h>XXt4SprC^gTZgdEq+oBo)!YA-|%9*WdKP_5q%?YY#6(y_=$ zhWegGg`|;&D(3SVMkk?c?w4v%u(mKPXEJaI>DgWoj;_XdP}Hx3lkN$vs5cS2AWvhP zZn50SHYX6b9}Dw?;6uYos1O_N4NPq37+!Mky`If%Xe!nRKTcWR?#!g*4YD%6uF*ku zT-YddlhE7U1+VlA^4S{V{b6rG<`@5?8qkv;9v7Oe|qn@6j1Ch^+`{Tik}&7)e+(PbI=k3Mf{^bzV#ci zl7V5yX`sQGAWU`6WIWhReV*ndP`LBK`(?Hdi>|S)XS&{#xK(&wD2#vVxpC8<9N6d{ z+_?-Zyc?Vh7A%B^B?xSOTTq1@S%mQtj{cCk=wV%17`TB_yRVqcM1^QC6&DIB(f;@IJWSLSeongr_gPE)mO zCxP^mxG5moUcG{SO%@64L>}0UicZKn(lMJSn^qU@f!<_+Nd zn_pD>?IB8yv}D8Qun9(#`>!g!p!r3ux_v>DQl@bM&!eh3T+`RU*^Z0H$I#QHQ9-N& zr`66}Q2s&6`~)txj&zL5HP}C4W_f4)cs_yWyz!oq-&IFGFlw>v({nVCWgB56Up|}Nn zHE%&1UR?0IxV7b(QLcc}>`E#pL&)c~)6tg!BG;fV@i38rt&ocx-NWO(KD3U4$z4gz zPP)_#iAOqi+rJP+3e<1#3fY>-y_o6{`_C9FyVD;MzxOb8G1`(v?Fm42ziCBRcmNBWBVgGmkP^y+*UfpkJ|7w_)H(qF4LY(a8y z(=(SO&ExieF9`p6!a&ZZsNb*C%@j@UPG-gL{i3Zw=`^~pR5-RaRJ<-&tI2GoN(i5K z;CPK@p^Xc@w{F;or6E0_Y0yachcX}a*_NJoq)h+0^l3#pGVVYLRQl9k zMzpjg@M~_d6Gm*)xNlW8ZuXc*pOJ!|OojhY5;v!R)iX1br0#o*HmBoxY&}W)TWD?h z*(PeSabxVqXhD!&-=wUB&8au^Qi**@Bwv5XU$M5`|`HZ8~cmXN{=Y!Fp zpl$>bY;cVPm?=5BYFDNxN(UJg{nlBbG>x^v5z?wboq_^zdfS={m71#_97LsOB z8@)0eEQEy&LdzgRarnPd?}cOPgYopZwkcWRXFz~-BgkldkF+E8>R{bE+<#k*?t$k_`95)hy;sa!7o2_c12)<%z>Ja^7;#Ly2vZT z4;Td@k8P?$P(A~`Gil^$|-@p7YfXo~AzOve0B5r=+zMGE=?52ud zjK0hnk>5VQ&^QT;|E~FI!(zTlnDf)W7kt@D3oz{4f*KxJ$%5aLWU;_s!LQdV-;vi^ zjB0Tu2=3OM@BC;nI`p2M1ZGnrx8A)g$riiUV{z5ZSYew;+V(1M5SS=cSC_ z?GN_;Jc$$ddo%d_{$4P8sHT#Hoji4+_Gw@_VJ63ooL(_HME-e#&J*4E+HzZ4R-2S8Y zz^O2oFqbQ)qpPYWp=;^#8ZQb=A*cWYbC?YB>R&u9Y|#CCMe}=mZ$Ft}+8N_T^$`6| z+v30I#K8Px^rFs=NqWF=RC)cOYF5A>IXnE=mTS4Sj38>byc+oqBsINY-xj{l$hOalKbm9V{bNOP%2v@*m5%7(jklp{Sm{;`>_Ut4ctr!)Vt?jiv^j|8&&V@}Fb+c)qsUt(Zs&G%) z@R~gkrcCHvY&o*Le^avRs5(0naQB0GTc`l24-YRHUoGg0tYiny8f7DbeX)?iPLg=m zxx`V!b?P{ifmf`({}-c|$P_eLb-TZMXM+B(dgL&V2++BL*yzo`^>GV**Iq##lySVPrRCRjPX_mU5H}4j>{Utk*U)#NHOmE$@*jcWI|fn z&%zfV*z=M}PcA6H0zJs}i=KuN);@rImzS%>?tjnu`t_=Xg@xbG5_fgCoIEu|H-2(@ z%JXarQwr^e(DgFEPiPVH>Y<{uXR+`&8^+}32bE96dn0h}u)U-`TdnBKd4@HcC=b9a zd|a>6lfZ?C?ho^SdMzH59Mfhr23%70pLd9p%EdZ zlh#@E;Hn)WR|+B%MVvGV3H-79k#9=ouHODfck@KM7v7~&*#I2J`DuJO7)1~_MYY>( z*mE%%J2L?e0>kaY*j$(7A#COqLZ=Z9PeeY(Px<@}|H=18elH* z0$@2s(Te&$@e<8)btQe7Pqcf$)@y33-mRVeAH2~I)JXarfABKf#{-MEaAb>22sdz4 zI%5~y&@1+S_RxRwD~%(wZ#-6|Y2EN&n|M;U`R#5hG{cMs_a*g@g&JN`^X<_V9qHBN zb`wa0j1{!Y$nw4&hCu8wz+Z&j=W%j)S~_4yVLDjw0YrbFpXjxpzDzT;&S5tAodC3J zTwBfHLRT{Ahk^{ZUq`Z8+y{l(OCZ=#8gTALdeOTjQ{I|u0#H-}@~3xh%lh$Pd&_rO zXv-{6heJ*9)gJwx>jtN|`{^ZEa5zIs%U!S4>b_>rMDJHizQaNYAm}x-!n>)2tApD4 zj!DOeZX|uo16qZsXWxkqH{Dr?=qTPyh;`_Wz@Ec?k1l~~samcg741}<`>$@}({|+F z55wzv#0W=)O`jE+^g9XkMMV+*$3P^ete_wWss`L&`6M1N3z@6HN6`lLyN5HSCX z(MN_wq??Eq_ZsxDO=i1XT^iQb)-CPryg8#_5whU~QN&-n&)~?E^nK@*C&=*|WjU`2 z(}8k|iHVuhR0f70m`QmhrJ24lmX5T2^PG%~Pk>NCAos}7U19m-@UXC;$jHT~{c~{4 zlydqED6Qw#-OnqAE@`Ygf-D%hbj{dfmF)4YliFTB5JzKNx>y++6IB!Q1x&pSv-Cdw0uTWOg$1|^28(tSrkm~u z_Ta4S1G)g)GbW6Jq>;R|4J`T#G5-;G3DRxVnVS4LSCh7cO+=YV*C+(_0)aWq|YA zP#XJ_mh6af9gh0(SbhOV#woAfBP47E*GMMC9xMiJ2-keNHw?xsN}%YQo5et@pZU`e zWZ8iDfKmZI|Hg=Q2QXXfQMWfh`Fk4|R|GUMpq75X$S9{-wWA)d4fGZmw#Xkn3W|x5 zvaw+qciHwQ#G4XK-e0^;)(;*u)Ji z1knH6_^Gc}MMs53gFIKQ! z(_!Fo5+!DP^ho&oLXvMN_?sFhEvev0IByWkg@V#k4koAsWbva@!C^)czyUgGS_4F! z{U=%UR%%9u7`zl5&!+V9<;zfz7-Z$%xai4bHpJ5SGM@@Lln-1da1G!~lQq5$R{_Ta zf&_@>9-Fxmj)_G_Yx3+6*4C zu|1c^>7UQ-UJSj0O+f{E3B?lg(XZ9o))XP)FUl+vlc;={z*qs~D;08zCBS>>$dNvv z_*RHtu68}f;fM3p6yYu5JP~A-rUIdXC;Sq)*RsIAI1Ac(IdCN6Wc7Z1|KS5Q2D_)zLDglv} z2|5jG5TyFRkt=b4+CJjsRDblo6tbwKk~y!ygziT@CoKFMB%whbK&w8j@3OyCvBvc@3wjXj93cOrL-G^(4l{heZ8El6B-HZBg#)@%v0%VkLg9N4kT!zTe zWwphu$VoF$wv>;}kb{`O14xWp9$=zEcr1_#q5AunJz!e=x4ll#)s2^z_r!f~jf?y1 zW7mlTdo=@!s_WF43YS@JQfMw;{FE@&n)LF;Wm1!8r}+g7k8$njDtycHXng*tpkHmi zdR6R}_YUdD@b{kueHI^vNF5c8lRPtL3XvJSz#Tu|qBj>~-7&(kFJUmoG0&qD9huT) zl#!9416F9MFN|o0hQlkK2+snC+YD8?MN0jIl{j@e-g%7!#+~<|sYt5Axs0 zg?AeC6gF2&xdI`gR*|Q^Jwe{q7&>yYbzXfs-wXxX+P{e^iKqRolj8!wes3`RPd(6fB_;~G# zcVhg>wXtBb4~;egX&W5h7>1m8gfL{_6kvptu3*tIu$Ll+#TI-fy46QZG%|7AEpT7p zxS{KC+N~W&D3t!G53mN}uuUcL?**7C3JMCA0Yi$&!sk2UDZz#eJ1IsnRxb$L#{Bz_8y#||UiDtMlqMA^2(D;i<3w-+DntVr zo!Mnd*3?7?X1^)0(@w%d{tB!|i2J|=9MMocp_N3k1Q6L{n`8%a1~6;-iRcvy;P^HQ zg2ni-=KPqi=`lLSa_PLe@kLpaC_<9uFrn@@-(xJQ4?n_X7J@m(Zf&Fm>jJTh96$*a!+UrfwKvy8j7G*gIG8RRYszDROxm`qGSYpK2T{YxmwboK2$mb z{!#)h0G9XySRLR9+EkRns42dYI*BdpZma0Dl(KQ5=&u6ihkzOawaX7^H!SdIoq!;P z2nCbQts_pyEplLw=2uI{)7;O`5X%^tHewK01f0MJ!qV0DU06Y8A@>~2v0$=5AFy)) zE1}8Gk^0oZ(Y>Q4zO%QvxeQH#BoXKqaD*+t>x0(KgT9{(e0=eUMY*dD^O^X&h743hDp_|y zG6*~^1H3gzFELFE{h@yT0u2b9>#J{Q$ZRoIX}2qH2uCXs@w(s_4kD!zOwq|kJZ((E zcoQWh9D~BhNM=I?4Gq5*{VBMOhOnUe8$8vNg>L})>;?21GU&i@1h=B8qvIAd%(Zqo z@BqkReygcGx4!|q?;(gRWZ^xN`^T{i4GrPIAP&0~{EMDHa@v3Wx>ltnD}!5~{e#IR6OLj8d@jP(r!N=e;|V1*aWR$+GB(nqwFTJEFa3q|1j2Nx?+36Fs( z{NpIb1PJI5-z7*kHn+Cw-~b;mgYX_qV89|o#lV2bMBwtrnxQ@;P4Np%`M0Uq_e!|QddlNo4qHTlnr;BR;&n^oXmXWWu zoL5;v3`9>)59LEXs5nCdE!>4mfD3eRH~r z*vSIa7o%Q0h>j)0%!(fSU)Vb_H?I&@X+a#QtS)2fZ#*YBMel2K6P3UtL{Y z>Gsz0C?IQSK{3Rjq@n`5Y=nU|$0#k#A5crvc9xtd)cG4W%aF|u&!TK%neLU!XcDQN zz}bTHWQtUB&PzmDIo_FH-z^0TYH)pISGlrknVbXSC){hV2=F#87t@K?#9bfEWVgR8 zl-S3vqG`{X8u7iznrCjv*jUnc@o+%W$i;j_!CK(<`{t|T`P&+7f-gM*3bX}#xtS`w*Pu{n#k*x(f* zA%Y8c_j?79(B5KY~rYCqGmZ3mF~_?4L!kG*TQ%^XI;?S z!c&eHKjulzYmcsIdqHdTc$!f4+(KO0>V5>atZq)`PgX{p_4^q76ehMYC}WAM)H3Ye zy{114)%oBGQ{0v{h7MT?N%&5@My6GJQ!4e2I~|S{!X5AAuANdzOA0Nn_?&-!;_Kj&?t(u}@bob#1_kJ~Os1M4hH&8oTyGgAa8-=NuHMdTX)hM{u#iPI#R;ZrLuOMuG5w7xK2+hVKGfs9pNnTsP zpY)iu!%jXckzGc;S*cP6vkrdXXj1Qr+mpw(9TZQK#IQ z9+%8A%WZs%gnspe@VkVxfAy!jgJ&ozmiCMo&CKRsDcm%TYpTBa;WPg6q>7I>7q9|& zcex{!a&Q9COR>S}>YZ8Qgms7U8?&ml>#q59~a zbrng;$gd1|pSM=8vS<-o-dYs+AIkqQ2 zn(&EoSctO&o`gU1UB?$Q#G}5F{EP$@H9uZ5kt$Njb5tbBnY8c``1YC>a8;)+k4^EA zVT2XZJT`nTL4P9UU!5V4D;E_fc63X7a%G&L`1vJ;r@1MlY#1oL)VDFo&dugP=|Ka7j8xisG7NyQ#9$c=={>hVa>Aq&&;q1gM zn*~1ftX@H7U3wIZP_zMqDplGWx9VY9d@s4E8J|d1Okaj+6OK-V3j4rOX1C;HsA_@g ziQ|0T{uw?5J=%{@O^GC?@sc3H*greuzgd+rW%E`G7VZrBT4$X}ymG^BcPokf$UEt| z$T%T`@|#T!HB6rxwNB^}mE;^F@Gi8VM77dCQVg=bQtZWcmGXveNV4T#VeboL6DpaL zD>YoET%SrhC%}DWo&58gZ>QOU5~@aq&>Khs^%+uKzy<_{ZvZ%F8g=KKf1NC zs(!^YL_?DfM!x-3sm>x4A(H(?nYB7=T~(L?<+4s~Dp?;Yr;o2VGhWSW6TKGTf*C0l zVA#(aqjiK^Je$h?eXyhGF6<`nwaM;?VZD!TE~Y=m!W1Z@W>LM{cZB}rUUB-(^Ta#k zIqH6WO(cPxaR)m&+E4E?ni3H>S3jKmb<1jb0Kt>fIgQBgHW(?&8Yn1-g3+>g! znUC8e(8UWbI(Fg682>J2{WIOye0P_ld&Zd6AbC|aEbCt570TwJ8Up<{aOm!+fwhlc8kw9zmEUK&kKJ_gt6bOvy5bH>;IFvESOf4Pf_0*UZ65k>Kxd5^>GzA5f+2**L6_ki*nKRRA?}x8PhEw&Z z{bt?eYKY9rk{g+D7W_M^@km93JLzq?3?kbMD&A!E`e@}skWO6=Q37P`6fg}J9rhvd zFY4;csfiYIn zxyjUU2<5`=5runHxj|`R_}Y^u=LzHD9in#+Sh88@yx%Vb=0&xYVPYmPv&Ag^D$!s^ z;q@`3E{r@;qBlR-DaXjB_lTnT{zh%;{z&YWHod%N%q@P$_D9A$js93~v@L#aDZmyp zBXL)yFtR{W+-yv^t5A~tL;5YUkQRCN*BSKm3E#Y9goWn=bek&|R9)0xFP4|ubrdxe zO0Ltq<)KmW{ZQBKwRzdhvHRxV{>-$&k33N`I3#3ow1N%f!*sWJc0Mb)frK7GTvb)^ zsj2rY>_{AE?m%S&c%$8{H1rqKkokrL3;on*%C}imxbM0n53M5{u=(@XFW>*_4VpIP z5Un-zK#&OV=9_V_-Z`aAj1HW|s8Q(<1l#i)XxRUx%aVlCsn0oN!~#(QCN#$Awwak3 zmZ8jVtk4V)aoT)>5Hvy$kUzLpQ7Tt?{RKsXDsEGzCJ@c>s3Gw&%Vu0Hwr6j;z+u6cuZzI`Fg@r7zG zripL+{rW0N20=>R0MUrJ(DUG*hYWa$Z|v%oG{xuhZ%H&=6g~;}8@)&6$L9wt-26@A z%{7k89wTJVRP4KCDp_YD(2>7-}pcWf%RwV3QIW=@uB^orH2Zd`A)*cg4@{&z0C4{!cvcIqTm_Noe+Vp@$d zpml!cxu3f=E!kbWetjmt>HahXHifp1fvg;Ey(B=+0Grz^8#pVPTZxRmLCPRS9 zo@x##-svHu)ELdI84JcG6hBM*ePF|n~=r1EjCH(@j%VF!sI zA{-{lg4CuY=xzfVp9^OyjqRX?B2%u(tgGkA`LY%C0I#6q^e`()*r@rRH7%Q0N{b** zR^z+xX;`U!AJVWEzhuz_QHM4w%LFKA8?OhKj3hf#@!HqrNTtbjI?rXNO^UH?LfCvckWZn22d~A6R6Lf6j+Jv<}&9C!a&T@Qb=brrzBM6Rp09L*-g& z&|Xc}9k*RlQc`w@jReg>1aE-zOaV(`0CSNSju+4qt2jfqayG=;w zQy>uBjT|f5JX>-%!uHoZILnn?@t;PwQQ=$#gB5@u4h{}t%pyxm%V#FVYKuLY*bu#w z#}!|K;3P|A^5AuVW-hAq1AyE0P610@EqA#=uDt9hlql@mX^J=YIANn z+-tbL!sP)v>cL+i5)zD7#N7TfIVxhIyStwsvDPpmFu(HFFK(NR6&3)n=TlO-bih_9xbM z9LskZd~<~VYqyiWkfxSosW86L{}|cT*tmko#EnW}kXkMEP*b~iLV6pA)f6VA@aX`C zwK5=I<7xq63DDGmyW(b~2y{n3$M(*7Gu%(&|OCM~EHo&YidM@gzWC zHja=Yz(+{0k%bY0;NKe) zKe)j?r*O{$oY4sinPm=Lym+6qaz(Rx3*1hfGEFDzJ^;82&_qfBoMg@Dyl0wVwm$$p zE10n`Ah<&WoX-GyOW58h?rDOos>@fd1m!e=xZEg$?KLET9ULAahC5FCwcmiheYaT* zR$};XaEcl0EqUT7xHrAPG752SsFks*dq^G$WZ#pLk$L<3hrN^HJ3AnQL<~{-h;7*K z3IL%4l!hOC@{Ns+*NHhp0m4ny-A5rgg`*Yr7?x)zj#{q8tG_N2!dd5cK&w<`Te35eO7XF#%`T6NBIQ zNbZk>_AC_Uk7B>KpOreIot5M$TMhg z2RUDO4M9&7T-9?rAZiVwKxW}a0t8T?^8+0)c4RaG@dJwlY{)-L%!WbK48bEnmw`t& z9f~7B3XmTSXDFrHM9av|eg)!kfHZFt6So0F*9f4fVML`1j4#A<3x{1xzCy*t#rYAk zN|cA|RFJ%4A^?Lm3eHx|vtQS8+m0R=GfS9triB2&Lc7V{C0BwR<8!c}(IEu&lDFQviQP(r`^V3U9tq^Zy+2&pS->|be zIaJg`*>InCmU<=C#!6u9QmZQA=>sl@VOq$vWRQ+rB|~(7>JhNl)>|{;2*3u{ z71W{+^E_gI+#NdZ9kk)!aI`=@EFEPIo1|b@rX(lF1YilU@Gp=N1R-3B07oJGq%Q1_ z@RYZ}!>Yp+nGz`{k{krKYi7Nl*B8HhyzjCh0Ji{Rz)q42RyP=CLFnR81p-+4Gq6-U z?#~~djsBXmFyP}SW@eB>;L(Oxm__M!H^D<~4G~kxa#TnLAYgN|z+0hcwJN{BhP453 zT#_6WSg0_7k-Y*|hLE%IJO2m+=zj=UW!y+Fn<4u=;69iG1|B^ZumQ;-VA8(~LkRFe zc~w=a3&9_65=#Ij4|qQX9=*l{yg>|~d$qiI)LhSO41(C?)PfSDflC8Nnak6_ z5W(a5c#Fim|Kfv(4+SJb>Hd4kE4=fTeDW)@^uUTO6VEGcZcZN*6r`XDj3k%cN&=7& zpreo!fB!sNt?}E7Ld2`_9cn|MXh?Z@s#=H#qLP#zTiMzQ=k{}{pp`rT8ZKQkQcvef z&N#gatZbyP4@XLg*x8jRfz!|)NdQC8-wIS`uhE(Y9j>qDxOA0_(b+*-k)7+%vDy-r zEEh$B`QwS_cn4pZVICm~W*~wI)Ka z;l8y4hq3CQ>bvyLqCY8>7gj%T{!c^cYW?lyMD5!E;ddKZFTXJ+^l*}eu$`ZGt|q0% zHs^e3)EA0>b5k)DZCoIEb*Yt!{M88tU^KiiIvgftS+q0AQdYw5xE3bhcL^d)X0`+0O= zH{y%*GZP_z0>T`Ib{|$|o(+G^%lnKxO9-(7m4n58A;ieS`Ra$0UL;Uh|A0-C*|2?p z_#A3wB$f|F7cUCQl7Q&iiAVX1kOAUeI7%D0oLIcv4T^=@5^U{f$Oi}W59W%tB>X6F z5ivZ@DvvSP-A){`=I;{_c*BMb$;~=2-`eO+vbG@$vH;daKz{$_kVFf3Ufk?(KMMhK z8xqRZ^vol?sX99+Ef8$hx{Ua+bVThygY^S)!Jlni^Ix_-)|R z5pPLbP2otnXYIB--ojN9=u=5sQBLT32SBUD?Jq4h?mLbEpUe=Az3LbF%a$dwl71%F zxC^x#@al;DeZ_$6t=VF*O4ckSJ(gZ0cXV`w5&H1aQ~(q&5D(&EmSrp2-d>XJHa#_! z67vjMA(2fQ?$!(x#z6n(0mFb?J_4?5p7n&L9a&_-aHqwU3}Kdl?6~(3EeDn}0-bAw zNaPIo4t0yw25a2;V4XCC_S9pQ8yRR&K-HV0kQ_|#<^$Jt$@2$4%uyt40|+oEbU2>Y zP-JUD2-=Y)T*O8zO)dh-51JYPr471)k0204FX?{+YqWx*A_1QpHz3y2`!(l05%ijM z`b?Y9==@y~Mx>}Pi2g%Fp*A zD)=c*&s46y$R7`Kwz*aO@ksijL~zGvYX>}BJ-QE@UdpexbjK#93ywi4o0qgy=sj{)$v{EwG(OTYj6Fvcsg_5hEHWO4u@Xi>F`tMiMl2#^gV8yKu~2snbI!$F<^P*@;c zne3F@j#{e82D-Kl3Tr5mt-lFoDlvgR#BOy+80Z{`Ie83a?*k}{*no}zpYRrB7>YXv zBbA)n(IVx=n?zzVG69;}pz6|rt!QPa_?oP&EH^jzz&|xfqW$`qoms9j)N7!gvjEW` zG*5z%i3db^K9t8mQD20l8XQ=(UqQSc6v{|^q&^b?q)mWl8L2_W+|OM>a7M>tVGR{t z3p6Q?5DTiVL2(gDEVkh!#<+ML0*LN;0MVwGuS&Su*VkD*f?*3&9->MREeS#mYG`W0 zy7LgEYOr?}E#Jp|A1$9PAiI|Ds=qS!NibVrb}HbcRjMM%x~cih>Yn*q&CfKUMz*EO&Ci#ezFXrjOs z<3@?oRwcRWGfv>1ffJs)M*Tq1Zl^W1Cp9KwR9%Kg1XP%7wEiy#V?K>b0Xh9-cHn}3 zwT$X$Wl(SbC4>!D9nQJs5rSUasn*I}5dw67lD4l5d9BiGa;owe64~APcc=&3c`ctt zq<}pe=dnu$aK1`z!mInBkdf;M{o6~U7p0Cfa6Ls&#nR$=SV}K?C}S5mFC;pd+ud4D zv8o#gUwKig+IplQ_pGTC`^yjd+%JAO4F3|$DB66E!jxwvnNSS;-+7a>2T=JZDvAyW z8j1_K6*#q^@6v+@b)c)8wg!TJ2W|Nvj=)#`ft7Nf>KUiIdN%E&M}bpQQ=&fc^z`)5 zd){Qv22OAY8W0vfe*CC9VELoy?aD4tFJB=I|NQy0s1O+tks%==Z1Nb!YuM;$&>;K! zz%qJfbVP9Q6G+RUcgkBEy79sivi+KYy*F$`;1a8EY!vxfY{L(I;3ck>HwtcYVm!4a zqMKyINPyvVB{s`5-7|Y{S|q4V#)urnI>gdUa)^@$enxiP={=cV?EX9K{wKoL#UIFf z(!()5_KPuUr;KXkQ6374)jC8qhK1M9vN^8+)xEDdCO5|8ksA0s_+1pxx|ok=${PRT zR$^qEo~(|tQv-vgiuQDqRA=mU{;J%KS0WC7vB~N|Ue#tMT;dzV|D5%po!X&~<&gh~ zgC#P?ihd%sZH}-AMX*QzL+U@h0Op%x^S>Q&Ytx%i*JMa*KF5j<>x}h|L!5#o`E29+ zA@;RiS0yi_=IcCICGro-)!|hM6puo>VMLoQp%cef+x;hN$&?%RSnm_pDR;{UcAWOs zI4=J}&it>`cdFH7Ux{UzuP=Y(aZrAKzS>k{kQ9y4P>EV*k$QXpDY2`SdTQFxu$+?^FgAI4EJ#iS zJ(}W(iGI#)C%F;ueXN=nqN#1|eG@NK zj?#CAzQnzp4i{tbUs4ZI9wExgqkGj9Awm{)SJ@_9tfLRHSRzfd$}&h<%%fR68a-yse zP648n(EO^WuLkY4SzI7!63u%PWVvNcUi+x=Cg;-+P_IoEW&#fynnEpSOLtW*{$9X9 z$JXy&UkFw?$`4V;mYU@SA(3#Fe7Y&4m6drR;qK|(toQfs_ZR7E8p@J}9gLv*i6q7< z$6|ht_($Ofq_O{Q<)Nm?}scO@7jmg85?FSQ`-OAytSI%$#g0T!KS zV}h5ixtp(CiTuk&Sk7r_IxtzIC6u_`Oxf?^ka{-7jGThNHNGe<>obv9X+5aL4@FcR zkHOLroj&Q!N^Q2+%+cJ{%h@fj9`vhMeH=F$yU?HRKBd|U!^)EFOp%~fAuIUIhR=NI>Se9z6>fksk*reE_QOS2e zD@bpTEANZn7tmHpOGa)S6})fMp#n{6iDTZNUwxOm?I%lc>v(>ekYqF?BF$xXP3mQ3 zih5?W>Z&XFUiM8ZYW>)+kbc<;7Wd-byyFj`r97vsm4xsOR6@c{;g8wdy3rL_#;8|uUgbrw(l3F@bUV)$K!%_(!uC`X$mA1 z0oiI(;2%@mg>4Y_Zr9aD9+m6dw#UcEN-#4=dsBK5nop$y zi;YFb_XQ{kq!TYVleP1s)s1FPptt=rOvzCiXM{=vdj|)LxfZ zd(8)Vw4s&=bs!@PB=Sa-kej#YI`y!<)cl zUNUa=T?zLE$tx%{6xhko(V`?6&f7t_;qz)G<`*i}H zZVq~rYjFtMGL2iPG!L?CHaR^8GAno3H_*z&lB;}j0cp^Aqx5Wpl~y&!9{ z+&p7{eDG*V$*<##*MXP$m7-RQM3_qk!!iFk#+yDwP;q#oLi#~p{HZXQ3z3lpFdu?* z!anhZ<`v`GyI~TIkQ=W4tOqC#sufCwX%3v#k5l`40NaD|6)ET{01^D!vyze$gzZB? z&yoKFfqIsLbY=&G5HPmnumq6yLjW*PK*S-9=YY(T07!voE3LHgp%+=9QJrw60zy6_ zZI}Vq!G$3#j~h(Q=z%|h0^IZjKru9g6iJo~3J$(l1LOlzivVfhM^8@{Kz~TjMIZtN zyJH5Mc>ZS=wpND)@8->?NEfE@QdXqI07z$8GiW)GV*>jQSu}S1Cjc|Z<)Q7(niMKK zKtE}OfptFIK@3SfmTX|c1LWxk4L&}gW7h$A1$P(S{VO@Zcz`z_NuOO@To6hV+Y#gr zg>WZh+{1!P%`>)i(vo*gjQS)E{codZgg0II6a8Yeh`m32 zS8V2s3gXMJXmt07FM*lnS#27*_(;V?-=!hE$H;^Hc*YK-pQ$*4?VyWzA`m&qi~^+c zL|9CWm%}Iow5J?^*~oMRX!V1n*+5xX8tc)*JpqRw@D8v7!6#ox@ELJ*BONNp-~G7& z>l>COl;X6)XT+*OXiD(X0-635=BYr(L-6d@vv%=O?!MuOMjXJYGO^#_%~RtXKfy$W zXqZ(5FK+@H;iVdAm@)$DjWx+*X=!Y5%cjVu%D_yggrOC%^iwc0c7hL8nRo>TsQ~hj zhL)4SAR`4RP&)v=ZGX_Jf%pJy$O?X5a4{f6Wpr02u@ zfbx}m5YCWKTh0Lr&s`oKWGu-G7`p+D&QTnOLEP9N;Ekk6lM;M89` zgvT`0L4B8Cl2?=$AMNwbzzy)baN(aV_lMpJF4-dwXdG&I`O2s9rR4L5TjlXZs|t&& zV?m6#?RTwvZ~jNb8-EPoemq$H-KGer$yaNjr_{NBc5A+kRJpJNh|yZ4!6G7Us4^}> zGtU_ab~eU(Vl*L$tPJ=BytjP&<5tj?lcQ7zQxj?ykoJMl+#WqyP8^y5A}!S5=eWAM zx*2Na;Xt8>K=)J1h&E&kgDG_my!a^z38(cSFmBxeiQ_$JFbFh*5+P_23N|uuWupKs z6)0y~W7Pm>1)1_JXf?7~~uU^Lonz{n=YV7F1R#a5P zf28gQv;s7ug&Ai|P$vSsHT^DP=!N&J1q7L##{+9^rnvef)7lx4R$xyiIRf(t?|?*) zL{a~X32+2doF1-ZC>MSL6$kp4Ztm{R!)YOssn7>?N%#!PRJ-8F*_BUxl=5fi4VVIS znoX#!Hfa2A@3v`Szoye^bP)qDRzJ~dMB)GdcCwMD3lnG0trzYqSe@LMt+;u_96r?L z3C=S2A9borxus>n+EIE#DiVe@FxG!9^p9yPS%)qQBtczD=FAE+LCGD!Y_W7W&LD!R)7D46uR4h zaSC`USoTl6;Dw{?GQe+K27Y7whJBB(&w0`ynpALOV_>?9 z#pa9%%*X;psW6?K$ND}D(3qP$#1#hLW$#8Nzy4D&BG@}R-XI})7-qmmD!oXoH_hvtl_a(0J+hb+%K zFB0JA=Z^&s3PMF73oRb0bbzzo(C`6V8_>ClZ*vmm>ji*VcLDFBW#Ag6_P*#XL+l54 z?B*oKR)han*j{!c$N9JH#9um=N_n&o6BELRwqv=1Yyv>})|N zELzS-1*8{C3TBP4BJW)IKU(%;`oXdXC-3tZbGc>Q$7|F6V4iH5e_L^4zK1Qm*5imG zt5H(_>47Z?E*A5Z@vxYBUOFzD8U;mzyNkccwq%=TZV-T49~H`wp5Q}08UPNu*2&>; z7YExlNfC9LCEiti1CYBKAYzrufv+_D&5yjx&y{&-QS=J%+rft?)yzXL6ZiVXSw9q% zp#b%?=&-~%qglY)rxij~!n5fllRo2bML+!x!t*5W{J~oJAeA*$*Cfl#d#N+Z%3yKm z<$~@s9sq!{;5oB!afeW#vr7N2T?2z*kL{Ja&doeO^UW&NWDtsA+I9NyB>B$AGm6r2 z0dzw)qBZwRnb1JK$FQ)!f4G{?gzhV=n?$nZ!;8lGR#Cl7-)Fv;YA*+C^1`!U?Cam= zuzUAZx>EG*iOrL-rZUFwmpkHtJP2xf1Cq(k`mboDhc0+EKEsiO$Om4O#yW~sVW!`w z?Faq);7s@pGoD_mrvg!)xrYP{UH0hTTQ%09qla$13iR9_{PQYDATYi36RCX&knrLAzmYw?q4fUZcLh ze}n$aQ-H%bkN!;Ej%fQXFoA$yWOapbAQ1iTcGdA+qzV~0Qz2)1N3veapVX{L{FIhc zb}L|`K0lp-Rzsd=a+|pMo5HKx^T8#ixjVxf0p*+P24m*6wC|XdV+F4j;_rVZQw84X z)f*f@L~=(9FY)KD-(qgGJ$dT%V*D#5eh8jNNYr>@`6e+7y4vI$l#&z;7<8Hnj;TQ@PL_AEcqJd}}_AAQ(@}n70``hCMH6HMS zvt#FIw;Kq2&=Ry2_h8z^HZsCVzl#ixCdfp!hndERmEAyr1|{t`^bJiUe7wf~w)-xf z9r$cMppXG?Ftf$BYb3NNz$O+NdBdpz6jGQwI|z9&?;;Y8dWkiJ{Dbj9Egc=;=MRPw zD^SdL*Txiop1oWI5wmv#2qf_KL$(Lq??QeCl5jtP+yjorowczDu!4-l{tF;g;8NQY zqDn~FVOba@0;k^CxBJ6ev;7^0FPxVDkP`_3)$`W*c=O7dkF41dVGu)*TIBAfgn@%Z zS?-|({3UKum&!LkK5cI7~5(6AdLA zyJ2zehEt{qFS=Ts1TBHhq2?IOGLU{DCGU`_^yCt1wnZTI!Z4`@8oVz+C*GVk-JQdg z?0o1Pb_$K2t@c)5hd_iN2o!)Kq56^C9$%#f%1<41^vAlML6kfE{GVh{xArKBqg3?M zjmYgK`^8E{WyI?FNkFzzwC0b+%Q@X3h`-6Ry4OUa?PORX4nJ30eC;JITVxzAm)NK( zUu~5Hq(Y-{)qV+{zYY+r}Gn?T2B6lF8waZ2qD{5!>P7FN;@%X0k<|L@^47$26{gjgcmuPA^ zt>nH|_GCx$QGFNB&Og0C9w|_x77-Oil58kbfyqH{pjt>Oj&CHF5Cvs=_aL!ufN6tZ zMuHzFiVbbFL-7&;GBgb~Bq5(Y6TL!)=K6T)<37pOtR|!lLY~f5(1{vHMk1j`1uFlM ziWw9#%?Uw!5S1HSTYVr;Wpz3JyHX}{0@xCYcNS|g$md{5%tP&80$6S`tD5%w*oXBr zOkik&TDk4?(vlC<41qyMA0DSIcO-%yp^*MT*pJ3jq)Ze{lALi43xsf$;HNPzz*-0Q z-W*a^2f+w(To4RI!DRXHxy_dnP9^kxNu+AMJRn-XSqt^T|$R3h-Q)3oHT%{Qjg zyVq#h!DM|Hy4`CW*;_z$wdud{dhFgMfS>RIVoAc(6d*x{Ck*wDoAQM z%I&w}1>YMj9>!P>Ni3~O*oYt5nr#2RA!AV|P8TmLbSwl!@bmBNI1FRWN(M(46SCsV zA{DVCZb#@Q505H@zK9BU8w<-V8MKn)Dc9l{9H!>CduhG?B{Y6n`85N+Ul@9*vPwca zi(oXUPDR4`QUhTzr#lRQQxZ1!lIz{df#8#?GwEWSMvUK5G-A_9U&~4!6LJ2>UeD)< z=oT(9`CmwUl>oUkoyJeM`CzUT06%CE*#99h> z2;zjAq-M?Uva62#;Bfg2#X2Cis;m1~zZzKC1rJ>}cp0IhiZnet3J8A?_Q4PE%{b?{ z9^6xcFg_Hi)5KODDv!#|0wPRYT3Q6md^c|NF1M!+0yPjE842wV%<~sv>;RMn)lE)T zw??YM6@k?XgvzLlYBglOtL>^%!a>ZdI@gGMy#AqPCgr5INCnRr7q0I;`ml_X=&SLj zf-AVjJ|(QSW=Rmml^(veKK&>xV5#d69j1YETr-ck`90>fS6%z28E1P3FXVz_8IU_pajo&*|(t&WG4b6_Sh%kX#am`SOAUR3;tC zFi=Rf_=k~^_W0wtxW8N?HJ2rkA+Fg2OqY8IO&?qN*wATV+rv8kFe6m($7>*soT|RE zFR2_>e~LXzsEd1+OK@Mq3;(VgQC zZ$21GIYZY4;K8*?`?5339+JuCpgp031{>cV$0IzJP3H2gg;1*auS}=cf03t6`saVG z>l16?&%^Xk_6>=qP5E(+jy(L{Hid!8kY;0egk;Kd3bZo8!;6qqM1;7|EOyI;b}|ys zWBuJBd(w<|6P5EtTBq4X)MpsO6)V#omhX{xJ}QPsY@aZMo-14F2N!-_`uf z)oeJ;L2*&M`eL!sU67D|<}Uw0DlP%RTR`s*ScWj65-O+P17^*K(GtxI#YteXgfAq# zw*pCl94p|{eglySyh1=X_4&wW?<--Rky3oN-acTz96Va5l>v`~jr(SkVXkIYT1BvS zs{jfJ9wxgk5R0xLM(ZWZgL=PgfFnn9ROUtf>`4YG2oO@WegS1(XJ^hk_T<_He zD{bRT-@3F-BNLgQ3%6h18S8ShTodY#2tk1dl?GK!T248O#wJ> z{QegH)}7Y5Ej_{hHk~a!AcWfrDTgM$6mwW6Un?~_k<)}^52)jb1d%=+%dy_Hz2Ar3 zeE}l=Z0(f&q2Y1chMj3&Q!cvM=&TJ36=v#OYkY+sgwpAlkVUbSert3*k1s^!%o|0Q zrqO?Pbrp}9o+^VW&ti3$8SLoDTwvgRtk>TiNt?v8>f^w07%Ey?w4z@FY*7n>ST(!k zM(2M5Ni3%a5z?5U8NPCVmmxzy*x34W{}#;vI{_IWiEp$`Vw3VYVUPSy3A>Nl*gtms z-~WE(z+?T7`ita&-@e(#m}YI&b2F|-46^v=uPAv9g8BJTSX=1$z+>RY%LbN-MwoC2w)(6I!9ytrducVl7J{add?KjnC!T!+cta8PsaJu8s zx3`-QR!wCMi(eSqV%&DM#*Nfv9oetUPUTSH*)yi;9)CQ5ArLl71;h}`{M%d;aMz0W z{_X9$TErg2>vSR4{BxOx3wa+C>bIba_v|CS582i{WUhF-T_@gO2XCTwNO>Q-Iy1zL zUnJ5veho*99o+$7cYCRxBMHz@SfjHj_7s56mMW+ zaOdrnHzWqZ74w|d^<9c0Zi#*MG$}heamB^kfM%jgczmQ(C%i+7A#ldrA*Wn54e|a4 z(TNKMdwY9RU9~OvtdZ|G{(3vDWD_k^)#j$CF~KuGtOwQ8WY_Rj#d~^Pyny_H8fQ)}HHlE!FypGw2nwZycplrU|Y5rWkpR zpdB5nsRPPRfy`NKKh>6ydbp?VdD~UJUndq@KkhKkh97Ot-M&FgB(-)JaQk7|r=Prn z;mY`MeUZUzh0@UXAh^9`*CmSc6sNf;qBV}$tFBRTmW%)P!|}d=?4I4^uyE>;l00KZq9a4EX}&A@|= zcjm&l@K$)-cdiA)TTzMc`Eft|+xO_^`cgu+i=ddx=4AWXT!gu!GZ!CW1Ld1^Gd_~K z>0SR}M`PP!Vq=blcYnKrQ{IoP>Z8S3;RSk{FUnMj2KPlDJ6`a6dnvljqXT{jD}rKC z;>`U9ypiNX5}irAvp92EjEQ5dPgx~oeN5h$(NJ@*82Bm|f(#h6VtI{(wq%;7wsb>Y z%Ly$`ba0K6k(fSm-YpcyaFj0(pdTK%_SiZh;(ZgPj%<8vuXaJZK^PXs;nf%(9I7Jz zKMmE_ag&QV*r4Nx?~yVuY=`e(W$-v^a2PfNKW>k-C}qx(pw<_w<(D3*}t{fn*CbTrQ>$P zlc(?i#QVBP$R52S|9h*+{FX7tYG;05|Bv;9q}}bjv+XX_Ej5eSS62Fq%!}{4-e8F_ zW21RB8x)hzbcaq{{ahR9O9Xm{_e|A;gw!y?7Y zZA^iaA$YeEmb@BUj@2~Rb&I-Rq?C@dhpAbK1v_15%uAckZgaYP-dfoZy@za{3iA8U z;K>Ft57Ve#8C$nZ4e#X`EYeLkO*9_(`=*v>D*DpQKXvSW0hrZ<%`dSQkv#nPOeMONhBb75H(+=WOyp}6y2lnVI; zA9NTJJ}e{TviKMix&3>*__8+FlM!~ish{oWnmK84RoaDIl>*oBvl?P!jZBEw*OHEE zRK9o$sqa#_uXWsdRDHoMtGE~sdk5|FYmS?;>R$^|A-F)Uft%)kH7hf7ERvHs^R>SPD8lz+2 zYUA{toJ&2w0`KGIxDE)L-w$h2gO_Ko?pr^%ocAAeYSGAXpP)R-*qf+#qEmLvv}wPF zuO`wJ#6ReSZ06E0Y!t}zn_%y$6;Lj&{s|k%!oH$}#VUvQrfcysPfqLt=TL~6y2r2S zr1g=F>$n&f2*`*MOxNsc_39PngtntsmUwc0jb_)c)X%qReP5$`pW>K~bKThN+q9kR zH2nig*oYm`gMH5CcTk;vQV_(r_z6q$w*K6X2zkNQG0M?D^0UV#aJI9RHu1aP?4wh^ z$5tN($hZbt(xg`mTvu$yxm{wagiBb1>*s6NEtA8W+1EyS|8$ktIg%Kg$v8^)JQmDq zCqW$&(>t9R0Z+25yX@G7~gv#Y{MK2T%mL1hGd&pI^Pu-L-IJO{>~?lQWVr`s}iA z);Gsf0vG;jvN72B-_xZX<^E0cIpYA16IavDTe1Ei*{|t+a zC84+wbV@eUa|L@P-o4L3>fx=1$e^&d8!JtmS}y}S)^l9q{HhnOU1VrZJK5xHeVE;# zQEC5DlPykDAG5X-pJ)H{0!rJSAay9Bzgguui>bG@z?0a_82f{WmnRkyztLmf%`5(0 zWc+$qUo~?3c)#8~-`8B_W7r(TRszTR;(axpmqc*_Bkb9<2D)H9=q#*} z*LsT*^4Y``tz}&jtec3++Gu9#XfM@Tv84Q z9DnyDm81IctYnv#ofDESm=0W|;Exq|R;@Co;3pMlcdPhu*?N7iy5?P7 z?37k44)Vn9wam16i^eBUNsc;hN|m27=IOVKo6zVtk+_qlqHaosR3(}Pj>w)zlc2MOi)nkPwFngCKo&T(M8xK5{kbhwwos9jzYvN zO87PHo;w_g1sBCio#iSY29PDZZGDj8;B@otN`g3hQYf;W$QjOdk{_Y(2NSo^# zhYAG=EcDU_Qnmf37dx;+vno9DUbXhM=^8rNoi$RzdBJkEye(Flf@fIlq^y~)Y(|+$ zdep8`sL`KXYK`MwdEe!m9~n8KNfif&jj%^xo;GZg4M*=w+T^tVbtS=kicaml%6J;G zt2Z$*(hg^3lbsjY;T3oe8x=>c0wI!vV9~WX(u9lAaoD;>r{-W~_!=I&FylRTDEC&YE!NpvJ)qrX%*#M9v5t_5}9!^wa|Abs)2!df%@X zIkV8-vsNd9{IR)T$#<8WXFkzqJ!5D+a%-NwkN}NuDf@(lo8Azi=RQX%E(~K@Xxy)_ z6>`Mgs0~pRHXS(b*F!#uWN=CmvL}v|lZr#0%APqH9=IDSo!t_PJ9so|XGTHP?fnK` zSNiU)@OdT-$E5YZ`rYvXPhQ?YB+uN@eZBTHllC`v0de#%q1ta@I=8|vc3auwLN4*x z3hnj$D@e*9q$k1p3`<% zQQa!VxQYslulpXr>v=@^h-l1gwPJI8CS;E~{UJ$Z)?!vJIwo@)f6Wd_`=z_^7#FJ; z8tR2C)A5xly*!m=uS1&KKk%u3wsGZ=-jpz@h@?W$3pW2&IJdP2)r`0R1f)raKbE9S zop=}bL-6!cR>n?X2ojk*{ss2nq|M}bIKnCH_AY8o-?gbe7D#!6>UKT8-mGDduCZjz zcS?cei167_zjw1VIiRKe}@diO=~o|7=fO-ctiVepKN@(ytd*;u;m8yxw1j#}?OtdG`!08_81 z8jxK=qAyCJLxi(qH8-*`W$x4(r!L(V9`Sp)@~WGr6YE;}M2(`VOmh||A>Zr3`q^ZI zS+mT=*k_O>7~_Z;a{F|w!}daz&HjLosmk;3U=F^-tNg{H?F4ckO1r^#WxgqI8ayE= z6qq`BY!R>53ff&or5JSY4X(6T?f0R4On%^-8*XFXVyHy#V}rBH-Jmz`KxDyXu4@xN z6m@;sG;y&-{ZqKQ(?VLaUQ~gJYuNIU;D_vzW9yE)o4}~ z4W`e%dL%KLrQM~srS}L~Bq;lB$?r!4`*g~-q^PQyYsXd*y;a-T$J^mE=1xoLf=rfo z7OC^Cc?R~KX$l|0R=2e^G+4ztv?QRX* z#OOWmL)ra1E5xx$kbHLk!es<81XDRRk>DRMML<&2tympTS^d{+!F5X#QZ|w}teK#k z0ZuZU=|6{}#{3-r_v;?aSJrdKdB?Ha>KulV8rL9?Cq!-6jP)sw- z0jJ9tJMromts#ofawaCCk{uS3$0N z-QxVOTB^) z=5Kd~NpSE5cEXaBAKt2&?j+a_(1+;k)$G+FFzB}8Gl~0{??w~b48+Nh<&-y?4d1xN zmjZ<)_D`gmyqj})ckBcq6z}}EQ>{3KqwUr=*GMFE5g6ZO{AglVDlch3Y&4els`y3G za#8=*{hO63KBF{Ff;A=bgT}T;+#b(9pB_c}JvoOm{eHW&ys)0mzk*);SLpO#zh~P- z01zYhruk=cvpbQx`WrPIanCe3A+Nuidn%{5v=d5pN9G|36&cRVAA27$N_$I8xpJod zLE(fnvgrEv@T^p;9->DRXYBda^}fJ-r?E_N^6QJ|`yq|cQK~IQmL)-3@8^p2ke*z_ z&m_@jK1qAiUr50^X2|N9xHGs$$uk_7{g$XS|Bm0V<+AsV4c^j9Q;6bY;BaDo?yRrU zQEX(UIZ*>G64a)UlOGn6ef*%1F9nDr>-Aq!5GLO`o|N`4VE%BJH6t`OotiW1V(z!3 zD2%K+L}NQ%PyLeOgBM7>uB19w(Vu;Wy z)fAQna-R_#zVRup-YJKh1R>ZSWK-~T*Z=9hn@n$3lw!I|GEuK7&ktDYQ-oSPTQYs` zn7HB^j@t|Qlu_FXncCyqC3%*p-vT*k8se7;MGP+Criky?s$mtzH>^BLF>iga8ZhU2 z@v<@z_wK^>%acu7bKQBGLjN|l)))n!`ZenGifdl9^@hu4Tn&JI-ANfV^O^bBy!%!X z?GLaiZJDZ`nbH2ju+wUq1r{!tuhA@KA9A*(;YuIPX1Z@^l?BEJ{3sF0Z0RTpRx(zy z)T3@00M}fsdG}QdZrBA(8j?fil3j&wXUi!1(BY-jLpI@|(=|wL{wzd1FL_ICTa4ib zJc5PpJkzkXpFNwOYv+x;pZXWNRrWc)W+}iT0Y?qC&0^zss~f-hX4 z=Cs84h<;bsRBIw6>9!HR6O>NC3WZLZ2M!2?Pk$A146MR_T#y|-zU;9>HX^p?XLxKC zu1SQRIi_B8SpIH=i%)%pIYqo}5c}4n^0?08;u~ulUp0FqAU}^=V-08xu=t+uku^#> zoD-y2>7DWE0SZ3a4rw}d|1TN78(LfhHS6Ybj=KyfteEeV=F42DtoGFx+0_3vtqN9Q zpENZ3wRi0@W;W0dI9k*9;AB=_Tx>7;g<;FY$L5w@5(B)amgK>)U#iiWEqr#^VD68N zC|~P_-FjGN*lQ%xJR!(L^1Inv^mmpsW_jC(>?HS!5ls1biq_{VS1C^TKb9#2J79m( z2-lGaFoga($%YaZ8(A&e%$!1OEX$zPTh6$Oi?B>DhP-2>Wu7QB`)1^UN1U>jIpn>! zuNg&?sdBSA;*?vmw`?!cQwWkm2={*$?z||l58EwW%^dThryn|0|0+kI50+^6g zjSp?3wiL7)D$S2)@gTpd)3YJ@2KWc~rhC0Z zVFi^w;*jT)9IeTEi`Ch0T@$+;G8_4u0JktM>D1N5Z%E@KESx56BRDdyBj-GP=9oAv z)z?0gnL(7v5LOvA@N@rMhuyAh<2Lg*&N%dt@VRn|EBArqa+W96S`fnMVpK zD66?Poh|^>i9N0C%-`dU`#=+sgFY;&Mr2W7s*4$#Dj@@Q-;;xY*RE+; zbk1987jCxC+s1ibw9G+bn!T%mSIU;Wf942rn8KhXEk+DJg^Y>I`)|oZno;OqI~4%O z0C|-2NA~QRq5{rosU#eueKu1J5(>w7aI=E>ojDMe%B_B7wm*7Be$Qnc=!z>bJe_r3 zr$m76Ob6Z>x*khEQ8N+m(`AuNm3N-h7d3Wpfi>82|3RYmKFzyi)|Pbj&{190%rTDV zmIH>@?r31U;raHInqj`a{VJp?zG7Jf3j+gk*2SF|)Md;ps>GaIUbG)#emd-sOh`kR z%Gi2sy?TI#(8F(+*dJ>(2=PVzr7$K!?^B$V1n~i7k14_Rx6kYik!N9wH0;^d`09&p zN>oTR1~Ay5DEA&#N6OHd*DB#atNfT$NO;F1mVHWBQ|DY9o8lfT9kbpY@>I?c*k9-> zhxZctB1Bv|Sm2YIJF?tY%5j%B%c8|6s*8=)mnL1|uHe*d%m1nHOQN&gO67|EH|_B% zD@q`v3nrpj>&3pO`>WzlK?m2)%|5`a8ZSn^TSdR-2x-rYgbhYBJQ34Bn5)kUT$Ehd zmL3ZBO#jL9(JhAZ&L|r8wK85VR{ysNxdC6pMfpk(AW66$D2g06u%;t*`v{GB^wxMu zOY;rC*#1%jLMi(;YJ_z`vq>8@*BKSq7r}1XclF>C{huy1iK9-=KV2%H>erI9Pf<*p zxv;r>>gVruzl(ure;7Cr{FueIW0YBJUnYmECJha!Cfn5EuLh|F#MBkm^DD66{S514z$d{`;_qN31! z{?Ls73jfC&e)K?iLjm%yo%l0B*S+FS?b7jaF?@FHH1bxmF7c{du`N<^P3H9UvWQdP zUwBeQ?lmR}G}{f#%Q+)!4W8&XDXpK4CwD0F?H%OuszF#?b~$ivwD-bMD7-%) z+{`uJC$yQjl3B$a#yh0TmFWH7oUqRJtzF+@0-CxdPGIcEh>Ytm ziK7!Ly~UUi&s|wLi&>1!T`3&?U6b?<=Gp_F9UH5y-LtO?+8Q;nv0@JiG|y%ypRMWn zh}E?k;lu`QMXi}~4jZ>0{E4TQ?s6)A(&YPQMmy$>w4HlHs1Pez^SY%9JAus?n)w~Q z>wzCLnn78jB$K7TbRi^op7VLdDi7omK!ZvEi?hJ@r?fvH!lN}nSSB zqBBXQOLpf!@5iQkh+w`bn|sH6onF4IrL^>RMc`%|*9bFyP@2$xGPFR6hlLqsPTs&o z|D8D|*}3$ne}r|hSEV>mi3vr8uS5pm^sV%W56&Lo-e-p7vbK%J6wbdc$*==UkjtxT zy*3$uCn*)p4Y)yUWiW!aqVUj(I@|C91VByDno24^mh%#DIrH^82r_DL1XX18Tia%V%Vj>}F(93^4-5qHloZ_&j zqW7JZ`LNC#J3g*S$)r$7>&NR7&V!h;cOyFCFS|?aSaFIMcWxysLyjqa!U$~&X2*XV zSd$K$#um#*#}(tV2!OId6TGl-N?7^|^S3}rpR#Y-KTO?>vn{v7NwP2{f96RT7y^N% zjynCyzBSD*^9-|cv1!S}&NiLqy7j%!oV?7JGe7|lw|f@-+lo7=HOu*q#6p3DC)&v% z#cI!cbsWCUM-5MX*qcPv<^Ap3mob)N_cyaxLrAspB8mQSL5y6{9i18FgWZ37AHAKd zyh?c^#r|MdN0I8ZES}Yh(P6+h?PRIgyrlB4M2OjuYSFR+Y&wy}35F7@Ey%G{Ofpq8 zQndG@0ZJJVtR8iqHLh>w{bki?Tx$Ea94BkORcI44S`eqiC45>zFUs&ZRw>Dj5>BCB z^;<`=Afrs2o(f*nY?vi+ohF2V4SiYF(QtGL|s9X<$E?*Jy@Lj-xylw8!aTvpC>ZV9k30RXJUI0VR=D5j5L% z=64e4idNp|!+EyK{PRJycxQWQ|LI?ioN|7IkkiX&g$y-B@d{PS9I4~sB&Y#8GLr9@ zNz-e?|A}+vmjZshLe}-U$+%!Lg3`W*s0h z9h|mmtVLSzE_>)>&WJDt-QPw`0<9_ zETOhqbc0&HvG&B}Ha6^;uT$I%6})l}NgCFz{o~MWqwoU#4=V2X8Z`KbJxLtA#G{=D z_zV5UTIxpVK-rpZ8E#DF7!g$p7UR3$^n=D*rG^YT zIu=*bH**m+d3NxarAhVO<+xQ7IbCmyQ=NUzvdog5`GB0tcZ2UFs+ntlV_Kg!R+}$! zn-@P(Fkq=q9ryog$pW&}Sk`NZezOdc&YI*CUfzX(~fTbllgZ8xmijR%K|x zrX%mD8V3jLYEhC(eCjouVmwToApXivoA}eDvQzyQtBiN5X6AUek@uSyI`zbbsJXQq4DrhzLc7@*?z%&N@H8ztPIte=_v;c zap~-{a7{5*6d*bLcgtCNu#g|*)4X41QWD&G3b;nr46^K=|SUM#Zf#LXD&TI=Q1dT z9eI7Qc5W;iQj_7ZnCFq{dj@KXZ70bGd5%W?Hsg8*StB48YW!<6*`@9o24Oxp2xAd@ zNtp<&4EL2CNwYFylAQgT2?Bac_i=^M(Edt@RtG3CfnllG8~w25VWiNh`~0x6El5;Y zF?>ItuZSDt(8AqBdk&@pK8MR+QiL|9D=#S%TX6jX(!yB!1*T1551fI=4vJF@_wS95 ziFbYd1$eDVkqydMr>xZA7z*rNMx1GC z{=HyvLXTeF413w_q+=#G2HaJ>;MpUo`n!nmdQS!vf%w;<$h7x3*|>^&_+PUcEG{uge>hwu(+3<6yL&0qDH<#){qK%_ zhhrHLwhh!L`(qKT7_KJ|*)E+@7&$=zDXln9Me!u3XVSrN1~QK?xN(@wT=!RAI{)b_ zdAH5fL5x%;#$Z44ZhMiV{6CTVv8qS^aV-=@Q3(|uiYnQxO`_LSU9cl$ly-lKkx}`?k}ad$gt)FjL1g{wmqb^xe-TiII4| z0oOd5v;;||8WX2O!!MPO`F5D5&NSg_=JRG8>hyJ?0tC<4WXx#TjmW^OlY547rc*dV z;^Um0g<;+4H`l|z_<)QoudXymZX;~L+^JTN()N%5t)WgR-Lzix^myKy)E-k`6d%NA zuyTs6zIlgJ?DfpmZf5`PJflfKpIs8Yx-CE4MifoDtFnO6_<=9VtB?mdAvT zvUQ5sgUn0DfoLVu*krSOu*ib=h30Oj*z(iD*$N7q!DOWma5OQaI~Vo%WK0L#`?C`N zeo6re@b_r32Y9~>CQtO_%3asx+U;Xt@8ph1MoXSLi2~3>+#T- z&ytG1XurK|^&-3w2m#Td_oVt9mo=vv@Q|~I4EtuF=#3MZM>*J2o#K9;%iMW^?{C`d z3|3+%-D&YS;#uM?i$@H)wgpM-1Dy-z!7AK=AR++Q@)Y_V2tLZ<3~^^Xzia=}kr>^mk4`)-_a7$1@`hWMyk{@A%E+0&esGCa{gk@d z<>=F>)o`Zhp@mIMYED<&iL?NXumSh1#uO56d%cW!3LNkR>$ahvb`H%=jtyqLLmIxJ z*ovc9w#2p_D#egR{&VBl+FQGs;4*6$u8sz~&3TH#W!zpxb%ejuNuog@tukIQrN+`oDRr zx=;jNajA}fem``S?We}cfW{__4oC?&#N_VG} zib#n_OE)MT0wVQ}wcYpgd_TVD{f_7Nw~u4rw_CWb>%7i$tu^NybIdWK{H1a+pm#M@ z=j>mS8s1(WtpBKIP++(R_qZtk7dMX)8W{e`S0F!mRem?Dyyf4|_#D1hTKDPen~tqe z^B}U(3YGsn9dsk``1nh>)w4X}liqP=ZvL-#3EG1Pr|?bn&J`)C&#!F%UeR+K5PDwU z{T$FSTjTAr)4TM=KhqBQp>*Kg{m(gKAW{qCTlUzfn)81@z^V{6pzIa4d*QfBtHEG< zubaF6zL$tSxy%^2c~gg0ulujh%@_UW1-vgSH$MBPe8e{@%lq(J?OE(k%&ptl*pNl1 zo}x_&AK1;CH$&p*GvVApej-?nP(&~garp0@m*s&UZeLWOnGBD6+0Ja8l8x|VeEshg zJCq*F9KC&l?aG;sP)KI_{nu*)T4p8Epk7nBJd+&le^z&6?V&UOylpP^&iw_|H>-9& zkG&L5{g>W%s-|A>pC96Xq}|D8`TNiR{Ab!$5Fs44G0m5_?idmF`#UYd52`cB0;fLQ z-4%P0|G__@xr|Eid)pgo!o`is|8e4Q&7F?=G}$8z&;QwOalm+D58%U|S8BDYC)3GAZM5Ug35uf5>TNC)_v)iAv_NKM za$zY5%KDi<^Tj6KuXY}@4qZ({*+!_l-x?eJYq`Wj7up6V7M6A_k2_y;m6qOcNn&2t z$Uy@J%%^Lo4fOPIUF=i$O@MTbD88{ z&NK1X`j3Xrd(8aCHtR_bUE+qFa;gy&=^CrY{lF=H0-w~Pbu?`E0s;blLn^pxi%=U; zuTp(yV^~2um;@ifWEl4J4GylJcyQSH&eNw)BYG`)iDHyqv8Bwf+(vu$QVkS32& zijR#=b;0(*KMqBpwa}e4Hs)GdTEc*G&y1r&;BF?Sh}_)Q5V*tyxlfBuD!p9vi`iMb zy+@4n#d^granlxeTkOA>`?R$8`{?YIx|BbE{@gS+z5$8(91XDk=+_DcZV9ZCI(>RI zi}xdF+E6@v^hm^IQ5fGxx-MSop_oCGTS>2_Y+Xi(5Ytxco=+R#2o7C@fCkA1$Y4N7 z$wfX98mSHOD(nrLi@V_Ja3=f;yctjG>+8!qiLng!mA{~Wcv4BJA!bg}$1vbi@8p$I zvxuIao-4`Sch<3JH>c?lJQs}YBe7d(76dl0euQDK&BgDJRYjcVGw|Kva*|LA+3H&b9aqLzzln@|(9xjtbv!mI>LBr7K#V}Np~BFpb1!3OO3RH@ zdT+6*^;A?;+}8?&Fz71*hnF22A0$ZdzH~2I$SVrRlf;MPR^G@AK2kINN#}?LFI~07 zf=R6)^hD$wc_>!?B(KO|r9!qU5`h8^yyZrD@S&fteOdSk(j(QNRmZ}T8Q%md53egK zWZ+nF?)vq8oeLdv38rI(3uY2Cv6oU|T*4I*la!PdG6!)1qJ|A&H9klm6Y-1G8>I=O z)eX?Oz74MhB5egZz|Z4z(+$Zk4Mv?Q*H>c_*#Oqm#E=$`IK*{%e!G)!e0ur|2p3sH zgr6VU1TA9wupJ4fyW>{x7BzKsg+K?W$5|c^mabbgE1VyQ*vrG>4Rg(p5WKE}S%pQe zMtxJ0^}=ZOG-Q@1v7LG*ZzU|Js(L`+;+2mN4Ful~adGuR2r;9jx&dDdf=a1hFI>5@ z9TuMK-4^uc?-QGny|}{(8o55W!^?e_miPa(pYy<(1o0G@Rd;=Rdm2dpKmWYsrjnit z`4d<)&xk#P?8D&Z&BvuIP9Dj(M~&+n8&^$aCg1iX8gMGtZu?z6^a+j_%{i8AuJbQl zUuT3uwkMA$mSq|@d5I_)r433qVOPe)$KSB9cm{dJI_Dp!_k`u@S>tnI571(&sScPQ*&eJ!dKUW3Oofqf66b}`N6w)#|!a? ziNMaqhbQ))aB>pG4Jle`ExOnus0kaI{=>^Xhkr-A{$akK@6 z;UjGTksQdnsLtpK20Fl*0R|U)Fnqoa`zAe(?$mnt%Aa~H$-iO$6H!hG)qeRRi=l5y zdbq2e^J02?z4##w?%>of{oZ3BZ+Vx#;$m2GTn4B9QvVF|wPZB}qF zvz(lqo1Oq)cuh>OF$|LrzSsa6dAOB)Sr{+6=F-G4JuyLK^@s<1upFFl_H%M>jNA!} zfN&@c!kWkenr3iOPtDFIzR0l1X&nl{VOpDKZw~zt;xQjcqo5rFb&6H~ZdaO;G&A$h>oGAi!&?tZs_}+Sv$M0@Y8lW! z*@kbnTgZ%w*lFwX`?cojLo^36D*cJs9kt4Dox1LIS;X<9&Das79_5i3a zP9d2$S~?U-?k_wny0G8hTnU#_3#R`2Bo=ooF0SSMw1uCZJ2uPYT)UgzFDlij@H={+ z;4c;p$Dnm@=cMO*1rmRP2KoYmziY zM-A?MIFYVj1!ILAWm*P?xTS=q;Uf&5kdVK`#T96z^rGu5lveQs^%j3m-g0s}iWCDb z3z-yOJU4FG&<$Uk8xUn6f^kin_J-lv6;s;_CO) zmv>=z0r#J{s?h^j&}3D+D$<;%$xh(@_T0};PvORE8mgwd>)>j@24i?c8V@{fXce7? z8Y%LWy25AMcJtqd-?*|9Q8#g(Z8lJzw@MP?jC$9r7#R`qDJ$mVO?K?^U3~G}d`e0* zL&K@*={H7OGT|Th41Q0~{QWewbq)l)^=z%yRJ0IUO=@$nlVb-ml>42{< z>@>>_wZ~7z#rIxba{=RfJ@2)`gv_5c;p>Ru1vVzskCNItga)9^^y%wYFXcqFW@XB6 z5YelxttAN=+3Zl^i-5f_>|E|a8*=L&3Fp&y_P0i~X7^xO+x+-;2PITbSJ(T;+u5KU zny0k41_Cf}At63Rkns5oY49Hn@pOo`jV%y(B`RKU^nhe_oHFl!?jY?ycMvrby{D9E z-+2eU3vt{_>#X|I4lgOOe)3dd(K%9+6SqmgU%05R0fW$6$6{Y=%joWR2* z{&K|P3`XBjNxTQQG1%`EBh@f$h}#7Vo2)#_UCI5Uv#`Ukg6I}b`VyjFEbe#=vWXh+ zY&Jyhq(H1AmXmLxiUi@bP{^T8!>6QBTEs?ZJb!vC@{A-KDp7L!VzK^advU@i zM-N(!Vt;;w=g%~%lYb$EG7S+|q5=!2nJ+LFkM2MC6jG@0&ZwCxgGKx+5*Y-HABKms z!S&@j)UJ>V?S^m`4hwn#qn&U+Qs%PKykuKSd0{LPXEs);6rvPK|05Nq$-Ba4p}e|! zu-PD#jv(%^2?^0f?i95jTl2=SE=o;O59a8a5QD+TN0_1| zLdTl|F&NXGb&TfuC$SN60^~1@Ic{orJg&X#1yyeZ#Lh*Q&U@A|7EYTt|(Db3(52v@Khd?CVoVJfOD{i4|!BfC7R~0k{gBagVSz zU{G`b&Sh$uM%_Ptlo3f_NPMAUOBvk?3ppa}1_fB-nSd5ZgwY{N>BH*|R%pKA?M%sUZ8Zy6_D-8)-j9t%6sneon0a&z9V z-bNlCu54m%j+oWJ26da;V5n;d@si6lR>3#fuzvmf_V!?uh}BU-?r?4M2?(fwD5OdJ zzlTuIwhPe}1A32(;P9k>1g3gOk&-S7EF|uvqqByA9Tw<@&6^YWMXX_x_4DV?HEY)@ zpC8*yT(jU22M-h>0fuN<+fq15cGt%${QhgNuB4*XJTBQX=>OJEqM=rM&%GM zJ8)YRE_N34Q+lUPor=rPwzje&=6AsO;GWo`+_@c(3@6I!l(yA9b1$uzH%AvPu6J8| z`g1p}>g~%)Bw+Pa5A?m<^W159^D?s|4Rv#6mfGTjw%>f~_QhQ{H+OBn!meHZNC7f= ztva58f$EWU@n(v)rAO#DH)$?yfiX&6MZQF~Omv-+u;jXR>kwVFmFzHJM`Ve!N|Z-N zMv__ws^2#^&p({H+3pe0w#m%QOyFJef9`X2OwYucf6pUwC~@w)v;V*U^9mbc!N2l3{wp56}v9z-K2u=5_I4P7OhhR6--rkOV z%yH-tl9%(Xjl(m-qN3qV!S9VeC4J1?Z0!otGevP{*1nHaQc{FD5y-}h9Z97Ga(PtdgGJFUu3Xq+EJ zWJd+L>Km4AAWM}E8?J7Cs`4-;>!`PIyFgtny=Mo7%BsL&hs~w_1Qt$;y4RXF%8-_NNnw! zK0aPqOJ4pimaBlkt`rX`$H@{pBqf{q6lEapjhs~jdiF2M&ma&V58g_V4jT((%YY}~ z#R!*4S-{a5H+-d~rT5|FPf6i3bxmP9&G7(vIQCIQbo35d+J`kaxwGxhBJEXfqSpRB z(G7#p$7BcZJN>Y$yZgG*;r}cj@6%Cu=$l%y&8rcpO7S~Mevwg8#4{Ps<|e`?>_v%s zo!V{e%S83;gUA_B3-|Q*m%xB3({KhVif@rid9a8xNJ>fu95Xz1;sgc!r4t(mq{t)3-U;lu z_Mg=fOg4tu6&OXIKY#wcE(Cgx1nSwup7%>&%r9(X*38kYo`aAM=jJ@)p_PNX^2rjNDZ47vOuVatzMLx;(E z={(b*;_K`CU71*y@*^Q1y(010H5#ttKL7ZKWhMSm09>Rq-cf)R^CCF-qNQc3=?eyU z2(d{@c4p;#PSPrnQC3#=^G5V;8M8WV_A66C<|;F>SH>f6)h~)yFBm}N&vw>KF4g5% zy2V^6VZ8x4(QUFx)cbz^+@LD)eypP)5GgOogfNEH9zt4`uyPoB~eD_ zQA6g(PU>SESlA};5yx`N%1d*ew}J)NWBlg78tUAtZcx{T;{KgRx#+s>%*>wf6Tr0p z4LIsDiQ0J}Rktc=@X$&wZD^PgTH)io?}qc>sP=mb$Jr4>bt=_D`h)xTTfmUFHLkPD zGe{v>s{lS2)DT`zOYB)$Dq1N;()vbx>`d4S5FuJ#jWQfF6u-w^SKJ{BkGeC}aDMQp z{g}q7)2E+!c<2HQ6w05tmq=1w2(Y%&HmM>7OQf|;xt(#d=A+$9Myv4T_R#C8UW^3; zaOY5_{0@Mn6iYNA=>`(4l7B3)^xu9C#u{+3yAMDSAciF10BlzcSf-=)L%I<;x@lsfc$>PZkXhSzqgG|W zJ+Vsh{#nc{EM71Zh7CmGROOA=sN`yp>&N%CuDy2$=c~oyZ_C6lot>SW)Jp!Pv8cX= za+~g#>#_<7sZ6nLuw0j6-Wh^S$MA!ZI#Ro6Y&n!L)+qj4hdN6ms=WzMbG~o?agW14Hx_?G`eT4AH{@8m z+fopDeAKXSeTghBEEFe!4;2vA-T>+|d?hoN@ z9cxTvggXe(-RDq0rG~C91a80MK0Tn2SE^v|O!62#bRbgEbG4XW?kkhmRr>MU+_S2a zWtA3Gu*=0?Rp}#zHC8|HsZ$vnA4ht9qBYI=IZwrx!=hmZ2} z3q!dbh8-wKO*3>~BRhvhAk}-gjdD51!jT)RT9$F<2LI~}j%+(SyJLp65zf;_Ff*|1 z{z#>vp^;JJ3zf$pQTwgu&Ygn~C?MoMAj3KD-a$kD3lwB?Veg7>g0f~^%)H2J*@LEW z9b_Pzq~%BwQ~C!74Q9qY%f5W+>nU-^>y%rv<(~pnd0Y1rZgRD>hYm4DUR6_jD*qJG z0F~jL586xH6W~pW>a}NZP-S0?Ru4uwS5wUs|~ z6ia_*!V!Yi3jJ_bpc%)%+gGc)53A3Bu6SzT84twmYz zUG#BM`=D6^!&f;jcTZ0+&hEm2WVOGu3I3Mk9Z;dIO}Kg#+v)82^N;=8ilPR6VX`yR z28{c$r)R^Ec?r^_pFlN`UuKxL`ge6{Biifw-7rG2bj;-Yvp+M#b#G3tMuh(etm-3x zg^a`5r~-OQ^ zI_x50*JUxtp2KHV>sB`v&-%+Q-RmNE9xnJrgG7m(2ClBIDD3Xm+^k;}ko9MFv=WEX z#Wi;6D0}b_oEiuFjQZA#%JDgbL4D z?O8MeFhbB>L{=*#=M;rYv+B4>rKo2qD__RKAmw3SpDqP3ELnI_Vr{MFJ{bsBmn3r%8QFkiPf&FsPb!0%<;|v~;KoP)jR@#pqCcv?8R1QArd|P3 z#?Jx+E3K==&lwpF@m!*UG;M8CH}SZ(u{j3YAfippeKqaOLZuPV^27NPs{qQT{5<)% z$UDuM7l#H(CJ=pj%7Or>!xtMB1VP+Tio)iqn0Ug#9)`fp(9H(yZny->#O?fvkDK6* zrOL%sjpc$IerhN_dDZ23Wgg`ujdGl)iBsY2X2dIrqa^IC`wtinp#z8SwE@RsZeHFr z+*0uthui9Jh7ZXG2|tI|t2NHpjT<)t#T7=Iji5tr2fo!8xw^iy`FRT9M{{#?hDoyz z(sCS4nt%3YBTJ3n^3&`Y8vI+u|&SKVvSc^~~7o+VjPwz#1VCdjps}+|KX7 zi<_)`w6iC0TC6OOub^$tVQ=G(ll2HP6^VtBqc||WXBh5)3VDjDaw6mHj;8cmlRCs0 z9DEDulP4+RYDC~m_y(=EK+lwDg`+8T78?*vFr=arNUmFctwC#J5Xc1qt@Cj`4a;|; zI9;$y zZsNkx!^Ff?50oQgnKBcU5>s`KNb)yO*^ls*AA(b}0?-U2Kr`gmPuPyOC>>yDHy&M? z4qZ8fS5w$xiOitI5r-q!Xr|M7+A~fiIRq8A0-`nN{{3fe;|x|?GEOdtLJFN}8tJQ+ zXP3B2@#M)nN)E39QD4aRoWl) z0F<1a^RvcDSCG^7k)T;y3`Ikn5?3oH?gjRPqTAHmTy|nyD)tQL2_(}OxLQ-L-&>`K zlh;?i$*Z@!`|TI~ba|QBjErNW9TzWMYML#0Zf%4!U{yVGev|lPO?hkkZ=+^0T3KFF z)?+*8r3jO-%Q74@C|@{*goOM81LGS)MeXIPf<;v{3mlb3+j12sIgcEJw7XN$+y z^KCsH3o-jcClWRDlsO`OwUSk^12c_wFfk<{U3qJ|Fh3uQ145;hcV&gN3DLkllqkm$ z+2OKaN)>~gIev;Ci#eG=#418wroDceH+kf?1@H&8W+-P9pWw<&`60vs`QyQOSv{B; zF%+3VCY3Za60k^+vj7EG;;{m-H$mByrGv%96pW@LQQqOMnRD zEDB|=y1dM@9ggyqkAs7699n#w930YkV1|aV$F2GvbMo>kqbjUGOQ$MCJa2K#2#>`G zb*l_V<=`W-Xc}G?4I~%L23XnIDI>X2yWM>I3WP>iR<12i7o)n^`Nm~wMkP^;BT~wP z{w>hzDBrXZa{~hdTl3GKJ{>x-5Tt92%wgkY#OU-yc^M7?)JRAKuB&t3|IHlqTPOC9 zUiUG-v<1;t&Pi}>@0;ygL&3trB6Li*06kUG>@Dm z`4)_m=;_a+hxuqLbJ(R&36u7Be#m_(nxwd?)~+Q^=EPRjYmcOyl+;5dtq{rM*m?y; zzWq{npN<ClYn9!%t)ZeK#@aVqm5^xc zhcDl*sI7KCzEMW{HvGy3o-;Z)<<6)$;5bMiF&5{ElZjio-T9F=sPe>JUVf!5Vy0A@ zVGC4pE=g(L^A8tqBXH*Pu!&Br5ViU7#xw42Yo6*l)ueD!ts?*r zi+DEd-!REIi8g}W)3d-wVm0%!OjAD>7x(&0()(4bYgeLa1eP7ZOC)D0JhZ3UPV%T_ z>;;C6gn|^B1mMSp&p4jKZ78YpX+5B!TL3Q5ztu+*q{TNb&{p(rZg#l$l$pJ&!1i6c zN{IV~pb0%(0Iv_#$2y~;Yx&iuel;~NZcxGh+jksSl`1M%`FrAKi#kM}}TE-Ul1 zt>(MYfFWiZ$Y0bX!6S)Ap@K%C#mds$j;W&iQ$j<@IjWBU9xU_R5DZKVc`-W8WqmZ+ z7%>oytDOGWIpD2k9w@@`|I2UGGH#v(FzGZq@)n>KseoY^C>Ou_LWh7GiQKSLfJc`n z0#jqDCuge=0y@&9z?J}xO?O{b>%BnST5=9ID-~(?AkG;GxbT6KMgI=F<(TF>8)D7V z^0Gt9lfm-OFT?n0AcRbCWdxv>(b6UYr_WE?d@1(hTJclBncg-Hn;(DWT3~I|l41DZ z20=2g{f50%V`EVrr5HEy#`Cw1ijKk}Pp>}a3IUa50|h80`&Y#+7J5+xi>r-eK#e6((Tn)>@rcFoF`OwW{fio3UIj^XXj3*^4$5aueTS`| z9KsQDDZj>QRK)T5YxOp<`VNkbc>!w$fYBtS4_3kBoE%}E^GB`v&U;9)A?X6z@e%|N zaE=^CMn?_nW1b66S>upI`55awmxDYJ&eQOS@%>8wOwc_5t1Zg|iNG8~yVO1DzQ zAQ~H+;yh{qlg1DGs|CLB_cmU}(b3QXpwV#d!Dx6&%4OqdUwM4A0v1`#khqvwJq|pb zh5<*CrS=aE#Zf3BmnFfKYS#ys~E znz)! z8~`o#_~>`O!EQ}Jpm^IbJma`)$BuCFM(86X&{(LvG*Rcc08#4+3q5o5m2F`ym90*%n1iMtCYR9K&aR>JiwUd{Y$B;eLMeN4XoX2bwH6y4xaj9D)%MRSb@pjE_3Z z?3Y3m5kxj}yBpQVDP1VQH&81uO*4y3DpEanHElEvr=bE6Hf0<~SI~yfFjCK=KRLf3 zzus~X54>nwu)NR_7L~==F98DXgdhO?J6>e@)Z?NkEIpW4Qd%e|@O~Qo+h5Dzc5T-# z6K-2I+?tVNi<1HkI_jM}ZPcZl4@HvZoD2urDDnMr4uJfK-;s%$I;r8LV?OwZ&B1Au z;AQu^8|(O$ZRLtGal24J00v3q|J4e9bv(S}FwCq92G5+FEJQPb1k zx}dP5GJY(G0`-nCA~za=4FkXOc1x}-9>qOYb{9uFb|2wDk-prD9o4|s5OMeL@EZ>v z9I61c`aCGePOVkLaoMET7_BImU*z&11=3baZs_ ze$ULXN#cK9=+m@s*He#3-6BQ5`JvH^<<6M6uRpT~dU~wdnGQGbTz*scGfq>3(yV&b zrmQ$o_LPK)tNww5cJ5D}T*o#VY0KRKvKER*faFm)qO&fJqbyM!6`-uN&D9F*tlb0Q zo_im(Ge7F+Ap+k}-;eU@@EM>7XspDf;w)(McV_QN9tF2z06w^fDJdz@ttHq#?0#<{ zYMKTDGNtahB=z?-D9!-Y+yGLs|KLF@a1~Iwz?e48^x*OdFdLjtbLEpZ!h+8UpT8uF zi-75jxHdhN6l7XN=9sf6d&i`u@^ndk3mX|dF|KS4sr|K17URc_=lcw&jbT}TB3O~CF+V{NE*V9AH zFmZqImrm7l>EbHso-FjHXi?^8^Q`S^H7_EV62Qt9<)uhe<|!84r+78r>8dLM&}Y7Z zhD6Kk`#Y-vrs?F;7KMT}R1023YY$@Va1rtao} zD4R(u6@|V@{PH)MjnmTJoyFyc{acjrK*{B-*-Kh*q#-nccnkmToA^wU$DmM5<5|A& zv$IGN(0Nu#z>gm{NtNH)(>es=qkh@5eOV>0>Q|$;zQ~#H{B-!XXW!_xE6@COTF?C3 z-lO3APP^VRn)EQxZ$>lU!p0^e@gUl+IQn-`Q@f%4teoWg(L@kEYLb(K*a4{8zjcQx zLvV0=rYbDJIbhTgmk<%Lra;SEE_(GFuu=dIgf$Is*s`TWJ7<xvV5(cpLW})~qEPtBd`cO{6#;$jgW-JK(H^MRY{P^J~Cs0QiEC5XGFw-<0P9 zUIX~>Dy^4fWHtg$Pzt%AtW1lvg!S05orpq-`6CQy4d6jH7*jTV-NK#hIXZ*i{RmUH z7RXLdX9I}}Nk{x($g5Y6U%YtHV63^!p!J_VvV~t$Qa^ia}3wUfh>NSYyTtst;@WN2UsX5`BcQ_970Ov3SIUXko(ldHs+5k9z zbQFkE{EPX5+lsgJ!gT=B|vNrtoh7$Ss0rZmp$;Y#m8fJiAM}kR(`m84A3L7q>Im7TpLm?c{ zz^C2L#3YM;HHZn_NWau>1Cc6ln){5Mgc7wEa5KE3VjDz-g)ghARlGWKgD?t}wP1=V zLQ+<&Bb{RmnKf7cU%}?8jwX$9mSOm*V+7)mwunBOim!lW;|3rBt3$@o)7y(?VFc=z zHEY&PfQ@@|p&CYA*tUGSWz-*wi;-t;uL=}Ow)vwEFqZV%HI2kIiIE~s&yJe5>knQV zYP4i~-U!XFEVtd`vpj6Z^H|Ygz3gJmPCbLmuU_k`bB{gaDs|a6sL?Pk{?Ezkx~`}? z^kYdUo_Sr2W*z}6Tj)m6o)1DHTLVa+u>1feHfNbK0)glUn!K4w_!%HTf(=q2m1}-y z%LOtUI6o@%4MzYFbT|w$!&CemU_RtZd%z=sA-NnQ4?f`_Sqwni(ZK2hf~=3dLjXnO z6MU!?3Fi%?VVN%Y>q;PHgkuF%T!irFuyja)3vvRXEuc?Nhy{4veiWXlnEP$%x<)S2tg={WC#KTIxB>*qo4}Rj(2*0 z(AGwwL7EzXsHkaZtVSvNziSmCr>M&|zeeh5@>_DzB){AYVk$95MPKecKTWwdAKG%{ zBqxXk8rcK5TR40z09K)kc^1nFc!o2|6hdb}LQnqyJcZ#r;m)B0P6t#o&l4>asXY6EeBYXh~3C5rEiH}X2y=FgTsVn^uo`t1e=fC zIP4njpS6*|lgSVq$peX-CpsUL7bwi(2@2AJ4*zRlXX^HQ8)2f*c^p?2{&1J9AGp;b<{H&pN_d`u{)9vLjXRxX)?R^1kgQcgFu-aeR(1$^06NPM2q}Mn z-~;H>m5@LwkP%|BWt=)SfU?oB6m|Bof9o)@U*ArnTS?h9GU5S}H<(0WVXQb!k=%r# zTqT5KH#fH_O(XE<{xZ`^_jL+q+tjBWmng`A`DbqY5*Q&ASiGN11gEh>bj;1SsY+Ek zPnEM{9Dom%Vq)l&NpdH+b`w)mSQ=`>gfmYnb?1o>>j)W=0&y)(x10v=ZUMq!P1xCE z#*H4h8_&Us#payH7)~ZdBifPQ@s+XNblY+)Tc)inEMjbqhu7Tv)X~8bEEjz-+uh6S zA4(yk&{j8eC6yCYPvWqi2Trp4xXsOZUbms~)Cv&n2dYE8K?^{;kH8x!H%)ieqAVgO z82VU^tE9n$0d(Kn)#V0W4^F@^oTsE81K>T+d5-8?fjD|%lL?Ekg&P>fgw@zEX7?`o z?CC!lhNl*5RT8;&zTslLqdT9>sj}tGm&k}c9R>=V_XS`H{Yz=hy|@>aBL-GJm#(bb zF%Dm>I4YbcA6>cR8nc(?yId5*_cd;FedI~}n zLemue^;1|IKbn&FAi9A%jk@e4+81ccq82|n+>4VADgM=q;YMvask7-k1zMLtW=>os zjqN`O{t31d4K?+9fF-C~w^5MQ0&u(!dGW!0`|jMozXm7MUHQgqsl^{ZCS+-9YI4cO za}k$UvZ)BM3(bZcJimF2Bwf|x3+F^FpxlbqmD;Is+!fGuel#WqDg}c1BNKhqPi6TJ z$i5!n%o&~BpOPO%A`=oZwX1kWmiC~h1s*d*3|kGLVi1=u3>Is?gLNVccat4@b;^1| zJy`T&xKw4m?(S{^F9xeSG_>FFBe0&*#Mhdd?TGiLtzW-x4X=4zu3KAymgRZ$-ZMr~ zlVWk9a=ZE9L@fyN-tZw^S)MDxlpF(yFsvAH0UmWVGcQ=jRs7^gGW#w4jz|96rP;S$ z@%4LKbv=Cxi(hnldNEJT9n;htssj(^`=Ud#d6J$7^(p8EAHQ3m&hzC!iLz~E$%BYJ zEf+221YwwcOVH$MlJav0))1TosYhFS8*;YDWhPUlUD!C4vAT$!jP zZ09)a&7tD8XD|EwPANKjXLb7zUAprH1y&<;LC&knE=ou2T?*@;KW6AT8c`KtE?HdD zx@~24PSvmJjPyxfyNAZ(&;JHm6~fqm0Dcho&3*@;d@U=Z_(pTlez?&S9aeG-;VC~x z!G>^7tfCSBR*|@`mc_mDpeziWh=|CmQ}@0f{GLTn_|M*ZNLmSiWdPjB>mZe2X_6oV zGM$|VVFzQ;p{IThvGmE)r>q!9!3{S_q4vztY41eWa==~E38Pv| zpR9y^d(-HS2Q$B%E$wcI*`@uO)qld_7)y7RWqgwx9%;lOF6Nc3{!WWihx5wBEUAki zTwPH$&_{Q{P}qdkD+EFuy!*SS=O)*in{A+FUVOfov2#`4%<4D7?C$PP+0S2Ftj~7b z@~u@=d#;G%lcUo*kFQBPHKhB8n%7{3R9dCEaY#P$-6Pc7o*`~_@_Iz+_<^}oG}l*$ zr_?c8%qCvIgO5B*CA^^45k9g!w-8;&$Oq$LUY-N}rB%N(^B60re0WD%WVK{iu@d*K zOgYdPwW)NZhSz z*hr#$7R}AQq;Tr{&6+SOB=3uW9Ct+pnsycjySY&S{G+%K^0ut(JhJGo82UheISkRv z8AMb9B!UM7%6tM1snG*Ly$lLAmWb>^*Y*I|kVqjgfqw_o1*E_FNH-7wOw}0Q$0rw7 zAf%|~T16@=3-Wvs-;x7-XakfkNg{ z*NR+}@4N+x?Q|Z@$`A=L>Q5+%v_VH+%Q6XDyf+&94juyX#o8$vOS@Mj>fcQ zEyW?#s8h&DU%q-p56WW&CL2rw7YEu_6bwhIntwxU@_WaGP zAu+*5`Me;uJ#B~fh6!I#rJ=`zxt|O(7c2><>OY}9UvcTe2Z0nymh1lc z+FMy9T7Cz4uq{|lO-7r&ETj-#pn5*lJFwEA7E?&apD#UYP-isQ?z*TY1&bXn10W5_twkKi}>yw=&gD0}v<`&Hys*@mQ*rl7^;c?qG-$ z#)F>FisgXt4H|hDR*=rOH^$cv0YngSnoY@4bL3?Gsauk#l#>LD9Y%R_$4k6sx-!1L15*FoAreey7G?43K7)eaVxuecMS z4Tk}Z0bHC4&hJ6lS8rx8C;A2bhr}oj|G|+F*}p(Ky6KPDL!Euli6Q+=j2i;s@L(48 zPf1CUQE|D49IBQ44(=ufDyzX#dJX?}()mzeucUKPC*&i49YmvP5PJX!E}{Ycfvyhx(uTI)9XD=@!d5$&k|5E7?zL z!&b>`;u*h6$?WvpevSseypi@m_VFxqlp&%^k5E<9|salsm7ds(#*uZ!GlS}htzQ>5?_F} zrmlGsMJgHkLBr}jIFV?HlXERiuadLxXRKVfl&5Nui@180$p=gdf=ru=(pJ#qyY?<; z!`3VwG$1gPa0M+2U-^V`pE7@_hMpTVvrL}1)qFXX#uk(*y;e~Zp`n^V0U)5LTIId$4 zbW!pv%~cu*JN0X;zjdvm#EncD$8!c>N*-J`i!+wK{()KAd9;qz=QCSKciY^x%ks|* z)Or3nbF#w~ln(6O?z$T(xDIM;oAHiduz6aQJMBOo1BTYs*LMcrgwJ<@%hCa09T{|> zr+pVS95u2cnwpyQ zy`KU><>2Kl?B31=hz=(eQs(&lfu?ZZ9>6@Hk^@TQls(F2J=P|IoM+#@eOXErxEwO5 zggJu9@UpbDG;pw!t>ScW#GsJ?;+^r}WktnL;3wl_;wCc+hTCrl4WsHZ0Je&Tzvb-6 z)nAUcJ;z?BF&$}q zMj1<^Vk@Qs=M6(g9>*J8vKY&=y}#1Cfyv0>dPU{F=}-Hd)z$Czl}f7Lzcjt|_Zgdv zkp-pAEY~ki8nQ?O@{&{Ta@qX-ca68*|v1~ftk_!C13W29%jv{KAl7L&~ji{DThiZ z!fsRLIdk^u=^(g_M*kd zfEOmlzrAoP)5>b-Iovl;Xu9#r79pW*hD0eP%vTvTWyz+;cmxJA0@%ysS+2r?L&mAp zoln~w*L*P8H!z^A#~WIKIVF|d+OcvsZ^oF`Y^nQcBk*qR%#f1gmN>cKq3OpOhtKQt z(N9cHrgB)su_@2Iz#+7Gw6YMhX?iNX! z>ykg4QdlJJxNF{O#e=p2^^|7ZD^rG*<`O!ejIFJGCQ5q@Ny)7fPEGB>F_=!>X| zNQQTi-U{D3u2EIK9h)pZR4HumFgiU|X0z4#5AD2qV|PLlYgF}t`=26THO)wUn4MW8 z^(jP&wOl9j`muD;Sg?!BlAq8(X<0H&a(U95^wmM@63Q(OId7fdLTQtKoyKd3Gr?uq zQ~8Ydn8>pqA**BJ50x@d_X&PvKNQ7mm@V!W9=FQ9fo@OWg4c~B1-u92oFsz;8ax|M zZG3Xc(C(OgD`oLbQSDa--*snZ*k+XrPv8NbEV99{U`lGBwvC$Dnlp?C6@J(5i^ zCC~0FI?COyNHjZ5`8?I8aK?qH!7u5#%$B6q>%I#%H9xfI0ymip)jN#bzUXy#O6sz# zXq;UC4jNbeaxTCi&!?-Jmjn;6PI1kCJH3sJ&sSTdgN;}WP>;YT?RHH&CjA>a#Vvcj z_An^b%ijIOKwW?6iDGr>Q0t*5zfMnX*=*MRT65UCf&KZ{`wfyQCBs>tbTUI`a!nUB zPj-8G`m(eQUnQ1LQ}JQM}-B@km9v2@ETzm((x{^bJ11K))>lc65?IPMI92}FISAH;UT~|_4A{;DN z9cDcyyYOqULkOW#8=yPL2adGCevpvic6`m3EEm6mhQhY8)IHJgljtj9IDTJnNN zU0s91Zg<|I%`CI1zjEX7=c@{%SJ#~IEO=$EwY=$3(_&@%d3@ooY%=@HMXXy*vn}xj z0!k6Co{u>0U;&0obHTg5`Dq%seLS?^gD-r`7`8MAncMU<|(yKjsqT13vQMb!s{~GW{?yW4rSF zFce&{e*UH!gQ6cSSgD8^7j03XCz)48wK*;Gwb2__nd_$rs`sFg1(niC?EH88S!#l;@H|w|A z+S+>Re6wkvAjG$R;qC4F`y(8c%|BTP3+GO|D(++{ zkvw)cW^5_-&$`P>itl3+c-CZJirVi)cb&t~w@-I_o5bshO^))GJ%>sb?5Sy*?(~cV zljqlPgCa|LAJ#EPTk7)w9|d7!W8psy1{C+BXWvVTJ?#xt?%l(1Qa9WEi-B;~WM@)v zm*ZBG-?u!OG>d$u*m5a?zRw;gyz^mA$>*Bmkz5oFB@cqyW&~_^>8+8<+?Q5qJ~6p4 zb~G8+F`K_cProMnLX@qM5I3!Ns8Dg&r$*a)B_*0V1L{J`lVklC$!4orX8!%?p^%7t z99|RYu#obHin=COh;sW8GrcPD7wK6KceE~Fu$`1%#j5josDm!PGuz#baqYRL&kFuhS7@?^QrfQhmD^6XbXJv zU6?{{tj%M|LXhHs$klp(zaB>FGqRy4DVSO(%r{4`?sQWYE?OEfDhtUD#TLdwesX^J zbiClC8<&WZPrCc#ulb8@)&JoF6mYbpd%mmK_)&C@HAmBDfr{)3gVUWd5z*n2owOAr}m}OkGA{ zS{2-lG?#*5x?2_pw&Al^76&C6gQ&37(e2#f1~O1Bx|S?1zpvxd2ojEE%#$^PL#P~G zJWA4p0tHSNQ1y2cL2TJ=IW)ZZ4{|Ca?C-!V1knkb19sjsK3;v{aKRZc9!ZCXlk+L2 zI9}TZ)XJ|MYl_|yY}!efazJqEP|lI53Uty?V)9pt2Pc`oZ;+hpbd^L&h%0{tzzcQy z2|c|7fJR|8Lh5Z4_9@LKZt?8|fOmEl1JQIJ`fXgv`L#^DXXgh)Z=^T3xg>365{A5g zFYe;88#4jM+n(3O@`^|=HyLxleE8{Is7=oZd<`&~D$*Lhnz_B$B5mcKipXN9o+8~Y zE9Ys3+5DMRU*D-2$;kN>Iczys^vCx_-g4=kUFPzR7KhiV6x_pVj(bsB-kJZf?b5P$ z#mC-0*8=~7@kQq1ZobOkOaXd1b|rRi1=}fMuOS&{XH&(#JqOK4i!2m#8*90~HcKxL z2xukdlAmYp(xXtM3$nHyED^fE|iF7WW>pn@IeOa;y@=iMFAOAZ_yFxNW$we&)4 zJa=?bn8)hS!jk7J&L;j%qWN~a&lPIiF~6K*FCD>_JF=p^uVjH=B-4otd%~<3;H843s-U>C`{zH6c5HdXOYwbJtUdtIj) zyb=~(EsY=U>ib&dJMeC7G$tuxzY}|OTGlh%4W;NQ&26iNjp8(J&rQl#c(HUTHqy=( zF7PX{YuXygT)Lv*xY4a;N?v7U7u~DDmn>yrw^p`J2_?V%^`7PERtx@VS8|#C=eFrc zX1u&T{v}%2iJijl!8vj>m-g`5wA+sh&bp>N3#etyHYRyy^&=YT+6b_K2M*=?J0T8$_3R5IEIa=;k3vT~BYO2Sc`@p);{*0<%R# z^>qrPxmI--g#>cqE?CbkgE9!!M2^hNOfnO;IDBn||AiP~BTw~}6ZRZZFchqWFAaKb z6|Z&y8tr6+5CDR-t*ro5_xb?}{7SG>gK{d-n8WaLI(mVab5}PRMwcsKDGMZa(y7iK zZfI=eM{6C|i?##w75SlvLR$JD#eZ?!`sg08sC2zbTA*M#yjkkgz@o2Rt2{Y zEe!eE_fb2{&c8Zpu+=Uv7}##_X3ht)7Mzv{oIr ze5rZi#I4QyHpFK96x~_e{U$5Fp4)qm<7zsO+`z2WQkNCf&is5^u;$FCZ`bQ@tqN<= zp4s-MIA+p@ULd4PxT&n>RmV$h;UVEn1I8`}%HCdMwm9``)9+L93_|tl0;nhnc=4*G<4eMm54eT8IPH`eSwJ6;B&(gr~8Wq-oPfaWP7Vn1GFf53^ zYn!E@jX%tum9$#TC8}rXwIVGGn^~D{gjb>a{kKgDDoQ79YwV?&-QLA*Jll#Eo3%oZK7I;U84@i2I zW5P#Tx9gK~WIFte&oK^6OJW8zaKjU#E`@PrqK}6jB&BMhv&g-*Tkwl_kpQKGct&)^ zxM?>D26}=?s7=2X$*s{XLkepKf8bY?l$~2k&EI39JjiGl6O#wpj6k@0A2OPe{eZ}U z_;fYn=5{P!@R+}dWg{>VWlazIBX@Izo1QH`49J@+nCqz2d#U*ldQ!l4k-ViFcn>GX zk%8UfN81K5VD#B2lLj!G`{Ba#m`5>g5?rENKI=|viEU|FyhR9NI5)ifk1IU9K7l?x z>APVf#rS8`$d;NaD`@X;Tx}Wu|=lSEgpVqSWpzFFm*XQ$ozt8hLj^jMe z&PY8pHYr7(Sz7rnb3c}HAy_L=l5r%&TLeFU^-BD^I6jh~G{jAai{tjvi6>%u+o30% zh9`$^y<2=VG3$1!liz~iFEcNHj3JuD`yTpM5@*5` zKi=R=#F;%u=G<(r)@|uG=d5|lqQ)z1rW$uQod4^Ql?@uaNd3*q{$#xAu2BwSTA8Td zc~kmz0;L5k3o)lZH|3dl@c*J-|kl6r{#LKpQlnK z`vt`BT)u7XTO2P7F@)*vZhm=r;Z*k)opvN!S<*LA1LZBJe~#twvaL_64N=e2S)FSpsA@$@Ab|JEVOuwK)0qQ2A;aHi{0MhR$aP z(9Pfy&`??{ut<5S+N*#6o!E9K4sa&3yVhwXK>QgyWV7W z6?GqNHPf|1*6a)awqoe?3~jP5hiyGt1Zg) z-R`~!y?^uO+te|Ni1PU=?$s&T_m0)&-|?#Z*O-FU-5z~iRvF_r`|`K`AtU>Qjari5 z`E<>fu8HMW`aX^JrS{30=rG~*#}gC;k^P??fBZD>MgCjg;|@F0Q~cg|?hjnJy)b*L z?M$VAd8KXtpmgv2*HyYHdU;+SN1RRHGqLHmUEl1F^|)!bH>BX)`S@kSMg~@0(){vQ z$k)aj;w+-u-TavJ(GhT@s&H1fDMy@=wKA4rWqt(~T=Z6EwdL)|b7>Ql(v_CKz?jmFSUOIPZyyPf}+mht$U{gkv2ojJ?zQ!`h- z&&}3sw6?n4nwHac-!4njJ9*~&lU=H!^s$+%_S%VOA7?JE^n5jFNM6h2xKY)w?2ZOH zu!R%4)P87^a?+~Z_%SAVX}#CmUoV>|)+F(7UDeB51on80XVPC(k?4DSjT&`q*DhtG z7=?!E)8>2|P`+-0bJVsAFMs;mBCECM!+lpyMPBVN>~_ff{kLadTWXSYOob7G5EGcT9KeAzlFzr)iV z$5k>?Y{tJD-LcxHXHT7|pLO5wa(i3aHegJrn3)-Y2O4Kbce_4khVt3{5AQTP7qGIY zhVt1>JMvwNV3BN_mbg|-U~k^*{`i;It;Q9fSeNFNZPMlKv&Gr$+$4xQV-&zVuRmrnK3xx97n7mqJWO0yy?ThAJ0>~?W+ zvGh(YgIe5~Jni2=M?!9`sgIs%?eSLd&t=6Fhi{IQ|t4l?58`Ln@LK?`f zUaj0Usq3-g8;>77x}04Ci}++$o8NxhyKmpE3GE`CRm#)otcb47(%N#;^xNI83Ys`p zY>ixf@ZiDUev1fN@#3COn0@g_r{YIj@LhI(_w)}ChomnwO+JX|)Zy!iuV?+O9i~zX zl5jphVjJkF8-Y@2=hJzg&v*XFX~GGI`jjq-*H2#ITVTx**r@S3?Fs(RXt$g}=p+t9 zZ#0+*#zePa^7`{L^tIkqY-(a+R&Zp+nUb!v7WZgNnk<%9}d_1Dl(4N0{b8nH6 z6aPZ%{@vP)w+n(FUK`hL#noNf7j&Cu*4^s1_M(24*=ns?^T0-p#=dh_rAuwYVg6K(*)A8<^!8YOzhd_)w=>p zmCbitderEbR;`ZhQoCUM#EI?6zXmJEYS1jS8?L**47(T7;l?`e$*yi67T;)It?^b1@oIS}^ik<>QHS z=N_D;r?)U?S#0x(t5!wKGB$qaYAT29Z!31uG*QvfA!{`j5=sjs>xw5w+eL2#-<9<3 z)R{B!9OqidqpTr}+LKDf(|T_ucZ$}=9p)6!{r7`vNCWIaqtNr^zg zzKb1giPCFg%=&N2H|K@hALB|L5%hF$$#pvPR%v4Xrw;#Q#{JZpEX|yY`=g?VhAkXvbD+RV)#+fNdr07eki_t#6Q{YJpJh<; z)lTD-Q)ql(&lFWdT|bwde%mQFPKD*XR~>58KT%m=`=@#aCgfLhSGmW8Uwbn(cG>Vz zvArfO-95|5kl#|yuT0T1nq{Rju_9x1>vaDK->)S0?dYK$L$%ybT}uqvac`E9W!h6+ z<+G1p7^ZcbG%fVSxl3irJGb3+wJ2Q^q+&FWT1`N3N{@PoN;>8%u z3Mj~&EP4fcByoR1N{iS+TqDqLljx5I_!UjRVbBSx4KV=4hOO8z?X>hpBdzVc>Ujgy z;^Ggdp^V(sF}_(Vzv3IHg{L9rK*QgQb^%Z%e87_-A%1SQVu13SB|POMwD=+qK{&uW z-b4JF^JZlAyAa8p5EfD8{`~XLi?2S})7v3yIP4)hesM{z1vQI0<`9x8ZEUO#iW4~P zyYT%fqP839dc`PLvuxbQ6z@;dfVEh%mI$iwbZ$krJoYFFBD$isDKhNzA=&}UdaJ-2 zpXSp~HD%hgo;o_-;m?*282OIYfLXBRE1)%6w`nthn*uoAb=0WbcZbl7OKYeYZ{ScT zP1Yca1E%MWc>L*KRb36gH7pB0mYb$$JN92*R(aWN?f&R$KPNbGPp58g>jp#J{2kVC ztM<7yRu^kGeo@l$efh4#)22H^t2RE>A5&L)EUhn?g>g>+V#Er^v{1qZ@lz; zP2iTa-^jT~57;%fqAXN0edEQsx}%4V33_q}Vc9-E?VaXBG)pHx=paV)5+Ox{PHpx< zt@f6R`z`9q^A|3NduoP$9%B{QU-W?tahYSwqVXWvmV2Uiz~$}6Rga&zo6m$%qI)1ZdYYT-@YR)l zKqhD*STQNI^zGKyej&vjmJRSMSvh>lUw_$s($ZdeExG}LxS+5w^~|&m-MU5l_&z?0 z#%wtbDD=$Ezh1=U^1GF9w0xJW;hDx8D@@sfEkDKTymNDFpy=dq^smXAE^a2ZS*Ad!ZF*a$HB3@vp(1U zL?C#0rnK;CiQ5+I;G>hK*G<#CquX}p76ij^byOQAs>26hNkr$*$XM%lcJG&lWWG)- zPKtg`n@ecK#Jxd54m%5{m7TdXpl!3%)B$e$Y;96s|MO)xAU{o+xs%whK>4t;xIFjI zt7k!Hrz~7}+WP6V$&>G@hN9TtdN;DIO0LJv*CEx$OVWp?<~%ZeFe<=Jv9yVD1siwU zwjqyJschn(-+v~zJ}|j{h!2k{sL%IVH=6npmJJINTC8^eK67XNuiyE{nq6D&xD=28 zo*(XX`#Uo>zToJbZc`r2LuvuQ<@>_ys+1<^?86TO>>#O%GYO*agnH(avY+Ai)C z>R|FaW9t5WXU`(u2lQUc*LE9US53UgZ`wDKTo^9;pMs!-w7-zIGvuJ z1y?x(Zh`9AcTT{1hZ6AAAG`g|@@XiRidF3w;_xA^0_=Ltp*Zj$CXyyfFm>_3Z2n*a znlG`sq&M0D*H2qf4`0%BwO0<7)2apT-$WApWXh)PBh@sOlc+F?~3l}bo z+^Jv(W4*@kk4~Yu90G>@D9>YmSr%arxTl)Z-!-<9GEXAq<7rm>?hWaya<@7RJxNCS>E8NkQ#AMWNuT$^ve zLlc$LW4kUjPfL3)GwDzDO=D-`{rkCz?M=mUg3>-}w}tH&%_lS08Ql#sdV4_qX~mVk z51wrg2`l~_Av@`AY%ZPuZ`6iJSs~z6Au%2HQr7Z48WWfqv=I=1V~E zr-f9SF2o_>#JDC|_+%5O+M9YIhx)Zc2XV69zGsj1^P3w*Z>yG)oVFCidRF6P(CYr1+!#6!E0NwJ$Gs()yVTE8qsEKnWo>TS>_T zgY45i^v!NIJT#rQ_rogo0GIEiYtfwUGiYh=1VD52(j=#e_&LBUy~7co2oQn@8BvSd z;cv=;(w6Znd|%O9v0O4-ANWic5}`M>ALdBlq|=E$dq#aaY&e<|MLniw`TL0c7UY9d zbahX0Kcz!VA)Xun4dJI}O`F!7{**DVSN>78sGJ&R^4g}8YD0{7+RLeXcgEE1J(kSk ztke%U$TiEZPO(rtxoEg4_Qm|)T4pWE{~YhFS4@dU|?d z4G*M<1mSk^%GpLn_YrVQ$SW$EZD@E8YfE|^-7_BV6iT7C^6Z#>d-rb0wU=e&JNMkB zONAJWi-)+C9rvFs9VO&gS&z6E4;gX*gfi>m3LN=Sza?32;CcKMxOvu`&g&{?Q8U9P zo?z)$@D)fd+j5by6c3FeCJx3Lc!#cfq!_7RVMf3H3%F%x?QP1 z4_#c)%E6Flk>S8z3It3t>a4q$o!Iv5<0<&d&}l^Jy+tPNEekE7J8&LGQig6YE>*`wl_O`aFyPVR?)%))2F~A1U?|J*=N6QAiabLS`ox}$5 zr3X+qUYRaIj`^P=(_O zUU2ItG9irR#PSWqA}q7-9AA($noQ=YwFT=gD_c^dpNE5eVPPTrEN)kNsbVODo}^V& zJd|W00PL;n+e_gJgYwvr0dMyB_*}unb1Wzqt<#De*H_1|G1xE1Kvvd#ag34~Lf~== zSp>u_YeIqE+__~0fYuvu|J#SdBw4a6(?Y6pOV>|ANAmA@1^au)kqv7C`coJP4JOIs zq*()SfgrK3rC|kvTCA52k8lZe4UB#99QWmpBZ97(CjX-aaNflVqUSUPI2ZCq5IW}70fh;QQTL7DtrA!6~kg*_#|YWn(&ik`_d7C@cu5& z6EBuM&|T+v z()>HWWK`~@iqfT>?qP6X<;2eP(I;p07)uwrHMA?BoRB zk5B;F5^@=y{)9H5_`ImjX7rA;M z5;;dS=7VukM1F9Sj?!Y5<@5Q~=S=BT$@!|m+@&w}CH}w_I;3(rda|x=EGIX%TNQbP`RTxx zaCH*kkz!43W`M)NcGM&d0~>996*!M$b>)cBxhpbyufxVO>FI=aCYvD=iC|XB#&4TA zVcWJrG&W@N;RVTVb=77Z6R%TGZB?~h%=jg-j{{!1!ZKwejwhMmB=7v6aMWI8A`7jp zTmSakcyx>$s%K7~ynVe$id0;m$VRv@|5UvzSY|-3+k|Bni!dIdC}MY57W09s>M#p~ zv)`C*Q^?vW#ADC`h=3G6>eAbWfhPBWiSpY9wByELEWe7S`!vdB;5c_>a{-}CoTcwu zjCn0APQF@lv$#6#F$)&p=^rqlPgyh z`yWECWI?8R`plWZixPiBX)_jnRI*DMyw%(HfzJ~DtCEOiN0t|{(@vO!L z&H^@h_rworMmJV#VPR9692cRfso7Ue?KBp+oM9SE9`*2D_sNiQaO30Rg=j>D+eKPI z%RvgLD14x#r)Mu-RF2Ahz>V1kQ%$pi#ShE6>tEjlFfPyY(4mB5F3;#3+7X%kteA0V z8&PfnzfY`}Bw6vWtX!#Kq&4gs;W>YEuRKP)f6i1#r>GQ+=B6>#fz#dLYPCwl#FGfyj-npB z7RTtYl%9u-|0HP8KyLwTEU>WE-`(j})y`YHAG@x9(XmYlj%!Rz_5*ugSrdYNO`a?= zQN~8?_4R##Ia1@BAt|HpBa2DGj8zw$3qx9vHlJo|@r0=W7L?Q6ho~n86j(0E=|#f) zZ!p2s#pWN1P`@3CirC`rj%4^<*eMgJSeXEVwxugif`~3glo%?z@a(LfRFikez%nwA zVAYD1xlS1*a>-x-$t-*D(PIO8dD`Fjs2^SX)s_NzX|JX8mlM$?%@ZR>KtZ-I>5SmK zax7qB?VE0dF}4PF?bJ%)8K>?Q)L1oZvFY)y9aQB^M>bH4_fCr1Yj(P~@2bD0{fwfv zg5q>l+co}JWil>>R+q5Y(%sCBj3>c5E zzwPpUHc`3LS;pXxORn0gMx2?lh_g>cWpUu8w3*14xDpO)W`Mjke0LCWEEqekCwAqk zl+7~M5E&K6=#crJtqB9buA4COiHLLS)22-uC)KNE?16Pf`hH~-D!4qb~}G*ZDy9&cE3nU z#5Wr?Ck_o~A`WiZx|N2(_ib(OT7?`d+qMs5Bl6@?v1brAhcB`4MO(pXUa9PZl@KLf zg|c5OSUZRSKy$n)5V(wrRS+R6*ePWky=&TjTfn0`^4Gg#5B7XBy)sWNIc%pk^)aW_ zLP{e#9+#6Tuhy4k0GWM{)@JJ4eR;_)@K9a{a6GQWS#hJ_$0L!2u-hz1d~n*Gj^&AG{e^ ze_=Xq%;=unaQaySh(b)MF+#C2WW&JW`d_`8wo8keA`VEXkGi_^&W!YQ?+m-Xrc}u2 zJ96K<4o}W~jNm;yTflfyJf3E_rB8B^e$0vgK%a765~qww9PNWCUD$#NGs$62mo17Wpp1JKBCV8xnCuAaUFVwWh1ktTrut8e!ReIaS?|N5U@fV#-$$= z@Q`Am2+m_61hzOtDI^kyKU;nOVoMP#vhXJ2X!`F|m+(s!N8Py@f;`JYvki2DRCH2uN#(}!I}R>=b#6~OqN2^chiubjDfaTn|a;WqT5dfJ`vu&yutZzET6@PH}lyytogw;BgL5 z+N9?o(F9{P9fl(}g%*YkJ+Ziw0IBD8EM0*?= zV)oAjnEiYA-sJli7>d!XKv9xIV+9B1WC2FC!FGNQ14CUwzQ_b_TLdqI$$Bi%$0SQu zn%sdIlXfoMxr*30w9X-PesHE8=h@*wEam4>A2-tZ^Ex{`$go9VBk0?AxlxA%B@$SU zc4KisU|VeU^Ye>*_K@~+4P`+{qf8nuAp0gv+!;`mJj&9-A}8@Wb4-;1@rM%}UuT8( z&oExmoIA64`6z#?BD{QCu3Z~_e*zgv)U3bzL3@`BgDxbDDPW-Dh?UZf^z^!`CS^}P zIrRw)<}&xq`*AEip51NAopE!vx851|QuU|B%Udm7Heg6|1bt0z@=zklnZTSDaKejx zh@AAWQ#B8qgv!F#EC{Do->yNWu4mM5RAMz+E;>soz_70>!lI*)1Sr4!{y>+24!B!S zn6O1!afVD)Xr+67Ofh3c{7*GQj_%)Y?zS3ZIGXZN#>;LsW+4~z3=+3OG50?kwBhN{TvBqISn2>ID%6+Y2GLYE)&#Emn>Qp+a_M` zf9={4Hb(^ojMmg1A5rRq5hIynKwu-|X4cw=3TzVptHLDEnCRX2q7yb+4k7J zwk0yU9Ovw%aP9kv3FazFvXx|MW3S(Lo}EN&R4k*-7Fi zR1qP6L(wD$*QPC7HZgAI(hy0s1|p8CR1sxHZ6|9l*Z>k*Q z6lJ#-=u(il=q8KPiSk8|J+?qD5z!Ycqa*=BFDm8?MCaTrFOsv$Wdm zg`wK3R+m`24aLw9fb5gSI~KA>HjgTItvVlHl^S>YoKN(%&Sz{uh2^ zM)mKxO6ftE*{qutBC&zpK^ZTnN@b*7`%63SbZT-*7Hve7f_0J3b-~E6u ztChIwf`mn5j^?X=|6)}WX394y=$OS*PT4D$b$6iqnJ~`#n!A6#9KOn3zUBj6w5GmY zby7&w_ywJZ)t^JO{HMv^*w&tSF}26Hrr+u1PuT%C z^4!Bmk6!n3MU1I>sqUIlzFR+6e_I`-ekga%Xg`Pgt#-E0f9%r#|KI-~yeAPTN+=`(oOrgZsUoEE(jpU&#-ZSc;0P(?n22@DeZ<1eG*)Mesp^| zc%(Y;NrA71S?CD5A; z6|5^@Exccc4I+fJN$az9UyKPm7C8w}*NCCPZguPVohnSn><#iTDdjKlFii?x_xtkB{mNevqVs;ht~t`h_h({1}VX74JH4F(i|Ez?$1A0ea>}h zAPnwd4fDSi4*(r3KS3 z>d=J2yhK4{{^DX(1?V&hrn`#jLfoDW^YCEcUJ81Fgk}S*m103iCVG@+(wdzVeP~YA z4Pk`Df(dc;h{|iuGHNmE_(HCjkt$ba@2P9r~7AwA|BJheWSSw35tx@p(PAl2HU3_kG3rbJ?c1SeMg`twq8e{ zf#*SM_?)=FPgHywd?%StOEs7LJ8h`zUs7dD;k>R{vu3dPcldZdCnsn9H-j_fYcO&s z8q+*BVzE!|LD+tl5dWu!GKJx1`$_quocpwl0u@4h2=ulfcv$$k%NDf|9Kw7tgAc-g zY*pLqsGKM?m}I(4OT18&Y>2JhD!U+{$}p`QMwSu;()imCLU!qZ$` zbL_)g=Qvie_la4Bwh0+?GC}B>_}Q~xzoxj9hnQBaxQJLKg%<)E-@z4}<*~xvC)piu zS`4u}j$V715~H8Np-j7>Kt#YpUAuLAd2;E2`eP}h`>WcfZ6d!n)7XDr4X0d8kq@5B z_^8dOdcfL&>o;ZAan`M5v9XRtS&AJOGC$#jto-g5Gy8Q+&4-2}OJFvm7l6IT=GFe5 z-Tu)6Y;Ht#hCkSiOczjmM0t-G49m8IvARR?#~|ZnbRFU~o+N_rPeH2&Vk9;wHiTzX zf#r$Mx}$}~#rLFBk$@ zv$i66tm|u;2vgy!q@*+$nOsH4xv7jkV$A_LJ&bU)BuJ>zZlL;(Q8x^h7H!_fsHo}* z8FO_QZOA;RA}rxspw{x|k_COhn$V}@$FuC;c*^o=C8!Cx7ulowZEfwrd?Qpp z-KjTe-a?Qq?aaxa=uH)@8I+=rnwnTP1644}CT?noF>FvS6XAvHRjfrk%14M3JL5|J zfWT9=t6_lOX`o>Co%p{Aw21Tsh_(RaPW%Gl^Ywi@i!$v4MDtIDrEbuSEk+#`rMb}T z=6CNZKjL z4Vl4P2yr09F5vYQWR(elMc%sLr^k6GMvCr&mK^46$@pmw&ciaG_{fn&Hm@s5fdZtn z35!S6@^DLY=FJm%l_*^BsJQGWZa7pw!%xYf$FmfrU{nI_x(q^DN9fR!LLs!p|r~vKrmwi6y6xM!E6| z=KLhkhk}ggVT@Z{Kfer%;KO-dz!#yqfx99-kyME=>%!cCc&KO=<3jMku~l!n_c1fn zb2WOBzKZcu;&cH|TZ37+fWN5L{?)40A27PeUkV8e3Yp6;u|b|tn>JhUDibaqv78vr zkF9c@2YH{*L@$MmkLIY9m?OsnquOCW83@;E11De^TCiY{YEH&PGrgWrrLWL=N=wMf zH)%Ar{>gUnMzYHz5IGVX^ZCn{e-pR0Y|<`A(YNe)^w$lHunE`D>dQPeX}{m< zE7L%vF9EWw3*=OIuCoy{6-nV_Kr43hr>J^G@Kt2Z+~)*jBC0r`bG)+KH8~EHW5ouv zg=T&3Xl(YI1W(9zF7;h!8M|(&JqP2p+{{63%*PrUs?J=0vyzP>Ug0t&k0e4Y%u$1^ zNIEE|EFim5AG3XFpsUAgTGj&7>}OpfG|=32VePX6XV0FEJZMkfkWAm@ z@CoUZSb852S|K8-51&3+5zZAd2Y_RU7(EW;p43OkJ&}9vfqq0xZl|PwuoKUeaHDxW z;316wa!|t;|q@_TMb&=Br-(usDx<|j~G?BjEW!qESxraT)AgAU65;hoQCxQPIzy zJ>vk#P6tJM7kJ{$8pE=$E{v9i0FYT7G=BA#Ka^NZg}7zDx&Fp{ob-ohjrpR53qSDq zuLz!xf54No(|nxoJv<@9(L~G+Ep%k)QXBjIo63LZ$T77b^g8D~`IMxYBHjEVGz<~_ z{_~8z{(}>2H$dKt6$b3{dBc!1hT-!sF-OCjCqDPhxXjGrcHkns?k{FnCCRinx8Px?A zAZ_4?e!4by=K8iO#>3UV%K%zMnl85WsWGqm`qctm2FfQ5WvT(;A@H?@f4CW3-IKq3 zM7}E%;KJMgk{CYCbNN#B{2loT*Ow^3nAFehKX@GT~`VkS(oDtI%1GFLG#%ubb3 zdm%i&RSb(+C|m$^7~_BW`udKodJ@U-_79>zqB##2o-YJZmB9;tMn-NGlZZx@EJH(F z8~}{tHI$*u<;a7~`u+FcZ#r(9L$8;rw*Aq_9VG~ei%^gjh2Nk1iIcNTmLShwTI@-< z?$AWlbXb>yxfjRZPfYwtdNbey8=U*PigrCuYj3w!~awBp0_KbVQICf(>5%X=!!E(`3eI5kBC{ zd63{zmS8+8nVB?n!Bm%gZP8)qE(zC{+Bf`ykxU|o1th!-Ss$|a;RZ7M(KR2&MXf)` z*qA+>Z*&?&Bpw`ZAmS@xIHG2!uN49FQc-1i1O)|IRyZtwlh&8Y zX&S!OI5K7f!pkO-ypec!~48(bDLP2 zk(b+GGWTj;wAz?4F}Ag)*e^KUOF4U6SXv0RObA0}F_HC&Q5R~cPEn>_JaA5VC$)N9 z$oTX6yt--X-O8Jg(+pu}P&jp`Fd!|WXgRFy;A?5{9h%x#H)TF-M0wqo&6_{K%QMvT z0ju%nmMt?9#TSy6qNxI_4CB%D8a_Ph2fS21W`@y!@DP1LiGKXt>6?|+Yk6bq2S;CU zL@{V+HZ!s0+v;CBVi{gH+$TAnwuAGtPARb=Jd)3l+HR*HL|G7Yuewj4K8!QF6Kt0N zZ@jZG{M8dQy{uuTMZb8e=Z_ZkqJDsD3HSsva2RBAKJ5qbANa(f?*8-wH%Zy=9qbFe4ODVBr&LoMb<@f%uudkZJ1* z1SB$LM`VJsTiB3dqQ13NeKE7VXH(CDYc2>KANY-#!L2`NB*xq)(xr&PW zM%o8BLZmo5$lA(?g%i*shr{uAj3xqP@Sk(H`k z#V2_p3QzT@=E)k$7xmvxC_QzB{lC+69I|E^V1R6)ch8=Uzc{IDYkzxH&xjOEy&5_# z&`4BaU>ZEYhxN6iVf5O_Oka#VDFej3Q4ka`!_XxLxoiEg^33*8iluT zadBZ6$wqUf5hPiM6Kn!!qWC*f0*S3Abt|WFv#}iQl4N+}t5c9yJ1#{!X}mBh@@jX)R-D0H(O+ zcczmT@ye6b$D;XWM9C#DMlzK9%1prJl7+N@Oi!eUQ^e?ObI4Fey}xI_}{>Ek2K zTxfWuri7CgSdI`diF;GbNF=_0cY5Ez*3sCTt*@=JUg1Fnh07T_=3bcVvk;{R(suKj5RYT{1_#F1+yL5xT8Mj zjGI2)qv{z$P~yoDM0KyA!m*@(MrJNaif5hDnbP2u#@istmr%F2yctvbaUklh(#la& zX*R-fiffa?$=k_Vx)rGWMbe87S(I}mQr8hKF=|wyfvyr9g)_GS$3A$Nj2~MuL2nC& zg%6QVvFXWK*D?Vk$RtX0ewf`a3!)Q1B^a(<&_D3a526kH;aC=>EyGz~A>HdacrXv8 zo#_AR0#-=f&mM%>=EQ2w4iytL)C+3!F5f(w0CZbFwu}d|fbw^gs9@&C~Xmdpt#mf zF#BF!?~Jo(_veoK&A&oURb7t5Mu{ndE?lH6!B|ZOM2lMt4X>H{sDx6pV~9iQQbIVfoVgW6thf5T==4N71;!Pa`9-Qd1R*m&LYaD`|rQa zy;$z}q||YbLRxJA@??mhEJhM|4Zp`4%2z@{yoWpWBXI!ryW(6jzv5=u4hQ{B;AZ8;O1zTl26r4kfVjWcTz@ue%kHO8Gtk+(W-au+?mY= zVU>1|9#CPUXrknvkv{)^e#vc}-`g6s=^$F)cc;fU!UeFSKw5JScoN8`g(`bJdu z>e>AvHZ#B-EjVN2?%&_Z>1{el5j;72sW+TJf+2YzzLxD!aOjS4muWk*clqK3Vgw<=9tbJg#b8<%92-p|#_19n++bJ;G;TepSA#SA z*4h zNpk5-eV)9pgD0GJ-d&5}4|I8b00VVXCl`Cuk^y#8r^o?@6{=q2@zcPIlaT;J}u20;qX)(B7{G_`@V! zx;7GeJ(jT|6%~>O1Q)x{B%22JXM?V^tIs_4)pgZ=Z&p|CK*vRFUS6H&9w4f6mi!BP zl}?P?+Hq^$3kJ{l!T@B!kdopEC{GcJx%3SBro>Un#1HFN=}9AFWeDMQ7*6LB?H!!C z8(_Wukw4VzN!`)oJU-6>)Gta4$m>K$O>V(%S1|dc8)nX+%M4$h>H50MBQ7DCwOBGQ z`XbFJh;d9sB1O>+5bf`f7cH_?s5ZF%mTy*=jI z0MM~|sqJN#%l}tOBZXoa5d|x?tkgY4E_<wmPxR{kM9>}vnBRdL$-4-QBg2@;c%(w= z)90>zwE-kPqHL+90H?tzfcb5T=hQx3M~{AHZ;aT3{?Oef zm#%QBo-~_?83h2Vj2A?=teJf*Qe0oVV;4YZBZXul&rc*-3Tdln+BFJxnUO`y7t3nD zpI^(HEC`;uL{GXMT2l+LjLF{yztUFTB=s5SYbr?rJrJ~JXk|AL(^cTT#k9b4t^SMd zdoio^Vc?$nlqhG_cMgN@U1U zdjoGZ2m!E|Oy2}HP#Lp+BwuncC6&~@l$x-K=Jq$DJpT***H-~Su#o287Ngvpp5JUB zjrGibmBW^H4si7lIIQDqL#NX%3s~ZuPqhisl}{Go{IRLESq*S*M}j~C`n2fQ&%+u`+0&07CSsBE5K}AD2$deT`0r@zv?0M50!-c?8RXKRzz|-9U^Loy0WjeR$&6`9j z+Eo-Hh|W(lc0kSa`qPnqcQdPJIa ztDw(yY}E=W-0YgL3lCPU;3|2_F_EJ#Q_Io;Nu#aVl6uZ(Th6wXPs5Do09$zY_iMS| z-K^!E&f4}l6Y~27Hjlj=AUPA$Y=?PGYjfhRLmNiF19(weTP3s9ICYsAJq10ld>uH9 zb3-oF?COp{M)RoS5G>h*MFicsPepnQ68|uS+?a2b`{#VlUtU_Z{BzU91pP*49u=`c z`2k3|)S(#ixFE!#GEBMr)?*;1L^ zc)g&6%-3Crsj9UgcEB`k3=9nLkU+9AK=MESCmoQ(oW?M^_b%Y4p6h)26#gJ{J8u>< znpN8_H;8w7K^hA`Sn}o&I7n+L>7ueg(v$s2VjsZkFL`oNl__j-)i4d1<~DzPk47L!OdaU{H0$#4k~tWo9wJuJh{GU7;n%;b|k9 zDnuIvm<}kOQ|A=H;J;*=AcGyGL%jA=c+4Q?+-}WGOs9;Xc=jrFS$6N(EPqk0W zq@$5t;AOjW=8^8q(bvb8!(H_ayI>G117EjV*P#y2cA2XHBM*ihR8m$MJ9g}bs`=_? zU;4(td;)g}>4fh`rhVvq??IMIuq_EzA=p;lAupi8!SSo~v+`3ge9_(J4qq#al@>so zj2No3h!0j;z&mH9LkTv&Nv9*WSnjDXp_WuC&g)=TcaybyXSA`TN@$LKB^kmgwwKZZ z7PktEKc2*5w@93lkOM6ie@dRG(gJamiI?s53AR;*XQHKOr~yU3kiM>Gv@Hc>TGJk; zv;YnWdyrU2;LWo_tfqzB=oeE{zB4s!sS$aO3f196g8eR{)uTWel97~AQe3=5L@CZC z9^z%Bf*VHBQ4-G~(sCD)>s>vF5J}5cd-tfQs0J#mCrw5b$dz+;3RVY<67T{}p81EW zq>{(Qv<%@c4o#OV`CJ>P*GSUV>tXBX?IJqWP2Xcj+-Pukk%ZFj~o z4S5ic$1d!?n?YPm$k!Ryzej6hTXlEG?VIKnxJ$DZHfZTh)MeTZ3)nHO${G9LRw!?lhHlBJv=?8XH!gm)Ce6m zJ@~&RP4|?>%#O%HJr*fsfMTCM%hb#cV!Q-r-syhbeqcadLql)NOkA4cd6=E$Q zyNY>~oYjO}7-e&~TLRZ%j{Vekn(TH`wtFnL2|Pi`ngv-RlwTO~kMy||DYkKI{eU*H z8h!fp>xObn;B|Ecqzg8((Yp5D4QUyc+1q4#PXjq18W5MzwM2!<3}P>@iL++yGx;`K zIreuLc4hwyM?%0Bz%+@J%TmKacGS9?FC+Jp6d|KUVNizSgG4Ef=)}KE^R_z%6G9&e z-bXMSTjdY77h$OCt-!1v72cBOf&4IE5-wH188m6kwjQ}^BI9A4V0+Eq+gku+u@T4A&I_P zL7k@gjXnmvQjtXnp+1FjZh&ikJ9tS>ZJ%|_ge`t}B6d-D_ziTgA{0Xp_~ywaUE-q7 zst?CAqfweroh&9?N+AJGOi6jTgu5>UrKmlLd8~IP{Qg~Kc!pWYm?QDuG7A^nQW%J$ zFJgB_OdL#A#d~ery}Kt=E=Ahmb!@I;pigoc8P7z?`(5~a$jeJ610%a6lWWe~zhla+y>H0 zkuHq>RyjxU?0EihXT>&IQPieBqw5BM#&L$K=4f;a~@*2-!Zb;V%}Tcl8&gm220hw#fyM$^17fO41+og!NrPc@HEvKE#7 zqQSKxVixihbupwM|G_0nO0eTKyUv6DinkNrh6No@M;@BZY~u;i1qu}qha8c6%s(kZ=K3Oc<|Cw7Z{6Bb$w|TOT151aDcRIt z8njGEduhlwTwl6!x+8qyy`Dy|8zIfPR8?Bl^)=?*(it2ln!H>VjUvY}p_4pCs|e{w z2WpG1dc^iuCS3o-rmFq5XpO6;H)>Qzj%r z2crQnN54c)gwpQ|S+pX_6ZUb}9{B?qpL&Sl! zg=ik({O(J5%T?{_aaFfHK9+wpx|w{b#^BUT<8G61w4`E>nossz5(pY^Z*QH2nG&`7 zRa*zDmfVj5aj|_LAlA){aT|kW{|jz2+-qi_*%nH;289j0$RiBLQ1(xF^-1q(h;>U~ zc6`^5Xd!VC1Lulsq-{h zt8U;C-3m+v-`JeMrQ~Xg>*b045k;C*)}ku43~#D7WJub3t*>9cC<+6DMA1(MF3Dx~ ziJH$REIQ;vnyex|N3f*Mn?wy2sh&(;Yu?s~VZ9>@#{ zFjV{0EQdgoyaDDjF0eU}KP3JAyY_LZ<64fo0~U}; zTM4;Eljl4vc#g;K(5f#D%vz3B$-GdTHlSMz$q8h(9P3NAp}0&XTZso}j$7R~k8w*< zPsV|{b&u5mEFV;7cx%wS>uKLyIvN-jzH0HyFXr585%Ho>J1T!DF{FFx%nU!%B?szv zeT^?bo%(s6G!^a$FG9%gqGurOcm9Ye%u^E*iDSsQ8i=;xdsX&{wx}axtn1~DgVFJe z)hK~nygWDv&*e@%p4fFf!V3j~R+`q|`gLp9l3@o2m?iqvR`#a!Szr+GrETbrO&39l9uP|`!?Nv$ ziunt*Y4ZF<(A?H^bJ3);OElo*R#FupEr(m_flz_8C^I*RuvU&AXns+V1b#x59F)!# z9v!qjNY_z8O~Nfdvi-%|luwJ(&h0ZPnGM2-4mbK;sfg2ESz)hfu?UL(+7BhXJcpvh z0rgx#RVi%3p&<+?t3`c17!p7F+b1JH4tb$ijs4uBMRcD=uHQapR3R$df{PoYdw?$7 zN#TFepi&eoQIubM(rtQjev(cdv0S%q9V8ZAfp`f3Qd}>K??CZ8bLPwipO`V&UdVk^ z-9pHM^?2g{OK#MFE|G@RUPD@5a8AQ$mp&a)l7InQaX|7=_L3=Tp8lb&tZ~1L$2PaF z;eyZeku17WDg#B!=s7XZV%t&)HdqCpi_4`;QmqHf%N=@k62aqsKCpEO=Q2i6d%+Mo zae{PS`{56<8sWsCy+zF21>#1!p_8Ql0CbiGh)e*Q;ncZv+gQo1KvVIqg6lG;AQj^S zDU68MBJtxl#TsX3=k_-cr_=hO4RAxUEfcqh6lbC5MM#K(fyMR*T5i%HOGwCe$6THI zqB0a&4Bw%QQ_(zhzI?Hg=v(i(U%PnTV#_nOs^3L&%%}m|>T!~CvjzX9N;a8ASeivf z*-)bkwZX*s^N*N}0pPGiI5Lr}m)YOiu}pCn>rE5Ce_JyGov4rs%PV%X7CKPF?kS_c zMFrqSlV~ZkAxH~VH;7sag=}{cav0f=22uq}F*`^+t}b3oI+`)d+4;K}Yx~ioN4v+w z#7Jh*owkB6_swc$JcFnhNmmCE`IJdQPm#9P&u^HxeEF3h^?i3xZ?ZZqYFlN#Og_W# z1`{)rUhyagiT#(UK_LQ@A;>S9^GF+haVyDPvg=@BZbDg}@~+r3i{2{!H2?Y6-%gyH z)jv#sSJRh)CPOAPzSYxacc|WCli4{l1N<%0!v_DE+rj7X8Go(xrb9f>oen&0G2vEY z$MgEj7H-u^X%_2h<bN`CrOKp>Sk z8;mzGNY{UMF=moW`%YQHlk=Z_UT;2Kyu~PZ2Fx`uID~B0i0SS#i%;*L-mlZ@*C)RJ z1`v_!jj*sVoSEhhr6m-i-Z9cPBet~W`r=bi^6R--Z&cN=2V+3OA=u`NcZaZ~RB!y#mUiT|NLiQ~cS zriS76CLI4qAhE-~Mok+%y!ZLw;6Wchel!~Cb}lm6Z`Bh{(X@;V19idU$fl-HJ09kM z3SVuX%JhnIypficmD*IqwB|*HQI|)b7hwoTtSQ-6_?}}r2Yc+^z1tPB_#>VmA3Rq* zq%lm){jOU(dY&%KKdewF>eRO`4VeZPc`5$D6NLF)VVo~?JcKW%d4P2>2cu)a+bQ#R z4*+AIjFU#cgf3WRe(kvO;UAI3XMC0;z4zDaS4acp19EX6j*^3))6>!pw2XRo1lyiV zwbv(Lv0`6g{hr;;lq*A>XD73=vM#N!!~H+ICYmUn^QLrl2rhr2%PY4p9ld{vt}}1C zwAP-B`%>D<^XUmLd=bbSl*Dod&|Dd!rR9I&LciwCo2w39IJwZ7-#f0_b$iMkj?iPE z)pI?@9Ez^aEwutA6FcMmJ>dDLgGcvsUYbj?`|!=FdA#QGsMele{<146JDqZhS1lr; zKi{!k*nRaVJrDkRLDVa+ru7De>3Qj1-Xk%8o#DQJikharR&OG%j#XH82` zJh2RxMy{a9AUONEvA<#4YkwLB=AD=KdG6;ve(&#Xm-UbHL0&bBB5Kx!!eyo#Si82U zhQ(dQ4z;1+opXFHjvY6SNfrgb9>QFskS3uFt}o!L`rFn1qgB!;YMa=)oJepX@ z?5k6bn$f~h_at#UA_sOFLkj_AOJ>Ev~obepZUU8rVM)H z#s}alsu~`6T{8!zldWF0a3W+=%ipE>3$yH~glXv8o+TVfb9xEfDK3H8lP6VpTtqxL zwF-czdh)|gIkjtgALaxch`CffNonxiT7{x0oQ?snP&NED4p}Jp_=+W(U{1Qtmb7cN z)hUhTZ8R|TGJRFo|I&Jyr5dmA&frKK-KDvPd&@d5(Ixy7^Vp{c;ul{J$b$|EspqO-_A#5VV;1;+Z-Txnci-Ei8Q{3_$F)6nHh;2U$d412b znl+(-24pUc_>Lgcl4$kJBP{3=T2TCFnCfcvff@%6YaK2~Jk8%x?2?)Iwe?oPbmG$J zAcZN5IKhb(TZGHmB2-jL4KzEBba1Udf;9nxPKz4E!jqZ7e7>PzuP&LY5Al+xiDEf&Ktl8V;kl-H!FI05{r}a%c0kK#f#G z=zrTN2NBFu7rb_-A^K92ipps$WnUv{&HCxwXQ#S+SES+k7jmk*{^ox6V0eIr(88W{ zdBDn*D@BcyNtb~Z&GaYb(l?m(0Ful}RIT-7&$JRs5eplozlL_SnMyUn+yxhzo^Cgd zTndY=9y0!EaUCanHnY5M&hs0sdYyMO@1A^4!3+WDr`y42*rV%3mO$Or=)08~C?i~O z|C*nkn7O-%u$jX?jEsz^61{9gx<>5xm@ypn)Q!xal@_LTmSFSw)3$l)r5z4ucPb z(bo(~Bk(e!?yV(TF#|h!S{8yKk2{6)O?~`{5s|pNCU0%g?`qM4BL8B`Y25z=*h3eM zJ)6?J>7zPBV0CRp*acE4d)baCC=qQu)-6b@A)FL`I-40A*QA+YDJ~+$X>2-dzEep_ zPwBI1e=KL(Okn8FDH;4FsnPk48P!v(v*VEXX5=`RIrS4?T)J@{S)^m(aZN9{^u?r}jI9!&iuuP&IFLUx zsNUp%CHFQe!*uYAaT^+@QiXpHA9FWuR^v=JZ2&W(oGkHGd^lt17pI7cc1s%-M+?A0 z+IYq+YD$j;j9za0gq79tu&0&P>ren@qQ*j$L8o(sIUud34D{d{_AW)c!k&0X_ zC}dDiV_SOc!!~1THkJ&qc5%w7^AVPTiw>4?dAbA1DQz(fIS^GPYbk>y6u75L4ljIJ zGbFs|h_iHIRYCyK`Spk>-=`j0S&iJLob}cMyE9<&uXNljL~nlTo~i46CZgYO?AWo> zSS1O|OlIOHv_UReuqn(U%`x;sfE7IS()Nh4>mZ8Z-lsEM_`; z7nA3%S@V7EvHRse*WD~s+&cJ~8uQ=9&jwCt0iHpA+_yHO$$;uEN?zyQKrrrQ@IMT_K+RD{{uj zX6BHhoL)a({wbcSl2gL!y@CL?EM8rp#ihe8xRMFh)0-0jhhxMdBs5n$!Uf%E&YorT!XJ4pScXbG>+ZYMdw~p~N?x+ET)<~+VqN>)~z!UT@cRs$iceOiD;!y+ zIU2f~+_v_gu#*yx7+47`$T?)Qb+!na(r1RgWUkxT!-ig~8lgEuX1pI9C+n8>$pQnZT7z+tJKVO#l+; zTQf&02mNunEsc*xw*DY4DN3`#HmAGN;Hm|SWL3OfHH8)s(Goh zX?Q)3ThE>~aPQY|`0~K6&U3mIzrLGmlfL9(ZuxT}4BNV|W`C2p>t6HYixOi4ZyfB2 z);(Tuol5)V8dXG9!sGicy)=LFrSC4rOp@;TG+m#^Wyj%lzpT~2c~5z4)$Pv% rQbUIK<9hmUAauWlp#RU@bGPLQ)sU4}%cQO<*#YJ3pjk)!mTmtJ;?kA% literal 73845 zcmeFZWmJ@Z_x4RGCWVsKC%ACCm^5(p`h3f-pFQpdd(h_YlGWqI612 zch__B^SbVJUH^5zc;4O5de;4h#hN(hoNw*DkK?l^@|l+Ey}Pt`v9Pf2sXbA8j)jE_ z$HKx{BDf7a0>f^O$HEH4Qd4^T($jP!4L_A~_^`_=va}QOIZ{P)gQJhuM?;%;5NRnI znRmo~7Dwx|aZ4KU{MIcUJW4_W0t7SS)4`0-cH`z{^S0O2_<4ABy;E{p7v1dk`6-b` zBYdSFGjrMq-;&ILD-f`Rf`C8IyH@6T{`n91lL#jJ_Y?0F*q8tHFl*Qo%$>ilR=WER zN&fe(2ntpqu7ADafs&=xzpsZtr`}u_c;*WzQu6QHLZ7hw|MbEL))I@urxLd20utw+ zk45c&eo;%{)Z~yEH2dZB75nD_Xi_3YQ_fzd^{vO_N`Zw8wp zsKT8X7;+`a_f=PhH#6~8enJW#cvBX=no$7XKcB@6O$!0$MJM)4VRI5NhX~gAs{Y5o zmAO@aj+m(f6Rbq~#At;XxN;(!{dzG6F#A~qUkc$jliBmG;&Alu4gDPXzqj*$N9X_O z+A()%=?eY3`4Nd23_`u%?CX{Ug5qtQ|;)%wnC_2f>E z{CD-+O_O~oB3w;%rsFj(pNETqt-Y(s(T+(GnQp#16gXZtyPlBUMUxl3_^PF6JCZDn zdz+}lo0wLVyGe~e=bq8$<{7e^Q#6afF{Xd+El-j2B&@#he5ajc0X4M{C%4rPK6jLG zUF<%|$=dm$NHTuf701LhOX0Gbom{tBJv(!cQRb1YA8_-VY=>i3anr0qU0sj51dMA0 zoAUGy)<*{}w>+Aoif3Lk&mWK5GL2T)zmRy<4RToV+F$MfzQK0D^*L-F9l1Mv*i+}e zzQO2wTt6G*^zgp_X|I`zd&5e)&y?BK9<|Zc$wJ&heG?w7kYS#D@YozF3-CphIt^j_6@@Ln=f3Y1B`RSoMVO~ zL3l5rXk%q%<$hNav~ff9+NZ0q=O(pcAIN9@w;PY^2>EN6ZB0_w`t`|o_jOf$XMI#X-;72RCmvI3XpB-izYWvte1{{25s%7w)8r&@H zV%%CrImH&J$$B4@_}p@8*bT2=e6Nn_AkF7KpLOl!(@AluNycYzi=TuK$WC9KZ*QCW z9qJl2+w{@a&q{ArBurW-n-usp)YBiI4ZYBImzeSV{GoaJ&E)uLiL2~hH`|uF+1dL^ zua&e-Zz?{+SJytJ2WRWWM$#w3q{H+Ham4|b>u-ua@aP-fuc6thnuLwm$epy3Y#1Oy zKAD@P8_nJZc169zubi0rwQu=T#L^q)ql+2%cx2}pK3la_7eCbn#`iQOreC=)`s;H2 z!16FCsHwQ+e%>k3H0OP^aUZ%p(^!8#Qr%=d*|ZZTfUIA$c5?w4Gt0mgB^D*e*A^a~7gzVe=lz2O5=9JqsXN1w?m=w~U z({C=@+|Zr|4ecCFI!&sI?_g_7ni4t3L5`TlSf=zRIsyvH1uR3nr=8pHZ2>ztu9I*N zyZLy=r=CMS3F7mN(=v7?sP5Mcf#UCv0(E~_QMLg`OHCSSQp5en6As1WRj}#0l$yH3 z5hJK1u|hPQ&#Y;xNB&hYq_nM|5fSOj3KHsS(zwWNfheFkd*!ZA2l@`lOTSC4QF)ZV zlJ330YB>cNhy}$j(4Zw2cb-G4>Lot}Awx^93b+L(`82LkL=f4Reu%+mylK zpO{@5kcu*1)p7;OO~lSKUMu6mK~}&;WthU`jaZu6Rx+4GK-(9dzi(;PzuC;%yo$i{ z7u~VEOPIRiGkcz1xUWE)e;+z`r-OdQGTmWs%Kv<`ia!In;BTICkYvZ(un|>qv}5cF zE2tnayH52IItC7@(WFa~TUV#cPB^_YXH?X11wk6Za;HuB z_w+;q$cm0>_d{TYO4zg%89d;mohfT`%438j_LG#*N`T#+3?Vf6`d*~u&VZQZ5fEU- z^qIANb~&~QtuiSG(D9dFT5tttK=iF*xG~1 ztH^g+V{eh`OBIx}Kr%`MhjlTfvJFmwx?FdJsAF3XEc*$Q6wvfm41_`F9gTCBJ4y1! zckGRV6Pc492)GFx4Dc+hH6X2wv%BKbc$6?gLQGdRbF=lp64Xk3;bFFUga**`v+L$r|?MMjlG0GhXroyvMC$50g&+ z>^A^shIkYHV4Jvqt*s;xBq*#aAXFF}vp+;(*9IT6h){m4$>@J#0jK+1FoBTd6(~>) zb-ucNk5*~Y7beCNnHmcWK;00!J6iAxO1!Whc`;myNb7uKQJkQBu32w8cnEMy*y{C zUt(M|9c@#X?$IQuqRKWproyOA?FJ$SY`cYOFlBL0_{`jdR0jUY)`z|2U2nFe9rKXC zkdiESKZ{?wKloRUB%X%b3OXTB6cyx*^^()N4dRDvL$qHi@{044PvOlE@?PH5f4M~9 zACXV~RBr-7Y&Zv-fW;i2ltFR}O|D(>Ck8XBf?*Nvm)Xbsx$q72nIns{S>-Zo_WbEA z_wEHBaocT|FloAAYK!4)b?QkfZOs-Mab7lv7mY+1^PVL!OEke_-`&!f_)Om1d?YUT z$0=mRv%m%H%{fojdv9gIbE`D&2QWnVLm_7@k4}QHgtUWqeZMGUSb_CmBQw3+JPx_)X3vfqg zTg3?~e>btA6h1G9FS7INkDu>26?le|0z1N7OA_b5g=a?#9@yg$l5IsmUe^%wz5^24 z$kFH6>!Pi$-##Lq)QYuEASQ*{q7lgG1#}^GuUHl@vE1DqUJE~~j0yGvY6Xgjii1(c z|5cuYc|cH*M>*du!g(NSYQxph_u^c9>_dOkMGGxRA$~uyL?cf4Ih6CFBwH>IfKXg1 zZrx^G{_T@YO-~s~QBH>Mo|JSp2;wN4IVA{0uyY9Ve9N zVCJuV*i}iKqyNH$SZU#5*TM0u8_$Xsut!QQ{A~Qbrn;+@y!!bEBl@su!u&EdsL^$# z5GmWomjNEU=e10%U+QAjFAk_ZtXe{6>t{DooW&nm^`r?mV!Dw6;q}qF54}@arHa!Z zJN7ks3qMNq@}a=3S7wqP;YLCZ-!_|J9nZ;m+l^#?Q^nEQ>?i6_LWcDOkXHK+NxaT< zBGyKy`?l5|xw+20Ik6&h6)d2zp^&n|i(#J6hmiIpt^4cYU?2U8M$Wkko9_zMu+yJ* zUZ>G&N7tS14u!CFJzlsvXSAC`GGE@5?eZ&$!^YT@ypS}j!z`~V|MrRDL9ffYM~bww zDb-rNIhxKU6Fi_6L3q|K;5@r&9Ggp47a2x<~R?;Z)|p^rp>$SJyJBx^57%oszs{nFXzfNq?hc6BiHMwAUd~Tx5TMtPgI~*05?{(VhBc z*kCv?z3VO5JgQJb)M5#DB*y1ZQX+eu2ewEUm!iziZZ8z^879`VGRJ1x!rpR@jqNJur1GHR#Bq7fxgkwG_F znpenG@_lESq{b`c+|Z=7YR>GqRWu|)R`ZLEYfX5^hE=7(Po zJ^R*h#3F00e|6UD2*@l`MblH%hWr#y_4p|bo%)lUUUo`Zo-RUn4edn1*YQ+ZO4Dugu0qv#?^;{E+VciyM_!xk@j}1*7 z0yr69?#m1hlnLZ16e9WO0S+SosHpj97(zf71I){3m2XXty z8M>&@T1f}0fog6PJ4IZ8-7uF@ZR*JpA*>VM$q26p6pHr%bRu6FH~aQ3>Z|D&#@vSk z#?X{2e=haOXBnVc_)#EV{WZaBuuU~5`K)*Ags+2q*6BC@CnW?0DAuMNY;yMK1=S)K&;iwQGTS?ijU8j8MoQq@EmH2hFR z+aLT>9&`V|KNe|J{wmXir}j{0=(`eJr9@|@Q`76h&a6jeagU`}=D4%HQL%f>?@oVn z`W{tZxsTHWy4NK?3V^UO;jmj{F+z333q2dlX_ORrG4-}r?1z>NE`2-vCHYkodL6yr z?#H4WCJ-StMskPY<5)RbhUvJ)@9=PMU8aI=lT3TE)OG8?5v56!0>5T?-HSOTq%>%- z+UOMm_uU@ts&rwx^jTFFTv@!IF_oP*T>mg=%|f~j5qV6>Ju8Qj5wUnmyaTma8Yt$? z5VvMHr7R7cET{PL=sW%~`$c_A`TFEX+i-8^&2cxD@s&6~P=R8`x!Dr@Md@JG;MJ}> z%McI$vfbz{HvGEP#@VuUO4bMOH;NPF|6{IhjvpgR_UrViC6035){QtHC8icO zBe~ZwjTZc?9V(JBfg^S-rl}qA^OFT!;8ee@GcF?ME5Ri}kM5vn@`liybbox8(plj^ zbB-+TE^v6o^v4J%iLXB36U z#+0Z@2A>G`+8fiwXG($)<}p#-D!9j(bZVDVKsq2tA1OHzy!gkr#C2f#)f#>UPus_; z)H753{Bi@BFjT{&rfVqKYi|?#kZyWejlAy7RkbOizxmZqJN2@D5&6lX#pUn*zq}h@ zPz*fGXfhhSJyvy#4P3R)>bCHJ6Nq(5Ubksck1~nHA|+i(U8fC_$5mn%cLTX;rjH(! z_XwB9IH>Z%w*)O3Jq8sQ%P}H|rT&oL=(jS3E9*z}zldkSGR&m_mM z5vB>5G0usddn*{*;Ko>rm#CT7YpRla&NzJQW!*;=0RG9V4_-{F#d zTykeHW;m4OIXDo+>uYQ=e1Bx4sk<()G9nHv@22~<;;ux+cUgBTc#Q*#jEwJ({U~2D zURsf{PzUh5Wh{EB9VG|ylV|;OQgeH)`zrA8wgp|Rfv~zYHkD+{+I%60;6ZKuW@^O} zB8fyL2|qNO8ji3RKp<_WD1H=G6ywiPaY|*(mlY(Ye8@dJ_jBMvlfhGQOFF~O$7erb z>R(b``1Oo7k-;q;-oN_qF;%kU-_N9dD+%5^i9dE6W8VrS=_^owNwsZbKrPgzDoVu; zUb_f2vLG8$!4#%Sw;MOKd9zqz?=JGC_|H$sR+7SfpZuC3pLMie>H5}H3W)|%I^GEZ zdJ)y>k}Qq2sS#c!1fif%vcXE`o2bos&y%;BqjFK!EoI6kQds8MS^H3Cs%LOatLX;2dC` z+p~YalDhN1qHq~J_bCPnDet-Gaxz z@xNB@=2|A0kvGA#eIUJqA#Wuqc{K?3t+4#Ci<7h&ZLttS5oK^;MSZN&`M^b1>=rCj z^S*5d4R}ou$mQQn(peIXYV}8z>;rjS3ETH{0FMTx1!Qn3=i=*yU7u+V_Izm{5VcNi68J zfuN31^-uVNAt!SUzBE4AEfEr%Z4n|m*I7RCtNM2EiE&j*l(}Fi{WecEZWi z+i^-9$v#yOCW+t)y0eqz<3CpQ8HAx~>tL^|1(mT^B4+~xXdlg__eR?huXmOAk&w1r zXBr81xeAm+Qzow(=n_?B6>5q+P5Qne?d8@YcCt(qqr}%;s_)GiL|3Q8iAI|5wR(DX zUYz$_H<%f-jo9U9^e!hyRTGY!g3?8NlEe#F{Lus3lUUfO%X-0wE87a5+xI=5vJZjQ zFqc`TO??m83iK(kMfWis>-2SUggQijcM^YlJBi#ztlZVf$?MUt+Dy{hYs08|tVEoU z+xJ{aWDlPCy6e;eM%h$6%ec@j5}BPq>FbMqE1#j51h$ ze8OL8Gt=O;wU%ETTUUm@#_rH_~tZPv_Z0 zz&893a(z7c#KLll34O;_QrSc(*Xj(5n5h<^dM{r6IK$Ja8b6hwqLNWX4BY((Dlzu% zm;y{`GmmlW6DWHK}1TFcjJ z^f`V57>u^Qhk7il#|2Y2#Yz>i5-i$C9H`JJ;{M@NikyWcEYSqV8P^wGCjO^OZ!kZz zKQ#Bun|iLKc}!FR@9*L>e7R~9dic5}5PJ*oI`aW1)78A*_Gn{#YpZ^{%F3yBiAuu# z^_v|r=Pj-b-=9@3Tao1DTl|0`7b$&t@M{{lN6q6Y_;~4U#Ry_CY;@C&b!F7#3qPi} zo2)8apR5-C)OxbJFio!g%5NjZX`&);eWVaIeB4Rrv9@%eYb@Ay)&KzJ2LzQ|t@Rw%FoiESIhT zwXWJ#VaER)%5$89g1HJb>?mlZacX{Cgf(Bjkv{t9Q1sn?_G`L#&qTz6-7krm?m7`Z zqbkfLa2IcGyyf9Y>z2xcZ}~-K@G$oloQWb6>H690lP1O7~1#?`^sDkg<3KtB}4-Ul#(G5j;Yj=3NC06apYI(m@@8w={Ge$BwVxfjuJDJ~PYP9J{3>9!Z?J*6^^_G_862)lV z3oeh#!_j)b1)jQjy9%Mu!R|pIqelfx#pPXCf678NB~wZXGvYH&)((B>+Zd$sHm2XQfkF z%7o;yka^ILDZwkHBM>_@X1sO61HoAZ?b}(|!-usQZ@0JbGZg0?1s|xD8!-XA9tW zZ+`Y$>iNL=3IxLVfP6GSbq1`SW25-4kA0htCL9J`Sb$nVNrR>vZ}9DsAd`!PdMMQ> z7J>W(Nv~}t);&MUl z`+Wx`QSGdI;iTtlcUyV&`txR)G}Z`N*~1r*peis#8QIyQ2onwt!)%O-*~-?=AZnhx z(gXxpgMUam>z0p)n@$1JO%vb>NdY~&9Hxuk_%PtRi8;_Pof2TR;B<7IkK1N2XaeX> z^5+&R-#|8-Z#e7JE3FC@|0d_Ogb}JbYw`cI{ z6Q|H|p_3oa#O;dnV*kVZRQL26rTz0;^}?D%6sA{o%T{)asYqD~OGOgy)VqIUIm>j9+T` zB^>zZZ6#W+$UEcWJp&`;sh9seqy)j0K1EyE-v_Tk?J0e`Px*qL_$|6cg+RWMltRc~ z_$&@&<4+|E_GB$p^iHX>zU)+-CQr|JwyR`xaHm`mA;^8hF@8w23@~9JgWq?C?ptz( z?mmq!y=yT=mK7G~2W~4BWmyL4LPp!{F~|*pE(9_N7k@dC96$3%jf+)zFcd(7IH{cT z7u&(6MFKo#SQG_H(Sz;62p{%UoO$LNXSM_L$KSLt)86ZaoLPIM)bPw~KK^BZaVhC5 zT52aL_j)}K*wy^Ci)8TT=;ZbjX*4}fw2SNRCSrFDP47MhUs~+k$&!RS;~yY4#CfKa5lsEMWkDqQ{toeuiP;G>E$;Xc~a#wj|Df^_=}O z{e!fc2XW|6u9q?vlYX&6B$9uezY;1FXLj5X(eme0$URs3F3){_A{9r18yA(1ZxMtv zXUH7(J8_GX3uy9%LVmU_E{W-UK(c9K%}sm{TS^EeUrv4YClq$Pl5@}Zz2#5(X9Bz? zjJ)rSrC$`CTZ9!VK6y9v(JT1FOLb*st?|&`U(*7QxXRcv=k6qI^FfoIGQSY_y7rYt z+`aQf3{gzTqOWg^aS`}#&;{@EL)=Jkpj!56vr!2$IR80I9LKHd9uVupt3@uk(o=wX zLJfDcBY6bsO1hc18hlu`Tp@1>@NkABYwwVA*8I|v=Ie4N=3%iaC#VT>u%*$stZ#y+c(l&>v?xW-8?BkjC4Cn`C+ zX+rQJlWpS69HGU(ZUWOEFcy`OQg-t-LK3ekf{CQ&w)~3SvWc`*5@ka45?1NJ!CBJl5IXPalx%t8bU41PsS;j@(=R;;i&KDSug5(;M zvwZ}eiPUOI&DiOV)Ivy|+3#fxt}sYn19Fjy*QBokY)`|*5sAW7+4dWuzKrNb*7`b| zD21~#(S83KR2RQZEYT;lNoxS(fA8_aL!JOmFS#_v_|8ktK-<-!#~i%1b|1f0?4Y*i zII^n6`}X2{wo|dlCbbg{GH6TXhcbMLhT$t))@@p583V?VgQkYa#Qn(Hk2h`v!uW4K z2_vtOV#NbV&Gf~}Q6c%dNAaX48Yp(65L)A)+4S~<Vu()vgekJM`E5wXr=Nyte}xHAzF zU#JvdEsfkXvRGLe6@^r#nN2}4a%Y2an4V;TGd6nvley&)#BX31Vh33~B3Ux^*{rk~ zZvU8cGqqXaXTIA$v*qFza=`$?S(Q=R=^d8uX29xZ+$Q0^z>7-HU6N|ClJld#uay_K++el5S~Ib zBGrZAqf##mJ3(wz?YlxcCDveJQc6f82%f3Fd@}lR(vw%dA|8vj+nUPo+nNFtO>gO- zr(!(sAK8+f*4c0o4gJhFQV6jLjuNtEGZO2Tr0O+@MNZ;bK5%Sb%T>czC|6zzw@FNq zgp2lE#V3*!Dc|_n?^*snC$2~&G(xhTjGy^5vGd0;xdYo0D_SLvk)bdyB>xL_AweYo zi>OYPyk&jzAfn{j#UeZ##1cvq9jD8FLZDZ9BGlrN`29^$)LChBgnMGIi2TFg60I7; zvvbv*`%|io4jh)TpE!p;EHu^}GH=+C1kAeJw@%rk8Tj+~BFr_q2OhOI#E^s% z80nv2W}5bo)3*F^(b)>ly2{XwsrXKhW!^Zu)A&d!wDBXxs86))&9@88hwR-@Tq5Ug zqS%!jfRf~L4^WJthmQj-#w{5^^^kE;W(5OPPrN0fHanrwy0{H6RAcSr{@ECXitjJo z$(~>$=^K#bhxnHKYNUE*H^wTvH2xG*BZ?7(hmNyX#CS=_hElZkwj)bQH}_R1`nZ-s zGLX?g;RvzD(N1q&u4U)^1OANV=e1#vbzieBWAU&YS`^TazBOXg*t&TB>b_C6rTv^` zKd&DXT7TthmSqA~zshX()~%>oj4Ms4@IS2;@7exNwh}QJ{4frk8VKBjG4K7a;gF9% z3mfUqHcWI3u|x5#%1fSFgejhQId3bLxX_<_?f&k<=nx++g)ni4xOmiP#;%WvlBo{C-5mV_;0s_vhDm=KoTs5)Px6+9$dj zJn9SY++Y#i9RDSJ)xm#k?uhiHv zI};0|cZWtNytTw#Bu7*;R{FFn?)+YR8^|e!HS*X=sIN*Vo3M@=!fLO}hyUue_{Wg?4-|q=sG5>xVzI*BKqBptQu9IHy*0WXj)ykxgZ$Ov zN~l*Cj5;i8NKL$!FPW>pkf@Yk4uH6Oi)|J}}E zMCv+d;f3QG?GiI{miPtf160Wce5I@(SlPRB_&{lp#qLQJKT`MXSafRcTT3@$_GV7j zrMCtz_;~&EfQ>+#`y`-;2@HJL5^oIhg87*1bB|!*)*5#eyl>t zScq7`agjUOq}=IXzca{tSm@ozmN@_}E_Y~H%|SWJT5i>?7r_De+%4J6zqWq2lMenq zGQydE!Um}E-pHIc19b#!yv%wFU`5NU->3S_TW$f`fJdQGb(PY>#`&Nslk&OVtt=q4 zY*$JFDQ@^#m4GF!L9f;3LELzcu=Dz zO1#MDcxzC$)%B5i3zoFR=p)~g9lL-?NgYZcf%82f0pNsNGtBm$r7Xdmt9KDZ_wj=s zlWk?7+Yt^5?(6IqS2hgZ* zzNWn~tni(3=}M8d?#MCg8IZg7CAZH+adbJy6m*e=IgiX@&T~) zLy<+Z>$7Br`dR<;aW9Was6=(2_+*VDiR@6CbK9M*UbCw*XaLY?;CNkwS^~yx<7f)5 zEggP%d8W&BgxdAJsa!V$<|Dc40K#f|v!tDv^LdbiIo;t2z;atyGrk$KcsIOz@Jri6 zdaLHM^zT62sT*{1#g?hFndGhM~m9nIfzcmEtk(nqIagzr~am?q34q(P*9La zkKUC1!-F9^6F_M*4ItcPh4mX{y#+E#^wux>o6ff!tT%yWp?5S^I!VvX@fzn40U6qH_aEGy{(X<7VlIw7%~>0e2+F~-hf2CYwClz0y|a1Xak zSbvbKVJ4uCV@kg_*_E-M7g^u|{NVdpWVt>#}q7A19jN%+>UriI2?j+ap&+^YnUWoS?iaCwg zSi+W4S5YR-g&ERpQq4Dj#ZVgi`8s<%QXLD&+!x?uB^-td49cefp-xvF9plXWhafnp zg)0-;yJB;ika5BOkbEwvdnZ^B4cHdWfgI6GgaQpel1hJ;M(f@I_}8R7ZI;LSjGn)- zCz;l1%~#I=MF*xpG^(S-jf1aqcPQ%8sb=oBkqTbvRHmZ%cR?z#r0p6ulqj_WeJ^AZ z;Hw*!hzZ#aHpYJ??MF(U495At$|6)}&m!FQx=|U#l_o#Of!9=GXsvr8bPsxs?vla@ zM45*0NPCZpOzJ20fMy3PBSs<1P(F1`bgMVy*+BuF5H00-6Mo;aqXD3eU}^p0893xj~lxx99{*}SoHaWn`c9{28@KAr3ZH6Ho^B`o+u8zW9Ad? z5WJO}lnxjVnVDm)vW<5M{8d|hZDDo~76{K66pazXsK zDVVbPDdZQVL|qc3s@>^Ei(EqJrm5}#akV~WeYrE*?%Pw0m&OTE&sAf7WC8NLxHjrJ z73=7V#l9uXW|qI|-Y(${n}NruC$-iGW+&_V`6z2CBt`1D;xbP_twj;!mhsIUfN3i(a$n_5z4vDzjq z0stkj@92Wc+J_)G0SBbsv2^&J&QeFH?G4a0b`053&vX_9YUwSR9OT+o}&0Vhk zxS9%KPV3?*s}0|jIxd!F=R7>6iA2~YbS6r2ib=8Lm6reUlHL9F@hR=HEC;=280W`4 z0V)Z!?GxjFSUH1REc7A~hXOPF^AT6m;mA@V_hx77#N5duP~OR)l9u zW8AJD(8g8n2MAb#bF?e{eRca3MwlB7b%06_Yle@^VPT@u;qwqSwV7|JQRV9ocfQ`3 z0XTWgUmAY5%92;T#E^aowVoh2Rw;PR>m#HpPnJ&EIpRg|GB}^(P--O=o^?oV;`WZ= zeD!O_L|Ju3wf6|WH2S`?5R(m8*9xEdZ-)ZDN6dT zi=$lJlHcKeLq|ba3q%x;mbIG~j*HW4tm5`uRY2Zl5S^tmo{6+VRTm8_y-G1E#Y}(z zg)SJFzhDVi%ECwUzV~6vIFe0PA`*owbdp_74*HvIeiMF&qHTEa*Xc= z03C0wQ`Ro0iPk`lSQY)Ra~-54e_|1EG8ci0`ou*6UrbT76Ko>1c-CV{9Hb&o)w4tX z_{l|$5Sn3OxotC=Z{L0Pxln`;XRC?tIM64gbfZ33f!(sv97EgM^7plYo?}Ob;~*C| z1T-mf=Z+EU@>m4asVPP7xk=u;kz-yyAT%;d(aeT9FmAmKd-efog`wy785e@bQHk0R zgBTS>x|lgjl}`V>1Kh@f@C7p`okC=}5S#(^QJr<^cX+M2(g<`YE~TA}@-E$41R-mi zh;;f!6}?czm?eYN?rX9fQ;bk&e<#Mee;YRu5XoG-Fw+b%Df_RwHd#t?RM*>t;1$^W z1o}$s)yiyo2VpGyqZhWL|kmDST&X=<{8*7!I61>S*6@2#H` zVYPj*W=ag*wdXyrTJT0bISmZV=C9G3SGn^=#ymjjlkMf%A*W%Ab1zY*{}B1;)1Q*g z1=`jiC%Pl+^Ki|Voo^*B?v|X z0!VxV_hZjRB@{-c9&Bi(sUxH~M%_!h(BW%fA*#-a7ZYcrhE|`#8K>S2$`ut35FlVw zFmPc}qfj+sBIg00u_sBg8ingTlFTq6A!VgryefRV(2*MV@qS%Q_#p3sGkAh0+GaIU zwX(wfv8cM77j_NIOZ+1Tl^&h|>wx0rc$M28P5D!m^%d*S?_CRqOKF^K?D zU{=FlW?g&%XjC#?d{2`R3p9V7Y$@YEUj6*^?9Q=j2AG+6E5B(=casf3_cSM@B3y5& zGaqv^<|+Z4tXKR$J?vkojQL8b&OQn01`+1QnLhZY0+6f!UB3LKS^syBC3>&Od!Bp# zj&%+E&23RaVO0G93zOxdNcjZ#gr4Z<+rnw-&$Rs}$C+&}1+SijSB5DEvjbRQz|{u# zcX8(Q?ibbOi}Jl{D=aKWA3F#)kUQS8#$5n|1qcJy<3lbsUJL%A$DtHBi*5Vye^80I zH?8?0e@~RZTrtP@eryW`GUoxbgpn=Yv?q#7=NLHR`69(5^O7|%%Na`Y_ndY=-SEsR zB@M9edF7TxZSPGJK7EAJFYGt#ax4SipbU@!c%oG*y|Pqzn7pQ*ILqF|`^xitnDggJ zM_K;Z&y(P#WumpsW#TP|mE&L-rZ+}-1!k>=R;~6EewwqH$&gDoQmMeAjB3mgAa$co_{L$ z_i2hTmav2mjsT%<^EgD!soAc}>)|vn&lJF>rGybCE91TVV}sPj2pu`TTE7i5?#dZl z7lR>;NB5|)OEf7 z6slXqkDuvK=?MpCFkdKeM=Su3F&4JdM%=nLSLv@SZhnWA+pY1{N1%CNP$+SIJ&a(# z03c|3GPO1qa7&n%lLk^9CxKo8+Rg3E8FemwIXwYlYY}k)C9j))eqXh^<|3zmV_X1q zt@y~MC{do9%s4C&50AEWvy2l6c)+bIkvSG#)fL^GHqjGJwmdePV)_jO3OK8lC6!Y6 z#$-I=BQoJohrmzmA4qv1EJg1K!vh>gB!FXv^}+uFwpCcRQ>dMz^X5rRK3_73jEU+#^S*tq+;HwHdoXJz+V z=qA+XR+=IDYy>PUkP%&EEgqnovUV^4Zr=s+K_kS!foqc!81)ysb zWOkX79e>Q5QKH_KF9-yjM%{owmOjva;AbDE0dI~ApmK_&4JUFpeR5>rm29j1H*yT; z7tkY-bN6XpCnKOp0jN(tloY>VC+$iHy&gZw2pEq6q-5=Q-nm?c@T48hRI6Ybia_ET z%as!Gr^!rc0{VLem;z1!!Q+m1_653KlpjNoZ4Nh6beCiGs;=o~iV(E`67#T0Dyu2< z7hp#%%>>Aee#k2t(obtT8!oN`dgwd!M zEx?bJa952k^8)Slu_$5dr@k+~ad#YVlq&(#H^SZ78&pftwCgL{k0Gaqi=4lSoT6~~ zMSnImE%sItJ@oCg+>tT4gO3sp87Rr>u$W?`lB^1|I?}*E%fLmc($g{aqd%5ij#Fpy zUsTL?-dq3d756@d5Qs0Ke9vIlr6}~0C_At+2sFW z?=7REZnyAZ5QIT$0HtearKG!2MA9OpWJskMksLr8=>|cNP*IRh>FyNijzPM+-g|tW zbIxxp`%ThW1F`4qX6>0R8LoYw)KLYm#~l6} z{RnzpkuT6ro1yF|G3VZt83fGfIq>n5Ex#((whHRAJ*o<;&{&lqyIgI)Lv(AIuVYF~kxc+^$w3OJfr zPXL~x^$94To$Ah)cnts%%0_C$>34eI50eO~VYKZ)8PUiCu2*Q2jw#@JvHZOB+xZd$ zzF}Xg6d>4~8Rcw&Bz=pVN8fS+-Pm{U<*C_!EaG|YG6D!YBY@#FQRc94Uk^1&t7Py+ zBh7XKZ8{)9lrs(P&xVfYdmRu#Zlt13w`^P9brLJDo&&l2@WpQ>nId-_N8oG32(|1#icBz5%1>L?e4@({vu)?!A0}Wvv!Hy0CLq~vA zX=NrhJr@R20P_=?pPMg}J#rCNq2=twxCC#gmB=KX}@wWzqhr^Jc9F}@{ zI8mawwrN36cwgKOy(kcXw2Gt#bxl1_P zl>>3Qy*zCS8XpEo?VJ4S-FFj!g=CN{JZ6;dpgn0*KBY>@Gz!JGNOk?3lbu~~;XLJ} zO-2v-EIMN7{#^oi;TQm-mHu+?2b;@`5S}8N(4!1}KkWIPlAr1bV18rs^ou~RXwx5S z3q38xml#|BA=7+f3LIBo$(w zL?X?({PdE$>HV@lOcO^-#xIQ*U*&nP7(ZECf%I#n>ANpXI_2=B;9P6nI5?5Ex=*?v zjy{mspA@*{R%y{R6A9YKN6aRKbD zWLk>qmGSroo$a~@cslWdI5dq(xuE>jZwem)-ArkXFa}_ z=jcwuo`Xo2W_Kxgl3X9?n+0sH0RovK{lX2YAu5N!yR8q~PtI%4`$}W4eL7A>#&eYR zVmd2N@{u5({3tE|dXv!}-vm`~N_>Hv@Ks5Y|QYYNp2bw6c#aFOETGC)e zKYSmo!se60=DAbcpi0ecjEtWlS(@EQG*7{?>C}Wu0T_Vuk!S zFweLt0Oc7Hl0)%XFXpjFpR~$<;{ku}$9~*6kj_#5gn9aWRG3T3P!aQtx&2SG!r|>g zl9YQ{X$SBh%5bWXBqhM6tnPOp5TR zOf|7#T;s97Pm%x9zvnOmi=q1O#3LQ(9%qI$|5gk18paxJp0iFHRHQMZI()hti&Qcyi3L=+pRE%o)FGI=41L%{JzbqKB>*;_Hu_yy<-Lu^?8Xt)GN z+hdtk6wDGgqtL7?p3S2G%0xRBXu?7KNIMOl=djQ!9KQ`ZbH(+%`uJM+W~mEakg_a+ z4iJC(LqFv_-+Jz$h&At3z}E?LZxYf}w@hN*WifN$!4@3}I?IhvRGz~7?32u~z(OUX ztf)Tj$LFY6hRtO2SbIG6bcfbhm+Sh&9jP;}sIuO-lD7VeSzNI#3xNrtoL|uXg}43? zR97K#ob6Fsw-mYci?aB?kS(-QB3c9;=9^z=SZq2gR+@&=kaP1cz8KEcB^P8SsGVz| zi?peLGD$-nbTE+9!p%1ul%TviBRB+<&|krhNMr#etdlYUCy1a~>FV;LC;FzwbM?Eo zm_&(aMf>B$`quL6Y!8;bw)oqfG#MC5SQv(0UY?%__qkR-Bd~WT;En)I0DfcD5@oyV zSiPVx<9-BeyvF%Sc&Jn!OhDtJtr#RlX`(&aBVl4kgvMP?ZWS7|fn6+lIYGR$)X*Uv zNu-4F*FByjh-i2w_uGTZ)YAv=>2ve3gVJ+7ZnKw>|A}qDo>7*O^fBEK@vV4VqPH9% zn#J<}c^u8=E`02r_-HBiD}YDw4^nbb^7V74@pbgjjQ2gWepsgF*9C;fg*P!AKp~7m zc@9cgy_`sN%ExJ*IiJJIO)2fV;}r`tz%b*Bl4dmh zXCSPGqg-imxM7V~qY$r7zk#O8!R=lhX$w5T)r)vQbJA#HI~_@^)(!fAa~v;^&gU4$ zgksu=(oryqscZ@cktnonfbF1!uD0W2HUcZRG*&jFyXOn4bo3?J$uJgPi)8fDn2CMv zWkB{X-CpeT<-55nHHTLK3abM8?)OlIX4is}mKNGG)s@qCpKxXCU2~|I2nR~t8ff)e z=gW-MY;U}s>)GlfK`d4)se5GgvyjE~3Q6Zve=1YDz#(}mT4ih4ed(#s!g|0@5% zU8nQF!!g(vKhYemB7}_%_Hq-2TF})mcY!%|~wS zPWqEDuid~a`>NuxJHRS~e{2B@m0wLK435;L2wGHD?1MjI*h3;+Y7F*ygg6Av(iR$C~wPdijO~Nqz z*2A&qy-=~MW2--2$wK7SCLs1#1CGqZeDXIx%~O`S!{A2V%EjpCbVj#W`lms{I|*nc zDFRU{b}GL|^3#@5IInxm+ogTH*zMviXW6g^?0P-JAM%W9*G|?Y7e|>#3=6X(j#Qtj zeRU$LxOZ(~5`bn4Kp0PbFP-HFD^G;ybD_H3Ew(f0lH<~3(t!92f~mm{lgYu`CX=mB zV|C23Pdf{^{4xU>Z$p}&?cM2`A1zofRiQBJ)lEWOhk6WY|9j^J7lE=)trnC$decIE zz*g`#TCJeMzp>}v0GtWwR3019Ej~_`bagCIy*S79Kn7KUT2*)cC9#$mm#t<@;vXBn zj=ZA@yE=|#JvB}CRa6V@$yj5Gozrzb=U>mXTeR)?Cad=PWMqJ!3Dk@H_-*}iTTWQw zLfduHD0dc=wBA2YTQg>qxBVG#RYI18-rEE`8KIqpd-Tes3le5 zQH3_{G>^h+zC}){IFB|9JW!yVPX#oxGa#F=A!qCSEyn zkI`*f1fD-QSb|HP$6vCmD0%{CMV#`c3?X)p$5lL>#IxmEYjC(>1QX|l%?WXn@^*A0KmfxT0 z(6wVRgb5pX6VliOo^935=(8$_0?E#usTvn8d8;Krs(GQ@a8c|XcL)v$VZP&=tk zE3A&%nIm+jEcfn`{0Mv_n_>%=q!#&zvYun@)mhzD@fygMuTp;sL)y_rc3GH-N8|2~ z$3|O8?f*30G0=kNfdhLpD@MJ@RdE6cD=dfEn@7<#wq6AEiPZvq|2YiIy(-FXq3SvCo3 zDg!c(?O{E;O0-cRo1(b$ru9Kv3!*bN7oP&Y3G!EgITCeG52_8%)0HpDtVLEMd7H6M z)C*0#FW$@`ot@G81bg`ckF$xHGU5B9DR0JK4j;xkf#>^P76^Epze@pSmIk_T=frI& z2JGMp;AUxbNKkkI*h|GW-Y%Do6t%OTHPYz6W97xU&!=-2rnqwQ9LP}y+Qx@kD0Vv# ztp+D9Q2I$6k@7kB%i-Dx*V=+6b{?=(Jyf`M#+OIRSKh@_Rnf-aH8~zwCdYCOPOP$r zMlZ+~Ax~2i00^`gt4FiCCPjAgPdkmShuyHxP->kY1WX!h2C(gjdCuPFn3uL`Zuv!HC=#nvT{HT^%*?EHsJOapBR}p|g zHYT}DY;e0$dic>*e@~I~)->o=jW_|nzfnm5$S=#~7I}gE$L6GiJxx%>k~Y_DT?vDX z>peu#lVJ9JmxHGfe4mhnI@|jPIvi76|nsTr2_5q?=v<*#H7B zE#llefTlW0M)J%d$hzHA`XLJgN+(k?Lh3M4x91}deDhO+AwO&fZ0CmD`>Hx`Aiw9! z8Gw?oFtZ4>pQ|y#l=_+oM26u68xnx9eN zr%;5T86unD^%juK!j6k6nV2-X{Yj^}neasN) z`J$uw$335m++xc~&2k5%@k09A4LOTONgut&)>5ks!JEqR$;U%fAeGSuN}>dyZOBX| zHkJ0QF~d35v>Po*4;Hr*YWx&ds2lo0zS`IyxXtpFg+(|vzksaVIPO1MVji})LhI2@ zBx&ZctP;{FeGfnJB0F-ULap|$HT!Zh%YO%2Zc6T9=2dy^oXsf|CG>tI!%sG;;@iFr-mBhj#1~E_ z7Ezw0E1c(VC5>8XGa6<=HDYi8X09ZrxxY-Dv(8-ZcaRfbrF(J5t0LF#fwau`HY;0@Q<6$W zKrF#*w_FcE9h=`m>cw*8FanY6i>10S&5G% zI|&-7Z$6I%*+~#i#v?Zn0c}OflVHelavDJ;(5grT$89I0ER$g@Id^IB zfQMVj?Ds27^?4o^(`vVhX5rUgyZ-@dSwie{1-zo&Zbq^Jt5W7h20#PnNL$-pSOHfB zc%-F;&eNr_7E}YlaYcDU%kFH#KxnH#%VoxLjhz9c2boiik9;Q^2hzrcNke&Q4}#T_ zbrJl1d(pv}lW22{!P}Kl9@@MqR$_}#?`tN>-l-_<{{1!uA3W`@S+vyrlU|XyxeD z&fFj-c33g}UPsu*r&M6%t!V0=Lm!6_)*5o+#YU$X&l8bBAuh_D!sHKPY_(E;Pj8l_ z87QEpkNIu%P}0X{o!xKU#a@;yQLzx-gD5W+AMIwQla2)^=I;(i& z@xmV`-_IHXUnV2ax+(kwjOuwL_>`Dzq!Slhd#gp!w!axpLA=uAc&la?Vh8RqIm$EF90 zj>w7-czTv0I3{wh`^tGUJuXn>FXOq1ka9m1lv8L{VN&7OC?FaoBDNd-yUt$Qd>R>fene)4o(=7Cw!q;`Pg+uuJb2)%%t%Bc-SoU1nde$OZ{ZIfP*$!g!Vli5 zA+csJML?I`_E)v;z>jY)WJvQh0KX3Lox6BrMCdFtg8~68YuxZ#oCN---{iu=`N9JJK0?~45u-dk6t?( zt?3S0iu!)X3yQtTYi7?|`30i*u}2B`yxnR|IuolNyEs&khcVWo=N0HZ96wzvB16cE zdwVea)Op@mXzY=)Cl^kWR^DjObvC=&HY(8v+}mwr(grc?A1MwM((jPq{Kn|KAyZrU z)PI=OkD+ZLKDb_f2y>xy-ej}@`&nFF_zRk$Um?VYpVUJ)@D1chShE-zZ!p7uMQr$P zKZh36w^q*$Qj!i6m$$FVqnMe3qm?U%LWGY7Xy1yH8OLrY+7Q4TSvOYik;ii%W>yz` ze@T(+?7%UihneH+zRGPQt23bHZ%W-g#8m#|kad@~k2!I+l$%}Jxk!ORS>C5g^<8#nNf<%e=PK!9a z<=7p*ovUYJ^paM$mMi$=vok~|jT3cey?WY5Nq5Z6v}JPts8}xH#bi!j<*j1QnGYU} zDDtqe#g0fZ-fLlq$a9aWPBZhR=X~zpentIYLRAgHkg>M4tPl10-jG8N#Fn(y9UAVyhbEIy z6%IFTvJQ)Q@m4wqIpj%INecbUii5wIdiN1VZ`j?8%G4(MdIPQ!BtMl)_- zhH>9F$zVhM%zl)4-$XE&^^n>G%UuqNc~4I9-lK<#pPo0UZ`C+gyv~}um~y5&oJ0m7 zY~M=QmoFbl_en0Ne04wUPAT;&9yXK^UWhbTYoRrayN&$uo}=++i6A7oi8B!QmF2{j zJJdUIkMJYO5fBLPwB$uvO`AL=2_i=NcS<+I2@3J+1_l|TiPI?cz#S#SCcB;SsCQ>- zy1?ol6+|TWVfWm3`PT&+GTiT_#m1a%fY(d;a~)HXVc@D#nzH*+q$)o4HUSMQS9H-r zoXSzMYKU0)$ko{SRT5^;mWbWA;7Y?v7E|vL+tU6iCN$q*)n{}aj0fQmgJ>^$!ab^9 zN56l3zfZTU*_?JT7ue{=9!JWYj)tx579qd9-Mmi0)KG0JCu;D#8`C&-Iwml2PGsm) zVkQGcW4pj^5BaZmV%S8+!SucCgwwU}HPc#B4!HH5Y=@?PUoEW$6MQzbcleHnVBH^% zAxG5Pc@gP9k=H_dCl}TR_ZR}wcXXD{VduZUA7p5dd<9xq22{u6sObjd>+RIOdb<^9CfHb3in5%H3xOEWXey5ACEg7@5o+RVc zRD1ekf~5VzPNBWN}})-usn&?n@(xue3_S$2xG*Kr)KwRK-K&R%JG*vbsA;2~MRyAH{ib zcWKqdhg8JJAsfFE_lDd?@~otDLNiv}Re=CS#rhCEO2+uNSXcaL=%3Ls@0!iQSeRif zlh)8e>nJPyB;F?Lz%?5F2W6l+Q^XnFFc@K>%>ZMzNHpVT`S7(wI1+DvuMd%~RJdc~ z-n&XuNcCqX&CNe6;yW(dbm9mAH)2v%!*?I-1N``XYR$AL(B9ZcO5t3Z6O^Nywkyw8 z37uz<)MnC$8kbKxhHNaL8;pdV8?JNy z6#9VlF$HM-uew0%U0=jnhbQjfnYO`_@PxGhTFx`>_Cdn=4Y~nQ#Elhxbvja4X2NvL z!R~X1aJfHAnamk{Y?M#bSq6GmWY(2yJMFf{tp|W_o??2ljNERtnreggBWRQe-*ssx z6q$Ts9J%hh;9}^u!s-lqcgfCCyMb_`N2dUW=sN5>Ai(9dpbKv*LW`q>Ec=1`-AxwZ z1;$}Q7CO9`@?%$1r0Fh}72p@>i2PX({BXeRc#ZDlfPY7mpfp|w(+Xs)ek*XGKxbK; zOql-ky+fW#0*}xmpYkUQ~8d*uH^o=ce{5JO~M^Oa#w{OhvANP=O9s{odZ~w zk7*sOPx>quZQrkkeXuz-K?g)fTA#smia$0YY@tvtFq^{x=<|Jnx687%1ok|5XeP@8 z#TFXQz%gXBtp0T7Z2IWWtd#&_2HUmcyDD{Q+J>$z=sqwV5F6Y25(?YLu;)u>^JE-J z%$$S=v!9kc;#u|n@j?`HHGp3llznXHP{VZ^zWY=hXOEQV%$V>C&p?-ue@p~{-p#w zVZIZwpcG+n0U{?nDwZ6YJB;KH+P0n?)S+Tk|11Sk__xucTn4su7!(o**D1$>myBt#DI{q=-dwcFk-cZNxyE> zIQZ${x4lqkA0Q@zB0%rnyl5S?@B|+PK(KqM9$}>?W_AOenR?k77zMIH8xmZ3aWpd% zhx_$A$>-RnkjnmvfPVRUHyvC#e~zZiG9cM|UPM-Lf=VWPOY^QW4fJ#KUjF>-NrBn` z(GkF8#de(D*Y#qaeb{hghEje)0Er|lvX`do22n1!!DQD&8 zMfMW7+x@*_@;nbC^C!1QQXR-tQ0 z-;frP70>{I7hI+9W#4=D#yJeg^JxpeDhQU02n!U+aFmn;v1E)C9pJklerkz54rmD? z(Y`|tu;*Vxfc?tWHH${<9`OaX_4p>Ncw-Sg@N|bN)7X?m;e8W?wfoO2PHs@*V`X~3p1l{kDBXA!>L6B)wuquno&0^xF5pN5~ozX(SBIB7_q zWFckNa*HR?Q%iiv`dCxtAT5)CU9}<&x`L+e@&+}DRSV$~Tpl-hbJEIYJl&laqm-T> zv#&+9{Pbl9Qq-GF!V8+AmwnR<_iM)*vD>>b#fXJWyyxWL+qRz@zS9@V74PuFp6f6a znw!M;^!dwS`Kl1Re~NP5gu)?gI5ZYWVys6RD^o%z29VYyn)CT4wu0>xLfeCEJmnYt zFL8ELMc!l+K9;i6-@G!B?<==PzF@S+A;fK_@%7O-%Sa%+)BADU(?hH?A~N~dQ|T;~ zC_=G2Y)eakZ&^7+%x_~c0x`EY#Cy<#F%LQ)!-R!nR>75_vZH=XCjB4f*d(FSz;IZ0 zj}ZePTMwX}l#T#1rnrSj5B!#xh}Ddjo|bwYpS;5J; zc5eWxNuEhtc*h$As{8ApfKpuv)N=;Jrr^Xq)4+#@;TQ9{O5|iF{k@1N2YOLaIPGBTw~mk1vK? z^W7H$KNHI*Dk?K^Si5!v=NumTChpDONuQ^pn>^(s(DK4$8+S28Hhvb4EoByB)S_P;A;<3hgMr zJkZQ>l0%CQ%!`mjz;K}={3KFes*HJlx6hXrYyFC&wt?7;w|Z~_^CzTnkRt*bJ@Hv)uwJI zdO#_x7U>V{Ok^u1{X!jyrrq24R*0R^>QnDMKX`bg@@caxhc8&Q>(J0p!ryb_bGNbO zwN}`F&*>}h1#X*6{-6xn5eo?(4OQTSB7$a%y1A_!jJ7lXJT zdM18%=yyL$Y4b)MRl1rWIzA0{`9tMR|70uZr?X$05kW;ox^sD409Ye)B+LXmXaw1b zMBT6(6HY9r#6&Eq0uijf2Oa@YgTjfr#D*Xle-JB!=L0QOY-VIvdt--KZC6bWatM5D!35IT8ftkmeD4L*F?4zeZvrD#<&+9^LA*+=Ke%AlB$~J% zl9^+F?`u9zX;HLpO{WAeAU({aszl8*U+4MQ7Wp>+9Jk67)$Z^5wcU+uO4S3ov%7*W zy{*n(%qMC(O!SRr_??p3Dyejj<4T5%#s5pQNjCNg(G(t|T4%FFEAjPr$i*JwnX zn=#hf0<^7$XFIp|;BcbP9^*aD`f9T0gmxoC)iw+6CC-@=HI~!DvL0cUGn3(JRE`%j zDXa=|zaLHWUAcDAP`5UVf8Av#^!B}=*CSg+|D9~;v_ZKtKw?=oU zLT49Zxv|+9oP2BH=&Diwe&lAVr=b--vKUg#@)B>1Qm^zIL0#~5Nr!#i3DX!gE<6IP zxIkpT{I=%_^l71O@LwCg>D1@$y&^p#yQ5Ioujn4Mlk$I+5lyGpcz=an*4S8Lf$xGF z{C6GoXZ9o$`ZNHf_Vi^gJ&-1VN2hrE&uRSca;u=0QMcpwRjGPk9tn$Xl8m$nj|I{~ zzKb>jSsFYlr@ggfeIoiLdaVdTT)0p^s0sNm3!Bm=_u2se4Qe+RYpmxn<5C#$55@V*+ zVogXVB_7XsS?R!Uyt-VOt`BDQc-xif3L>L>EGRKhYG=Dx+QM!@$piV$EuILIVF$@! zvm1c|A62_eJSrUwCccl)G@H8eQNHtDu;(FAn1%7-E8wZ-aIA%Trro6Vfe|*{($t`x zAojut5<9dw`*v)aD@nZERQS`WL)@hnY71ds#mXMRlbUw)eJ)(GkkwXaQsMuI&giwu z@>3bqr?BFq;k}iy06H&O28q^cho+w)`0vERdrILn0pB5WB72oGg4n*$jM_g@#rD+Gx3_IvE%-=H^nE2wg?XR{)H z=rGUx%-{KN7@W8^aZE%OKp-r=eG*`+><`fub@HJZJmnK{9%39hT9H^MiwYRsO@Hgh z6TWupR;1Ay!5kZ9Of;GnMp%B=%eq1^i1$#!s-HsnnDH8ssPvgq5I>4;S&L3#Lbyn- zZ8?m_e8L?wB+;b*wc^0BZGIIvT+R0qcnxQ9>W&NWgnEM)c=cjwmcxx{PK9bF{HQYC ziDNXXSP-60O1?@l8OK*P*F0pn@e>Yki~G*DW*P36eo<@{7duiQOfO(EnTu&~&fJk} zLpI9pb$_vrk#>`?1H)%@jQ$izV9-Zuv2`#AL0EhV^olfZTN!79=-K?j?S312SgiVNTUbLe+3@Mbj|k(KE6J??g@-0m1U&cek|i2|U8L z@%#yAYQ7NiiF_QZDf4{aBEYuXiqcboA}-!f#_hkQna+Dz6pD}&Ehdr|=B~dHT$v7J z0Bb(leVY*{m6(Gh-4F?sg9d>|t=#k*Fsz|A2o3E3RgRPeNSGZs?yJ9E48ilGx<&w7 zVwZIAcD5c**h;2&)lAbfIj{R9#^zmcWkDY;J-=Vm4^o6nDl{TBrHz+;Q=YHQmB78! zp~#T0wf5(*yyOl+_~y_Zjc$J=3a8YgUos^|#**=~}el?IjjX+?lJ&w{gKSg^`LBQ)BGC-vt1Sw?Xg zJp9tu*T{qAM6Kc_2MV%)E%^bwsI6>)M$VmC*W=AI94!EFmC}wMe%)X9(+@J+eE;;` zBR*|I+iRg3A2p1f;6!%T6+{_ByzJ+K-Kdp&sZjY`yZ;VO?;btqCOH)OrqK0n<+@e% zg8$CkYnLU+ujIkAns+A}?AHQ3?Oih2YG($jr7n_Dn-a~F^}u@m^0$hAL1v%!GtecV z4-%F1+8`yFf!w5(5=G|B^!^UL-L2g&LpomQ4dxd#9guyIg;xx zgT$Igj_EfxXps-SR-oWq9Ymq zCv+OWX%X~0h2c~mZx;|6CYBue&p)-k+gf8q&(7d!EV!7wH&1#zhIcLw z&iyb5(v8T?_6+5*Bep0|U+!kI=n9fV8pq$`e>Ip-2-T?FVl+-#LAnk!y0M8a_wv78 zTJzTE?BRo!oy1n%`^h%GC}mtZwxld|%V+nAh0Drdq)SUe&7Is-iltRoC&wlD)teqI zR`a>)!2^b2)-}B;+-qbN0`t<-s6lZ zCy4SGebj~}Fq>3+gc6Y|ih>jo@>%U}AxiF?&^B(O94$`|I(_iJAAcgVwh7|-`*XIN zq;l~=MZ1p4GU*n9iroVVwgdYehaYOKvC`}kt&M8o{%c3wUdQp>dWEkGX^!=Mv+Sl) zNG<@FURt&#M1lyhQ13Y71{Z0n_P<}kB1v`lkXa;M8&^e;f2HY)wQGBv&(1ob?ADr~ zdNb|C^mcnxwndanE0 zyHoT09EE?Oy{DG6zmLl7SFzV7;-Alx_a&~!$M=+ZzE-6#GT=!RY~|J~aEn(yEVmq2 zB(q2lB;uX+=`h(VdUnbc$0B;$s4`=oQe`(BE9A3A_rLC;WaQbupYuN;*GIvXWa^>~ zwN`^!UpLuPd4nt0{{iNT-{2c5FjlZKeKnYM`z&}_ZAj`L2(l6k1q#*;YC+3__v~^{ zEUKYj3ZL>_As-%mvik+#6DmzqPj~;j^ zE}U3n!X3?cWNy_-u{{=Rxe)|j8%d_3K{~Kt^|8cXzz1R`GS>p^#a-^2>}h%O=U%)T z7r9Dq4o@Q!Uv7sG>j_T<*NC(2b!q37?C=Jbxfab|+RexFK8IT0qA9k3|$8cu;96Q|F~>ZB8+30JxFZT0$D$M zI7#FG(H11OA$BYG4&p&^1=F;FLU-SOcZED8`x%)22b+UA8UDA_Of0VF+ZG~LeI4wt2g4>Qm64zbdn>ea5pFwN-}l{^j^C@Xee&aC z4vu6#k)&e~zqC{e?nqEWFO_e^mZ!C(28^%Vw3lE{oF9fGDcEXG^xMSj^IKHXKwY^j zX+X_x37rXm6Qj*q82zkIM;MZn;Jw?Pu3gz0l7Za-JSpX86l`P0oW#2D!99 zefV&wiW(V2xKZ0>_Ot=5v*TH7AE7GX(CNF=)>&u1#C9XQOV{_#7Hjp}m^+)#TIEU{ zJ+w}$A0Mr_(pOgxU4?qq7@U0j(VWwGA#UN~Rdux-Mi-x(mea*+BRy>_IryugQj^`x zBtVOHjk_vMi^~AMlr~tEgO0$QnZZ5pEWDRPb`QM{>$Gq^@_T|9KnWcQZlo7vFI>)1>Zx>u2Bz_(?g;1nw z*Did*8pcoir0ZJ;an^>Wvi8Qf3wgX$nBs3`wGVS_l)~*Jy)px{2qf7(>B7aT4W77T zHXm(^wKeteRanIH>YDCVcx|+3wMcbKHC&>PB5Q%ApSFjz+YIc(#QJTC=+5MS)(R{) za+{6%&cz+-Q^7k_1S$9F2)W}2K7K0famHcA#UcIT5Nc1kb6OmnnCYO@G}0uk0ALsD z_n?w53K%-xv|A*6O%$q2I@RH2v#_RXDM}d~}tDLC*09c5dat*nanHx!PUJuHJIf z7c9qZ1=W4~J+oh@rH!uDI@^V2&9LVKT?KGGUv*V_(lXqyJxK{BpZ$cBDl2%~ zl|@?j!gcxd-x!6Lf69wsRkWx)4SpS#FsVo;FT@ zE6&q+01eR1151QYRUsLNENtOzpGAVJ(pVxX+C5hU?$ZjZcHTLh$xg9uKaI2k;F)Q-M(DC`haZ_?hA(WBiG%w^E71iIS#fSCF#56aI2so69eq>{GZz=WNT^v6XCx;?Di*Q zoTbHU5|kqstktGK#D%53#;S}=TszyR8n4-pnG1 z7kk(VdY|a=DfyBN_*(e5?N5XwzkK%(bOrQU$4{!Y1V5 zL<8Q5_=m4RbURDb0<4caP{D3sAzmpqNkh{M2uzSZ5r!NLK|J#x5bB3;W%PA(zwcGQU zykgmV+o|d5-+VTjG&MJ4wrjKT`2t;N#>*bLl^I`|T~dFNL{wAGrY@f>|L`|#1(ycv z^YRW{j&pq2{mbi56~{ydI4bSzfEw`m4xf_c2jZVt)wqI(mR!u{)gzc&ffNWq=!zFs z^~(Kh|C^+U;opSRzQ!|xA4!zwLw|e}hWDOc!y!~Q;*pf`t2nvOa53mnNA+<=_j$q7 z>x3#ZnxFZ8x6r01xF})5?sL$?!*|KzQFCtoU^FzOm$h%Sr0TzS3FkyCT!=#>%_ zrB4CuZY(#=7;dOvxD!*SCtUjDA8fVI9z8hT^)d0Ewm;iaXA3c*a(iEkU^R%mh?kUKDqdt5T;IJ&oS|Zdc ziPG<49QGmUi=@HwPf~dOm?xad?Q=HsDe0g^Z_`Da)4>r*-|ORRAEDJ;vp?*K_8SPK z#xyD5L>11i0qgIdd61G4>UT|E4X$a8)Jh*~%!%}gnk|S22B$)nT9|v^T*{;_MOuSAh>J?->x8p2>6tet0%RW%v! zABLz8dDW)OIymc=CBW}ExnJ3D!Mo0^<;q)l;g~$=)Ga3GLL4v~r^?WVW*nyXNJAMs zjq1f+Qf?3~$kymOGHeCE7TZ$Q;o;r&US_Ng_oQE5nv;fXVXpSC^1HA}>c_k;g1UP? z?r`DwQs-G|kuB+*@{C?zMy9Xp`Hqxex_kf0?wiY#U#9^O94hwT;e@ev3Rpy<5n&}`5T{PhP-8R1WyENI-e!jFll4j=R z%k>VZHb;)W+6z5D#+6ls!tJN(sJG7ln(cBj6NG?cfBVf!x*}~atPXb zLmKV|w@49xMbj?;dl)R$IL!_TyK0uL3#GevW9Qq8P=0Lag8Ez!d|izAMD(J)pD*a{xJGn<`eTtjRfh+1|>c@Rfg)@vmk^Y@nt7nF4Y+D3X9K9Wn+E^k?SbemFcLq!*&DJBHe^*%aK$JgSJFxSu ze^(c`lX%+;dU}x;=Y{s&e8a{B+Yg^#-K5T#caF7AL4)o^4HD-2*i`q*QNd9ICkcd`qff~f;UZM_s*v3m#Gsi zi=i#?gmeqfVLGSM$SRtt$~eOC2|!PCT|nIOd5bs`{xKD{b?A0aj9$5!HkJLb%e#}H ztV=v75kwU%z9Zx*k;qAmGdFe&rV9yYXj`l2&N*gA4{^czS8%!oot}Q3P=!9R?VX8W z@UJ&v+{5hIEEV6wlGC`X2qAnI-cEh&p};9}w_SAYiD&B#GDFb5p=Wp`7_3h*4M6MwS9C#93+VSnfbGnxr-ir(eqL^ z+ox?5(HoSLl#g!u90f-XxGn@#Dl^pBOf2B(k@4ZW43Fl0zSw~xF3(8{wJwd38zOKb zIchgPl6uJPX7=N|PZXJ#eG;2O0^0KJ79@6Y-l5!|cZXTeG=_N;`y-V?-9Y1^*?aN_ zpadf1Du}%{sPrNh7Fw_+ebM65sLa11u_WLbrYL>TAsR`GCFduCpHB<-?el0T6bETX zII>Nz^~6J60$UqRT=73A`MV2kW5Y#UA^6C|=E#~877 z*!l`dg&!=|8*Hx&IqRNVT9C+?8eu*AlxDnnTw_CXkOXEtJY0>b$pbs}KRbzEiO7BF zTIn{(qY zY?^Vh)^Iyg4#tP8FfM7F{v9GAX$rCG#5X-!pIJ8)`Pg!yoF*sR4hXPghZ-{#prdUq zeJx%*J%W*GFhr~wHiJxLGuwq_x{#90K_ui2(3Ec`rN05Pzk=Q>XhYCQHJ?5r=~b%x z`X0@>VG5`jZ}t>OdZ4506tDdF_YtUuzHgnmo?vr8gsc6#P3X3C_qsrRu;hY*(3w(A z^rYP#jGqgh7wO{2q(EG{`8_cUXm=!g?kNo~1uW-vhJn`8%7T7JJuUFpbD`F`8XT+_ z)1;kUJx?B9DU!ChK))Ni>JkNMoG$u1t&n}xnQ6X}Zt0}?h={kSa?`Wc=FiBK`~Q30 zjP6WKTt}5GH5H786`1rwG}Mex8kObl>;WAI`tYzXkgdoKE3>6qQ6dHGtQxpWeznpa zskBS4*tTlxoFav5d)gkw&AlP|E@*;!~gux8Tx-Z5Wz?P)lL4tm-lb{<^Mjt|G%s~20PmO zC3dzmKu?cQC~^)$kwp+tkSsX}MW&D_Ifnuy z=M3N4KJPi_J!gE~{il2M7(M#m6N;kPwf0_X&UxS0%?xLUo~M6b7-$Z1YoXur_l44B zAP@z*jsL!oS>s=a7w8>fQC$Bo|2kD;ezQSL6HPx*X1~)5R~C<0P7k1eYQ^^Vqa)RE zz^6^I0lL&AuiW=l+a34&lc4zr_)`Wi0mQcP?sC7ez!v#48q11w8bNb)7ruY~Zxc26 z^Z$fyZ`+nHg1l+A+0zd|7oIId`u8G8<}m?f;In(T-d8qUqZu{^GNry;ppX9hz9is% zvkz4iBsruc91mv#vR~i+*AHF&`$OdKM*zWW_uD`JG4KbFTMr(3?OuK7L1ZCuplz>qqfZ7FAY`{2YpYQ>2cJo zn*aJ5p~dnz=gT!bXod(L;liIu>`IKg9YD;UHGr6T3drzI02lT8QbvTfMP1gh=vMMp z&EM-2c&vO&4?^waeyJMDlz$;e)(rtSz|#N7607^@Spl1aOMA_r1}q$&%Zq={{NRjs;B>l zF36qxSV*sbLM!g!<`Q*seo(&wkq35HT^e2}i!MA9JDT5J74X?v1%bux7eKWhvmvkm z#mD~EO<(@xOZ2orn(#({KL&uyN0t~AeEFqWbA`>E zc^ZIhmQMjSuq}&hck^jp z9c2a#?{ro`^9;EoUikwluK=PzKzF9mZymrHK6J)$l}u@v7x@7ZYWJ!uaGi}ES5XR@ zqbAI(YPO#6S~d7wT~>OJY|^X&6T$ylt*^sC-X6Cju*>GV0%`a-FqXzSnThCl9DMgLA;5nD!^4`}4Nk5@6NM7D1>dsrg47Z?A`tnPPmtJtpR8ZLGZe{?K%T z?*tG~8&B1uXn5Xvxq^&{31H0;FSlKIs?ox}@Hn&vL{_W=4!^^TEJYiTbl_M}e_oY> z26nsXGZ**)pb1pq5Iy{f`zB4y-JHs24xl6jikgbP%|RJ8!a(i5jqO6g(GcZr0)%WiJ5HTc0h(QeSDQomq z3+RL$6g`xaANB$Xw1zV{(?hAH;}D=>=a)0Q^@lrH4{N97TyJAnGf0w!4n|uUJd=ge z?B-m+ii&Yy_!1Al@T1V?>0QNZ9`F02@STXX*j|FXJ0S=1z<^5}`&XY>`Mzl!eDc?S z(=v)Y52~jsq10CD6E8Ulm2s!Juyp`GFNuj>u;+u79s z-#_t6!(zdofJ(1(f5K5`C|xSRK#O|sZ;FR-m}mG=2E$p~1o%72e>s88X6)Q_-0qq9 z#ZmVJ03W<>od9^tym1O`r*!AWN)U?oEl~3%Ycc&K1O8Y)i&;NvNi$PeHP2W zwJ2aq?8|J{1bM5g>Jaf0Lf+&huQC7_hGi?@X`CA^)`Pum^bt@kH_`xPi}1lr0K@SF z7RZnq09!_#2NPoth$%nkg=Xzbx&-YM;y8<@H0PiY3~tOegpdRp-J;*{g~xyzKpG0+ zAlD*X@`EMy)gj)JTKx%AV_&t%LbBMehLC()A(uID}-JOHK`@{oA)2XNQiJqmk= zrojR92;5&FB6d}1@-dQPQi>a!C}3vPxk+hJ+|Jf+bGH+aNRwBESNSOX-!LA&C9o00}o=PAt&GB3r?<7}!bzA}I06cszj43h;6)^txPc;Df^XhiQKc zu1R8XF)x|Yc_K>($pEmAmriMN|6v31baY1YbS@I&Ad^~yg4hHOip-S{02If1g^;8S zW_{Sq?J+|wWSPvFVVT477&B8TIv2{9S4V1ZFY`Yx!AkUPJ0zw^nR?w6SfH-sf5oj~ zgVe(l7bl(<-9Jov8@rMb{a7;pfOnr1J)m$54B557O38GORIu%#S{Ffb&_`Er{@96j zP-DkRre8e;NX=?8xa>9|@nT6QHh&PPR4P9*>VYovEIN(NmAP$rNGiJU$# z2cP{|-97_We<>`TzRBxC9?u@m!^jlT)jX%$fZi=@&8$m1S<^cxUEE(cTCiAk4{ zn8I5((#}?m$v?|eEm1fEY7PLRFHHqd9B!hCg?g3UFX@FpIs?!j%Z2^3J1ah%seG#P z|F+$N4e}khkKqNcVY8PDuH(srRQJWdap6v>*KMS91P0Oii)cD;1J*z;5Y@?4xAYoY zxe%u@F3+A~FtxlPGbPXsVVFeVvYrTrx**giZ)MM1Aa_Ix&T=7NeSiDrZszp{-|RdN zuxRZz(_9_WyNC7fATbJMn(7&PUt9 znrTN^i2=oW%#n%2&S}4b+p>1=)s8yT{8G94$JRdp?bI3f4SC4!AI%?imObsTM7Dhr6obGs^u<`zQ zT%k1g<4y7junRaSiZ~gl?rJ~i=&ajnn^vj<2EOstkrE3kJef8R%B*5pn4dO1Zq@;> z7C2+I^VT4d&u{kO!4MtIKc`_Ge_CYp@8bHyH%Xoa$!;OZo)wDevW7~OI!X9Ch9A$< zwxgC?zetJr2fcvF+<^yf0FDW~1JsZ3pu zcUwlzZ&EX#s`J}ZFQ2=HbmE&24_Vn1S@R_B+KPIe1V74NCv8iQkE;4JR&KR@;(eW7 zPUM@JLR@zOkZeKK3*`2#nr}`fVGj65T>T&a@qcex{!b0||1B?L_HQWoN+Avxq@Bx$ z6a1_~4xEAGk)w-)1hh%ebP`c!y-TtvlmA|{&%>sv&P}lXOWl_4(FeH#jw}C|1^(^W zOzMl$pI$D~ZyjwK1_{+`Rud1ZSM}y61_LlxwDq!f{j(73e}uN630LVU1So->~o ze|}m5Sn@(ca7whCEN%{=7`rq^pxE_pAr*L7Q3nwXB?ynZSdi~(u>vtLp?jTekdl!O z_&DbP@co_R`O#uEFe@4efO8oHJ-&~>bF`-W*rDU8v-%`}w;8;l29t;A?7vSP5Nn3s zH7~mHk5U|}1pjH_X*PlJw^!gXa6*|+Wh*6Np|jA=u&O8IlC1`aAq%Qm6A*uB3q4&S zwz$%grd^jnSzcZqh7PjWf_lcW|_`IJOOV zT>X$;cpZxEIsy0HGUU!C%kjI*hP_5iZ+_6*7RAyZg6y}86Zmg6fs7&?4pGpnpyb0k z9dLiG1An4ITvw7%ci9Pe)@uP)_5|dZb^3XHu(1LD34Y=M9#)m$u=HSr=<){)ytP6m zgggP2VU^0xg@qi)LWUi;PHNqbY{~q-zx`1>rHeAWi+%V&GG_10LHwv)SrK(bZym6f zOE#>51F#Ypk42B@o`Y_+N@WDF2K(+Z&wypv1xjP5D(7e5fDo&F>*{GdDQ{Oub|e%^ z?|h~ggxhxIoKNJmd@JoX&iz+;*2JQ_k=66j3afXhyGuRcuV{wDVZoz61@x;WUz8Yi z_2mu)LJ5z+9(PZ)ni14cZNgaao7VthHBy_)&YzG53x(6CYTfcI0A}M~`C3{#fCabk z8^4v2x^+yGN&3zTTDySorX4Bpxj{s^8hvZ%7;?8U=fo89m;(oWA)qD41!Y2sl;BSB zEWu^c9-e7usVOE2tOQ4Sk)srHJN{D1e2@T|^a+KMq6KF7@9ly=_p)doBet;4sV;x+ z9pvhqar|>Vc);}l#npdZ50MSce(*FFuWd`6fuyM-gDW^92ekDZ%15ANSrZ(7hog{u zYZl#tcdz>?CJZ2;v>luw>K~x_cV9Cb&>>L+i!J3hDfjxJC)?AEvcDB0fC(#i=ikiF zEf^D-Nuw?o3OpB~ALi=&-FH# zwEf@<3yv6&2^$wZf;boWb3D%51}kH42~rIQ@8Qn;*0ee>nas^xf66TaH zxujnU_M&{j`Z}-L?_m^HN{=yT3*4UVNv$RFG)$s8fzR3TT~qErOF|CQo5OV5v)W;8 zRmdH~lamU%agKl#R|WZi=|x?JHPnc$EWa8{K8JN@iYEt$sj|_~<1>S~ z(lnRYN`UrtB+d?uG>J#o$9?ev9U#@$`cYcpr(K$u;EScO=_A5;(kt45i6Cr#t^VT7 zil)lXK1kXL6yMPcrxee-YnDbp>8`nh?OMACH}iTOc_H}g-Y%x-6cm@XP+uTr46&FT zgJfZ*RCfSd!&osmX_R#oBF={bQ$LyS+V9JMgL$HpniK@{MF~ANWENsBbQ^n)h-E(5 zc9C|`hUh;R><}~ll`PUtD}}bE4R7_lJ0^O(lp*gdSz{bd@ov@EB_mD1eh(Ddy~mGU z%e=*GiDNoNfn92+ejUwTq=f7yLo^=QDxYk&0a)CHDn)aR8?Z!e()y(zA$4rIRfuX{ zq#qoB^}z4i%DdVEuowxPb7C!M8M>Z5uaoOJ#M1mjz9-<1ijqlK^gcmu_eM;NSymBS zr>U^JDZ64}A0fy5cTT5AM{DWk2BlddoQoB#toNnC5K(%b@x$4VCL&`lPQRRufdTCy z3RWz{KP=kRB{NR3kE61uCQU7e%Zfqu%57rT3Zm zeeK6vp7IEBKvVe*_OgK-hbuDm@@%V@ zFI>lEEyl`zT$nW}Fx?fhSI{xr_kP##;*XR{yNTv);N>4?s=R%`xTzPhBU_;-dpMOP zb`N5D7|-I?pfYG#C$}4akTf@G&b5Ro<>9=EB0bQwVl=0KHy3Tqs&8#!9;Z{5EpzJ#r6Z4}?4pSaC-CCZR zuLJ>)E=`*73Z}I|ZrAtkX)6jUiE2i&buUsj+*+xtFc}*(gt9Hl^ObYX*<12B1wDl{ zlTxpjJav`OoMs%@LuGkx;*-|jte8I6B~Z%rs_$tlG~K>}vY-r!xd<-Qp;cip2b(EV zDG5SXhxdGr!hO=JAK25x7fg2}Ll~4o4J3*m z@IE~V25pfdof;1>r$(uzR%Sy*DS@u5x~ORmqH(YDsBo5@A@0)+i=DN1UR3DTcAJ6wWO5N${$c~KNV2P_hAO<(os6IjuMoUgU{++eWrs5t~d z$^dqyFIg=OLIW4z_=q|nDBvel#&)HOjtw>_lt6SD$IAr|C9f1bPCRDD*4(AxHIU=A z(h5Q#FB9tFl7H@SWle}UlnBeH4%Vy5TbO)B8xXnCIPy)tGRzbE^5)Q3IP zHSo+u_34?dI3KYUr5-Vf9Y()`T9S}-p&9%|OEGI`3eq>{BY5mJ&mYsB^vLAjNflv4 z+rh0^^&Vgb6UglV@+E-c%lRk;nH{X;19S1_)k}Mn;lv@?G5G}0MLE4tqRirw{`%sD ztCkKJ?bru{HZTNhN~FFnNxB^2d-(H(k_nB^FXNo%6SO@uB9d4jBSH;mWA&m8e-M8C z%+%$8{NN1Q9!!O(*DoDLssO-^EKIM4+lx_`1{jHcP(HeYwEn3;K%pDd5>@=m!Q-tq~Ya=J$XLq6_bB9c0xj1P%~ zZybGUXxZS2$=xsukW1$#a&HgblX~h);k&7Ptlf+Ha=EJxVs;Acn2g(<_T)+N`((X!tKG%Hel4bb3xtw4w7&B|EnN z;KkhdDe4;tP);PH4$i?n*4iFpm-zY}HP`H2KvBhI%~f$Orc1qf6MgWK;8V@&;0Hkkaldpm{%t(NolcYa zlcrn0y%&A=M#2ZMtU9xS8*<(xQ9nJlc~c5)30t+&%Z4Nm&HljY0-b`dj{cn!nJ7N*LUq^E6xwa zLL-iuSYwNsLko)$^_H(3inoX?Xcy(-Nye|cV zm(ya++1~8v;XEriIHaonq9SHmq%;bhH^ebqK->U2-t=)$imcJU6TVsO1di8z-T12f zPA*b%w^};Mn4Tt#4zC=0{WAfLIE|{(9PU?yb{I>NTr-jk#62#DA{n#PLLh2DoI?`nB9K6wZJBQeVU$a5%yY z)>x6H!}brZ?D1bm2cCa)%C*o{x{8-=yx~;dy!I6RAB;dZb@*+zqBb?Ejb4 zhyNPB{GY-h{y+Y*2d40YZ1J=9Gcd1L?uMXnvBL9_Qhg;E`XHTY9a1}V=f^>uyX*8$ zj7Mh>KED>kY&B4?_=9<0PYNKbFOLZ5fm!)F7|JPj3wCsNS^(f@On=B=Fx0FTu$mMR zb^ZQna_D!h`q-lROzf6rpR83iU~DOH-@N*7{>-;}>l&O`XnGhfvfZ}3`hI!1DB}c> z^H8VZsu-rhze8Gc{jJ$%2k|g!0ghUe?@nM0G_g5@?k^b%K4!z#c+m`OOPpkcEO%Q1 zrsBUzyEF-bWY8N&3mnu}525s}LZjxZX^(#Y4Rp(s3Lt8CtI+^cOFJF6Ek7=hEvi%a z(GJ4o0b09)2b9MJ;ntKq4wm~{%dU#ZDT{0&*A{za83YPq7C}ADPpp~oB+T3yXf@2w zL#g=2Ax3^V7+NLd_#*5;rc$bN%b?j{UV=v9JBeZjV}-o`1SxFMYdJBbEKe%H zv@_2k!cPyHRyaV|ow&;cfW)EMrsH926e2Uu`gRD zphF3n?V_PEFc`PGJ1&2TuWAXSsRo4*2KN>LX!TftksuW1_5rH9g2E%Al!Epu{%ula zuwQEypMo{}HK+m1IIBR3IyeYw>DGyR*~znDO7gngp#7$X6`D}!LjZ$EMKu@;O#rmg z8q|9j`uc*M>>jNnH0hW@-W6W@xCs<37 z9O*;oCd&}6GC5qz*2Bqzy2bO2i}UV3r$7@^W?P_H*%y}v=0TR=JGBQ%g&*QIZG(Ov zyw-6y^!Wp+51>kLHSr76ZtMwOZ}2B9HHeHGbf6od7}K(DxVqd$AiVM)_nVKCLJFR?ubqo1-Bq}l4K(N0l6hgnwIJgFcb4}z@Vq5;nAyQK&%^i^8Bz6=weSW&r zy$1B&e)bLnsvD1;DQF>iu%<>0@+Jr|2e`@dylJ34hp#?7-))nf3rvd$yJ5*J`w#qQgOS z9+{zz=h+V~DcYkAYp}ShLb&UO>j2nugF#zV`ieGu|23yb0bpQZ`p}Lw-d;Iq7OKI^ zdPKz9)J@})t{W+*>!Uw%ohKzpj0eV0aD7D#2(OYH*}~3zMdMTU)w(+F6iQe$jYFyh zm;Kd*aw6?MN$}1bS8j2$r#68}0PCALayzk_+s{Pz2AVSPJ&!tdZeEs0;F%IiC^Fkh z!CTz}dhQU!oEQhtIq=N9evRxNfe>%NeXLo}=J@hP)RSC%GB#)Id%@p>eB~y`tVw-9 zwqI)9QQXN@UL!_30RB{>}^a5HK)7p2{mAk%8rPVO!(hE3?0XlfTVlxd^9>1i*J>7h3WQ0FeB5 z)O}byAwZ-^$ToXY-w}_O@u+6H#nE*_Ln?CME|gPo<8&IdH*NNEfHT>Tg2{Z^Qr9k z@B@pr(|b6xyas9kae(*$1PkBvmpYY46rlX-&m8ad3s!LM0B+(#?`&UOdiur_SP+W= zF-#W(Nc*y1>!wU4rJivz774^XeoIKjoB2d9{F(?;FpQ+EdCn&uKWagWl=OBWXvi4V zLsF}=e1PYdKF4{^uLrcdWbm^tz>njqYMeba#Vxt;MIo zX)4}-rE5#Hj+-G5WHWv73aGR8YvcsD#c_slV>8}W>6dDI$unH(GhzTNk?V}rJ1Wtb z0*y(M$%i?HQurE3Z~@u$EI%v`=9}-5oP=*~>zOTV8(ISIQ8Z5r0)4`sD!jkY+%rq{ zfE+%KGVwCt@9`1V?ee71H)`lVVELVjsluWLqN{9b2 zpK&9zoADsc<~u%k<}pORFX}k|^TyU#&g=#Efetg!RNczR+OMip0e8ENmlJbP3pgTR z*TI=j;f5sYQ+KFb^o?juM$XNLGcr3&kp{Y%Q{;qhalLo5bt6c=2BBEy?ga6;RWOD* ziiieYA^v>xGO~@yjZB%QbyqS2q*gvO&^k6^Qjrt$c^yz}TjxY|=Ip-MH&Ts-g>h`P zNB4Y9pNa-NAl};a&B6ul0$biqxDaqnwY!N}_t(Fzy?C$0gtQyZ4I6sT0CuFO0g0n4 z$C8l5Ag{+OdxO>o*Gd+ph9jr94aF_TK`mtGv+2#)ND{QwO0CJ13Qk3kjZB zCzCa&G~tP?If+N0$#y$JZdn49DJk5pBpcaQibCq0a)8t7bs2TQLV>O%0gRoMcCY^tkg} zMa&K24X9=UR>d`+=tv_S($jCk%oa}NOmGP3yd6W`ZA7NHdBYgAy|#I4&yQEyi^23s zYzy_=IK7pW`yTTMTHr>>8|FuqI>W}Oqga=N*+I0+E?u74`;+7&5BugA?Z8OTIs0=v zeU1t98xTnp@UyYR%9jH(oB8Y}-D<1>!nBwpxp*8m?qK+P4vEP!PbX;n?fOY+x@;2d zdzKy60`fh}l*?pO(se6f&bH^mUW%YKHR^e}v4=_*LXFpqiI4h@e_Rfdhah!+TybGkdU}zOPd_PB zuP`OIoNj!niEIY66mEu#b3R;bC2JFEa}+UQn4$MclBdS+!CZ9&k6pIe#A;b zVlX0lp~pDV=HN!yTzMJPV;rTt9v#p44z=0j_lB~4_TgU1`rr_ua#BE@gOhx=$7KI; z$;;=K%#m|9nP~vQMUKqJ6oA`!#QpTb4QcfUr@3FP_?DHLJIIW)53AJp^hE}JHBga$_b=jWnoG(fY8G&7#Y^9)Gp z;|yN?2ga`wcq(RR1Gm!rl~kc;Iy0jO9x$-~0jk4I6{q2T@O&wT!i5idQ~v*>?!)~n zrprJYpfOh`4@rc#8URsvtbEYGpP==5u0oq-`zFB~sj^NU{Dmr?x#%y&Rr)bZ{JA|c z>*!lO@~ELfG*HCfb(5!z4$U|q5cqIC9n3PmP<+33HUnxQigKVS7(l|0$>n2TQ+j>3@*`4orUe1Lr1&Yd)8xbgWdvn+wJ1=A^Xnq=NNe8 z4v>LIPZ2aKR-{~4#a>5Y$+){9zOV0d=^f0;0b_Xec0{ML$ zf=}*~&Wn{&M2MzA*;9BSzu`NTKS1kH6~!XUw!#O9Y7%@GMXmG-P0S?EoFO#^Q~>YG zP?6XX^mIKQB=8E$zC&=<1Ohh<-faR0$4jc`f#p&9wgfey07+eg)N;A2f3RMeWSYKg4O}MHdPJLf7{nHGI;>g@@Zrkz?lx1&%XGRX#7 za>hFDI)?N7pKv|KlhFF!(}U+kcC@W{Y$(P-i9IKiQPafc-L)jePua`c=8$IwCMC8&7Br~jpSP${jL$*Xne?bGB}v@;^rhT*0=(9f203$ zcMHlv&A0AiHAdZ2TL?|e6J}qEd{2#LD16W|q<_v(e_o7w_Eeg=SpYs?>2mujXmphlkB+?RQ$8be`nZ7hP%bT0cS=V8}MyFDz*7QcJ>h zJdf_AmPCXOy~bRuL>?f>Xoz@30-j5_&+It_I|?{MPrRYb^S2)A&?D8Lwto*S2wSyxT81Z-C5k@}2DiY4u4URoC-8oWyH7 z{mxa|BdIELI#hptdrYq4>X`cZ*o;+d_sm8*E%vb5PzU_}++EPvxV=-JS-Y4pn%xnC zzYPmJJBU+VB@j&E3OMw16>&cVtwb%M$KJ*26 z_*}X?yNj;0WILjc+U4pLa~(4i*H472M`Ql6*?9lm1s&vSlG_hMT*Z>252(%=DAX~-WH0 zvFicC|8$~|R`jD@PljWbNBtRL?T0PT*^QvNo`=8ESi>;iYP4VLW)j$emYn=)#r2oe z-;7RG*fLeqSx9;%aCf$Rg)-(~VgV=d)EfzA-xKcqe$Ysj^DYeZx@7!_Pp!MVi15r5 zxPGX?zpL7HapECIfSW~|f7zgR!M;ctDYu_XI#zKw8$wa=RWMBKc*%mu?!_~NVQ#AS+CC9IiQ`)R_6;kW$v$Mk#ymP zPXgHlG+RwM5Z|XI;a2**rqA{C+~h;NPYgUOC(rAYoq3F^Xbi`Y`0kKr0e1S z?v`By|FiQHA-krbQUGq@XK)^=*&J&rtm z-HA;*9N(dPuGVM8KS036@Izk+Z6=l|^d}vhWivEab@&F%`Lb`^zb59ncZ?r$V_vr2 zk3;hMN9k|xY4yLoL||&|rU+Gk=<)2NA5~1TkPbX#!+j9Pf>C|RI$rpokPBD)n-{_7 zXKi16-fJ*P$?yxmh672i8c^5&hNrZMa5krNRt=i`@20H4-viy7>GsBp1LHeupFB_33Fz%ju`tf$?LZG4m3W{MRk#WdfLmvrd?;T0xG{_uBnY zQtO9KO8T5L|FKsI>at}};61}49gei-YxxXjD72!F(SHOF--66_%p zahWfNfxEkuT+etLX-~ADwB5lJ5qL_4t+b!05ZS3Q*+4%rx_VAU?9X*0r6A z*qi>$dvIjNO@v24sI;APTBM|Q87~o;oIXRJ4|{Y`;CyFTP;3L89gv)>Mr?-^GB_7e0bI41ub^x&FtJFs=F$PJl*i8_m)8C$DOw+gRyaaSb;FJ9kYTi;hck*ipIKr=vM9SwU^*jUM%nbq5_pr9LG|0V96T{=S-(LLY*-D-;C zxlg9=UHr5nyd0So#I56C>jIvCv)4s#XQulhB!8L->Cj&A>a-N+Mf9}n+B%*i{b9`A zVrn%*)Q_&u)CsM3xt?Ja^bi~tHL?p~jIwQ?Z(Q>sd-=6|qfW5ax%D?Z%(cJc07FVL zV&u|pPDmGO&3Ty2bbuu^HNsmbWbNr~+F9sS4th@u3-3<$FmX9aUCEF)9XEbreY{p5 z_Tj0NK$I&bo<>@|SSH!`xJFvtn5=kQovfYH7>cyJjkFDiKaw7VueIqC=+rA)i!7B} zh;h}rpk;cS$Y^upxkV9iYn}^KTeW&UR+q!(njDJi-8Q!Bbe}zEf4#6*b%VtMmBB(3 zm#&BF@_ydFlI2zwSH-kXuN2eE>Z|1HjO#3OvQGM_3^YlifFQ+Ehc3~FOO2;UJPwWz zsnPK?;QMe?^l0m^W*h5yi(*+lJ?i!hf2Opw$TzMwLqc#IBVUDRjk<=+AdQgp0qy$oOjM4<6a>D2##%OVe}0FIR>%+4)YpdTFDb zkIWN`Y?E!T-(3}M{pg;(bNkU$`n@|Hy5Sw{o_yoJa`w((s2DPrv=NcnPbUdi;u(3h zPP|}m2UdOs*V%+1b=;1k#p{J;Z;qQU5$n$Hm4!~#7IKzUt{$)VGx`1|+jf$^&SteA z;o55J$GM(Ro$IL9nnNP+%G;zxZd2E#vT~udTb%kJiBxVh7#lJ^*HY%bGZQ&!jTc%Y z`!jQ>&DNN0x2?U_%*|nvBK-Qts&NcF?r3eV=bIgF(E&rX@FUCgH+O4Qjnrlii7L6_ zj=Wa}yWB(EJSrXK#8&1O>BC%CA7)VVua#R789p0i8>KVv9nbt`jIb3!O%-eQ?Lzve$w9_N`I}h zR`sSejAOjMDZ)$=N4zl&WSX1ow=VY5uq}o94uxq=_!@;Rd?VNQ+d`*xkZKLY2kxw#*~aDfyk^CpqbW@W^MlG2Ol zANi$6#|DryF3nq>@-<$jD^Ur{pklbp{Ti|SDlPo&@byH3n+|r_>>t(}s)nygS~$1C z{Dl}{MsDJHz8jwrA4nu)q^{5%+>Tph85cW0j7*)R-a0ER$V>V|(VD5rW#EZ-NHzBB zpsk2$H(uDow8>>S3-V#t37yx$-rU^~)=imIyw4YopOaD?o_5|&c`qko(gN@0vqtwbWX7wI~Tt3Wnn17OwUH;pX ziToiJdsNJTL#pxbZ)45rh>c0l7i#ZEeO)m*>H^`lS^McXo|5&Z+nck z-}vXX649Bzax90;(8-z8&ab{#Y0qazRpWAN( zH>h+$==bziMHjlWjJGG%kc1)R!MU*Sj7{oS!?oInZfECX%OB0U&D=DiSzqQr?<)8_ z08#a!doHJUO;o=)OpbCR@5h5Vs?N}@>Fo*|?)p>P(2&;0Jp_u+C=Nb2rY#yWTC^x8 znS2h?6RC`=+GXg4KcJSnL_l~VM{({c4ZPxdg*H4QIQkO{mS8V+3a1|rG)VU&4~8$i zZKN~|Wx2+oO2FX`oFz?W-|Ue63f#5)+IHsW`{ngAj7*^))fR$kR$` z56v;Drz|PHp`1A-TVm!mLW{OkUZNl;eIKY-`~Ur;XdNBY&+hIn|MXa+HV0RQuzFv+ zKzLM+2Ak8N1YEGDz&IQFXDGLzj@tM29MGYJl7Iszaq~}1UOdBIxA=wIC=guqLk13_76N7gCC9I5K9UueR^BXkmT--hwld_#qCf?=Gxu>&~xww`wBdIGcRD&>b` zU_?>|dD)y<@Vf#lx{s}|?L8oN3O_$PY2{Umd)Q*g+4|@J*d^F-QurPtd_(ydANF7D z6?h6D{MEiuHn{?aR`ApJ2n;-|p%h9AQxErU?99=8Zg0`#wFtyGR$GY;qdKqsNu)$QOkg>?Gx9M29{?;3InNH}IU7Qv+c!C=Gm3_!Z$qmUaAoLGw?@|A-;dbi8Fsgf?zpIU z_j8ALQvc^k871_P7UHA`0H>HJs8-%ZQ`BDwN3qJIrwTO-gr8^Q*)15w@mnRo|MvB> zt*ptXsuCbr$cD`LTWAk(#pFXci{&s1U(9-CD3m(6>)rlb| zo6%J@Wjzez?YK+&yhPLR{rY4Tq2Ms%_o5c+W#ILA3M@*>iSK;yKKEUh95*lNiu)z9 zgZbOmkY`KCguy_@WSBFaGc=N>4FF((GIdLTDx*MaDN3lL!_4V@ln}q+qu;oNX+6kJ z^9WwNpI0b}YxFIIGYL)G5WZ%pfhP#HY+_D^50i%VLb!s5sHU3V=YD@xll2X;gW;nn zfEp=>HMV@6*hbo^MJSl{0|?m6ti&eXhiVcy_vPRrbB0zQi}{WFQ=YAG*2hM)6zBf_ z0S z(EluewoU!IHtK3~IMdnPr$9k`#Gn$*y6lBao#hjX$&-*aKoe;CE#GD=Dx35+T4 zw1e+cL_0!YP<NGCwWS=(ut$G#WImGM-U+7}9t7n@0cyVypZk^sUw~yeA*|b62XrSD zzNu2(&ZQM;C_P0O;%cnlH*jC2@eVt|`}(0TG}i{{|J6U>#p0;bk1I0Pu_i+ zi^Zy>e_m$%$bRKUm)O@qn^5Y5z4Mce2tzjD@nh2sx8GsJd`#l;c~5up^pKV0W0GVX znwGAr=f2?x7~za(;@pxP1Z$AC!QbMGWZc%ok6WQIw40#P&96qq&&qr^VqM31N}r;ZcMkDP@fyA}^AA@hV&PZO3U~N(N15R6bTBpdE!VmCfDvf`Y zQU2X9Q$x@ZI-UvF_QizU_a#*vcb zZ1yNd^2DQwa*lg$fgGrf&~#kh##ac8O#$VKDbdTj99C2kJ~z}VgP0^99H`5ai8pGs zi0bF&6+hj2q@M<}uGGJ64kRwUqy%&hB(H`qLVtA7g<4l zZy2-Ik&;|WjvW>o)Uq^cw>bl5HPY@yz=xRiWc9L6Mbo11sa&@B1*ii(1~5XON1jq{ z;$S(=J=`u=yc69sO8@u7Hfm>ccoeX)wksW-Nz{|NvKRO+lgMu6d%3n+$)UFhxF8+Z zQZjnn!o4J~-yL_A@scRFocOFK=m+j& zs<9;3_W8-j+GK1wu{H%7mVNQU{=L$ZxYZ8M43lv#!- zW5%=%4Q4qqi>MI7HttMOiEJcO6cXOg*Llx#pLL%5UF-SlecxxT=U(ext5bXb_HY08 zcep;+=en+MMt!``OWxYs!?Lh>>|X#5sYc(mgR@OxWd|(3SVl@F>{){4w-IIx zUlw`$RJ|XkKUNzk;%1G%VZ}8yO6uPcBC>_YkojB7shw7YA9hanP6=WJ7acSbLRLQ@ zzj8P0?=w_E*&-e{$!=D8QuD=+R7%X4q*9Q>{4g{1kn&qi`=isO{sSAbT!0Brm!Ko|Vko`OJoUT6>ZRPlhW`NhLzoDWG<+KtZ+C7~C{v(~zp z{&wmAL;V2d$bWo#ida4KHaLm8RdyWT@F26W@QU%!Gg&oZtE6gWL}K|WH(RDY41VXvn>_$deJRNj>&Bz62J@w4{H<;}>|p!|`zRF-Y-b%!EDPTHnv*`d;{;3x z%QzL}^s|lH6?h4tHR)RY&+P=D0{v9+Z(E+Vp*}4zh04U4ccka7* zLmQzm#$Rb0yc6?rwa;_6NT#aux?vZ6n!PwZQm$Hm_*TwE3z<`RV)(Ba!A*0pK!_2v z=)UrR^z~uU=msruTB5PV9gI1g;d_3w=f-Yi#wuKD?5E&Kc!3VUG%qqSg!4du zz}<4_1h7x}PCN?jKFy{b|6=XOpd0)+O|IB+Fg|BMUX|>0VLekrwRLdjd=uY^X*f)M z5^z=IG;CI52V~*o^y78hkG=qu47;nwb~eo)%);8eB!D;Bxmjc}cmgIxytLz>sI@e$ zyf3`kSl*=-*MvH2{%riubR?UFifRDjn~F;{a#&`7+*vwn!K?PS{SmLcY4>fj00ke} zCh%{6HsYNx25Q&dZ9>Xq=NF!I$MZ~s1c06Ln6qpud-HStOy@DE~i+2hj#ov zDh^iB4Df0nOJj>D062_sqkG=O>n;8vn=B3Pg)GQQ+PCLJYik0_5E7}2%>GgJC9mOF z8F0{hbBpy%%&z=V_V_>&eN8(t>fswDP=&rUMlxzgR+{k($D)RPXF<*6r(o*~fnUVn zPX>l2!eTyj8XUCs)`fgi_vf-2v2QthroFBvJz=ObtCUntI{qamJ*-cT($%Ka6t?=N zC8yVA57#sGsMP_CJ=BgjB=%^_Fvu_pob&SmV?l!g=hExTc5I ziEZQy-HS1_`;`trp@TX*PL0z#{_WFCFD*Fb)qW3^+h%IQM9TLD0eHAbF1|KHQq#H} zx8(f~zQRnq6p)&CT?@}+=0H1}6%ZRYT*ccAN%Z|EVs2>6a>s?SeFONuniaDoA>VirHRcG2_F+(zai9iY;p{O@V zrnBuO$JgPOF8$|Q5T&p@ZUka_A|+UC2#$p2wj0Jyly}rMj%o{5b5G zUiPp*hB@#cR{ML-4=CDgig@Vc8eb$^Cz@Ei0M3o9X)7^Q(Z~6p$JPF|r`6xi%#)c3 zPS-VNW22RR+Rc;g7i~PDcF6>d?^BNxmPtVK*5CB**W9nohp(M#~WN5AFC@9rpZ=$Rhj*F0}a zsF*4v>Xa$libq)A({s;I*WG>MAJ00);S79zMbKpsDLT9JI|xy7ue6j0@53*NK~dzBe?QWvcc&`L7p9 zX~t%FNo`9rWq^LbM}uqGdMbYv~mxhQpiToLMu*G zGnT+th9SLwej}RiK3q3vy>>+euEcWbaNQ8th^P`x*oEh30;5@$VxA}%>Q8+iRv7hx zQl$I#(|tsp@27D5l=-LdF&UpaaM@?zR^g8hoHPPMeG2@MaJW82jF<$kkIl1A(idhV z!M&X?VF z^aB-zFxp*RB+z^6U*WPp(fTg=YlCp;{p?9IKadx3MTTpj>#4!@jQ)@=LnaGu+k0>+ zd;}wjtH4#iRZopGQ}gbH%K^V}*(Sh0EYfq(@MdLi-xk|;q(zpTfw%wM4zHczN;cJz zXxKXm#x}bYZTRbMzRO9}YkmDstN{sf*#ZLzZ|0=ohZ2%aqvU8wlX1FA_9?2Hue5@Z z4Ic)3R*?(*1;kNIhUz|(&o^dQ zIg0pFY*U=!om}%h2Pp2dAJ%SMe7`#PDV0|L1%U-&}=Y^5yN{Y%jpXCLDz+R=c1Dv&K~F&< zv+tpPm|p>-r+wT~1;CQGpiLB+m9B#H*5v$I5P=>^0pIq|z1R8}{nsU%VGTIVqCt z$l5U=@?uZm5SZ_no93aB=Kx=<9U2dKkQ!zJ<9+%v7Z^PS-`2nkiYzI=eN(!0cun0G zvMyaHAK{{nn)Ug4XwYc(;3#Y5A3)5I>vDb>o@*H2{I9|dXi5lv{ys?+RRj*;<%KBE z``3YxX{@z)76D+|*Tdhd&3yGR#TN=C zmSq$XhDrartN%tXx+fX&m~NB@y@|IV+HK!#QAgy|2K9i#%95NS~}e)1MP3Xzjt@C>lCY~98uOm~tlUxeP0|A^}2ZNEG)QO_(yu=F;hCWIs(v+ z+9C`$Tg6MX@X}V7vdIp4c)QMrcI$GW49*57Qvu1PT`02G2}dvNBB4-iQ>z%&$M+Ac zo)LC^x%T5MJV^g)+JeXKK!LW?14~FEs)STo(Uw{zR1=%~nax!u>mZ1X9N$=OI`LTU zGZcMXgKhJlWRHc4JS7}nVeD;|5Pai;g=^DfUtnc;zwRG=a45|htNX(eMvD%Ty<+z> zGq0@ImOq6`Qt#^6C9;~U_>roK$4TuU`?#*;$I#NeXG-6mKbr{#am8)F%g%glg|E!( zZ{(wkIwe|C2ud{LmIl2Tj;=Hvk4B-#Su)Uku-k)`#hL5tO@bBI3rgV;bIFs+1@ZxW zA6IzGdh5)VX5NS2ZCEp@`c`#{rKNn40tC)tPTU%Ajg-be)g|Q|!pIvAjV8ql*SUN(-z7uIv%aXFwJ7Yau;W zeGa93TfBokk4+`<6$yUC*Dq*c0w3u=O@MYOyw4hY52k`lo(Gx%qe(Lmfj<8e=8MLY zf+`1z6RQRVRn|TmTCIaE>wlEA%NL~ruZj_VHMWw&#aaw};H>|~>fMBO8>Fy>mB>rs z#8|vOS<5ncMeE1=O+ZyY84bbiK3+{kBV|fF* zkMv11CMm+ZBOrD2@I%}@PaH0l=EIrlcJ1YRn8qxh;=-5^4@@Vf7m48}aK?a~O7jzl zw-S(Q&qFDn=mecyF>`9E3xt>+GG}X_aHIobKFZ<;%zRAaFh?;T{}8RS1k`?+AWM1J zeB)X7nM3TY2}OIp>JI=1e9or=N?QU;WrY(A7)^CvPpdc@c??$pGWFL#5)PO5TWHr| zdwL_he_-x$663rDR=gkneDj0(%O=Q_q^$X0b+$2K5>9d~Zhl;{H&IlUc?Po+;wtTa z4MH6%rI46T{~84U&vTCGB|K(bhOw&(yulen%IG~ZwN5Y?Sz$W~H(!x&@h{LsrG$s{}(fIOb?r zBWgw-O32ZEstYD3Vr)x1Vxqhj9bd1766RZ?WJhj~n3uwR%ZCY=S${oV8-B(Xw60%s zpV>G{E%B5KQ|2!wKJkKCYwEa1@hTUp0<4m_nLx?Nxunvy81q4h!GJLEEy?-RE)xC^ z%k?1^4YjyaCsk&KgF8?EcH1VvryZ(u?!mkDnsD9aqr~#Nxe2;F^!r8QNDp)pPIf^=lyqn6qr-T(r-^iopAP+Rnt?o8kL`+rKRX9`@ z1Z}jono!phBJ4GY+ES`V^Cv@xhqfF*QM5h$-Alv$kWtt~TTF`{r}l(vLWBd$(nUQv z`Qe+}M?$>|EL`?noGB`nquXDeUKIO!&8=GZTI)n%@SGavVGui6zX0-$Szawupo6AJ z6Li#@wp_u6U=+V@Z~HM3A7s9Ffq$4EkMl3^2xvJ!!+fi=P7>@!rdTPOuvX`Lr4ELO zNQ@>>X14QWfjwaOF9EKtO|qKhh}QGM@qQ1?^}{{)#Y#1%gwM%NMu%? zB!qY}XjCp~m_e6!e$Cpa7d9&M>LZpH7@G1!SH5{oB$N(iB=kk_X~>Qmw*!;Z;OqL! zcm77Agu>QOd_G5-lD{v=-GD5JcR-I>+}hdqWzhRy8Js9&be%*xlGnXwj zcv$|dJpnrAF&lIt)>G{9ueI|AneP&hmvYAZ>t8wA^mE(im(G?@6UpDN<2(LKc(fp^ z9Ht0|dK7URhjB{LxIEYUuN9>{Zck415cC_CuQ00P@;Sr;3VtSgQve-AmQ*mDVibq) z-$-YfaF?Z)2P>fPmu_T6#}she{=xItr}i-OI9yZUC`?f)jc|n(X@ZY_PYVw=^OnP`e8$~-16<$PZ(;>DK**S__xdn7MfpMZrqxbhO>_K<^0jf1r(eLKkJ9S8KOOejGM;61g zR|+acc5J7w4ezLgLm!fP6jmW-_pFhbi>i+es3tqC9=h(>bJSmHu;ImcK%dl(uJ*yM zAzPb8W;xW%_KcpkerYm`vPC|7Yyi(b3C9fRKxV$9kYWL_?H>eX>sO|8oQi#IcH@JiBK)czKdG=mXd-=KVTnZl7 zezsm(XH{`T86x^x5~}j^ui3(_?aei)%>eafk>91rj6`%odnubXUhgXv5`S4%pFx4p z^b0hImjPOdiCw2WM{oovMG>V6;mB>GODkKp@C#|4Rv{3hrc(jySn!oYWK6$E7F&z4 z%xsBy*8F|%=`tg6BUp3RlX{2z9#-N)5l%rJg@$F9^a#l_!CmsX3!YG}z2)SjiJdmE z0|n02Z|P~?Lzta}Pz*C2^EsYmsIbxTNz6|fl!Buo^7gfk!0@;|8UvVM?9LW9NPTWv zr3(jn%EOC96fJ#cJU?7n{o!XhNH2bXwDxv7{T0q1F-HljuM{nV-z1)7R`~&~gz)j~ z6xTD3`UMzQM$C1nN6f25;1tBWC!Whi5~Fqs2pj{H-O&x=T&`91@6MpEI+Ax4TYtD> zNV4}q{Se>|u8lNkR5ZwQmF=a;^7@EExnN&S<3JhLyGfD#U%WO4hG9tMPDR*sx<09s zmTv30v;+vR!emS^G_g+b&`Ej@r#^+-Zvs(($fKSxVwZ9;AWFK?Pzu=W(M8yE!v@4l zD6zMh+1;`nc=o%v-2f4g6F>=FwrxdeVu zc7wtQk%(YkW*X`vSiA#RqxcrL1T7&o;XJdp5v3Y{l?7%2IEXxYX~C81#at*mGe-Y_ z)Tu(RN_`_q)`D%bi>OhcY!iH({5a6E(U)|J%0cTtLe}WUy9395XQyzF>`dJDrTsAS zitIt$bcgxuoW@g+CA(YDXz;^ykr-hwj{ke_{cUTvJ8 z^Tf}AXgE~mL07#cXWRP3?=1DKvFHN z_ib$2^rH8zV(oq|Lt*w>(FSiMl)@4S%B7S=SR)!-;l7pmEe4PRhzC|3mI&bKT~$j? zdDROIcMiq07{K`8l@Lw39EfoW7O2~)&CU>szmQ=v0<}1gqA4#_|9bBo&L)j6ESrhN zeBH$^5y+nU{4(6XK+KjFul_w`-}3?K^3C%!Df@z!HAn3BD4E()uoXC*uMrQeldKzp z5}dCo__7}q0czRDP-`Y`%bT^Rv8)vLbK{$gij*Y9AVNn8qY}*IbzaEIn$S7%FqmIi z`Cv4=`dA*;&IyXy3A*2cS-grV#wTib1+xV5Emg66#Tbpfg4sNt0f|ZYO{?Dri4|-h z6UNLF6CC0BEIN91+|E!_^dRS;3iV8{ZjNB**tFg2wJZ6DK*qge*yiKp?h*xst?XyF zjdYs1_ZZki>*|m>_3XjzIZ{8c0_3}BlT_7>t@)l4^yfqFfZaw%CH~weHTp{spn* z|Lypxe=%rkRk#Y+U9vcBk{%5-p<`-L8q(r}jbGU=MNBBiC=2$Z!ujcaHP8ySM{Vr2 z`w%%ymF_ds*II=(&ZdGC55m1{x$zV!)Zfh%p0Y;d05qzuj1K0V^KJ(qB;;NlbA+M@ zcHT)C&yh_i`h5}TuNsdv5U-tHhK=2uYyT9k15PyIa(}Cbm@NolXBM~$k=|O+GgU#f z1Q!sHNJYDs3OVD2rSP+71B?)js^6=x6@vz6NZH$Z*cf6!_W6FfTZUY)fqy~tNNjOd7Anh;; z8l%FN!`o^NwULh3w`S4wIvJ?6vyl5fskg>^skBAx$=;{j0H%G5YJ7h#YC;xWjWA_m?1YPWHTVvT)e#ED?Iw>F^mOFi>vcWO{r_`Q-_^J`$eNJbfhU-LRsB} zr`e*|@tWqMo;fK{hd@Omua>=w1dE#sp-{Q=QLHMJ0>?ESMIJ+YsC>>KFQ zwjzyD@&|r0tj`*Nlit^Hba)JyS$8$Kyb+j(6BokPEKk_a$Sw_$vQZXP7RxoX@Rq_k z3XR8f0fVquEVyb7B0&b2+jz89NY_3fq{ezyoJIQ--17py>oi*?#3PAju?RuRJ6F>k zYg@8?ma#4q3Goz;AJLNAlsKyln%y+CczoeVRigY+ShusG6fsqYi{Bhj%@Hu3d-d+h zQy!JWg6Fzk$F%UOT!n4yNZ?x_(KtQ@T?+zZ4A?aNzV{eS!uJ<5zt?3IpOu~;?OyT+ zVDAe*A?Sq)au9a*7m|TSByHK;QWk#Ff|i&ajO|lDfj+fVM7(2gUxaT*ZMd@9U5XBT zJ4_OROO6+HaU~+Bg@uA}6(FN!Z%Q1E38I0_JH-a(;3AA8XncD($`GTNn{Vh+^{zz> z^nxf}()`LYCy4XlJMpAbLo3sxj+;dTkcm-z)(b>Bziy z(|60SE4D_YF&!VcUdlqQK5%XMU2rZSY~NBREXM*7Hw{rjn(8YDrlt^(3aX)EfF)xc zY|l-rV{4yf^%?{-SUE_fx5aTf^11!l5lmV+g#ow>@IEvWE71O2tR`h>Qff5*4;xJ zs{B<@VOVYe*IbN;!b{a4()Y0prEyIGDxk;P-q^-JaUOt9Vw|C=eWu8)i|z+HHZA53 z1`=XpBqH+!h#cTESJhi-wfjjY|+W^q+C+wugW_!mDSPSXXY}J0lIn!RW{eu-$B1 zj|eL0X*-^#7o^8tQ|^kvuvZ`{0a@$3ictT&d82O-vL!2IJE#jEO_$V^(hA&fQ2)&p zdx0GIxD0qd%M+4fQTSS`R76!{$0J7D72SiacV7Z&B0S+-OAgvQ4%&oujLvbSVOfMz zOw=?UkEqS@WA)x!Fdp}MtN@6Yid^qC#um^&(A*_nsEmAZ5U*6_n$*g3uk${Gfi&$= zeKhTwGk1*%+<8=&R*cAFyd_2PO!rXiB;hs2noxv{{~=`=6CSs|>`PFRKl;ca>A0kT zIEz_j-!zn<(Y%KSW??ppC88is&;)Pe89ehWqfe_>uFs65+H`P{G5}|Z8QYo{z}Ld< z0vDD@Q?#WL$c9cQjed}ow|sO*WUy&TnO=f`m-gAc3D`2CB)~QzX2>Xf?mBR&YWp|% zf5p>hiR2_CpDGq#s<3vWzC=n9_B+FBm}YbgBqm5pFal?$`~y7NjWr%xqaSc5yMepC zs5J|RUeKMb`Yw799kbFNq)t*UnPrRe8<VJ|RQqOz$b{KYXwg zZ*QGzErqNPMRfR4rm(&|2zDNqaCjwTG#^|l3t%FAa|M}@&SKVmiJP9DL(gCXQp~$I z03ibDvCYLp&TrZ>W-V^5u!~V z&Jiw69yi=yKMR1iqsQprPyctM&0#be=|+s2Z%JB$h0h^n?{m66WTbLM_4V;t8~ETNW+U~gJifHhqr3Ts(24R`=>ge4SjQS)1Ss(++xF2f$F z$0!oYORKXlA3$nXdrk)0KD23TP}o~sn@0*Ym7pDKM<^^#N!Q_Qi+w>C;7Erh3FZ|z zyC(&a(K+1#9hCrhMj&Wuq0NG)%@g%xly-bs2T0J3TrOIczOY4*7_HieX^b-*j_Tl;doDqdSiVt7{tioaQ#JMh4Ru#sw74qv zK$V>jeOec-mVUMJRIy=Ds&rX#H3e^dk385OY4bJJfMMo&A9(f{7_AlLp>ozDHIg_3 zBP?>Pp!!>j?Df=(e*q{RZdxxKNrVRskp;~+rL~0z8(OfU+RMYKDi&OAnEk*TlmhkA z7`*}g3}MvpQ%$lwj=2&101kfC(u(59v z3;|Q1$%(WNJ{YBGsnLRw4nDyfNpu2tRP@~hmJtXSU?o25fYlq$+I|Nj{y^ z_NdtCsdCV+lP&`v1;NxCaifhYTfJ#Yfov0T->VZVK^9p<~ zq4E#~x06|sICUJ-3QAvX+m!)7l5o~S4GM^y=lQk{GxS0*+U>-m2GHSyy;45-@wK=$3z99R&Dq2;JL&F2&rH$p7wWc2Orvh!Cb1z$yJVl45C+y*e!6Y= zV;74a;Rf{As$4cgr z@X3zRw7MbKN9LY;|HhCq7Dgh$o zE(cR=E*7>T3%|<|mg*ey^VW{Pj=YlKh58^FKPePngx#8qQ~zEXp{$d+8Dx-maR8v( z#b7xxR|3Iat;GwCBawycYSVH^N%VFe>YXNEQ_5gJ9^vlF-e@g zpFZ*odQJ^WNW{Ssf4t0q zUo|L_=tO$;XND|c<GZY+-?^w1`>fP zNyc}V#$+WBPPPh!(_+8w>1l=aaB{f2beZ$UXdF&8ZHR#`fn zN#2fCld4L~%u`o>Jbt>4PMar}32w}#tBXGM#?24dT#X|0JRNnc%W1d7lN#yC{*6yY zKUB~SSPyzKS-*M`_9`4fl6r6KozK5RJkn!UdS@ z_G#iWMbFjYQr{H%Km6HT<1gM6v_=uA2G_WT8SxhTNbQfgic`4uM=`VU?as@7m9y7C z?Rf^mt_|bd-H%NxZVu!k2wtKOq*uhUTJ(ZR)vnQ~;QYL0S{R!^(46wzBL-_V13Lg` zcW}yaig_AC^*eU(W}677UdICSq-PBo)TtJ0!I<(mG2NNw7-daa;ziV+d=lhD)rz}& z3S(tQcTza#o1TP~KPCt@ONL6Cs#M;{f#LA+e$Dbo??y?onX7n9LJsYkKhMIvi8WsR z^9RY^K{L{u2`cpq^aju7J_2fjRPc_5k#n+nIcp}ha<_{;RWe6V8HBhi!JJTCzZd2$FJ1ZFISI!vtZ7n+Jo*W>z}fu zRt+8+2iHRd-js~Qe*sH~4B@jJl1=X9wM^ z21<^K3+O5VXd!sDtj93Y`3ald?4RqgbT<%##g2;!uZ1I&bK*&}6eB1`TbJrmFwi&H#VSz==Y4JYNFcFET6jY!P~Z z>>b=-&QWG{;7IuitF9L6q-<89h-s+}ugyLROd5y$P3u;U+sU;>CL17Ci-)Q|+v6o< zto%g1Ts%OH#x1>$&X$FM4);^hv|liXAuM44bHuSITL4E{*TFCF(XhO!9_#nOlQ9y`qz(|78NT16##RaPWns@|vke0j@ zuuLX`J4ko1xzQj3S^R7#8Fax^m_rHRsd|YA+lXKp~}+_9g1 zx#5SE>g~eTnazHvp@tnQNJ6#b$QtB=_|+rsY{wDUTGlL&_lG?2Uzf`wIikR@Qm`Im zA^R$_T~0#j8fA}4|F0*SzCvlHv+4E#LD~ApY`fEcXS>kRZU-_Vz$(f@K}{w%w4760 ziBZGn3r_0^kCwp4dOD@uK{yh*Bj*ce7PL-k#qbRs zRsSvGX8b8*Xs7!Xfce+rKEiYe!)im=(am$7gHVu!_aS!&vMSIW7c(X_b@t*yo!(cm z_Y@(fVInCQr#>Mz1v!3%rhcXJ$X5+6pNfF9Yx1V6ebfv+6uE6YwFSVDSGnZ3AQ~ix zE)cf_bUiy&_6Px|q8jtX?!z%&{3IapL*XmZ7JqRkmOv;D^{GB{caUG`n}kjWzbciYNCD zsy$80fBK96HIud+C176N~O38Sp1;ziBpyR%&Q>Jvy~VXc7W%O72euPNuF0=i|eJ!jmPwJTbD}9 zvLq;73_BB~$WAm|1rX_~wud>}4l{Vr8G$D<=Zl^T1$kjg0T-%%*A>kA`>e%x5}N^n zCvU3K-mo0VDIW{F2sm=PVCroI?z*N9B;b_7%@2WcYuH>Sumgr0w?J&WKE^mW7nVBh z6AZp?uCcS~>0C|4l?;Ly5*T_k5uqEbc5(=b%Mujk$mbdr9iim0B*O|Cmd82x0mP;v z#3%U@lmOq${_x~}s^5wP>dC_i5OmQH_@20^@PUqdAdaOP9P%T)^5sXDe&n*~{#9`S zWgQ^!TTU!G)z2PgP^6CBgtTOOlj@9OD9$&Rnw64j!;cR6 z;exk3P+2%V)0BQ+DAliXpb4l|W<{-Ip|3PMt=?B^3Y}s)H|Y($bNCAAV!zn!Xz_Io z?gqqOmK2qy=&k1N0{cREKo`mQansq}kLOF&w%J!&CPYk&?Xmj+-8jr`0@M8;P{{11 z8v8RP^50ENwmvT{#KEe@kjA+65sQ)cpL|(9gk6=<2Zi7Bw#wM1YRkVdwUf1;5zI;o z+8}E6F_sn$q!V>E&Khja zPp)-&-=ytrg7ydAi~`GeHN{LW&lOodMhCkH#m*mJL^_{M$ocu_Wv%~>hX3C(5dZ2( z{6Ew5W*QO;uJjem4}oo=exr5;?j5AB(Wb$b(5Y;S)&j!=VPn__Juc)NaGD#gorG$0 z<)UycddE_&XX6U0sgUsiIR}Jtf8Ufm3H99FbPB{eyxA16X-Zpd+6gkaBsXmX=XY}= wwUJP6$foQomT+oQb*Y&r@c;GOe{O7Lb878&CVW%g0{_!g)j3^o@^aw+0{s1VfB*mh diff --git a/docs/mir_actions.md b/docs/mir_actions.md index 5011ef8..51d0f73 100644 --- a/docs/mir_actions.md +++ b/docs/mir_actions.md @@ -80,29 +80,29 @@ This plugin currently supports three move off signal types: 3. Move off on a user-defined signal. - Users can customize their own signal type by implementing a `MoveOff` module. -The plugin also supports task-specific move off signals, such that different signal types can be used for different tasks or task phases. Users can specify signal types in the task description, which will override the default signal type provided in the plugin config. If additional config is missing in the task description, the fleet adapter will refer to default values from the plugin config (if provided). - -It is possible to submit tasks with move off signals that have not been configured in the plugin config. However, it is up to the user to ensure that these signal types are valid and compatible with the MiR. +The plugin also supports task-specific move off signals, such that users can trigger different move off signals in each task. These move off signals are either pre-defined in the plugin config, or configured in the task description (with the exception of `custom` signals). It is up to the user to ensure that these signal types are valid and compatible with the MiR. You may refer to the Examples section below to get a clearer idea of how to customize signal types with plugin config and task descriptions. ### Setup -Users can configure multiple move off signals for their robot fleet in the fleet's plugin config, up to one of each supported signal type. If the task description does not provide sufficient information to configure a signal type, the fleet adapter will refer to the plugin config. This is suitable for users who only require a single signal type for their tasks. If signal types are not configured in the plugin config nor the task description, the robot will not have a move off signal set up, and simply wait for the full duration of the timeout during the action. +Users can configure multiple move off signals for their robot fleet in the fleet's plugin config, as long as they are supported by the WaitUntil action. If signal types are not configured in the plugin config nor the task description, the robot will not have a move off signal set up, and simply wait for the full duration of the timeout during the action. Steps for setup: 1. Fill in the appropriate fields under the `rmf_wait_until` plugin in the fleet config, with reference to the example provided in `mir_config.yaml`. It allows users to customize the behavior of their robots during the waiting action and the type of signal to trigger move off. - `timeout`: Optional, the default timeout of the waiting action. At timeout, the robot will move off even if it did not receive the move off signal. If not specified, the timeout will default to 60 seconds. This value can be overridden by the task description. - `update_gap`: Optional, the update interval for logging purposes. If not specified, the update gap will default to 30 seconds. This value can be overridden by the task description. - - `signal_type`: The type of move off signal for the robot. We currently support `mission`, `plc` and `custom`. You may configure default values for each supported signal type. These values act as default configuration to be used for the action. They may be overridden by the task description, with the exception of `custom` signals. This enables users to trigger different types of move off signals at runtime for the same robot fleet by submitting different task descriptions. - - For the `mission` signal type, users will have to provide the following fields: - - `mission_name` is required for the robot to trigger the relevant MiR mission when the waiting action starts. This is a compulsory field and may be overridden by the task description. - - `retry_count` is an integer and an optional field, used to configure the number of times the fleet adapter should re-attempt posting a mission at the start of the waiting action. If the mission cannot be successfully queued on the robot beyond the number of retries, the task will be cancelled. This value can be overridden by the task description. - - `resubmit_on_abort` is a boolean and an optional field, used to configure the action behavior in cases where the MiR mission cannot be successfully completed and gets aborted by the robot. When set to `True`, the fleet adapter will submit the same MiR mission to the robot if the previous attempt has been aborted. The move off signal will come only when the mission has been successfully completed. If set to `False`, the fleet adapter will treat aborted missions as completed and end the waiting action. This value can be overridden by the task description. - - For the `plc` signal type, users will need to provide the relevant PLC register number. This register number should be an integer and available on the MiR. This value can be overridden by the task description. - - For the `custom` signal type, users will need to fill in the path to their custom `MoveOff` module that is implemented from the `BaseMoveOff` abstract class provided. - - The `default` field is optional but encouraged to be added. It should point to any one of the configured signal types. If no signal type is provided in the task description, the fleet adapter will select the `default` signal type from the plugin config as the move off trigger. If neither is provided, the robot will simply wait for the full duration of the timeout since it does not have a move off signal configured. + - `signals`: List the signals to be preconfigured for the fleet. We currently support `mission`, `plc` and `custom` signal types. These signals can be triggered when specified in the task description. + - Provide a unique name for each of your signal, with a mandatory field `signal_type`. Refer to `mir_config.yaml` for examples for each supported type. + - The following elaborates on each supported type and their respective config: + - For the `mission` signal type, users will have to provide the following fields: + - `mission_name` is required for the robot to trigger the relevant MiR mission when the waiting action starts. This is a compulsory field and may be overridden by the task description. + - `retry_count` is an integer and an optional field, used to configure the number of times the fleet adapter should re-attempt posting a mission at the start of the waiting action. If the mission cannot be successfully queued on the robot beyond the number of retries, the task will be cancelled. This value can be overridden by the task description. + - `resubmit_on_abort` is a boolean and an optional field, used to configure the action behavior in cases where the MiR mission cannot be successfully completed and gets aborted by the robot. When set to `True`, the fleet adapter will submit the same MiR mission to the robot if the previous attempt has been aborted. The move off signal will come only when the mission has been successfully completed. If set to `False`, the fleet adapter will treat aborted missions as completed and end the waiting action. This value can be overridden by the task description. + - For the `plc` signal type, users will need to provide the relevant PLC register number. This register number should be an integer and available on the MiR. This value can be overridden by the task description. + - For the `custom` signal type, users will need to fill in the path to their custom `MoveOff` module that is implemented from the `BaseMoveOff` abstract class provided. + - The `default_signal` field is optional but encouraged to be added. It should point to any one of the configured signals. If no signal is provided in the task description, the fleet adapter will select the default signal from the plugin config as the move off trigger. If neither is provided, the robot will simply wait for the full duration of the timeout since it does not have a move off signal configured. 2. [Optional] Create your own `MoveOff` plugin. - You are encouraged to use the `BaseMoveOff` class in `rmf_move_off.py` as a base for your own module implementation. The class methods will be used by the `WaitUntil` Mir Action. - In the plugin config, update the `custom` field to point to your own written module. @@ -112,25 +112,22 @@ Steps for setup: To submit a multi-stop waiting task, you may use the `dispatch_multistop` task script found in the `fleet_adapter_mir_tasks` package: ```bash -# Trigger a task using the default mission signal type and a timeout of 120 seconds -ros2 run fleet_adapter_mir_tasks dispatch_multistop -g waypoint_1 waypoint_2 waypoint_3 -t 120 -s mission - -# Trigger a task using the mission signal type with a specific mission -ros2 run fleet_adapter_mir_tasks dispatch_multistop -g waypoint_1 waypoint_2 waypoint_3 -s mission -m some_mission_name +# Trigger a task with a configured signal custom_2 +ros2 run fleet_adapter_mir_tasks dispatch_multistop -g waypoint_1 waypoint_2 waypoint_3 -s custom_2 -# Trigger a task using the default PLC signal type -ros2 run fleet_adapter_mir_tasks dispatch_multistop -g waypoint_1 waypoint_2 waypoint_3 -s plc +# Trigger a task with a new mission signal and a timeout of 120 seconds +ros2 run fleet_adapter_mir_tasks dispatch_multistop -g waypoint_1 waypoint_2 waypoint_3 -t 120 -s mission -m some_mission_name -# Trigger a task using the PLC signal type with a specific PLC register +# Trigger a task with a new PLC signal ros2 run fleet_adapter_mir_tasks dispatch_multistop -g waypoint_1 waypoint_2 waypoint_3 -s plc -p 30 -# Trigger a task using the custom signal type -ros2 run fleet_adapter_mir_tasks dispatch_multistop -g waypoint_1 waypoint_2 waypoint_3 -s custom +# Trigger the default signal configured in plugin config +ros2 run fleet_adapter_mir_tasks dispatch_multistop -g waypoint_1 waypoint_2 waypoint_3 ``` - `-g`: Takes in the waypoints the robots should travel to for each waiting action. - `-t`: Optional timeout of the action in seconds. Default to 60 seconds. - `-u`: Optional update gap of the action in seconds. Default to 30 seconds. -- `-s`: Signal type for this `wait_until` action, currently support options are `mission`, `plc` and `custom`. +- `-s`: Signal/signal type for this `wait_until` action, currently supported options are `mission`, `plc`, and any of the pre-configured signals. - `-m`: Further specifies the mission name for signal type `mission`. - `-r`: A boolean determining whether to resubmit missions if they are aborted by the robot. Used for signal type `mission`. - `-rc`: An integer indicating the number of times to reattempt queueing a mission. Used for signal type `mission`. @@ -141,7 +138,7 @@ Do note that this task involves using the same move off signal for every waypoin ### Examples

-Example 1: Overriding specific fields from plugin config using task description +Example 1: Select a configured signal ![wait_until_example_A](../_images/docs/wait_until_task_A.png)
@@ -153,7 +150,7 @@ Do note that this task involves using the same move off signal for every waypoin
-Example 3: Use WaitUntil's default timeout and select a configured signal type using task description +Example 3: Use the pre-configured default signal ![wait_until_example_C](../_images/docs/wait_until_task_C.png)
diff --git a/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_multistop.py b/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_multistop.py index 4c260df..337140e 100644 --- a/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_multistop.py +++ b/fleet_adapter_mir_tasks/fleet_adapter_mir_tasks/dispatch_multistop.py @@ -50,8 +50,8 @@ def __init__(self, argv=sys.argv): help='Number of seconds to timeout') parser.add_argument('-u', '--update_gap', type=int, help='Number of seconds between logging updates') - parser.add_argument('-s', '--signal_type', required=True, - type=str, help='Move off signal type') + parser.add_argument('-s', '--signal_type', type=str, + help='Move off signal type') parser.add_argument('-m', '--mission_name', type=str, help='Mission name') parser.add_argument('-r', '--resubmit_on_abort', type=bool, @@ -167,11 +167,16 @@ def __init__(self, argv=sys.argv): "unix_millis_action_duration_estimate": 60000, "category": 'wait_until', "description": { - "signal_type": signal_type, "signal_config": signal_config } } }] + # We only add in these parameters if they are specified and valid + # The perform action plugin will use the default values if these + # are not provided + if signal_type is not None: + wait_activity[0]['description']['description']['signal_type'] = \ + signal_type if self.args.timeout is not None: wait_activity[0]['description']['description']['timeout'] = \ self.args.timeout