From d968bc9bcbf328f4d2c4f0dcfdcb018f04721021 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 19 Feb 2020 17:09:01 +0100 Subject: [PATCH] Add multiple nodes - carla_ros_scenario_runner is a ros node, that is able to control the CARLA scenario runner. - scenarios can be executed via ros-service - carla_ad_agent is a ros node, that provides basic ad functionality - derived from carla planning - respects traffic lights - avoids crashs with other vehicles - rviz_carla_plugin is a rviz plugin with the following features: - provide a pose of the current view (used in carla_spectator_camera) - visualize the current vehicle control - allows manually overriding the vehicle control - execute a scenario - pause the simulation (if started in synchronous mode) - carla_ad_demo provides a demo setup (also including all of the above nodes) - modify carla_waypoint_publisher service to be able to provide waypoint for an actor id --- CHANGELOG.md | 4 + README.md | 38 +- carla_ad_agent/CMakeLists.txt | 32 ++ carla_ad_agent/README.md | 13 + carla_ad_agent/launch/carla_ad_agent.launch | 13 + carla_ad_agent/package.xml | 18 + carla_ad_agent/setup.py | 10 + carla_ad_agent/src/carla_ad_agent/__init__.py | 0 carla_ad_agent/src/carla_ad_agent/agent.py | 290 ++++++++++++ .../src/carla_ad_agent/basic_agent.py | 129 ++++++ .../src/carla_ad_agent/carla_ad_agent.py | 133 ++++++ .../src/carla_ad_agent/local_planner.py | 203 +++++++++ carla_ad_agent/src/carla_ad_agent/misc.py | 70 +++ .../carla_ad_agent/vehicle_pid_controller.py | 170 ++++++++ carla_ad_demo/CMakeLists.txt | 19 + carla_ad_demo/README.md | 36 ++ .../config/FollowLeadingVehicle.xosc | 270 ++++++++++++ carla_ad_demo/config/carla_ad_demo.rviz | 173 ++++++++ carla_ad_demo/config/sensors.json | 48 ++ carla_ad_demo/launch/carla_ad_demo.launch | 71 +++ .../launch/carla_ad_demo_with_rviz.launch | 84 ++++ carla_ad_demo/package.xml | 20 + carla_ros_scenario_runner/CMakeLists.txt | 23 + carla_ros_scenario_runner/README.md | 45 ++ .../launch/carla_ros_scenario_runner.launch | 16 + carla_ros_scenario_runner/package.xml | 19 + carla_ros_scenario_runner/setup.py | 13 + .../src/carla_ros_scenario_runner/__init__.py | 0 .../application_runner.py | 152 +++++++ .../carla_ros_scenario_runner.py | 169 +++++++ .../scenario_runner_runner.py | 33 ++ .../CMakeLists.txt | 21 + .../msg/CarlaScenario.msg | 11 + .../msg/CarlaScenarioList.msg | 8 + .../msg/CarlaScenarioRunnerStatus.msg | 14 + carla_ros_scenario_runner_types/package.xml | 14 + .../srv/ExecuteScenario.srv | 10 + .../carla_spectator_camera.py | 13 +- carla_twist_to_control/README.md | 17 + .../carla_twist_to_control.py | 33 +- carla_waypoint_publisher/README.md | 6 +- .../carla_waypoint_publisher.py | 11 +- carla_waypoint_types/srv/GetActorWaypoint.srv | 1 + check.sh | 7 +- docs/images/rviz_carla_plugin.png | Bin 0 -> 525827 bytes rviz_carla_plugin/CMakeLists.txt | 48 ++ rviz_carla_plugin/README.md | 64 +++ .../icons/classes/CarlaControl.png | Bin 0 -> 16301 bytes rviz_carla_plugin/icons/pause.png | Bin 0 -> 184 bytes rviz_carla_plugin/icons/play.png | Bin 0 -> 433 bytes rviz_carla_plugin/icons/step_once.png | Bin 0 -> 586 bytes rviz_carla_plugin/package.xml | 26 ++ rviz_carla_plugin/plugin_description.xml | 9 + rviz_carla_plugin/rviz_carla_plugin.qrc | 7 + rviz_carla_plugin/src/carla_control_panel.cpp | 411 ++++++++++++++++++ rviz_carla_plugin/src/carla_control_panel.h | 104 +++++ rviz_carla_plugin/src/drive_widget.cpp | 249 +++++++++++ rviz_carla_plugin/src/drive_widget.h | 91 ++++ rviz_carla_plugin/src/indicator_widget.cpp | 53 +++ rviz_carla_plugin/src/indicator_widget.h | 36 ++ 60 files changed, 3526 insertions(+), 52 deletions(-) create mode 100644 carla_ad_agent/CMakeLists.txt create mode 100644 carla_ad_agent/README.md create mode 100644 carla_ad_agent/launch/carla_ad_agent.launch create mode 100644 carla_ad_agent/package.xml create mode 100644 carla_ad_agent/setup.py create mode 100644 carla_ad_agent/src/carla_ad_agent/__init__.py create mode 100644 carla_ad_agent/src/carla_ad_agent/agent.py create mode 100644 carla_ad_agent/src/carla_ad_agent/basic_agent.py create mode 100755 carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py create mode 100644 carla_ad_agent/src/carla_ad_agent/local_planner.py create mode 100644 carla_ad_agent/src/carla_ad_agent/misc.py create mode 100644 carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py create mode 100644 carla_ad_demo/CMakeLists.txt create mode 100644 carla_ad_demo/README.md create mode 100644 carla_ad_demo/config/FollowLeadingVehicle.xosc create mode 100644 carla_ad_demo/config/carla_ad_demo.rviz create mode 100644 carla_ad_demo/config/sensors.json create mode 100644 carla_ad_demo/launch/carla_ad_demo.launch create mode 100644 carla_ad_demo/launch/carla_ad_demo_with_rviz.launch create mode 100644 carla_ad_demo/package.xml create mode 100644 carla_ros_scenario_runner/CMakeLists.txt create mode 100644 carla_ros_scenario_runner/README.md create mode 100644 carla_ros_scenario_runner/launch/carla_ros_scenario_runner.launch create mode 100644 carla_ros_scenario_runner/package.xml create mode 100644 carla_ros_scenario_runner/setup.py create mode 100644 carla_ros_scenario_runner/src/carla_ros_scenario_runner/__init__.py create mode 100755 carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py create mode 100755 carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py create mode 100755 carla_ros_scenario_runner/src/carla_ros_scenario_runner/scenario_runner_runner.py create mode 100644 carla_ros_scenario_runner_types/CMakeLists.txt create mode 100644 carla_ros_scenario_runner_types/msg/CarlaScenario.msg create mode 100644 carla_ros_scenario_runner_types/msg/CarlaScenarioList.msg create mode 100644 carla_ros_scenario_runner_types/msg/CarlaScenarioRunnerStatus.msg create mode 100644 carla_ros_scenario_runner_types/package.xml create mode 100644 carla_ros_scenario_runner_types/srv/ExecuteScenario.srv create mode 100644 carla_twist_to_control/README.md create mode 100644 docs/images/rviz_carla_plugin.png create mode 100644 rviz_carla_plugin/CMakeLists.txt create mode 100644 rviz_carla_plugin/README.md create mode 100644 rviz_carla_plugin/icons/classes/CarlaControl.png create mode 100644 rviz_carla_plugin/icons/pause.png create mode 100644 rviz_carla_plugin/icons/play.png create mode 100644 rviz_carla_plugin/icons/step_once.png create mode 100644 rviz_carla_plugin/package.xml create mode 100644 rviz_carla_plugin/plugin_description.xml create mode 100644 rviz_carla_plugin/rviz_carla_plugin.qrc create mode 100644 rviz_carla_plugin/src/carla_control_panel.cpp create mode 100644 rviz_carla_plugin/src/carla_control_panel.h create mode 100644 rviz_carla_plugin/src/drive_widget.cpp create mode 100644 rviz_carla_plugin/src/drive_widget.h create mode 100644 rviz_carla_plugin/src/indicator_widget.cpp create mode 100644 rviz_carla_plugin/src/indicator_widget.h diff --git a/CHANGELOG.md b/CHANGELOG.md index 9583ed44..79d65801 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -7,6 +7,10 @@ * Add node to convert a twist to a vehicle control command * Add node carla_spectator_camera * Update carla_waypoint_publisher +* Add carla_ros_scenario_runner +* Add rviz_carla_plugin +* Add carla_ad_agent +* Add carla_ad_demo ## CARLA-ROS-Bridge 0.9.6 diff --git a/README.md b/README.md index a075a57b..5f2dba4c 100644 --- a/README.md +++ b/README.md @@ -48,24 +48,18 @@ For more information about configuring a ROS environment see First run the simulator (see carla documentation: ) - ./CarlaUE4.sh -windowed -ResX=320 -ResY=240 + # run carla in background + SDL_VIDEODRIVER=offscreen ./CarlaUE4.sh -opengl -Wait for the message: +Wait a few seconds, then start the ros bridge (choose one option): - Waiting for the client to connect... - -Then start the ros bridge (choose one option): - - export PYTHONPATH=$PYTHONPATH:/PythonAPI/ + export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla/dist/carla-.egg source ~/carla-ros-bridge/catkin_ws/devel/setup.bash # Option 1: start the ros bridge roslaunch carla_ros_bridge carla_ros_bridge.launch - # Option 2: start the ros bridge together with RVIZ - roslaunch carla_ros_bridge carla_ros_bridge_with_rviz.launch - - # Option 3: start the ros bridge together with an example ego vehicle + # Option 2: start the ros bridge together with an example ego vehicle roslaunch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch ## Settings @@ -267,17 +261,19 @@ The following markers are supported in 'map'-frame: | ---------------------------------- | ------------------------------------------------------------------------------------------------------ | --------------------------- | | `/carla/debug_marker` (subscriber) | [visualization_msgs.MarkerArray](http://docs.ros.org/api/visualization_msgs/html/msg/MarkerArray.html) | draw markers in CARLA world | -## Carla Ego Vehicle - -`carla_ego_vehicle` provides a generic way to spawn an ego vehicle and attach sensors to it. You can find further documentation [here](carla_ego_vehicle/README.md). - -## Carla Infrastructure Sensors - -`carla_infrastructure` provides a generic way to spawn a set of infrastructure sensors defined in a config file. You can find further documentation [here](carla_infrastructure/README.md). -## Waypoint calculation +## Additional Functionality -To make use of the Carla waypoint calculation a ROS Node is available to get waypoints. You can find further documentation [here](carla_waypoint_publisher/README.md). +| Name | Description | +| --------------------------------- | ------------------------------------------------------------------------------------------------------- | +| [Carla Ego Vehicle](carla_ego_vehicle/README.md) | Provides a generic way to spawn an ego vehicle and attach sensors to it. | +| [Carla Infrastructure](carla_infrastructure/README.md) | Provides a generic way to spawn a set of infrastructure sensors defined in a config file. | +| [Carla Waypoint Publisher](carla_waypoint_publisher/README.md) | Provide routes and access to the Carla waypoint API | +| [Carla ROS Scenario Runner](carla_ros_scenario_runner/README.md) | ROS node that wraps the functionality of the CARLA [scenario runner](https://github.com/carla-simulator/scenario_runner) to execute scenarios. | +| [Carla AD Agent](carla_ad_agent/README.md) | A basic AD agent, that can follow a route and avoid collisions with other vehicles and stop on red traffic lights. | +| [Carla AD Demo](carla_ad_demo/README.md) | A meta package that provides everything to launch a CARLA ROS environment with an AD vehicle. | +| [RVIZ Carla Plugin](rviz_carla_plugin/README.md) | A [RVIZ](http://wiki.ros.org/rviz) plugin to visualize/control CARLA. | +| [RQT Carla Plugin](rqt_carla_plugin/README.md) | A [RQT](http://wiki.ros.org/rqt) plugin to control CARLA. | ## Troubleshooting @@ -285,7 +281,7 @@ To make use of the Carla waypoint calculation a ROS Node is available to get way You're missing Carla Python. Please execute: - export PYTHONPATH=$PYTHONPATH:/PythonAPI/ + export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla/dist/ Please note that you have to put in the complete path to the egg-file including the egg-file itself. Please use the one, that is supported by your Python version. diff --git a/carla_ad_agent/CMakeLists.txt b/carla_ad_agent/CMakeLists.txt new file mode 100644 index 00000000..8f5a7216 --- /dev/null +++ b/carla_ad_agent/CMakeLists.txt @@ -0,0 +1,32 @@ +cmake_minimum_required(VERSION 2.8.3) +project(carla_ad_agent) + +find_package(catkin REQUIRED COMPONENTS + rospy + roslaunch +) + +catkin_python_setup() + +roslaunch_add_file_check(launch) + +catkin_package( + CATKIN_DEPENDS + rospy +) + +catkin_install_python(PROGRAMS + src/carla_ad_agent/carla_ad_agent.py + src/carla_ad_agent/basic_agent.py + src/carla_ad_agent/agent.py + src/carla_ad_agent/local_planner.py + src/carla_ad_agent/vehicle_pid_controller.py + src/carla_ad_agent/misc.py + src/carla_ad_agent/__init__.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch +) + diff --git a/carla_ad_agent/README.md b/carla_ad_agent/README.md new file mode 100644 index 00000000..63ee8ffd --- /dev/null +++ b/carla_ad_agent/README.md @@ -0,0 +1,13 @@ +# CARLA AD Agent + +An AD agent that can follow a given route. + +It avoids crashs with other vehicles and respects the state of the traffic lights. + +For a more comprehensive solution, have a look at [Autoware](https://www.autoware.ai/). + +## Publications + +| Topic | Type | Description | +| ---------------------------------- | ------------------- | --------------------------- | +| `/carla//vehicle_control_cmd` | [carla_msgs.CarlaEgoVehicleControl](../carla_msgs/msg/CarlaEgoVehicleControl.msg) | Vehicle control command | diff --git a/carla_ad_agent/launch/carla_ad_agent.launch b/carla_ad_agent/launch/carla_ad_agent.launch new file mode 100644 index 00000000..209de6b8 --- /dev/null +++ b/carla_ad_agent/launch/carla_ad_agent.launch @@ -0,0 +1,13 @@ + + + + + + + + + + + + + diff --git a/carla_ad_agent/package.xml b/carla_ad_agent/package.xml new file mode 100644 index 00000000..d2b3d2a5 --- /dev/null +++ b/carla_ad_agent/package.xml @@ -0,0 +1,18 @@ + + + carla_ad_agent + 0.0.1 + The carla_ad_agent package + CARLA Simulator Team + MIT + catkin + rospy + roslaunch + rospy + rospy + topic_tools + carla_waypoint_types + carla_msgs + + + diff --git a/carla_ad_agent/setup.py b/carla_ad_agent/setup.py new file mode 100644 index 00000000..0af8e3a7 --- /dev/null +++ b/carla_ad_agent/setup.py @@ -0,0 +1,10 @@ +from distutils.core import setup +from catkin_pkg.python_setup import generate_distutils_setup + +d = generate_distutils_setup( + packages=['carla_ad_agent'], + package_dir={'': 'src'} +) + +setup(**d) + diff --git a/carla_ad_agent/src/carla_ad_agent/__init__.py b/carla_ad_agent/src/carla_ad_agent/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/carla_ad_agent/src/carla_ad_agent/agent.py b/carla_ad_agent/src/carla_ad_agent/agent.py new file mode 100644 index 00000000..c1cc8c55 --- /dev/null +++ b/carla_ad_agent/src/carla_ad_agent/agent.py @@ -0,0 +1,290 @@ +#!/usr/bin/env python +# +# Copyright (c) 2018-2020 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +""" +Base class for agent +""" + +from enum import Enum +import math +import rospy +from tf.transformations import euler_from_quaternion +from misc import is_within_distance_ahead, compute_magnitude_angle +from carla_msgs.msg import CarlaEgoVehicleControl, CarlaTrafficLightStatus,\ + CarlaTrafficLightStatusList, CarlaWorldInfo +from carla_waypoint_types.srv import GetWaypoint + + +class AgentState(Enum): + """ + AGENT_STATE represents the possible states of a roaming agent + """ + NAVIGATING = 1 + BLOCKED_BY_VEHICLE = 2 + BLOCKED_RED_LIGHT = 3 + + +class Agent(object): + """ + Base class for agent + """ + + def __init__(self, role_name, vehicle_id): + """ + """ + self._proximity_threshold = 10.0 # meters + self._local_planner = None + self._map_name = None + self._vehicle_location = None + self._vehicle_yaw = None + self._vehicle_id = vehicle_id + self._last_traffic_light = None + + rospy.wait_for_service('/carla_waypoint_publisher/{}/get_waypoint'.format(role_name)) + + self._get_waypoint_client = rospy.ServiceProxy( + '/carla_waypoint_publisher/{}/get_waypoint'.format(role_name), GetWaypoint) + + self._traffic_lights = [] + self._traffic_light_status_subscriber = rospy.Subscriber( + "/carla/traffic_lights", CarlaTrafficLightStatusList, self.traffic_lights_updated) + + self._world_info_subscriber = rospy.Subscriber( + "/carla/world_info", CarlaWorldInfo, self.world_info_updated) + + def traffic_lights_updated(self, traffic_lights): + """ + callback on new traffic light list + """ + self._traffic_lights = traffic_lights.traffic_lights + + def world_info_updated(self, world_info): + """ + callback on new world info + """ + self._map_name = world_info.map_name + + def odometry_updated(self, odo): + """ + callback on new odometry + """ + self._vehicle_location = odo.pose.pose.position + quaternion = ( + odo.pose.pose.orientation.x, + odo.pose.pose.orientation.y, + odo.pose.pose.orientation.z, + odo.pose.pose.orientation.w + ) + _, _, self._vehicle_yaw = euler_from_quaternion(quaternion) + + def run_step(self, target_speed): # pylint: disable=no-self-use,unused-argument + """ + Execute one step of navigation. + :return: control + """ + control = CarlaEgoVehicleControl() + return control + + def _is_light_red(self, lights_list): + """ + Method to check if there is a red light affecting us. This version of + the method is compatible with both European and US style traffic lights. + + :param lights_list: list containing TrafficLight objects + :return: a tuple given by (bool_flag, traffic_light), where + - bool_flag is True if there is a traffic light in RED + affecting us and False otherwise + - traffic_light is the object itself or None if there is no + red traffic light affecting us + """ + if self._map_name == 'Town01' or self._map_name == 'Town02': + return self._is_light_red_europe_style(lights_list) + else: + return self._is_light_red_us_style(lights_list) + + def _is_light_red_europe_style(self, lights_list): + """ + This method is specialized to check European style traffic lights. + + :param lights_list: list containing TrafficLight objects + :return: a tuple given by (bool_flag, traffic_light), where + - bool_flag is True if there is a traffic light in RED + affecting us and False otherwise + - traffic_light is the object itself or None if there is no + red traffic light affecting us + """ + ego_vehicle_location = self._vehicle_location + ego_vehicle_waypoint = self.get_waypoint(ego_vehicle_location) + if not ego_vehicle_waypoint: + if not rospy.is_shutdown(): + rospy.logwarn("Could not get waypoint for ego vehicle.") + return (False, None) + + for traffic_light in lights_list: + object_waypoint = traffic_light[1] + if object_waypoint.road_id != ego_vehicle_waypoint.road_id or \ + object_waypoint.lane_id != ego_vehicle_waypoint.lane_id: + continue + if is_within_distance_ahead(object_waypoint.pose.position, ego_vehicle_location, + math.degrees(self._vehicle_yaw), + self._proximity_threshold): + traffic_light_state = CarlaTrafficLightStatus.RED + for status in self._traffic_lights: + if status.id == traffic_light[0]: + traffic_light_state = status.state + break + if traffic_light_state == CarlaTrafficLightStatus.RED: + return (True, traffic_light[0]) + + return (False, None) + + def get_waypoint(self, location): + """ + Helper to get waypoint for location via ros service + """ + if rospy.is_shutdown(): + return None + try: + response = self._get_waypoint_client(location) + return response.waypoint + except (rospy.ServiceException, rospy.ROSInterruptException) as e: + if not rospy.is_shutdown(): + rospy.logwarn("Service call 'get_waypoint' failed: {}".format(e)) + + def _is_light_red_us_style(self, lights_list): # pylint: disable=too-many-branches + """ + This method is specialized to check US style traffic lights. + + :param lights_list: list containing TrafficLight objects + :return: a tuple given by (bool_flag, traffic_light), where + - bool_flag is True if there is a traffic light in RED + affecting us and False otherwise + - traffic_light is the object itself or None if there is no + red traffic light affecting us + """ + ego_vehicle_location = self._vehicle_location + ego_vehicle_waypoint = self.get_waypoint(ego_vehicle_location) + if not ego_vehicle_waypoint: + if not rospy.is_shutdown(): + rospy.logwarn("Could not get waypoint for ego vehicle.") + return (False, None) + + if ego_vehicle_waypoint.is_junction: + # It is too late. Do not block the intersection! Keep going! + return (False, None) + + if self._local_planner.target_waypoint is not None: + if self._local_planner.target_waypoint.is_junction: + min_angle = 180.0 + sel_magnitude = 0.0 # pylint: disable=unused-variable + sel_traffic_light = None + for traffic_light in lights_list: + loc = traffic_light[1] + magnitude, angle = compute_magnitude_angle(loc.pose.position, + ego_vehicle_location, + math.degrees(self._vehicle_yaw)) + if magnitude < 60.0 and angle < min(25.0, min_angle): + sel_magnitude = magnitude + sel_traffic_light = traffic_light[0] + min_angle = angle + + if sel_traffic_light is not None: + # print('=== Magnitude = {} | Angle = {} | ID = {}'.format( + # sel_magnitude, min_angle, sel_traffic_light)) + + if self._last_traffic_light is None: + self._last_traffic_light = sel_traffic_light + + state = None + for status in self._traffic_lights: + if status.id == sel_traffic_light: + state = status.state + break + if state is None: + rospy.logwarn( + "Couldn't get state of traffic light {}".format( + sel_traffic_light)) + return (False, None) + + if state == CarlaTrafficLightStatus.RED: + return (True, self._last_traffic_light) + else: + self._last_traffic_light = None + + return (False, None) + + def _is_vehicle_hazard(self, vehicle_list, objects): + """ + Check if a given vehicle is an obstacle in our way. To this end we take + into account the road and lane the target vehicle is on and run a + geometry test to check if the target vehicle is under a certain distance + in front of our ego vehicle. + + WARNING: This method is an approximation that could fail for very large + vehicles, which center is actually on a different lane but their + extension falls within the ego vehicle lane. + + :param vehicle_list: list of potential obstacle to check + :return: a tuple given by (bool_flag, vehicle), where + - bool_flag is True if there is a vehicle ahead blocking us + and False otherwise + - vehicle is the blocker object itself + """ + + ego_vehicle_location = self._vehicle_location + + ego_vehicle_waypoint = self.get_waypoint(ego_vehicle_location) + if not ego_vehicle_waypoint: + if not rospy.is_shutdown(): + rospy.logwarn("Could not get waypoint for ego vehicle.") + return (False, None) + + for target_vehicle_id in vehicle_list: + # do not account for the ego vehicle + if target_vehicle_id == self._vehicle_id: + continue + + target_vehicle_location = None + for elem in objects: + if elem.id == target_vehicle_id: + target_vehicle_location = elem.pose + break + + if not target_vehicle_location: + rospy.logwarn("Location of vehicle {} not found".format(target_vehicle_id)) + continue + + # if the object is not in our lane it's not an obstacle + target_vehicle_waypoint = self.get_waypoint(target_vehicle_location.position) + if not target_vehicle_waypoint: + if not rospy.is_shutdown(): + rospy.logwarn("Could not get waypoint for target vehicle.") + return (False, None) + if target_vehicle_waypoint.road_id != ego_vehicle_waypoint.road_id or \ + target_vehicle_waypoint.lane_id != ego_vehicle_waypoint.lane_id: + #rospy.loginfo("Vehicle {} is not in our lane".format(target_vehicle_id)) + continue + + if is_within_distance_ahead(target_vehicle_location.position, self._vehicle_location, + math.degrees(self._vehicle_yaw), + self._proximity_threshold): + return (True, target_vehicle_id) + + return (False, None) + + def emergency_stop(self): # pylint: disable=no-self-use + """ + Send an emergency stop command to the vehicle + :return: + """ + control = CarlaEgoVehicleControl() + control.steer = 0.0 + control.throttle = 0.0 + control.brake = 1.0 + control.hand_brake = False + + return control diff --git a/carla_ad_agent/src/carla_ad_agent/basic_agent.py b/carla_ad_agent/src/carla_ad_agent/basic_agent.py new file mode 100644 index 00000000..91ac8ee1 --- /dev/null +++ b/carla_ad_agent/src/carla_ad_agent/basic_agent.py @@ -0,0 +1,129 @@ +#!/usr/bin/env python +# +# Copyright (c) 2018-2020 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +""" +BasicAgent implements a basic agent that navigates scenes to reach a given +target destination. This agent respects traffic lights and other vehicles. +""" + +import rospy +from nav_msgs.msg import Odometry +from derived_object_msgs.msg import ObjectArray +from carla_msgs.msg import CarlaActorList +from agent import Agent, AgentState +from local_planner import LocalPlanner +from carla_waypoint_types.srv import GetActorWaypoint + + +class BasicAgent(Agent): + """ + BasicAgent implements a basic agent that navigates scenes to reach a given + target destination. This agent respects traffic lights and other vehicles. + """ + + def __init__(self, role_name, ego_vehicle_id, avoid_risk=True): + """ + """ + super(BasicAgent, self).__init__(role_name, ego_vehicle_id) + + self._proximity_threshold = 10.0 # meters + self._state = AgentState.NAVIGATING + self._avoid_risk = avoid_risk + args_lateral_dict = { + 'K_P': 0.9, + 'K_D': 0.0, + 'K_I': 0.1} + self._local_planner = LocalPlanner(role_name, + opt_dict={'lateral_control_dict': args_lateral_dict}) + + self._vehicle_id_list = [] + self._lights_id_list = [] + self._actors_subscriber = rospy.Subscriber( + "/carla/actor_list", CarlaActorList, self.actors_updated) + self._objects = [] + self._objects_subscriber = rospy.Subscriber( + "/carla/{}/objects".format(role_name), ObjectArray, self.objects_updated) + + self._odometry_subscriber = rospy.Subscriber( + "/carla/{}/odometry".format(role_name), Odometry, self.odometry_updated) + + self._get_actor_waypoint_client = rospy.ServiceProxy( + '/carla_waypoint_publisher/{}/get_actor_waypoint'.format(role_name), GetActorWaypoint) + + def get_actor_waypoint(self, actor_id): + """ + helper method to get waypoint for actor via ros service + """ + try: + response = self._get_actor_waypoint_client(actor_id) + return response.waypoint + except (rospy.ServiceException, rospy.ROSInterruptException) as e: + if not rospy.is_shutdown: + rospy.logwarn("Service call failed: {}".format(e)) + + def odometry_updated(self, odo): + """ + callback on new odometry + """ + self._local_planner.odometry_updated(odo) + super(BasicAgent, self).odometry_updated(odo) + + def actors_updated(self, actors): + """ + callback on new actor list + """ + # retrieve relevant elements for safe navigation, i.e.: traffic lights + # and other vehicles + self._vehicle_id_list = [] + self._lights_id_list = [] + for actor in actors.actors: + if "vehicle" in actor.type: + self._vehicle_id_list.append(actor.id) + elif "traffic_light" in actor.type: + self._lights_id_list.append((actor.id, self.get_actor_waypoint(actor.id))) + + def objects_updated(self, objects): + """ + callback on new objects + """ + self._objects = objects.objects + + def run_step(self, target_speed): + """ + Execute one step of navigation. + :return: carla.VehicleControl + """ + + # is there an obstacle in front of us? + hazard_detected = False + + if self._avoid_risk: + # check possible obstacles + vehicle_state, vehicle = self._is_vehicle_hazard( # pylint: disable=unused-variable + self._vehicle_id_list, self._objects) + if vehicle_state: + #rospy.loginfo('=== Vehicle blocking ahead [{}])'.format(vehicle)) + self._state = AgentState.BLOCKED_BY_VEHICLE + hazard_detected = True + + # check for the state of the traffic lights + light_state, traffic_light = self._is_light_red( # pylint: disable=unused-variable + self._lights_id_list) + if light_state: + #rospy.loginfo('=== Red Light ahead [{}])'.format(traffic_light)) + + self._state = AgentState.BLOCKED_RED_LIGHT + hazard_detected = True + + if hazard_detected: + control = self.emergency_stop() + else: + self._state = AgentState.NAVIGATING + # standard local planner behavior + control = self._local_planner.run_step(target_speed) + + return control diff --git a/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py new file mode 100755 index 00000000..9c3abff8 --- /dev/null +++ b/carla_ad_agent/src/carla_ad_agent/carla_ad_agent.py @@ -0,0 +1,133 @@ +#!/usr/bin/env python +# +# Copyright (c) 2020 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +""" +A basic AD agent using CARLA waypoints +""" +import rospy +from nav_msgs.msg import Path +from std_msgs.msg import Float64 +from carla_msgs.msg import CarlaEgoVehicleInfo, CarlaEgoVehicleControl +from basic_agent import BasicAgent + + +class CarlaAdAgent(object): + """ + A basic AD agent using CARLA waypoints + """ + + def __init__(self, role_name, target_speed, avoid_risk): + """ + Constructor + """ + self._route_assigned = False + self._global_plan = None + self._agent = None + self._target_speed = target_speed + rospy.on_shutdown(self.on_shutdown) + + # wait for ego vehicle + vehicle_info = rospy.wait_for_message( + "/carla/{}/vehicle_info".format(role_name), CarlaEgoVehicleInfo) + + self._route_subscriber = rospy.Subscriber( + "/carla/{}/waypoints".format(role_name), Path, self.path_updated) + + self._target_speed_subscriber = rospy.Subscriber( + "/carla/{}/target_speed".format(role_name), Float64, self.target_speed_updated) + + self.vehicle_control_publisher = rospy.Publisher( + "/carla/{}/vehicle_control_cmd".format(role_name), CarlaEgoVehicleControl, queue_size=1) + + self._agent = BasicAgent(role_name, vehicle_info.id, # pylint: disable=no-member + avoid_risk) + + def on_shutdown(self): + """ + callback on shutdown + """ + rospy.loginfo("Shutting down, stopping ego vehicle...") + if self._agent: + self.vehicle_control_publisher.publish(self._agent.emergency_stop()) + + def target_speed_updated(self, target_speed): + """ + callback on new target speed + """ + rospy.loginfo("New target speed received: {}".format(target_speed.data)) + self._target_speed = target_speed.data + + def path_updated(self, path): + """ + callback on new route + """ + rospy.loginfo("New plan with {} waypoints received.".format(len(path.poses))) + if self._agent: + self.vehicle_control_publisher.publish(self._agent.emergency_stop()) + self._global_plan = path + self._route_assigned = False + + def run_step(self): + """ + Execute one step of navigation. + """ + control = CarlaEgoVehicleControl() + control.steer = 0.0 + control.throttle = 0.0 + control.brake = 0.0 + control.hand_brake = False + + if not self._agent: + rospy.loginfo("Waiting for ego vehicle...") + return control + + if not self._route_assigned and self._global_plan: + rospy.loginfo("Assigning plan...") + self._agent._local_planner.set_global_plan( # pylint: disable=protected-access + self._global_plan.poses) + self._route_assigned = True + else: + control = self._agent.run_step(self._target_speed) + + return control + + def run(self): + """ + + Control loop + + :return: + """ + + while not rospy.is_shutdown(): + control = self.run_step() + if control: + control.steer = -control.steer + self.vehicle_control_publisher.publish(control) + + +def main(): + """ + + main function + + :return: + """ + rospy.init_node('carla_ad_agent', anonymous=True) + role_name = rospy.get_param("~role_name", "ego_vehicle") + target_speed = rospy.get_param("~target_speed", 20) + avoid_risk = rospy.get_param("~avoid_risk", True) + controller = CarlaAdAgent(role_name, target_speed, avoid_risk) + try: + controller.run() + finally: + del controller + rospy.loginfo("Done") + + +if __name__ == "__main__": + main() diff --git a/carla_ad_agent/src/carla_ad_agent/local_planner.py b/carla_ad_agent/src/carla_ad_agent/local_planner.py new file mode 100644 index 00000000..ab14dfca --- /dev/null +++ b/carla_ad_agent/src/carla_ad_agent/local_planner.py @@ -0,0 +1,203 @@ +#!/usr/bin/env python +# +# Copyright (c) 2018-2020 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +""" +This module contains a local planner to perform +low-level waypoint following based on PID controllers. +""" + +from collections import deque +import math +import rospy +from geometry_msgs.msg import PointStamped +from geometry_msgs.msg import Pose +from tf.transformations import euler_from_quaternion +from carla_waypoint_types.srv import GetWaypoint +from carla_msgs.msg import CarlaEgoVehicleControl +from vehicle_pid_controller import VehiclePIDController +from misc import distance_vehicle + + +class LocalPlanner(object): + """ + LocalPlanner implements the basic behavior of following a trajectory of waypoints that is + generated on-the-fly. The low-level motion of the vehicle is computed by using two PID + controllers, one is used for the lateral control and the other for the longitudinal + control (cruise speed). + + When multiple paths are available (intersections) this local planner makes a random choice. + """ + + # minimum distance to target waypoint as a percentage (e.g. within 90% of + # total distance) + MIN_DISTANCE_PERCENTAGE = 0.9 + + def __init__(self, role_name, opt_dict=None): + """ + :param vehicle: actor to apply to local planner logic onto + :param opt_dict: dictionary of arguments with the following semantics: + + target_speed -- desired cruise speed in Km/h + + sampling_radius -- search radius for next waypoints in seconds: e.g. 0.5 seconds ahead + + lateral_control_dict -- dictionary of arguments to setup the lateral PID controller + {'K_P':, 'K_D':, 'K_I'} + + longitudinal_control_dict -- dictionary of arguments to setup the longitudinal + PID controller + {'K_P':, 'K_D':, 'K_I'} + """ + self._current_waypoint = None + self.target_waypoint = None + self._vehicle_controller = None + self._global_plan = None + self._waypoints_queue = deque(maxlen=20000) + self._buffer_size = 5 + self._waypoint_buffer = deque(maxlen=self._buffer_size) + self._vehicle_yaw = None + self._current_speed = None + self._current_pose = None + + self._target_point_publisher = rospy.Publisher( + "/next_target", PointStamped, queue_size=1) + rospy.wait_for_service('/carla_waypoint_publisher/{}/get_waypoint'.format(role_name)) + + self._get_waypoint_client = rospy.ServiceProxy( + '/carla_waypoint_publisher/{}/get_waypoint'.format(role_name), GetWaypoint) + + # initializing controller + self._init_controller(opt_dict) + + def get_waypoint(self, location): + """ + Helper to get waypoint from a ros service + """ + try: + response = self._get_waypoint_client(location) + return response.waypoint + except (rospy.ServiceException, rospy.ROSInterruptException) as e: + if not rospy.is_shutdown: + rospy.logwarn("Service call failed: {}".format(e)) + + def odometry_updated(self, odo): + """ + Callback on new odometry + """ + self._current_speed = math.sqrt(odo.twist.twist.linear.x ** 2 + + odo.twist.twist.linear.y ** 2 + + odo.twist.twist.linear.z ** 2) * 3.6 + + self._current_pose = odo.pose.pose + quaternion = ( + odo.pose.pose.orientation.x, + odo.pose.pose.orientation.y, + odo.pose.pose.orientation.z, + odo.pose.pose.orientation.w + ) + _, _, self._vehicle_yaw = euler_from_quaternion(quaternion) + + def _init_controller(self, opt_dict): + """ + Controller initialization. + + :param opt_dict: dictionary of arguments. + :return: + """ + # default params + self._current_speed = 0.0 # Km/h + self._current_pose = Pose() + args_lateral_dict = { + 'K_P': 1.95, + 'K_D': 0.01, + 'K_I': 1.4} + args_longitudinal_dict = { + 'K_P': 0.2, + 'K_D': 0.05, + 'K_I': 0.1} + + # parameters overload + if opt_dict: + if 'lateral_control_dict' in opt_dict: + args_lateral_dict = opt_dict['lateral_control_dict'] + if 'longitudinal_control_dict' in opt_dict: + args_longitudinal_dict = opt_dict['longitudinal_control_dict'] + + self._current_waypoint = self.get_waypoint(self._current_pose.position) + self._vehicle_controller = VehiclePIDController(args_lateral=args_lateral_dict, + args_longitudinal=args_longitudinal_dict) + + self._global_plan = False + + def set_global_plan(self, current_plan): + """ + set a global plan to follow + """ + self._waypoints_queue.clear() + self._waypoint_buffer.clear() + for elem in current_plan: + self._waypoints_queue.append(elem.pose) + self._global_plan = True + + def run_step(self, target_speed): + """ + Execute one step of local planning which involves running the longitudinal + and lateral PID controllers to follow the waypoints trajectory. + """ + if not self._waypoints_queue: + control = CarlaEgoVehicleControl() + control.steer = 0.0 + control.throttle = 0.0 + control.brake = 1.0 + control.hand_brake = False + control.manual_gear_shift = False + + return control + + # Buffering the waypoints + if not self._waypoint_buffer: + for i in range(self._buffer_size): + if self._waypoints_queue: + self._waypoint_buffer.append( + self._waypoints_queue.popleft()) + else: + break + + # current vehicle waypoint + self._current_waypoint = self.get_waypoint(self._current_pose.position) + + # target waypoint + target_route_point = self._waypoint_buffer[0] + + # for us redlight-detection + self.target_waypoint = self.get_waypoint(target_route_point.position) + + target_point = PointStamped() + target_point.header.frame_id = "map" + target_point.point.x = target_route_point.position.x + target_point.point.y = target_route_point.position.y + target_point.point.z = target_route_point.position.z + self._target_point_publisher.publish(target_point) + # move using PID controllers + control = self._vehicle_controller.run_step( + target_speed, self._current_speed, self._current_pose, target_route_point) + + # purge the queue of obsolete waypoints + max_index = -1 + + sampling_radius = target_speed * 1 / 3.6 # 1 seconds horizon + min_distance = sampling_radius * self.MIN_DISTANCE_PERCENTAGE + + for i, route_point in enumerate(self._waypoint_buffer): + if distance_vehicle( + route_point, self._current_pose.position) < min_distance: + max_index = i + if max_index >= 0: + for i in range(max_index + 1): + self._waypoint_buffer.popleft() + + return control diff --git a/carla_ad_agent/src/carla_ad_agent/misc.py b/carla_ad_agent/src/carla_ad_agent/misc.py new file mode 100644 index 00000000..9495b815 --- /dev/null +++ b/carla_ad_agent/src/carla_ad_agent/misc.py @@ -0,0 +1,70 @@ +#!/usr/bin/env python +# +# Copyright (c) 2018-2020 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +""" This module contains helper functions """ + +import math +import numpy as np + + +def is_within_distance_ahead(target_location, current_location, orientation, max_distance): + """ + Check if a target object is within a certain distance in front of a reference object. + + :param target_location: location of the target object + :param current_location: location of the reference object + :param orientation: orientation of the reference object + :param max_distance: maximum allowed distance + :return: True if target object is within max_distance ahead of the reference object + """ + target_vector = np.array([target_location.x - current_location.x, + target_location.y - current_location.y]) + norm_target = np.linalg.norm(target_vector) + + # If the vector is too short, we can simply stop here + if norm_target < 0.001: + return True + + if norm_target > max_distance: + return False + + forward_vector = np.array( + [math.cos(math.radians(orientation)), math.sin(math.radians(orientation))]) + d_angle = math.degrees(math.acos(np.dot(forward_vector, target_vector) / norm_target)) + + return d_angle < 90.0 + + +def compute_magnitude_angle(target_location, current_location, orientation): + """ + Compute relative angle and distance between a target_location and a current_location + + :param target_location: location of the target object + :param current_location: location of the reference object + :param orientation: orientation of the reference object + :return: a tuple composed by the distance to the object and the angle between both objects + """ + target_vector = np.array([target_location.x - current_location.x, + target_location.y - current_location.y]) + norm_target = np.linalg.norm(target_vector) + + forward_vector = np.array([math.cos(math.radians(orientation)), + math.sin(math.radians(orientation))]) + d_angle = math.degrees( + math.acos(np.clip(np.dot(forward_vector, target_vector) / norm_target, -1., 1.))) + + return (norm_target, d_angle) + + +def distance_vehicle(waypoint, vehicle_position): + """ + calculate distance between waypoint and vehicle position + """ + dx = waypoint.position.x - vehicle_position.x + dy = waypoint.position.y - vehicle_position.y + + return math.sqrt(dx * dx + dy * dy) diff --git a/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py b/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py new file mode 100644 index 00000000..6d19936d --- /dev/null +++ b/carla_ad_agent/src/carla_ad_agent/vehicle_pid_controller.py @@ -0,0 +1,170 @@ +#!/usr/bin/env python +# +# Copyright (c) 2018-2020 Intel Corporation +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# + +""" This module contains PID controllers to perform lateral and longitudinal control. """ + +from collections import deque +import math +import numpy as np +import rospy +from tf.transformations import euler_from_quaternion +from geometry_msgs.msg import Point +from carla_msgs.msg import CarlaEgoVehicleControl + + +class VehiclePIDController(object): # pylint: disable=too-few-public-methods + """ + VehiclePIDController is the combination of two PID controllers (lateral and longitudinal) + to perform the low level control a vehicle from client side + """ + + def __init__(self, args_lateral=None, args_longitudinal=None): + """ + :param vehicle: actor to apply to local planner logic onto + :param args_lateral: dictionary of arguments to set the lateral PID controller using + the following semantics: + K_P -- Proportional term + K_D -- Differential term + K_I -- Integral term + :param args_longitudinal: dictionary of arguments to set the longitudinal PID + controller using the following semantics: + K_P -- Proportional term + K_D -- Differential term + K_I -- Integral term + """ + if not args_lateral: + args_lateral = {'K_P': 1.0, 'K_D': 0.0, 'K_I': 0.0} + if not args_longitudinal: + args_longitudinal = {'K_P': 1.0, 'K_D': 0.0, 'K_I': 0.0} + + self._lon_controller = PIDLongitudinalController(**args_longitudinal) + self._lat_controller = PIDLateralController(**args_lateral) + self._last_control_time = rospy.get_time() + + def run_step(self, target_speed, current_speed, current_pose, waypoint): + """ + Execute one step of control invoking both lateral and longitudinal + PID controllers to reach a target waypoint at a given target_speed. + + :param target_speed: desired vehicle speed + :param waypoint: target location encoded as a waypoint + :return: distance (in meters) to the waypoint + """ + current_time = rospy.get_time() + dt = current_time-self._last_control_time + if dt == 0.0: + dt = 0.000001 + control = CarlaEgoVehicleControl() + throttle = self._lon_controller.run_step(target_speed, current_speed, dt) + steering = self._lat_controller.run_step(current_pose, waypoint, dt) + self._last_control_time = current_time + control.steer = steering + control.throttle = throttle + control.brake = 0.0 + control.hand_brake = False + control.manual_gear_shift = False + + return control + + +class PIDLongitudinalController(object): # pylint: disable=too-few-public-methods + """ + PIDLongitudinalController implements longitudinal control using a PID. + """ + + def __init__(self, K_P=1.0, K_D=0.0, K_I=0.0): + """ + :param vehicle: actor to apply to local planner logic onto + :param K_P: Proportional term + :param K_D: Differential term + :param K_I: Integral term + """ + self._K_P = K_P + self._K_D = K_D + self._K_I = K_I + self._e_buffer = deque(maxlen=30) + + def run_step(self, target_speed, current_speed, dt): + """ + Estimate the throttle of the vehicle based on the PID equations + + :param target_speed: target speed in Km/h + :param current_speed: current speed of the vehicle in Km/h + :return: throttle control in the range [0, 1] + """ + _e = (target_speed - current_speed) + self._e_buffer.append(_e) + + if len(self._e_buffer) >= 2: + _de = (self._e_buffer[-1] - self._e_buffer[-2]) / dt + _ie = sum(self._e_buffer) * dt + else: + _de = 0.0 + _ie = 0.0 + + return np.clip((self._K_P * _e) + (self._K_D * _de / dt) + (self._K_I * _ie * dt), 0.0, 1.0) + + +class PIDLateralController(object): # pylint: disable=too-few-public-methods + """ + PIDLateralController implements lateral control using a PID. + """ + + def __init__(self, K_P=1.0, K_D=0.0, K_I=0.0): + """ + :param vehicle: actor to apply to local planner logic onto + :param K_P: Proportional term + :param K_D: Differential term + :param K_I: Integral term + """ + self._K_P = K_P + self._K_D = K_D + self._K_I = K_I + self._e_buffer = deque(maxlen=10) + + def run_step(self, current_pose, waypoint, dt): + """ + Estimate the steering angle of the vehicle based on the PID equations + + :param waypoint: target waypoint + :param current_pose: current pose of the vehicle + :return: steering control in the range [-1, 1] + """ + v_begin = current_pose.position + quaternion = ( + current_pose.orientation.x, + current_pose.orientation.y, + current_pose.orientation.z, + current_pose.orientation.w + ) + _, _, yaw = euler_from_quaternion(quaternion) + v_end = Point() + v_end.x = v_begin.x + math.cos(yaw) + v_end.y = v_begin.y + math.sin(yaw) + + v_vec = np.array([v_end.x - v_begin.x, v_end.y - v_begin.y, 0.0]) + w_vec = np.array([waypoint.position.x - + v_begin.x, waypoint.position.y - + v_begin.y, 0.0]) + _dot = math.acos(np.clip(np.dot(w_vec, v_vec) / + (np.linalg.norm(w_vec) * np.linalg.norm(v_vec)), -1.0, 1.0)) + + _cross = np.cross(v_vec, w_vec) + if _cross[2] < 0: + _dot *= -1.0 + + self._e_buffer.append(_dot) + if len(self._e_buffer) >= 2: + _de = (self._e_buffer[-1] - self._e_buffer[-2]) / dt + _ie = sum(self._e_buffer) * dt + else: + _de = 0.0 + _ie = 0.0 + + return np.clip((self._K_P * _dot) + (self._K_D * _de / + dt) + (self._K_I * _ie * dt), -1.0, 1.0) diff --git a/carla_ad_demo/CMakeLists.txt b/carla_ad_demo/CMakeLists.txt new file mode 100644 index 00000000..56b4a771 --- /dev/null +++ b/carla_ad_demo/CMakeLists.txt @@ -0,0 +1,19 @@ +cmake_minimum_required(VERSION 2.8.3) +project(carla_ad_demo) + +find_package(catkin REQUIRED COMPONENTS + roslaunch +) + + +roslaunch_add_file_check(launch) + +catkin_package() + +install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch +) + +install(DIRECTORY config/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config +) diff --git a/carla_ad_demo/README.md b/carla_ad_demo/README.md new file mode 100644 index 00000000..e6b17f51 --- /dev/null +++ b/carla_ad_demo/README.md @@ -0,0 +1,36 @@ +# CARLA AD Demo + +This meta package provides everything to launch a CARLA ROS environment with an AD vehicle. + + +![CARLA AD Demo](../docs/images/rviz_carla_plugin.png "rviz carla plugin") + + +## Startup + + export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla-.egg:/PythonAPI/carla/ + export SCENARIO_RUNNER_PATH:= + roslaunch carla_ad_demo carla_ad_demo_with_rviz.launch + +### Modes + +#### Following A Random Route + +On startup, an ego vehicle is spawned and follows a random route to a goal. + +You might want to spawn additional vehicles (or pedestrians) by manually executing: + + /PythonAPI/examples/spawn_npc.py + +You can modify start position and goal within the [launch file](launch/carla_ad_demo.launch). The route is currently randomly (regarding the left/right turns) calculated. + +#### Scenario Execution + +If you prefer to execute a predefined scenario, select to example scenario "FollowLeadingVehicle" within the RVIZ Carla Plugin and press "Execute". The ego vehicle gets repositioned and the scenario is processed. + +You can specify your own scenarios by publishing to `/carla/available_scenarios`. See the [launch file](launch/carla_ad_demo_with_rviz.launch) for an example. + + +## Troubleshooting + +If the example scenario fails, please analyze the ros log and follow the scenario runner [Getting Started](https://github.com/carla-simulator/scenario_runner/blob/master/Docs/getting_started.md) to verify that it's working standalone. diff --git a/carla_ad_demo/config/FollowLeadingVehicle.xosc b/carla_ad_demo/config/FollowLeadingVehicle.xosc new file mode 100644 index 00000000..db33827d --- /dev/null +++ b/carla_ad_demo/config/FollowLeadingVehicle.xosc @@ -0,0 +1,270 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ + + + + + + + + + + +
+ + + + + +
+ + + + + + + + + + + +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
diff --git a/carla_ad_demo/config/carla_ad_demo.rviz b/carla_ad_demo/config/carla_ad_demo.rviz new file mode 100644 index 00000000..35fd2f9d --- /dev/null +++ b/carla_ad_demo/config/carla_ad_demo.rviz @@ -0,0 +1,173 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + Splitter Ratio: 0.5 + Tree Height: 78 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: Camera + - Class: rviz_carla_plugin/CarlaControl + Name: CarlaControl +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 25; 255; 0 + Enabled: true + Head Diameter: 0.30000001192092896 + Head Length: 0.20000000298023224 + Length: 0.30000001192092896 + Line Style: Lines + Line Width: 0.029999999329447746 + Name: Path + Offset: + X: 0 + Y: 0 + Z: 0 + Pose Color: 255; 85; 255 + Pose Style: None + Radius: 0.029999999329447746 + Shaft Diameter: 0.10000000149011612 + Shaft Length: 0.10000000149011612 + Topic: /carla/ego_vehicle/waypoints + Unreliable: false + Value: true + - Class: rviz/Camera + Enabled: true + Image Rendering: background and overlay + Image Topic: /carla/ego_vehicle/camera/rgb/spectator_view/image_color + Name: Camera + Overlay Alpha: 0.5 + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: true + Visibility: + Grid: true + Marker: true + Path: true + Value: true + Zoom Factor: 1 + - Class: rviz/Marker + Enabled: true + Marker Topic: /carla/marker + Name: Marker + Namespaces: + "": true + Queue Size: 100 + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: map + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/ThirdPersonFollower + Distance: 13.610654830932617 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0 + Y: 0 + Z: 0 + Focal Shape Fixed Size: false + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.49539870023727417 + Target Frame: ego_vehicle + Value: ThirdPersonFollower (rviz) + Yaw: 3.1504008769989014 + Saved: ~ +Window Geometry: + Camera: + collapsed: false + CarlaControl: + collapsed: false + Displays: + collapsed: false + Height: 1050 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd0000000400000000000001fe00000367fc020000000dfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006800fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000046000000e6000000e600fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d00610067006501000002870000001a0000000000000000fb0000000a0049006d00610067006501000002a70000001a0000000000000000fb0000000a0049006d00610067006501000002c70000001a0000000000000000fb0000000c00430061006d0065007200610100000132000001960000001a00fffffffb00000018004300610072006c00610043006f006e00740072006f006c01000002ce000000df000000df00ffffff000000010000010f00000367fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000004600000367000000be00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000077e00000044fc0100000002fb0000000800540069006d006501000000000000077e000002e400fffffffb0000000800540069006d00650100000000000004500000000000000000000004650000036700000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1918 + X: 0 + Y: 27 diff --git a/carla_ad_demo/config/sensors.json b/carla_ad_demo/config/sensors.json new file mode 100644 index 00000000..3d8fe104 --- /dev/null +++ b/carla_ad_demo/config/sensors.json @@ -0,0 +1,48 @@ +{ + "sensors": [ + { + "type": "sensor.camera.rgb", + "id": "view", + "x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": -20.0, "yaw": 0.0, + "width": 800, + "height": 600, + "fov": 100, + "sensor_tick": 0.05, + "gamma": 2.2, + "shutter_speed": 60.0, + "iso": 1200.0, + "fstop": 1.4, + "min_fstop": 1.2, + "blade_count": 5, + "exposure_mode": "manual", + "exposure_compensation": 3.0, + "exposure_min_bright": 0.1, + "exposure_max_bright": 2.0, + "exposure_speed_up": 3.0, + "exposure_speed_down": 1.0, + "calibration_constant": 16.0, + "focal_distance": 1000.0, + "blur_amount": 1.0, + "blur_radius": 0.0, + "motion_blur_intensity": 0.45, + "motion_blur_max_distortion": 0.35, + "motion_blur_min_object_screen_size": 0.1, + "slope": 0.88, + "toe": 0.55, + "shoulder": 0.26, + "black_clip": 0.0, + "white_clip": 0.04, + "temp": 6500.0, + "tint": 0.0, + "chromatic_aberration_intensity": 0.0, + "chromatic_aberration_offset": 0.0, + "enable_postprocess_effects": "True", + "lens_circle_falloff": 5.0, + "lens_circle_multiplier": 0.0, + "lens_k": -1.0, + "lens_kcube": 0.0, + "lens_x_size": 0.08, + "lens_y_size": 0.08 + } + ] +} diff --git a/carla_ad_demo/launch/carla_ad_demo.launch b/carla_ad_demo/launch/carla_ad_demo.launch new file mode 100644 index 00000000..c679c7bf --- /dev/null +++ b/carla_ad_demo/launch/carla_ad_demo.launch @@ -0,0 +1,71 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/carla_ad_demo/launch/carla_ad_demo_with_rviz.launch b/carla_ad_demo/launch/carla_ad_demo_with_rviz.launch new file mode 100644 index 00000000..2efff80c --- /dev/null +++ b/carla_ad_demo/launch/carla_ad_demo_with_rviz.launch @@ -0,0 +1,84 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/carla_ad_demo/package.xml b/carla_ad_demo/package.xml new file mode 100644 index 00000000..4d354b9e --- /dev/null +++ b/carla_ad_demo/package.xml @@ -0,0 +1,20 @@ + + + carla_ad_demo + 0.0.1 + The carla_ad_demo package + CARLA Simulator Team + MIT + catkin + carla_ros_bridge + carla_ego_vehicle + carla_waypoint_publisher + carla_ad_agent + carla_manual_control + rviz_carla_plugin + carla_twist_to_control + carla_spectator_camera + carla_ros_scenario_runner + + + diff --git a/carla_ros_scenario_runner/CMakeLists.txt b/carla_ros_scenario_runner/CMakeLists.txt new file mode 100644 index 00000000..877653c6 --- /dev/null +++ b/carla_ros_scenario_runner/CMakeLists.txt @@ -0,0 +1,23 @@ +cmake_minimum_required(VERSION 2.8.3) +project(carla_ros_scenario_runner) + +find_package(catkin REQUIRED COMPONENTS + roslaunch +) + +catkin_python_setup() + +roslaunch_add_file_check(launch) + +catkin_package() + +catkin_install_python(PROGRAMS + src/carla_ros_scenario_runner/carla_ros_scenario_runner.py + src/carla_ros_scenario_runner/application_runner.py + src/carla_ros_scenario_runner/scenario_runner_runner.py + DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch +) diff --git a/carla_ros_scenario_runner/README.md b/carla_ros_scenario_runner/README.md new file mode 100644 index 00000000..ab803b35 --- /dev/null +++ b/carla_ros_scenario_runner/README.md @@ -0,0 +1,45 @@ +# ROS Scenario Runner + +This is a wrapper to execute OpenScenarios with the CARLA [scenario runner](https://github.com/carla-simulator/scenario_runner) via ROS. + +It is best used from within the [rviz_carla_plugin](../rviz_carla_plugin). + +## Setup + +Please follow the scenario runner [Getting Started](https://github.com/carla-simulator/scenario_runner/blob/master/Docs/getting_started.md) and verify, that scenario_runner is working, if started manually. + +Additionally, please execute: + + sudo apt install python-pexpect + +## Startup + +The environment variables are forwarded to scenario_runner, therefore set them to: + + export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla-.egg:/PythonAPI/carla/ + +To run the ROS node: + + roslaunch carla_ros_scenario_runner carla_ros_scenario_runner.launch scenario_runner_path:= + +To run a scenario from commandline: + + rosservice call /scenario_runner/execute_scenario "{ 'scenario': { 'scenario_file': '', 'target_speed': 10.0, 'destination': { 'position': { 'x': 10, 'y': 10, 'z':0 } } } }" + + +## Available services + +| Service | Description | Type | +| ----------------------------------------------------------- | ----------- | -------------------------------------------------------------------- | +| `/scenario_runner/execute_scenario` | Execute a scenario. If another scenario is currently running, it gets stopped. | [carla_ros_scenario_runner_types.ExecuteScenario](../carla_ros_scenario_runner_types/srv/ExecuteScenario.srv) | + + +## Available topics + + +| Topic | Description | Type | +| ------------------------------------- | ----------- | -------------------------------------------------------------------- | +| `/carla//target_speed` | The ego vehicle target speed | [std_msgs.Float64](http://docs.ros.org/api/std_msgs/html/msg/Float64.html) | +| `/carla//goal` | The ego vehicle destination (e.g. used by [carla_waypoint_publisher](../carla_waypoint_publisher)) | [geometry_msgs.PoseStamped](http://docs.ros.org/api/geometry_msgs/html/msg/PoseStamped.html) | +| `/scenario_runner/status` | The current status of the scenario runner execution (e.g. used by the [rviz_carla_plugin](../rviz_carla_plugin)) | [carla_ros_scenario_runner_types.CarlaScenarioRunnerStatus](../carla_ros_scenario_runner_types/msg/CarlaScenarioRunnerStatus.msg) | + diff --git a/carla_ros_scenario_runner/launch/carla_ros_scenario_runner.launch b/carla_ros_scenario_runner/launch/carla_ros_scenario_runner.launch new file mode 100644 index 00000000..def00183 --- /dev/null +++ b/carla_ros_scenario_runner/launch/carla_ros_scenario_runner.launch @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + + diff --git a/carla_ros_scenario_runner/package.xml b/carla_ros_scenario_runner/package.xml new file mode 100644 index 00000000..a7701fe1 --- /dev/null +++ b/carla_ros_scenario_runner/package.xml @@ -0,0 +1,19 @@ + + + carla_ros_scenario_runner + 0.0.0 + The carla_ros_scenario_runner package + CARLA Simulator Team + MIT + catkin + rospy + roslaunch + rospy + rospy + carla_msgs + carla_ros_scenario_runner_types + std_msgs + + + + diff --git a/carla_ros_scenario_runner/setup.py b/carla_ros_scenario_runner/setup.py new file mode 100644 index 00000000..1204b037 --- /dev/null +++ b/carla_ros_scenario_runner/setup.py @@ -0,0 +1,13 @@ +""" +Setup for carla_ros_scenario_runner +""" + +from distutils.core import setup +from catkin_pkg.python_setup import generate_distutils_setup + +d = generate_distutils_setup( + packages=['carla_ros_scenario_runner'], + package_dir={'': 'src'} +) + +setup(**d) diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/__init__.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py new file mode 100755 index 00000000..dcff47b1 --- /dev/null +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/application_runner.py @@ -0,0 +1,152 @@ +#!/usr/bin/env python +# +# Copyright (c) 2020 Intel Corporation +# +""" +Execute an application. +""" +import os +from enum import Enum +from threading import Thread, Event +from datetime import datetime, timedelta +import pexpect + + +class ApplicationStatus(Enum): + """ + States of an application + """ + STOPPED = 0 + STARTING = 1 + RUNNING = 2 + SHUTTINGDOWN = 3 + ERROR = 4 + + +class ApplicationRunner(object): + + """ + Execute application + """ + + def __init__(self, status_updated_fct, log_fct, ready_string=""): + """ + Constructor + """ + self._app_thread = None + self._status_updated_fct = status_updated_fct + self._log_fct = log_fct + self._shutdown_requested_event = Event() + self._ready_string = ready_string + + def execute(self, cmdline, env=None, cwd=None): + """ + Starts a thread to execute the application + """ + if self.is_running(): + self._log_fct("Application already running!") + return False + + self._shutdown_requested_event.clear() + self._app_thread = Thread(target=self.start_and_run, args=(cmdline, + env, + cwd, + self._shutdown_requested_event, + self._ready_string, + self._status_updated_fct, + self._log_fct,)) + self._app_thread.start() + + return True + + def start_and_run(self, cmdline, env, cwd, shutdown_requested_event, ready_string, # pylint: disable=too-many-arguments + status_updated_fct, log_fct): + """ + thread function + """ + status_updated_fct(ApplicationStatus.STARTING) + try: + process = self.start_process(cmdline, log_fct, env=env, cwd=cwd) + self.run(process, shutdown_requested_event, ready_string, status_updated_fct, log_fct) + except (KeyError, pexpect.ExceptionPexpect) as e: + self._log_fct("Error while starting process: {}".format(e)) + status_updated_fct(ApplicationStatus.ERROR) + + def is_running(self): + """ + returns if the application is still running + """ + if self._app_thread is None: + return False + + return self._app_thread.is_alive() + + def shutdown(self): + """ + Shut down the application thread + """ + if not self.is_running(): + return + self._log_fct("Requesting shutdown...") + self._status_updated_fct(ApplicationStatus.SHUTTINGDOWN) + self._shutdown_requested_event.set() + if self._app_thread: + self._app_thread.join() + self._log_fct("Shutdown finished.") + + def start_process(self, argument_list, log_fct, env=None, cwd=None): # pylint: disable=no-self-use + """ + Starts a process. + """ + if not argument_list: + raise KeyError("No arguments given!") + executable = argument_list[0] + if not os.path.isfile(executable): + raise KeyError("The executable {} does not exist".format(executable)) + log_fct("Executing: {}".format(" ".join(argument_list))) + process = pexpect.spawn(" ".join(argument_list), env=env, cwd=cwd) + #process.logfile_read = sys.stdout + return process + + def run(self, process, shutdown_requested_event, ready_string, status_updated_fct, log_fct): # pylint: disable=no-self-use,too-many-arguments + """ + Threaded application execution + + :return: + """ + shutting_down_trigger_time = None + signaled_running = False + while True: + if shutdown_requested_event.is_set(): + if shutting_down_trigger_time is None: + shutting_down_trigger_time = datetime.now() + log_fct("Shutdown requested while process is still \ + running. Sending SIGHUP/SIGINT...") + process.terminate(force=False) + else: + if (datetime.now() - shutting_down_trigger_time) > timedelta(seconds=8): + log_fct("Waited 8s for application to exit. Forcing Shutdown. \ + Sending SIGKILL") + process.terminate(force=True) + try: + process.expect(".*\n", timeout=0.1) + log_fct(process.after.strip()) + if not signaled_running: + if process.after.find(ready_string) != -1: + status_updated_fct(ApplicationStatus.RUNNING) + log_fct("Application is ready.") + signaled_running = True + except pexpect.EOF: + # application exited + log_fct(process.before.strip()) + log_fct("Application exited. Exiting run loop") + break + except pexpect.TIMEOUT: + # no output received + pass + + process.close() + if process.exitstatus == 0: + status_updated_fct(ApplicationStatus.STOPPED) + else: + status_updated_fct(ApplicationStatus.ERROR) diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py new file mode 100755 index 00000000..77ae976e --- /dev/null +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/carla_ros_scenario_runner.py @@ -0,0 +1,169 @@ +#!/usr/bin/env python +# +# Copyright (c) 2020 Intel Corporation. +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +""" +Execute scenarios via ros service + +Internally, the CARLA scenario runner is executed +""" +import sys +import os +try: + import queue +except ImportError: + import Queue as queue +import rospy +from geometry_msgs.msg import PoseStamped +from std_msgs.msg import Float64 +from carla_ros_scenario_runner_types.srv import ExecuteScenario, ExecuteScenarioResponse +from carla_ros_scenario_runner_types.msg import CarlaScenarioRunnerStatus +from application_runner import ApplicationStatus +from scenario_runner_runner import ScenarioRunnerRunner + +# Check Python dependencies of scenario runner +try: + import carla # pylint: disable=unused-import +except ImportError: + print "ERROR: CARLA Python Egg not available. Please add \ + /PythonAPI/carla/dist/carla--\ + py-linux-x86_64.egg to your PYTHONPATH." + sys.exit(1) + +try: + from agents.navigation.local_planner import LocalPlanner # pylint: disable=unused-import +except ImportError: + print "ERROR: CARLA Python Agents not available. \ + Please add /PythonAPI/carla to your PYTHONPATH." + sys.exit(1) + + +class CarlaRosScenarioRunner(object): + """ + Execute scenarios via ros service + """ + + def __init__(self, role_name, host, scenario_runner_path): + """ + Constructor + """ + self._goal_publisher = rospy.Publisher( + "/carla/{}/goal".format(role_name), PoseStamped, queue_size=1, latch=True) + self._target_speed_publisher = rospy.Publisher( + "/carla/{}/target_speed".format(role_name), Float64, queue_size=1, latch=True) + self._status_publisher = rospy.Publisher( + "/scenario_runner/status", CarlaScenarioRunnerStatus, queue_size=1, latch=True) + self.scenario_runner_status_updated(ApplicationStatus.STOPPED) + self._scenario_runner = ScenarioRunnerRunner( + scenario_runner_path, + host, + self.scenario_runner_status_updated, + self.scenario_runner_log) + self._request_queue = queue.Queue() + self._execute_scenario_service = rospy.Service( + '/scenario_runner/execute_scenario', ExecuteScenario, self.execute_scenario) + + def scenario_runner_log(self, log): # pylint: disable=no-self-use + """ + Callback for application logs + """ + rospy.logwarn("[SC]{}".format(log)) + + def scenario_runner_status_updated(self, status): + """ + Executed from application runner whenever the status changed + """ + rospy.loginfo("Status updated to {}".format(status)) + val = CarlaScenarioRunnerStatus.STOPPED + if status == ApplicationStatus.STOPPED: + val = CarlaScenarioRunnerStatus.STOPPED + elif status == ApplicationStatus.STARTING: + val = CarlaScenarioRunnerStatus.STARTING + elif status == ApplicationStatus.RUNNING: + val = CarlaScenarioRunnerStatus.RUNNING + elif status == ApplicationStatus.SHUTTINGDOWN: + val = CarlaScenarioRunnerStatus.SHUTTINGDOWN + else: + val = CarlaScenarioRunnerStatus.ERROR + status = CarlaScenarioRunnerStatus() + status.status = val + self._status_publisher.publish(status) + + def execute_scenario(self, req): + """ + Execute a scenario + """ + rospy.loginfo("Scenario Execution requested...") + + response = ExecuteScenarioResponse() + response.result = True + if not os.path.isfile(req.scenario.scenario_file): + rospy.logwarn("Requested scenario file not existing {}".format( + req.scenario.scenario_file)) + response.result = False + else: + self._request_queue.put(req.scenario) + return response + + def run(self): + """ + Control loop + + :return: + """ + current_req = None + while not rospy.is_shutdown(): + if current_req: + if self._scenario_runner.is_running(): + rospy.loginfo("Scenario Runner currently running. Shutting down.") + self._scenario_runner.shutdown() + rospy.loginfo("Scenario Runner stopped.") + rospy.loginfo("Executing scenario {}...".format(current_req.name)) + # publish goal + goal = PoseStamped(pose=current_req.destination) + goal.header.stamp = rospy.get_rostime() + goal.header.frame_id = "map" + self._goal_publisher.publish(goal) + # publish target speed + self._target_speed_publisher.publish(Float64(data=current_req.target_speed)) + # execute scenario + scenario_executed = self._scenario_runner.execute_scenario( + current_req.scenario_file) + if not scenario_executed: + rospy.logwarn("Unable to execute scenario.") + current_req = None + else: + try: + current_req = self._request_queue.get(block=True, timeout=0.5) + except queue.Empty: + # no new request + pass + if self._scenario_runner.is_running(): + rospy.loginfo("Scenario Runner currently running. Shutting down.") + self._scenario_runner.shutdown() + + +def main(): + """ + + main function + + :return: + """ + rospy.init_node('carla_ros_scenario_runner', anonymous=True) + role_name = rospy.get_param("~role_name", "ego_vehicle") + scenario_runner_path = rospy.get_param("~scenario_runner_path", "") + host = rospy.get_param("~host", "localhost") + scenario_runner = CarlaRosScenarioRunner(role_name, host, scenario_runner_path) + try: + scenario_runner.run() + finally: + del scenario_runner + rospy.loginfo("Done.") + + +if __name__ == "__main__": + main() diff --git a/carla_ros_scenario_runner/src/carla_ros_scenario_runner/scenario_runner_runner.py b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/scenario_runner_runner.py new file mode 100755 index 00000000..9ff8da61 --- /dev/null +++ b/carla_ros_scenario_runner/src/carla_ros_scenario_runner/scenario_runner_runner.py @@ -0,0 +1,33 @@ +#!/usr/bin/env python +# +# Copyright (c) 2020 Intel Corporation +# +""" +Executes scenario runner +""" +import os +from application_runner import ApplicationRunner + + +class ScenarioRunnerRunner(ApplicationRunner): + """ + Executes scenario runner + """ + + def __init__(self, path, host, status_updated_fct, log_fct): + self._path = path + self._host = host + super(ScenarioRunnerRunner, self).__init__( + status_updated_fct, + log_fct, + "ScenarioManager: Running scenario OpenScenario") + + def execute_scenario(self, scenario_file): + """ + Executes scenario + """ + cmdline = ["/usr/bin/python", "{}/scenario_runner.py".format(self._path), + "--openscenario", "{}".format(scenario_file), + "--waitForEgo", + "--host", self._host] + return self.execute(cmdline, env=os.environ) diff --git a/carla_ros_scenario_runner_types/CMakeLists.txt b/carla_ros_scenario_runner_types/CMakeLists.txt new file mode 100644 index 00000000..8184efef --- /dev/null +++ b/carla_ros_scenario_runner_types/CMakeLists.txt @@ -0,0 +1,21 @@ +cmake_minimum_required(VERSION 2.8.3) +project(carla_ros_scenario_runner_types) + +find_package(catkin REQUIRED COMPONENTS + message_generation + geometry_msgs +) + +add_service_files(DIRECTORY srv FILES + ExecuteScenario.srv +) + +add_message_files(DIRECTORY msg FILES + CarlaScenario.msg + CarlaScenarioList.msg + CarlaScenarioRunnerStatus.msg +) + +generate_messages(DEPENDENCIES geometry_msgs) + +catkin_package() diff --git a/carla_ros_scenario_runner_types/msg/CarlaScenario.msg b/carla_ros_scenario_runner_types/msg/CarlaScenario.msg new file mode 100644 index 00000000..bdb90fa3 --- /dev/null +++ b/carla_ros_scenario_runner_types/msg/CarlaScenario.msg @@ -0,0 +1,11 @@ +# +# Copyright (c) 2020 Intel Corporation. +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +string name +string scenario_file +geometry_msgs/Pose destination +float64 target_speed + diff --git a/carla_ros_scenario_runner_types/msg/CarlaScenarioList.msg b/carla_ros_scenario_runner_types/msg/CarlaScenarioList.msg new file mode 100644 index 00000000..8b2df049 --- /dev/null +++ b/carla_ros_scenario_runner_types/msg/CarlaScenarioList.msg @@ -0,0 +1,8 @@ +# +# Copyright (c) 2020 Intel Corporation. +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +CarlaScenario[] scenarios + diff --git a/carla_ros_scenario_runner_types/msg/CarlaScenarioRunnerStatus.msg b/carla_ros_scenario_runner_types/msg/CarlaScenarioRunnerStatus.msg new file mode 100644 index 00000000..cf0039e3 --- /dev/null +++ b/carla_ros_scenario_runner_types/msg/CarlaScenarioRunnerStatus.msg @@ -0,0 +1,14 @@ +# +# Copyright (c) 2020 Intel Corporation. +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +uint8 STOPPED = 0 +uint8 STARTING = 1 +uint8 RUNNING = 2 +uint8 SHUTTINGDOWN = 3 +uint8 ERROR = 4 + +uint8 status + diff --git a/carla_ros_scenario_runner_types/package.xml b/carla_ros_scenario_runner_types/package.xml new file mode 100644 index 00000000..5df0ef5a --- /dev/null +++ b/carla_ros_scenario_runner_types/package.xml @@ -0,0 +1,14 @@ + + + carla_ros_scenario_runner_types + 0.1.0 + The carla_ros_scenario_runner_types package + CARLA Simulator Team + MIT + catkin + message_generation + geometry_msgs + message_runtime + geometry_msgs + + diff --git a/carla_ros_scenario_runner_types/srv/ExecuteScenario.srv b/carla_ros_scenario_runner_types/srv/ExecuteScenario.srv new file mode 100644 index 00000000..d342a73f --- /dev/null +++ b/carla_ros_scenario_runner_types/srv/ExecuteScenario.srv @@ -0,0 +1,10 @@ +# +# Copyright (c) 2020 Intel Corporation. +# +# This work is licensed under the terms of the MIT license. +# For a copy, see . +# +CarlaScenario scenario +--- +bool result + diff --git a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py index 7877514c..4d1c3201 100755 --- a/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py +++ b/carla_spectator_camera/src/carla_spectator_camera/carla_spectator_camera.py @@ -24,6 +24,7 @@ # -- CarlaSpectatorCamera ------------------------------------------------------------ # ============================================================================== + class CarlaSpectatorCamera(object): """ Spawns a camera, attached to an ego vehicle. @@ -71,7 +72,7 @@ def get_camera_transform(self): return None if self.pose.header.frame_id != self.role_name: rospy.logwarn("Unsupported frame received. Supported {}, received {}".format( - self.role_name, self.pose.header.frame_id)) + self.role_name, self.pose.header.frame_id)) return None sensor_location = carla.Location(x=self.pose.pose.position.x, y=-self.pose.pose.position.y, @@ -83,7 +84,7 @@ def get_camera_transform(self): self.pose.pose.orientation.w ) roll, pitch, yaw = euler_from_quaternion(quaternion) - #rotate to CARLA + # rotate to CARLA sensor_rotation = carla.Rotation(pitch=math.degrees(roll)-90, roll=math.degrees(pitch), yaw=-math.degrees(yaw)-90) @@ -98,9 +99,9 @@ def create_camera(self, ego_actor): bp = bp_library.find("sensor.camera.rgb") bp.set_attribute('role_name', "spectator_view") rospy.loginfo("Creating camera with resolution {}x{}, fov {}".format( - self.camera_resolution_x, - self.camera_resolution_y, - self.camera_fov)) + self.camera_resolution_x, + self.camera_resolution_y, + self.camera_fov)) bp.set_attribute('image_size_x', str(self.camera_resolution_x)) bp.set_attribute('image_size_y', str(self.camera_resolution_y)) bp.set_attribute('fov', str(self.camera_fov)) @@ -165,7 +166,7 @@ def run(self): self.world = client.get_world() try: - r = rospy.Rate(10) # 10hz + r = rospy.Rate(10) # 10hz while not rospy.is_shutdown(): self.find_ego_vehicle_actor() r.sleep() diff --git a/carla_twist_to_control/README.md b/carla_twist_to_control/README.md new file mode 100644 index 00000000..4fcfd7d0 --- /dev/null +++ b/carla_twist_to_control/README.md @@ -0,0 +1,17 @@ +# Twist to Vehicle Control conversion + +This node converts a [geometry_msgs.Twist](http://docs.ros.org/api/geometry_msgs/html/msg/Twist.html) to [carla_msgs.CarlaEgoVehicleControl](../carla_msgs/msg/CarlaEgoVehicleControl.msg) + + +## Subscriptions + +| Topic | Type | Description | +| ---------------------------------- | ------------------- | --------------------------- | +| `/carla//vehicle_info` | [carla_msgs.CarlaEgoVehicleInfo](../carla_msgs/msg/CarlaEgoVehicleInfo.msg) | Ego vehicle info, to receive max steering angle | +| `/carla//twist` | [geometry_msgs.Twist](http://docs.ros.org/api/geometry_msgs/html/msg/Twist.html) | Twist to convert | + +## Publications + +| Topic | Type | Description | +| ---------------------------------- | ------------------- | --------------------------- | +| `/carla//vehicle_control_cmd` | [carla_msgs.CarlaEgoVehicleControl](../carla_msgs/msg/CarlaEgoVehicleControl.msg) | Converted vehicle control command | diff --git a/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py b/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py index cb9bae89..dea8861a 100755 --- a/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py +++ b/carla_twist_to_control/src/carla_twist_to_control/carla_twist_to_control.py @@ -14,7 +14,8 @@ from geometry_msgs.msg import Twist from carla_msgs.msg import CarlaEgoVehicleControl, CarlaEgoVehicleInfo -class TwistToVehicleControl(object): + +class TwistToVehicleControl(object): # pylint: disable=too-few-public-methods """ receive geometry_nav_msgs::Twist and publish carla_msgs::CarlaEgoVehicleControl @@ -30,11 +31,11 @@ def __init__(self, role_name): rospy.loginfo("Wait for vehicle info...") vehicle_info = rospy.wait_for_message("/carla/{}/vehicle_info".format(role_name), CarlaEgoVehicleInfo) - if not vehicle_info.wheels: + if not vehicle_info.wheels: # pylint: disable=no-member rospy.logerr("Cannot determine max steering angle: Vehicle has no wheels.") sys.exit(1) - - self.max_steering_angle = vehicle_info.wheels[0].max_steer_angle + + self.max_steering_angle = vehicle_info.wheels[0].max_steer_angle # pylint: disable=no-member if not self.max_steering_angle: rospy.logerr("Cannot determine max steering angle: Value is %s", self.max_steering_angle) @@ -53,30 +54,28 @@ def twist_received(self, twist): """ control = CarlaEgoVehicleControl() if twist == Twist(): - #stop + # stop control.throttle = 0. control.brake = 1. control.steer = 0. else: if twist.linear.x > 0: - control.throttle = min(TwistToVehicleControl.MAX_LON_ACCELERATION, twist.linear.x)/ \ - TwistToVehicleControl.MAX_LON_ACCELERATION + control.throttle = min(TwistToVehicleControl.MAX_LON_ACCELERATION, + twist.linear.x) / TwistToVehicleControl.MAX_LON_ACCELERATION else: control.reverse = True - control.throttle = max(-TwistToVehicleControl.MAX_LON_ACCELERATION, twist.linear.x)/ \ - -TwistToVehicleControl.MAX_LON_ACCELERATION + control.throttle = max(-TwistToVehicleControl.MAX_LON_ACCELERATION, + twist.linear.x) / -TwistToVehicleControl.MAX_LON_ACCELERATION if twist.angular.z > 0: - control.steer = -min(self.max_steering_angle, twist.angular.z)/ \ - self.max_steering_angle + control.steer = -min(self.max_steering_angle, twist.angular.z) / \ + self.max_steering_angle else: - control.steer = -max(-self.max_steering_angle, twist.angular.z)/ \ - self.max_steering_angle - #invert steer for reverse case - if control.reverse: - control.steer = -control.steer + control.steer = -max(-self.max_steering_angle, twist.angular.z) / \ + self.max_steering_angle self.pub.publish(control) + def main(): """ main function @@ -93,6 +92,6 @@ def main(): del twist_to_vehicle_control rospy.loginfo("Done") + if __name__ == "__main__": main() - diff --git a/carla_waypoint_publisher/README.md b/carla_waypoint_publisher/README.md index 7419a7ce..a2b756dc 100644 --- a/carla_waypoint_publisher/README.md +++ b/carla_waypoint_publisher/README.md @@ -13,7 +13,7 @@ Additionally, services are provided to query CARLA waypoints. As the waypoint publisher requires some Carla PythonAPI functionality that is not part of the python egg-file, you have to extend your PYTHONPATH. - export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla-.egg:/PythonAPI/carla/ + export PYTHONPATH=$PYTHONPATH:/PythonAPI/carla/dist/carla-.egg:/PythonAPI/carla/ To run it: @@ -40,5 +40,5 @@ The calculated route is published: | Service | Description | Type | | ----------------------------------------------------------- | ----------- | -------------------------------------------------------------------- | -| `/carla_waypoint_publisher//get_waypoint` | Get the waypoint for a specific location | [carla_waypoint_types.GetWaypoint](../carla_waypoint_types/srv/GetWaypoint.msg) | -| `/carla_waypoint_publisher//get_actor_waypoint` | Get the waypoint for the ego vehicle | [carla_waypoint_types.GetActorWaypoint](../carla_waypoint_types/srv/GetActorWaypoint.msg) | +| `/carla_waypoint_publisher//get_waypoint` | Get the waypoint for a specific location | [carla_waypoint_types.GetWaypoint](../carla_waypoint_types/srv/GetWaypoint.srv) | +| `/carla_waypoint_publisher//get_actor_waypoint` | Get the waypoint for an actor id | [carla_waypoint_types.GetActorWaypoint](../carla_waypoint_types/srv/GetActorWaypoint.srv) | diff --git a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py index 915bc708..95191278 100755 --- a/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py +++ b/carla_waypoint_publisher/src/carla_waypoint_publisher/carla_waypoint_publisher.py @@ -110,13 +110,16 @@ def get_waypoint(self, req): #rospy.logwarn("Get waypoint {}".format(response.waypoint.pose.position)) return response - def get_actor_waypoint(self, _): + def get_actor_waypoint(self, req): """ Convenience method to get the waypoint for an actor """ + rospy.loginfo("get_actor_waypoint(): Get waypoint of actor {}".format(req.id)) + actor = self.world.get_actors().find(req.id) + response = GetActorWaypointResponse() - if self.ego_vehicle: - carla_waypoint = self.map.get_waypoint(self.ego_vehicle.get_location()) + if actor: + carla_waypoint = self.map.get_waypoint(actor.get_location()) response.waypoint.pose.position.x = carla_waypoint.transform.location.x response.waypoint.pose.position.y = -carla_waypoint.transform.location.y response.waypoint.pose.position.z = carla_waypoint.transform.location.z @@ -125,7 +128,7 @@ def get_actor_waypoint(self, _): response.waypoint.section_id = carla_waypoint.section_id response.waypoint.lane_id = carla_waypoint.lane_id else: - rospy.logwarn("get_actor_waypoint(): Ego vehicle not valid.") + rospy.logwarn("get_actor_waypoint(): Actor {} not valid.".format(req.id)) return response def on_goal(self, goal): diff --git a/carla_waypoint_types/srv/GetActorWaypoint.srv b/carla_waypoint_types/srv/GetActorWaypoint.srv index f7e7dad5..7b9100db 100644 --- a/carla_waypoint_types/srv/GetActorWaypoint.srv +++ b/carla_waypoint_types/srv/GetActorWaypoint.srv @@ -4,5 +4,6 @@ # This work is licensed under the terms of the MIT license. # For a copy, see . # +uint32 id --- carla_waypoint_types/CarlaWaypoint waypoint \ No newline at end of file diff --git a/check.sh b/check.sh index dcf47bb6..b16ec844 100755 --- a/check.sh +++ b/check.sh @@ -4,5 +4,10 @@ autopep8 carla_ackermann_control/src/carla_ackermann_control/*.py --in-place --m autopep8 carla_ego_vehicle/src/carla_ego_vehicle/*.py --in-place --max-line-length=100 autopep8 carla_waypoint_publisher/src/carla_waypoint_publisher/*.py --in-place --max-line-length=100 autopep8 rqt_carla_control/src/rqt_carla_control/*.py --in-place --max-line-length=100 +autopep8 carla_ad_agent/src/carla_ad_agent/*.py --in-place --max-line-length=100 +autopep8 carla_ros_scenario_runner/src/carla_ros_scenario_runner/*.py --in-place --max-line-length=100 +autopep8 carla_twist_to_control/src/carla_twist_to_control/*.py --in-place --max-line-length=100 +autopep8 carla_spectator_camera/src/carla_spectator_camera/*.py --in-place --max-line-length=100 +autopep8 carla_infrastructure/src/carla_infrastructure/*.py --in-place --max-line-length=100 -pylint --rcfile=.pylintrc carla_ackermann_control/src/carla_ackermann_control/ carla_ros_bridge/src/carla_ros_bridge/ carla_ego_vehicle/src/carla_ego_vehicle/ carla_waypoint_publisher/src/carla_waypoint_publisher/ rqt_carla_control/src/rqt_carla_control/ +pylint --rcfile=.pylintrc carla_ackermann_control/src/carla_ackermann_control/ carla_ros_bridge/src/carla_ros_bridge/ carla_ego_vehicle/src/carla_ego_vehicle/ carla_waypoint_publisher/src/carla_waypoint_publisher/ rqt_carla_control/src/rqt_carla_control/ carla_ad_agent/src/carla_ad_agent/ carla_ros_scenario_runner/src/carla_ros_scenario_runner/ carla_twist_to_control/src/carla_twist_to_control/ carla_spectator_camera/src/carla_spectator_camera/ carla_infrastructure/src/carla_infrastructure/ diff --git a/docs/images/rviz_carla_plugin.png b/docs/images/rviz_carla_plugin.png new file mode 100644 index 0000000000000000000000000000000000000000..f7e8208d7875e3c8439497cfc427536e0ce1daae GIT binary patch literal 525827 zcmbTdWmr{R7cRUIq(neKKpN>5r9%)2>5%S_?(QyWX^@g~(@1PKuxX@Qxs!9x zd3@gY{5)_eUJKXSbInoreUCB26yzkHq7$J50Ps}ugQyY!AWH!NQUdBD@CwAMlL7pJ zY$z=u3OxMz{?-VI2d|*neb8_OfG4V?-a3mlr(Xv?EKl0-$zKvFWxzWDwtkDj7{f)QVs`EwIGBYuKmzNRpr zlf0m6ED4B7nn3r&or+ygS8F=i{<;$w;P7imiixv!+ukd7@yAG4%E*Z@Tks%k`( zQlTn~9vhoH@Jfr>4_gG4GUz{l4I4>f8mz5v512dwue|K8V3C){>LgVC_kUn}+`4;s z0DjX}2*A5I`U%v(_hJ`0tS)GZ2n(}dVY%+s2mih2RIiheDo8Z^Z@pS48W3Gu z%g6a4@OMRwcg8x=*1QGtHdQlL@7}$;zxR3jcD$iMz|rw+dRn8Whk@H>PJt0GfF4^! zT``N9qJ_|rheWk_U}&h^=guQjSJ#FwW5jH1=cG&ro|KTVn*JocO(l+c+N#F?>`wE> z6UDv$YI|%;{N!olvZ%vgCldpD{v%Pq4=!FyZ{($~?svc@d=Kp6QgMFHc5lIT;5%Mz?|j3&A;#v-2(h4-&HiG%z8YGd!>CYOxC0*E z*zQFS#1`r*deCU0dT6YISC#tOv0qu4kx?^oEZwx5GbQSA(xdostBPsrPBa1e0$w&D zx<#qS!H&bRnvoiHv`#;r1OM@dYzaJpFGgB%pPr`%*gJP!_`B>g_+8CsIFuoy_9V8jS)_N%`}_DL zB&!=6$telSFA0DTm=aHEgqkJXV)({yIRm0U^qY(vF$+ViRyO9}6m*W{l?W7PP`SRy zH>;YqQk@mVlB-rPndYsFWcT0j_Y<>S=3VIP`&g(f&>PO?PR8hYvO5^BUAIMUAf|}2 zv9Be&vtO`2n5W%)`74&&g8TW@u51^xH@vlJi@cWd9~*KIy?7YzHawHVCZ6d z{9`uW6ZA+7!dJXC>kzCrzj(3nLz&57jJHwKP$6;Uu?BlyZ-OO6-|P z`*$pV6Xww^9W@g*JO*A+go1${#lFXs-2UATQ7HFN=5@2 z?zk(PJ^I;(vXMV_lwee8Z@=(+OO5x=#vZRzpjra?a*oWfyQf8M|CFHV$9H=lA(Emo z2G0yQo3HJ}`bQ$zf`Xw|qe~Y|ld1IB-?-9hWR>4PmKAhimZZ!}QX}Jb#i9{!_}7y| z**mFCVAFiA+bt>WRt~S|@;_jrV_`neMW{1RG1F2=+(t3exKa9x^#OY(qY<~W0I=?yNGD_2%0>@>7Sl_&^)|L zBF4U5oy|He(3zL*Kvx<%(7KsjXNpU5P2r3}X&7#HZfx1MLGN*MyqSyPntO{5?;#q7 zII)fx2ld(1T-C|+lRTc-Ce0*gf5kYJ*4LaWHQuo?Wqg;AykNjO%(4H_c375uuPJd3 z9ZgHRv*&q&6zX{ryOL?Kt=A_3(SOW9fO*hF5#nn8TvOU;sL8|b>=)<86Anfb_9EhQ zQr;4+Dq+{J@pdK~+faU6NgKwEZ&=X8k}rC&>qf3@mG!R-qcCEQoDOZv%}6o%AEjAd z)yE!7hpFV}iTBrbz1OQr<)!IUzZhPd30;l;yz&Zd9SRYQPqzFt*AgRiI`ZN|N6?MI zAAPL@7H$!=Fb8uwW5|SX8SfnF$y(r!7xomLRE%u&8pCm^N2D`qq2eA#L7=T{0_3W83;rSVps}$ z=bfmvy<*N~-`(iSaHVr(M{dtxdSObYI(*I)QCO(fsse#Y#n%R^MjBhGrGDe2=jWb{ z^KnMed)*TuH3yfypV%K7J0N@YOFueW>&HHZ%CBt^i9)>`obq`0vK%GK3W=a-o)&Z6 ztFFyLpAUzvGlOFYs~m9!kf28Uuab(e4UMzGGS7r>?z!MQ$Cd=@-?{D zmhaQ!Lh(@r+c?+F{-+xwz9h-`RW{bIQH00dk$Q$+&DeI(N!C<9F4w`_Kb_lb%?_Yk zpLA92%zKk4_io=fh=!6v5(ja~Et=}Pqi+^hjScw->!)!cH9|IC0lpfWoG-tzBp?w1 zOZ3eG%1e@oUU78)j3G#bfAKxcuYYgSICItid4b$4r#|2;1pgCuTs zLv7TMT{?~$vNv6o=2&)j^H4Lp7X%n_v@Ei5(j?M{y^rHlQ{zWJE^NmHw(!jd3xB%4 zvO|wCh~5$V9X-PM}JG+1wEZ& zS1OIq)UCY}VfUvBuju~sKNc3wE%Y$KI79w&6=pq$}5(XUHry=JlD!?&_^ExTiXQ&vqj+>uOUb-6ogZH`fk z*lyx8wh~779>!YV?F2)#QOFTNdRaKw!T*&L155EBg3B{F1jX)3Vo(e9f8BK2j-x;X)8&s&11eYph zvu3(A6^QUWoWDm#J|W8D%P#%8ZMMFM!p08m^*J9doIB6Zs>afBSPlsGxUkaG`=P@} zm{F`iUyyry{CVF3!{*<7fJxa>kT+^!&BZjw+bvIKqFycjGU!9x`{I#TQfNSKoN6(2 z+NwjN-^9_L)jf)u7Z8r4juLODU-QewDJ^|j-SU(EvEO%2fyJFk_w^*iz(4`+x$d;f zPhBR|Sws#9eo73&#ouvQgyxjzJc~sT9%rubhzR?f8XdWWHT*>Kcja4x+ke0&Au0J* z2$843Nlep>{;H4`c6s6EF0=TVf{n(0iUG?d_;>We$MkO#^lo3!tzecjHUWTI9lcS0 zy)8R@dYqNs*ardOk!%z^g^JNRV1CJqR+>B^u#(R>4}ya9Y>$*<2rKW99h+&qKjG z2yUx^Jg>Wc41@PU&+6$wz_tu68%~`pPYGr-Yp%!Sa{wrKYtsI`idM0em-EF!`GB8h zBm#D~P_y~^?cSttAr8$=M|-Fe|9OnrthW1liiC2ghu6FQWnA%h*~TU=$;YpD;eR=b zpa_QFYhy0Z zlW_bMoJ0x{C>pX_H6j01KONU@Dqi#CNj`7%ZF-vyPEL+X9g{{KiXB@Zu9#v1bs<+i^o8|lJolQWBB{uJi6FH;i0sIUG{)OO39%{9A+Ae+vd+$#oh?tftxFl z=$D48L76_Ry(UQ?i_pFYItTI<{eL!G{UG=&((m2zHU@O(jjN@iAJnKAfI0u?E z_bAhi#}qb8D$Em21tODudK>f(Vm9YI3SMfdTAY(Kc4Umt6zf?6_zzxYAJRSu$rgJw zyuIEO3l(AD+b>{*E0Ug_KPjF2=pwIok2Oy3j@%N#ymlC#maf^Au~;1)hAuX8DBL60 zNDSQ~q_D$`>u#OvALK-k=r<-=9b)Lb6&TEvfCw{>x@>fkzlDA>hj zFHyBomNX7-d!P{!F!>rCM7_wce-Tv}KpB)Gi{D8N64jkw`SAj4s*0=r?8qh{?T`Zc zX`fJv4w_V`qZt6AKDF77%`7kS6O@o!N>rIBgX~Bs(_5`nq!ONsp|Q?OY4|eOiq8Is zVt+v5JU08CP0vi&^KEuD#LhV`UK87eT-dyIT0lS_B0m!3TaSgeLxb!6dG}3-uv^y^F1bt0rD~Ig zqzGbg-B-feE2u=Mvb+|!{f4HTFUe^O(0DSiOt{Tw<-KYWxr|45&ysg3l!%`rZGm){1B5zN-n*BJ!G^bO5;ElT?$tZe5zz|=x z(D_!yfM;V1d@^XP`CL08VFu@_W!V}-~(>@s2 zrbn>G?3oBpU~9{f0IL(%K$O95|%AaQa8z9w39Xe6N zNK(jD>cIrmo<`fQJYDguwkfLS+#YpV*OQ>*8sl^!K=7mb&6%4>a0wSH+c&n$(JVbb zJ(ZG{R{8v!-11?r(wg|yt5jL^-~grd9j#FdC`bv_3T9BtyM-$DHgPF4uI1CnoVFcU z$30#|-#5@Q(4+;2U=i`R(Y;kGIG|JO&Jgritq34lHCg+h-8g8JCI8j6-1TZ*llS3hJP(V|s5YVE#M^6hy2EbjKW$+;mbcHqF6(!B~QEs1NDZ`qw}-QRPRuax2D#guJVDNqk>pTY?4Ic`yJoxw%%O zFs@j(H#yW69GR}WMP{w$G!Q(cdrfHWUBdld$lFG48{?Ows13ioJk*?Q`u1hh*tO=q z2Xa4t*R{X9>7uvx?jN;6VeKUn(!1{7-Z6{uIO=C2ywS%38zc*Hd2NSD6sRCveaU9m z!n^UCr;SilB8$1gKD1qqA>I)!-~%B9`*~>P)9i77UJ~G&q9yIA+1$@0gQ5PijrA*= z1Fqi4oqmJ3_slm{Bs zg&Qg<8G?dIFbW;cJ98nJ+XT%0JqpzJS2nTj2qZ(Gly;-$wzkdt6n9zvsqG+dNl3pI z0qzMZ7R7S{4YG)?u<%`PCN55oLQ^vZ&U&Y+V(l`r7Vs)Dt842K`quHWZBvh@iP^?* zw4eyd=XV}7YI>Q_(0%7F10-d zyAHm)`RJzj(Qu6Vq*QM*5PN~U;o*y2T~vow4wg2I_kszIg~9W@u3{?&H-iqkb?=l` zS{1F~?oW_kD<~0He_E_#=W(;F9sG@6BMPhZUx}%RM=F(`(ZRvNyGZ3Dqo@?aGAi2< z7@X*EEJApG8EKAmtK*B7MhmZ(@Y!x{Y(D@fl_u#Wa+(}B+}bzxLQ4mu3@ruyVILt^=r7W%Ge z{zpb$eHX1J4IE|0(g3`5CK7FN|Ph6!4_E6a4$W6ZEaqKr24&azNtvVZa* z>O5Wa3QZ`rqGq}7mpP+|FZ{@KuRBq@6vK4jE{Oz4!3C>4A`DftRtXjL&Vgtsk-vUx z1HufTY$D+o8x({D1PQ z={IkxBty>?bLj7P2A@EsIW^x-Gk#ljk`IYM!R$=CL?1d()|mYp)z}^+?8tx&wpiK# zEibiD^H-uMaZK|bwAIgvJ)fjxWmnwg3YDJ6DCQB&dEc zWOU2PMl(@L47H08s?IF_{@pu&&|$*RV*vzYhc4D=>|iBx*eniiynw(Ql&@5&5J}wc zRoZ~6K67_ppBnvh#{4*JOhN#!vx9@EG?8F^^{5od$P`+asqeZ{;O{U=^7~!Yb>4f( z=$3MTg8u78XC;?lwvSSz>Z$wdAB4M-2F^WP9F8ybE%CC zrQQ2I5QO}N zc9cO1&qJ13{yvXVIoQDMPnY5Uys3%-;lkgS#uiZ_{C~f7Dli0wN?Fx>RcRdY0YJsX z)T~)GwY4p0)S-%5R=nkB#Q*!Tn+Dj7nWxj)fj4i*yW9tgI4xlh(39?w&4h%pP@Ul) zCbEm3rZ0h4o&6>!QE4zP+j%kq*9!FUv#R$f65>I!SIy>wOmwnt?Iy6HjAqo?mw#Vj z*c*GF!CBLz6SjD#erxH|gaAy~&fRv0-;7jmnN&^B_7$7PlpQp1`piJ|sA*|dG(`Vy z-1SgB>@aE7E-&wUqWV=|TNeI9(=E6toE>j(%Se(Vs}=F5q;Yt}o-S)eLXnRjW2w)j zr;`M>ro_g+@Lk)MUmUVo5O~SXpn=!1JcMaJ!7(;FJFCyJD|C4AePA}c?|fx0SO@N8 zMMPv+H9eToe0Wo-Vp65y1C=i)6ZCXBIX;zu&-{O1uBl~Q7d<``@ zHnqZKzH{o$2HEzN*#xuG<~M%?g!`+jkUNxzg$84Oqki6Zc6P%k@r(D{X}m^V0(!+J z1Cjmx16noYf-WR!um5h)eOgdxwN8}goiBL<0j{IR(Lvuh<5?eD4oB5vZmKfAmvCScP^`q*@RoT6fRuifMz8?`;Y=(d;W zf0v~RHDLh+&O{Fu8a{Bfn92_*Cuk5H* z({p_9vOn~40!hqE8Pc|NfPZ@jyoZTqb!bbC3vx{8;~FblPO&!AId$Z3Q@;X2HGTd1H6kKnc)M1Y{7(`- zFFc^KvNDDw%4YamQ$s9W<|Y)h1K3G?z(%^ z|0_uExaYOpm;?n^;N%;;51OjIeEv{DL4ox<9*O(J6&~R5*lYN30&8(_)jbp2;bgs3 zWAXk=dfX#Gv(#j`9E zP1cDqkOM2+?wJ8Mqd6wcjB_~odVYRBVoQH{v)!N}R8t2Z3-EdH?#REq{GG^^)+k!p zccix9a}c;5yWHq`zBzdjM((3&w|^Uq!r;4w4%WWGe7?(z<GG_9GqXPFdFH#DG+Zj=<2%8N9$&p zau6Xtx{VfJG*)tvGVd>(O8Hn(9^-k{^R|)fRfF@S)Dz62`1p9w$pn9YghKORT>r=8 zh4D#AA+j(2Cb$RLx%V^su~Z`_Rad2G<=j>Z&6=E9Ay0QMwx{n5c0aQxWyI?=`v{7B z7Rh$=8AHw7IQSZ&RPTHoGkx@`$d<;JA%^);2alUM8*MwOtzg`OUioeTV* zwP6)sBvpJ{s$w(2@OA0VgDohhl2?%ZGYi0w=;6Ik0Y8hcw|zozciwhFwSNC<*05rK z+I8tLHurfC)cOW9qT^SU=OmcsDm1OZt?f%HXN{#Tkkem;TyIv-cm+~&o$r1XniL$1 zw_n?a+M0OZoVNIkzWw?Lc<~}N4QAt->abTIH55a#zoEuNM|T0E>HB?O_xXR8xeD(1 z$y1M#&qXhJcs8rdAGi&EdDhjrP5cx1l&4wi`|Iv&GtV)Zav0+vo&R>GMV^zU*IM-q z<*P+|9IZ)wluGvW{b}sx7ODWnMEYx{%?hQF!-)s3%VRdwJN;Aie}7?s{R6!yX=l<_ zKM&*Y)dIr7#=qj#pIVGz`}cRK*^C(NT7QEzZbW z;0?3>!GBlh{Qs*ui*&>*NmW%lsM*52=kD+16eW;B~ z`l?-(BvkYKzn=0@tX(Vh#g=nG0B`2T<5&W>M}U}Mh99h9g0=QshoIM78Zp&xQd{FkElKSf-L1bFbpW3pka(H2(<~lHc z*hg7QKt}fzent_qhfvkFpe0NQ7t|tTVr(MG%nfd3i^i6W`;quZZP^ss`6XoUyfdyw zpQ!%)k7+#w3dgoR(QFZnS_pG7E_2jXmy7f0`#bzVUD7=gtKQ7+r6bu}NxzC5G99sJ zKXMW=h|&Mrd)R1)tWC?|fL8oTppe)b6$ES%jge1U$Dg!g>_rP+VW@H7EBeS8_5>n{ z&`9}p9|>5|{Oe9JrRbqBdKQvK2|uMUDnMA>zNFyrVfMsM@H|~ysrQM(Ez$?Z7{yP) z8RPW-V^>wsBGrc@0m2MxJY{AMjL65QDnUFK4j$?4T4M3m>@Sm3R{%dHbRZI;>)91Z zk3^%LRcbFLpq7)sH{C{$siNUKjb?-Pfi&17L`y6(4pd7-${;fAzMdZsM^&do<~hpt zXCgt65PRs6Akm+2*jx-N-ZT|;KW1@X(lvNhV8@)5779s&hu$*fM=JG_tz^B7R9g4K z3zim>P^?8}AKMXB|qOg3C=CH_Ui= zF)+Dkp9Y;}mTsQpu##%9)PE{yxYERrmz975JVg}1Zy0~Z^q+*4Sk~4ETV*I9>~4e+ z8YQszrif%0DCUYs5pm+7iz#B27oB`m*1u9$KWa`8S#CJCo2-N3;NYwe=)H2?*UsE< z&&=X?-EX*h@&juU@vERG7d8zx+fo|BV##i>-4e0aVJpf7Ecu0=ujB4iMc1<1P?k`$ z{<4U#@5ATMpZ)yFp6BO=;O{K!&C;x5V@TvBGgSl2XPs1w{V#n?~o&-ba7v{ao; z70nS>+Rtt`lwbr>YwU0-4rmvCtr$}(j(!)1vHqxiUFtKI%|gT4oXjb!y&4P?-85^{3S z_5Q7?sfc9O{Jgy1D`8-`XG?79W~O)hA>=CmMjJ9)E(a)F-^5ZEq7SsOUMv_!DgsIz z3{4F z@ZSg0_(Bb%U((Yn*JC)7S#`kt=i}pJB;I^Uo@%r|qFwZ$C2n}FSh20O=D;*1T2(z+ zDZ^wTrTZyif2z*0D>_3ww?enEzP#bq0c0Cbk=u(`bipAm?BDzQWY3=6@4gwTg~Rzx z1$=)0yjXl_u}_!EM@K~^e7idhI-iPE#abi50}(zx*VM7G! zO$UNfad^16xX+)T+4AuV-5#z~7k(t>vZ5&0fO<@YPP=QLUA>HQ}Sp`jAW z$~(*LAx8qf$NPX z$&IKhz-;W+$gEF~R;+V!mdOxvcb^)7OGokkC5jjTvPK|#Zzbo22_XTern3oh-;!8r1`dwu zT}=-m4r-)uk$x;maq&*NET5T1Pgv}bAY{a>OuKG-XGcqg=$E{ZkMG`fDLQQ#0mG9zqDrQlCv#SPk5~t<;XNz(4bPrnu z*DfS2jPPq)1ggluN=T9`4@m$;B$(17*qX1su1yEow$83o-`@+WP$hqf=j_S~5$ zjUnMxx;?rWUT#-ZR6I(4ViZwPVX9iLn~|77ij95vD`f=Caw~K)w_9E0PJE;QSYS?m zcSOX~HaZ`#_9Pao5=V7{8&kp7NbQOrpAUf?Ojo(CbL&l(Xy5`Mm2GY&2ehR>sMkAb zXli~{DkR~w$kX;y(108v1!%ZuJ**^7em234@OwXaqHX80nl$w>LGp? z4W2;}Puw2vE)EJFv>R26ttUztfNlwvtfMnxuHEUXWcCTTYdHi3(`oScF#x7H-#hCg zFi8sv2rPW%F#uh-uC5N3w&^*Z^2VNIJmUs2vyntJ8L5y@+pb0xG6sp=<*>mYsmx}v zX+E9Tu``BT=mL_}i)L#d#3O;O^zoywR>S4>8S(!9{tyP~%y(Hl01pq3S+{cabW8mm zwm8@lY4W}y&?ULMiR;Lrf7CMPenQM?F_r6i0g4pb;D*`Ql!@oQU^lEiA*gcRnc%i1 zzchkzAsv^|cBk`HZ*D zr1si^doS`{ntSBN1&sHthe_9!=rMn9 zi^K;u!0WbS!n09Xnml^MO#6qOqDUL3l*YyWdSP9kSkq1*IU&V~neTcf=3c&3l}-E9QA#R2D{IkmrE|PUrOM&pzWgA);iWGzh69!E zqxcfXUv#eauB32#S6A{kCe;lj&&RL3vex;Udrumgn-{^id+R(y=XtTWGYKp2I{@{B z3(X1#<1$^nfiB2T7S>m<6yoy0NKKE9N~A8-ov%M=y20$SUz_`l&V~@}*n}j-vGRm~ zRlCl?xHGaG1XF^R>w3O>-Tl2@=KU$)iV34Sceu;+;7Lmd8{F&p?3SwKbq;41vU-bX zxSf59KXACKPphkgBYe1sFhG|Wuada%xx1c+TB-cr4GIm;&xah$G{WT%7HGJ%a*zkJ z_?vy&L;mDDALl{XVn|RB-bQclASm|rZDh%pD-0#?RM@YuO*M^x`rv>irn7aX+bSgQ&LcYj}Td6 z0ka<@A7+{#T7sVtbjJAN0wt$QeY)l{YNPG+O0EbT`(^(io*pqhK* z#cCUD>O7tkGFRSSV2uaIJxpuVb2MQ-TlwsvSme_cMi2^AEts{Z^<1&+R}S}6a`uRg zS;p*Hcrf>D@7K`c64LqTDxq|=X6mr-dEc+EC&tV;t{$HYj=YE+*q&>MH5)UfhmI#( zHOv&)$dZ$jN3VeRjsyqiC91%G7+q{IEd9MEO;hON{`60Js$r;BOl>XC6%!LsZ8h!C z8t^!P!b@N;K3_WdkzYd#Ve!7!8!DFkv2#CmbYO)}j_AC9I4X@xi#aKYMN2@)Vzt6( z1b(r*=6(;tzOLvO^973SA0hG&buQliBU9DpqXc?{`O1u-xE;7sySlmxKB7tJN+)_n zwM;W3Gc#M6F;wVA=43q<_>z#&V09Hv%xzl_hd1BP6!#^UkL{ct$oVwO>F;st`abpR zMr4i%a77BI?WBtY0IHIb)-e1CFN1NbQK(Jm!*vt&+X~&=OD!Jha#>W^rxn#f)pp^cEJgX6R z)l!SLoZvje);BrF@J1_+vs^Wty^#94i1rPM4dZ$HHa5qf$sqFLXZe-(O&zl3VU5WB;}_|kFPC* z<#2z#Ue?3XP*-=sGk)=4xG4|<=_(p8_PxC4=jMj}{P`1XDUVck+1t+7TMv)QH(&mK zl0)CbeRb#K4QBWmV{pnEBuHsKri6E`G|sQ$GC<76T_FKL{ z>|bCnNIID{5!05v69c(@!TZLm0nG6Y+6%u2Gx(De(r;I=77>M&9A1N|cJVjkuShMZ z)eBFfqa&pqJB3;PW zpnsDcc7U@nI9aL%i!SDdgM0l->d!V*P2ZkPF1opUoP%ZX)L3b2M9W%zCsIpo&3I+4 zYLHFEa$=h`n;kC5z_2w{vDqXqs3KR1OD8Xvac!@V!8iMGZMi?^u7}rgpPnJ;StHt> z^x*QVRBQ6_$;Nzx^G=n#kR|SOl^nGUFX^Gd!G$_Y*Y=R72ut9Hf%xEVcT~Pwb1!bu z_u&k-NE=ChkiK96%@lO?nJ7u+O0(XsmLJUIpR6!Kxr!Gq*A;wFBWGWUKQ@uwG=M|` zQ~7P&-?qw~<2SfyfR6&)MdMPhv=s(=!qVHO@g<&yuZ+>#jS{EIaaU?9?kB1sI$JyV z!kD<-1Ic{k2ilFxasmT5J~;tFUK)ov4hf0ZdjAVxs@d0fE6VGkJ?41Ja<10?;r@=< z#4%=n9)W^~r`EYxb)+i>1qmr#!2P(Gt(hM4WO~mfdF|-rT8eUnq6ZkF0hz<#kZ_1=6uuWJA3i%kee;mZAW zm8O?^Y$RA8XJOV^d}l_<C?{|>scm; z_r)Kki+)aLCm&mvF{~ix z7M~$2xi8sDMQ>u6_Acs?6iZkB`kX{kn0V192m0lTBL+K;#Ju zp{SI{StMeL7?_wzC^HG_Ulxz0k-}D+v^tnTC5H02p+J$_V(gV5XQ}yz56k!94ERTg zTxduL(&Y_;a91>`YKc0p+wf>)1t>wdvRrR&t!*u@Z6QPkhj8@t^?{Q_FdG`FxLng1 zu)Vo`++`!>|GaC95W5W^q&Y4>#?TJJc29B#+Wejm@#(eILoL_7bkSwWz_AG~PIAP+ zo^|?LZ$6L@9d(szLAQV9_kmRlp=EK%wmsyGwYcg1&G~GN_09~mFP2IIBIEu5hRE@C z`W(qdcLFR~&BsT#IEjUTO&2_tCQl*+Vt>bAk?hGG`K-5hGds53Yi#V0K-J=r9UZ5! zW^4kO_pD3c2)+D-vX_$s7BjHqrmMz5%sS*4N3Fq(AJK6lY*NL;vI^KHN{H)$?hfK=HbyG;Ia$C6rFmjtCDHQ@3MF5<&)*QRpQZY zAL8(y+21%e_aXN84PBfcd$>7jK1QC1hTFC3bAWj;I4HrT(*U;z}a+2QR56)EEu&Wi6Hl9{4b zc)$a7SR^a%x;_-<8c{VKXWJdQ8hsWy5ATh2ideDe1O>hK>d(y0&4YxMlwRjXVjpkO zfteG2UMgvOu{H16;&*SH@fbio#G+rQZPow6jR~L!=Y0G2O{q<*;&2GqqZYIsrup%7 zmEa@RN8)DH=RF0J8v~cuY3xSg$(#@+7Z;bUy6Uw$So&mbLq~8(NW;l_p3s9f+~Vvj zsFqEF@aWjqzS3CQ*Oe??UG5EQ_GNU}N&29ynj71)TPU^4YKUrVrAk;874d7gLlCSr zJ8j{pIdwT|Ac8`%PMw7_m~^Abg%+B0_%~QKo%r7S_$W5;TXm}Gfu)3wO=!`uB4xm2 zC`T(EbRk`zroO(sUu;@2E%gg5d~*Um-+o^Et?xAk5GThUwPStfu%4;z*P@+cEz%lM zz7rVQnVUPkZU6@sz%BsJQ(|Clem-JR+fDZi2~92;A_}G(sBvv@*73s1iR9(wrOe;? z7mg9@89egeAdOqGzx+J?s%0fU81}&Rra+zvn5yRQEU7k1vRcaENem5dj1QgzTq9cXd1BrAw;qUFAPgj*G5Bzed){ZhM-Vnu6*#m3(>f z!*`W1&p++nVVyRuH4Hf<$cyP#b1qAf&oMDWU|VE$%Tt;;FFzkdp6^CJ60R+ROJ6n4 zTp`6o$rZz${>bPX%j3E~$A2J;42Y+SWa}q9G6GMgKet^5;}U+p%R*28C6H1%4lH^C zf&vFAY7t7RW40pEpAZ1&a6P=oHLF*K8p}&!YKvuew>GX9W<*3Y92^|GhX#$hSb$Mi z)7a7Afylkhk1c7ckttuI|q&(YD5VxjV~fdSa< z%HXj#Z1F=l-dL%zo@qGl?PKL$D6n5yOlIxt?Pa`=-~&=*zH3yO_+GZ6JSFD(p;?;S z)v%h7+s_jX4!6QHH14Nl#wM_f$Lz-P-YZ$EAv$pOj z`T6c88ZJXVC@aZ>Ln^t&wP}5bkulA2#gmKf$&$JC|I7mXNPMv!N5^Rt$)b6B;)j4J z(AY2ovvob)thl}PYSx6#)L6&cz8Wjn^PL>bC{MBvUu*ej-_Q`KYy0`6S)kbbju0mZ%2K>6&=m$+9$SvS?M?x#I(Vcux~g?OZR8j;{7+c@sVB zZaYiU@-o`#E$y;rYAl+^#wLI)bYoCRi8h_aIyGy017)^ma_;-NRxu~jplyd@i0a&q;_z9t z5x>BOrj1`L?`>uZT&>1~Qd|)+ zN&k^R?&)JDw@iF3svL0&fp-m&dzFK2mN}| zF`eN{=qJEa;WlhI;?Ws?-Vu(o<5Z8&qUrT!rP$WQi}NJyg`U^FhJm=qYVf1@tuFVI zEVrDCoA^a<%il=umPDmoY;5H}<+5vuXEOebRrk^xM=D9`>L;*w?qBnCZ*FeB55>w7 za@D;*yRAD3#Uzi8j&8CXKM^1YmBC~^pS|Iu=oIN4)l!g%x~}y;@0GivC@e)<8IYBc z;Yb|-6d-aG012;0b%1OT_OBZ2v~kOOa9lRB;%6RpM2FH#S+I-??*aKD2Cq}W{*C*g z3$Jl6-qItc*F3SV#LbQyavPkIl9FIjppEab;yRdzvlYmZMz74kEMeBO=l%UMS4^tl z*AWoGi z_UB9T&+&KLx!P93|Bt=54vVtw+D9=SK~Vt#K}zY6Qc$EHM-dST=@5nnN$Ca^P#UE> zMY=nN5hSFgn;`_GyKArEdB5*{k7Ms&{IP$3?R_6SJ_9pz$8}%VTIV{~xz@e8ww69S zty?tIB7n~*%|fdOl*h(kxTohLfhJ|1w>)JhW_Y#sRu; zV0|4lE4tfN()z|LZShwMC=**LqouQ?BqVGfQTZ46hUOT@#et1c%+i!{s}xgx@ZIvY zfDK#=H{je1hH*VMV!bQ(;^Ueo7B*v|Evt#fh~R*!yzi_euxwlD7Ki} zxbH}Ae337=uQ26tu&=ud{mA}9Bd5HPjQPd8$gdz78!Q+pt12%qH@SS;Iqv#N{1t}_ zl_*cu&{n)`H?hFQr*9B=j5h@E=;Rc9KgfOk$Yk|KIh5(c3;aYIIw`SK{3~2{Sm+qe z-8e77UHe)3az@qW$vy1=h~=vde(Y`v)wMTOfsQ;y=t{x{~%eLM!&r~DfcKx2)PDK3n%a`R=2XI_Y&W<<%JMJAz zx59+$I5@s+n-fnx9={^7t&gW8JrT|@O3UfKb#=E5m3pL@en~Rq`Y=%rnec{d%?-k zi4{R5a3rtQ`fjAm!i1N?+S)HRHg;>vMizCPJ~_wLfyZ+26ar|kTh#l>4= z&O29c-G90~p4=g>)RI;2cg2WkZ8}Kwfyr>Ok@ieWnE2J(rT1+V4Gg}OmF;?dCbZp> z0`f-rW3KTn!o*yq3_1P1{4&wgBfrq!dL|}|5MGi}iagY*UxT>az0^h(zF1OX8^IY@ zWxG6FiyU+M36}nV(lH z{#nC(>ZAgHHAA7|KC^p$_F7`PI^apT%V}gPK3-*^q|_hXiGD6E4Fo9UZK;HvLJ8@( z^YtN5o2^>3s%I$3&wtHvGa&hR_(k>i&zETv+)o<5wZ|+kEip;st#52Bj8<&+?tX(V z2WUb4mXL$X*~)qG&r-%Jw_7LapFvun#GpMI^teEns+XGPs;31CWW2ol&x7b z+saiYz|W65?w7UYjN!XPpoW^=B%;T38Sz3iYn=Kb>=FS*vG#Ohj=F6an<941R!)8p ze7ebg^gOFCGY{vklOFPR0&55}D1eVgEYLlR+vbW{(oy#--t;gv$$<9ber-p`idSNy zXvhhBPgy;#a4}~`N6?PrqIw2QLH~2 zmEFtD#hIm#s3@@;xJrQ%z2V~BUT40yzqBNRsi>(b`HXq3>emXZ|IV)$odOkcM4rl* zxHvO&^YJ2a0y0BG+Nbj}eh2dl2#-tGzP*gMS=AjqZdjoN{=C}J??BDxKHEA0ue-bZ zoCmJBze^fKgD5A|)^}^3iYgwXiSIrkOc5vIPJXlPhHbGA4BGzOn5roIxH7!G>>HK@ z0nEZu0IWI^#8rpm65yl*$oB)oQuSqJWwo>t38%(yhqyog_1)6YU0CjO0+;76qmsuS zG&8AX!p=J?m8L_#SyzXL2QL;IC0%-EydQxyM}c3fsyh5hME_!RcN|xchklxE{980Z$}=Q-}QhG7x$APrHJ+K)4*fH1rn$R z%5py{U^F$EDlvKZ@FD#t)bh&8P9I;@KM;bR??5UJP&a z0tlzpk}hae?z;Rv?SekEQ|kXr`^1wFQVXR8r7PX3Je~d1Mx$Tnv1uHmE;`!!P*(Zb zjyUzH4+WV1cFHIwR}@%e@t~80h%$S~v!M@Hszh@&&HC8Zkd8ruY?<=W-qLS8YTA&! z9VMhWwPTJ>E=4=juIkEHXa%<178`1(-+UIgUU&J5ELjk+-V_(9%Wn`*AvVXOHFg>l z-B77>fBwR1qve;PMfLti^}bA*k+cgqviG)@d(!L^YV-rjY7PwyTb0ZhB!WG^KCkO( zog1yNhRLR6_=U@h!UE*?c{9HYS9ki@V#PFr86{XQc?jr!VPK$@MBqsTGpcq!M^K5_ zBrf_9ob2*Gn7o1bY&QADD_89pv=^uFpT#w5gbB{~>DJcvIHBScLY?tUVF7D=ir-yA zZq+>6d;f0ZNwta7iAJo{7fyu zf`k4FN}t=i%C+2+A!Ak8A4SDTl7uJ0vhYVl!j)C0K$VxYLDr3PZ{?8KOJPq*M2vMQ zBNgIZ21*h!JPEd?=2W4##*Pyb^Ft}P0kA_HobNxJ(rbOD%te{CscM;75wDzWGsdbI zB=9m`qu*C@JIi|#)@czUZhDP%Gl;RsX_qrz79%J5G4>t&Fm{{ieNwNEc;(5?>PzVR z`1wM%qWuNVl0XKABo@RygXc5B!;)ERo(*FiMqbLQdnX1Ze^-u_!ASk{-5>Sp$@!nc z2@$T%i3*RdzM`H>BaiT82-{s$>J3rwWcQTCB(X5ilI@5Rdv%2;waK?$fKhl3gl`HF z4$j~F%KZ+lb=~)QczSAUAIp8ZliBkoJ-TvBoH?cUmhUR zb=mqtC8f$pXeErBawz$LspoKnrg+$`C8w}aeSExT;N<1ow{NRsblxx|;U$5vhonaK zl~i#r8F4rUUrD#DiukR>)T%~1gY8sKRccq)E4RMP&Cq}L5vmTeeW7<#bYnV+2Yoy> zKQpb?tjHECqA3?zMV-t*drLC4iuTpMwS9gPorIP4Ku+EJaK!Tk^*ey4K+It~FIW65 zB}0B7A?@PX9ur5|OsZ46jMPdl`&N)p+tO~7_1Lr7rTi>3H8Yb(Jas z4Gk9#^c(S(7!PD9#?<5f^Tv$VOX%i@-M-rpS)BXlmFF8TLP7LF;71%Bp%Tr7q3wG? zzcOtpqhVBW99+cR4%Ufwl6P;OeHiB@`TGCtRb)65+!XFYc7B1uitifU`OwKlN_qIYjIBl0t4BmJ8T#GV|eE^D2Q-mbN3F)t12riE1U<1 zhepOOKFcOL@_sxSDn(Mj?4RQqb9V zpm7@*D1%%rML?t0uO1~h-ro(fh^MJN^SxUyQo8=M^Wz94|s} zX1TdxP#}JtW|WfDw#Izy0O6g79zPki4nS4AcoLFvK5cB!Xzu9fpKsH6{W|7>38zH& z0Mfz&1ih(}U97AF?d|RG$%X#yh?%J;tQMFWY9h;r!onPUd;`P7jTrR%m>B1$^+Td3 zdnxj1xsAq6LAQZwGwRDU)6uE(!v9icJ_eGGot^8z=9d%{Owz(+t4|!b>q{pg2b+^q zW%d{J&^8Q@l-uL@WESw-#>zS#@eWu+lzxY1)LAl3-rq62<7FDjWpvBQz5f1wO-&Jq zr;V%iLqD&H+t?^*X_-(`#()@lw9;0xQt?y;bi`#RTjbwBkdXYwPl}9+nzxy~emyWgUb9gO z68Q1);{f>0&1s-6$j7hBYE`HfX461fbU;7=oV`-cGbrj;>NlgLR3{@F*xP$lBCVtI zfxQ*9y-u$0lUXPNvU{RNhKCOh4#q~Pufl0;9h^^M@vYV3CI{9>Pqn4Fo%I(P9Cxh7 zbwrCBe0nmAlj}J%@W(g`R~dK5?@QCE%#cddQ)`#J1v+a~Hp}wW1L0wqMK!m`IZ=OX7#$9wQf6^M1 zXF;O5l~vA0&X&)c*_o0v{ucD2E@?aIf0bp_Ob__X+uz>?MrD3AFEd!b z;#CS0H0>)WDG{`sI)xN`bL0oofFHeX>J1;CfG+NIt4BLWiIRi_+SBZont24o2nh*! z5f0=s&d$s*F*7?lA7;+@Q{ydpmRVuF4nK2494@F@09c#R9UYw*eSQX`K__?FZ)fm zl^1(6l&6&L-ZgPQy#&7PaK|+vJ|0kQ@`_IO=PzH9`iwa^IQ*!2K=5m~>@+(&i}23Q z9%+<<<=@jINIPl#_;HPwS8A3?YO=C&j@mUO#u)Yi42?2STk+>{(w}cRp&$+y+dJ4t z{d$;gj;aLBCc@i(+>x11sID_FIvG!l#c7HI&N5M_oLE_CJX5_)Gv!TBOSv=f8!KfJ zudc#k^iBRfJNp`aVrXL%3I~gRU_zD^9vu8y_Ven*M0%Hzyj*T;p{c%pj(Mfic4kpg z7JMj%kB3X6QYGbCj?N)O2@=7f;o&-FW^r+G)HH6Tf0U3&bb_0}*MUV)j`VTr+OOy_ zG9&FRGxW^O-KL)z0JO@<;poIVuD_gIjb9YTp-{=>0(MIPy@ziNj=V{6hGZ^0-5#<{4>-e@rY zOIevr!51F{p4cloy1KqVWjnha4z-IERYrX|i!g}J2V1NG&lZ=Loh>@KAmpEmH=!c3 z1W^;Fy`6)C*I~9Ts;4n0Fi;wns)U65L!-59HGmB+E~7(5=*8{7z(_$YseBXnc^tOj zSfS(npWZh)E}UM;@9kO%W&m6$mi0i;e#gce^RBfJj-XHN1b8-|)x?+i!3p7zKHjpGYF<~e+ldQdc6XbNI#@-YVv;Sm+kXCh zWIfvkixHH`-#Q$&W#niK4Lxcy+Y-jJEQOCtGvUtNg+>_=$R%Ve`nR%U!x27fEYK9H&LHI~kOJ^q^`PP>&M1|~> zm?%6PhfH$M#>CIsXJ8{COgtxenj=n{?8g1(r+I8_3obA3Y9;dzKDPh-qE+XOU8t~W)fFSW7itvW;7z#G z({FxE@ep3dIU-Q7wT@s=4QGUSr@1^mw>9`kndr<`Mi$pql$}@mtLx_X)4yN81_25I ze7+};nxDZlePMR}do;LuBTm@!_pj?R{b$F(;nuEK|6ja%m-hU9&AVsVPqC3Ni#l!X ztWqnH?R378RKI|8q5;)-lauI*@}d5WasRWuvVHs=8p?dzf?CMV?qtP=w*G5}G{U`StI`RhSW%5p;<$s1-!-nh=|%U2+qKr zIiXR~VulKK#eYUxo@kh9j#M}<*KOR7@2~a1-CY_24Yu`SKZmokGZKjb)d!!&_z}kV z8#sH@;o`H%+U>X!w215L^YAWY+*%4(LG}t__2Vw_+ZkCvYb}qI!8SK};oa#iT=BH< zoRKbUg!H%9);otRfP8s12Mh3B(3)q3$AY#C3Jp^A)I$UW+c9y&Wntn=+u7Cy^EU-F zq(Ssf!MV~A{^^H&ACX@wH~H0`G#OFHjo)|ks_#R2CZLeEwzk#?F5r5P)XhS}!nSut zEEcy9&Rw{q0GjN?#ECMDn>rK&Rann4$;2OhAA_`MT5{IT&JMkJ;O}NEZUB@|MG>wzM4dioT|Qil?`EDSzbeG!iEhEuvWc9mms_+!(zW2%Uim8IN3xmfh! zTUMU8WL-CuoHgkSyN2SFAL&lKo-aRb9<4`Z9x~Jm_7?w~6E@Ec(cLsG+`oMR~c+^6>Wd0CMitrLzH)NyBXd>}`Iuw+=R|CM-${J%)5yBw4Bk?2! zl7Q|{x7{Mc!X5ytCK1BK>KhyzYf2TXqF`gQ1soEVADQn-!&KTXhRBFOEh7}Wd9k-5 zyg~gkGc(g3FFexUZwG?TB7^qfO53cI6kQ{uKOokQ;7~U(GovOWYkG1OXLob1)=`sy>jJBa7c)&i_6N`@9F7~&!4qkLuI}BKyDmi@{2Gwh!0@AsUH}J4kMS` z9-0pR0ueQ=!t^X2pjvyRDUhr9%3f`L9hZy+0@q!eDO1yn&2QRE?{0Xl#LG5DuU;E|ZjJRD-z3!=onXpR-Pil+d6{4@Gv8f$!~;S`Ox!r% zufq6B!BB!lDf@y7Sorgq&1VFQ81w@6$IBA)3slG);)-PZBQ&{jndPH93|3^BYs~2=PFMI6giu)Py5Tr)-~v3kawB$yub&l#{)#1l1bw z0gV>_jc4F1%5qk3Bm^(34-J)zjz_7~H{5-2C%et_~ z{{B9~J6Sc75Ro@P8R2Jk1MxflK-VhalR{MC`=H{AC>KPHT{_Br+DY@ns7Aj%EfPGm7@^a$)d!XYfc#Q~y?&E~A zaPgr-a|En;qVeFSaoZByn|!WX$f4L19XP;aRTsz*TOP@DrHO&*b?47FYMZt6^B+7s zKrE?l^9ys_3)+7z?$_mSYgKO0&}inUJ$4F9A67(*#p6snyrXqrnh)Daj z6i}R!l2sV)W}Sup96?wD>(fne7f;6T5S*E^3D))Bb3J3CY0F@ju766CURWYYh+SSb z&IptcqKX%=XiAkEk4mTD)_RwgHV0L74=u*2z-$AEB_gtf5p*_zNDxdnwip5oX>)Tk z(*1b*j{*O2{~{xGS18;xQ|ymT0^rJMv2VV6@~1r@NtB9XlN*uKZ>mR z!muiU{R3Y@{pjtThYxpP?IJ-o3^^!GFx}8lhB6Cwwf6n}1y)v8@WfZ}@ttSFlzS6% zU_nA5Sp*kST1JLz_=hB37ux+4vh%LT2iuSw@9OF*GVI)0Uw52XG5~}j3J3wzG(eL; z%`&KbU)lIGoDIfzd9gzos@_QLc8sfvtBg+7JHr>ZLR3P%yc#xUT7T5lU8j1K58e%O z)#~c%GBTZ@upLu(1hfu7^gV3qx9wc{o`J3GjUdEZX_T~ck>8Bat+1ZKZ1KYy@%-J*zWAVb~|6n}64 ztoh>uR8zhG^9%h03aR4V z^vGeV-Ukp)8mnw2B$#g?>n~3<3)ubsRfcw7S}@=KUQs4@V^!!RhFHDC{7DQJU<9rH zlo1tCIIeL$IC5I4e);1cB>bNg=AT01kcRSI-KtSTn?%%8jqmJC#B14=wixecJn zB0#;7?{G0S)$w|(=U3zY46)7m%W;NZ{}Cpb{P@aGSUr^9pr-wEz*U_uVTIgl&E zG->(QaLAs7Fh3uYq1O&h}$mr_m#Ky&89Hy_uN!z1?N(%~Dce+6Q8T-g`3huFC zd$cWtmj${_pnG%$=_+=0AP^raDjeY&0b)SLyf-8kI3Z=E>o$Osp}|3LiA9h#hAN8n zJoJgNzJ4Eow8Wy>&s|f2|S`(w?HQo zN+axK3U4j+X28EAAf6BoHxcIxm;Nc==QD!^wt2l9*iBX$y2hj$40T zl?($K%zIt2(afA+I$k~0-fjlcXP`TTyk&CWOR$o_tQmB~@&liF8*D3kD-`YQ{YeSp zd|jSzx2#qYos(k*M-c^~708V)UA)*9{ot;kp!(QWD;FA4^fq8i0mMM<^oHPSbx3IF z(;sImD4u2}YgftC)D*&vfGoHP+uPd@av{Gi6?I?#U~3-Y6)aFJf13n!2_YS54dDVc zDs5gZLNTmaXS^^rS^)>iAQAn@G8r%cp-xLED;H|3`&i^43*Llj*QXB&PN;o-hNsO< z4%K3ylGV@t_VG0W5Bw|KuZH@1az4~r9X>FL2yX~|K%GS{AG+0(HT@7n$aSs*8Z5gTqy-N3wX6v$OqR@}RE-L>DcE zOOumbP?84q5GB!ZaT;(reKT;%=7agP_wE(I*&w`ukcF5bT@*irS>|MaE@5|hB#q`Q z7xFIcaYc-?2@JiMvY#Rz9^N0gop3W?k?f9IcV>8jJI%<*XyiJDi(mLz4;f=HmKj6g zgmv&dn7FpAr(D%*bpYmaIYAzx>j)UwztuO{)60um#N`n`{}3!`m}4g=CyhB`A&(&Y z53X`LGb}7@SPTnC5#HKAK9UL>7#p(@Ovz^r>Q2KGX+%&6JQEWWcmTuT;2@+&;Qr8x ziXy3JqGMuAT=M%&C9$w%<*eLRk>V^Pv$n-zZ*37KLKK$F0zMA%m@p1^)dryy5teYD zO0wIjGKrW5i__5|^-xDgZhg?hZ@LI?Ag;{77kCheK;r#9dn>j;3?f|1Ebws{H6?Yc zkr%BO6=rB%5e?xd%ulipQ20z-*$-HlWGGdD*@N;;$F>E{Otjj=IdNF0cYVj_uz z3`8@)$1~o!lL(_?d>RdI;f2C>_xY^x& z@pLF;217B|9%B!#1DbDwZZJQe`&+p9JQxi2)C)u!smgV7ewIv}~<*!9r%N2DNr}LhyntHhN`hx&(0R5&=y$ z?7+4>JSAlsYTyB|f*F0JUFQjt4C0^7AnWUZv25+^04ha5EhZ^gKD(ts@kc+we0zNO z0G$g)!FvH-eD?IIkinmiSMmTZ5i`BSyLQbLB4TFg*hfac?%3PgPXlp^0hlEd$(@8m zyBYgu*=?NJlnGYa|3n36bkysvf$KuwAdp@H^&`a4yzH`V1@xb4j*oTEF#Su3>do=Q zfS`TL9JR8fcCgv+n(Tk4-M*dah7oaf6Smis{Be#+>J*_w~IdeSU zC!S*8{U7W--}jaUhS4Q1kmhM;Of5S*&7GaM`OIIxem!cEhuUf5>BOVW z)kH;yg#6g_#l25{6|l8=_g9~1DL%fwa`-So`)&i92@HiG;8XV#7uy~vz5?FrCg*FF z-0N6c5a;iqu)JCywVYCzijeNfQ7xJU3<#$SVOXa5!Au0Q(f?KtkRsQq1^j7*1w=%~ z_evbWrNIfPfkp|+lS(ZxnoE(uAGl10maR@f+~u|A0}*;K$$BZ;7#}0in|t%wt!;IG|AnlUt4<+e?O6 zh{p;l8&kxQK;*%1aBnDqYa`TwTL1@%dT6Ew%J9xu{vy5R;2ZXsDtilP$pSp0-Rig4 z*jPZQ2Zx8yW#eU59~RZsdlSJPAgO9Klto%4=XRCNAIQDiqHZogh&9B^85+)Yik`Z_ zwSdU3(sH^HY8L}SdR(DsYG&=986K*!?_2gyuo0wlO=EAbfDG1{6Jm;VKN|tCm*lE zHAP#JdDIfZW7vQ^nzr8tD@s7l{kKLOl=UQtxJtuX1pI=l`5fjh0C`VB#Y}}aK)^aU zl&e8(umc{uM9lBzg5uMsPh9}+H|#)?yWDO$dY#vI2<2=K=_8m-9PI3#gfK}(VdMj; z1$+0h{rh}1SlK@Q{P`2yExSf#@9=QtAa-iPqJmj^jq1@F08zM0fC8`K;c@4j(JVN! z$s42=FcKUp`G4bC!tevCm4fs9C)6WDP{BHZ7y(G0LUvI4!ghtWySp1gq{-D)pf1%*|v%l0_r@qxF&rkS&`!6$?ojgE!DaP^u~ z!(sT`yg#B9S+z`!ZuK}U{H`Q>s}!t^6)+afq)iQG2g#` z2a*HIGQ+LzV{HR)DFEg{zU>ZnufdP(aBnZ2o*0^V!TN#P27Um(pmv#QjUaRN(_wYm zS;FdsA;|!XIZo8w4VERN5+$z@_R8QMZbQIxcz7ro914TqXABaSelX!cUUx?E%(e4j zdW}l}!Ro824NG#N6qfMxvp=R`I~qe%zi>{C=+IC-ZEcXLq8KHyCYsf^5Dqr|+h*ps z>?jv@Y`#BXMXvY51nI+T1ec4oC{Q@wlNLk>O-vu%zi+j-HVGuqz<@nmI~dvpPOv!l z`1p`etZZzYi9#KNEmq|nzkz^A^gbP(4txyI2CUU}SQpTtsvLqX=obb2LmT83+?c^9 z#euDX+QM8UdK?bvxH${SAqD3U=q?AHjC29_g5kBcvB8GUupV2j-oqikFuVbV5B6sS zdj_Mz{4(;b#RH(LfRTWMSc1I(7)XqO&=&Z4tw$*3u6hr+3;Dc_nYc|0O=atD~W;*UZD0@}gt+@8||B#m{xyD-hx^A<1D zTyda-tf@j@`&eC_T(BM_B)0ifgL_YZ*U?D?<8N%13^yG&#Vh5E{F=qykZHkjr&B%b7K z^22p{UMB919Haz^ObsFCNyPXe`3Ep7IVFWu40=eo zESC%bQP7(MG;M<0!5amI(9~4@w{O?hCVxQ1?LQ&WcT~#&nE?So5Wp7-Wol~b({1@H z*RFx83u3=PFyhXuC^8BPHE3Zew}9omgcMn@#TgLdL(`2P7z`4xz?%C^wjUZ& zL4-8j7=RD02LUb^8!zDAcDW=W%3O9}_TZ;^A-R%Masw&GO9GQjtNZ2j>eg+Swf9O{8ijhzfUmp=Va?M(q6;`R z2rr?xLllI-y6yj4#MUr0*8t}5KFlO=IRFJsfRzIFIyJ$AK>|7>Bqsi?QBqX2I99a_ zwEzW{)6c*I0~);=M}_9(<>j5F0(Bex?}e9{4#{cc zmz7z7eiPDRmLX8E3p2rs(A?Y{d_|DAH#xu6SN2vK8XA~0_yh!JI!u5!;7de+cS3kW zY=I?u!Ia52d58T0wgF&UdrJ!t%yDXR5Q_jAn$Zdw?LDv!lB1U3rV8014pIx(S5_Y2 z!?^GOmVj0@&CNca2oT<OLZEq z*!DoI0`bKQp;RD3Rq?)npN7Ivn5OkjP2wD)5T^oe1 z(CAy-MtJx3Dok;tKMSPd*ZTghxVRX+A!@r{9q1X*kL5y1Jwt|y)O5&ItO0~_FyO#| zyctu^?V0y)g%vuC#o4!AKn8L_H5_n-`|*M8biYmrao9#-#plnT0hxsF5s6`=meSHv zaBzZdN9Ad0X=>y&G$PR z<3@$6-}pu|z-|M@39UMPlU;Vl>_H&m{Kq7G1~PV^yu8dXHNpTg9zL{#`330%c6~By z>rDtVX<#^-Zo4aV(n9ABTH42WmSB^B4sKB?`p@j!z~VMcQAlh%0wRZ^n~>mOn8{_( z1&T&6U8V!#A|T;D2M6Dvq^yDn4qz(0jZX_{QE2xDw+>4Q#|f0cThJOOJrDPGUIWUYf8GWdKhSb60ZUA?a|f_s zSz+NYcoQJ#AzcPxQDY#r`T-|!vk*b4mcPXkM-bq{6~R)0=luajgf#W78#j`b7Ke%q zpFXVz{{*PZLs;WjrXPrOMnS=mp`i+Pjm9-zxK?P#H3(V>Sm*FrXso&pHwtE= z0-m;+8CE3(`2z=_BmfUU7)}4oKe6Fm)0Y2f5k2O*Dn+Hy#^9;KW|o8pc0!YW?5)uK zl(8y(#fbE&I?m|@h`}1kNO1P%;92JBnK4x{Rmue$M@K?DMQEwg$T-(IZQKe>mg3^W zVt)Ag+Fsz%*7TFU)seJLNfdHY!xU(&=LOjM6r8{R`ul$h7nB}FtpI~(gg@bahkoIkk;JWQs=o;Uaj-#uoN38Xb6({Oi7Wj#QYa`q>a|D^?h56C|I zUrE!xqZ{*_+Lr`X8L_H1u(@?{^fsOY4iW|Zlu!j zGOU2&e}w}t1C{W)61C|m&NxC45qa18{Ie$hH&mf#ANXbWf0)_I-O_L@^ zJ{QQEKBH_?Qz+zM$S8g-_X;pipPEK86@GB~Qj3-VkH5~GjJ=~_0av6W0( z2;V04%kHlq@RhCYtQVD(q}aBQHfTZn!hN3gpnA`X1TuMY#^dE*GQu86cW}<$3@;u* zA8DxJH8|jsiXlHIM167FoW17kjJtA&k7#E9I`-nYY2E$Gy5;2cRpoP@5<0+i$cIIVFj zd`9ax9C5KuC^8(~pdJLuNu$>to<)f4L(ImV{yCAEEh$pLvcogDX{ zYIv6;tHVNE)8u9{FQGJp>&Nnb1%FM)#50yqdQ>t=AmltJm_(ACSv+O0sH@^_=dvP5 z#>Gp%kV-tigsL5CX52q0IdsjNy>3Oko`-piy<^{IEY_9G&Evghkkdx~=ajm*vs6Us z)z*Ai`b)(q_w&Zp?dRLtp*P5?efoLS_{+3buAk_`RO#o4d)GTykEWQLjqNYJ+9Rb5 za>v(Cxdkn=zkC7!3OT8)`f}sK=9VzzUz4oqvX&1BRZYLDsbBo+9fo%G*s{ z=5@iida81`{*czM2saj55^X9uw#y|yylb_pEseQ^yhir)R<*iThrC2tt+e^5XI7+$ zpcTX)%d=s$a{l))Ui#tsB>YAirY^*G_3G;>5$)v3lep{t^6jH>PP66%gkoPjWmm4- zvQrU=VZ4}aS651FSYl_zSuTmO`09N2gu+AVL;B09o+}P#6L17O0r%W@#)Sj|7i%_; zPgZg=$A4Y>j8l%oaBjtqB{!M9Io!0>@3(_rTtQs(%kU7r`;Mx!zhn6t=P7h0d>U&6MK6U*A4qoCp8)fCOLuYpdMSI%|o=Ymh z=MHx7UEP**UF<&|J8y~JJFZbC^xSW_I;1{Nia0petTQ2{nIIa96ss$V5Yh zIC6U1W}&29<8!$xI;qvbktjRqR=~6tl2*Nv#Sqx+PD;YhQC|I zR+C0G@`}a}AZ1qEHgs>F?)h6>yGC%lCN5&N5f)gP`DnGFQSO3FMoj?oDUV^=I z-V;Yh!FOK#duR+_wvJEzmKh&aNl(3LX1z`!0`eviA)%wR(`om%S;tPkRrli@{>pA` z1}5Re@(??v)tttSVKu^r*78U0wD%Jng%1t=_nX`gbl4-_PsRpjA_bKWx#v1ex0IJ%EIbmn)TYR zr0FIZoI7-#n^5FfYF>d-U^|{T(u-Yv9E#_bM?`XVM+q-#Yj!Q5!n}p9$p;tjuT$Bu z@w=ZK0Rk1`DzZ4OfuL&KCc}F3gl|r{?QuFypugtTT@} zbR72J|4~-6y|!Ftp_;E%i+$Naea-Ri)gPzZeC|cSl|gq#+tzTbgzWGX1TJptl1K{B zJJz`DqxTDL$4my#UHAMJDqtMgyG2U9K>49>%>DbT4FvtKyt&k8IgYou5;`v!Sy&+Z zN2*R|B6h3uccB!cBG-AQr7tbPaTa;}Q@o_VOPpqZM|786!|8B2=9~*0!);M`x7rGu zw$ow?nO{^d*e@NSllfEb>CG>&1S18iMVyO|v5jaT0zIrj{+xpX?7p$F2lwt-{#gTQ zA`xa6wAJQlS8EHIPEfv7?lwe3?ysIs;^VBij*K`tg@4p`fEx^C>n&XYK{9hp>GJk- zUK5JX#YF@>A#&GN8I4JD+P~m+3|>xENRq{oWxu&uar7fd2uR(Osw({NAa-cwx=mi~ zroq}b(gO^Ac9sos=KZewMxzm|05#xL= z$(wvLwiTLARH&D_TiL2!5GPyr4fG6g0Z*1{0OfjyW?xDPbeKuBZa~B4-@Om@jwN-VmhcF6ISm{Np`L}PS!YMZc_+ehwn+^C(L{Gxhk(+kCAK4x`TnxhUiiwT&`I=HM-^P%%vjfbt4RNSCx@P4~G zGJa_d-+5Q$q&{RhwR>!LbXlMSa(25buIs2(SAus#h8?f{{yii73``tLyyt<|Tz-dF-0qk&Mt#-M z&dtK1myS9ghzp78gMP*9+%&`a1KUO5LHfvlyjCs?mVXzu4@||tCEV4) z3f<;l#s-~&va}}KvFGDzLl`6r$?E|PlrcQ|v}-6vx={$olI?}>F#p4S8%!TonJp?| zcJnl;9q6B>?!ThLd8QFvlE2&@G*O((_t6b#=!x1V(5TIN5@F!BedI`II#S6P(+(Xr zrOM1G$jQ?c*eqE<%3PYw7tsnyLZ+B@JA2#h-Q5|h3b5oHfBulu-10%Z-ERqt6ST9j zwVU1Cha0||qhh%utx;xYW6FN@2ln3n$7;vbeQC0DlTS%McD%TTQ}$`iPwS-Jwxgf)L8JB< z)Qh{VJ8`QnbILUvVL|Rw)47X*0Rf6^VGm4{1~>)}4-P*+DntTdm|L}C?C4ipv|r-x zeg`3d@gcqNw9OQ0Jy&luZ}511Js^`MaMWnrALo4y&+gJr==3&}f(P7_mk%o~t@Fo) zZpp-5@Ru~S8?bi3Yrq02dSjWIl3A$O}!8D5>3VVP?AkD zr7`A^E1v(F(|!LgvZPd82`|1%n)>qx4!6HBa49%JVMl6j z{XWLyk>o|gTWx_m&n^lN;D4BSu$uQ0`nTyVJXU_uXQ4S@iQ}oAUJ~y*+g5^iDEO6@to}vOOm6e$f~jtwsBM$nzRN>@rXGtxeb3RBDP8|dCHT^RX<>Ut?9wO@l| zziAln*gu-x*&ppBYf$rjR?-je!$k9#%=Q+$>%j49o8JAf7u%Es!o00b7~9ihwX9;o z&4WhHg6Fy~!oD8kFAUcN5wVk8*{xa5!O?Wk=Hf}?#WT0Ca9U5RHhwDWEt7uxUhSQq33L_vj_prGJl8YMOLwyXP(gYEdadzL5{GT3TFdV>#z~TP<^=r*1B=4w)42}2Q4avn! zp{5=|YIemS=BhKhP|e5Pe%>VZ^)!oW^0^?wf#nf&85d5?s*JQ$KtK?(+UCu!yo^ST zl|IN|hb_rj!e0bV$BI~geE%!*$tMCz-R=a`TWG@IN0!DG_TFRwG#FTE`7IeD;Xf+* ziA6=5sji24*RF>%GhNEnpyZ0M-WMW*kcEd^F@s9Ps@Tni6Pe$yS?1w4djzUG*V;2MF9BAa1HJnHQv zR>7b0q& zNCTJEeJJol!3~0VVF6g|2ke?%<=>Hqobt?u69UW+UP5 zr>m!91L%`qn3FNg_Rh{xRl;!;<~R>6UO)eB+-BB_?WVQpmMxsu z7k=|K{!zE-@#cXBJI}iaqzJaTV&@zg$HI7ltGK#4ty8P@n4tZbKkwS&?X{B>27JsSOKIe#>Wr7 zfGdVPASPd1n9=nQ2>Hg#P}_s+#E?g0c!x-WR=u`)&I>&pr1df4ux3pIwYr~+L{tqO zliuc){1x&((ss73;y?VxnrnjFpIY3LliMe>P9S*>I{JkxdgEfrBV>9(t3tJ#b}6r6 zb(y*14Vh$vJaRf5HCDM6Ta<;{aqBMn@ck`Ox7prishF}ow=hb6&3WN-M!EXzF54zZ zND+d#+LrK&iNchZ0gCtFI zEqh$u67g4)I@dFU{{BWulk?9rW&`e_(aQJ+FK%3%<52j&DEsQ5xVH7n#t9PKArK(A z2PeT@g1b93?m-ePcyM>OhQ{3`xVr@j?hsr8%(?G(?|W~irfO=csQ#mYea_iu%lECl z*7{!X&7*#>>aJ+1;b1ixe0N8cI8PD@p!-jX{bsW{^{>d&$sFbVqNH0mda_voitRU^ zsM#oIt5D8nrO_^&Sn^Pvd8fYa6`ML z^~&QJSS_l+6&tO1l%LCfdSQ$IS9*+L+B1I)Eg+4>sWm{%yVkCAkLl|o!RW4e7d{NO zP1uP=^GWEqUS88x9wZF4Yc)#05v6MD7C8H|U^A_2YSKqU>12S+o|nN%qcWA2mY4hT z+BSVx6W*cpQSrYYsAG!BL1Ia_gkbJR3qF_K1xs7?kMSoX3pz^7Lv5r`6iLs9Oq`@HI-|3TDK_tDbow1}0XY8W)t98a$Fjgek_CZWOJg?dk z5eJ735|@@jClEyi;7PKWd$#|9bPPG4oY!Ys{~VX93Y_`KVZt-ie6;Y(p9J^GNfC!P_fdwcW;@s z42#Ayxru#1U#*LN6x^gTtZ1&lP4kYzF7g}QM6XMrwD1n~^%>KqB2wLJc5 zc46(TyKR=0K(zXln=rg{`Set#3Dti8Xgrd18@WcIH(v%&H1&nCc6nt>gEIANKF1@YV2l5=y?-MQeV2mf{|_|ySLDg& zi{%OQ`agdG;Ew~LZSVfZ4*wOJj_PV{GymuJ0GcI8bpg~z{|6HU+KB#twqYv11^`$8 zxy~*-rNgWLv_OG;iD!ZTf8Gc$sN-tKVNm$5O9@r^Tv3t7{L{p@`v|lDqXEL$#{a&; zH_z{by8nHJ9-pAM^B4d7H~q11|GFo8_JlkHvcifA1fmIr&hb%WtNwmk#0qrn5e}ul z|H0Abe04~7^k%<0FmYJzDN)~}O&w7g_~#VW^5ZkW@bUCOUxO(r?HRAOK?e$)2n!~U zW$<~(Aj^~D>Ew#jTg;(*|Gmx!gg_2^~r$j`T;$iH}@GI z%iN{e?T81FtJ9|Z11ASf?>}#(5d^)Mk6``y2#8x$J$^b33=W2}1E~d&Pb5%Mf@JA! zP5^!B%OkBXCpS$QEYMxXB2_4>P~Sq(Wq0=evhtIB0<<1TCW|eX09-H; zivZ}tH6>{$LBr6ChAe>pwcxgXk<TS;~G|a`1gzY0dU>c63ythXo-9hDp=co5`GgkJPcr_Bsp$g!#ao zxqGm}vIz>>%hUBT1B0V&iqJIAHw>tI@H|?p_*hT;KE(KLu#tSoj02D#{;V<%oL|}W3Vrf7Z@g|> z$*mmDLJa@})cDJs)7?1`U?LV36>+4F4kwoJ*taoz0Y=UD#f@z{SwKLn-zm7?0%TGXfO5bRGx5y+5%8HGtx0kCtglYA68BNJ>g3Xc#^%YoY`- zP?WP@0_MkRbyku89`%k9Y_)CIE1gd(%1)bq(b>*7M4*`f!QA(vG75zI6pieAG2*dW zK7~p!4%M16TxgiKg31*}0qn26%X@&gCiL>>y}tgcaxj5kvcWQ-lmXa1r%eE=(jE9X zktxt>Jp)j@P5@@j8X@^#Rx%VI8F3M{*4ukPkG8gE4!Sw^WI+pT?0ovV;1*3L@Bnc7 z1kbx3^%oEv0pcDU(#^X2N|GMS!u&jb@UP82IY4`U=()yNnXw48f#I_eq6=mQjzzxd zzB0AF+IaTpsBKq!X!X7GrbNTQz}h!_`OyhjbK8s<|1+saJ!Y?xUy})5MR~ND0vIG~ z$K592@~fE5_wmCAGiW=f9tlhOk*S3dXA_4?t9HcvGN3|>ibCKKFao@~PEN=wj;^n+ z@KJ&Q_Sl0iP;yVJ!B#@h5b!L~=T1L4JUl%!Oq?J{Vl@OHgN^=3EYQ}LDIA>UY10;S zp^7(4@_K_^$k`+CO+G$=rvYCBp2+5?1nvxlA0~90o!xYG)A#<8b)xq=Iy;Nzu^NL)Gea*h?>BR7%^Q7u{A> zN)x^kXL82%zVZE&edNII0#ssnv*+CGI=^^#xA=QYN=j0)yk0r^yIMXlt$t1uniAPA zeZ5Ry_u34jEn|X5d*Y?v!RG-; zYO?=q7nj!q_X^e8Hu|YmLsPC%rv6g2q$^wMBPhhp&A-(Os4aboI+i&dqywWz{{91;ZpKR<1PAUGuC;Zc*=^fl?C z!-^((IgDWtSmRC|w02!&UI2veQ7cl+_-x*CJ3S6-N_Fp?k58A~%u-yQhKA@B_;MWP} z%4VgL$bO7?;d>gqKH?c)EIDccYJ_LS(?(|sJ`LxJA%V7?ft`&Tw&`-b_2$g?;K=Z$ zW{Ve?6DMbe_pJL@z;gn1dt!mb;qmL-WgD=P046f>Lgh+y0Q@-+OZAt!DrU$GAZtBb zj672R&)c6%<8!|n{OHiy_|}LW4unOB=1zJ$+5P3~7>N46w$3Xt48il?1{z z%6EN#KZTqdja29%7Q-jnvhD2TEXMesd3u&v><$$4BzwuvzWY)7zF4QWaUR-!vb@o? z!${yz1fCn(TQ;BkYfa+|C5QZqt=`M>Oq+agAPQu%L1oUT{yV5@M1x*vcza82ufAc0 zOG&+_5g_~vChQ^Y6V=5>|7Re7rEs+HO%DzIktY6kjPbA4A|+p1=l?rABLxXvtG?U_ zJ>7Pm?CZ&cOp2LlC@t#l?6J~ra%9gMUc>q`U7{K2tGy(BjqRFhEE1!uADfdeGL*R$ z&ftW@9N4qtl>FxPLPSAvsMSVgHZsKw9Z&$FRW#!1+g};xm1I7IV(BO@%;M*}l~_=o zy14R=eK?#d&Bs@YWkeh5PB8HhZ5&Dax!svn9q%{>e+S)L=IIhkl{gU>*iH z*%SxuXPxzFstYpS-g@~JUW=bT%~RjQ4HP{pOS2O`C_IpSjO?dQ)qejW6p0}dL?oXNT)e#@4UqkQOyYoWeV5xVs^KS2jmK1%0S*Nny?ia1l z!$`LG%?3Q1gc`B;ujH@$dxx3#fkID_Y4uziLNA+V;?S3+{LXlGI;%qdpPG`iHn~q@ zNH2065`6r-3(rTDFoWG1IWcZ7MCwGBF4_bYknh2K(65&ZUt6zfGTcMB_35V^PRJf3 z^$TaKxX1SPf4@8-WwR_m*yvy<{pLZ##B3t$5j7mY{aHY(N{?c2a7}&)8!W@gZF+Cw z)zxf()3L)GeC#qdaZgtt5%yx4$FIz)gUwO%IWnF6>gY+#2Nm-HQ&Y~mZ<9y7{mI?y z8h23d*S&sCr9}@H&?^Gs32-teH zj_yXEZGWz})g1ll>rRYljc)hC67E+Y_UQj3OSlZSg5Z_ChosD972{s*e^zH~ih3=Y zPugCfRq`znldfS$l7XECfw zfoc8vdrexX7NfZ|eHWb{XSe!mVH&eed}5M-Fizg^EECv81Y~3w62ESx`Ran49CRW! z%$g}B@hZ|D{&_N@H;)k$KELzHi4qNw|BgnDzmDi$gSG{vd~iC3Fg_{ogrLr z;?jbXejQ?CRt3tMHlz42I_NDC-j=sO7WbzEoE5ix*oR zYsbXxluX5nBgXy2PKrgBc4U!|;aF*~i8ksEcA||}jxhFdyx(sJ7t)6he2=l{ab^Dtn9cIEN!8>omr!$F#F&MvL^Y`bZYG4pU zykOnKs^W8n%6qHL>Ki0NQ~U4HPrHrJRV5i5v%0MsYpwVCRPm;r%{DmGjiMachp;;l ztY@7Lk1JVTzg}6vfpn#NaPqizGi7vv7?|I zD`y{lzZeyKxL=?h?*UB?rZmCD4)4OwC!m{5q0r?cM%1uR66=T{nG+1AITxak$v79; z;<$~%`uoqDYZ83)7{%!KnX%Hg#)UBrAATHtAJTBm;-~y>;;00%Y?&Zwkf>qjvhsD8 zs%Bs*eOI-lHiG(yh3o!4cV_j;)T>-3n!2&Z=3$+krYQ9SeabcCcUTz#p^eO;vy z;f0thrtl&JBhl04#nW9^WIDNXxOGu)Vocv4e9SAc z!aC=z>^Ptx}$Qp{0EzCg(V)oXbv1_er6vIQ<m^{m*CLnl4MduFmS~_#O4@@OOyoZug=?_k6DP8X zOC~-s*cPaR@Jon6ofjURC}zfUi+6kC=oiNM z&Xp+B$-Eb2Y*qeFiBM~YBKi8_{yTb4&Y{$>B@~~oknH54z6%2lrY!k}iRt@Ui`UZ+ zB_d&M8&H+Zo78-)eotL2NK^Zw@PIt}2(|%B7BE92XtR z;JawzYG@v`vnXNV=2Y*VQzWX~!BehT%g)_U>f?~e$Bry2vz~$MVQVAIfSF0aS}Fv5 zE>DK#1DuQm)eI6T%Bv|!K7G;$dOSpwCY<~$`|^;Knu_<>#Xn>uU7X2yaI>jB!cG+A zNOX_3h!^^XZVwQGpqj%oyKmCoXA_%ek6oxT1v}Y@;vANK8T)9P(IJ6t`&vphKs_N7 z=@UXV`#s5lg&M)uGzu%bRw3k)uJA$Pq`}VlvJ7JF2xJ7QJPHba3 zapdI$)mMWPQ5b=y!e*ugjXW1av+rKEx&}^*$yop~kQl65#qyzebu5dN_r>?iFOLW! zOFri>eJnV^!&3}0471DHZB~|so)=*A@=cQ2$7~Jsa z(HKRLF($!wXAhzs8=5vt+ zm9H@>j`VAd$68#EQ*wpnjm~4YLOQNyHT}gAhk5Y|H$o=y84BqnkhHp{m_=QbkC2jB zv}ddPFG&kS(F4Fa`gRawt4IwBi8OU6e!$YT-h>ON;sK^BD?cDc0h3=_$_61oWjMtT zI%dh?QK|L3Ir%HE42DyU8;%Zczo{2ybCd~$C;^2*DEyVidx;u~Gvg;-I=e&nmX&R1 z|GJApr4-kQ>u@ILS8K_5^nKatMg0Xe+G})03G8iAICFM8B~^P|?FBvvTvucjg0- zWxKHlA#|EJ_ys@N*vxVhXe210Al|B~a84LmdabT1^D@6QpePw7=7w-kE{v|kHeW^c zFrf{oX?ZH@55qrjZDVMggwl{K{Pl3Tm+Yt70ab`=c`R5Y@drlqotG^}~9FVje{O0MsV+nZk zB_lRdkfL|Wv5*LkFgqOkUB-ExOeFA-Gk7>$_Lcg<1WZczS^1lEx(<2f6HJ#aN}P!5 zrHoeM#89Uw-T1T_pV---jIz#|N*-1!*FQ_@w$xP^iF|dqMobfAJ8bBcTQu0h?&#lV!$y_tlaT4$e}lm&_vRwJ)Yz|lSqNyHy1c}EiI z^u@KnrW+P>_^Z}%Q$`jHJP0RVH6)sxVSb0i)Wx$AR`+!P@5BI&5U3nlMi$5;34>a= z91$_^22EkW&`&Fe)1S=9fBm$~ zdeqaVLb|?-b%?sdF(u;BM8KUyl&7!+7)2vqfOx(HaS}x~yT$7QjV|xgHapF|9)#=1 z)7j=3OV-RUJ`<*F4Y>yN2!+n|RhyczGIh+lnx8pI5s>JRs;7&u1!N1+S0j>`tSl+m z8u-;o$jjhqM)&kgaP{;DTbpg?D-qz$Y7KH@D({W$@+?wUP&_;FAHMbtnQ?W06Jg1& zlvh`<>K~x3-|RSzx@A6lnBRHZBuwp$fT&?QO#LoA^b(pNX%sHmOK7Fatqz(b9`2H< zX&0pkRha;haao0X5^zO;%yae+Ysl|?i0IHWGkQQ(RZ7F9LDw)&jEGXS0U0O^^*Odm zqs`5e8s!J4gB9Z~Ef5avKk3X*6~*+Qawtt=$oYw)xt1o`a79sRMr>cvlz~VTO{H`x zR5HthQ1b0DEfZ>lt?E^bMhb9Y!UtjDo5G27Y^o4ey8O5XscgPe7AC-IBfYMDt0l)a z@0EqvH>4f4MOkG`=qFq;Li|Ii<1N&dt}pCw2+^@@PxJ=K}AgWglIvQrOOxhQ16IUR%oFmmS(c1Y_s2@mxM1 zXOJUDi(77{)HV~R1=A8LcQ3h9s|SV*OV?;r(B5^Z3AZ=c(2!TPNVt;*&AM@Lktvc! z2!2nkOQ#8Kg?ams2 z_!Kq4Fm;f9x>v~NHu>J{>?Nu)%vr%)RepW_?-&>RI%gs*o|%N`c2?O62N zeeBMc3mNx1+>F;BHP`E#yp{Vek@xlLnpVc#ZMqh*d`(90Knzt?44QDTYB?(r+Pts* zGBof^e}RSfm`DdAzTTm|#>f=(ZTP?rD#N7PrtB^}4Kx2$!V%CE55mpz*-0HYk& zaVC{O?m3U{xL-2yt9cb3CJPTorv^5zVEOz`^0co6Z4%~#ejOcEs4Rhp`O3VTJF_h- zHtu_n0GBd!F2Hu&jqJo4iW_QFUK#{235NEZDV)g)H{vu@>nC;6$C|SCbZpQEweklU zgy|_MN8IU+Rs${rTeUd?VFMcqyh-{jpRN^~_5cG1@<%HgR4omokx?}`!UEi&DtL1|9Dh#s zMaNl*;I|eEX~r`2nx&9yJZp(?Tv97jbes@l!gu(@Y;Z~15(i+kngY&HT#{ZhCXy~} znE5#Kdv$=s_OC$S9?vtv0@JlfPR^RV)NE{Zl0v0_ky9U9`bh!J@M9%g;ux=ACZUje znI1GLWd6*{;U{hy!!U0BuH>9zMH=eOv>Xo50sXW0M}^je*rT~;?YXsK z&0M?K)r8!yfqar$P-zI3<*M z(K0$^ROxB=!x}8m4t%bV23eUl)360TlTN&o0@UjwwiqLmoRsXFcENiB)@;Dk#uiZg z-u)Pyo!t)C8!&PMxAC*%KPdS*xIo^@@91?ofsIq(7*P0jdejrUU>)mdBo-<#01vF& z8OyBb#~d88MFxr`hMwhuvaqHtUa1LkgVn}{+V((^c}MDH+*KwcXAO1AZn~o$_{6Rx z^*nNkS9&PsHsQlTDm!3IT6t|-tqvoRYUcb*HZ+m&NT?b_Talo~fO`vESk6^(#AX!f z_7PyQX;~m>WaZau6zEZAj`3IE5F^Hm4LfCkhKH<7Z3!2B`d1q2TqX{b>Cnx?H3m=; z=FLI<30QKG5_sB9x%;KgWS#q zNwvDLW8D*q27TovI6CWLutN2$Fw4!kMY;;4<28nzrPE9v*=xc<(8YQq{G)%)x0~F6 zRM!HP27L2cu}p~6!HWPDH>JYW(cHu@r(G{(+WsooFqOE)=jLK)03a79LbQOg9c4U*T4fkhTWX=q&rgK`*s zqV}RR?~lpB$>w;)KWe$#ho5?RA4XpUS6bbA51B{2lk#QKw_NrNKRzEi3GdWEVAb>} z>X6Ym+?MEKYw}=u)aA${a}H-O4n9rqEF>F7)wv9n=I?MqKuogr zw1V;c8K{fd@6uVn$EcX?jVP?AMmWU!b`!f#+AAWfXWk`Nuw}=8Wx;`d`*Kc)8Lcx3XKM7I7ob$JSv zwoc`nM#Qq`|*K@wy4kyWn@abf&30U;TYx(F3J);9}nJ&*49|;FmtQ zx@axbiP33WBpF|#!yp^NP115ku|uVNXY%=c`n)jTPaOquo)}fw8eyk_dB3QjBdQ3G zsDY-V00m*@-T)o1z{z!(hJHLhOpQdg0dxD}hxJZlYif{PSX&?Tt2%mRb!wwP!PQL+ z&zQ&7u1a(8s@8G`lRBxCG+#aKrUL)lD3#SrdQ|9J;d)qGtM)O4(x@z}(Df?dJVOUpm zv91%QDEc#{27B6Ao5i$|?pg9KNlfu=S+z2C{-NflyPcH?1XK`rNNHK|Gk!hli1$}P z`#|N=2daFYH(yV)qtW%~7#d+wHFrphHy4Iu*W+MPRH?3Xx?ac1l?=eV*T)wdGC zTa*(wD9+csktJI#P@mYGJ{NcNX+p7aCPIfUlOZ4w>WU#R>Lkdk!GRGGce?PIH(HcX z>WLvRdIbJZLO4_B3Y|8yu)St9J)+KePGTCY+Vb#5j&g4aiIqDTHVvFa+I|?oZS-RM z$7EUH9wOs2<$gFY#WVq50tCz)+cq8(HMkO`Z!By%goCMm-ok zIyv>j<{v>70H86FJO7C=ScI8E35u^}N_z4=S}~UL#2QsBC!;KtD}=}MA1**$HH^`~ zNW3wj8bp0ys^X}rLQaQ~TeqbZLqR^#j@dn7flde1f|jtQ49rAg2|R0O?g~0IW+o$I zt`Hz>f|K@I{aHGW#~!#V{1di|^QKE_h5jRlNn3<~0;bT#}9zO*?O%s7m8 zk#n*lSi0uWdibLitDg9s&o-hqGQDw;4FYDnF^TzgCWSW3cZi4`XGk=IRxy+Th_U8y zz5eJKKmG-Meq2Apt9EMO5RyWWN1>1vS?o5GkcA=DxSO26+0$4Deh_Jzl_ zsiMPXSVhS1TA^SD;+8e>)*Mv+L*u6y_4bS)u{nSU>5vGSgg5Ru>mT3}%euQ~&)H{y z)XMVvzuA{8FXM}|>VLe>5b_+ORFl=V5yQzIaSrNUo`MH|vJkD!NMz^|Q$1A5cb3cT z3;qIj=Fp_04p2&nPFSv(sw&lZ0{4xe)#33^COn8=AJ$6hliAmx$d(VMeYnsqOqOJS zTd12wlfafH_oCt{3#DA+%&guq|M5%KJ8G^muw0XiJDl6oYd|H;=-{f#HI`z+mSX*I zs)DU{I?!5x4V&wgQLTJ~1wqZMR^dz|F@zefvRZX-^sMo;nK!;6D9LNqS^!i~6QiYMTXZmi^rGV{o0;2lPdlE zibzp))p>m7Ntbm zg?6P16tO?x``JPOg(GP(KKv*PRrwtk;s;=`Z+RNf97QHEiZB~#hRo&Q!&gme(`JuY zxM&NZLD@6=8g7|&u7bMDs*g)tm!iSg@oSVz`s^rrMjNokaWU%T%w;3}!fNK(L8?#mlL|I6DXr zKQTpP=IpA(_1ou)IY;Y#$VQBIym=J@iF0|rmW`66c_fY&!cGVqDWRCStyU{B{*QCg z3H4>--qEBKW0d@8s<6vztu{88^T&|o<^;pTNrnMJyZ2h{P0bxadAlwzlCnMExm zbhJsZad2zvjrxpGYZ|IMOaDzlVtcs{df7^j+Y~RPv^I72ac%N>t-4q0(=vPAp<*qw zJ&-=`Z~bX9*R1Sz@wA=)Yx`z&w8Bq1dA;iTAs=hc<_|<^B$H9-qNp~2FCv>dm$sDU z<;@08Hhn{-Zv9hxVN?(_PjQp?%}Sos_@Nsa)q$GX`0C;X255!RGCEuEqHp}vPEHdz z(QaXqDJ^YnT_K^egcK#Yv|S9M8t>>>o<-Rj71_!B$*f{hhU;;cdy!)Z4n3#Ruk(D1Lbj_9j%9!L>H zjk(y2MjM>YdsDni&J%4_HeMQ6-l!(DRgBl^<+goMU)9jI8}G(}a=+#?5tkU1&lum^ zV46G4u+^M)HCH`CuD$Mgu{=9zrUj$qxcL!B9}cMmCf2SQmQ=qSvAV~cDJKS?rPmyf zKc4`3!|%(6_La`|b?sU0^X`sUmpK(dM0Y#G)HyLDxf)e$=O4J(ZLx@X`FZ@qC0-L( zRCH~FCY(MDl+KCP9qEl3eZaP4g8ehK{`9t-xeP>vcd|)moH!o;f>SGkwMx|0Dw$=X=?O;luJfiq^UKRu8Vv9c11}9k zUo-13ul;KBs@Y_OLUV887L=KID=bXq><~1Ms(;H!3CJEm3}=RiyogNgjQC1YV{+@J zqiU=2SI0hoEp)%Xh&eix$UOPPa@1Tw4xhEhuXEoqv0Ob0=ww=D`?x+vyktKi z#-Ikv5;!rm|Ep-vGa3e|YZ=yvN)>$^gyqfGUK5mJ6CRoBCt zlcK7iIe#~0axr>xE`e=ItDE9lr^CZ{(Z<9T2v3#Qxerzi-T5%!#Ic0dl9)a+ zi_F3ql%yS0g^UaNfzSQz-M4u&GAZ*eC1Xr{j-`x&`4k<(;CUr!B1J~lUSe)eG{U~u z36w}xIN9(1q=$)i6vC`l-vLGBW=zj%; zIhqVE$QO0!vz5ltGwGtcH~%M@-xbiCSPP%Yhx~P@81ed%ru;sU1d>k+<(jM;hPE`p zP+F*sEc82MaI$=uem#44_pEab!0&#dLl_KHI~=%r2%TVugg})ww;Cd(l6jh5oqF^2 zo?z-!sT2!sj|8Ahs0!*J_&ufWG)+#58PLWcl+!+R*FX` zqu*X2-gsJV%)0wloGTDy_L5S2CN2s{R<`QIo$T3(v;vnK^l%z&$G-Zzbl7jaRq;)k zj7&Q9k`%3Ho{WQ|K3{9y8gWSeEPl8ZWI$Z5?iDmS`-80ftZM5kngGp1v>6_*j4Y+T zF@rzvQS8DH`xMl_L&@_J9uh0o^047`5v#~H|hU9f&-FMuJ%wr0bz?AhbIj`!J&_>U8V z7>Ihe@v^3&mV(72v5<0IQWXBM@NIQdOd@7bRwGaPy|BFWTn}1D*ZQsU^SJ2uFl#^dw0a=6J{$u<-wgp` zmgYndyuIYgzUKAfBVJ-#xtvF514#wfoFRK7I%aE6(1P*^-rgqTn=9}DUWFoQ8~CMV zYPJJLLbuD~%Y=UYvth&hmUFWH{L7;;=Z)Jp%KBaKbL6qVyG zj2aTIVHJPC54-Q?TKF{$HeDLK_D@Qq30l({8HF2fj~bp{oH6%y6H<$=ivg*Y2E1d8 zy->fPy@tTv#6*&J--^)vdGzz0V&}DeL`p$+VTC#To5iF#$E5+5bOTRqklc)&ssP-E zM0lyfgodK;^OdE|<@S-A1+%xAS{Ur_!Ib*T<_t76ao4cRmH@tLHxODXx-gQko08wu z_4HW?zXtV)4cRK=%cv#q2 zn=_lHw85q!>S0(A6-=rp%=3e-s(4UC7-jA*1CuICAub49<1c7BPA^%>|EX`xhEGV4 zOhXmx*HgRaLV@Rc+M{#x*PA~DGPy@OSOyrX^!3}vYp~SVgOl$5!V>xyXn0|boJ#)4qXooIGZoZaqj zLgklgj*4`g;ytMy#f%|-0_;D-aNi;#lA;B6M+$!%q#i|a()74BLG$}DnrWmihW7eh z6%qV4qyqHTZ?SK7EJvaqj1V85iXG9)_a1W){)Z0geQ?rA-OML}e}5Q)JKUz)>jfV% zfBoY3&AOMFV3#i0!0P;SJQTlh_IxtSg#4Z4MACIB#O=QF=^&mQdP$qFZX#{uuf|0+ zKL01)_YcPS_{FZZB^5})g>N~6-5I*GL_kjZ)7#_a{54BU-2M*iqYc}^&X3h=|3Jl# zyQ>+D=id)k@$K#KwL3Eyf`7W7c-9{;Yx_(By*lpBUpT+KJ!c8pG$^Z)*+J}SlswXB zkG7#ZK|F3Y_@YQ)7Cy8Zb}%gW!?kSkFe&?BKK-JeI&+;ymdAqAU}5PX`c0+p`R-ch z`|Qpq?69`rGW$yrFFcdSg~R+M?kN32RtKdwo!n%OwP*I~$1@78%kB-Eg)gI(QC)N5 zJ?Z*JK6b3_uzmXS-ak#s%eHqB=9b|N8^_D-K3q<(x(}`Gd*R}DkUf9q;`ojC6NM+k z{%Uw;-f$VUkyX)|X01aArmL4W+n0^3bM>mygFbFzeNEHEX~drY&lN%TmzS5jr5JMZ z&cx}3wf6OpnAZ<4$CYij>wh+CgN&7{&9n)Vl;}Xg^eTF0`u5J=q%aa)y}!4A9TN3l zXsp!JldbZJ7NCF(`X~uMd~9mn7vzKCrH9MF9AEI{r4QX_XrUCNw`w|qN#eAW9<%%O zG5f0$cPJQBf-%#C4#8riL^p{_)6boK@7*h!J{l=LA~h@obT*iB%%A(&%L$dq&=Z@X zaE&BhDMVN!;i(f!LL-BQ24o-pPiNN=m7UeTod+f{_vK$4U+B7s>I^W*Kl%{o*C_-T zdv<)#uZZx9QC?jrD|Mg(>en3=g+<`r>?+KBo4K3=6vt-GqwLX@y8ZgJ%G3FHVEJ-Jn{Ahu94f3_MPY(fJsUxnN3Zqu ztp4%rn4EOf+hVhapOPYFr74TLO8lT@e)XsFMR1|4EtNWRJ!HPaIxQizD+6{x2Psgo z*%4<>A66C9(ocrB3Exx}`={{C?&0sy4dIFgzI=pz(T!j^mTF^&j7lcQ+E!^6VetxVJa$_BZuW^K-(Kx!^l8SztrgLC9 zeIxAx5>{t35hj5VxIZR%v4sPru!L{;BD~K@cl~D2!%O+Lp}m*V<+}*NgwS*GfFe0i zgf>NU~En?yN@E)l#bsD{FqH+**t1HS**9yb41_eJ4&YsD-j3`%#&ymIO=Rzx7Xkb!lkC(WkK;Xu0mHhAf|YQ%~3VZ zmz*|n;yi6Q0NW3e_)(+zlM)RkbY;qaL{I6uXYn0svsE_%aAxO!5R`3`ZmehUQ1=3+Gu(X0z3pb~-g65Gmm$^C|TOa_<}QO`afChGu%l{_PwJ*r`UL3-y9$qq z?N2*J#NT(k-nf(!l%f0W0QE-CR@?KF(m4ptlX?cX!Szk*l}l|oiHpHBGBb`dD!5c+ zW%z-$>Q+GldhHs_g-y*65++SIKW*fadi=7}LtWIj-NJ~BSqrkmdB=DL8FPIyE~}hv z4%7anVb$o88e_D~a}2f86g2kfYzl6~7i{ui8u8KT@R(|IkJ=9hyz}%V-3?oD(!#ee+} zk06s;7`0-JP1JQ$Og1`Qc4(3O!NQwhc#)sZd*GgyxKSq}w+-K^5O%jIzR7s(fzW>k zas8r8EvY&2JHmT^vtb4gyH#BG>Vl@X((cy$2fnLBtG(H4!!^5S2EA*JX)ipl)|L?8 zJ~@My85l)3e(94BKV}CvGvVyT(a>Ge171-Mbo7bzl%ui_HG{b|CpC%RjQRyo_})G( z_}=n#T=1-|1uh35go(5TbJ-8LQDhI(rSbP@+QDgZnOD-mwGK{NoQnepXAVHNmggV0W9b;V5?ymMQc97&J2bTS4o7+Eby1Tl_@4ZCzebo@)p}iAwlnl zKXqr19S*Pbyx-xERE5r=JEF=v zx~RgI>tun`H_Po>8q5*nk3Cj*1N!I9Jh-^Af}!eT=QqbWB3DDUDvTvdMH$6n)g$*MqA+Bxcm( ztGm75ma$RhI5e5*=RH~}Z_$eu8}9=|L^-qllhUEvuT|m7@m1&OV5(H+M)Q#U%hNPv ze{54oZ)kCx)2v0pVP%dUSRS^Q5HV_nS3v(|FF#xJN1t%HD13SK#pjx1@VVS4qL`j}nUO{}w7 zuiWH>h4{d@{b6{sZ$PWTIn4IB6kiDcjhf4Qp_uMqVa@aGmu2+xzM|llyCyVsft>8( z{3nZflmNB&yA1Dfaxrsg<@9=be;b~d&hvUQ8vs@SW@Gvs^i=(V&ATWMd`L4{g(6Y|rGitR8G3FkX3jX6bkQB;zqjUqIf7?2hE=P3;7` z=C9K@pOc(ioGuXWvbMI{<1NoHel;9pr_e)mZj}17Y4qy?yQv(d)irxHT(M=H_jUSj zP2P^E+zi^5RC3A5?BPp7{%dIk5H-66@d-7TXu7qp6S$zcSd#Pma< z!>m@)w$PQ<9uBsn4|vPY5QBi{XM6F*NOI&wL+9AT+F^}pSARSnCyPA$$1YtJfE9@%NwS~D1j>V zno<;Y!I;#gLR>rwb91fjmH#76MF_`^bH_NnY;qhHZ?F?Fj@*hHyEMVKIn#7PWKhIs z3ioJ#F|^Xqd5C^1u@vI$VHHzEU-_%J*Z6kf1I2qIa}>%ceA0t`Aga5nH!02XGp8$E z|CNLZd>Oi*m$;ozRrm<|9$*70;b3P3acW()R7@N`gy0x+f82zkv@B8ey z+&h=ZoDM8;eAu{HN6HFwy{x&~nE=ROIQ5asm$)JiRSYqs?E~#l1^J<|(3~Q3UW3Zw zy)BHiU3&om3Zt~~;>&D|CmxI1d^@5lIAB}+d_z4(FmryF@kpEfwRK*VE2*ncE42Ry zHLvdmj2g!7BOe@7?L2_i)A zz4uO{_tCo`h~DeyBzlP+q76n5qxTwRh%h61ADtk2yFT~cZ+ZU%&ri=ed+&ADUM~U! zR66LMo#t1w)?-BS(x=EXwY7_ld0R4%87#L>uNzu(hi5fihf6%+VEz*`XPuQLexrDz z7DSpL<x z>t#ai)ZHLQGSTvqp5XxDE+x*zV!ZEru9^KUYl*vIWM5qG2GQ=N>0r%i-Pejk=8N59 z8$>yLMhCUZF;SV8Xz5$I(ne1whypll$E|e7z49%#=fc_To`67RmD9Da^Mis-J!iO* z6~&6QQ|LjJ-y0S2nks8!NH`@KJuw4$yTHjAIY&l*I4MOvmjM3(fHekc?eg*UyfzBJ zYtM)_O*|p8MaLO(VgcK@k>+$g|D$e6yM11>AzPZT-<^ zQ-WW1Jo0qiApIsYO+}sB^Xp{~DSEtippmokeA_BEAM7z9mF*oRIK&ZKj-KbVOM)J4 zR5jx7pV>`ozV$K;XO6kqLjV=V!7_b;I%Ae97w2+2G|4SA>fd zY*}FC^N&PNmwH}n68gUt!RM;l{V&)#zJ>j}(>p3-#1`>TrUGWhMzLFb5PWA|GI_*o zxcN!ymy58DQ^7y=KRE+72%{)Sg9@!{birF5&{;gsSp}fo0lx3cq^2W*=; zk?Ym)8Z|En9oz9wJHSF~tcF44cT;>jjDpd-52ZY;nlH_1YXfp|{W zvnA%$Z;o($SBkpYuT9hA+Jtq@HYiWxN0)UJk;>%JSBJ-0MZaO_LvI#+IQDM&3ppI<4T6i9 zS7*N5)>&JV#lXhKMxRAlv>`(6`}ODSbiMCBOI>O=WU49siZe;!@- zs!dX9<)FWuhUw!_s}i(?jry28a)@n_z0+5+Uq4Q#c&4f7LCJ> zrtGW1fB_82XBYakQE(H!fzNSthav9Wb7v$p$z&_*`QXH|cX)HOc$k^(Ub}UZ+I_XExUZ zd(#eXU5_FnjBC$KH3!RJ5XIZYh0J^j>r7vx!aUobZ5nc-oUtBuwtn6+7bm>c>h{J} zrUE1a`a%SLmnXqK(0gOVW;%T2*7yl2(F3(3?v5q}z6bC%wGiUF^o`Yg@#ra4^Cn7J z^p5MgzGpdToO5AjVrH*3f>WMms%F28t=x(0ds|Gfx(>eHzA!Xr1YJL&QF7~L79QUG}|xfu;P zae)y{FuW*VA(AssBJu)>9&azA$0sAfU3kmh236bfK(VF9glp?^EquWe`MRY_9pHW+ z4>F47K^;lg3Vqtjl5;s79XuDGxbqfIWF%Gkb5G?1q5NFxu4aa0Wr&gFV%bT9ZS)L-?UfWc8K?ba_g`LE-Zz+Eyur>CpL#+)X-rRcs$=o^Pco`dyaD zE_12xuntCmpR5`kaviMBt2kMQB*9s&2X?Xgcz#_kdGHmY7R|wF-SzQ9h61PL*UPObj8jgD74d**H;M80?3f<6^1?WhIbLIr}i2Vw5^mli;B$5JPmgm zIv_(A0>!UdznDw9BtLI<$voI0Mjhy2yu!DSJ)fUvS9?eJS^kwSkowq_?(dDKsF8P& zc~EG#Dq9)2ElBi47g8n}cot#vAr03wnMr6=6$k@D^)YBQoZ|4Zn?#L$@aXx_$uPBR zoEpHN*@hB1d{74%q$MOwIguY~A;U#`lz^Rb zj@a4!9L8v6Jbz6;e1eE5HgX%2M3RPbQknZL9ohn)N|hf)RsbKDJo-9B3FNjm(D^@w z`2K$i@g(eZtJiFEBkutkHtTRqm+<#(8|L&e`rf{`lfyDPptRw;_g7Cxc;bZkfSiFQ zd0pCCbieF8L&7)u^5atOGAd5=>W#VBYJ>44m5_kJ0}!%~ifRQV*r*`DxWgp6FV$*b zpZx6~rVl`X?Tz9AsSVoN)}CKgw^c+Vr_IYbllO|~&_On_4wElbl+vNMn-X;o(XQRv z)_8GWS;`=<0Kr{vC*zY+DL30K9{f$7a=@0KK4ZxC?w#4z@*wYea(*A$y?kXZ%(p&P z?>%Y~jK+r@kZUl&UN-oN0Cdaq_p!&r|7xYG^)niUVfjR}nN&^vCV62kn632qn;*zU zcomh_uX=1G-Ejcd*OQnfiS38}@5b%&&Fhzy3xjn>%OJPKLLXQQ#;<3Z+x~QmYJl$i z$NTx4(Zk)oLX0)ntnTuQoA}VssH_QfZ;3o*z=SvS{_y4$s~~pv@nY6H6v*Y{vRJ!) z!431^nGDt4PY-y4mUPvLuep}9j09oD$_L}XLr?qsI_4jpPdW>A+XK5SZB-3jj24ML z*V*gxte2a{W?0}{KVJNugMa(SQMlu6YaBYN>H$4;yx@(>fMv4|T5Lq3-JEiQeR*KI z;}$Hj{Co_Ud%g4fgK3JKD8TC6zB|TB1_UV!?xv{oLi6Xcj|h{OT)9Y@hkc2sWi6Qn z;W~09w0hLDTRE?*dWn5g!U;TCkC*sZ39_{KovX2aNn|u!98u1&^L_#w<#6L`YUGIt z$}fzVA~XVC>=>9XIvQFG)8W<13djY-Y$^FPS@}3z{BZ01-p~Hw>3;k@Yx`b24dNAU zSf4Bxpk!g_{Ty=gwKZ%rss=J;>coF!KPQYx2O`dM~ z8)eysdjKB~w#UsZ8%}LE9UGYy2S9zg4)DHnq_XIWx=!!(D)%9sE zW*XZcDrVfDXd%Wltr|qVqGb5Qs0+>cHP>6E`GwL`0l6@w+P9w-h8FRdnArB%+=moq zj`Dyk@u*+bhCH)cF9iD;-!ab?)4DE@+DR9DBOhW;Q|ujWv~1?r0|}s5d4>uKy^N>P~^&XVIwH-x+@|Nj~p#4;qZ4C9!%uLXGx1Ic;6P^cP zWO5raBh4@@)rPesr-E%~uY^COfxWyj{4P?&X2v3grbkvk^m0RMGIlCbAX@wW@c!`b zJwf*|z8C0mcm0#cTJ6jzkHTSYb4Td@Uubc|_(lLgU0=;2u`FH3S#HtXr|fAwhtRg` zcGOX-SvUEzXCJxaP)-wi2MXEA1D!)#R@xXH2|#Ce@k4p%kwNdTjxElrbz>oIYC)}M z(B;~JVne$ZZc^SiQ3nnEAg1**OY5U{2v>*GhmLO}gH`cIB6)T>W{C)kpf9*g@>69l zGb`VW-GR)}7}~;i?({fB17xh}=&EmDbTIk>ZEL>+-;%E=5n*b~c(4{&4Sqwyt{DnwiUvorNol0|yh;i6WF?AcR6j~RXRTNiDn=dI7VX7N`HQ_bo%~T@d$v2-n9kPG4`T`1Q-d$`JIYBmdLm;^*RdD@@J8mJi zOx;L#?9;;A6RN|KNt4u17W013l(xFq+->N|>+Tq%ShFp51CJ2^v6s9>s zuWE|-`8)h}&Zy*#KZFIg8O`wDhm-9_hXGOf3g#%UZ2)@P(<61YY1I)+&pm_nAmh1l#F=6DyB3LO0`cs9}=>=a;CU)Gw;E@_;7CbU1>uIH2-v~#Pi1UR_3O(*DnIGh1Z4%)KO^;f)cq`oN7xPwV+%W9;f<&(mT_(P?NMzc+NMI5^ys$`VL{bX_rHn=hL#`QVErNpRfL;v;~;WxaG_wg)#^D9FgkRxP4Lj*rWjUw;6yh+YDtbUL!<Iu!DR! z@inZQTo#ryJ@PlN@!v>QJ08J{-cwY&vF_6Dt)3s*G{+ZMY=Ha6$bl!ti-)=6Vc8Je zp1H1vh{&|YI_H&3v7q}k0T&}%YOme|N-pYdD=03QhjB44DIAE@<#Zp32 z%Cs%36DH8Y9zoKF;tuA@`bw;5-@>FPNrwO5g;Q_b>QJs zzO1G(5U!;;M-?2u|7XoC>iAIJ*>{x zuM?lEFOuh(BxerETt%JTAZH3`FM7Aj?C@NC^=2yxK5$uD39iFSHOKu&!w;sZp52G3S4>G6itG;+}Hh+dIo2@ z5M=d1(IBDX#}D~5b(!O7EO{4vn8>gghIilC4LE9s*#E9UnV&VfoAMB&sPDBgujNrQ z${W&B+8_-^)IYQic1#R5d5O|_S+bZswG>HfkTWw5o2qvfx7@~jWayZ&8Mk#`FP<-+ zOeb1b4jUUjT<|+qbQ?8JRl?5-4~$f+2kkOgR$YO!n7S$qb(6`Ug_8%9IhxK+g&I=$ z?csSLpvMcEuJL)hk>J@Jv1N_Jl;FV1U`v`=EJh0%L(cc6`c!~ zOkj1zc zau!c_me0OTWN(>tF2Vu!>BJ!8^usYFnK>5>+j1?7a_tp|9N1m@+rFb;cI_#4rX73O zpE^J^ax`y?h$CME%)7?iklb~`%a%gU=g7h=E;B`U5md3raJHS@YTi~99W|G${%RK+ z1P?eh8`$L-Iq;bfSBWo^zc4*rQ~+&azB(?h?OSc^O)&}5KQ)5K|22())0((Qjg z$}{`}8?V;^O&TOQ*}=+%F8_C9jaEGlo#+K8ZM7F>3fwBpG#n>-<7=WEnLL31xBZxP z6x(yu;!8|o5Er;3WU&m}MgULUGQgcef!8qdeX7Wn!}UFzzd#C61;FhcjVmo;cwp$W zs9WW01-w>&ZTDz#p7uSI@U<)aB>av^$U7W+=>*#vp)7HY8+SK@D$VqETQ>w$BYT)F z>K9lWGAs)L{1WC<997Z?*R{>V7S!0@@}@?kId0J)S)j-Tqp%JWW@~9pO&Ox4I>RqS z1=)^Z5~zqa(KLM&Hf&XV-`=PIBSgDC;cz9HQXV5lB~XEuoakMeZxD0tD?Mh^B2v@j zHb+Los^h`15(uy^@g4IEbaZ-uY(8GYKl|G(in%$JIL7Bo} zRwRA|BhE{{@9nO&%pRT%5CaJ0#%3B`JR|s-F-)~qk&rGdwi1vLubMKeXpd4cn_GTvDYB2KilNbr@gKOrLkz^xk?IYn8bzM0Wi|#W#Z)F_N)r z$D{aP9+o7Lg(MI4N%~Vm(8iMZg3QTD&cfhZ-@-h(GR#wI22&u8j1UupNtX|L8IJWP zmUsKsA0rDgw@)cisIC+wJ&lvL*&xZ;3%~NLUeqT*Gi{(p5rQg3+T`UIdszMtQ+S)B zqQOzUDn|2Kh*h4;&I8cZ0%!_QZ&4GW@16^OpDc4%dbD#F`~Kj3$KA~#c1rp&Gl$;_ z)gWV3cObz3bSvErbRiOYXCE@le5?#H9^utYgC2&@F-%>(Jv=!fnvUP*898(BX_G<7 zxzLi=khtW!W22Lvf%{=Eno@l$$`57=&DOZaZX~0Q?@tQ_1vTW|Rfh~&*~d;xC2xI0 zLqm5SqW!9|%K!!S_75*xnUz6_ zqTiUimy;a)%j>i6Ca+KlbD3XE@85r-V4>5mxuQ9I>KeLxx_e(3Do8QGe{Q&9JaPF3 z8{QzhF0VLCD3BhO@NE4Ch@5*6I4p8c9Ie6V+@NfCL32NXPY zU2F@_7HRI&J;*q4l47ksS-9Z+#x-Z|SALS7S2Nedhqw&e!-Br`BKs1CaWh zoA?MN*w#LadqL;5E;i}(d|G;rHjKYKg$$t0pB<_$^i^@`c(aNXt?bFTU)U!0lLE-S zsI@$63UrO|(%G|ZNleehw-gccgthSm1C5q8HbJLYT(QTfg*IP!mKo-x}A+$^__F$FgCj5e&=@b7L)Kfd!wo9 z)U;>&5q}WM_&8=y`$3?B=u{L5JE1^F$Dy*RzI|%AV(!W;GYnkmK-_k_iIlf#2yu&`rL_czH_kv93nqJ#-6-_yCO^%=do8Cz zUbvl%$!Zi0g1I3GK zhbioqRFxzA=EjvplRWDxDRxBZYN1x}dtcctBi9yz%*}Q3YUn?#y1TjMhf^$>Y6}&A z+Q;>t`@(17;;xz?)%-|M;hn_EJp%M^J^9HSbl2ec#wN^Gya{RGk(VXrBPG!D1-*;2 z;dbxp@ng%P0+dwJEmwTW?16rVQoeJkGpH?q{BKp&RZ<5igtO(&#N?co)HriN9+wBOD)Kyg&eqO?Pj$LJUxBt7JKS&y!dVr^7MUZd5Tb6z=tA}Ta&`Q`K@ArZ(hWE zKl97Fhw+1e0lWDsDBM4wJlM71k%Kwy5A`Q&EUPK$n;G35>vP0D_rS$#f`4Z%LRWS- z7;=e+%Ar1HV9O;`-ghO!k#pnnscnfnYcv4^u=pIfYs)iytn6wm5jtTlg#$K7c0 z(}&4tdTA_Z=eYj z#B!U@xLnVL8>o4IrUdJt?%#v)7p*LLfYJuVRofDk0L1}N{BT^)#f0m{6*i$aF~U|< zeLH2bH~X~$%}yD(x5uX-YIL@|Ot@Z2)MK29P@sebp`68r+WvW2ngV=#Mome9@zd`O zF&@$R?@P51#~;_*gY><1nOyu4MX$4`KMDNn=`k)UE;28uyW?(y<}HWjm~yqhy+bUx zisWpb1;b53?zbSqtFH7oB<_tF;yas7oex$5|3-1bvLI#K z=SNNjvdFU<{27~Un&;b5fNS*-C2 zp%R1?GFI#hPAyEpV(Ex7a2A0wrL7Xk>s?V9Te0RHLkG@&0tLD1tygGj&Iz}wqL9*oCuv_9wqnM(iUfQaYU0F z)I1!3(Rth`OSvmc>iFYrA2Mj0jO*q?7HE=20*-Ci%cMb$@8nBh&-CYAd#UyG67GT^BLpw^O&GX&b&j_6k0QPm83nTJal_a} ziJ(_wr~Q9<0kAZj8Hup*Np9no8$urrdgiwv^ZKo**lWL3$OrYKQ6h0P;*Zazg;IZF z6Q=zZ+~HJ*nKRbw3pLumYwD)TS{6KV`^BhSsEbR+?`Z3QncYgKq%+XawA-%va3jiT z0xt*qSQK#i($0lWrrvLJ4e~N?#B#Z3 zNUqQLkL2S}!f8K_cm5j)(~2*~4r^O}i!`s%W>hx**KE!0B6P{bL#)Ku&!#0)DXLrA zn_B$Y7FPw0;m0d~jHPeT3Z;vKomI3D+sQe|vY=G+gKaV+J?bZZS3JIy#-kAYL5=S= zya|)>B6A1JaF)gR_k%nRCr+@ImQ@Chs#Aiv3dBU3V4mZqW^o_25J*%;BID*|70*Lo z-j}@@c8>nw;3D76+4luI?SHuQa>1pj9BkHD&$~R zf`i$p0;mQG5)DdT-(KZlX9JOThbO3f9J@X0PXf^~8G8!+3S1Uoh_d=Ximk|| zO6cpy+g6l0#^a@7X8KwzMtUqiR@#IE|D~MK2mL&!#BdaJI(rntD04~@3}R;Na8w*I zxn)z9Pv#SCnj@UydW2;Aw#4AhjM{j*Kh`2uuV2z6d(92GQb_hLMNyy}YDWn0@yXJi zQiwBC5j0ZTV51MR+9UYfggIQCj-NdfAzcxX^75)Wgf`einYuNz?_3oURIP0E4E30A z)vNx8`}@CI5SCEt3&g?tV7Xzs#8ii2R)q7-zUAsCL-Sn{)X3g`7uR#$=n~&JV(4oW zRoPjUh08x&Wn5fUL9D3XPuk0;TnSWGL!fAmrZOlxz|D@D5s){?sR~iF`?x$ zPmisSejT$tnKVwm9g7+yv>`c}H{AKZ-7hw7v_SVIFy9$GZtIZ7yT3y)EM;we7yR!+ zjaG7~Y+r{J7XY=gu0z$}DZ;J+DARe z^Hr|V7MdrwQ&rYf`G;Gg*D9KbXrM}j&`AJ@)r;!!+oW(sQd(y5_Y1UiLJgc(71)KE zbSpyv$AfSO=aq-XfpE8k*WE?c$EYSfOA9_M4acG6C0Ql${|tpDd)N<)EsbZdV;F); zA`bk659@OZoTKyX&y@2s`t;3Q3_Q5ObnCnA+1$_W?0=On_lHxf13TYLc6i0Yz5$~~ zQzHJ^R%^twW9=z?fRnfAIWNp+ml+6Dtp;Dcw14ag{kxu$hC_4?dK6iicMatKwSl+W zF^m1tRh}*yn6Vn{eR_ZD`sTHwRB~ewic>zbLav6VP#n2gn!x|ty-#*SPhqga|UWOv>&(g%F(Oh|Ko!tG- zSq~~(T;%a_8zj!#Ty&CYjxyP(Zn#KoAs1m#1(t@*bS_fMrwmjZip+@m9>8hoD2!(e zI`#DgccM+%yrzqi6=>v0(L@xy&xi3D)@QHy{tDU=y8@M35lD;>a+?%K?it<5NdvYr z3L69`Cw`o}st)j5HpTOLjL;CEm3@G&Kjh1duJZF9W%!am^!0~z8v`{p9f+e<8f~q8 zYV@z42^xwWe7v&9A;i|I{Uc^Um}=;B=*%|sP2gwO*OI>4%mO8b3Lx1?Zw#ywA*2^+ z;8Oo}j5lhL8)-Xa?&s!~g)JgqDR-(bhnemiN0 zte1fZ0}*Nz(^zHD!T)I!K3fL$TtI5=5pBF-t2YFbJSP`bK%Opid2UK$T|!aMM#Le~ zS9pkBg@-Q5ak1S@E%Ml(z4nE{9Mg{E&ZdT#nbyvtfA=2plUI1|Zz-+dE&Dja5inyT<(b_vKtSeY$B z71(jt?FAaX{%AqvnsmyE0fzpK&vSeI?{RzX*)MqQ@N`?)zLWRRpPJRyd2#96xkTF_ zq1fMWJlSzE*K<=C{P&SS`f&{l#RY~lEgFN_(e+3>+=Fr3G`ytV^YH%ZgNRJ*JHf*@ zZ)+RyJqq4F%|Bfw_gpTX!~}ILbdqj|uhA-yGiF15a;y7@;!2#kGMB%2;2tXZ#a2!F zHf;d-)fo>~LaPoRsWQn^&<$kOR7lka8&fxT%PM_1S#Kpl^y?3>OB4Z`WG#!O`$8dY z_wMf7717YigyfDBuTP6G_YyB6rtG+E^w&M|_w&ANk4>0rL|(qm;-tps`!{H{9gB9g zYR)h&FkudGmNr!-jv8}gY;5M=Mwi|FaDY}9AcUOs*k7Ec@U8C?v#HqXV*Vy%5 z+I;oiku-%QPr~-EmB!BZa6&QP6sBgMI0?52M+tDBN?aylaDHN$7p(m{M~cmo{OOVh-ys$d*}><5u>Y9laL{;u0gDyy=)2~^cdMBz ze8%`0PRd-l51?$8_=teDLjBEMnGYnQ!oc>&Nth%^6iJRtX!qd?e=h|tr{6Oz1k!q3 zeWTV=#@qJ+VEZuU(&cFlI#?f|8(bVfmABSn06WeffgK@>E`?qlD_T6R<$lM7E+U(- z$G_*vg+L)38`lwq?iFe^=fy@kaxN%PLBP3oq8hSENMq(|`{K^FyFGVuq~YMVq*m&K zD0O)yca7QV^K5;R>{a>4bvXVUiVlH7grc_%I$NiF^W$H)bBC-?cX4BgPFOPEOSc6q zlplKr8Jx+l80)!Y>L&1Yo+E}lOlBp09(Zfhi$5Q>;_DU~m0LjC^2u(h%2`}u}C zIe}1wJ#%bjHSK`Y#~87e2RbZ3!i6uob^FTl#7ir3@}0qqwJArpgp~l{K};5{lHDR$ zI=(qo;Fhk~j~uQxSA&N%FXt5{kM~{_zo-D{e@>D$tDRpFsU`_?VQzq4R^`f4=8?|Puw&>z0W?0{81(uugGoVOI%;cAtf6k!Y4BfS5X z(=JlT4IxTdCeRFDv!oU=OdLM$n(n7l-J~yJi%L2GD+;C>Kpy}_I~P@%I_i#GMCL<3-iO~pQywD1W(4oU0dEOPf_Rb&Ri6zX3mqJWm!20yz$I+a6H$P@k2GV8Mm z=7~>3#mCF;{5`(Tq)6{0lZ^!L+iTb;t6=w!WCV@DQZd;y7z8FLMbRhwl4i6J4~zC> zh6Lb)lZNlcFTbMFows)UEayS zVrg`)@BL4qdzW`g4j%H602r|9@Ji;HRQP!hui;j;io0X^G5I+LtsYaAmW6CEX&S=? zbK|ckhJ|;HU*kvImng{nwV(OfKLUij0KbP^7ZZ|3u11bU!lpvN|Gr2!Ui}s5z?Ufr z3Gax?0<~)rxp8X+&wO~WOMU<|KBwoA)D1ZI9@iTR2s~t+JP^G=$gOmLa;Vbf!nR7i z-yLZd6le$=?B|a9dNrA7o%(Fw{ea}AVq@Gum|#TcL~H$x>xE)qE~S*xwC9k8`Hk~a zk&9Ftl#oQthf~m}w+BvY^dcuGU^TG$x-l7$Z_ue2y1Zla2X**k3ytLCZ~)K4`FL02 zQX~xBHEz9vwWvnnJ=?JfIQ`@(9sI^%^^uG5QW zNI2B&4O%4$eOuQu&%6yefYZz8yTQS&cR91|v-b?}Y~XT5B&yK=55L}=+~$SJn}}>j z3(uP73}Fo~!q3EtyTKAM6cc$SUjBMD@iyT?HE?;{3G7s*?_V5^vxkbHx%IiG7B9q9 zYwb1BMJ#JNYU5`zPSPF%k3^sajNUGxTgFC&44?}$&eUB_ zTtb?O{v6{P;`QYtx3?jRDcOQdN9shra$ZuN&ryOkIet04FslWOh_#4=Nks$6ZEI_U z>^2yG?3b_@yJl_rCs48IQ7|b9Wyxay{Gk3$ZWh+0ghNajCu`$c1I>>Yu7M-l!W_Ha zy1Fguvg44XLwxu?H_6Xle2xRcRlP)jLa|lC5_>iO_hiy_Iv4m-PQ;u_To5`?R8TG# zpT-a)`n5Vy2uaw_Pfoh{2@_`{Ja5fIa;Zhbr3SG-2{rH);1>o^re`?CMoQh4E&+cQ z){p=MH8}F!bkUFogj<{dIe7x1+IXo&OP&D9lgUy7m=H}3uyLOK4Y4!rIKKO8*;Jh_ zg(&l9>v#gOEQuq%v01F9N#pO}uf**?6Y{Ibg?O*R(fZ2N=sF^_P1Sz; zD7vB?ac>W^@lhGPiLTH1UHtK8t3K$YHQDa*`s~~4xxW;JiGTXCv*jk7^09RyB$@&~q?jTQ zg9;^`q|wat@8niMOMaHV(aT(&o85aG72ooc9}IuIAAj%1>1F-XI4eVY|7iV2>-V+0 zXvdZPgyU%J!GK>EOy2RGBRnEJzMq1ZEG9A{%4pd&}<3_xeVI-xFXA`w4U^n zZVpUsQtWvn^g7-0zKsO@OMb`)b`?u68Ixk-GN>HRuM@90naaotbVJx;T&nXG2}Va! zbP-0<*SEerM!Wi7B8;N@OusF`WiY$$nuMss) zZeqe3VA8NDSao~j`>I4;&GE_2Jnz+L3Sq7HTxdAl` zPE5&al{J;) zN27KeKaW_;nALhp%%87D@sPGiJmj(Bge-P=4wXGV8GirltU0g7vpMlUC;tD{BHSJy zADUhRYaE>gz_#mQf3p-)m2-5OC1bP2hd$OY>IlD?#5>@7JbZYq;YQ&9Put4hQ|LjW=K(P= zRk+-31m5JQZyLqzHt?kwEU6tLQ02+RMS4RH>7#yr7f9&rE6#2* z>P+}%#F7mo@2c4j6d@XCR{DrR7bEIztz2o8=k(2M-b%T1qk?{{7Wg%6}FlruetODzt?ei25V z)InYr%r}f}V=ozUHr=Ihh2B;%A@Sy2+f!RBWqaeR#SdDc*QX_Qoy$LMIpxzzbmFRo zz6knQL)4syK4d^%z3PCN^b#kZ3kGJT6THn>_?=K3*TB)U~bhy2+pOm2`%J3unXO%i`V|hPKQ1Haba}?>&Qb~bp z3G(haVR$3tz|s8d$rBMU86-)OZ7SBMujCqGH#Zt8N~K12_N<7wyjw|hyl8WAul?oB zf%v3^au_cfp!fZxBo&KXbo=+M%X7qN&y)`hvSF!AEHFPAsrhu9zPt8@sob~{)WWL?VC&1Lt{t6 z*T$lk(B^mABjV_clsv;Xf%BmIe(t&8HerDV`y^e@tyYWZr^Bj~;PcUV(7(-*FgiZm zpRc}!-IV2nj9GY;Wzl}n?Sn_UyYh|h7Xt5>AA?DBRZ+qSdoKPyx6&G!X3crC`sG8J zkUQI(eex55&As>#--8a>gymxj#UHnU5}5{xC`j5g#iSzDv zHEMu(#0t*mq0*`w$fLjobKFG}uA%F-6{Ne-WtmivZ&3I0C&SIOtW6L0HdmfW-IVSF zS3e2AQi|rP_1jDL+5TQ9sX>YZW2qHNGZWXTWHnMSp+d@qD6YbYJQUhNyE$afs#LzD zT6w&ypHv%0D~dzJ$1y_NNrz@B)z#&dKz>jIMc~NC(b~xCDd{-}b{m`L*G#r-Uhvo0 zWy|O6t5d-_iA4T*b5b$B^Zn!Vt<>Y^@3ZA@+_tuc(A~8-x{umkpM)90mYQhpLI)q+ z%{-5Ecjc{snvUWV<}|>>=o7MFeIX%{mYMngzS>3{l&zRp;#M_IFM~rWpVi~bz95nF z8hmHR-VRIY#ZMix(WHZU`puQB;LSKv3J+|RC=v%ZnrPHta7*9)Jw*r9A%3((NEcc94X_V$FCP-P{6HjNB_(1IzGsMa_fVT8Zqv8h zCauUAiwRX`{P@B}L&BT!L%|!ulQWs!?8{me^U+(n7pxd^5&du>LqSg;JkCjrWk!Ab zx>~=;oMTofC81K&3~R$dv}@tgie%^|j^uWP0E~#7Oi;b+E@huzQWlQkN){v z0Y$HXKx?>h3cjE_M+9J*`|aod>-eiH+lDd4LqN(O~rH`Gy&m5RFq4wf>GB*i^{;rs*)Rd9}~*Foyy!|`(^Azx@>=;SlTcC z@V#p}b&Wmy-wWZta+l}d6qlI^HEN2A2jW2dN`k8=r8=XPHJn#a+x z^=m)O>PQBPN-y$-PZhZ>4reR1Dk2_TsTEF<1$+=_+$>O7d!;b!^)`CZ;#E00d;fvvg@z{mOcZn-mKY_Q6QGxIgC%a~t> z#epxyFgITUI^XBx>82HER!*RR8?^1sfawg_73Qz*>Z)N&v($-j$|LJVIUGK(t=wy- z(Iq7kJNP^Rd0;5($R>*NxMB)+B8%EnWF60+0c@TP4?mzo4j`2hF%5_!4$+)1x zUdRpt0-7YRq95L6;$pdwNjwuMcUeUlsj`tBj#vy^F~rd}EL!gifTs-cTNQ3M$@tp` zMcqCwT+JeGCQx~dcIM_!_9(S0g6h~cNq0Z(V9#vr{}xQWIxd_<`IOd`!>9=C{PYT? z3k$k`;qlV^b2lyQ%9i~@%t91*K?-RqgMVls__6=FmvC&<+tFmdUR9kg%k$~zTy5=c zH6(`iW4oMe{}L&Wd%Dju9pgMXz`ymYK@)Z$8IF$VaDm7t7bj$ynl(=1XSGT~d!!7N
*bt#{&&vY*_oaFu)802cAojY&-;jOWPdx| zLK(S-mJ_~=Sz@Bt03A3d1`Unps))AvQ^{^bg@yqoiZK~Qz6a3@(It})Fan9|U!)G- zt7&0mo#*t=K1t;3j1~voRDDr{=OQkq`c?xzOP>4N)9%3f&iheV*PdK)O2ySvIJMiB z9}JK(I8Y0s^vGd;J5_C8+E%L@fo^X8x)x0?Dv2oudlGm&%}!r;MM(HYOlvX*Rk@%{ z+d;L5&Ox=Jf`*NXo)<8Z6`6vevhT_eViuHBa#h6_A&AfV$-^sY-W`jk5F6E?Gub4R z$=60R8nULH^c)&8xV_WmZ}StsUA?;I(IshrU?uuf5~>+fx|HmGe1=CI*X(Xm6}0}1 zUSPV+Hz~q9!mu9%L*y1(Z`ZjnypuK9mAts2#L;q86LK!Prh%7lPsYlsVLAqlDGy-2 zp2w-?#~R7U3CRbSr|hS7oMZ7@c2dT!Q=dHui|7QhIrx0C#H#G%u79-QE7v(~Gp_uq zJgJ*+1*dHLJD~O}G6y2*8M619)m0ooScOS+xdA}V*Qj`>)_fLk@k>aXk52CIw_~9P z%O`K{am&72%}p(cGQLk6_AofphE;fqI70)UHvD~z(xg!O|IPfsMn$*Bj1tTsdi(QJ zOS5rm5tr9Ovcw_dg*dl6>2;y9&vBVZ%qLU^Mchs;_6^4Oo^C!l=05EDywqu4&1#{{ zQC742e_gezh5G=)L>Wfd($?U-!-K2pUuc(6d8>|b6wb1Yg-OB&< zA1y#cKs99PHCJuhpDesU;>hzuXZtRLn%k~0Lu_b$Ico@ca(Nr%u{N>D!JH(_^_|X+ zIBjXpZ40GnVrPqJnq{YjjN!!LavS~vA;RgvP7RiR;S>wrSu3uhPaTA)i16!bK-%mo%Kp1kF)+uIS$hv%~vv!@0c1V^M+1%f}_w-Wg}0gFTm^ z&8pcsUfu*_huPOowpH_Pzr5R7qkGoPumJ4)R%Jr%H~$~&*}VKL%y`_Gq%r)oL$=H< zkpb_t=RY%STku(K0@vins*6WMv~Vq2DEk+PzAE-m?#m(p0@hKh z+Tv|!mc&sGvZ0!^`3LjN~)lN9rxXo>M{D3PBhnp>y>NT^D0b6uXDi>8vRO9xC! z@tipcoATYv6FNT46eQ5YuLAlYtLYu}wA=Nn`mcLqhH6O#CgfGbxLD`B%+lTQO4>Tb z=FU(Lbv(ZL>K16Prn;JI+&=WINuWMSuD5BJZi zu|<#*wt34FiP6K>(6J=@KmNb<740L0^d+>9Elt8t>#$>1`royY=#<(Q^T;8s)7d7; zZYpWrY-)$STfz!k?=Fn&W|DXL_6L-&t_x{_cBC3FK4)gZEjevZ2+{DBt8-aA(O+^1 z2*ryJ0EE&I9dD{7zWR#^m0wQ4R^ZSfuKDJsf{7d0vwdD^yE^i^#w`tF zqQ4k!>g{>o>iBPe@Ome7RYl;dVvP=s6$bfY&?3(YtJ`l$y^0Wgs#}hOFMYB1W&l>-DYA3{K>4l zxYIkXg=DbZXQORrTYN4+%> z3_HZ5hgOu1vE&^Z*8Yni6u#7~_$VmkDhnu;P*`VL)Ev(mB%~GJ<>rEYXT~;h6aP}p z(}zm3$Dl~8?QVZ!VW7(B`Lm-JmzqA7zHhCV5Xc@*7%d|IQe`2Ft(B}XlIz8V%={V$ z1092c5c6l21s`KG`r1%_9@l&g*Q8_sObX`p0)y0v?yB!A=t*0WNrJKPec4QS7dnL)uZu zT#dSWK0H@p7@K>){f2)2HTC*d)NM!f){U2B&mbVSD}ciLNdq1wyPgw2Bp=?EL-$K3 zwHVe=J!a=rHTMY(M{|Sm`Pku(1}CFRc~$D% z3kJK~(R=T>Xlr)f8gLbgG{sDLwg6TNi5V~(RQ_A$!u4u!7IL+7vu=Bb;h<36l(s?n z$C~@eXB1>P#_hP2*6&r9#qA#lKey8cULVd2oWPpof&(jpEiI89987ABoP*lf;MW?U z6h1!5aS!{Lh>XqI*a;;8g@}MS>OUHphL$Wk1^X+7(WMgECzXtSF?e#W zlSzDIw$_f+cB((sR<8UMox&<7{Xiq4@06pHm|egB`Qx0^SBA0n6~9lw{W+Z!P&eaU z>>2ps5zhRyZXP)XrOPBak)jK4>66tDpjVKS8xZF%rkE2b!_E$+cBKBRf&Vh;F-z9qVyU~1$QD1pPonW()cbt9TN*HtG=8$8r~vtjj7+kqbm&KRP9 zb0=<>WwZpYeYL=wNFuI=vwI3Uk+npaEvsypnSF2--by}h2JZ6zmBZ;n0W@7S)DHT#44HP5e7=A;S zoxPIwR*GfUxk;*FMUul%*E~|OB{gtwX2ee&6wd|TUEeHqh-kElQvkZ`=WG_b3smpd zJoN9-#nVS;Q%N$JSfX*zlw8fMi0EV(vOdNF$AQST>bIgRlboC)2mh?lGz%f?xn3kV z$vnJoWOKpBsN-}xnt~Un^McqAyGXxoMMyy!@+{aXe)DSwTK;H$M-%;6olpbOW{4Zi z*wjIO@!Y$6?yF?nqOr%T3tjd!fw;0s)-?hG&zcgdMRQLU!>fUs1^e; zd7siBg%2D}lz=ESI_vB=GU9&nOx8z(s8#ZbJHj+sjT_eM>kw_}*S+Q%AJz8%47=+J zOR0cmqWkJM*DIc|Bj*D_`=PVhQI~J8Qr|Rg#PxPo^lY@5nvn6a{N1FJze3pmusn)b zpG5<}C)KAFaYugDPU08-Y|O-ak3Y}iT)M3)d8mChpGmHas9&!hDtsd`uBNbANqDOf*AhQ(;(Z;ok zx&BfFpd;5ZSwkB2ThaXjF=12rlnSuAxbGm~UDa02tx386@Z3vLr1iNM2nUa57E*bu zW@0XruF3@JDKM{wr>_j|aKC-ojUzQRbi%1x`WeSWIOX{Q3D7&%FFpB|_A(_VnsqAp z#&GrF1O$7!I$EBh!X@kZ3{J)->H$R5zIGv+nW$2jASA%vfGb#H2%18OR8wJ(kPcX4^n08VKYprDl7&)`v^wGz}@Op~8SK_oLie?-EE1?h( z^)5pj8xOGzDzY&-XTwK+*9obqpuS`vI+oGHejxBA4cEy<5Z6BmTKdUEi4!{Iau z)|^*>ae!2K%sYlkbRrCfjY^4JV`CbktE;H)=S{w2wF((Jjdd%aAt;+=6P#R?DZd8d zUU^t!sYw{JTD*E-769Gdq0tEmZI1200P^U3jZo*~_*v?Zc9&ZdXTh+XRDteJF-p1~ zO+%&IEqlJpWm8x&_y2;46CbUmTPxwy`K#L*n|G_Ydlx&9{*}jFg6H`RR$czwE^wR7 z;hqJ}dz=jlZbq1LkEI4)PwCVck?nBeACzZCV8f*3fpV$ojlK<6lJkM5AlXRq;CfE5 z;T%D*XRt@A&>I9+j#^Lj5jHv9<@`Z^(PS)iN!+Le*fuLwk%PEX6W6jiK;GSKHNSl;6B#faZS0!iE=Td8?{bV8)?7lXMS3 z_uR3GQJhN6j(pN<2Zt97qij&e3)H^EBr7M>xXu1-TK6l3WPBWwCJq`84MO4YK_E6H zzpUNQyQR}7KL?25o6Fuj_hz75WB4I8J>wKW9pkLY2OCGpH_)wWT55#yc8@MH-sok` zz>1IW!4s7(*G&vGcde0i!KeF!SKY-XC#89fET)gwM+r|~K=U2f3;h>D>4T>g7B#ew zH+hd+EWzicE+z-sHRTtJ4SU;r-spqo#&W)yFsfS0s+8lWFcac5$_IOyIXi|S*_nnh zLmnL^X{Idpj;7CN7qP$iQmbE%m>ch8yc$Uzmc#cpFb91k48iRdb;EWmdi+z$qOd;u z)~Btd7=J%=4O(R+Fjr<@v63ykk(kv>{t1u1zSf~GXL`2r5m`$6l)N3b`ZP5eiGd!@ z(@UiB*LPMj;Aup2UmFb9wW)B$NSWd2*+L2U^HE~rm=v2s93_PI^6t@}T!*^r<6d;@ zz-XFi=jZ+U48xcfwFgJ1_5+%W%3pN=VVq6CX7}y&Z1CBZmEoc%+koR*g*i{GroBN$ zlzOQqUSN8)cOa`1rxV-7Nb=_lWlo!-WT8dc^lfc})3X~dgr~^@(1~hVcq?c)4yWCy z^OM0@eYLR#iNs-P@l3zlG-K5~(EW*ct_`Lw(UkEnKIde<@h z*R}*oj#D+Zk~We(tBDI(5@4}z0kwzCFQf1vH{SuQeQaDk!tQKbXdbVJOg{vTC1Law zREq6p2L_&=Bfgf>e!U&!UXeJ=N7msg|B9s^eF;d+d)!#>cyLRBHQz}-Cg)KD#+`(A zYpJ`RIp4OMm>!{JO&^E1MHa-0{ciMP`CjkHO!WxDw*gWlu zD#1sz${GLW8pys2!c9CayYy@W2!Mn;<)se_zL4y0EJ{1l6)eJ8Lm2$d(dF+BYCMQK z?9o&rpq3jV8+pZu6XsAMqg@_&3u#`t?97>Y=G`t?_F)N5QS@rE&&iXIcSEjF( zN9LSM+r>?FT7DN3V|6k8HDC}o z`poWZi_q1<*}?F8@58R(Z?#vt4nzQt<`G)oQ%Hk`J~5Vh*2<=XXX7`FOf8mrL=LhO`j1uJ3_%=aFr6kO8LuKtd%w8Cm% zYYPyb7Qtc$-oB%k`SFt}bYsrm`Y49Xf&RDRl1Atj(Q9-F)#NRrWgOSr1D{+)>_}*& zAECs41zOd`u8@r|6b1-u5A<1f_lft&)F-hUDK?kOs10Zc_#~6-yeYu0LG+1$bnr3U zRs(mouQ%`Z^pal<=AW&8JzM{%C*)P{2fURK@*(=kI9AW7!{-9V9^Y83>t4V$1rtCW zIh~r{fXgYo!@}jm3_NrvIyKbgI)KYR{HSi7)Aw75qf^c!H_eJ0mh%sQ>ZMi&-^;@> za6Xy=p>^ymti@k#kM~?)BDp{gnn8+9cL);+$W2@%M>H@zFkI1Nj{)!~!xFwdo}s zYkm-p&sNc=4EM+S9ilJi=kP51F}Fjycn{g87oxe|Qr-%Jg- z^KW88o9NDRGC;u`Ux&NpEZ_?R#LR}@lcBxt;Tc_+@YYNjM4^H=y?LF8R8bip77|a# z3`fzw=OF>u;2n%NG%ZHW13Losd4zCpTc~aMf}2fIQl`0V(Ejg&=D$}q_r_!`G}~1V zHp)k?50&w3$QMzl`Rlo;mv>LA2MJwX7n_pZ{Zjy`P>k&rULcW*@`13OfE(|bLY)#? zD2bwhL8QsQliBQxivvwk*gtbnm;fQewDB?6*vzz9kDku~M3v=(sj*kCagoHiO}XTZ15s`8pv=^4e55qUf9KO5|+(dX-VSU4jw zIS|;#oLIf{xxXVQa!|bU<&?fL*7YpehyTGeBF;`qUyE|qZ5A&u}DTK#3t|Yw3}n4^Kl=X5L_Q+f%z*TM23pthgKQT#UHepFGph*DK#v}^!8Dv_*3{~sC!{#%oWM^ zvvn~`3jDU+zd(Y|f_-Rfqv-}2~0SFW&}2s${Y zKfH0!`o&ArrI+*(+?pQIxs|=b*ZO*1#2zD#6`aL~-Y~HJ+hhHqd^=-;*%}eh#~1H9 zSZId(--giH6Mb>zBjxS0D;vO;nbv0L`$7EKirEEwlTd?$hHb=aUAO9-k!fnUkFIk4 z$6hV7CV@?4KZUsXUbDJ_^-FhqnyO3zOfruV+>bqPrD&W9EpUVj$>IR)ObSxiyLf*^ z>sa79jHMZ6Evf9#Fo7QWv%KK5!=XE?QumXWJULHy$6pTy5kMIP?8DliEH*mnIwRY7 zqo9smaq;i$0HrB4`X8tnZpxXKq0La#HS+NRUZWAajb3==V8KP_>`5^Lmu7Z znROZEw}h*B<7u?^uJ~oq*gk3FY|6Cr;T^r9fDTdGL)ZJ-y>UE#D!oq*&vS+!Tn5~c$$D;G!!F?`fXjXjw3W$$F$#R2-lS3p?nd|*eC5+QKs~=BS4r2e_NQd zyJa;mA?DP7cZiF%|0ajx!K#K-vfOwF2NMm9Z`(d}3`DP`c9nXwu!%<{(eFy*lEK72 zIaCvjo`I6{YFror1EG6oxB;pKQum{@FkEwVas9o$r~zM4YB^NHxz`8&hwJz+Xn3SK zdFR6E5~#$ExR7?Uor{xNHLsKH?=MAiOXQ*)`p-M@e95#CUrNb3%*1gB~epvKIjSAeUi3CSUHWAJ#HbTNO}mvL)c znDhRX7oAlI9BA=re$bmTOd+O709;tqqfsGJt6HCt>IxZt8Aa~M84+=z7}c(XXy197 ze^`|465GuS4iXchrNoT*&Y|@|WCE;Te0>^zK+S$?4f#9-5)c+0sm+Ibv9dNqlpYKy zsMtvt_3UZ1SQ0k;CJEtf&2z`4pH|MYY@x9O_WT$$yx6YA7YY>e-nVVSgoqi65``fD z-4P$v>RxLq?eiH*=Qb_BqqmL3j;(#ocehbh(~2R!)JXF{r+T&BFmdo_%1co(>sB_U zZLTN9fY~6;Yg=HyKgpo*qf;alib`UvY&irsTr7Zin~t@+KUo{RQ1|&ztz9qS_g+a8 zplWNoFut<#wAlZ+8hpLq-L=p`#~{w8CAUhI{t2CqVWM8o;ix9)64HGSS|z!Htfb;Z zZrYfx1bN*dZen+iJHMXBVekgZZk^fvTKRekp`J!z!nsn^v=&YiApO-W$9+XmQ}c^q zhvuFAWb@fM<%-xVbVFbtcO5=3c*x>6W zO2&ZSOBe-$w3sGpARcJ3(sc1$+f4egF=*Jl+QG|a<%eBx#;x3@wZ0+APhHuRM8_tt zu13FQhm(torgk`_gmIGf>r0RnA}fPy3$aeARPxJv2?bx@q(M^ZT5keP>=JRgw)G%C-rmKh>(@EU%EJ;vF{@em7H1 z0Y4RI@f5e_{7AZi0mKDPMFR?E%<**c<1O7{UP+ZQ$@W8H!zfK-^+zBc97#CQtK_#` zm(D)}023TiGw|bXe|O{;$T$juxTaCSArP8Ve`0XDk&ySnP6!rqCA-QLbn6+AljZHd zY-4UsXTw^II*0dwGKWXrByy#g0bYQ8%R*F(y1;@4|j2e6wt&yP~w;A5vDH^_=!V zg&vaWE7GWW(Eo7m$`SU`%mZb#hUTs%E!!B8%#nOIm}mGOEr20h0_|J2jW1WL4tuOs zbnOc>oZEv2RliiI6ESb-jdyTcu)b^0;={{)%V&C=+1gqMFC^l3=}S`P8ru=kRMJAO zk9ksb=3Iadowrh=itFGG3RaB|)2PZh%c>gX*?u@Zs=7xh#KkxK4y0e)6#c2t03rzJm7{8boiYWga$ocuJ-SXY@(SN;3f`M z>2dG@8%Iuh$JFdAO8s`5!Ecug1+bR#C&okN0-+w}UJ7cVFHKAL-(cO$%>XP4ko9VI zpE~K6zCJl0kq1s=a^FqIU)%(!-~F!EUee>k{KwFzD9oG42XK#et8U;BAhcBL{bP{U z^i9M3*}sKHGn@6QZLL2&R$__hg)P`ZD zvr4=Mb821HPGyf1;p!2BWol`niUy<^ZRk-+ufe8`PdvtfPq()s`q5J1T?Z4=1AYdR zNJxnvN{<{woEqVhc~=>0Ysdzwv@%wZc$|28lzc=!ZFDamR%^@gVC5IrF<%tbb6#HOzk<574c@HJRKFKAl&Atz=Z;L5duEAdmBl-3 z)MCk*nB$rr89hgtTskAy<0(#f5?K^~oM>qH8cN3?cU+DksAy8+?AYiEv(O@kndsq= zVsa*JcoWEJ&(Qb7T%d#87BRf5$NguQo{}ah`w+0MX_^KR-xre23-qeML)_?RS4K6R z4>StrIkJHbFeuhE>Enx0f7k(8u=-SI))bQ@XIK_7#S&lYGoOJ5HUHrJvgF6OAdYH=bF&{M<}^u;QwzG))*KgCo4ERS^iY z21kRbiZQ5TW(i8S^(oi%N(0*|Z7zRVCX0oHdJA*;nWN}og(7I+RtDpah1h>kHZFeKC`H=mL}a%yXwG3UFq_zMb)Bays6$N%sgAfAFj^NEAd zzQ>U%+B5&f)Dn|$ZbUO@=3h81*QX0b$+63L0P;oS z?&Y|Z!~69DNBnnue5%R05oPKo#(6@6<%kn7{N@#wE3~`EhJfrAd?Ir*cw?+;CAO6_ z0{{rMuM16-DUblz7K%-?hW~qi=6|5$#3viNP}Fg;eC#MBWJvgH>0HF4wC#I(v9T$q zT*i`Ny{13v3{c+${t8I5tn*R8*Q+EPpcPs z0s{=J)>PC}mv?B7VW%azTh#a4QWbcopJ@w@H+#>>#Q!Xs^|kB$mpT`9v=tp8+1Af0HVG*ekG5P|tl zs;_N(yMQCA*~@s%WTB`D!whHy>Txwvr3Y(#&r`c_4LJNO2kQ*M-D!>Z$LNTiuK-ES z$b1ht@jIatm-VHKC@&B|;vzrMBikyqS_6Efd<9rWJWaBR2?~3+l;E>5=>JSog+7Wk zTH_{0;~Rwkv#_@Yqw{Yya74%vzY0%whda8usEtqmIdl+85iBW|Cl`MA>g5uX#%HL1 zw@|>J!KoDy(gwIIl^T8&uexLom>SV84*jcq;hq!Ww=KUT?rGQY{_URjB~NLWg2+B{diRP!;&@Lr-vx$aVYrH z{bHV@Gqg>>Xf}pb2YJJvexSn2`qSDoU(?XdQD&LLdTB+?INgPDYTud=?(eAGv1sj} zO<48%72{7D_a8}#4xkFJsC-~HTW=2gDvw3!-+N4|t$_gq zSl53K4|CazxtunJov~#dupz)vyJ|hmHx4WA#k<-szNRMOP$mQMz6s66e3dt#l$O#} zwp=&g1$tTNZtJ>r=cy|%I{GVqun~oV5DX92gyz-@j)E$#u`-w?jJtIrJH>ZFcfS{a zFx@Xtf1im@t_`|R8^szng-R;Z8TbcD$bTRsPv=R6y&VsP*Npfhots#yqLB3@KMr$dt{oSfBR~{?z`9SDXt39^cZT_qmKJ0pY(}* z{0;9%-!k}*m&!R2x<^TjSz&BT*^=%1t53f7=iG>{i#Ob5^nEeXYhQiM$p3K zNu+RPs511<4Fas_oZ5zB(iATa7cDS*x*b2=ZTl)mp*gNvT% zXJ_{rIf9#S@}6K%+n-l%uQv~ll8v89@8HK+vCiqErffDz6|8d`R^0x^Exb#DF@ne1 zGW0m6@Yc}7`=@yn!27NTbA+5)tWy)i znq4_zKrNiuR{OG5iWwfb*k%D*eih3jp~u52EQ7Zgfh zym*cc!%sNqIG?AD$PDp|FZ*&EqR+OsJPZYw1176cE+Xa1{BxO9iU8Qh0xsxU{5_z3 z04rk3!+60v`}WxTIX>BRDd^^7jK6GPQ0__}+)^GbaRJln5|t((Wdk|o?BYPPJ(xkv z=oQ{$Ul=~n0JVNSvb}y0E|oql?D-zs;ZRUk*g6HHm@Q?>z-=7jQhA#lvZ zmlDD4PxC*E zm)uVm#}7snrpq*s8y9XG_n_mzwRj1|I*8s!r&6dFA}%2|;jOg~k?q1Gbcpr|5`6Ne zyp79>YAg6IR}x^9in1zre||#IHSthhD8P+JG5j54S7N@Gqu(%wy?VX3Vy!@s9i{E# zAHtqq->A%{`qq)j+a)LB&nY!*6QmhE?nZ%Y3hz8(B2POO((ixaeZ-@+xRcIv+9ITj z9$uPsQ}M^uB4$A4Nq{bNU*}4Si<#p-exd4mI7RN%ILAZoZGvxZj+TF>!Yqu_p3Y&C zUoXxSC)$>AxmQ0dt*ktUXX=9r4kT`_Kj=uWJ*UkS9+q|~3vo9ccVAJ3pI{S^O86wN zpZ-JPI}C{2QrWmZa8T7^$A1ZjV^ z?{6m)|L6QgtA#Z1kx8?%`oY+#XpksCoOb`+^q* ze1G-0Hn~O~`8CS{=CgVOWoJNj6;&PBqOqY*iUu3{M)MG5Rarf(KAM}>_egkxNX5i)KkY5xA+GT-4UwML=C&8`Mn z!|SfI_>1?;wcl#n`GCYa#rzufZ5u6mVK;Ke^sic8KV5`26DyUnd%;=`-;LZlt5I(B1y?a)~0bGfztU}sXqwGtc7gC-fLNe z=oJI1<#4BT^WOW~SyeSQ$>j8YGD^?7t)@j9eE5`$%?|vb80T346^2^xe;X_cQx6jK z{vu}{ZuWipb*@r2OoBy;(eg)F35RJ=7uOYjBn)(nhU*LuS(Q|&Nw~1eE16vrOuY!| z9V1m|`5i*h@4OP&^)pjb1T)4}~7km}vn>ywCE#+Mw*vJS12qpp~Q2;pYm=GmZ2 zgTP1e-1f;^T+4^UWj#H~m7w$9I|l>Fr~QH+J|0e|Ly8j+vYPevQdSZDrkjiXB%NFj zXU6dTDP02~FR!Rb|BqBpxg1`dg>TZgLax84Vq_aw(AGw+sY;aE_Zam`@$XbfetrWw z{ec2A(<5SZFnat#=yMNRUeGv`I@mqI)mIQ_o9Cim=ACY{D~{HMpPuz`r|=+!I@!|% z6DQLT?F+ceEqhwi)|cChcTdQt2i6chZo!ASz>~ARhyGK7pzA?`$9=?uO~2&BO2Bca zuRV>8DfxKj-cm1ts3|?2CNaIWwG1G~DEfvYnn#P6~4 zf}R)a;p@*f6&EpQ@u7oef~V6-Nioi&S;&z~&`#$JE2zO5dLWQ?j%>I`96yj7RNo=Y4OWA_FV-t|*v3^DP#L~`fPV^YZYBV9ehmV1*f>R_@W2{h z2s@pDz_W7Rg-m6HgVxDqACcHm=ozdw#Be&6T4o9FxnS@6y`%n`r-cC4f<~p-B0psn zG@BA|Q+r^5|E1%nHzpLUMh0J_&0aS%u?aa-D~3pE#ng+E8|+cNa-0}H|6{}}wzP~A z`HH+ju-QW8u~b{L}?I3_1X33!Ab<)57P;*BakPn)9u&03e~UF zK=kb9p~J$vo1cgGDHE?K@IIwOLjE_H(2N*HZL*2@nPo0|f3oh9EHGany{(mZi}+HO$1y&su#dw+>7Rfbc>Is746rK&41aA~#X29vwy4D2;3 z+vjKQRvG8?-bm~_h3x;-~BaEuS=UzsZ&m$?CO0t>-Cw~Sj`9E8rVYKC_Rb5iOp@sLj zaeY?td6En`o_?#GX0=oGAUs5apdk`MymgT%uP?8tpmnStREPy&NTV{@_My7VN3%1pD2N_;Kpqn-hG@tZ9lTw#*I)5A{09U)Jbd^F zu5T==8bPiNUQ8;?6x3JXIGI~j_%Fw|NFR_u5k1~C2MX>tTi<9Zb*Aq}JfBDjY-Ac0 z))-R&dR>p6V$0MOjhg?$LANts2;PKv(;x={L7QXQd4Y|q@q6ko4jw>-OIX6|?Xtz_{a|M(~XLh8)}TOlXIQ zG~aaxU781T&@vCt8`t4Oa0Y6}3XGOtr08eVsziX8XG0>VW#VF|B<^Pz*7|T87TPMh zl3tYk!6`Zj_>(bU^j$W&t}33>rlpQp{H4nL>XJId$fsv!T<>gGLO`}(ZJo1x{^8;D zr!xlRyVq|2!(;ICv2VY0__uNtFW&kpN;9jswT`n&1_gP;Xd3h@9;~i~v9)fdYR^f2 zec=tthHqy#-wpkIVT)JsxdK3eE7hw?EnKQ<=z%FB{i@wB=f&9VDkg0~O0pebs2OjZtXmn$iBiDDiCnxQc*dlzt_Aq&P28mS zVlVaACJz+3b?12CqBDEKsX6Vf1l5>ky5?QwPM!_T$0|}~0fYS{!>Wt*T9s0aH9s~h zR`8)PSn}>BDzMDg214MnQ``h!hodkvtdl5Jss_@~%do}~ts}zu0>9<$P0Pf74BPzT z<)&=L$!nNlaZ2bO8Vw+_Hu-*GAY`e=5NM(LK9zJG>B#xz(_23I6MtWTTo-Vzk^&Wl zCpSv9S`SBxNLp_Ei}llE&1y%N7-~!4`=G}&-IUc1$@>GzV63^tyKM*=Ox-z)u*UcN zVtMaz9lcV^_H?5}GB+*l&^7C7Py-ih5e*F=+3*KjxUVnxIdg#FwxT;A5V$~#E!nx8 zc}FbYyFqBKTV0%+mh^j)O754ie2Kzm0K0$)rcyaW`3SWXi|EgAWcRJ4>C?#wp23jw z*wj)*<}OF<-Kn!E)fkB74O6wbj3$wHMAv&d^9;iejSaF20|lH1!UJCCjDQwCKC1D7 zaO-hgo_>l$z`^bEXal(`kH=|(=a^x?XkTguxNap~ENwbtEz};5*4PxEE~RCxaI`U# zXWY04PI&n-sga>!sG8e@kF2(rI}gCswp$qcpA!tv<;Xi1ZEV^Mvxlv^-Dt=A%DXiv zYlwGQLQy?0&hL{Y3#>UqvMlfM@9cr8`1sJJPw-Vx`(Cri1s23fMXeW6YG@DPifr&Jth+8UlAxgMruLa)qwHm)1UYy8?}5=dayoe{xR50Uut*GF zen#mxbnL))V_fWFiz^vsteR;|S$GXk+4CKKX7hJOhSoHKe{8Mn18u1iqnv5C`QLz> zmU7GeKv26TxY{p$@Yg4ANpb4t&3}F1Kzp5l%*qcPc}``E+4Mg10d4+GR(5q&m!3JVRcqRh7}H zZNFJ@rm|w*3SmjT7Abws$tPRw$aUZY@I;Mz)hNG+3_aaPJo0mI#y1Ytn@P;d_JT2e zj=$P_FKi$U6GEOV=2^kWTQy)DaII1bsntKkc97~>Ez5H){}& zH?)ste3!DTAEues+}yv&y zzFcS_kCah1mrMr-4ytaP+^=Vao78ac=*iXR4lki|N3ped!CXWnKkmc9-CN!;-z;mz zb!YTbfr1!51$Q4Gk1(ugjphEZ5bRoFKrAlal3 zD=S*DfQ5xd9^^vUI(6q+4tcYYd=Ra#lnb{?M_$ZrOBhdHKqkFO&8yy@)~BRCOO)vt zZXadm<5c9KtlE1LL^)-;L|9TH!!z(#Le^5VAxo@(>Nt5h#rV(vpXowI06VBHVd zcasv!zXui%?$;~c>vdCtByVeIT*L*3#WJRp0>+7hmT(c61XdxZ^RcQGf+TmYlC(e% z0?Ze0S+k4$JrepI+1I+~;p%xVePQGWdFE6I^D4#kL26g);)~E05*RFUaXi=i7SI2fJ>(xhyC& zae2nR6@>o{5XC3ml3vti>b>ne6zrNqkq8PIXnJn(~^XLdL{k80? zG|e($@ao_QeEo2R6{24J!HrRetj0PpPjG?6r3I;F4Cn|5d_C0#vHE2|KM9^v*U^Lh%d4_1>3z*;5APZZrp2U>rD%ZQuvSv1r*T+nPW1wTv z+r&~r6%Ig|u*Rob!{Ceof^N(ajVw$60|8+8;JK@XnaOlDWV|*1LS4bH8%qw`C^vr) z&-j~2qwPMuE2^J|f|EH@h(`ed-`(c>Tl+wq*J04pBgJE{~4s>U{;qqRTAAUVfQSr$+W?>m%=|6O(* zU{)+CN0*TACB=#=^W5M#Ue)9s1Ge?to@1Xf^abrYWp6xYY9EAK^6~| z^&KqZ7Z04|cp#FuQ^nbKeM^ z@ZZ$JVTpiQA(03>U-Lp%d#sqp=&z`_q=WrMH>}=HFX|nx8{i4)Yn#4C$~iz{W#blr z2;*%ZVFf#`T<-wGq4U#}y6NK}qa`rHDd^&; z{wS*6<*F>y?bkb0qY5s>kXC!}>HPx1lh}yF?!Xao^c+ z3#mH`Df&@?c*b#~ImEMfKD!IeZH$#oKxr0|^u;%9o*s{uEB3~lv;iI671k}QFd?7q zn^;`X`y&1=eB?Ll;g|220eBixTjf|w@yV7OcsPG^qIb$P^Rv?7%4Jtk7+kc7?@^M< z?f8WvRru5)6?aileusvob}tUdl#H?R{|{GR71dVMZkyol?ohNXCAhmwai_Su6}RA4 zq|j2VXesXQ?gS|=!3o6z6!*&+YtJ>mDXBb=EBIErkd6jQ)IirZ zUTA-~mEd<6>`il}+jIe^hf+Z~ZK!rx7Hq)G;+q4S_KhP2XW=E^CEL42*!q{`*cx&! zaOu1k@)A9y=%*o6Gld4ZF>3S=+1s_rK~4-F#9cQJfEM?Au*C$ZDfembpx87~977Lf zk5Q)6HcN?dR~7hY0KB*$Q#!5~EBeOfACc!A@O8c$DS%DmKg)kJ`@r?3t%bXPLQ;g0 zNh+egHy(1DRO#>RJYru9J4VT)v#vUG8TkpjYq)GrM9a9Ud9RBVak#)gcW5yQ7Hn#! zG@6LBo~*p%;kcnX9(msp!4zMk=QGdn9yIkl9!4`P|7K+RhEFYv{^b7i`$oQ_?^O>t z{=w)*@!!733_SgaRFe@Lb!n#GE=ubT@LI!$x_HvuH&vDMnnzSP?(k;c95^dwxVr9* zf%=C`hH7np+cuY%?u$^KKaNoR3lVv~_-`$MVNa6Re8L~Bw}oMoNjsmKuv@@C@oE=5 zgx%oFQ3~)nG{Tt-One&5X30DWz<$o}KaZ~6?JxJFK9yfCI*_K{NBlbddoh*sW^)Tv zaRCH|-8mp#oT2&uv-&inSx#rebbSW<-PgP*4X(r|Ed3)WCjYnXQp8j|sLm5tCg$H% zcd)a~s)<$MTcO0(_mLTq%WoLMVln^~>#S)qibZp6@0H>Iytyj^qx}+Cq|hz;WCGIB ze6ZYFD5bKZKgA)CL8-N&r+XSzF5u;kpj*cxl=_Hdb0SpU5ne z(Gtk#MbhYo>@ah(*eDkCIlXVpdXOaFj7wJ!H52eG-P_8if~w)JtI7%+E5GP+5)DH>Med`z+P!tyY;rlYgY;m{)t=t&tV#JhjfDy4F~EC=z~vw+*LBfvhWmr? zq;Y#TkevnGbJ)yg4#TW_0zlMpTC^|-w9zH7fD1tsWl9?L)sX>C*0%88W2_eWaGr-%+*&^d9YEi3 zet^wgvn#00>tb1hCJmC_+28SA@W^GB>Cc@uW~-hnY)3~;Y2t77Y3URFqC;ug`9!1aUnuu6WhH4=6Uex{$$DjqBQ8~VzJ+iXitO%|4Yyhx$jZ1 zbzZMH>Ba2n{(zL5;I~F=L3$6WE~3zl)p#*A$nRxc3oeLv5c{HD3U~0m{TP;@A!AdG zwQKQSve3Ve81f9uvix%0d0f037Ky)+W47)DP|ewVS0r1EaR$~`$M%9Gk2mV(xgFi{I=;thYS`8A%?{29=sA+$KpGk|qlWhf%#U}It%jMA3BzkTMm3j9RFZxo)ohwlUgIPtnwhAL$TNv&-nq1|%Q9_YWTefk73 zE^mZEz92}NS(vgr0Ma7_879_5{YNb~I(@lTl5&HdodUf*zo#ZjM>o1-1u`4xr}`Wn zZ36HK876jo-_ptHD=7`IDXKcmr*OrH#(c{FO?~`DP%x*o4+SD|vMb-wzWfzesR42k zOQ%WtIf(r=taed%diaF^ewe@ryjzBxKJH@DT}RvhO)0BVXQNoCCuz;le}nb0ez7br z2a-T<{AS1Ohb5bVXKOTn>OR(=2QBP^6&2aG#G^kQvNHIP3C2F#m!-ItwZ)^iB9juk zwQ1RtEDnPfB3O4j)&w+kzdr1L5Sdnb6BUpg(;Bp2owF-o&K&aS^DoLdt*-RSW1eZhQzJrwOCOV}S|*Ahpyid{dk`I;DJ zRQ3R^tR(=uIlyl#VpKtmVFu24J)8W{c?pRaO%ap&qxsHzJZ@#~>$6#&m+_YaHJ@;J zaZ@||dJx2mbx+BW`+PP_38s5=^SPa^?lSn<(=Gy62Cm>h)k5yKhjTajY7u(7pAXyl zU6TSDs6QuNze)(kNt-EcK6pNjSFb-pR--+EG-s4kInKFGL}cv^l(T&&|1>uLKdbS2 za(p~nKzBB-t#G`gCPHn`J()_n;V^aaWRWv3O3;gqk^Cx?_#i9PcsLyNbnhzuX|LgA zV9B%_`f^*pn)`S;_*#ScZ;Rv9kH^u&AHot}GEEK`eJePAQS9r9 z3n(6KLqcM)wlUun@=^^B$=2GdFzf(wx#*DLQPEb7POa96qbZ8yw2iBqaJt!E#RBI>`B>RRe(Fabq8cJVgNrT?7Nj+Htl&K z8|Ja2uweMY9L>y%OINUHKmcnxnu^MRipt#0-A%~RMed{7fv5lVBXb}-+!XU_lv-vW zsfy`_&XDk{jEagnG574Rw__>>5gGb|vKHp3-v_m=OvbvOQ@exwMVSwhPLqM|KDB-h}@so%C!MC8yu46=M^VUs!TtV|Q__YRfO?{$`Y*i4TmY zlM-0i+?Pk4_s`OM!S`eUc_J~0q>~XLA*~_WL;GJNpv^1y_Rq}!wohgl$S}MLRg{ga z%V09<#Kg#<8GZe4!i)hn=CH04+l zsYniC^gIZ^RgJSzPzBQ3K*urB56el#vvaVbD}L7agf;0q{69jvQSZTih)VSjvmRnT z@z0YAJ~TC_z?6 zfR!z`va7hr%6q3S#Or>4DA}}k4~=)a5;s3Cz~&rgzOKd%7NtNz7O~YW&{SUuTz7N; zU_91h(M}{Q3!VSRmUli|KpSa$t6ynE&bkDw?q+|v>Arsro4fJ~y35krNzWCdgq}lh zhEKc1U4|ytLe8)3-=!cFw}DeSUp)YxmbX=E#nQ+iUP`%8gs5fgo;g6{{9lidntgr* z=?zRcCIuY#%v09=ko#Rd%k%YCM4#gAA-V9k{B}u$5u?D1Lo;MG)9Z(J56|xp8toN3 z>58{G`z0nLA4M@wlH%XED5Up<1<(CHlQ1&OFtpes2vSl<>1B{`yQxwu_yQI*(|=8j zQWlDR>w^vXguZWaVlEJ|p7Nd#@A9Wre8 ziun(FZYq_7co-?n<6TrYs2V<=)i@VW=G45*(+%qQvDd0sT2-{mESF4DSDZXmM@4Pr zg8fo^74nXBK~AjUMO5ngYx}>NaN@iN`?yhO14CY)&lSaWBFFDiFV*hlXd(uWwi9~Z z(Ft%!iC0OG+r2vpL(C?mg7kJ=U;Nq*Zn^~)H4bBVfqsSu$pA(yA=f|O4J|%+SImnt zuD^yjQ1zI5SW`8}{fQfgsJ86$EBDZc0508`h}@?~nifMXaMh<%fm190>6~!@&{oynO7l7+ zc_)mdic4#QrH3JhyZPv{2%?sO}rYf97S3fBl~$9f{1qdxIHk z;+d=IzJ{EQtL-mnNf*mZQqCqnFy!rB6P^Y9$JGdCJaph zIxc{S_(nemAD`&z?jU|EHprR}nr&G1lSzcle&^a0~4R)95qK>Lgt{QR^ zD6E+gxswWzKRUDq2pbzi8}RL%{frn(`CxWtEf1Q81eFMu*-8Qbb}@>GeUw{eKS%ld zWJk7(-2~YhqhX)E+=n-E5#GpqY|gK?Z>)97VCpe`pC>I0)8ZCbJ1GpsOmhBfw~f{^ zKV-(p?9;Po<6w!R4;#!}rVx_8l}FTyKrE>=kf}CYG^4v+iypMj+^6>hGA~^uNSqx) z3%-10G3}Zd^h>SdMVxUFe%#3wd-+j~lQfNQP?QbjkdPMiDfvk{XI)n2*t>Wrx!nk` za~T4IT3ZdkXeEtZf;nkbv{ugK6&yPp)`k@CiC)XR#vr{j-l-Ef=H&i&P z#6fF(XREz!vHB*w|3d*m=t*5+I}^gT7|&cXcd*{=&1D5wk){Atm4;7$rQt zkX#>tR;Ez9)Gul)X@T;S*-~KfGUAVa5r=~we-?2?aGRG;2^S%u84y2RknqjpP4KN1 zyFaS5WLey>Bp|5`n;SJd) z4O$lO*ULguwUC<&cj_)*p~*&nB@yqjve7hp`>g$b_xs}4T#Bm?Ay05$-e0C2f|ZCs z!~SPCsoKV6_d%<&x~@O4v-+o_|A_%U+&A_Zy$p8WZXX^jgz7$?+zeNDt*AvE8F%ru zzsN321CO-<$L1l|FI}|Wek(tWIqXKzEpw}Kc3-RG*f}}&Zq0SUsc>4=n|k2&acadx zJvq^;#)=b*S(qg7FU}GvmgtxhSf$4C`-z;H{-OeI^a_hp+kjmGRzZ8TCHH<*T|>3$ z$yPzw3G;V{G1kG2SM_h>0rjbOzZ;XA`fszk?Yd2##l#{(4=|z(6;c{tLIg#s9xP3` z$2<*^8RPPx$uc7X#D0-w%%&)U^i&3Pfao{U>wZ3hCXPZZE>-1+6-Up(HM+q)qLpKYVBsTBnas5nNi{ou&; z1*6F@hUxGBs+^?0IcUg+?FsODil_OD=zI(mzQjUN&=PX z{$f0A1V3ShK5~Ryve0%xlN{;4Vo(_N-|Al!CS3q0Pn)B}pUR^(T8<0|!Q2f-89yn> z%tEu;`?2S*$Nxd*ou_Q8DRPTPEAje+?^L~qchr$<+;}&-Io|1VOK3lbtUp2W{*}Mf zim5xIL`nd-CFpRA@92wPVDecm^>+lf+j|S4;(@KkN!RCH+@2;Ze}N5hZ+;@GPHfQ$ zr0;O*k0t)ddhRCaGF=%vsS-xc>&q>MkLL&bT!vf(-*4|-kGecQ)~{N#(ZX@)2tvs% zPexHSi`U;%O;rgK=lqcE3IDfc{!g{;P>vqUCdX!@JD|j1A66uUWI2h`V#)oR7kC82 z!SPv-c~j7esFFVZ#*9hRoLgT%&NI8NN_z~^9sV)P<_!-h5_#s{LLz0(VeGi19M`GH zP+#qRt$60W?gc#}%>6n44VG1hYBNAU(Ul!$s5dm=o%6Cpf~bW!=blJN3X5t~fMU7X zcsVBBU;@^t##S~J7uYBjkN|K0Ol(#hn=x-+2^KfF$o185cfV?rGj{!v?0#z4!vQ}N zylM&T7)Z=(I04M_NO^u|cgTWMvtPhfGnXcveoA#GS6d*&mX&Kk^mKAnH}mJ2V!fy2 zy2JZ#Lm#-8mYLYT=m8fLq^;ZNU~2^cK$F z?gR_@K@;`x@4m6pJ?STgjY?%86{R>%>4qE4<-I?TeCb_yPo*=@DNUMBNGAt4uCt57 zS`JSCg_#u-<-2{8@lcmp^LKkbBDz%?UmPG^Y(SKE-Lti+zwU+KYggJvr+9k5YOu)s z0-!!vq0(T3o2XzPdEDF~`stbP$_;B?PB8(C5VnxHsci_l&*WSDDXdy-n6{8vB&P9I zkbzur=kM0rfi+C`VnSXYWkm;xXd;;4-hGD!9+jhgRO|75KCeW99w)kW@1OKvr@mEt zyRvlc=4XE#TD}APl-gFWo>+$+HiZ!PdR=pw(Ezkf>F`O=&K)yx{R7O-Mq(_x%de^E9M^ld?e<7z$K_xBs7UWJpY0aTQO9=1TepobqE zE=Jr1jo{d@u$o}`#&6xX<<;HK@GWRQ^WKBctm)%+F#m5`@h2>BzsEH)Hg>oY_qRhk z-;3XUkF#oR<@6yT;x98V=fiu%04E-DED#TH;UKrJ>VkM*s*3w9K-H(QWRu3ONt5M) zcqzgLp@M(mb%YzliwGhEgf8tQCW&DDyMbGEG9{5Kj%@7fEvNuAYP;1M7qUy}nHaf2k zML?6+G;B>5)8+}$EXy}`ZObYTZYP&nf<)Eg;yR|uFxG~PSY*UgktB?SmDC(&Q1t|N zA2+#oDvnz){QGwRa}n=-I?(aSKC*XNY{yA_*hzUUIYm`Bx>S5WG9hDyeB394L$V;h zLCXzrPeMcF1lQcAJ6Yr0G>T(lcZqEg>#=d8FD)%^)xuaiBg505eq>uW>au^&$Y@zO z3`J6uA=%n@cmzy7v+a4A0U0J+W}uM<05GH$2ZbJG#g? zpLlR33?dQ>7?4n^JGjs^WXE=^smgOEO9{ACG+A?@QN_G1qZL+6`Q+l$uh#AB&3fWr z1>n->t|kqdELC<;{6LHRpA$eN*H@$W^E1oK=HUE?jZZgXyRYYGK3vmc+m@qwODuQg z)tcC0$ZzU6IRj>o(ty*H1$Tcsy`QZ;_7+X;@~s7y$UW|gZv@|~9j@v<WGIp)n`wKh)2 z%C78{tcN!0KS|vkZC!BQ*EbH%nJ3TlB47Nv4AVe5io)yK(=$=MlutM*}wb>zg0ui>`WC$?EJXG{{I5w9OTk!0@z|E8O|kvl%Js}aO79<@)^G*!cADaAiVR8dXO+4NGt9=w=Amiuez6OLnP_;G!M7b*E^xE&CuyRV~$~pN(1hHydQUu;T4YT zKhUYLA9OV)XjyPolN5Vkzva;Cmu3F0xclyZ7`5j-xa5*+vQ?GiX+saY&9^xvUwwB%d}np?z7ne6W*X zqu(s(`Oe6GzHR*e;zE7ai!`$GW{ocH!b)z?zv6p!ECtcK(fbEDJ7Hv{35~HI$#hLY zOVU@XP_l{14GN0i7AebFdOkM$ynZ)i0YpsREGSe3MC>uVfzXMJ#RGt988G63`~@(e zQXczv!f7o_4HChY)U1z15%b_CyEiCB~d;)JT2sAU5rMjOXc z@)+ISFhlnDRA&0Tps%a}+~B^g<99Xx8Yw4wkgQ!?)>U*EE3IZIvqO0&$RrMta4tsJ zYO9`Ee7ywPR2Qc0hexNhNct*5r=D3z()~P>l4gWWs;%&}Du*1gvq9;be;-_&+v?pc zY)Bkowt5tk-<=_gZ$f+Dy9tCtrXJJv2Y@lZK(0106GvmM42BefTxB={+y%(sUEkO? zfygicj%klZlkr9NhJ)O^Hm0up=c<%p0+Sc#RX@vu{(WA&8Uyp%{?1q4N&dHlI6W}H zbE)Wgf2K~Oik!qA@Nt^+#z2!mqb-oA4h69oEDIV8t9NxB{3x9ptZr(Zy077w4NP3&i55mp z7RE2^QdaQ@5jVa7?S7NBw2#%-8QX;z6K-rwDXu2q?C{~gxrvpjkhM=6R{gmKQOGVt zfDb}zKA5@|-|G~@ls`WvxfQIib64IN{s6CWLb zF-w9HNs?KT!d@bi`4MxDc21j1k!sqCOaZ|hB^G6S#*PQ$s?94mgB;gK-1anxM*#lS zkMa@GE}nNJF7Aul4Vq8)P0rMUVY?ysid#uqAi!g@p8PpWY!? z(Gc~%Rh7lZlOqnp6YkfLJVtiIjK~ZFjYE`bXd&r#T*L@ygCgnI`G|;LR}L4W3Kr6~ zP0E2(8CV5K?$MtoCce^9{c0Xn5hZi?TJicWpl^I7DwQV&D?=KyoC$Mh1tJw_issYc zNQ0WH(EG;>2y!CJ9e049}*nKTs z@XNvNsL5pu%LKAuJ$Ym*8YUoXDjzEW*t~*BLWLel2UmuEuE3v)`y+D%8C$vDu=na< zB9<&MID?@AMz(Rl^Ko4>!Ul&yvyz^UR2bX(ZIjYhL}4@C*nMrg+CvaRYXI`vp~xU1 zs2pBW)zuK`$Lk|6`R>9axi!*HgdrUfNUVNgh%Z%AVj>AFYU4PU{w9>9>!z*#EpMfV zE^a{rkyxb08JpJmvz*iINZ1|O)O$7uN9LLQ(@*U- zHGI$D$*I%nI@o518AJ5V<7LhaU?LC~M#Z4w$lUOZk|54oAOY=OM=nY&G}W)MEK0n*sr^Pklf1sonjblHQcJQ6gG0QQV>h z^FUT|B5iT?Sa6uK{ON`&1}zSX8JVs2`E^$XQMg(4EvadRk*)@dIJP%*miFa5YvVca zFog=olFh|8r2Z&CQ6_oB4pSWiNwb+h*kS%aDrbLzqJ<5C8W(nUG_VXIc0E<)Z*Nfg zw{35#{xN9HvpbHMtk@yd^Z1PpI#4DPDmmfCPyfLL!LzY%EpnGSUQ5FK=ixbM`{}Ee z=U61h@kWk7M7F%r&s0#p^1r)Oof$Dk7@_0)tr9*Ge<*=XuvRzKaPl=1^;Ts}eP#j*QzSAwll*d z)YYpz!7LG*^5fMZ&1ako3u1a@55f>&wegjZ@p4eWmBqF1H~<~hv7xN#{$nQ%p?wqSD}W=HgmxUTXVdR7*!KyO5=H%MX;+7zu6JJ~m3U3k3~{U*FB~0T3lA znOz(mA8nuAS)N?q0x#N5GW^ZR7=&nt$|J`pkFp%0^EiyGF$>^@E;iKt?Tes@}hX$SH^NufzYt!XMvzKHRp&o z6TQD+;H=dCc?DW1$NwPrUpKzEONZCW{?Fl6p63mpji+PVYVWDn+)Tfhi|$8Ip#22} z@e=T%Nyz!=YzCg$Un2iOfi6Ma6Q%3VUvc3< zWKjE^7*tWKwQP&ElGaOx;~fM+$Ko|$Ss$W*vyr5xXa6=a!v0cYeAfA9kaV%HqNH4` z4oE!N@&Lk$t{82u8#6G9fghGpwtN}>ckTTP41Ig`K8PW%pP<+NsNp zCocymz&7c1_A9jlmh`G`t$&RSlwx-MQ05Stp~3GhReA_VWaH*8Z1W_UdyA5|WnX4u z-i8INSeMc_F_KD#Y~h>WTLKv91=OicgRlHMm531P>9pyPzzD+w{Q^BVu9Rs_eZKl4s`J7TwK%zS?tF1kJlQplkdK~Bw%!Hr~4WjWAWN*P)d)s02W+Bks zca=RRZ+)eFq%#GK$J4w?4=6!gjxmHlMQmrOohR%Vzbpg5VR)OW$&oywpD2Z*qo~0S z$P{AX0fQ-iPIOLpr3pXp0+IgY6w7b8QC1~$%TOh9+5%(T0;n?l(v^m)*CCnbU;KgiFCK4rsV%*aq(`Sp@J^tbAWxXIO zqLH5a2{tl^05g`Q@=mh+yqs3{KORG$Mvy7$=*@Gf>8$!klQDWmqCQ74D}!w5Sspr; z&cWZOe+q#h)kKdm$cYjY^M+G6n*%jr5`cUm)@i@UsV{hVtY_IWS&J=@%|9_Ccam;I zo_H;Np$_w7#~YwJFr5rNzzx<@GSOS1$v6iFRL{La;EQBlJhU(1g74C13=!&%Pg&hh zZQ5_<7-QLX3jnBjx~KO7Uv|oE=}9ec28aM#=U41=qH_MNM_j+lc{|&$iuo^1O{yEs zs4A0Gq|C&8m&aIq=A;qu>r>0kOHmPjoC#J5aR2fgev~RqTjW5O3_5cb&F(Pu`*;2U zMATtl9Y(J7Sd>(l#Q|`rcbxe$eH#fCd6Ml#gWLTBB2BpR< z%)lLoDk9jybT3F{-ENNUD(_ER?2(3lWEDF*JWC5ga9Bf-rf3MsgpyW1=N9HAZXYK8 z`5-nNDBWWY!H#Uneq(C)i4n*fhr}wVlV5{$8`x|2opr)MGdf0JIiPL7qEaUzBIfoS zRWMrJldk|on}7safU!5RvWyr9MH#>s)m%u3;Ns1?>y>F%5b;ek-3?1u7uN zvTViaB5dK=%&zhdD?Ol{fC6s&yUG&BT#2;fKjAE&FDAA&uxByE`~JRKm3s*xISrK` zYbcJ~=G7C$Ve0L=uHr-M{L<_F24%D#4Q=|uAq!>6;YSnoP2@VYvJhQTR3T7dA|~6P z5*)Xd)g zq|;Y6j!oDk#PjC)DP3OA2cJd_N5_we@NqTi0ZuJ_=)L-~Szo?CwJ>Y9r_K5mGw9)j zdQB^if2xVVpg0V0G?KE2L%DJw@Z8*e6Br^?DZE14sdj(va(`aVqA*F&{c?@d<8vzZ zDOdHWOd3$FX=aL<6gn{`bmhV<)%*79-=o0`q`sYWLyN|}*t_1GinC&0X6dTl*GF$U z?ooaf7%jZQHDs}zOkjO|bd)aXs!9l^{%akFN1*exIwRq$+eCD@Cb9d=4hdi97f7bE z(-Bd1FfHsLi;Z7Fhls*uG3nyR>_|dX@;*nJ$Fs*}Y`P0UfqvhgVNf@+fAyrXi)3;e zRgZ4}Z1ujN9rQ+|1W~cuI^pi8_-Yy3FlT3NQiA*gvwos4TJ|-}d5I3`OcyaK1NK_6 zOgKrG#GUqg8|In$a)h_1vYr@6Z~t=6sq8OQdRnIgA90tK^VXT%H=lWeeR37iBo5EG zikyEKHl0A(LP99~=yf&z`n0|KJq?(s{hO57t9A0Ia%!u=SLW_gBp+en*FYA$53Qw67ys9c4s-u5@F8Obh#bFjPHior?B9>>R5hUOf zEiA)m`yDmf=)$N`Z<5L(rv`0mc}rDFdDl%9jW6dn97#=4f-!CevIXN-XZXGFwy|Le z5g@y*2J|5kjK(w4c@!*Y;qeSzkw9q?p;8R++gStocn(CBui2`@h~r5sy=)tQ2WGyB zPq5NK$X5UC0%1tWFe9I6;G7-lJ5d8?ptSW59|Iy-<=&=}%tHANc1<2H_9+=OZ!B>l zIJxw0X02|bAE&wYgS#X%>@u;yFy;THGV$MHw*nHCr%7io>l&SR1&+OJ-{cI)?CcKj zeD<0b^_%Iw{}dg*9x}a}w6p4pVaCqD4=Cp?X5SDw)%>FNHt6O)_$gFPOEs>4rjFcy z$c|e}S)$2Y4CREJrnTFfU{*ZgAC(L+miv;jqw?!qWL9 z0Mp>7JXbPSqdO!xY5PF83-&L|F)#EnTDj!JNH~sZQ2M#Y^@>BrtedI;B$Oe@RNG*jgNPuZn&#=C-KRmX!TAyCZ;&F5};pVVKa}7Mo(v^>FEx? zt>15NPO**;1XIv85TKI1*((h3PxF-^hu<02z|kVuwS?{4iEdi6OZ<%>gs2b^ zKl;u6=%%yzmx2$XX57&Za>Ye@M-!k)@qNL3Pl0pV&rg9VJb_@-O3HXrFt0dAnA*~U zCho@4LI<{AgOA_Ramd08uXM9K>a2GV{Fh$id`ff2_1G^sjqoaR?8;>{hb^fd?PH=DdvTtQSKKpt3k=M5D` zpj!3HjMHND0sk_<+5P>6-*b0?xhoaa(vm2Xuk z8xYP$c^Nj_4Jdt~)TUvPRlF_-Y6f=LuulG=_q zPg7Rp^9HL>4EPviPBx)iC7)IKgvhKe7Omrp-UC7nukql)IZU9%3*m2cGU~|qgRoTw zE+1}FG>VMS464Z_&zfl-_t)|0JXK^kP<+r?5j)C- zZhj_fUOm6sIO*+BBFkhc2fVJyI`}LkmFDa;*zX4R_c#NvxEgNcSmJI#@tZrY5 zJK9a`OZcm+{_z0+>YnrHFK}i5Yg3~KL?s6FKpeaju$E_R-SSqYTbJbk(Ymiq?NUqI z@UQH4)xK=Lg-g6>=w?V@r?ly!b)%|_j~_S|9RUVkBj^+)bSar3hX8Be^0l$Ucd@Ov zhK$m--t+)FCiiK4370Quph|}ipEPVu<&hCI&`P|5$IOX)R|RAdfdjmBJcc~P(xFIk zUsp8+vyj8xbUb-UNdPclk2VH95(5ymXKUGzjklszMndW=EuE(TuflK-tQp#)9Xh?R zsl{gwn181W4jH$%o$iBe_t}Z2q?m)9iR|`RCWguR-KsQ9#ADS*@Mub!6ioc4R=t=;FVQ4;&Ga zcZA(bemOhjHW2KaczZ|A#GiMItXNkPG62q?;MvX=14N!R`8zHz&qv9CGT9qiMMxGu4};nHLCP+-eoQIS$IUzPMD1mn~HlTp4h zE!F7jhD&J$dw8MHkI}`C+p>XQpWJH9YhErw{5t)6N604fmS~+=I{XJi&P+QEtM79k zWvX&V1zuqv1uk=}TJzquGx=%YL^Id6_WKRWv~MFKW+4P93Yt;s=JW4zg8pKg?kH=cNP@j6@QeZp01A;41tO4O^ zxgiG0WK!?kg7w{2OoM$sp##Z?-T^Nkjh@RnaHmWwTyO4dDCe{75>FvE7zmsb@40S{ z^y3P37nQ(3HV>n&mF<^#NNub zRyX!U2}zi>8**N1C|(8>5gg~>ATxl3dhu#;QfA}s1cj%9Bus#na-kFIbu{rfHB&DB zWb05;dMb>l08{JNL8qs|49Vjah#B@ixpohDvXz+09bO-)G_`4u4k*if-`a=D(3DR{E^mW5f#Zh@zdx(7r#r9%;@qbrH_+F!9)=vh}9PrLwuv|%%;w!nECM%aUF-V zxc-J$=Wg%$gH{9z8oJ;sHJ)PS1stUp#!9t>7(gP4iBe@X>{w2mLIh(D!^f(; z_*gR4h66kG4q=Bc`d1YOu?i8JjCF3rEM9~jix@~(7-Uq8=3OjkjC8JiZ>Oo0cca6~ zBmfac-=<=yOQcl3Ac=iMX7>pAVCp0C3#T(~Vp)Qrc<|R!@b?Hx5CH@I?b=v(O9L9f zOKMP*z)Nux4_!>_?;Q~#ooMDpg_q4$Oc#%hy|R*pqCy$}mtTi)y!>ou6y>T{1XV%+ z3-Fr6`!GvE8oty@K!d_U@O6+py1q7EA_h?4n}K;2AMoHY(UCxZZr?>7gD<fo}1|h#Cu^lE*LzI{7 zVQ-KXy@%ZgxtR_Ch&{F7bekD}#8hzc%(Voo_Glc#)0!)TQ3Bez)k_d?ynRl_$ImtndiFl8_YE^t}f(Kid z<^nu+k)4yN?~KG(aIk8xq5!+2`Ev-d07Hlhg7qzEMF|jFSsR3$xxD?QhwMx;i0LzQ znDN_uecGIlkpc>Uq8?e*d2a_Vpa6A~F>vRLkKQcB_Y~@1-WD+{rQ6v)oVB__lHp6RqO;9|BDAB?_A6ftj5wn9Q z>Vl>n(>{HOry%Jr{*eDSYaTx;P=qL5wHk0?hiaRJ>iGO!=n#b!I?H4-W>Te5?!r9c z^tDyEXMK_in4XdoIZP&wL5r_P@9TXSKs&d1uGEjMav=wRYZuFl@M)f2V5-KErW6AY zFP%>VLpxoFxj;gN(K%2On|{ul9dGOp*Sw}_)%B(eFA zyk`kl*xS-;x7L*vT-1)Mb3$?uu7pzw+OG2mGYQ9!X0kWJR2S+pfrdZC_pMTsh1he- zF(jZ{`iZq(ZS4{(cmK%G^ZbU_wj2~LSaLhfkfhu!&JTMC z0T+lX@iOe+9rx?4+&ma$==r1HcwM+KD0(_Ey!K0he%5`I^?A3`@hGGdPv_%#f?P+y2KI-9sX;b={mmNmKiD*5jGuGLpBm(dVcs-qYUD7M0ffH zP}K)NJ3M?|RhBu_^G0T9^Mi4YnLaJcmvpu$no+@zlfB54QM`|q2~w2t@xU9tZT=7R zxHZOo)0^=WTs`(9O$0)TIH>+)z7+dclgu+8=!fRGjTIwGX@+Jccu7#{Z_%=f2MD7I znLpH8+9*vdJ76#UsAEu>)sF9#M5}EamROQR04|ow;Tnq2UOwpqs8o}GIt%A49>AIQ z4~!FU>@Tcza0%b`O21er15spr6k`$m*#Cs4S5{x-NtrVmqPsSqgH*fk3Q5b!qS;=C zP2s43u7M+g^<7hCHwJ^6!)J!r_|SoPL8+uBMiN(8zWn#)`BZ}FSo zQiEARcn-V(oB4^p>;#ABFLDSl6)n1fk^KV?6bp3SGPFoMtoe$MqUH1v4)f}kyLf%a z!syNn3*_80#ELrSlry8!$z&!9ALU zhA@vfuuMQPz)LGNEF!y%S$fZKn+bjEGM@(k-ZREd0pDyg~rV zoV1hRskXl$AYvJWl0fB3Nfea(7%g3l5H1Zt(a2FLPo2 z&`QraZ&De`fSI2w&!?%?d^R3&@_MEMSaj5R;^N18l+P8`9~%@#QtA%Qrp zg6qr6nhgdOfW{VM5|;3qnLa+{=}=VO?b%QkN*g;j^{BW%#kLn}we1!@+hoYdg@rLT zxx$)^@jW8#^(B+}XxI=IEQg^fo`$oG8*_<`^Y9GUqtRqQl1XZ8nW6 z8z5goWUtVc5?w-TR}2(`L=1o~=N%6EKcb%}&14k65jFZ2el*945LdEChZnI1ashS= zM|oLe|J@&y;jk+Y7K*11O((S>7ES9ck__7x-lw{W37@aN_oPPDY4_~URfhi<{qO1X z(_70$vH+ytRzCEY6tm)WnnLVhGm5PEyT8W~Jjn&Y+VX0g*Hcm$A3Qs@-|Gks;H!|Fk>SNy zk(e&<_!QD<)(nqISR{P!`N5jd>(B=~a?9$6+gGJxtQ=>+sqfpRH6GF$>8Y%aTIvJ+ zzp}V@!KhQqp78ROW1X1{>H2Tz>b4T4=>bs%Jj-y!O4*q?o0M7=qG`qKJ2`TT!T(}J z%8VGj$x!GQ-cEb-@PzS+dnaKp%%#pc6jk-!2NUPFpXZft32$1fV07rlsVA|0)f|#* zy}YU-xTAH^;`Z%C#XkYk>_L-sw@$_$4c|+`BD9fAvjWq7!5K?K%SnqKf3p00MzF5% z?7;of-J4F0;uB%M*93Q6wJQ%`DYl9aoY7zrdt&i&lK~S9SaZMLIkMt5WPlH+(Y#Ve zb20k(o+rmgtZ2U5YC8kL>8Tr>@*wxGYjqL_>GC6^nMaT=>D4QR?6NWd0mumwN_sJU z2Dehjq^UkhW@vhYa)>7ApUPX?h3dJR<;wZ$4vos&^(%wfg)A8%0myb&XMM*fhtwKT z#vJ-gp?{Ua%wM~^I>69jjiD3Sw+(_LzUJc8ZSSD=KU#lPDM2*q)PN(o50G)kLm+P{ z(mjy3m;9=fNN=pC{NeYw2El`N5pxza8S?&c$vj_cSxgB~3Un)qbxw$p&9}533;ZZ690UA!(>7SSt_P-yz$ZBbu{Qa8*s2PRM z9NO>hkS=f!GmM#=1hrdwSR9Ja+PIZ0w$)-L@HvQe`T4i4?JYe$Z=_-j*M8Q+ouu-~ ze*AM`U(NKRz5Jmxr^UEBksF6Fp+A7vD+kXCEBSm)m`B1ib`u#B#)(&RtoSFaC{?RhgN+Qh9(mE z#TN15RA#L8tVjO&iR=rF`o=uG0EykEc7*67O5F-AS|G&wL_?KD7nmoFD*2VuW%l;a zi~B2c1VbQZ`9$#e`nL$=aS?-1b&IW^MAV2b1cbV3M(U|(R88t$sz*3NmUw$ZtS;}% zvL1HbeI1Rg{nRIZpi&FPWm96gU3I@)LX&oR?C)^g%eA*-`R>!z6%{~J`HjQd_RsO0 z=qKez(NZCpOjv4*qL0oG#XbM2}Cs*KZ=8K0S&+E&>Ef!f+O zxuBt?Cu*6$tDn9EIX3V7tjbNKhpuGaPQAD?f`3@@O_U>%c;shjdMI{Dt_ylOg1)<7 zq*e=n?>1l?XFn6$+l3YS*u*j}vT_9bd6HqF#rnl)hJ`l3>R2z5;cYU{ndYqic%f(0>SdL0h{&OBkO?L#)tF)RGVo8G{8^J=AjI)?N)4?fG-${ zm?`%DmU)}wC*_4#H%EZcUnF#N>{wiF{M}-p>4I=qx6W0=%H>}R{4%2a^40dJ#2ZQr zr{1HYd=AP>v5cSO<=cJ(%uxS7R~$i&%B!uHcCYanQJbgM?nXnX zsjIea6ykl<-U^1Xfd^A0qD%Pb(eGUQo(;hkmgbUlfQ1MZgz|L3TQ z>S<$tzT>$A@2Jj2W&R9~o6H6`rv^zCj}yRZPSX_P}gGXZ1NsKfMja`Fo^crci9}g5u^|SZqy>_vt|SVJh~OoA zouzoi2faXzyF`_Faab`CBb@ji%NR^u6L9-*L6SCPAM9r{Ln`#%u^x!HlKX8s^g-Go znr;w1!~{k;*znQOh+++=FP8#Na}4fb=@RRQh&esVC8w|nt-Kka-U{!^nA*mup3!i9 z9NbwbkNIg_2|j5KyoVktawu*@h*He&F&o6(SwLeFsen9nHA~so7$mx(7c1{8)6JEi zgxMx0w3C8UVRtmCz`%@sY$@S8JC@|~+tFv2t{u?}BN5Loy;P?NW>!81HrAS^Oclbp zzNXz6;W`^A1Ie3f$tJqz}ZwK5*i9#wuXy26ZnEeeW(kekXb2ah%J= zRzyUArst;>zG)&F0!V{f{-)_v2=E-6=mwjpuW5JX`+Yk-Ak8>I+pVs@1NW#rC{N* zaRL`g>XxxY#T5b^lJ<0;?@Rd9)YdmTR}I5n(fZ1=bdRXkihfUlerV7=OuPTFyoJC>@&AW zX(h_d)b;Rw{!&~j`pfAP37vwzC?Q{U&$;zi)8Fr412xmg#z}$U6 zx_!ZfBmr31^i-rpAQOyVHW|CDURE_2K8=~1D`7}I?gaI^dR!GdKiGNeOwsd16KafQ zy&kyxYEQRjXT3Wk=i5&%JSqG9uii5cwNI}rD{S4ZU>~6X$7#ihRj!!bVW;KmgID&K z!L`n{TP5lK?;oj<)F@l3w5UhLTfFA59N!Q4FFV8XBG~p-+Dx1-Ek@Onh|-vSBN-XC zbWR`b*Zl4_&bqo(m?DGm8O^b!c^esP_m_uv&h6%5?jLVN06%KfV}pMjtu1$vO@NKGRrtDJ+Ks<>B64s4^S%q%4U|+M z6}NWxXg0ok+33GG-FnBNHonE5sId^B++lcDd{UTN)~AOZTq#fyJcxYLBFWM=(1U_) zr(w^1RJ6NELP&ZS3u>_IEf7G<{%;3|chpX_QPR@P^ay3`#7$~`6sqtXl@WD|OY(2W zUtT|F&)BBQP)hIm-)6AsousqF{1Sv$wGcf@?2lSg2@t_&=7x&Tktz*+nW2!>&$A7tt|1-3?LWNc^oXNM^;siDJ?jDXb2dP4%3R5zF zo|N@OorW||#H3L%ir6fp?EgpcAo#T zCkkBn`{49;VEl4Dn3(BZi0OA9q&-RnTQ-|5>Lp3qRy8vHCE)PpJ(gCcg6o-HWJ;)* z*0H(d(AC=AJ>sRrG(?CsSvXV3sHQ`0O=pqoC8|eheP2GexQxuFoiX;IQvKQZ?fEIi zgk5KU(EY}_`CX|%O7A9xYdYkoDs)H87C@|-$>1oESJNtxiYV=*EX))hZ#We#82gsp z>2Z|6(q4Bpl3p8g?|kX4-oY7pmf^Ad49Ta5mzSgFuoWtbUCvvq zoJ;_+=Dd{Fy*--;5}>q|-7t=+SCi3f`^%@)(J~>ME_{C{e{T3{I!?2ARsbq8u8pQ?N4M9LnP4}; zFY8?~M{fP}T|0O{1q~fiT%pgg(Ue}AB(C7_dY5klNDcCCa$?fD%Ox3a)~q&-p*@a` zoTO=c%GdC&jX7+me&lrG0Z_@r;@W64g8;kY13ga%-#1Ogo zw|MK5HGmwR8$i|2K#!jm5U3fxveL+!rhxf7tsw1pEL_7^Bozh}oy#DGAkFPTS$JxC zP6VW%6$#?fva`3(W(Df$cq96wE=W3c{i4yHu$gaJ)BrLypSf)R3#fgw80m<&67}XO zpSB2=1iwwD^N2#$Lb8x}@kNw9rP06Ylr`Xgime_f?`Ye&tk-_A*Pt`M+YZHpM{gYS zVX0D8?ZDfI6+642_=C~OAkI*sPrZEp5Rctu*1&lcQ6(~I3Q5ec zn%r(^$(cK-Pon^H^05+{VjC-@BL`5|sVy}L&uQtYUWl|!t$Qd4=`pm9AfeIy`-`Gl z`$sX;-kH(bHEn>TLIUU)c&vd-yI$A_`IVaC~XA6eUg6T)yd-CDaHP15wJ5Xx?s!?*76TgI zJ|zE1we#CV!lc4nAE=Aou$jgoVJ?jYP|(=HQpLk=60635n&Ekou_GcMg_%cZ4acg7 zXd^Vt08+!$Nn~ZS0koDzu-anN`5LdWIkB#NOvQTT(=!tM(a9h46WJfkZqyqq=00>3 z{B&&0pQsTQNFOxzh;l^faL~ zby%ZWbxl?avARUxoVXcL?C_V(-OuhtuvfRYz3Ktq{#ewVaJiN0gL0%}%Rn|bV-^-Wwh&0w-b$R5c@ zyM4Xxw^XvO!46z6H*B{mL$iq-apsTr7lJ97Q7YCh?)?jl7or4Z{s(Sq;WuChINhfDcfKaPc%nCe*Sz1uT=1c>Yoj z(*gz3*u%TKVNtb-RMcHWSdiw&*Cbmwam|s_S+G));J`QzL136OZGJ4$05D8lf~s2e zZ0(dPSj1ecn();=gStxV<$b1K7(sW?-9I^cGJb9YRFRncVh8@ucoV4u~HdtTshZN-Qcjyok(YquaG_P-TA0x zAoIv~S}b3%mTf{%>Sy(4gW_SNmiE@XmfbEcED)7Gj!JVNV-aYM z=+0Io=`n)>HL)%ahYidu*miuf4SXtfPY%5^>tm$utTVbF9$0WA9VA%czB1_q0zafC zeK|_#*bec}e2N6A61ZTO<$?wfW0(}bXP%t$q-?U3ED&m4*=C6dRU#aIp=uO5T>H?4 zFk#)^S(-*OQ#ch70v!by-(caMxept>8;xV4y1@9`_|BX+IOU+(_Ki*_^A1m^@H0(OA!TIVs>#`Sr84`Hmmvu z^L?=dt-tt@3whNMW4x#0L^w1E%oUVyr9Jo65rN_%t+R}z8m`SL)u(Tp#cL%J*lyC0 zJ8;_)?>yO%(dhZDeHRolXwdbs!ZI@ZI@`Nz=^D z0r&XiU{BzxK-qUE>VG}&|1#p0)wv&a@*~h8k>rev+z?H}2_7ot{k_MEmT45_**=8^ z3+vLiBmd{@S3b(khgo=$D!3r~AC#2=-#j;Y%@b=v?65KVFdGck3xomf zR?4Fe7(4EKc0=d^;q2(;vJ=_97Y7Wdw^LU~4n`d!$GiS__465MP5LIi20i%t+$q{z zET&7Z{$21|s2QHbnRB2dayCh=U{aSkh@v=_t|7Zu+Oo7$$xph%9h9ot390*Qzf^>MjI{RnL2#y|yO{)y_x z73oC-)Fs2qjvCI=^pX{(da-OvQ{qbsK*U*rWJ>(OSNkoy<0gy}a{}8(J*ehkeYfcLPcVFkJMqo>_c^TWFxF+B}JqOoA&QJfyF5s}$SGWMDE+ z1rJer0JVHBRXZsJO@K5cRRU2NH+R^)l%WVa5cse7W`F6#*T?66BSmGewWE6_2(w%# zM6Quok_0DxY_x$9;DMsmXaTsp3$v!DuG0Ikd}z0VcVljJ9OP}?PViBeRe%N<@Btn9 ztF}w_^FF!_&zANT*nGB+b-$fIW*J&hK21$q!Y| zyqMvE?KmMCg|p5H$zJ}ki80n3Pu%sXh|caU)0}kcNsBh03}cUFdepz3DpMNzn*PK* zy@Rf-b%_DGMqXn}aTZT3>9MbWkOGD=r79Z7hm|N3Fmd=?jB!gtZ+Z;bI4$j_QS(Qy z{@LuwxF?2{jB}se2LdWM3V~8?eAr$hqG|u36t0ZnedfbV?_XhYY!vDrz?=7 z)p|Bh9qDp81Zxp!heP5llG-#XI_+EWq_(zPbV&2f|$$9((0G4$`fgS=9CN zaSUH_jGzgX;Y4mM7n91A^mgGS3bFljit&E|Gaj%GF%)Q|6m0C}YRPnYO}Nf>i+er1 zOALI^ve}~EE<(Dn5aW(tR4sa+;QVf#g-ZP&x1p1t0O0vgW@gXOI6wcVhhfL}ion|I zvv&1rM{9OG$LEYam?ETpfJu}o7cF23$ule79-t)7`E1$UZ5n}FL!N)VU>O{#hea9& zrM{?_<(uHm!3@;I#pucZ+zsYZi8Qg?MUJtc}D>I z5^?IRPHMpK@MutW{oS94slgqh8=oKHjD5w$;eVK?lEB4A!Sp$Oajb*j?5PUjv2$!h z{;~NC%i`(nM#h0Jc{y0zq0GP>^IKFE1q2?TH!#liS3QB7EcJjK-sI-lSwm)F$4oWV z8L?J$rZqOWb{wZtY>ud2UhZ>&ym>fITe#mpTYym{_}8IRlQy*-r}Y8qwsVS2m#R(K zqlmJH1>_%H9MtmAWOn@M&1k<17@}pESj5)h@_@KQBRFEo!`%m|(2`rz!a_%ZSg{G8 zS``1$;hV|2c{uw&dVWGQV&++`4ZcrC_cGhn7@Rxc9rz89?0Gp|U?6(*?4D@vSEB{| zi){FAHFl*TAfi_iUw~&DGRwXtHrFAUwH`2*6 z)QS%~*oqQQ?vj&I2A5AY#~MFcO+am*y3ni@S8$h&FR&L_&8ob)T14n6{o#}lDY$8E1XYkI`#huB2LS5QlaD4uvJ?NR zfSne`K_5}8Sc3ma?^C{9}uX0nPAZ z+9VC-zRw(Voa*9#+ojs}-|jq*M$T4n_xj0OWS90Gax;9}q#n=FNB}jo_pinC+2GdQ zaEiB`jGKDdwTJyF;XPaz$~B6fgly4P(_Q2*$WDY+s->G0;L8L5%i_n!v6Z*i6tUrP z_(mos^)TCvfu;9f##jDUxg7WAdN6spxft1#=3A!aR<&{axK0de8Q&KB#N%{#=S%h5 z6lOp@>dg-#<05E^wc5_^#m^;s&8SkV~rMl?bBC?Td%rC$Lw zx>6s^g?1bf&4*Tw_lb~6ZT|(1R&Ln*Lm;IFic>IIDhc@ny$mxy+`7^6ObiPHmr!Z# zi^|Bpr-L!mXAp8TvM?guDBhyP{B93luD7zgCG?^dr8Ywembi#}aQ0_=`H*y90JOO) zR@6id;_)+Fh;_mj*h_j$I%BwQuA75r?*3kX^-6%W=t ziJ=YvM!%0sOjC1+j=<}1T{3pfh8ik}?&sci4>-uNt~WMh!v}8Hx%vb*%VH^$O-uin zjNKfwfVoR(VI>PeN{?5lxp0ard5ufLvVKadwUmN8lEFKS+5ioGm#|O z7GDpk#k`b6Ptx!K){qzwsRYU%CA(&QqMx$PnH4M~T&Z26P@J;Rw%N@mY(1i0x6mqg z!-mP_oxtfJkmqQdKQwu7aw1@bVS4&cx)r3$9dD6^sZagH+fmdLmD7(@C#CbZ*LqnF1-IS|Aa0si@cA*j!%$k?y*X@f#|WkS%>|K-q+a0^3J zD6lhu7Urk!#2Gb&OOY2m*$vCz(#eQ6yg6@ft?_m%OGZ7&xZ}zqNQL#+DAJp@EyJ0j zQ1SZO!f>O+2vpiA5b7t`71X07>^NdU9>uGeqB>$Dd6j^8NO_m_{9(u~?55V1+AL4B za3)~@lSp2HM^g?aR2_?J5Vt?6oalq2urNguK4fk)&z0YLO+MOLcvPlD{4@fIGEz;n z>j$y}7utvT5YVsqPm_(jjp;TRVd`}vy9`pW$Zj3Xa#-*0RX#0!C;~o@>ObxjT!-8T$S0H zharImZQg>dUjQK3v1}X}P}8ax0ug)8KkM}O(MB&!?R-8IOP%)fskYxf|Hh7#Kp^)q z_9XW;th@D@^S|Rej_1*W0RxEE)}u{ce5fg{iL*&JBg`fP53_@__lYgr(EoDq1BaO3 zajtYMw^>^!%d8EpyfzG1LU=oNEqNU2uQdC2BM&skv$3Dv?ROI#xotgBG5>p2 zb+EmEq}*dZBQ98S9;czj=Tqfj{geBpamR}2Lk7Xx+dqSPZDUeAN$GfLV3l>r&j9f+ zowrP)6gyj8#&HR$icF1ppjt@~9Flz_XiQQX(yM|wK-``-6UtLXN4GxK{)60yV(X7u zBO_8ZMRolng!7veFS~aU?B7j(Km<@r1IWo93)X^(#q{P$*`e)e0&o&66ybAx_cY z%EehIt@S7~i{jn@hG-2>_IML#qgQC))gM`yZ}7OPBH3j-iu(7B>e#^k`_6 zpQEaMusa#;VL#O?5Dna+d*K~qN(f*(ypui71?VuQ$XQ_X>*h|jWg{Q>}5f+()v+T}Lg>+eI zO!#O41)#w)$Qbpw>{hBNnzr@*XWFo4nNFP^gW?(phoVEIhT9(Tug-@ZO8^*G-m8d~ zoG?JO6W#>D`|+zzC2Xokdp_H)ki(9FROFG{afk(7$uMJXuST8~PgNd9pgh>6twOHh zkDZ;br=0(d+5C5c9KedaOY5ufljlIGmQUrtLv5UKQK!K zI|N6Wdfqi+?*1Mgzh5t_aOEjEaU%y%LvaRE!{x-!%eHX^k<5p|(M)P7poG?XB8Ygf zxHMI;YD&&oD+>B7GYIWS^Ux%=L2o`%c;cP-ncV|*mdAdAm2{0Sp|EWK|18;j#wj;9 zbz?q$G}ER`sjIA28HE8hFi_A^bob-q`R<(PTV31=p7`v#)>D@Usf{LbL7B4Xx6^i5 z&&pZ-xF-JaP~|M68{-3C!Fwy&^qR3Ii7n9)m<}T@%(YWa2qq=<(b3!t3`oJ<#rN6Q z_rhJv|K?fn25Vf^hJ#ygUnzIkr2ZAqdnt6Sl?y_DFG%@)1y2`wUZNJ z<^wJOHSnP04qkoOJg@(Y5!vw_d42MnL=3_!rX0gRs&Xn4>|mtx8JdYoyAgGYLTLC5 z&mQfspE(Nvxngh5oRcf61x6Yu?~*0h*5$NHJ1MRJs)7+Sp5m^K+Eb20tVn4^C8N8q zFUws8i;4|cWe^NgPY4*4@t8C7AO`d-=GJXCAB&y5JFsEHYxdIuov_&xKOR@`#Ijg4 zqm9cx&DH;Q+z%6@uNkKo$=B@8E=135M<6s)FVOIMmc)lNVg~0>0Hl4oGH_P-)!4IU z=J0!0$2VMu93v%KjFDt*&l*XPwvET4G8|U6B7VsX5QSTfd;7Zr?(7QapPdi@?t+aR z5oyc@-Vf7fV!4>0jkVXOwT6GET6YD=ng|^;lRyw@WqJy-f&9F!!BhW*BY(P=0xl6% zaG9IdvdXQWG2`KfT1?J!KcPFrjy7`UoTAI#t(l_T4O7wD73UPN93?U^Tr!T2GjJ{_ zIuW74`BpXHoyMuD5*HR6bLKAVU1N)?gEE(oILQ#mLUt7Z=r3ciza1J0sq7MktK!#O2 z@akUK>SnxrIH@WIq@AK(`%YXshxSWAnGva`;f5q`@CQ}WG9$FZPf^9;T~V1m5kDri zYI#n9gw(P?Ng>dN=M3Y!P<$*Rhy_jtuG}|zizQ( zMUFG|6tiRPEdu}hAS<74u*cKw;0f6@`+)dVM?&v^$7T@`uvs9RupwY}is)ID~E|N3Goe~crn-}UKb&3{g&w{z)K96N;BW9ei& zr@RUU+j;cuy8CIP+}N($%j2%v@6rOwXCb9W&()N)Nhxea9@gMTD(2-3SM#$@Z`w1? zbeh3b_5Ky3n!Cs}=JQEfPDz^i-`R7JtcQPdwM-eWk(=o!`rM_0iEQC% z!_Jq7>vtK{TbKhn+O)9ooi-ONbvkb4)>Mf@vfE#oltF`d{Mb z4k1GE6Q-{`h%B=lmCY!!lvUJ~kFbEU>E8HwJo6(rY;Uj+#H4(up211o$a^P4o7pr2 zt@!h$<;1~-CMkm7U6!-WjRnX+2cRvE3NWm0Z(nJU--|lwOY#=a@DJ{pVK~TBrKC=; z7embhb;J)xA8CBYI^SIlY=Q?5Avu3rNFqWS^ZDuR_u*VE{)HVzGT-EwiQ;7il$v~1 z50`~<7dOmP62(3KFu3$$b*6&WY#R{saf^(o<*d}Jj-C*gC}{>EV*1Z#E&xqV+w}n7 zGJL?klr=o9weQy}eO#4`$JJ_W$YQ~=vat{9(N8&C`V|8#q{wN2gV*d0BeN%Lu!Qu$ z%o!LT5rPijNlK*N*+fT7%%J&ke8C{*d%d%#;&A4X?fsywM1s9_z)o$3crDA-MekFLkW` zd?9Mg8o&jB{a9MpF5t0Tq&bNndtCf;jh{daqB~YKc#q$?iH2Vlj4)S;G13BUQSUd3 zxz*EOim~KLy)i}N)}EDGhg&PSU4TfRYycbBTc-8r9snr)3clWBO}R*8MQ!)$%>oYC z4qRCb;)YSB53E}u1QA$T-bF+5y_Hu{0)c?!!j1}p;{d5!=n9!uMU;{x@EvS3m>Vm_ zfee;XQyYzozu?yL!zN04xsX9!myY8?r!p7IZ8hRRe4NswLP%+he%>`{4{8N zOSX14ZMLc^kH`5(OE0D?7h`rT8%L>G1h+RTEusVG(%5v zI#X;bb!i%Hm-2KNpAdj$wYjV$FM{9H82rk3gC!2X9gT{O28!jpzToJHN_yvcl@mFe z{*659>YlzdAe50ZF7g<$@XWAFtdaL!-4Ij6+O1w~p`aop}+#dC)y?7@9o#`H!k<%jNo4<(p}#H*pn!(5%*p{nyfwL zQpW?>cq}Y#xi|oc>?|`47xbz@Wqk9Ufsc$sZwVx*m08(2p`!E`UHMatTgR>6#S*ZU zX(ngrP0-{ha$Az!EwKT8lVRe;vw2`g2cAnF2t%Wg{%Nl|5V>m73OQuIEx=>l-h`u^iXK+Q5Tu^qpH~JrPL=o4485z=wxPh>nP`*^>~p zSoF+RY+@rsAtA)Sa}ZeaD+9 zJ~mq-X1&0VrHz0nV&aI)C*JdMq!5XLfDph==a~`I0{fTLQ7}1#A+thfWIxp92!9;E z^0v@HqGTryW%h5^X9^?!J?5wN{7k~><`i9b+J^Lw&!BZVlm|U={k{WyUx-;N;JK%H z@HYnNCz9pxT+supSW7eUa~;!_{lLl>i$S5rlhpv~KncX?SejiL@o12R8DbhcVh2M` zl3_p}BI<&0N(2#mALj&TP;+Z)0FhLrJ$$Go8@xsojt3Gp4d7kR4)X;S9ln5nIkwP{ zE`!rI&1i$2l*nGjBy!s?NzPXfX%rHWcI%T}|9;pzi3QM`$f?fSzIO(ukXv%t2_&&( zvMz-wy1M*5Qn(-l4(>3JU^j)M8-DjX==BTxHQ2+g^FaO3Oeq1z1<_;|u93O~`qb=k zW!QS!UXiMKX7PM&{BobD()IfOp?pB-ep_K!J1|e_dOTp89X%TC{4XAg+4BfmuhS|< zYWs94C0wCa`T2+4QR>7(!;|In_TCw%ql?cyj)8;ykl?}>3^zgYTfvjaT_m2C4d@=3 ze2pqdRR{$OAu})+L|Kp^{7^2n3TcjN2Vzjo+q0@v&3Wv+%(}5D3AUpY9AQ$CBvoc; zDwO1ERok^M@BXuDBDT6IP@z$jjq6^J`zl0zJ5x!Gm`e?dJ#@3Tb?+^D672Q&mYxLi ztKpemeM6a{8LSOB zh@}{~i1%*Q`s>oV^Z<}G;~t(X4XUuq;ENbMKLr4?eYv|9#)F=RV-KS2iDSnf>S{Gr8m|{b>4#g(i=cb zowz~=KNe7nD=Z7-&A;m-J>ajnB0cL6M-QdkM;}I9Sv#nNLsk;4i6kr|Hc_x#R9uGZ zLRlZ&j3_q1A@QbUcETnp1`!cF4}MlVZeO^ojg#K}J9&JC1&N}hh^lTEU#6!Z6vqXH z9F{buw-W(yWy2`J!NhQ8^nj0&)LA^1^R`#D?1~d_)e~z#?**C^ahznPc#7XS0=+OA zG{kNZcna>>pMed;SIEKchOnpu%DeehkQ&eE4}g&T5dWJ2urdV+why2wS)Ui>t^wg- zaA!7P&3f@~tebR`Om(~%VclYx&>p4=R7Q4)H|29=loj(6J-EkIQOha7rkHzYoFa?u z7xJYjf0JV@V^$;_&UjY!Ji?JF0QX{t3MM)jHt0NjtC0{z>7>&8=;|;;`j@G^{!%6f zvLf>^8-PTwFbUY90Ylk0&ting%cH4LLwyJNeVIJsoUVc#txjwKu1A2uBpjXDrBOl? z#~!yvU8-myWkJSC0RcJ`qyY&#{TJ~ZX(!4Zu76W;PVa^S^HRCZ;ZdY8UfQD8JFUlw zre};UaUe)IMf25Xp{9U%>>&;jANNLbZE*HnIS&?NylbBlX@Qo_`=iCyShZ%TRh z<4%_@IeD@On)Wj^#c6-P{o+rCgS!m-jGmf(C$1%k!zs@g3?>N=hX7z5Da##$msW&@ z6^ZvxR%VPDU@seedU}=Cgfx+Z(;Z)??w=93ULRk=Ow=~tHnLxPy_M|le7Z;2j8@)O z*4~+@;6K*!8j+tb6bLl_aGR%}Kh(>>g1@Iu=1uC;6GbInbWHH@bjQRSCQ+0h?2{c>Gg|;^V z+zHbiN({YC8RHFB&gien8VH4}o@6i%=>IWDZ4Ui_h+ju#x{J7tMZ={&Jop-aTlaIh!+ORNX#Swga{)S#@9Rn#G*L?J@)=I4LBhkq@sg7}?_=wix$ z5qxR;;_$k&MEm@wD&|{{?J6I>m$L<&q#JA?Cu-I1Rc~%#OrEV@I`Ver=lmkS(oGOx zM!a_;-BABcO;jR}F4?n-djxrz_xsNmT&5karM~`Pt2`Ici(i7v4eul{wd>DO*p~gJ z=H&^{D-~azZZ}burH)Z<&vnix-djPhM&hpTT*9Z7s# zptgYy%@6!rrzo9R6`LIy9gP?Go1Wznb);wI^!m}T=H7YYcFVa5N&M9j1wv(-8P7F2 zq}2oHST#j?-XKOE?^$8Zj=$aPdG>AU+Vg7CJ#ia4-|!Kzv_a??xvIf*^s4QTTDi~- zr2Rg0)B(8MaQwvyKy3j+PRdU#f==A)p|;ISLv2kQ)vj9(KK!U5_#>g`*pY&Cy^b$Nhwpz3R;E zkv_af&~l+VplD%Xw8lP|QLI2q4{?CGX|++g+P6Rr3HCBrbXRAcbFn9eiLST7u`34c zQ>{*|V4KbS!z-q@z;JSZZ?^V=Rs&3G0@XiRR`VM-ST&jedvuKg}!j0BieFV8f|7!#+ImaN!pP z=~|d|m=b|v`bL$iVToUf!VKv%OINydqiThFE92AZWjh(t?NA3T$i}Nl@i8UKh)WDm zbOk%OkiqJkic(+HktK}v>}Bz%&H)S|Q+yMq`Y?8;9&zly#dQy~!a#mP^(Pr|()G$k z&Pr#r(S?S7P!IrqEP3qagF=8_LX}1k?IF#eG%6;CYJ@;UeQw-Wbbyjc0&;bZw|fE> z)!)|~hqbfQQ}ny1+4klq62zIz5=%ARp^KXg#|i;i6(+xDUnxYULA^{wzVCu0TK|&; znC~x()B8dl)!?G`gqv+}M;2E8IVF!>JXp5;D_wW@T4$Ho>*EUgCRio)LZ4|+<@M|R zRJJg>!sL=L$qX65Ag(OGVeX-W76mC7xuka?WJ>uAc#2KDv?w27!n+rk?}br5tcR}opH=R+sQTq|9rm1q|$lc-Bf9gGWVgGoHSbFT7kEf?$9lmxi%+jTrArxjH5K;=!-k80TRMUE$y>j=7JMrh>`RD< zk_mp7WYGQ|0pcx;QJe~YQ>xj?X0D^Bv_zGUce7seA)YDKrI>r^*6Ta-&h%clApBQ; zfX+|FV!Oz&r{A=60-w=-aGf&Cj`|ztkp+U3Vd?~?-Xcbp8%O>=&iVh?daI~7gLYfD z8yaW`fo|NPaStvbK;wZxf@^ROuEAY8IKkZs?k>S0IDz2q1P|^U*4g_%>x?zlO zRrSqT^L-{Je`TTNefaF`r%b@jb!F85lBTH780TZ5TI3(twGw;9kXhrzCdd5?r%`PD zlg!hNP%m?MgxPQG#30>7`<%?1Edv!xBW2#lr=|Vdw7yBZM=QgAVWc>RvX3|QR;UzETzn)C6rUx zBhH`3k-0k!Lh`Age&}4O-{`q*i)W?H?ohe@B3rfE_Q%1up>R?QlL55d2*UYiGE zPJY{Y@7Si?)} z+LjBdM-&oEIR^floZER`uXeqfo2a%r6&t@+i`-rlWJSmwh~%*eSY)!UyX2C`{GBt!9paB4$OTWz<>w*ulB zyHB;lVbCGxwp2Lwzt!il#?||qzoIFwI~3*Ryigb6+uzqB)?W>m6mVfUnoY&qt*c&- zluu~!o#VEyluwtov%huhD#ta(@Dnk&C$GETnk#89TYr(@prWNS<+Z%TBHUREG4)dri&g>u)_5A5M^Vp5mzE_&y)E`WMe3D9Nw{ggfK! z^JY{Y_60Sbw6-{#8vY#bo=9VV`d3bgb%9N4h+P&u{C$YzKzXGs9iI!Jl#FCEe7C88 z@=}cvB?(u$1^1B!Is8j<#gVpgjXICd4_2W;qB z0&sS+q44(}mDN^6xz=fsiV0-SA)o)DA|pqVc6T)G`#w0#3M^Uw_)1yMPN6Y&T9Q56 z?sFr)>M`v7d~d!Pl~p#@-?}yhLJs&HgZO3jFg>90d@-K&^W5U`e$_qhbwR#y_udqb z0*T7vr4e{4Uv?n-d7z^?^%XnN`BZ#2jRc;EtH*P3Jp1=aO7L)PpsHm2`BbL#-19P0 zmg*_gZe{$e4n!M?F@*! z`Cpw%Qi+?mte!B)&+7~0}#d|k#??-0b7$4V^XS~u@LViIpmg8#rcp8b}Cld`= z!`Yayp%8HZt6f4q0vzUAnXqk;@7rn%zi*BjK{M2fes^*{&p!WMz0Z0|dOo-)?fn1m z?T_d9T{^qh`?Y5H_{$R;1my#y(HXcm>|?%11R((SF{Fw%@iXWKH6BRx3*Ues!0@VS z?o;NvEpvZP>5zqD;#ExpQ@K&Zo8yo)!q(l!6)Wd}miWt(&xDDcHlzoW9nV`&fwlFa z(VPV!DmoPIvl30*xnz(j2M$6(>Fq&KvR!KzQ386K{(+kFw_Qkwsq*VY!ACh1B#+0 zlO!~xHmC>*&;oR~z_yjJ1~4>WWB5mhVQC^KbFf=JLV16ivWfQt6tHeJ=!Tg}fXqQ* zzlb=Dg6I`O#~Ortmzl({Y`*kdSePM`(@B%C*NVYge& zE5Qu@ws!8d6@i6|Ol@D)c@M%=aWN$^vzbD&IgpU~Qn-Kg#^+)xO-0wJkcl|;I)%LrdH#OI%y-Y#D^>Q#BRDV5qn8Yw(7a^} zVDZYM;1M#6>)=O|?0cgu%Uqh*^SX!8l4-WKjd0|;M_`qj-*uN@%26DEifu{%X^Y_{bSQdz z@|5=c;Cn;)ygOxw{9iZhe_ys5K)dqt(qU@mF%4tiMPxTeC9c@YI;$TXBTXeZu5`1! zGX|72)akXK4SwV?qC+^gMPqhRem&o5Q2Ms_4s*A4FzpW|m<|roA}en66BMY;`}i#D zr#GWvtB+}co$?n6hnV>nVGhMATv&re{$g?@2`LI2`LN1t{BOyaa1kbD-TC3rNFc_5 zl?D|IL7yzpyEuo;h{0kV12N`O3Iw8WUyi#HHX`6{Ws7`{-)b?c%h;u(4YzQ{QNXEvS zLELsOx#sDp6e`mluo9!&cf+oM7@a(*9DhxcF>q;6>A>b<7(v2DN-YORdq|4XNV`N% zW{1eDjw4!67R*-NLEV!*wP&{cAp`&~xNqIi%8I;=?MK$%p$LDL^&<}8sSk}59>J}eewtSmkmFaBPVga=63@Y8btp2c;_WJeeobke3SJohU!3yW99 zbUlHO?v~<{=+Q|^0tdIMnz3AorrID>iy<)v`Ik7z3la8STI`M9if}u*T+r;QOLa70Xy!yWR4XO{IQ6}K`}f_*=NDO! zbYKbW(OY+mF2ySQ0%aV%J)S>r+Ony?4|nc2yuEJ;`bqg?*1T^fht>i18LDZo_Hp@) z^Lfv%rd$}hc<`qt2*cLjHS{Z9v>g$_)|NrJi+Bw>?ach^mU*)q!4{1ISLCIDVcC;S4oiTd6~su~q#80k;J;!&Z2 zOY+X8dz1#68&UV0=7+1r((u_C4ilX3Vo1M|hnm0WF8Mayg=B?wCl;W5{}zIose7&Q zMjY|<+iLfkvWB+MBv+Oyk7N@Mh=ApR;OOrMX&I>*LN?X|U62egu?IV=Z~)9E-mAs_ zNLvPgxCrh1pr52H=CR&3F!qDGIhUI@QsBk#MwPH04@zBYI!R!E4vuT^Wwu<=K)O`q z{F#$x>>WgHS{tbceU=4nt#9V5?kbIXw>JWRE&(qn%LUg@K~}_qvWhAE=qQiXL8!%47>UC0i@o!4#Iz-=tl!l6{-X?i{o4QQOpF1bpOl!^jqoG5=+LY}}3-LYe4M3CBE>CC$V>k6vNr#4-eP5|ZEf9X*+} z{pClZJUwKDqW1)Sa`nSd&Wti!T5{8%5%!yNl9K`XA$LQvcmvx+VC-Z0W^S-F> z>k#S2Ar`V-znTcUwqwm0WgI>xQyS&T{CIe;vTS<|y+6FG2sjd-c*=Mo6qz}dFWpPD z^^2OQNJF&uvP4`?Rvf9P6O`#iyMq@=-Axr0l+0s^!9<)KuO@_w^bwSwO=282)mC_E zcvW_5kBI&&%q(*oPIv9`@hU~dldO>f`($dt5CK|uvGjFVZf~t?G65$Z8JAj6w4R0R0xIOuk7CcR1>=JTbrJUdhgM%2?@pyNOlmAH zLM9Vw+ks6tt;J8nNTjue{qx)F3&>zj49H;UgUa#;hPxEkVl-Sv=6-}Np<~)=IbCG( zQBe4gvjknp#kv7TVBVK<9v@P+ zbk2m2vgrPqC7IrGXjQvdxEngk1h#gHkbK|QDh?yA|Q-Qu{ht40@kl@!2uI<`6*egqi-KPea zqE83FiL3|b7s7T|0f_%@?&C$@B^KvcdmIb{7a)l~@pYwsch~i>$y;za>PYUm8aZ36 z3oecX6XT`EVeBM`!ZaAc+qiPIAUx3#;Y>D!FIPl!LKUaSI12K+4s=gWjzbJKEA?RvWaRpvgX>dJtnG8dr&;<7uMq zR>u$_!D1AI4QMntT-O*Y(f@)QJ$9q@Zu`2?WWaOgu+v3WQnFX_H##yH7G|F)FL-S_ zZt(Hs%VTLq#BE`cc~!uPk@ncUDhkAMGeZ_L6O1l&^1v0VqZ5M|8HtgMcyF-L6Uog=v3AjfcLJXgF6$*=ux0VIQ|GV zrOaD<(yxLa7X=+jyTRCxceCtDd&_()e|k!sLzJ}$n7$zOhJR-!?#YHT8Tr+ODn*6^ zZNb&;Q5=b1Rj4HuO5l@QzgPd(UBv^e4DjB+Ex_X~crWSmCmuj&B9RclC~D!pD9>4p znoK;x#BranL=Cs^7O_CN(BobovM4UGK{@Vea}1PFId7?3^}Zhr{nV-p7TNRtho;|g zbf@p*dOe&i7*)I)X%8}lD!=d2Od^2)EjqX){iN=vS8u4hpv4VT;fin#wh!oQ$c~Y3IKHgMp!4N3Owee#5(!!sUx={Bt0t@BGYFZ#txUo z{Ox)%E+o9r+Ey&+&QNJTE5RC6NpCR862l=2LdN2G)dZqMvw?@saZiY&;=f2*B*IRG zUqp23Yy4Sd$VhEb6t20pXC^3Of*{l&Miky4&|y6I3qrYq3qS^^0@w*NQhvB;Uln+M zFuT6%nVx@aDgU7pN$LG(_K;6p-!s28dz|6+37aoxAbi=)rLllb&v~8Dw_um_tD)MQ zWWHtko#B^2z5v71>f&5%2-iE@l&`A`JetCf7v_M+wbsi%V?H6z#sZsC_-&U2AqN;& z;Nh5m{6rKzPWlAmn#bwva{q9bdK|Kz7R^UuzZl8M1ejJ$Qq}}czO=}$E}_RF+%MK5 z5DNuJE?H+|wEfBY-VYmBw$%N0ZSD@$mcQ)zF-31*nmT*dYgY$!$;XofG!CwHLqC{P zH%Wa~RdvYXS-qPpYxb_E;AAi{Wl}#MI+$b~ToRpBI^bQzcaW^VYOUsfWc%&5G}g&< z+~}3A{M^`tx16ca*KWs8_#=1cdkP>pA*al6 z&uH$S6yGEN1tpHQYbcgl)aZimz-~h?v0J@}>PPD?0!%o;ZXTM4qyZDl1wb5Y{0q!| zmG5A3Jowwq_mEON2Ra?USN#z3xz;@>xqU;$O~OFP=dq?G5n7e<^!9003xdK1gBiin z((!9ViS)_WA1l58;}0~jk%I5QWeVaSaeFn3gJ%+1$n)kp5Q)~PEUu<%6Ypv%06umm zRgaoof)QM}XlwmdB4Qz)*NEPj$4?bq_X{UAvQ54};y z7^o0!?MEBJr9NXdXA0wwdDV8&3)enZ(sxRI?8@hhP}{xwzx$3$AIpNOzLUpOa?!gQ z=8DW!5$_c{xdR~Der%*Rae7Kk%p@AeYrR!p@2N6tPyWyCZAaapPPAi*G7#jIL3`qW znwF-AgU}7E2?q1b9>_vYMcHS+b=_AQ;wkk1S%~&s$A*Jr;T~*Wo?Gzk8k|q2Ggz@QBYcbSl$ckKou;@X5s#DnF z=*|xwf%HhvKhyCMKpR9PV2!U=L95IUTobkCAhf1J*$M0<-Muu%z?jTt#Z$|Q+8gMU zRN7_h(8z-*SK>~zsjqbC`Zdr>rE==k1$v z{*ytg5$mUG(Yt0A8(o~_pZ}WN4r`U(+I)xg_wR1PqDGFsp1}*X$KAFIYDqcu?f%(W8e9x8*tC6az2!;ZTK!(S z{Y7{7>Z!ki#IvDTjh6Z6S15oEYBl)Lkf^(|a*2$=7vW?66|_dugyAP)rb7WW*j3to z`$x-=P-o2%Yi)QStv%eyG>655a@XcsoX{vyg%J<{h6hO*F zxMK<~AdcE=75U~NHfAsa$q$U+m?)A5A=BoC;QbzeP2t*C? zl@5KH+Oal8AR@j{8v|}Eai9YYjKm!M$?h%+7r&>*G0zw6MCgr`1L#pAvgjEo?;!q~ zg2%03G?3#5854E8OFdu(Kdt$xmrU1S}SGSG`4 z?aCqBQ?6o;Z+$#c0Hylk4@hHQ8b{HM#8|4K2r4ZRx6F>U^e@Zz?g=Yo%GPG{+Ma7D z&dwX1=oPLOOR-y97G&|kU$iYOR5^fK)%@*7KmzBvn}`%JKp-m9N(PD%9`lKrn&aqE z*2YI7iH+$$S%A}Aq%^`6pwu9y-)_ceLn~3OhZQ9Ub{qApw=Jjy2B6>c95ouy(}~!L zbYmxW!-)ge%H=LEd`Q3-_M!+3Kk3&s)+xb`%iA2q2bTAaUN=Q4Mu)ajQ_=63ngcT5 z<;YYfsU01=zQ|MoP6tB=2fG63^R%z>(}j6CGe!Dre`mC@+~1lyjUJGH3^XvvguK?Y zn%a7%{sR*oZ8cAU^X$okpXCoLX~Oy*``ax&Ws-p=QdGMiMDD4Icr{;6^HzTfRECD% zrANZPpP!3ssz(_NCM3e47}=~A+aSOCHc}Zf9~2mRo}g8%^{>9C zAKNINh6y`{vKeHIjy`pu_(HJg#kxP63hb_qiVmS`h0^!ZIbqa>IAG_b(r|C)8fbsa z6kPH7`%YJ9Wd6z%%kwaNq#!KxOcGFzU5=K{Gf;hv#@_#WL+@((zG<*nxxfW+owiXy zKF+RA*0X?9ET={S+dY(ncY*!k!FhPMD1XpnUg7$qI7;mjv8(&sVk!EYJFRXUOIApX z4h*bw2@x#+mhN2Xv)(A(Ie6Qh=U)f*J0!&qZmt`VG!=cV2ySJ+`k1=Sb%4!W?pHF> z!i;u9H)pjzd~Q?VN=6d|buvEbuAxd-Yk$Q!(xq1u&p~mK#TElwNLs%}>Pw|rbai?@ z3~KyutMtEI(@O9P7ep@3o(}OTZTprgDu5?hCXttmLidSP^5{ zawH9v`p_g(wn#a%5Z(u;(Y0KeP~8RO`mm~b*`nNtC#Nkbcmwt zb!`>x4_ecIx(z+?I^yIO+>HR@0)L%VW8u#J?T$0@RbS`$A;ak8ND&`39mxQc2y}g%D1yDYA>eZ39lrCC!g#9cV zrl>}eSPObEtmU~^K$kb5r$?&OoadGw4@LLkqh`ZR+ic49?&Jf+03w=@Y3D-Q#1h_oMJQk5)i;CB{}ndGQARkkD+DsjyB(w0&swmlG`Fbs2e< z$|%|F+eK)oNyTGq7YoZO<}g@rhwP z(qvSo+O_Eh#iY9Mq8v%k8qcsShR&f1>ua#mvQjyzCq1sQalWEccwFvvO}(q>Xm&6W z>rI4AYvCGUs93Zr#X?39e{B!T%5e$`nN~f#`+gHsQ?uu2IF%mzrQ__@%xs( zX`58TUE%PdB{tN_TFXck5W7xxbm!AVVLjopt~he!3Dz>cEW!VG+9Bg^^PyzcI$CP% z+pHI~T`oS+v2&YgKz%^aclixaFTAD1;p%jsoe(8=Fy+G5*ByuJR6Ahz`Ulj@V)vp{ zqjr}t_|I=|REmFP^pcLjPBTy>?iDx3%61>E81re87}gw9xry&kV0cX6?b5^82E|aT z)@1#b4Y`bS^P}jkQwrrKXDj(KOH67hX2aTAlQ>9GFf?MMHzNTwtgXs=0d_?K-;j~N zJ-H?i2N%(<%ChV3n7V&L@}mC?l(`c?+E?4vrbUfaMGwk0w-& zyg!@uq}{vnbaQIAN8fv<)#YD1KYuj;#Y5k+zSqpt#$D4x6v+>OS~o--VN8Xf9w}aQ zH(Yvikwaj=t{Fk9c&y5L1Rd{dX*!nXA4nND-*CWurVzYUTDK@~B8BjTX#!@T8`gG9 zqAWDQ1l7MohK|-HjEPkc{Cq?bXN%&Qj@KyQ~Qg_gQ9@$fDw$#IaC4m zA-gMH4Gvc2Yzy7R(j2eWIwbsI(yw-p5I%9((u)A}3>=;;dQ_a%dL`G+LC=lfu=5ie zp;iVAa(3L`Y2BaAz-qQjf^b{(!+HNi=gh6g!CZx$o#G8NX|<6kON0~8a>VTqCS_l* zk&D3?QEZ)d(glJ-6Fe`Pa=8J?{Bn(CkLk>vk zQjYp*WYiE5AH$K*w>fa#+UnC@VyGx!E@dF^Q{_+mXo5*hWcX?ZhXk>niv5L2WN$8>1&(pW=wLFMj#4d>q3aKIN1NS(VsLM{yvL{`S`wb z!bY)clz{(+dvC?5 z#ldnxML=2@2%Zeh5&SGH4Nm|kR@D@-3M#2P8foDDu&kE2(iSeh)6xIqni{hFIt6F> z$Qk+pIgZ-(QB@Ye3E-PksD_HeU)8muhYWQ~u^3|bH6MA<#uw1e*#a7Ha@5R!!n5z^O# zn;xj!&Me4&s%qVAR}xBW`;0FJeh=Tx8Ux&^ktYtowol&Ey0D7(QsW9)KT~;{_{kOe zoBIr4(uXN|QYudr;uQrz@;r=4WTtsQOFLDbr!~+KnAZ6f&06}_N6oR~b3pp=+mCLN z0%Q1L6xI6nM1b91O7i5|@LB){Cs?rtfJ3aNyBC$H!-iSM5%1lT7u|y;A~XDEsO+)T zh1>MiFz;9r_V7VcTql2UDcKk;mX)MH!@o9Z zch_o>{o#^<|IMNy(eKxBX#e%H^@dM*Mp^R=-jQ~OWO=Ghz#d{@VB63detvgVp)sv{ zGOTR7xXb}Mp~;3cxkLF0)3tK5Ehhy}1n%P;&87;S0s9EQvf!?_Md0AY1fj^-S3~ z?sJt<45ECT;XkR+zxtX-%=qzbh{P?4qtd413g%Zv5ZHY?B3Nk8h)*1apiq*7#M;mb z3dd(;A^9<3y>BO4JUe#b?ZzjmG5J_~c7G!3@g$|?<6Qe_GNgzNKx)&N#TCFHLSh-y z&e7mn`|Y8M^i?%d16Y7eoow=licd5UjM1fChV4LFmqDk!G(tIX$g7jxf5z#*7-M7Q z75pOcB;YE_>YfQ$^Hu1<@Ye=Xn6TJ*<|!h%%-@)}GjyCVW+SHhxEegQr5j1fU^;qC zm@~5acu`pZ_Rd}5eIw;Peyr<7>uM`u!uzF+*{5yt+G06Uo+}^mk5V~M&fEU(dYDxDk`CcSCNN!#|1 z_P2s*gmDCs6Cw61UH+P6%T@7cPXeuFkFg7aHOXEz>6yy=WPyAyRG#U6^>L4%{iFJ` z(3;@nm8rwNTR?LsJR!%UcCITHH&3PMBizFnvSt9&R=ZWyw)~hZFf(3knWdgr4{a5hLhb6Z=wYC2@#QGoI zcpJ9HW>`H#$5>0meSdFugnP#S(lP!}tN*w$CHfHk5`8-HCT9YgH69c)6&0rQO}hxy zzHdS7l~)S49Jo?P#0QyPhy=}HivVS(?;*UviF~GlTX$5{I`3xP@(&DUCH#x6IVZCR zYSOByIK&^(4=z*ZLcqoXCs~Ci)Dixi>B>moIkhli)r<#;dgzgo^M3kGw^*jW#>{-@ zgSkgZt5Bj82f;(l&TeY<`R&?cOVl=7^f&9_cc|#iaeG_mam&+j#dFdN$?Lx3d`B3H zv$AqLbY@NTBboX)PA~g@kB=$ok8Jr<6#ygvV|b0XBvIbfMwiKF;xmvK=oi9Nrs1q^ z-eZipk6KwXIVrntqBeBJ9*u;9na-{mTPhTI1qav?2Z-#Z(|p!ki$( zk2H>6k=|0mYAs_Ye}>%(2K3)pR1ABZR`u*w2YxpF_VY!wJd&D)YD~K|9O!Clw=4H) z*Q@RZg{Qtxr9ZOlB(SaJ?(X8wu~*zr|4r>a@9e(0nvP7E(<@}&N`_gB0W`!vQo)ZD zg)GZ|<=?*N&sR9g=CFeMw8M0|gaW?@K*wzWK79aXRnW5&MTiz{8s zjj5$CDNLS(@BoM2?c@2eoFt#7opdzZ=RRKyym`Kfs{#eQQD&ke(#+gEf>VKUF$`IZ zB2tW!>B&RvPue~wxf1<|u4p;T8lCKT$$H#arat705lhOCDV-7pvKM@{FED7JWTr;R z#-7Se3Ef4b*IX z9?p{v1QO^X16Pmi>!%#T45UF?%xa;_dxVkSb>`+>SH^{F*7N4rP5`UGsNHn2@%HNk zC&8~}sg%6z=`0=wuL&Ap8-O-I0};KqgV0B4+QP@6fHgIS$~Ub~wd{9fcTp2}_7mdb zWG0kn3DJiQuSB0OFBb+Md9Ah(IZbhq@sLx0$#e3`cyQ z)t#Q+nK7p5Tghg~xJHZxaGjhZ*W84E>cIHFIrjg11n5KCF3+}K`&nYxwLJwPuH4m` zh!rsWzC~~zaV$4v6b6B4%ZG9qF{n(hR0V!GZQ-krGE4FHZ{as^D$YTii5~C*QIA|D z5Euqz5=sbgD8yKv$+FA&XN{UJQnDBLqq25)?M{nCnMOhhj>=^GwyBA{922azX}&1= znH!faKbesZLX2!7*H1-X`z|&Dsz@!@PZWR?pK`4G*?LSxRZW4z?Y?~W1H;$HB9csz z$Bo8u(aX3T8#aNd$~J z8mg2xW~E}z^wC2d1Moq4#&ys2HalS~n5YmkB)(A-VOmJkRpvm=fkY+QvjvMUkNt#% z8uV+samC&F-`a!gB8-k847mERb}(}GcOa|qVbVNdv1}~UMZtz!^h>+ClRrtuD?TJt zq`Ba~k%xe@eX_PdcCF;cI@TrPq&1P zPyUT_k+Aj?~oRQ z_{L`4+r^06fD)GWMlPl4-M`wwFKK^Sz!wA&2jnIxD{7n#b=F{gCENXrkjyu)ntzFE1uP~1&P}A z6^8fav;E^?KR9&CCTi9FDr)8;44=$0BO(k>+C%Ja2Ns|ybQiCApl`73xwu2xX^c(~pFjOP zxnIYL;f?WCmj2nTX93u1s%ZCE#N3?WzP~WhyfT~v3`;fK3tr)4{6Si~@#3r@LFAkh zre%S3yH_KJGpS){0ApMzaX$|cOvoYP+S-Z=K*2s3UR=2P-a-q=n zINShRsB7-dHID#EOWAVk56k-7oD!Xk9Kgit4byWJbLFxqK&YgbbG6?a9^!8hR`SFT zg6_ZH&X$YlH&sGE&r@ln^v1~I`f1?;Fxk8&?3Iw&{H>_XC_&VK(H2e3)Hln6%7sq5 zJ2pNjEZLQUrE}U;jSkxw?r3xNC>myEGd*^%%3y>~;g$cSNp0$W|7W?-r&;lM?s*fE z2L$DG>pirh3CNMIIL3x~}JZ!>mt&8#f{o<7a)S395fXuT#Q*X_R;`8fPl)*X7 z!(zIqP{7Y~bacfr&mL>d-L6pcH)C{RGul=doazPj*15g3a?tG&ST;NRPO61sk|0L{ zF-g33rKQS{sh%L#H#OwPFXljPmz(!;7>bHabjosKbX0WYIoWumY2K#j=;$tL$d(*r z`Lx)SnV?vG@AK2WJAe8DJo-3?h;Mie^fk4$DESa199o!^W&0=2@5e`G9W@rucjni~ zHx@sb%U4KJ`juvH=O-%;jwpjvGd4H4Gyq3~3#6W%>CC#Hq zjKp+w6u61v7sf=5c7?8ob#Fs*pZZbkj&QEY9=w!m8+3D)n1u$v3~=|=H}Dl^g^^|-ZRP8Xsf9w zNhxWL9%|CS&0e{mZmEi6LWb@AE7-5KxGfW?Qj(T`HoS&g*(A$~eaGAn&>CRmq*G>O zrL@8S6h%5WoMgS@$0*4|JWH(vnsH>zV`uuD{dLx|<*Z*4h@|Ml`_i0ydsz=X9>PNk z@9!JhM|IdS3F7ViUi$u3BK!PIi_K`cN>R;~>-rE?pOWbNe?!<#C_2848b8=21zz{g zZ>vgJXI9c8jveluassU=z+zB3y#SX(;4ogfAv+xqj$LK@7Q1nE5&i~es^*1C)8?$&$ zzNhT4Fwa~h3B{c~AmKa*WUD&UDrH>@xh2WG=Y4P5Q)cc0TBamv?v^ktO1NEdFk8@u{D*QcR4cFZIkol9q_i zMU9giP*8Ckh!Yzh?0j&S19;#3>%&aJzY@EbbDO9;Pv%ojw(7$CvNRG7o)V5Me7EJ@ zq(if{<7gr^qtuKAT#TvwJv0|w{L_Nfjw+DNd-GZMjcCV-w9hc^D$Sbx_gwsHE+SkI91UdifwZa-7}HA8vSI z-r_&=doR5#8 zm7)ajQcV9c5A9u3u}2bDB3j-&%;)VmUs$<)u*BVHp*>iAy4LTwoQ!OLB%k3C77-Nf z0Bh51T$OsBP>Nz;S%2fLT=~xE%gI!4EKH_N2oht>V|VAOf}RC7R`}l8d$|78M5MP_ z0N*lRR+#|qt%7hsG4BMXg29PTlCPn*YRTK628KZI#0i}AEma@T9LYTwaUSOv;c0Rx?96OJH;NdvyhU0Z+F=#Xf`0gyf#Juc|3HoxEgM8R2!mZZ;UiZuW5a%yVK^` zatOnZ`jG=%>pt-8W0d~(TjpV_&J<84fdC44*I}L)v^vjm&ggL%cx)eNA@dNa5#u$u zJ5~8v)h3l|DLB5f6}RE*K)3$yTfXl1n^!9&m?i)0<;!5=OKHwm*I$jg>jP~H@JN3; z9ZV2alybptsZ!%-E^g*;XZ2gT+mo@;rU|h>H89lY*J<)$P$@Gp@x6`K;11ahH?!jU zvY;-eW%Ug&_B*W{P*JWp9*_ZMhFL1*x=`|{?vWdTP{g$~heaffk4$)m49Y^^Gri7t zT=@}?VRcT{7q5P##{^`8nM0ZA1WstbslPo5oB=2l3eWz^I(q0rbdH0U=@S6vIC)rRBM$GL|P@;DP}CX6fk+4O<_P3{->P&T4Ad7|W=@AiQd6$%l<#2?V|s z=yk8u!T&?mS4K4*hi#AUlm;nj=`P8Uf^>JcAl)F{-62Q|jAnF~Fc{K3N(805;obY3 zC%^nZ|IW_Y9oKyYh?V3MAVF%y$$Q3IgQ0xhTLMU)h0=I~If>jKpoGaY%8-^GyI;If zj)#b2seVuc*GHleC?+6ErG+UI$`K&&AS;EXl*Gj)F4kr;l=s)Vnyx*QN;cpXnH(iK z^O>B?|H*gl>1^)POO|Jq=f~PJtgbE`KU*DuD!iVR;jRDe^>TVH5bNh{tni}*qw+UC zJ-fn|VQa9yUOm1|(ZFDL_u$i7zs6Q!vpeQ74?uZq1Gu3!Djmdy{2BT4YVt5 z{aE9Zb)D6cDSOOTCTnByy)co)?ekRVMePtI-KE8!o6%`D=;+px;F3w6)2Dz3e^IcX zJd}8CLa1$P#<6M#U223c8Y%xv7E_p1R&H6_Ow+gNQmmPsno>eNzadn>pmSu4dXNpi zBMLvK_KI@U#}c#%jS(K_&bI$-{r@op{Qv%6Ue@wGQ|m`xE!)xd%O?#I9$}H#w{Xg4_*2`XR;iBey^Be?wkR{P+>0u`eVlg}B?C>O1 zEY_UKO2yl8BuABB6hWR+3c%>MOs`F-q1-4~c!`nblWQ-K#3RjW;+TkB0%Ka>VnOjE zDH}$ojbn*q5XiWI)z`fPSjGfxe@OMAYX(8@S<)D!>HH(eU{9lv#S948fV1ln?;Clk zS+55YoPSi#QvS`t<{epvjA66@aR&W@Syueh5>aja4Kt#qq%AKai%nwP$5L4~%u*J; z?3$7WFPE`he|;SQFwFxxg5T3pNE7F260Ni5Z*OJbxQ}Gcs7P6ss5vRqWsjN}OK;L2 zxc$d76-cXjKK;^WHub<0p!Kg~KQx zf=vqj@TEI`uOJarH+~pWEKt>S~T5q;VnT%Q#{BVD9hYds|g9z0xEVy0F;Uz!r z1=0dI``y(L*!#b`M$z{Vo8uTUk&vBZl*GpRo2OJVGl2LBfH4@-miP!w`;4MWQdl<# zYldh_AB$oZ0trxwtais`Vp3=^jpVL}^x8rKZ{N<{hs(Z{IB@P#rQm~VU+G`N(>P!wXF8-xLG5P6Lt~wX)I+r2}-e2bP+kp zs#U*bLxEOtL(j+Oi$7V|E1Sg>_=Y<3r_gj7eca3s34toBL^kf!Dckn^)Gn_teg3yc zo-cSIA+Fa=W`nAbjK(Ecd*E$Vj`m2`X}93|YPEt@nYJSZ#VW;QWq=&R%WLq<0c;L# z$SuvD4%0;OAhLk0$Sm~j5ns8xxH{``ZLB{3S*wqN7K!`4!1kxVO_@ynOAnay?=QDu zLS*oDD5Z_F(aP2~#MSszvEg{@2^&(vC#9#In%!foBK{CtQ(asCi^cc>0`SRAsF6za z=$S?r-L;W5SM~p}0FQd`wQ)1Lo-p$=9tqa8juOu9F@K-1w}VY4QaHYZUBi>AYt-L? zjF3Fg8#1dT=#Xlv9|l}k6rETv}3-;&{`(K z8(Mh=3mvP>eh?zMK6^GM8-cW2K9& zs=L{$Xtc=FldN=%(#rAW@q|`qB5YL#THq*n?m@m#@&nG5Ifl}r%N02*=tYgKJowyi zByM4!QEVT;qUm!AdtG@f;v#{BhZoM6r-b5%#r*Cs{Wqejlk$TO7(J`9}e zn47yV`AY&i?5v87lkuZDtY*goPs%y)vjXs_3%cC{e2g#V?6_{cM-0KvSrD)hm%HMmtq7QFRP6c~A^h3S6nvKGKYUEK~;;F5_ zefP6Fr9HBK&|kHR`T4vAVG=1yFTwCN!ds`NhBzXY(db7d&4x|{azU@YvPu`qx4^UD z1bn4AKQW)>Zy9zpLEZX-kllOH+?-}ZZ1%2$?tTQVm0a}}e%IZQZGC7rfIvi=9I(j8 z<+=g8UvTYtx|%s3XTHtUg)m8YHgyTTEE<`;?wmX;^xe@9Gw@Vs_B>L$a_q;`ydK5- zQR*?yKM(oT5I3RlylbIDEX*pwLPl2vA`akV(0+Wrtqu#k$use04M@ z1z+s`E`Go4do1Rn&*vjRj((nYcWck{tkCA~LB~J8cmF;IMEX>KN2Z3{yIb8(#{aH( zc5mHlR4hX0GqfC>{+M`ek#O3&{95z|QB?*=*D;S~61w>+0?EI!4Fe zH!;v%@cnJuyls7_Y#=k!PXH*&l$YialM1U-l(l$QuQ?Ur~+`klU@nH3=NQ~$aKJ!EdUyM|mWw)N={ zdEf6m#dqP6)II)w@toe+K43;3Vl^zfHtl=h0i?m+HM6T>Rq6Nz zkX?zw_^cV>B56&q8IQTr5^7#-7GWnbD^>$Zj6K4B16%Ga?u^XsT5C}FOB~UkA2FiM z)ia&yM{MU`8k<5RTWbnRkwRlpjE`nAd!Ftw*HZBja-w?6T#0466EN#iO_@HUd3)*A zNv_N5{n{*^AE1K+WolB3=&1;H5XfT-HtG7Fi(ga&ld(Pb(8MH)_Et@VllFP7w6`lq zy>-g}UiR%vUpvni&7O|OY)p)BLjQ%iZmu&*QJNT9<wSQ^QArVxpsMDhBbCp*enYrGy}QA+0^EJnr0{yNc)1$R<|sM?5EDUNJ-TN%Mh}z zDAPHe)K?;hbo96wnFK|L5LYz>h|L=-06dULuA}!~^6L}Lrr+hmZY49+&uQw$nx8B~ zt*EfI@I96o1y20nAA`ijoO{ddf{=%!-{v9F2Jyeo=ws}KYavaO?H^e?6Nu;$CP+vC zn*M)pu5UMAuXZeh+xzsgtM_1 za6?Lu%h9g_N3wy3lx-&aEO$or>)uewyVAaZ`@D^6r{SCNk*Das^Xkj<*ZV`R;gjtZC~KC5&kfWt3}farc^qTC+&Cf2kf{EpKTach{xopeL0IX z;n{ujXH6|fDH{~&G~@L7XnF$tKu-{VJhrFeEjX*jHs^Y~mctS$F*HsiBZ4+P&9t+_ zNN=PkP=~Max#s?HG~PX!lm6~|G+%t_Ht!spmHoLKJy)rUCV?w z)E4H-4*)ozhLRtY$!;?uKFS)YbE`B>=yfhm2cE1E0)Yf%^z^C`nMNrwhSGL?JxpaD0c8o<7guYzWYdqN2u%3OKeJQr_au-@r+c67foRoe4h z*fDIM5d3!(nA#+7^oQkd`Py2@jSn6aYG}`Hf=;j*60q4sQtUFQCfR4cwYZI}+(C5H z=A=osB$YA?7gpuMfNd8!OlVH7VnC)gFf(;ZI}7#s*s zXR_&aqx*^dygZ!S!;g%DPy3<8rs2+ z=QZD(B~;Gn$!gv)!*`&BPI;XW4WwQbuA6Mz9q<>|{{{2^2LRyj+46-UN)z$9YRm`Oph!YVrZlUlq22so6>l{t+ zGzaMsTZt~>0sAq`S=*{4$?AW`*s zIvTO(Uj$YVk#VE}BJho9zIl5xD28Q3#Ms8)^t`#v=gL%muav?Qe=-0JbD-XC^31UboiMboOyov7fb`od#CgHnE)d$cZ zeR||tcPU@13%WRR=KnEWG2^~Tm;@j)R!|{maNh^ie7j?D!Ir*sj8&nhWs(C*cLV5Y zXAd6J`peu;FlB&o_)npphrsrc?MF5`eKZh=;c=&Q`lRt_&ReK#hMS;sp(&3 z(I*1+xYhb2W((LG&e2Oh%F@T{(_SqixwDPdaL~}R2DbEJ?_X7?*)oKq(?qSoqStFA zQrS;uLAOR+3tp+woG)ifsVOasWh`_KnzgOJO*=A3;{WVUQx_E!@Xh#|waQd-K|LJ zOIy=djVF7&B?vgW@tVmAH3=6*JKY-3zB^@TdMSE~!>I9sZ;j9dM~99rUmsw<&HKKo zXeQ8)XDzq|eC$yypII|LI{6HL?CbSuusC}w7QrjSTyzY;7UAbL5%b^(j}F7$SFqvcc4voc zrcn!t{2@ZI04Ffi-k|h!YiTlPKf{v~Hu2aDD;G#R+@u(Eo&vECeQ(MQL#T1HlsDmX zUN`zbmqAEa+XZ{u%ONcQIxWTxdO1su9)qmMT!@%G-3?VfFWkLf;eRBh5goR0m>9hJ zNR_CW&RFdf&?1zi}8%TwyL= zyuO6IY;q18`!68lZ6%g&pS~`xx%NFj92*G%SgOD--)VX74~SFtHAY!re&rc>(m?FP z`1p~L5lhj0qoGkU6rd8&oGG?pkwgxGC6$FfE~eO9{(8x*x3`OLb%Wx4Pw>d)onj`? zn)vbPa9VeJ%J?uj!gfWs|Td$sVLm0v*LOSTbTOdDI&;HssY3-|qr z^|lP)VBnl8RFK!F8I{-a^1;F&Ge!4b6HVe0AZS6fAhP-S~_N2 zg(*zT`*{6%OtS0oIDc+|-Rt>F??Y@L2vCO5p>ngO zn2?Y0t2@T!k^LMo1}gIr012dvIldEH>6fI?0rCJPEHWy2ipaFYWseUZyXt$&@)v_{ zww5Vsq?@5Q@;3W}GxkrLL5H0@^64^|aOw1;U`j^WmDnbZ^55z$wcfz1(&TA*mF7?a zw-%$|(?Y!{;z}Y{Y8O)ZRL&F?Z-tu}VyQuMbw26z7FBcvu{QypEebV;?Ga_gguT3d zo?iXc;rx1F+I_a-;Zasqlzve3AKP;`J^{aDj{tDNi4RZIdZl%VF0(qP~$;~}%w{u1h zy>8$3U7np^)*YVk(8XX~l&V$YsGmPUd;0zb0@RlRTRu=M?uB(aK}s;CTFprIu(k#)6S-_V*8t`VQDk}s+Jn&d$S*jO}K@XG^J7FQP+ zIZU8uhG27*Y|eKeh_@e>lwOQ?rUlU3+2&1Fyq@TvccG}=Y~Rg#8to{&GW+*LpE$7J z50&3Yk&d9$s$^oDBY*yt#11h13VK1ZeV*YnY-|wM_+s6GO7=yZH}y*VCLkUk^4(!S zmCL}Wie0FV*(P_-##5l0x9%a1uI822<9?RP_6461ffN6f^r4tG!FwZU3<@Hz62b}R`#iIs;y@`iGM))|oNIv3i7`zwQ!cZP z*L5bTAVMgE^d>v%X%LZvXk~6@NfW!lA=FRFGPgVVF!*`Ua6eGFfvHuZ`#LdOHb%}M zRFQ!Zfrt0uz)qJbbRN@hZ}zDyLpiKWQ}YKku4bBwXz#00-`}pAp`sV-{ZS2psy7E` zZqosHu~A+!qKf~(cyz$n*$zOl7wB`L*KV9sRJ|lp&GGH-#UP5#WMeh&5X%7RzSDVG!^ZWFfJOMtL1VH%< z*@43k&5UBgG8zp`7MY`+zw-jUry_Cmp5uLltP@ChyaC4phjIGl8T_f7aRL|`>Oi)* zT3gYwYen@?#b!;m2V8ZGi@k8WAwnV)k^u~|dYVMZAonkOv?QT%VXeB@m{Mzz$<&ko z(!9q;?#2y7Oe&CPmERaRWzCJ;r}J%gUj1$%`>+|Xw*WqllUY)MlQcN3O}TEV&GeZd z5iAyD)0I=Zx=k~f3E-ipmN_A~2!G&crP;Bm)vLWSUPhCU6w_$AX?B!7S~FGU(62cX$WJgWl=vm61z&|nXxmREzn@Wvw6}@Exqn`$-3U-s>@qM& zl$-0PF7_VIVF*WLjQArHY7av7{J?+O+Zzxl`a1ILkUmDb)AV$BP>c)Od`syx*<*KU zwUl5?gGyzw;If(QG@p6={&)U@7gd;Cu<-MS?OPOly0Br{9g25fa4Bu4)+L{Rl7H3f zxd?342!4)SpolkY2QUV@0MI|{Ep+d;hA;{|Zovr)36P9$=IpZ3m$OhtYMNrkUcSYcY#?j@f{ z1U)9^+gQX_RVy#uH#N`=(|+-m*xXo|xWq_gDv}xH=AnLKP_zWe zW;E4iglURaC@RZosEEet|MA)Md!E_dJzT=gVWCA37GEaU9+}xT%^(W@og2ei?ytTf zy!v>LRI`10%dQ9^?6_94_#4jusK=3Zd%Ou$-J?bq9Ni{*L3N-SaFfSw}=gF(MDkCWtpD9Jy)vDlp25f$iLa6nF6}6$m$m4X6r-s;wVo`Gbowq;Iqd=F-_I@kgMmQm zX8jroJ!1l(LV&{t8G3kpeey|Y^b=cyyPK$yb56uFe zlYp^=vN36z35|z=32B5t2D%aaY}I!>2`RuimwqUh8hdagl8FwlMb3M z&z`z*OqN;A!R$PdId5z!u=7DY^6wC(^FqY}yng&$X~vqGm#4+#-y1RmGAK^gv8!j$ z4gy&e1C*jP3|xdM7ELwTCiW}iAE)7@L8SwhA?01(MY-) z)e}uLsh8#0bF*A}NEC8f#xU<=0pN3i6^VMQuwSF_@@9N-yg{XxL6)C;cnW>3>1~E~ zOq1tqrCJ{7N9}zbZWK?(O=ZT_$mNM6O5%(6I1C zx3paQ2F(Uh;<$9W@m;rI@a8LkhqGjexEtYV>-XyhOlYjw1h+~WwdCcaDe<$*w7gyV z5|^Jpl6vEjHp?ZXYO^{26lcCulTti%Mh0-)rcF_VMKwS>_ibbqDYLU+LqP5kBv^&f!o5%r~ zTb2@MaVKbPWOO7Kt8`&Yaryn{dYv2Yx$>u79olnc?q8AH?dG!5o)MFUv~8bJB6O+x z=>*X;cWn#Zx-I7o1zc>z$ZS=mHfc6*C#*L3&GriaZWuvSg}?kaDG7er2zEGIJbgL2 z9<@Kb zCj&Tx2G0po19PYzw#qB-1R4vk_K9f3rGwWFCrrrDcE2BuoU)T#gyQ{H&uzGLp_Uh? zFpZ^wzLSb+!$;+;tHOK*^)qRb%RM(?-%BSh0s_F22n(?lG7;-Y86KW@uOy59Wih7* z=n1d)cB-1aWpSmPxVx_%9mpncFiA-o=J73N6|4mWz+Oi-#;XdTS=gOHhX>Ao5(+;^ z7Rqf^(uhAT8rg|Z>FY7FjznQOq1fly=w!ta5lUtF$y*pWxg_M8PQtkvt+v)$YRXb< z6ZFl=#Q6t)k!8qLFr=&pb)yr!k7nCeQpyr{RK6K3JaVzDj1gpEc=Q_SpF4l?UrIj5 z7d_R4+>05q8ZGZN@i?_$l;>Kar_ufpY9?3Z+HCi3Y3t(qL7b-9ut;R{-5*O6@7Kl2 zZwBN_0A~c%HDR6j=ru!w)wHq~1tPEcU{fEOw zY2}kQ+mZCx~c z$7rN)$y=ewDi=#X%Wsl)Mf&=eCgfsfSI9Nt^_nJd|Mca2_w`KZmSZ@w;;VM?Wyj-O zA3ScwbpzmbV<|zU!v)O(|GKnU>SU4rv|lLrEFyqK)(Ccfx!J!hk|^TJI~kaZAK|4s z(y7DQe0mUYTBgv_wMih9ZGXM{&D`g^jGB=^!t3&z`E;|(&uX)YGY(NveHa;^C?lCi zE`t#%1DFw)r^qUE6Jv8rLRzNdhLdJJC}M`XZ*>@6Y%{o9IStw--ES7!d|=AEnNy>- zkbr1$X3qXH|L$WZ7WnsJvF}xlX8N52sN`pvwS8}p%i(SC?Gi{p%CV~`HiqXx@@dKr zX$Xr(2D|(Z;BgV^RVM6nCXrcg>Wdg5&`c6qeD3<1y(zrDNe~-yp?Avo73?2kT~s8t zIGl%w+`oHyGr78z#q9C=fVJY!&5?*fh%jCm60jETmGzWepAH3JZpJ_REJ`vq#rkHEq zyXOr))%#312fL}di1&tFZ4c|Pf6>G<-GsY}+Sp)3dgQbPWp~Gy61O0F>QJ(;5vR@m zd`EF%LMMu*{{fM$hLZGs%~yTgkGxEX-+oH#)j+ub4aNv#=pF7(EqS@Ve{oE;8s1m4 zkCqF{AI=WruaR}U4k=;N8QRnSSp+#Q^m`fXdO3*Wk~=4|eG~X@XH@eRqUdx?0oh#K zO7wI3Kcz+KOxLVZmZf$fE+&JC3?$%0pdpoJ4?<{Ej6sYo3H5<}O0yO@{5W<23DGK!=`ME)y|hIYU{y-FrosHQPFdundM+>_dt;_nj2<@aizlG7nVFScb)n zDTPUEoEmI9-O=*SmUsgQt(3P9bN$AO>Yt)CYsOuqXqaDeQ8z2(2#J#N~!3|2|mBm|TGBY3rZ*G}*3CY8P5{ z;1<7j2M=^P+0F?>tuD>_g0BxDPlfRDgW8^TM1G9cWFKzlS$*8ifMFVwVf&WR!HTVf zlL^imDEppv3m_sO$PsB;##iJnZ7 zEntB?W^T1cjg;mX(1c;`TMuzo6X0U!)P=y52Ynns~eYf%$k zEek9;Ox6)v9TTJS*p}qPOBv-z{7+DlX*198&V*P%?$nx?kdNA@=^AN=s67qr*ieO!t68>A;>#;AQ86>!OgZIUi{tL(wBGxP@0aK2bC*A` z5P~Lnrwi31KwpAHo%FS00O%U1NCA(3wu|dx=Rrsw|HBIz2PlJF)EVzB2r<#~^DV*R8+*h?jikK?VIvq5 z@DWGt#QE!ldIXV?9DLWeX$78hl39+U^5HmCaraxk)6 znG}hn@gsr6Of_dK<0j^{y-MmYOEtKrGbxZnExFWb5e}EbUs2Z za0fAT;-YtNt<9%q0@mZ>AL#z|Uz1=k{1$3}lT^Em`w^hEgxDYF0^-_uB5e3?9Rr-} z*r)CL9*+Pr2gpQa_^OSl2v9{v3A6cBhCIqrmf>iG99!E8`pJgtaz+=19~QW8!V!8m z&nb>9@w4b@=WF8c)obVWBiIBT+2AT~%Kly>DmUH?FMHG4dyn^kM$W13>uhHy8xo|U zsC6uP&Z|hX4_a6R2>WLw{?9Q*1ugfwA&#YB~y6twBd}Jp6(-!5$Xsq!>R(OES`KVTLtnirVV`Xf|J;j)lx7uH}^oHRE`A zoixq=z$3&0l36xEwjRCMZONmgb0UP`(IH~%%hSNi8_SiGlLRXw#jt-)$u08A4NC)J-r9=)2)up!_K4;P0bROc&S0$rpAk8hFjX@R zm?yUX0ykJW!V5X=qLbI81sOP%&s+YD(or%@r-zpt*2wK*io~cxa)1-CfJUa`y4w_I5tjxc12a6{3wy_TgIV^Tqr&>_hNnTb*iV1-?weMdu#b-0NfM zbW&7BEeF(^T3ia0u69z$nf2Lqf4B*pC)pl?x@A;E&96# z2vgx)I{EnO$FzLC_FSAIRaO4$7UF(kd9yWs1f2@9Jr*_7zmNbpG#&+HTXb51+je`wk`4p__*5&{UC7zTS-Yoo|ve<)&U zj=rU?es9y0GcMfye6lf@AKjtGFUHr*9x}@R=<_;}U%&oAM0DAzqGlz~%iG&q(zPUJ zjeK|@IALqM-GrkPH0Hg=SY(Z>QtgE$H7F{|uK7IZMF<$Jn@;OA7Okb@>aXRE(eG=p z^;OMS#0d9&9^gfD%yQ%YTmiaNeGj`;2TB%16cZzO&yC|(lam==A8G>MGF9*`zws z6WZ1C?g@9E)8NMy#!w-&A!+PKRV*9Ht*<^oX(g*(t6qC{G#m(JnujS3|M))>CJFTX zWYHWu0?Xay=QZFUUVff2Nk>#dX~bd4D_$_j0(%53Em)~>b~?4YxshYlJ4!FPJc{5aO$*qV&E$}i1oK#=X zJe(@07<}2>d^qd7%kTTePdD11P+IyN{@i2sv{>^PFf{JDEa*aDV@vQ((;KK_>&PuN zB_);c!u`pE#FiR&ZQIR!>3uFYeU1avKa)?)N5ITni?;Wi(ZrNvl_@F8Wkd)%x3c0a zPCbvK%y$Xjh&;$~S1Vk!l#4=M_AFa@;{G}ki$AN_9fEn8fnNOr;eEJoA1?0_lx6K<#XXo{z&eeK}A{G47G8}Y<>|cj z<#+B4^!09$q{d#8ro{Od*nSh*=#jc{SPv6%*y!9Ej_!NSmn2J8Sdu#4+Nw$4l|3!2 z?zx!dSc?)a^igTq^nd*u{@mQ%F7he?5yf0PEi zcF)bKxwv|A+LOG9w{Y!9L^7$I?<(VcJ${qD`qekt;3R*I0 zGxa~6=FAE?d0sO0yDy7P4J`_Kip)G&3O@UDzJ0a`g3CuA|Fyl|!M0!8aqhM#eYz4> zobQ{tsAaF*TxY>UAvg6QR}UMMCgA2vVuYGrV`EU|?)K&rgyt#z_0T7-*yUNc3el0u zm}O)Yd|&@s(1XJhT zRKBxCGw&5uGm)=W#0sUgJZKcMMT@|J&CX}e2*X6o-K=$5HRDW$yB|Q=n}PdY98H0D z#b&oA^)8gCR?!iL8`mHov;31p9h{D_i@}d<%T$M8G_m`UHdofWl|4r)Z+fQ&+;fNrX}uI125Nf zwk^i@-bJM%HUFqfuhTUMHMQn}nDhZcM<{-1zb@U|{F^Ar?;5#x#5E7&5+uBUC{U7&pLxitOtr>JXKnlFUqXNNn|p!SYkWFphk|#+wpU#B#gs zE<@)7!E|qk5!15hEu~KOj84~CM9OP%KNpt8Tq)UIax(Ya8uTT8pqDQ3Vab28Le_k~ zYsEqZP<0pEUjf=@>$Djjjs^Nnv_RU{0aHuA<4cz?I~v%}s0Na4G3-p9k9KPy2O`1l z+mxukuzA9QP7q*yt5UeZlUuR;L}2M8ua9aFFVe*Ky76UZ%5Itys-4WDF~R;w@{F_?*^sTf6W7I90ZN4g>Jb7|LARh~h54-{XlLZcDMAgVa`Y$Rp|Wt@ETlcpD_nY#QK`{u^VY=w##8t3=i*`AX=F@} zy>LP_nwG%xKlkVK>2Dhb2LVDiOk3LS#{?cnqr0g-#;H_-N#dvp1-D0^sZ_HMO-G`_ zQ{u(_z)w3GLiU9}K2;8J^&RPOWH;@%Lsq@+H-wTZ(`Tmg$9{9tNOZb|Vp5!*eE1f0 zac|ZCDe3l0+xo&Y`Vc+AM zgBd^gNp^5L=%)dU%f zem7H*2mXVx)^<$`Svv>%_K$7l0*Gb~Hk>_tzhLMy=Q4KGZiGoteHszjCxet7Y65I% ze^grvQ&Vk%FX$N5>v)1yvQ3hDBgfkJPP_enzt0mYG=a``zOVlB>(ebC$;IBD zJ0fi-rNV9<#O#A=e)#;2aBdpF20tHER3n{%P=`kHOxwBGh-a)_K9Bo|XpShk!g&O3 z#6YrK^Nl1GYbq%!+dlz`xFMZMeG+MyD@ZSv>a_WU?|DXT(`9>cv(^R+d~P|tbOb*g zK|GuT_IRqAV{Ljz>tA*@xOxi)x{z7r_#s|IUoPxw_R0@Fi+rgp^j>xN&rdI>Zw={~ z97^@iB#%^$n8J!0n@vGjx<492tOUc9+yyt7i6x7;IE=GgXLDrBijTpP%%G=wUhFj5 zMJ%67qyee%%h?h6@27SIRkE^F5#T029k07aN?I5pktq69gUiFb6WD@JU0&Y8c07#! z1Wm%7C^G}gk1RcP>Kn+md11u)`e;mfYaX1H1#pA&$H$`Fw*? zrBKL;7k!NKv5z6Uo@xSHp8Er6^Lc#4`7K=7H@szntvYv66nr5pdW*Fg{4BN^Tsi-f z*#nM`Z58n8Ul-(-9EuWH>`z|x_?R&bE;#dab%y2UyrrRT@RdwbgCI5DJg3SZXr{A_yzYogcWq-usY1K1-N!WEED8 zY-zVbI$~iW-jgspKCQWH(ID`ha=eKt=YICR)fVNix%}O}hbgh!-fkAlXtX!~kzlMfQhMMtM&r9%$rb+L8UN)C;Z4yHl(e@~DY*hqk4F)Z*er34=nLog4clQRn^pC8}4Ok6VR$C-BYXxiUFB`f<0{s3%a=@67sp z|D!7vVz6+`Ep-77TH_%ky6A(G6qfL$S><$Av-;4rebRCWTzg{W#@t*GLXfyL>xgNOs= zb!GEz@uSb@#Hgv~X$hW@+9kYcNG;w>{H^aE^tafiuUAOOte2CTe$j`+IEfEN&%ei; z4)J>e{`yMFgdFR^L`7hazvrT}_b*)-yFV(?nBd~{Jvm>Fb4T{l(pA3 zAq!u(KbdaL69WQ#e;D`+&)7WlT{RW&5#N6?E1N>JGLfs@Gdm3mIL+>R^?r(1?K?@y zwo9Itc)r?>3NZ->DR~Q zKbzy|SKuUNQ*{*&0l_@cFk7{w+`@u*DY?oAziF7*O~R+RYO?t^WB4*>v~2W-$}t1A zInt99r^_M)H6#t#Jg70nwBAVtx6mfxC@d(|G0JI=j($MvgMuxDV^Vb zPm6K6qBM|;OP7(7j1-cz67n)$4JY<@!V9>#Ysn85N2hD|CApayGog3yOeG8Q{R3c@ zyh)~Wf@?X&X95!ARZB=41tugWna2h^ME!PnBt=23)gPXx19IY-04A@8eHV+KyvCr% zbGQDal3O&i^o)<_C;uFI$XX_Uhrc`XonKt^WzyB^@63n_U*xH&Mz}7N$Rv9gLzSMF zyW02ECi$=+`Kmg0Ht>er9Qa9@6(0ahDwgk-{z&_`+4Tu+)6WO2|Et1^x`XKSd1H-P zb?r!1zVB(jce~(yIlf@ebLqB}PERu3gAXk59?s!>OY_Mr7-2A>R6 zaurp}_0MKh^lEz5_8?=VlD8h!Y(Wz$lS%(B_i_+~_jSr2z--0qP0V6lIXI}n`~?wP zH>2U|V~iLg*`-79>CwEpsuu1b>PSEMD;XY3@HJxVQu^*>x{o@KEIghrf~>$}Ems8~ zKRn6cNbgvYX}~lpbV5_Vz|<$@zgN z=B~?vpLyT5bO5^hgorfgy`lF;W2kT=)U^tWS<2|$h0gVk4oPwW(q>MZpw~jmLtLOf zmt8pb`BBy-gsF3{Gr6uzdvbATV208M?pz=)EWS>Iod;Rb+03rFfAHjz;ihh7tdv{& z5IE6C)a{ob4~kJ?9)dT6_K$vz#*)FEKiifdI$Wrsaa%jphlJYkRf5Op>otED0tKjX z3`T4Dkl(x8kx~#3K__8s}pIr zbXF@%fAybcx!*Fccd`1H&M-4;#tHvL>@Ishk5Q|j!n!JA87qT3G-pP{pMSsXtgxRZ z%O0-ZYxZ8>jE|q2V%ME^`WLTVv^s87(@7>D+=RA}s{z@h2z>A8AJdCVg3=J#H8~b8 zsv3v2QD^GS6ch9YuPy&B&{|Rf^kes@nN8T7bKj@o>4} z^!0yDHr@~ZTOj(#Z5{1++hQV}@EDQ>dUZ|rBWy=}&@qgq+EgF-PK;GvWfI!>Mk^*3 zla;E=P!G8u`S+INXlx*>5)nYm8zu(d7I?G}n=%Tpunmc@wK7Z8ud*1!(A8t|n5*eH z2;O5dJ&t_r{4Xv5(ZW_BT=4Px#*LdQVST95%%(CCD^>O<20=JsR4JKA!}$P=R#XiJ znvEL|dVGuV$DadI*VTEDX3wTy4;d?}EwPg#MLAoJAc-&D$l8(g@j{@C8d;tca}P>5 z)N_$ZHS%w@v0LM+XAY-kS$eiyJ3LSLw4FKu{(_y8`K0#RHw{SYeVA$S!j9%-#q51d zOh0c(oWVg$?RRYd!jCf`#DlN3He8^Lp&3wHhxQWY)2duegg}t~xM1c#?dN`^GBC*< z^CQn67y1RK_D38M!cZgD41%L|K>Cd1M!>1m+0ho2B@2Bc2GE)b)n-Tehq8ukoryV5 zRQ^~19LW`>SZKDONJQo7?CJR;W7v+yg(Az&zbs^@o{wo2@!;{0C-*)44N#Q}agz~=??}GvIh!#d zKqdt9yWaYpQfQ_3@fV;!K^vsmCHjH2gq2w<(^#9qPJ>v7!;Jv3IdR_MuE%&ea_({o3kSNQ&E$S%nn zGcWVML1aPd!APlC6qSzll$)29^ma`^KfL(o%~TJJ3r?kV{E8` z>>u`sd#)y@ioMmO>SrU#uldZm!>YF=TVUEp3Vj`Qo9bzgIaWGcKXuPU(!a@8G0Jak zk>mVBj_JHA(zFasOk=a+Yo5{{<7<%n{gMSQ&bMR8=`GV9N5pG5J1_QhlH6b-H1{pn z^_w5QC7{*pxd*p)$~!AwP)#pb)-uGz^ke6X-micuUx+p8&#X2+vq|>-Ual(Y zMnmRgUNlq5w{JI>>zgZgN3VmjAJev(kN`{OHGp8(_1>$AnIre}`~5Cbr2ocl;gHHz zYrm19cAV%R`sxzceL+)<1Lun0si6GZn=|M_RTi79PP(F0){(g1siT^ohKD>N(y#pt zWde;;GF+J7GMnI4*QEG;i?k-^nVL)Q&P#WpJbJjZNu5<3Wf4<+}x7Pc;&wlpa z&wf(AzWHMNMo8JVCrp=;fYDquw0N_{NG~B&j!?s-@YyJ%Bv_P!5}yDYBFu+($Uyvk zsGDfM)Y4A!nFzh!2v+E9GjE9!9dS;@?LQJmijO^jj3KeFBWSqVucz766vGV%o|;)H z8|CZ^AM&Jww7=4pRQ}?{Q}KV|wMa`$9`bYK)>9A-y(Np*ZkzCXxP8q_h`G)ySB-e+ zyN%FZTgeZ1%rcs?KqJvciR7gmOUM0|4ws*unyMTaWn_;C&nEbpQ`Ur{41JvjLzFW` znBAa8Ji;K~Q~G6lXhLgDhQpVW0%t(d*HVCDUw8vVc(AgN_mTFgJ@ZRilJ#6kv2YS9 z7~qS5$ruh)OzV?N9%E)^w6?}Ene^qAPrK(*fB{)|@sIYIZ3?nUU#W8Z0r%#cU#}Mi zFd15BzjCuB?6(;qFJHF$p6{&{Er?}vNcmllf@-hYV#Xc!ls2@2&i%;LOHxMWP`5Dm z!x2slBhqhcplVV+^=_iPwL{DA`8zEw;-D+R4`Kt>+StPD^TdXaQY7rdu^AQasEhrX zc*gz~`DBbtZm>R;N zLQd9zNjGsJRF)&kdBUSs{56n85s#E)ZQpFL(baUSL7g^n-AJqQyjZNwQ|W#49-cFP zXcSTV$rf+n+jdNHSGHOVQarux;Jfp}-}jeWyvig`ti&U^{JFmkI}9H0y-*T^g82u5_kZRl?@JHWB#%av zE)IjXIWY~m!Ec8L8&srhZTRWdCZP96cRl0UV|6*O~(Y^4fJh-?kAy zo+K+Uq*m$0f?qXs8Xu_Rh;_V0TIUk&& zAviu^kblR&+;Z}zhjT<A2?w#02a~nC4{_<=_s(7E$OMPvVej{Dwc9NsW3mB0|q3GABL$lIalL=uphfU z(N_fcdUxMA>An;MkxFWP2b=Vh#ppjJoB3hMXEfr1;=7Zd5%7huN7AVqOh;!B!Hzzq zmTSHJ-N%l-`ZoR$6bjBNKyQ9%cit2DvhoHpNsjK68)gl;r`%z$7ROn zUmfn=39-rN|9tOCnK36xE8;A|>)aHdiB)WBf1`-RFNV)r{PlXDl*z*eC;C&1==aaX z+#*7rAYef%xTtzPRSgt67ZVMK%zDYY3y?|*zuk6O7Jr_RB|%D-FrVhaDC!J^U@1~d z=>I4zMDd`!B!JLgy?1}_-_uGhcLaKPOEVD9Kb+)0jNL4M2*+m*yk0ro`idD5S+jl4 zxRn#*FwwvokwwQ?x9@=pyjlsRWcrkak)iMoiS$SQiHTf^Sift)G5~R@d&KdLn6F=H}O&}C9=@WEb__wrSB>b zQtM_xZhIY(+V7dsL@=1p2)E>Tk;+f7k|9E1d$ED9Ffrefx<;jL&uOAbu;au0z=Ura zY)AKds@H_2o+7xEE_?3$>+f5xl!ZlQu<%=Ni0&9qp_{e*!u6z^Y{X|JrKsM>%ydND z_(7lqZC#3cxP~zO(DQA+Ld0g)u*N{R(c!f@Fw%?@#sR?k@Lt@qLRY}9z#IF;cHo#i zqs;xDdwwi7#Q&qW#V{Dt>5z9EZ(*X3j>8AHd*wX+e+(*`IK5!Xob%e9k^1sFK46_% zX?3+5#~cuCDPX9bnx*~8m@|fKQdrbi4FD=sQ^Kdur2DgrRfe1PGBVVpUlsD_uC_9D zuRXw{L%LJ7qW40p4PK1ENjt%&oV0JJp4{)YEZja^VltPOIB7OBACqKpCgu_tfX#aR z^+QV8zE{bR-EmqwTeA@$E#NhFov*r&$L&g~2ypyip_$WFQb*vS_3LrK$1S;a6N>ks<=P&g&ap1XVBk4+H9WUAY2d=J&17YH7Wa989h;U|enGT(ytgaRh~^d;dfI1-e3N?VLv035iEPsTxsQr|Ciq z%r&^pORn`Pf#SB~-&>eyPgm{JZFnZWst|>qXoH52_-ijv z|InymYq~y)g=2{kzi@{MwDnt9uJjF=uVEJ?lxSdMwAOK6mIa#%6|OS#v^O&F#qX52 zpU3DA%V}N)?7MwYQk;6`!~arpAq`DD7_TOtSDm%Z!Oa86#DqJ*j0tnbEW%JwLG&|{+NAaY&f9ldSP$jc{rf1+W z7OH}(+=~0wJB%rU!c+!&q?x8imE=zjEsB!s_{ZS}ws?3qP~Di%rL?|6j38wNus8># z>enN{P~E^`2EJ>X_fBT6Cm`o>K)_Vo$lU!>pTq-0@L7N}1y+_IwKD~BZ*FeWwgw~( zm?`N2f=lUzbMwc8ZaMP@2J#sX6QjNjzc;U920{n3V+9ILZO1{hjFb%r6ciM~ShFrw zyVybt9X0$n{$H_|>SC9TZ?Lo-XRDi){hgoh zUQ=EJt;OFF6A!?OmGlIlgxX_8m{)ei(Bv7a!y~9zYiCJoC`$Ewr*`11ffP`wkKXxI z+@q+jIA>FDnhxIHuAK+|zPN(TF=u1@UT*BHuAfY0-?+BBBMvQMf8HBa*s zgMo5?cMgGzGJPk?P~dkqGP4E)W%Bh%N#{%bJ}-jy>BFYGhoLi%HB1EjYsK8ea&f1Q z0miqkRX9RwMM2dw<3_GVfai`nQdX_#X(AUU=gDP>mvo@{xDu^^8ocehtHOnQNLNCj zVt2(lq|2FNXj;#-;%2T*%2Wlr&}XT2C#~Y5#=(vv+@~#oyZZm76F;(1z2f64Bu=e; zpDT+MYWMxk;xl|O7YDFzGBc~}Txnjkt{d?V@&&w+Lkr+YdYW#)D0vv2iA?f1P&>HU z*x}1Q2^?;YzNi#bMH$#?udi^uCetG=`~9rSw~II@u4N_s0<<%d)%H~BG!ILpGKR;6 zi^iQb<4=oV^#-oFe(UE8Q_kwbx5=N+O!WucC$@F<8N_YOHkbTLc#3K<~2TH}6H8ho_8A-{CeHeTUxcxkOXv~(jU?CX)N6tmjK5dE3fQldSe zDOi!RZkkmV{@(I?L`S%yW7`5X30yFUM=A~N1hl>NMZzK9mOJeY_VQ+Q2 zcOrA$+IesB1$)B!d6T;@7cK`W&NjBNWplvxq>())Y#>`RN(1EMx(v%w5i;=nWaInq zlo9T8$XJxBHk=ZIRQuElb zz%%6<6a0R8D$^Xbu`mPSq639Rhc}2TSo^`&NPovd9BYVNfup&XMRq4d*QENL;1ia; ztIko`0HMO&gFt`FNgVUwhn%>~n4f1Q1lr-T07J!@-Mna3YSL&RE+#5HQy*DSL@6xf zIlHZ!THSWBnbQBmta9Y=c9oO+%kM}V{0*|4a7P#Q^-ZVaUgkhmb?vs>pRYlANLb&L z#G$EZ?e*TmfKn+SBO?d0&hkmAe)osZJBAJjD<_24vQ_x*a>)dgm%Ge-W1o(oUBrA{ zg0lN_C+VwOMDekYX5zvh&mDuG!6#PtMGsf`cdNEF*N6A3RfmUK1`YZ%EMS15$c4$Y zzDT;RqQICv^HPBKjju=bMRDkF2@1@FwGh4{^wS^LI4u3?Yk|$pEP-)V&BF8HySVIt z{SRNp(z$RZ9|H!}L4zTt=|2-?Bs+a7#S)`>ZLV&U0b>Dl#2*%3@%+fy-rc^IXvWs9 zPkklURqX2M5vYy@0D(D_0PmHw(XilwE`t!=ISimjilNP($j*mUBiXC=t#86ZuJI_U zT|+-QC7P~bbzQlCxZara{av0Xb@iuvt=1&()53iC%$aV3b$o&Scpeio=;kek2gReg zJ7eNY(r4>dI$R3AIK6axkv}eTf3$Q^)b&5S6&gor(L7}*D!LW89N;p_t(~~}oNq4g zLR@wyl~91{s7EX!2YmqRVry?=9&mqO9YOMN87%oT3bex|^m|%;r5k8V(N)&12vbC= zXRer6$Cs0LiSSV6JWVR)rW}2;Bpg>p*Bg=1w%+v#q)kb|HKd}h!~%O&94oL5qx!3N zphjkp!Omkb=1xIBB`c4cRGf?ys$`uX5rp#!g#m2yp{Wz9?X0@n9RYX9>pqiNmwXT)lH` zXV>+FS#x*?b*T16%G~XBznd1{vQy5^-^zkN&ydqEp8Dz|W{CEea`Mzfoc)wcS3NKc z{CRbMSEcF7G*+25N*RW+cJ+Pu@IiKE``8RDtfwnFCSkDsxinRG#v)ypqf*>B(}LY^ z%&#khfW=#6!G0_NZkAYI6<2zH)Rgd=@XPu}s^{2P%~QOf(AO`k00{4a{Xb8K8Y+wn z93L_= zQ0q}lHU=Mj%8K~|tFP3fYCf<6Kq6Fc^ox3u7q`EdB`SZT_oL!w(97=7hBh?c5Q4F* zS}PB)`KJ4l;!c%xlLgdfr(V3}n9{wbz3wReg~8x>Q=+(?=4a09MhMKrcV-MwaJl{L zfLAQ&BI<&K_`K}`e>@7mo(@t?L@yPxHj{Fk%>7 zSGRb?z(_d8Vd3`7mXGZ9%oz>!4~VCY*~k~*IzE1^!sl%#$4A3bpYeVIgE|Bjbg#CZ z5U`Gq=4brE^r(bRIE#OJ?6l9yq&&wH8WQHoReg{9xo=9`To(7W4+@?%G;w#YLxv`@ z%_^R6ml)A?9XIg0rTs(%c^nGM8E+JTeBy#h> z=fe=Hr}z-bZF6g-%qoFzp1fH^^PxTo;E-DuTrloXfHL4p)@v)#y{WSVcYJhge_x|2 ze@vI{EKui)*OtA={GZ2MMXTnt{?G71d-(ZOVxH6IME*gV50(p)ui8{v^I984&&1na zN}wZ|#R6s9ydsP_awSh~vgtkhPsaZ`4HYK6VpVHH#EN}E{{^1g!%swXUM&TF!RQKBK_7{=W zAlP6uI-JIhr1zDq_}y@veb}+pW>ql*rLC)Rz!2>6M+|+%Ev&_Y@|8d9P=Jx<=g#GS zV#Q>}#z&?bkmsj8cye_Ky7ZY27O9IurjHAhjwyrvVoH_p%pbX~Lv1L5ML1M=3DKu3a1JbR%xnM3&ccd}f zcJr!lYcnmMQHsdREm}WWHDw#9Hg0Ug0B%n%=mJTmHN4VKQ=dKI2Ca%Ue0{vk$CtgU4Aovz`JN5uEt zU!81#8L9|pNx0~@SoZ~T+PAsdy)g(HMk~*0`D^S;xziK%dem1E;KUY-9Na#P8Jq@R7GJWCE=2b=zwnaYGs^5_;`Fk-XLdfsF` zb_{%%BgXP&FJta%kyHG$?RV_zOo^nYm6ky7Hcbh|*=rSb3#%~C&};$z*QK=2XH|KH z-6q!l+=~jULWU4-2~~(%T*Upj_LujsVQ{;N}lx6mE1@w&#N>XCZW;ko-iT8DOzYM($U7qp9^{Lf)k`KNVI66@opyy_-!d6`h~cFSfbs^P7h- zF&!{J+4I`HAC$Sf-232tF*b}$`PSa5lsd+n=*pK9CXuS| z6;>mg8QsxV)caxP+%o5s>_o0X&W43u3ODm&z7n@TY@hjOozGXmbPtTaB?&R3N%wPw z=BjVqqaS)dzK&ijaKVj^mRvM9R#)SGk_}&#EAJR;Pl`YM9T5%dZJ+M%MU(>u#37^xA^$qCv&-)%js+`FK^;MXLq3e_#M&$G{-& z{wi@f-&Zd~pcFV3TvM2xvI`2Kin-$*Ot_*X6kH6fqRVNPXwoUUpGX4|ahO!{~wJgY4I zvs%U0J;oS$xi^Qhee$I3^ciE`Z#W%GC>G~4@GlstEwx7+QRRyaE}`JF$0UvwTjC~y z_JKRCePCkpkqn?Kh}OuvL4 zX&lHJm|I#tT;DAhlUn-!9SgtlX)|dBysK5e8XktLxkK_Pno`T_>2fI#8ngGEmX=!s zN@n0L`~S{|*VtIy7RZ@U8Ix_9MClvmk?!%_i!Kcid|_eFip{y&UFN$D8W&CQNI$6S z1hEh$m^)h-LeiXZ-G6nR+bFXP$_ivKxYhqK`M$;RIr5b?tUUi`&#lsv+U9X$rE@(* zV0Mg(RH#sv=}ffr9Um@$&++5U@UZ_<$(gP6ZmW@1U}mO%1w0GhoTy+pH7vJf=(Xdh zSMN@Xc4}lkznNTh6YQ6bW;M5T);Ey1F1*5EqqIfUsnMv<;rR70u`YHOkZ1cshjwcI z4a}*sns^9CyKA&8gI2XecLA$R_OErKT)OC?%nZ(6M)yaN2V({OPBXttFDyLQ%jP!t zv%5JRS?8&v;Vl7X@dm<1l5I0#(J)M+XNSJQ*#eRyQ8ewx+<_U;k8#)P{$Fo?`@=CI zRzNvaT*Bg!Us@6e+~Oi%YJr!OoJV~Gf9FjnZ(uZ4ksKlgM*xpVHkReL_Io||pkK=o zzn&6@2g#2UNo~`9w=12mUASE}kn3{E82!qvQYmh==6Ru~7*GDsa^yInOGlZ>Yx+MQ zfzYEgZG7a0tu?LKXrHwkB{weYI}S(;rstaQvZ;hc@l6z4UTX}gSl1i)L>Cy`hqU`> z4mV7YItx~#^nhjivgl9I%n4J!mQ%0KqKNT(OTBh(*EQT$R1cEN=rZ8N|5|TT&&FbU z7Qnj$8z7@7&>ZgD%FPV37&ULp3hiF;Ha{gbC8gMM34y&0#o{l0Z7r6bmi_H-l8eh; z;ZA)9FD3EQxA>kFhVYiT)i@-2KHO0Mh7w;}&kJZP;??-~orbf{rwn%d`7w3~qTBqN z%J2d@sB`&K1XWIC;M^w(CDw0OKjK1BzRi1sKQv|%oKN2W@-%2+!YDG`Pgk*fIr-GmKEjHZTUS5mZ z}GFymQVz>#A_O)mJMNl|yp+J9z?vp`t zI6T45rQJ|s)^yhx5pr|3_NE;!!B7Ab3JCJM``7;;7<~>Z1K&X*&!c4g#rjiiFMGC` z_dO+~rc7%)S^}1RxQkg*ZJpeHB9RH1p2NKv_JQ{B=ILzYxpynm;NC&AKF72ZK%;*f zuIL0+&$n%ffbVQE8V{*Cr&VeyZq-Tybt+s`75m=6)i z^Sl=sm%~%`>9Y$cTWRKhwf16eyVsu-TPS5TnntIYBz&may^Kp+lg<#|wKJ+Zm$kxW!SU$EKwhtRrBPEj>u+w~i$3-gk zEooxTsHd|+?_#LHSuNe-=ISZpl@zz;ab^BUaze?G23 zs})@2Z2A?9;{CF~ih-3bz6c#6>s4775C?=+0A`9r>*BlVhrCw&Zb;?9uiB$9%o?e} z8Z9(oTIu2);1wNFlR9K>FwB+S(*v!4qro>SbmF%>YdZLKU;^vS*0-5=tjMskFcX^% zQh8Eh@OPnSMxOGLb`(Ph21$3}wgPH{6L&t;G~@nrBRD)9M@Rk`v`%V*)NhaLi|^8f zd-K)v;H%5xiBHSfI`NT%eljBADXm}Ya+_iaAJwJwYkM4W(|A=_FC8kA&5?W&D)p=I znp7rkWA-?k0pV=1xX5MTZwWQR*#{``HT%>JP>gO_$QFwy?1U7}X8hk~$QacsOu5{I zrgSk;EQ2ndOf}_CRqLOt6;0o1!-oABw*xyfieMcoIW2kYd;iX%wZZ;g>#~I0UeB_< zSdaXhM|&;tcPT88q|Kd3P}(yX<#l@%TEv&xj_~Vz(})3+VSC)&AhYGe@x_wG=&!&2 z-5bG20abywd;T(M`S-UC-sULn;~9iwNbn(pD_?r8kOWfO`D*-O_{U@d(wiiz^}y$8 z*La=<+H#p^!pCOG2RiTdjM%P>9=j;DWg4ZMo0A#k{wBsUNuG2yX9OnQ`#C+X#q#{F zP%H3KIr!)d<*~X%nEg&VzhY*D)QMy-w@F{vZ*zIDk zb@~36N3%H}HCvmh!*J$mdb*K)34)Yba9Q%{mhP^2d}SI+rsIPs$gk$l(&ggFmMCa_ zJm`FcG#rk0X$&>N2&t6@R4@a1mV&fj9^TxsWhCpR^Wa!;4;(1#3om_CEb^*i2gISu zohd=qPnq5LbH!Bc5l0Cp!ZqkFZoJAh_+r!L3HQImFMi$e8KW_p zZSChf@En#Xp=6eBy7=O=v~w-6&8TP_KPpvIF+=eRuLs8?B=h0s;hgzltt$9&8X~(=DuLXizB@8R~fsif_T`Bb4MFb6so3yp`qgt;xU67&YVw7PsU3L}}^e;&DNV zOUY&XH1*~uI9<7nX{El(T_|8>X*i9P;9(~OL&&0IUb;I~J1xcgD!Os@FjRH^yUV|= zBKSA{@b@ry^(1kzM85I7A3BwPDEM+TP^krk{Z`fC7fJVd)u8rhIjyanQF(&z7IEG>o`B2_C~gwAa1 zTkwQ^p00V{2yQJA8&c8OkQsUzh}8a8sv8U|J4@@9?dv1YSiuKFpBOV*+j2gF2;&g| zycJvoAkfLby3q%fC`NTky+0oOd2pEx3Q2+ON+W zXSlr}eLd^@XUG%8uDwy~vUJDQN&ek==M`t?&8A@cYxTtZ#dj#dcJ~WRmfp>5XV63N z!#eX~Yc1BW%;n8+6z`i>_~{K_c}U&rYGn6;CPb?f;L}XTyk+VD7n17 z_HSi~#Izjyl#)t4a7DnjfU1qw|AtX$;b+UvCy6-*_4AcZ%{rS6fri{7mx|M0{N%GML%rY44 zQxgkWTwEHk>0BTtUTpW|z$B4m5LOr8yn_}^(<*RpZl)jb+q--D<3?pQYY-?hR)1=x zsA)x*RLsNHJ)cD#_0%pLa^t~FIi4d?@O9!ua<&mAmZF5d0CEFSK{=5(0Ew4}k0 zut*Mb&;dkZvkRO?X4O)yi#Px*)`BX+1IC7BB868HFPi=vym+xA9Nq{3eug27*ny(8 z)J9H8?Dzmzj*=m_s7!?aPGPH&=gqY1(n51}Dt!d)hRd7%jrDAIpbhoY(C8)u*)k&^ zF_iA~D4PeJn&hiAU9&Ti5EjZ*J#}?kSRc#QiWpLuF+pkFanZI|y7E3vwL^)ZY=ktmw>*LDqk1G7_{F zZ+_Op#A{kDsa%urlcpA`DPZZu@Ln_-5T z%i{PHQI)yg^HdUDnp>dv z23PN|UVq4~rzT>>)tT}MK99p#Ue9u+{C)4QdojT}y9k<#1C;Iq;-Rp$9i5k7kv?+f z@AdE8tSXYNM+zjtL3+I9J!Pylym{??aq7Q&U^nb-f8r2L*a2{*A8 z6#-Kh!+!!-CvZuSl(;tf;U*QYq*sB@svz2uO98xJ92=CucI!0pgJzpj%@WKVlR=Ha zx2HQrcr>*goJ|yA+GXz$IEj{iU0`H`K7vq~tc21IG`a!cdk+cAiCMIPgShLxE!Z&I zr#-~Z)J+tey85sF8ZG(R@f~)Y4IrTRf2aaaf8NENU@U`_K=19fjr(>_>_}D`)WX8P zhlJghZlO>z{z~!87EP6_Xst;jnwZYV?4{SUDigJ)!G))!s0lMFQfDBEh;Dcaaz(A@NuZaukPY)p(9M_oRc6?C<3-^l$_90~=yMSsog=lHDjkAN~8 zn54I`O_ewP%fGz<*Rb_@eKl4HDXW)5yQO+!Ni&Ses$)55Kj}I%8W0p%i-Qq%>y{Rs z8W*}F7ZktPRLL|+2Gj=~t)|FaEd>nvJo;}80n?dDmsud81x=*8I(OfYPS-%igsKXN zhZGxPT;WX_Y3|d@C0{GhVmI`N>zo_#rn0^iN>fZpG0m!v4CvY4I`_7c{A2+#MTBJh zRz(v(5>A*?MfH(c%SJ1#m7pt-FU=z|b#4~SPi zIE>2)7)~>l#6~jz4!hfA;~IK_xX4FKTtq$GmNCt1JAG2t5fb&ELU)8Gd} z({y)Fb`gP**{eMBJUcjXiI*0FG|V54Ry(g7gJ+6Z z`hrh=I%_QXgOB5^mL<$O?#|QM`q3_Xm1d+j*B%yDh<{!u8<^zL0)7X=r?4hRZz|mzj%-BwY{C|tms(;PTcdJ zE=`ta2=2&Nn3SGxs*7zeZeL4&k(8}S=$OmJf3wy6CV56(8L2UVT*C+J5-euScXMxW zEBTB|2z&AuZ89(5TiZ232JlD@K9p$rjE!I1w6_jYYUyEDFO%>=@IR6+^5fbRixQZA zT^DL#wEdo9oaru)Mwa6FIWIpEV+8DPfpRuS@*Ca8KRZL&^nc84OLB8rPY9PnG zbo`=oxL5jPe_M^6jr6pmL?}t8NtZ|aZJ*nDS^4tnqvzF{EFxYHKn?>vZ1V^#YYyjwB z=FGXZph$)&N^(Kn(TYv#{_=1Bhr|Eh)i5iWB<;@*8|cIe1FKAU;JJ2maqjdsH?y^B!h7TWM6QX@Qz za;<9>PQ;wY(ivI`Kl|J6b){C|@>%T?QjOnkhE`q`E2Mer^To~AtW9@)5#fM;w@}&v zNMioO;s^<|G$qv577A`}Z}+Z+-y^F!*Na^{?mtV^W#JNm4|1eR=}UYs4stouvoYgC zEY|hri_M$=F02c2T~-ypD`gJH`LVb@CboV=3oO*#QG|NFG*?*@B8?tiG+j=W zR5k4SNE?|b9dy5Ob+G0X)R5(6aeJ(_Y$f1N9V-X5Xf!_EMS;Dz`wL*sk|bRiMZqM2 zgJY>AN^p6$!}HAUXkm;jYPe6w3%fL&Ir7)BJK+qOP)h^TX1fE`ImuJpUjIE1_&LhN`fI zJe9A&DR3X{0rePl{xj6+Y?+txzZ%OptB>;8Ith~5m@8j!YHYQTe)-ob__TVr)%0ch z9SWsUn}D0VwfH_t!ZvA`3gxq&;nTXhxA(o9S{QE3=w9@R$USC5PQ{Q7<#i#7je8ZsdvCqAMWUd5tl z?OLPZLM6fvm>aW3O332kM1=ba2#!)ab0)w0x6t&++Mo($Yb)H8(VhKL0lDeMqE~OK zfr9gn4z;})sQJWDuPUGqgVZY|W7bXpDZwH}XP@h5vhb*Ma7i=bN8wotXgEygt6{~o zs_zgt5<@D51z%5DEe5+8A>>~x)0clTvp@1)9Hfe1<`>gaw~g2zSf@gbl5W((nNPi<%`#jcKPkB@7~eDB4qKu!D;fmaoA zC~!aRN8`fhv_gmL7%=eC#D`lI1f(IjK?AG45sEl`B0IXl8d5D8wv`Y=eFM*h{fqS^S20NfMmC||T)>B;g~X~VmkYa3$%TEm zSPH37G27LWTvl)i{uh|}bc#hN*8T1NH1%ueEl0welH5}kStz^DJYK3#H zRi#)6u-AB5PF`r_GsmvC29JWw)5B0lLiXqNyubD>mZHr@MhC!7 zKJz-6-bY=ha`edZ%RaIxQz}ya7!z&S-Zt;t@ODxe8)2#*!&q#JD5Awa_RhayGeAw# zf=VpL5CZJ0s%$J|Hvimd)wo>@aW&-Pb90zxRLfR3`m-g6LUfg_$0A7Iv{r3#tiY&} zqhG6Fs~I@+>-PY0Qvk&B6GOyeF(yx(cJYP+~334Y)eeAzU6;SlISF0YNc3*s_}dAHG>qlTv;MF4Hdf$5)te1V)l-0lNw~cJ|Ijn!rumV@2+db1Ye&~O=ta`F2>38|d zp^PVjc0DLN=I>$PO|D?j>Peq2ym(qIz9v;_>p~`IsmRSg==@KS6#5+>z$k0 zEWiP^Ehd(3w19NE%@yqA=377?9p2xOoUb?id0|@#>kDZ_OMtD*p>7o-eJYCNVKg{= zxL99}osml7Y{j;!cYJa$x8?WlFr}}7*r(B=vbdP)U|^Iyb0}J#dw@mQhc@FTl}&rN z=r~K@mCchAamsI$Fw`?cJsUESkqO{1AY|GSmxnaThT!&_kD#YW+oe>}*AbTH`(R56 z4#r4;?31Ox<3=y>VCeHvd{&`}@n0|rOxd=@=T@S2`5yN1Tg24V&}afA<2nx2LHd#S z{hAUYCtIgiUy<1SWhbVqe+1=#O$uWdn8v*Gti3w=W}iOp8g#*6#bR4LjOr)ak|YxX ztw%9ib)2rqXU4Dg+a6+}kZ1mGd%@r`J%= zAC}l}4ulxg-iBm)!&oD>^udJ?8ZqYG-+WHM#dh(RCj9rOHxGa3PLQ*m*H@TU=za~8 z0Qt@6AU|IK>;B&Ac4IvFw%e!k?&FP*pgdvg9dSq|Nw05UEBi%U+!QUgtk+D;5Ee?i zA~w82U>hUU=xkW0W{+CAh+k&VgI@pvW+N+)%`AC47{?L+n#zDP}iuqlZkY!jnn8@{5%rS>HiQV6C_sDgm#v>{j;8GNer2RuZ#Em zJx&?H$iiz#7d*4e0H%`ahbn2L7uIDp?7VEF+x_Oa!W%Tkj55y za7#yrL^@Oq_gIYIthUfzu~n(p}=;k0@NCRRgJdDq*G28@e| zA#!2DGnU+1NQj-YyDSQK3cVAYl|I|lG z>2R5A@YB3~#u<`qfFotd3vY(ew8l-H`E(o)kOW;GlpoHFe2iOws>u<6W>FuY&>mxc zqrMtSrW5h_`uHz&E=!Tj7wZ!r-)y1kvgC8I$jL(KBj{vz!Wag0uznDFl7L6w6tm(& z-8S$=ClDkD&(((JVBY>eOa<-93$r9*l1^*ujQMOqyJtJgx6BXj&E}&tBLX8m#dcnF}qxcLwwbi6`Tu zU~nGrL|NOyN`Cu15b zS@)5Z^$?!%d}+J*-QC8h7o96EW&FFlYp+3HF@J7@OIXLZR&TXQWwh&UdwDz-fh9vy z#EW^#wybm?7~f6fN%gJu$-(bHPX`>7tg5q}?nNWH{yhz(=Pqj9lOf7QdNHQ$IlVL4 ziRaGa%!Vx%>h4*;%%uIO=sib_0sEX8r|ylk6}V3Mh0IA>@3nVs9@m ze@;#*M--~}`fIM}+T!kPtvq~q_7xk2nTa2C%JX!s)n0VALmlq~(buC5n11F?iW#n| zG8{)&ZH=SJ`Q}+Btjivw%(M6YUeG^$p|vqeB(Xft{?R0LwK&xqFsIV_pD$u+OCZy? z3^QSn%tGsSFTN##9SAvxb2QN@s{`Mg&uKZG#$r!)e;mG(u@607RAYN0PZG5J&Z4eK zF*4REfN=cEJx&G$LgNmX`3*7SvmU)AVf$B_$l3b5VHWiHM&DuI=sIt=uZ}*K)T6|&|W^r}t&qaSY-vUxr-h`?e ze{0W4xX2uI+T@C_i6+jBi;lF^2apoQ^@NbWmZZjr3wPaPMg8sc2=O zP(FFKKxBR-09y1tPj*swhRs7KB9%vzx4O!WPiV;vYW?mL0-4*<;@&6d=w>l2!+(Tx z&Qb@_Bbrp~a3p4shrUiIvwIYy7P~Vx)mZ^Q3Kbe`D_QvY(cXik?;-rQo&7Nl#ze8Cx32Of!_Yq5&*{!JE^_n~svB93rL*R*sQJ76bkn9< zk=CeDL@~r`1fGD7 z+dBJqxJh7mOvKUfBQkCKzn$muh3L6o)^&wsHCnZ8;_K!Eyu8<|>H>B7px>4iNCf?> z+pZegj#uM&ZoCm%BU=6B9hBOF4PliS4}ZK9+w@Q8p_9vtHKfb zp~%la0>A!?bw4`{YCtges;qge4XTg53O67#k^V5=e_7;|kHyZaf!w|~%vNU)h^NTh zRjL3o<}KL!1?5hlQaF^P&tNI+KrufPHSRo=sA{6Mg7U>?q?I`2UH_0nJM|90X zkKSpjo8nHIX15B1U$E)o{iq`F@L{u^zEw%SDfha)tIIlvz&IJ?>_O#!DgdACkMBF~ z49HnXr-}bmU=azeMqrx+KIYTG1l5UwASKCxQk2Z@aU(amVy#>Js@82`RpU=~iHq4b z|LjWNvKu4{@r})JIS5+(>|Zyok~|p4QuCghnX-?$iQN#iHq((Ev1Zr9$T(JO?o`l35l;oZzwAc@eF?yvns$xRNn)Lc zC)#L)7(oF2Y=**qi7_^NiMsYtrS23`|Cb$pan%*7<7_}jFYRL(}*&ah%* zqRq!*KOB>--B~HXLw>nAEQURlt;%VXY8Q6p&UI4-gV zQPKoAXv$>UW{Ve~kh2noCi0Rj6IHc7l@Os$aSDVP28j(5B4u7jn543%-+7xW*T{&t z?I;Z^n{;S7-LiU%UTuzH%W?hk$aVb7@x>6w)ndzD*s1){Zg@lU5ROntn7Do^?qL5o z^icG=EIc%FClWJ?%e_Kv~qkJt2GkHU)e&n@h(5`Jhx4YWzbwG8L+`;*IrHoZdy+CP6~ zZWJfp1Y<|Pedp%>OW%?w{=Vt-C6d`lnw#rQF(Z)tK^Dw@5YMVg>(n$$-vB+P7R6+} z6)7HXwDYOL0bnhjs8Wq4ktba4Ha>5-ZW*JY)^3$UDzai0rZ|)Ek zw~EN9g!oJp<8!76SN*I!EWQmBRssSIXjQm>rx68!p}>Zuxt+^)e#6)+WE_=Y_@nVMw57^ zB1RP~l(4-Qf`?yBR%HH$vOc5bte2A{r+U4hwf1fHPJrG+{_KOYDPK?}eC+(fWMmz#5CBaCT}&MO!|gQXZ_!a`IJ!*1oG zj!8@FSH_4Jzw~d)wmZ6r*|WBZVG88HP18Q&_?6!!U25dl>0OJS;Tx50*KrgJno8&B zWt+(V2`OA8EeLN#uTv%4IBHf2a@91%u>KGiV8JcK4;npJN;1RJm7G0QC@J2>(Rx9t zc+`Jwra7)bUTtci8xqLOV8omV7LlFpE!H^kc*jG_4@qWp-n{A+7#&7v6-FIQ`OO^q zmaAC6V~B@wX?&*&fB`!15tpN*kjzt^tVS?3W<>igz?g+4!1B~CBAPMO$sU0q;nTiBFC(hv^HkE(M^mfr z^_R>{Iu>Id?b7GTc>XfYtx9R%(}IV;QIB9`@%7R)j=9!MPwHdDdjVW5Tt@;_6L^9Y zEC%pE3pm-73A-+Q9Qe9!-meFF$#50bmQr#woq&kH?x-g8CuY0oV`xc1Jco0m zar`~gc}LKu9GhAF+T2(h*vaZ-6)sT8FgqK6t6F6Jkv{%*UiqVTRJl@IQ%gc zRed%DM<5Ge`VLhUgYz-cbh3ef%$V}r9FVl%2JZw|P*mSIlF?xHY1g2^_(fI;WoJfB z+*j{w9b>XIL^K*^;v|lN3Nuz>jCFMu=ANtf^2&AMvS)`2__@6WB2>r34GVd{#ph*+ zQI)kCPK}v1^?~rA(q^%GzFUR_pRSbqfN$wOa61)}*HLCEw@+wvaTK8R`KEy82DfL9m#wA<1spd9YH*Rb}D%2c({N?GYse><#yY zA0H*cEI#pgP^b&WWT{a919$Dx5#0-d5}&-7fja3PicRHq{M0i64BV>9nHf28nucsA zsSB1AWU=X9CDUYbDxI##wTY# zR&lkW4&-9AF^KeH_Pke9{`m6ohx&AjT~E!?B!iZfMdY=YTO5imYfyFr`rUGuI@WGn zR`U7XHVdIXEwZSPjfrsV^Bi(rj<%lP!t;seYL?2Zv5Whk+Epm;z5eyTAB5-yVLpJa zuHSV62l6+_rTr#|rFK;N*)wZN=+XWvPC|>g&ld7$@Ye`{pUY6LJP4W$f@LKnKCRr` z-+>Cq1qQ%$*dlC{nOr5!qT+4?9~ZL`cRY!U8=26=HVm8T8pvr^8)tQkeHIO4b264u zFHRR3s$MT&6+e~L=eKivcmv9m@>H4<=mY|uG!a%4Hx~2pR=`PL2#_(*D4zpEuPueR8x`LOrJI}83JK|Tv#qKBtMqJcvZo{NgV{6;KfBz! zyu<@?-NH5QbnGUoKz(1^{>06^hAU!^58c|r*Yh=r8eET)E<=aRe_stMasCZR`}}oiXnVxS!azImLcuZ#t8rn5Up)3lG&Ca1nAq8B@g2Xtd7{%}9v z=;LGYmJ~zazw+e>@_W;@#{i1FjO*p%XY@&ocP1b17W$(rdzv7fii5%skH!>%l1$0E zQn7ysd+knj?dM7l0JUP`44Wri3#D|GxT(v_rCetDzf0Q}K6OaGw#MA~U^rp2);|~` z07xYf<^D8{xj}C1^eg7g?6;A-rXFt_FMhCm$5p>6`9l*i<1ECfmVI(D{Q#mJGv6+h zNnZ5PIqVzhR#qnNvkWo9YcFfI%(p%vq9D9mW z9(B)jsP?gLj8tPVfw>hf z3aydvR=+D1XfRPS!#%T6B|J`{BrJ8yv49zA?akwJNT6#k1fuG^JNQmu#t6pCJ{Qk* zQuYRZL+b;`!Vkxn9#6H)16*jf)6!9w%A8r78iY3~GC~AbZ!E5fXFd+KhQWkrm$tTM zJuH;2mnNqT*)LBxLX_5DV~!ergyp8BWR+f6Wh0)YaK*`s&wj%_6SO}HsO6)T36GJF zyf-AI>+|@cPU-QbfY*PY;{Q6&N?ZZD?Z5~PMu0@G=Wk0r<)R1uP2f9cnUR!tznf8+ zV$u-IaaIx>>7Vgo4&bn6I|ey@4Egefn~2=JqCN9y7z+6@HMqU3VfXa-@5^_}mF^!D z4By9KtYLSQb;vjeEw<8fj3InEu-Re1eB+^X5O0|mToYESsfXDuOW=xHk*<6kdc5Q_ z&E6_6dpg-sB6EjA=jA3R^a;n?b>)5tqqo*Z{!>@mjPn@}>pEN3CrmtGpmsldK?tZT zRVTw5CY`@F9zP>2#(e)|v>590jbj29{e4AFUYW$1kBjK5v5aQ4(+_qpKq%MjH=?Jp zclLo!OIRqP3O00!D?8OSxSnXc{4{upJ7vG#?&0v5=;}K-aFa&J5i2b=KOyDemMt}S zjUa`^JglrN->hg14?Ma2fu7n9aaf`m#kzOr;iQp5y|-L z*LbDtj6Jq|55tt6wo~2tkh8zAc|yis=xK1_t2(qdTgfg)nh;N)Usu8OvI#&L<) zH`bX`3GkL=e*EZR;>VZlB|8{gJQC+^SvjF*07%$R9T3aJJuP)ravfVs_Z`(nqn>US z+=a4C?eXzhl2MgY&fGTA@sR|icgN%gnn=?jTuqewpMrKNqJw=6`tEH`jo~gY58Voo zjeGFXnVCVl%cYR()q#zZ@-VBNm*TL#`RnPFg65VM`03x5@)VAX{kxk_y=vad_k`G2 z`;V^pD>gNCbS%uD9gEfpmXVp69?yvvrUU%DK2`Xq7SFj`d9u7BV0?$&k1PyTPHK%p zXZv`cj;;J6x0{uk2_{k7p(twcsHbH8i*c@w)PM)$V%!dP4%)8!uQITRL*!chJA*!S6M8#Cyiozlbm|DaKGZn=YxDi`JGCg1oUi)BtE}Wgn^+UyFxv_ zkf7P7$H~z4Q6&EE9d13xsou?LrPIZYgA(X>e4&`l1S0kfCK*PP0jhszZ(QR zd?pFeA}D@4m0{>%hX4W|Ukp*;f zva2M?Frdm^n%;Z#IY)dccFf0M79*Sa90lp@=4^$ZYB6zlVym{ccU{Y^mW_*L_8Q9N z9}~8Z0t-@-$2r3P5e47q%d4i8lsa_Y@5vv$l2ii<*g+|*nZDBX_IY--$o0?R@UCy} zbuci==arDed)07xC;y)M`+5~nZG@F+C8@l%zrn`;=i+C~vR<0lE7IEswVrD-@Vo(1 zyy?BM*y)lmyr9`$&jit0F7JIJm%Y6!w4`4RA4Tx;dsDLIu|_7=?xgY(KrR6e6U~-0AXpq+^y}R4j-HigmM=x$d;}jvmj6l3J``K5@ zQ23aPYklxTMh4bR`f+`@j0;t_{PjRJ$32Gmvnj)t(_MKv?V+4_?3f-{q+6(Sa8Xt% z{GiXp!2pvpdK^|)=r=W--PCew*NM8b>sIN?1YGKfqSV({V^@*|ukrl8XQtWH!x2vC zIyxE%zp@Fx-0^Ha8qsu^W-lyYBZhKrJA33NiXFIN#CI@fk(|y5xu+Vxi4_R5MfkUb zdvSmDiolhfXIfniZ^QS@!%a>$j>32a@GEulwDx+LfuL__%7zuO7 z;IT7`7r#ILkWCi*_g+g!ubUk_LRu!S|2_eUcYaM3P2Q1MoGIJs%VXhtmM)YCVleS6 zEzOOkjZoHOvX^t=Td`&QLhBL4+7SKOsygyk@$Qce8%m*>35o>}y~VtKty?0fk7==L z3d{=3#=|VWjTaO;?5$bzw@qPDC#yeRlh%5fW<7U+8{ND4PsSj*q~dpK9FLwdlk<}I z`=ZDs%Rdrt@+Qy?l`v|D+)lg9wu6o+*ZH*utaNF4htpz44oUcBu#2=DC%FK(+PuKd zZ+q)`suAM}GaO42F4Xd#kFd1OZ>!(_#}|QcUT=m)G$60YRa|N{_HkfuyfzPZZw1U{lv=FTw{_ISs7BAwWK)X zllR~cu$o92|5m2SQ2Cy4l?C^J58tE5Q&U)rt(UcswTWaw2$=7wmY8Jx4B_v~qhp4- zu&sm8y(dGDPrwP}gNedv2z~cldF(^z=1p5-^n4&$RPbPyFA8<Qif6Z+e?=K} zPm7Fbt@@9Vvr(U$4^!vPM+&hiAu-A?D z)fvTkX9PIAhxw=C?#w|utWO{Bx~-20xpF;6WgJl^m$dxUM+eeffhx5|g8BJ|8cw~i z!;izS9IoNl0lv*)dn5TysgGdwBn5I&2iJtZIq1g$UXAQ=x6iti@B^1EZN@lnt+o?% z+n{#)ivBEi(0mIk8iq$Y5X$)(cIV|Ew|sKzF3%K_Tg~+Cqm#f9DPi0gpi%bP7?*Q- z=?3?g+dCOOvZ%I}wg~kL!^yt|bq}JkmO*=doct_;<9fzGr;bn2<9a{YKmm-AIUuH4 zCAH>xeRdK`lwZlDUg0c7{dhxG2K2f4SUW{Rk&r~r_UFS&qx=F$;tgok7i z`-sxMnR`R`YI2Y5i{t+u+oyvHiq?CYnRRuvSsnTK{ZG9ZocDtB$w(BMAI90_+ql2i z@b^>wU@*EqEMh%69y0$LRk~T&k{5v#K~djOk-i~!pW+Xyw{_{5JOXE(yhm$g$#fjg zMkUNJgc7Qub;)?*)De}rq-`v#9{=9RJBT{!G_n`afN#ado-LH^+2t8d>7lpgW?Edy z7U8W&MJMLfGG0Lq9K@w1!$rU!grDjw4ShKC{~T|7^1wx5;Dyb-=py^J#O{MB&$ z8;7ZH_jtSSJy3iRzk;O;CRC-9QTcsMm*t&_X3OrxH-?xwOstchY=^`hh0PuzUqLk; zeWWMl873e;aCx9sg06N~YONT5L-_hj>Etd%)AdV%oOm88@I4L=@4d#oBtc-bLNRna*|bBhEq`0Y5FXKjW?%h!zAVewFQ!LqOcMNYlBG7c4hxQ3`Q*#Z=7 zS#7SKC&|&*NGWcE?yjg@&C7`QTFK*9Sp8;Aw^+a|*@rv!u%*)rNhHU(G6kL=ZZEdT z(_VBiDBb%y6MS`e7SJ;3(HcVh@V6JoFp%&+#`$~yGKk(EXC?qG<(D|gC>6!+E&wHK zaWt?PKzrX-!OfXseE;6ZSPr>0ebuv|ywq-AvIo{PldNt3N0&<^D%HCl})WH^K?f2c=G3z-r&lq`E z8EOtAKXTI(iYhm_3H{C<=kdr(nq{*tqrJ%v^9x(gw{J1ma=OxypBKQUE4VC1n|>%u zU$T-udT?MA5O8K|s6105)48hjI}-XiJFgBY&F{oQq};|$(fGt8T_62&v5eqB zUuj>sh4h=ceiu=P%89MIf>wgV)vfFO;pcLdx~u zYdNJh<5PJ}^fkdD3|?1QhfX7AH^y}AzeH8KN|P?04Q=#o+><0+5`Dbq8?}jcp=U!G zjfFEU4+;57XC{(`rP?-I!BCQ2kFTFTVICsgV3n>BpoAAn!$LfRoG)uZ^{#!lwJ`UY z_5CP5V;<5s=eZ?*Ge8S_Aoe+I)$G`_qqI-p(5=-QArb zP)?6$70ah$D;U@v*_u@0VGmB2c!TKzdY z^Ft$R>n2ltW_tg5RY4{au=Zwdg(ZiC!1C>n*6E9{+h|%=OP~Q<=K#q(==o)p2de{O(^C z5uiF558&HIupvha;Ys4Dw)_+4I@_^zLe7y}EOUa5}$9ga`+O9m3R9x94cq zyog~?(|edr^;(`MsqwT?jA>$;O15N@G)J~JFzZ;;*rm<9fP(eRtTatX0qkyEQo-2k z!V}-J*Xki5Ur88Qo=`hiSOId~%tjGU=1pQA0 zfReyN1oNKAGUN68Jj!hD6tr7*DjB`WQzeD1(md8m2Vg2G33ZI|M~r3%^&WqL8uRR8HudiIK}rH%94q zxUI4DtB=mu=I8VcDty!Ljp0VTWKH}|(LShapv5!D(Tv|8I(W!SK_y9SoU6yX+}OTP z)6uL;Y{T);HFn;zJSNG8CRZ5tbhHBMmX%Rq&fUrVp>(%^XRJ)x#a$mgE>xJ!A;gdHLa-m6o?RI3eR7h4SL@S7d?}pIE{4qX z%~njVd_)naXcJ#J9}BqXvBws8}Gu`xhpes=Os3SoZ7!O83X1wyEXAY0A5dHV5 z8t`GQq*c831uG=1q&KC&20%J5)stU5ORbcM4s||3??>7`&r=7HI4yM&G3EF?AK4jh zKV#>)HGd}+GLyn@->s^vtFg`k8qruieFwYks;V_Kddo9}@POp=cW71&w^VZg0GiHI z@*KBjjR$6zgFlypkzV8DzbyV`k^~%m?T2)0x1P*BW8hiD$r6Fpl)9~8xS@#%z;u>) zFjvQdCpC=K>oKKOSn%U=eZ-7=?pmomuIkjJ(p?GN!0@Ip=wf9kU!Gvb%dB(XDm}*r zX5zlvG3Kz;Q4tfDgM+SVL5Ne0;q{NbR>F$?kgLGP_L7?nc6w)XXm&Jw{Z{y{jndI* z4}Tf>M&#U(bTVnDG3o`eG~eY|$$U7CwOxNSv3GUu@UJ7Xmbiv4NC`V?Y{smsAFi$4 z{7oaOs%GmWT^QJtjX^sTYqQw%6TYXW#8+3TH|AR;duomo=EOkS)-pgV;v*`f(y zd{0eeWJxy#61#ZPp9+#kvKXk}Nn@hnmF8t^#}l4!Zu;}w9X3*LPne8{tdg~l-I)EV zNqh#{%w=%a5g|v*@@m>CyB_1{X6yIs z6BD9veC>d>67pwyT(`CsB4`?nD2k29VS*$%t*C49y_zxUUwB^3!bM9)3W7r;V`O|O z6STzcfL5#^_cd_}m%n%X8X6IDtHqb}GScYM%Jruwx3 z=v7u`XgF2eMEKU`Mh_@3L6xqLUJ@6F(7L&tH{ac}-U!Gvghk#b+G{#djMO#G7g zVCwFxfmDex58G$eu!f74QGJ^_uI@&}cNWiCedBb`doHt^22Vuu%0gjXr>b+~|4I_H8i;?pN5+*M1LVvsRHBmQh9 zK$12l>yr@xl^bMs%ZSO<3F;r%a6P&g?&IU5ko7U{mPWC~o@V{)H#5l2fIcUtqV)$| zBt+D^DD#hkf+_;=?`sHWH1Q2a<3AuTTTtSkl?V)v{(gv}|L;d3S+k#oG5s_var&hOU5U{L{QDlZGFW#lQHATj!GEz^G{*=m= zS`qjb6mR2xSEq0J;Nnl>^ys^x_tBd(pd=pOQ6jM$m#+T%e6@r}Jh8Emb!@Qp?2_5? z*}~tssE-vw3c2VWS(Zv_92#{LmaAgozV=g&`RwB2ccifde~t?eRJ(j=hfueh%@6lo zT0Z9N+&X@=nx}InSb=`T!Zhjtj z0tcbvniM}j0*pT53ACv(+ToPHN+*9&CB1~TAO!$4(OkWXtZo^@d7q=Epg${Z45T0e zY-=pEz5W?E47Ohn&=AMNE+EdSYGMMH4XNV9*h-+q@2`I=%+1-UDjOIev~GH!aNZct zLdB*KEQ&?MS>VlEoO$D28uHI?h*!PGhQ|5UFfJ5hCI~S9F^4|`wRbJ!Y*Gx5dR1+C z#J?ou7kE&zgVe!#D;|a6*M}Eh!wyzkK@a)AP8KUXXEZb+*Qx;I)rysHo>k@E1!t=O z;(6+Urm{JK&K_&LC7|Sd%3t3)jI^kkq)yy(VRV~tU`}bCgtUw#+1nNI?2nn{xCRW! zSQ-+I>Kse8%4$&L^P8^FO=s)KA{%rnpb6Q6zrwxCwu(1-`<#v#w!hT$RGBnE>*d_U zoYvfl@*kQiT8*gmDWX6i};T}+RR}JY*W0t zMxip#TRQYir{5vBOMhPZaph)Ch=~2$(4P4=#cg%Ria(h7C+==P1~o7O7^BYQ;D-C5 zHhE zE5j0cwkmTbcift{WZ#hs+_yZks2TZx%0U$U1yzR)vccnpV@l|*#-G1^Uw=fAzP4U$ zNtTUw6+AbG`|@<)Q}#TEV1i$*JcFv9BVVQ>7IzQKhPX8_w>$1!u{QHTRqHkAQi+XD zP*v%XR9yqF6M*NdJslp#0ce11#<;8HMsAI+2?t_zXoW~8D_LsH7J4L&`c8ta-#(jwB` zKt5IaXv!=_y&=IDeR4DqWi~BqjCo0>9!_CUe+br1ep=iinm03 zL;;G$qLrm&Zf;UY8JkG+ak22ZFtn38F>EeLGz3r1-`w}TMmf&L{P5W;*cTw-cOAQjVS19Q-(dL)a5C%b9IYc2 z4K<=kjoQVT-d8rSQ^)qGeqfon8ArOC74K0gPzcIvl+#L37DUT{L9>DD_ z@jXIY>;Z9&p#HF2)tm~!B-l{`9+*;;llpXnX^*T)L5*XQkhZaH832&tCR4`IClFJY9k7QeVY`4;ZNZx|A_~oG26b%ifm#9{34dCrP@ss=ADjA9e!2#ps%dq~?#NUCP9}96 zt2w1+!7E&ODHEs-5FIY1?vl)e)Ky@*s@pDCXsM{0?N{@7C1v34KNUib%h-9rj0Pzw zfMT8&)&~i%WFA26t2H4KjHl!jo2z!}3tr)Svpp%LkE$qkS=n!ZjsS0RJWp6)>SCjA zY((UEu(L~SB@YlCNBKy^rF54jG5+IaW`0{6OyhgA}Bc`H9Trt))2EiE}~AW9Iq9v z65$1NbJJn>-~|4`E~LqpkU?~K)H8###1?j|syxh)R)C?*F&6sOIqrlfNnWHi)7Xio zjUc5$yWL#;j~^l4IDq^-Zs6@FNVTv<^?Z$48sRQ;FwJk&$?}f1q9dq%?w`A2sLvx7 zmIbuooEZ1kMp67BohU9Zg9OM|Js_9x+)pv4L%Zv z%msF1-&)5to*U|Piv}P*FNhA)WFj*dOxlU!mQz>&{YwLV&6n*Xe3W4+_ zE%$^6yPKP_A(b8yl>^TzKg=wRP~SiYWtf@%^(n0bs-#hW`1hc6wbL`?%=meO_UcK1 zIcLcS;BYmIYNCtG4#DiSo%*bnBgDH|81=_PA_5B~Tfnx<&Q;9?Ze2a?4|;E6pqHn+ z+gkkzdj~*MIRVQu$OD3i@)7`95%SBlu}(FuP4zO`A#f|8X}67-2&N-=@zR+LY)Yq2 z#>U~fad@$`dFR7UP;+x`a*DZ}3#4A2d1%O8tb=lS#tcFx*j*QRXs5f8WC z$JfM5OCJrO2f|Ob+O|lqu!VgqO++SV$n;3e-VfPyxY2*S0r++IQ%`z_0$O9IHR&Z3(Eqei zUk#Z{t}*yu;>x=Ff>^VJjiqg$I+)qsi%&i8DabqKDW;GQW%dA9id8@GYyZXVSJ(#OcPvsVF_ z#lPGg%wq)>DXW9DaT}LDL05-|1EQxE6Xub@@MMF%s^k<3=p^lycnT@Mg{Mb$Q$n;) z7UP>wDv}B; zRRL`(F;^P1ln8nAK-PhpX@>*O(Poo(pK!UI>c5Y7rv_&(Ut$h!Jb%6j2BkPWY2MST+Ni$mBHSkdXr} zciN8MC$Hboc{10@-6?pZ2^|^`jbA;k@Qo1PGwlk;%R3ZjCZ1dc%W*ULQX_FwNve$7ibJvYxIu&;B;1czrq!BNAL= zqTKhsk2_bl*m?f0d$bpcGxp0OHnX~_xOEF3JI^93t~$uWq?{Lj&MDM#dGu_sqz}~X1L^h<4#$ThOopq zP7-0M(b?IE%+ai&BH5i)l&v`q`!2utz0b7u98*_ntSem7yL!I+s!d4=Symo)jprbA z>|KL7!HXUa!Pk`xbJzVpCX;g{zD)0gUAeR#+qB_tsY_W1qZAB0tp8gJAe5QYbz{7e zfwh<@f6d(Z{#|$`xbAv4{9?ZKaOf@(=dTb@*Yyl-L%M;ZFUMr&Ej}vYuUy*B<-`5I zi_V`Xz^@OgFSm(-;XCW)s4R&my9@&-=j#(hINAO7mV?Gx;Qf+_0C?ER73E&edGoa7 z$mFD6^nSgA`RV0SBD(3t)|yLGJ}P#70KJ7oPLJbpIAM@WQ;V3)URoa~G0e+pUZQ;r ziGeCAMvmv5BgneNH$g|wpFDX)PDNswm6bEDrVj9zA?sXx^+G0Pb9LnX@-EL`KA@^B96~XRffTfhfgE+0!_k zg>SCqurpBFK#IyuRX=+HK#Ym-y~^xzo+9`_ys4$6q~sBP`o$K(>m_n>r-SWaguyd~ z%#F1?S&!NQYMeq?;$G+NSu3DSI{ri5CIukw`~)hmTD0OX`$h>K{Bgn8m}>&QtIcGc zN?A=I67b>Rmt4>(gjh9|$yAf298_0c*8HP|4>+oVs1hCP?GV9=F3@$H_Erc z-9w-_&y=JOmfVQi< zg$v$FMh?8x-a?2TryYg?(yNOMuO!-S_QGJzpU3+t2V=&rYxvt@;nEX-erhz+%LZRr zYyUa8ji=6_%X~QVyjqSvbZnVp>*C|*l)CQZaMPREDTm;Jzp9G4(HB7tWz*g z!wF0g3T2L4zDXLy^Zw3jiiC zz5vYL>v+Kg9G?RtS+L4m(A~umMbb4AcnV06`e(FGA27noEcG*fwyy2!#B^ZNc0T9` z+smn}!)t!Cpwt>>^qweGT&)Q?+@PC*OWGI3)-|vIb7C}K4--7v=Fz9blpKahR_yKZ>BaeX0w z8h3>`CF;ZShKYf0sQb)Z8D?dHL0ee<7v0=3r%gwd4dV%xmP~ybI(y^6_@zz0t_i=E zMu%xAF`Tk&t>CuBM4eZ~G(~LiXAl*QNgdy)t)-16JNh?kmlMC+>~~BP{)|)-iGr3| zak$8HofLP3D~Ol>^KbUz%uEa}zRSu+it-AO$Pi$T%u&$;pgC1;x7Wz+ zO!)R1`p6)Bja5O9;gt4h{|9EgYc}+heqr_4-?vR<>!k12wAQW1Z%~m`$y(@s@6!E9 z(00VCZv5g%VT=XVs@mbh(yWZge897ytLCc}!&cw#NR7{#MH=)27s$3_ImYVYb2^q^ zP32iOZE&QxkBrt! z)!!=jGmDEdYs7{tiUeJE*F4y76X)TrUNZV=6%F4%|4h4@;h%USroM|?nh99N%kl!V z5_YxIITPu*_=ksXJ32el@>@Mgj3+T9>DSYYkRqj4ZRd_J4-TM!Xs2#>Fx^uYko9$x z=Z}cozL7(=#-sC8t5<-pTMA6d-uE6z-O+kO(^_UKo+)!*owMzr&R+fJ_+{8^5hW$Z z?%jy+li|me_leoXz&F`4TUa|KKFEVRA+CQEnRpdssU3ppm4Fgbb-0x9(~d~#uhBcQ z^?@N(MFhG%#;(5OlCzbx6Xywb*NmMH)q}QxJ6TZqzi1Zx!TsB@Ul;!by<6G254h*R z0pIbv@|%4{8N45OZ(Uf4^lBwe=H}=7s6$ZOpsgA7eIb5>VFCj`k||UYHZfWoZmSPk zo@5rjm}~O1vzt{2y?9=SoFRI)*Z$wrJFYo@-9Zc<^PL}V@>qisivl}z7Sbe!tL@|N zY;ngz{7c?`y*oa~$O&bc`#zL3S1C*f5HB3gAPGOUaS%4ihXt-z$_$+nec%Oa5;$!$ zg_?&cgMlc$;(q*WG6>w@;ST#>Y<+n+)bZQy3=>1bj3r7MLqcSkii#|aeaez4OR^7= zEy>QZf*W#14*syQ_J$dlqxx|fw|;N12LiU*edF`6Aih_5RiNWQ`2f~} z_xAQ;v!VLkG&t}GF1WySbZnT?fZyU1Gsl?{)Psm{sASP|_|{hbkS$qRrhkY&bpWs6|f z@@18}Us3GV?^14}u1vHmO7@WpUa{bCTR@t*`poUq;Y#UnC=l*LKx9}gR>)c!rRABN z5rOzHz+0V-4JyeGyK+mX7=TrKb3T{gU7mTjAor~M_{qgxV!^ct=JrXV`j)!GH0`Zy z`TMG&d{a@}*UAu@Mm6~spgHFT*T#bZawmPXTRf>^aW z>{p=yScxte8+#%njYGwN6vYuoegwH;ka1F{cx75QMonb&2MloD7`13tsbYv^+Qax@ zfX~W%dkKm4k|1kYu;_5Js{yl-?mOCgQTq{7{41IGFZb|!AC^Q)D68frdu3k@_*!1t z|Mps1#pasm+MRL=#AQ3Sm`@<`Jg}8x<((sc|3@W&X&tSHVi)9kq(@$ZR>fF@<~Xb^^+S4Zve9cc(ZZw>on$*vP+wO3#(%ue^3B z@Y1+9I6kyg>yuC=ME}1R_J3X7r;oRa;6QO6Gzxu8`d96fCW6;GpA_Exh@&I`;mqti zX@u{r_Dc@YPW(x{7QQ%@*_O2Yc>KZ$0LV_Pv$U@Nx$RTgkX3Z)y8+(mo^bkLk4Jh) z6uYo(S?4r1v^O+XdtnMzevJ<$udgF8EC#u$_3L5T;b4aYIz8m;PJdxUq=w>9BM|m^ zYW*z9{>UMAdxfQ`Iy5-O<9(*A{dT$szTYe03GwT#$#gf z=Hy-+pP)v3CpIh?0u&PB@C!nkKp>kaDN7MoL5OaP4Mf$fPK>aPJ&NdLJdO(RuuCQP zyl)W2Y%Xnt23ZRP?eDN^t6Ew`Gg>@SC-hQ%(p~0v`K|j1Q41lLDK1K>$B@AhAJ@{o zFW*1aV3YjeW;2KHwT^Oq9YKb|ds~@58k{Cs{2Xd(5bubelA&UwPZF(jMOa%8? zfpqx&q_22FoX+sS;q!w6`iwjnUz;TEwGy^lrkqyH@#jXeN4zc1wRk~cLCo&k# z&o}7%k=_KVj~UEA+0rUrzhUds4`WX)+{OHcSp4ok<7h|$YRUh_sIWX9&m*EA6Bn1Q zgNH$p+&}X!50j0g9&i0T)}4q$IrFBzoBbB*MNzF>md=>-F-{wGFO=`i0P4Zvm!-jL zO2Pwi(rSs*G(KGlmh16aq3_05(8dKiOg#dGJ14xyNIIR7vJN8?WI1NB9=F zIIVbWJ4Gk>!L*RM^7PuRnO}Bw*O}gRxVyeoKsj-1#q8iGixn9m*SKX1%*Gsi3y5j(Sgb#T1!<6fW+O{AmQM)lY}|7V%Ktk+P2AGAA8=rQ~vsR zLhd5d*K#whYfp_DinTHPOnG!iHJI}D*Vvlvfd8~@*o9mrZyNf@--JSYPPv7@#{aXk zzPomtNwIUEYse3S4_uulX~9L)z;~LELM<+2YgI z{ZE=AXpwYFg*1G71Kn;5tYm2lfvY5ord!UoUFBp;UcL`5Of6)VjYlez)zyinOe!Um zsh;3wuhh-rr#fY2`P#iP>{e8SYc|r8!K$gkQgwotEvNfqB=Q5DfsUd+Tdbc927MTL zL1X}oJe6%NehZJ58OG;fjZ}o{@&XYfsDR_LDmjD-Tz+gH8P+X?jhD{s;WQ@{PuRu9 zd0~YFqd&&|eifJEZ}6yDRTc*;Z?9cDrYyvPZVow+|j@kBATQDOolM>icSOCb$V< zoTSVRo|JL&34+C_v9?HGAA!;C&@$x9qZznPBn>6|8q^7b%Eb<|b2Sy``=0*tb^8OW zWA*0+{9AhfiBSXa`#mfPTFq~$g#qxW*uPS`AUKRhi_MPhMqG}8M+iyu4rF%5(1mp8 z60s+f1bIA1-`$)QPtV~IBoT40793*nWcL=pF07Zu5Ekosnp$DG=3z7c2s7B(uW@#UPxhQj*4mKzTQ&q>@$ z8{)hjcFbEl?fsk7JMZhc5tHe;PIo5w{deU2#*ELteDr?~ZP{Qi`)>=ETMe`S4A*Ga zlxjvi1d2{rS}{VttuV@R-AN(0vjJlWwdvw~Ra1-6BA47#=`^w?Ei?hyTUho%QtF&MZK`_ zVaGL_x^0JFCK10Z9BYJdAx45xvP~7 zFWzboWVQ)Zt9`4P478uz9PM|g_vu(O)y~wFnf|sDdpa^SBH-}k;pD14Z7)Ff%GH_U z>A0`9XHT?EeuhJMuz7KD;zRFUoiE(;rRwQaOuR5W^JO4xL(+DZKWJQrD@Q3mWYsw>kd9o8(xJO61h?tkhx+GuXk932ae!CP1 zR35=XU+7w`u>o>Tk zQWwu{4paTgZvjdwnn9C*tZoUMLOdY3yn(f~TXdgg^s$7n0XKQo(^6q1rS-rI?KW1x@cH|45CDG};jbX1*=g(qiPjJV52AYMON`Aqr*NJM3w(Wq9k77V$?Z4Uot$1PYLiREsMWCi`48jCzTq3g*OJIx$i0KBW)7O97qYZf25M*HaD6LkEA`O1 zpe%|FV6)$QgXvjRnJ8$$4`$jh}hX z3s{CdCW%$4kb6d0X(rHmbU|E3HqK(WPMAco9g?hvpOY+#H%cqO0d!u752J8T0Cmu_qX%%yV%a8g%L$k6z}_uct+Duj*{^a?)yb9!vdc50Y?LwX|-aKUl^NgL!h%huKHg=Xo_h^6c`sQ2EEeN}9B^RIQ8N^EYbE zK^zV*Ui#X3VURlAigHeP#as9+%QfU!nH38nxjI4o&-e_Jz=9|! z9@Eu(shcz(shTQ&43OwL2f78|7d&?qM;1aU0{lUFM%K{-DWITa)K6RompfnNhje~0 z8J!hsz~Pb##l@-c$jR$pfcN0D(@WAk9fV+=!@#CgdtgVKT_j_XIU*M4WN+AqHuqbO;@HI;}I^0YMG24}RrzeR6# zAX+k~A`Qvo7q)a#%?BDAE(X|;j?@g%&K9;!+j!?8b)Uc9vl3NF zh$n@F?f?R%WOAf>Sy}+6+u42sqHtlfXojWQCahEx_! z7qipr1z`)2I2VYSd(kTo8voE^;^yz*<#Vf51*<^;73k!xcFE@|lNBbTlwF#WyouST zpxuf%k{k9FydkUNi{IH_1FfXCmEk-*J}%hvUEn--n)>Ue>tZMrT=LRC(-inym?(d0 zu^W$KQJZ1hIWIGp?<^^lI7|>+@b%JlK|oy`X>1@!^6FBbi$2QH)%8T{@5c!sA>E`) z0Y~%i8<&uVaI#(vU$gQO5%29(1ah53oTWC`QWVizG+T2$UPJ)W092PIhH%r6sMI&& zd;>ocA2TO~ge>_~ek7x^28~YZ(o|h}^g~0N(y)C-6e)7_F3Bpi`ETrV-BWf^1&SX?r*g3ek`7e8z9X3?I`}wZdsDuEfZ6< zxBs$y>`4TI@31W~0nwaFIFBF>_+3>b_%gqJd;b8C=O}sjFSmU+S^IFSo)@8&WxPEx zOfZCcR9;zmQ)HruAN{sz8nwy{qF%|4unPl~d|nxQ>qD{S=W)7?yB4z9*Rk%qw|_W0 zvpX3?dg+e&f!Y7HIg4-GUNf_wnVvaM-EV0-oDi^OdU>^7^nGki^*z{Jb(4__T^09# zbXtakEc`<5mVA8GZNVq8?0qdn-i5T@FQgzd%wJaNnv+d_2zAHFj}BWl z1qEQ9*!kYTjeKGZ4Iz}^z4&(of{k*6iLoqKu|!EePZuK2I;m-KpjQ=4X8vjm;xa?) zC&e~?ka#IrDhH-r0k}ctki6%l>{h$$-yV%74mWyB=YSf0SfiB9KMNa;A0}2F2DZ`h z%0VaZ+1Z7Kf7g=K4GNT;xSVP@a}-cBExwZ!^7QBz!zXU#EwPGg_96i7{S~$jcID&S zUnOSBo0-2fSK7DQQV+LR!+F;+8il1m?-g{j)csKag${fbG&OQd9(GgDG9#@t{isN@ z=2hPb@(Dh4>8FKs7nsrJa};|y{ZbsN0qY$1&$>bFOoncFt6liD6YU}sO;VL` z04UEQXo4h^I-7U);hjZN;1Z!MA?ew(X5<59 z80-6Y=;0Pwxjl2Widgo%W#MJq#jdKY9om{<5B=X2oyh+k&-TQt8LI4|1(`IP& z>1o=jZ{KWSwpJIQh3&0EK(RoDZcBW&yij~H=&UvG7CrtlFpaL{#Y~78-F01`G5wDg z;Ck}%Zk@eJJy$WVmhFM4P>Ic>VnkV5X)I%jf}b}tAB|Wh<|W-eDS57wlqtURAmOQy zqleRoqZA_F>nT`c(pLAYZIymmMd%J~B10VYLLBcnu^YI=Kx#;crqxpfb?Z6z!lNz? z2gt~#rhI|xzo*zTe-KVLez2pTPq1}^F2G_!6OvU;Wm-zjWdSiJz^~+ZVMj1@SqY&F zsJf!|RiB|phWXy)k$;{u6`M!CS|Q_ZCLjg*4mkOKsC-?yGDp-%X1)M+-de8X8Y*p6VKDu$}8+Cr*~7^UL4*1NqqY)pYh-{ot}woPNL_yF!wyt`@H~6)7AUz zT5v3H<4#fXyf*hQTkP1z|A%?%FO2-X81;L!FzWBSpE4%;eM9z17~;C*aPp*| zZv=Ah+Rk^D_6{+U?F2Y;Krvfp;N#PqFL@Dy5ZE{yB%`@f)cNr`J;LkW;y2c9j!+OH zZ1$!4NXO;`Tk09oLM>FyWCMSI^Y4A^m^slSHE$;=ivRqq$-~1A_htx83?pc$OHnfe zF|C-GblX|wX|+&(!|18gYmi6|KXS5uBOUj-8eyDZEUvHpc@%SM%}+@mO%uYV)w9T; zVas~MmN1z{NeiQDv{Wj$EU+zR>Od9+mT z+-T!@h;3ZrG1d}F@wLjTkEiM{`ef;hvMD0D(}5kv__hu2;NV?T;4D(}_4b6}{6uUi zM{s%kwTD%Ac-~C@Dn0l48JQ_^q$;V>A!_TP!%*uYdz^S2qFTkv<1Ph#i#%fTil$iG zUlsMC1b|Z!AfoxJFOUt9FoEl5fjHyj${g~tfN19YM!D51LL1P0t!G1nLrRjTD1|Rs zl;S;ZoK&lJ=Hcge{&x&!-=E+#$H?-h)=M_+bz|94z5yArO{?;hHR5rL8RoN_2i*snfisb4@0?- z(Hw7LA)?j$By>p}D~xP9lE#x}f*<fD@M)pQV#-5tE4P z8ifLZKtYctq4dgN16e0N3k}VT7ZATEM?;Yq*y~=23vXa~ad4plGQda$Mw%uIKIUhqd5kE=GP^hW`$KzvY>619c9)}B!|N~#9}(NrDhf3xS5!N12lg1uOc z03YwVp4T*bb=05ZTX*iXn(-$q87#?JKgVFb@lv6lvc19v)hvT?zie_KC=oiDX>iGlbM zhc(C8)W_$^-KvXkeSHWgIT9Aq=5vmp8X#+G73YgUCDcbPb<$ON-)cUP$RnNQ6uc~P zJ4NB0w2Z*`bBLeXxB(U<0LnSxS~GVj!5=1lZufD+Ul-L=o*zS z3QCEc(YV1$qtT%9-Mujb@Si^L48fGX7rl-#8O8ukT8e)6DRG(NI1fIdhj9=gD8vA( z5_q%@WNif>>xq^ybOL2SAaF&+5=Z#=clV5n$!DQ{$DI;{K;kTKc5^U2En!R3p1l>1p5q>!t+PqAeCg$c&795nMj=t?-?M_PUmHF~%MM{us#Eo3f&QcE7hO)A#66(-vKmRG4Mr_m=d4lJLi@cJFOMtXVX_*J zcc-RHKhtR6wHEECR?FD@9<4PjWdF~?@jHbPk4qIf!1~0$unEhuM+lgfUx!a-rSSP% z@*h=-;_M7uTZ{>o3J?iLct8*gF7K!X<|raNiu(B(#f9*tahpWVb|Sk_us0NSK|HBa z5CQ|KtXGxk4>VrHb{gw&RK9PxsD_Be<&DzfG=yk;S@|JII3j~Ujr`_@A+pjh1Kt@S zg)IV(&w0yK8)7a)y2gE+Wnlu$Ul?*$PL+4-eC3%KsNc{JfK=Z2pU2_^43JuC;z$_d9Ne)e0Kb3hE^O{tg!G+cJ5h^Gwn6S*f57 z5)N0?b@ZzYNXJ^h071D5VjW4c<{wY4Z~Hy>K-v)s8KeS=8=6@t$T!d%Fwc zUElF^jK%$_Nn@*|_l7=gTW%}ET6+r{!|(qNFH>i>WrcEWY2j0pz^Q8of9p~s=ZQqR z_@LtA;w~yKjL8Ku1?uSoT)%s$y#jqEDKkZ*T>+26qWZC@cujrKQn49LNPLY9(wwC) z+7HHsOxIMYDbte5<=@jz zbdMuUojxQRw04ym|hVEcQ`3k9aNdYDGQwN2Dyzw=U8V=ZTn|7`fzt0eEu+b_+J z?9yVlk`6~lqEsjf`b{~OaXvoBq0hG(gl{+^0t80=O$=>iZZU!S6YRy2U++Zj0o*aN z^{k>4tl^7cbe_IP<@)2F$O~wZ32$b!4nxx)5xK&D1Quw30L1`BL_}nRSE)(ey9(cC z$2ED5suAqey+qO5elyIw_lm>a6!hc9i$9&wN|c9?>$US)Iixk=^yZ&NDF#0pl^TRi zHgQ!SLNDkH4*EjG(;O?QI9LHvZr?kv7R`*UjYl4n z0`-xoTdK!Ru4z-<`u3e@6EEH0GP&T+m{LlNPKnyY_GY9vhT+MOmwdl`<-4-rnAM#!SijVq|>7Cbkk;-P${C3!jAcCn&-p#2t+K2@ud^4w-Z z4+XS@g<^4pB)`!?a!;$b4};J^Q+yv3;MQ)#ACzzgtRSO*#^c{3#vBj&yI=CM(<`Hr z6?+@*UpH|;l300fc1ZmZlA)OOlR*Iv5rzABu*j!5J6U)pP@w#0uv~S6SV6FnOrCQI zUF}0?jIw;qDCv>l(;6j?7aSajSUAV;?p)JOtf+3AQwhHoGOmxy6$6Eb;uSQV0L2mt zZgFl}R&dZ6pu%??JM@|7Nz|gFVBhf*I?VHMd`S2`EzR!dM-c3-=!l@md(>w&?X+*= zUUkm98^xXIJNAJS|L538E)(d~76LQGVXNTPmEp>D&7sCA(&9!dYfFF|ZJ|Wj)f{Qa z(%u~}WTy*ko1$-c2yQU+vvF+tCe(oGJ^YolLNhD#X106ps?W5qU}!t@&qYrGqy3&8zd)*dGDWu+!MqleIu6k7N?fLuRS3@duwMSoxWm!H z?Jij1p0abpi$)u#34#+mxVj@=b$L3*!b|;vxw?2NySw2RK8?q5;h*qK_e^VP385qu z-DVmgs)=B(9~sp!8B=sxoO|7QWVhH73@v_#1E$Ggffk2hk_9u!=Av#f3TbV2aqJzV zmV5zDNNCDj4S7S*Q4YpgRR zf5Vq}B3JKg^{^uUrtGBs=oYY9opD$`@=NpcsKdd;J~Ls#?{kmZ;m#zx7^|n22V-@b z?|rr!h?uC!=hQG zF3E9rNT@XFS61#Y;A5QqR|icLQ9xt4l046QnQkUkYYnN~b+WL*4=k3JThHc7~}$!`rk?{x?@47B<92LRi~tvSy8) zmpxLNBe6*Ob!NAw=Wh>W34GVb>9whUfDr^Me!MOx53G8Z5ZCMm5-ZLy#t+5=)umz3 zwu`q_CX!#D>M6Rh?#OubH7UYZMuyCR)rr}tcWe5b1roRe)={YJPH$GH+MfFe;*z+) zrGt1_|3?gKL)OR3>F1?OHfeHO=0(debXXBY6#?fmBW_$`T<@5?vAz+AOo#UG|_<+Ub6cCoJ zYT>{cr}1ETN62E_CwOF@=FT1QHv6#zz;*V%_-_31g*Z(Jd^1P5_l#`LY&8G%(jkPL zE)v*ViWJAEK}tD!0%X~eBU$s87s%3?@wn~rk$YWmHSpe}X|?&9!=0Ifn!|D5nnJF( zEx#(O{&SQ$`nE-dVv2&y`fJ)Fg`y94I{uj*P!Ac8ZF6jgX7+m~XIeu>bVe;JpL}jr zT-R)4laqb{xjG1S0mNzn-iOgYuSy=Fwy$^-|I!Obn2kP*fisP#0C}I7vc0>MY3W&U zoqI_UmeviA0+g~f-b*3i(9Xt75bpD5`@+0F)Hm!OX+KY?6K)nP9)swX1~;iRyMsD~ zeZ*~KJqaX3BH&i20n9+0J3WVXMX<>2(Lt8Jjo1Y)iLUC>N)rqDYWP?MQ4-%wv^RMz z$Q8$PylVLmE*T7vO+ozbYWet=qR9!$YUX&b6x)7b;JfHskP7cPfQ9H8sOK=QGtQf; zH74C1`r}AcarXE)JA%h{hT?+<6r?WVG+3J}>LVCBSvit&KPdUFa@zB&t$@6Kb}27^ z9yRyLkf$7Ih(uzMIRkcFz(K!ewgpOq`@V_jKx8IN|wsS z_8_E@Nuq8~64*ZUrzCT^dy3l4+pggp6avI?NT-i~$+M6`v#A?KTH6r%fo7V_%< z@cX9ur$I;znKsn`ko2rE#Jhn^xC+4!j&RC+dvVhdHzhs&3^cyb0Fd4Bn zbxTZu`$Pmn;5dX@z2YM(#?_ibhQ-(@qu|qUuAyW+5+C2_!)y;E8vh!&pdjZbZh(Aa zmm*qNi_(9nvm2K;pf!BM^>2P@5Ou3SoF~t&&ha~LAjRj>10%sQx27$YCSVV;B#-BL zk1YLb;L@%NI^LRGIDRL3rP=Tf^cidU>R$V z3lWLwc$eHuiFy46F3;|qiUq@pEahy}@{F!+mmvS`N3=x>H~qJdw6YM_)}T1lf4bw~ z`?}fTufoIsqOWGQ7?JdyXG?X3Q53tGe0+WwY8{I2*q+~Yh}z!_zd~4SP-jxmAGE@d zUN1e(GeT@cmDDm$gfZtB__mYC^)q_oo45<<_eZ&7+E)5K6~gK;Z7chjg2X9l{)7+X z!!Hue7S}uN!d^988u>utHn-B9ChxWjI9mr5mQ~!BdQa|3i4J2YmkwF&G;&HysrU%R zMkom7$*DmaZr)NV@N8S%HRv7EJe?C#Sy@_c5{!IOj_NJ78ZyrrJq%b+76A$?(KxXP z$F~iDIhGL&)?MlWz>kuopkR$o~Vz zwBlp1W53TjOO>Y#%$ltn`Nan|~h(k0~_sXIz<&-=#l^FPRopskyBdqYD%s z1wX(T$yo5DWn2`3z6G0NlisVv#>7|s@n?!~xWOtpWW^3{a|Oc=dk~*jQd%2ARt;vm z$d7~IOPIw#ZD0Q6HyYD7AJ2unw&~gg`U$t4&n-NMV*J+L$TtQ@&H#hk2x z?`rSSd?VNMYdXRX_gX*De|M(XzG?naWHz!pPO7tf>%B^wX$ym6JIAlvB(az+FTZcT zQGoTMsf@QR@7bBD^Vy`c`reX^)-%kk^D?qf|8HlW$^=EAiUq$Kz|| zmM+|YAzN;zcYD_rC3Wt6nWPyR$Gx#loWoPUK?f@bguAVho6Xjdj)4C8Z*8gpi0iK^ zpMZvuN*El`@|#Zfu8K^?6zPL0)4X)%Uh1RrO>okyi( zEZ$hEIgN7SWX_y$yPpbp9rg$TcZNfbsA!%QG?Ih%cKY4ov^s)JmyIvxK0`8u8IYgq zU`uv2K%qH4E9uMOqSyG$ z)nsCEad=%xR=SuD(ZUrpo(l8%Z_PEk&5ruKNwI1W9VFAgjr)5O+Cri<3qCDk7S|01 zDBtplsXjiGQv+fmXITU{gE)kT?^9jcEfXiW0p;EI$q0qaZMjdcSDui;rfxt(WJ$;? zD_-|hN4Vw9&fy2dwV$kIh><7+iu9tjTou~;Gu-ilcuywoGW;Q|S@q*HvX~=NNA~<} zu0%NqkVZOg@%D=r{<6xIYivoexM-pu;v_mxP(%j&10RMEKsCVil6OWqWO~yj@P6DH zvwXMDjMNVeia^B3#p3;%<#vEq3WTYD&2k}zam5a54y>Cg)Ase&>dE1U|9)s~wik|g z+f&CqcNxQ;$amMQZ{`;7ar*57>UdOxEr*8S>I%D=5f9S#T0Xl49qJb4uUorMW)(o*^Ji2jXUo@DrVivm~N zT>s5_V@o7#P_Msa_9DmMt60eYkVMIpa(xafOy+p!Bc6WC3C*VeC3;`M;4+FXWSQP0 z^B|7Cqq1Y}gyOh9fNDIql=O5MC_39J-b$$&_dGscIu?h%NK13YBdd#sZPhu~gLPFs zH0V0ArS5zr5X`xvRCvONB`V4)5bX;0v}Uydjb3Frw}oLaR---dCCpAHBN^>0^kMjA z%Ph2Ua!a7#Cp&6m+t!Qvi~)K}*c}m>r+7W}4w=F@G&1?-ErNphoVS@w;----D)UoA zP7yJoRQPurS|O*sfcm?&$J2Za>~d@ ze~rM}kTB-&-y!Gs9{t%Gq2{l)+idOc|889sWzp>QZMW7Nc~XtFkwqGPxqFI5-I7j( zqXF{o8_vVy9haRveKZCr5x(|f44x-J%ADw|B^Sl>UU2v;^;=4@9R)>+WRynV*7}qZ z)MdjAAb3pkwriY_>Uv`kLv>vY2Z-(Ttn~|UaW4OI1&I6sKj33TDIMKRUkaFqqbRTl>PU-{QxjTG}=l8rkho8 z{KYYte#ELIFfGB?Ztc~n*Jb_fr-_7%bu)VhD^q*F_cvpGULAB!wCt@FilI-ZSty?u zS>p@msuuCsnOO_I0M4gbVw%Fgj z|9pBlzRynHe{n&|zCCvS;B>DyKi4X0^IH`4A~aBQ|6`N_aM zKO28mNHtS1Yzsc|zJZeH`gXjf@Vg$b&fX>Fn+XE4D{ z_!?@vx^$P-xeQw>#D?(>_Z&Y(uB=SLJWp~h!C69@3MZfP+(J8H(nH?fO0N)gTM8o* zdi<{t%GMdQ{$vv)+O0Sq;p2rj^@SbHUHS6FH0MNNmao@F4~xO>(A0M(;(j+BL2raP z;P9IqXQTv;C3(zc@-({eQYpvxG{ZnZR8NlynqyGRl?>7`&IP99KoGGK@X3w-IXwi> z=TvVZ?0Y?~Dg2m?gAi^qtcO{f7&z zO_k{)AiZEwoQK#>q<3OiPAta`*n7=mT3BpAiF@3ZUz|s9r_x<<3f>yo9=1!@8s=0H z(f70X-6l}i|1Hy`=RaBiMK0rSP=zZu5CA_|#(>Tb%(xZO#LHgaDBc_~w-#-&N*>kf zb`hMC7K5Q>^<;_u6Fv)L{DcUve*v3|#IcaP#Sm>XG3;(!IS0ROZJ+v| zJZYHR5pnp>C4cGk>Gr5ULc3ks@>t*JbKQyD?S*QsD&MNi|5MVTXo(SaWo#`xf8Q-w8_>wuly$ZXtLw&hLpBuEI9AJ z#cRnvN5pBsJJm-TtO$fK2Glvg_j*h#PaM@Iu0V2w<6qkr7MOJ${u(9)?XHl$lewlV z0p@OCswA2XYOs8BLslZ}hz9-dBZg+-eIE%Y3=05E>PbnI7h)UsPW0b=Y%yCTfEgdY2P- zWqrjyB(M$@*xqK(a-h-3k3Y#xV1@>fzSze9^vfe`(b+o4 z+aJC@wNi-RjJR6BZX){o=jr}YQIllFYKoeO$eRSxNoN+Lz}!MlZN0NMc~MQdzbt_2 zec4J>g5ha%zao?*j6ucI!#5Z->e-_j563wAD%`2w)NdDV1fUhhq~F-)eIP?4KJz8c zDuu-fi;mXP9}gj+I2r#bnZHJ|g=L;OzdS)04Cc%mZ!bnp)+arkWI=e!9fib%{Ct#K zMK2kj^?F>JU}pIR$%>=2e5E5!!lBZw3BVSi`;Jhkl0I&6Y1^&jr``M5Hjzyz9D|y1^=9)3h*k z@#JNeF5c(D3=kBSuGK?3V`;Uml49~Six za)OZDH*O`;wyOFRZ=0yy0HhF1pY^PMV2azZl~B z?5`c4ix-OCtd6-ETN=l7M0~jSUTx~GD*jJm zOXVhuD&G^r{8$9T5;Y4;C0l)if(Lvil^!Lf_Q5~!H?6W3JZ?^Fk!c2v_upm)dbNci z(JKrYxT5%+xVTHKD$m-$4=Z@8O6t6)_DiDb!kz5t>Wc^_`&W5rtrincYnxh7l2yyT zWre@oYUf3`Xi;hM@$P*oIEFviT6ALcll`wB(jDJi&VMjOUr`HxbU7Q3ck_J;Ccjcu zxe8kzbb&$VnLy{%+Gw!ETPTEsN>PKwRhFtVA+!@J3=?@y@$+yPI5&L)8q;K+5kGka zA833dEoH-uTVhFE68HBJ`bZue-q#4geVy(<8o5?iFMPM9MYy2X@x**xI`G8gv!Pr3 zKn{0}^Pd!;dr*Aaf5*eB4tj`0wpWfmt#ze>7om*SY9)<3@^Lbzwzztcym8`w72mdJ zcR<*J3ZSDol~&xG+IigolyY9sfnQxcRzZ*t_skB8vP5=u9?9gOsN%B0uGr+1@!A2P z3|-feGAg~?#;H3i(e>WXf-BP;7=x?&Nl$?|TF>;~*Z|4>x?pdlLS{)~p@wmS0doU+ zB^;OYepgG(5f=TL#@+=T4T5#E`E1?0R%f)>e)qm%tE{#Jywn59Nh+Cn!2w0QmN`>WNMrWU!H8=ZiSb!MOc} z@Qi33wOc$_&b_3mdmMSixBh02WA4Ne9U%OBkFO(uKms+r3R)^~Dy|djj>qc^Dk`gU zD^#mb-`sar01~K<@19m=#-RQeS!Ws#Wf;Hvu@Bh>iIQbV$d*x-?8Xv`WMm5?rffsR z*!P`C*@h5hC+pb8zC_HVlCg}jBqPb#VnR4`&gcBk`7iJ0^URy)&3!-j{kyK~dzHew zxi7fEue?FoKM1vdRQ!YYeX+8yDuv2v9^>&Y zp&Xn8d7ZR(pGr{^u6a7-@aDG%ruoiR7r|Pwa(7MmEa^@Z5tn zw-!zB%~3=+o%M85aB=R{I9Ey=CQHwt;~VSJB$?Bsbo8hDTEN6m9^iL(hdqMFI9@ZB zHT^d~h0_I`-u`VwNd7kC)0X}SJ?5Ci>&ppQZ7;byGXFS zbX@tl$~(fmhQ~cIa1QvRM*6{wfdv1@1*hte3lY56QIIb@T1P|9+YaMB^~P~m%z5xu z!@QY45oF3b_&X~IF3D}9s+%z}a?`H{YB0VarvWJPEUeBChI-jQ7xOBELn z!ilI2>l#|%z%m7q0DO$d!}KtjWmVh`ac#5EZLp#Kk>HLsI0w4^#HuUXKtS#ipaht> zFHAPOE_r>R5k(_Lh=E1v<>+%{OiH^)f_;dDBnM2^7|gTp74Ty$_2$bEK6(r0cyZ~k znV_=Drt(C4)cBv##sI+|WSqdG{FU{7@S`JfR%gb0^yu4A;iA_j-{A_5DzS=$tGcd8 zM%QNzORL>thD^KvUrD0sHFjVDz+Mc}43jwn$fsTEmGzYIq!XXf%M6VET$3{uGX zqMRyg625-{yW<9wjU9Y7d8@W2MaZ;}nqOIB2Z zx>`j1av$G10^DP3dLT3C4tZkH@l^ZgorXeiLU^ zx>FXQ{hqipUsMzd0XW>yipbMC{sULTwT*|N+P+y1ew}A|{Ilh~&tfrn=i>-hGKYg@WC zx%}2GKQse@#ZKE%!_UYCRG-Dd3OBoQbQIxe0R^uv`sMp(X$u;+c1Z;pF36yvj z>c+x^ouu8Tx#3Wnkj?U>(n@`IxxGkI2ZLf3uY#$bm zG(0m0UeioUjTBGM9Kj*y@7q6fDhP<|vb&iSlBYBVm;Y^`t*-E^q2o)m54kF<)H2SX z=3rrB17uv{;=U3s>Rg-lyJiBT9(IeW8Tw95tP%pzStf(7%+70&Ku~~cZ8BRU&lO#z zuv7~;eCOv6<2^;HuT(Re4pNZf8pB`C9~kTDnm z)018GyEO3DxC)~L;4!T)gZ{ALV3-N9rmIo3sJMs>-MIgyKi^0%&Z11kWk4A(0_GXA zP#jNM-~K!J+aC>%L1Tb);unW-60d1zB6VmMTQJHzCXxCHob`RV4zmzKyrtCIT|7Zl z*-EeQUu-?tJYGqid}p&M*lz#lY=U@1BY!!*v{t~?hPX>>Ir-Wh#OfdRPkhBPnHJL3 zHZX;RR-XNy(CT#%*M$w}+Z-Xq=Ol1B*ZIZbrRXwV!!&uf+q^>`K6VTIq49iiI3Q1;P1!pMT)Ho8ELV>qE4~4J5%we@&V*bqWZ;O z?WviAi8AL)nLzBWosa1cpYO8A{7eWl@q+v7x15%3}qus$(^pJD8=OATpqSj zA~XsoM($XZS1phf&>&-o)p;qAjP76Ba{wKtipO8w!hBo$^W-6%b(dbI@`;&9Fcb*# zAmF({PPqFW+TV_e1z;ufNu}w`hvV$#KAJ@t1x7sgQQAnNgFzNGytqYU{!^B8+_Om9 zOrJzstP3K!ww`hZ%*D3`Swh2g_EJ$7z9fy}7UV#Twf47)L;JEj_RF!I$5-MR)0m== zH<9OsEGwPp1EFvIE^_)Bz8qcU4h0X2x7O{G8ZE#OzoH7eitt4Y4LRNIrkD4ETevGY z5S3vn1593cOQoPKEc7sOp(qFyC@#r=*LBNK)Wws4UiFg|SVpIZFM>t&M8P~{9J^e; zAgQ~cva*BYg%+>X==|hMo#na$STQ#Iiq)VjD|3BiWv2yGC;$?}g>Jm1dJD6E+BV)w z=)S>NEyJ>(v;0ZsHDCYQ-uim`&9*`1I|jdMUlB^L@bVd(o1}Hj5xm~byc9A6-4#V; z81qjVXDr;Zk-o14&tV)hPBk9G0pqJ(2gJFfQeP^L>dRlM(DQ9KN?>4RP6Ftn7Q+=c zA&RXg*LQmV!jWkFn2IR<{~#9=;Bej%wxCXfz|UgB3Wh*9n0Mmas>SmR&NM zk$os5uc^Bv;?^DkNFLeqKz$An(12ZVjt}2ah&UZ~&^q~hYB6i86@2nVcYXSd)@OOV z*yFLS8zxfNpTah%kxMu!n;X$lDB}ZJX6s1DjQXGNY`-4;vx#ljykP!J(^m>l6N8N2Z43TO7X>{gYULhkA2%y#o19EXo+KV8 z#w0aULSzKBMnT)De4Roj?;D{K-HOIq zkfBgy#eUF2&*8yCRBvJKUT4{1&gmvNJeW)6#vl<%Y&FLa)E9-q9;zgq9HAoT@g3iSWx6p`yb=}&3euW? zXXLrI7tEVI+Q5#aWns9*HgrGnBNkZWMazCJ$dWv#R5B`7+pz9>lqjf?rwa zvd^8i@Ib0J!@1-q8=_@M;17)l{skt_fySMob+kgaD&{LSUK>axsfp?<3I2Bbs z*Jk74KLM!2bk0b1w-$;@gsWL<8F(^cuvP{1PSZ8~9xQ{)ayDntW5h||z+X`;+(kNk^6WM!#LqYIXdcj+Lg?1lAI3RF z>)ng1LbShgakZfjnky1N2!3f7_%zz`;&!i5@4a*Ak7no4W^)#jCPFXupXN`IY#(Ol zCiM-ICJyE8f}qwIuL#{s3+LIGRJo&!1a|vFpE8EzGw|U)>2`!~q?3C-odYGnMfqU? zD7~O9V@4gE!MWtFtSZK+QuaQ`7a^dWfibUpolpDY%I}%@qt3axP{#C(it)~%)RDa~ zTlR*L$*aJ!C^&O@ar;!o((<`&C7rfw+7El_>I>Yl&*|+uuqQ&H-iex@#_{hI5(n_4 zqy((fVoy)^?55}JCMR_TDP(%@9^ETRSa$S2dFp-twI6ED?LmVO^Dl7aRA4A_h@NJ+ zwTWl9wdxEl`6zwfSK^AShEnSGH1;D{-2dBG@w`^vt8>ku^^Qv$htW3T&e3COI-;$y zEIjnC;3uMv;__t6XWTKoz+7afw;9rBo;f^CrFNQKk!zxkQHBJ7Ns0!AL8V}M@kt(+VWaaNb!5;oKK$YIWLbX~jZC?rqB8gf zCsi%;`nKq=ZV14Y<~BIK*tO^}9PBvPHPhy_9WvBei|9%o2wga z6=RENe@oRexmRxYtnhhWW}dZjZ2!hTVN1e_H9nDETb2sfYwQ6+}900M6~hpGtYgs z^BnJ7AkA|OzSy2T+}#=EA*8Bxx}Y{ z+vmaOe2R){E+qqZ5Gnb&)(Ii#>7>d5Y$2f<_YLdzlH1nC$==lrD-E7}<1mps-uY*m zTJ7*P6OG5qF%>8f$N_hln_V@I>+%Ei%lAuTo@FqC;`QAu$}AM!e7CsA^xp6(-}Yan zk9i!V7n>I+U~KU&UYs|o@&K9H6TepfUk(%6OkKl3aFT_jf@ksC>VCmP``En86TjWv zTX$-Z{B%)xms$<8^FV(F>FeU3NlP>N9duI7Kwh1wRl|P3oBGRL2J|53Z13Nf7rZx) zt-#EKxR|Ds2XlP~{^WwdjWBB<6#^n1rhnEm~5G3OKFV-tJ06-%o{9cCZz{PUe(J=f>y2CxIVVt%bb#AYN?VhxOO*;^! zBKJBb)73R|ROgeRt{1`a;me_LIieXm|@xnd+S<5F` ze8LDxGr?f=G<%X1cyJImjhs|vACvv*T^Oh@?WbOdYxu;U+z5j5|Yl!pVz_tnCj$4Cm22U=H z^lui@;*VVT;pFkI9QX^ptgq8kns}UA^2a}AhZzoWpaBUYR3WC1o98aP;Rf;G8a80U zBBz?+dQyWU|Al+2#(rF2u!#u|dBZ6B|Czr3_o$Ay-(DCXniiZ)EZAvS#P887w+SS$ zDGEe0MOE{Bmb3FTuh}7#;OxP{qE=d0Gu(rLsGbrv~wF z3v5$qa`iezI3r_^*v9o&?R|b5P%LWgrwGE?(rfzLW8@xvN7U?1(SX<5{Z(hX)HCg? z4#h3;94ZXcYt)s3X&S#FQT|2e|Q063U=4Oaj_)0R4^s5Ax-Bm9~3MP)6$VQB^z$IhTr`TNY*gyAvc8#&7V!v znzv6Y7Eiqys>hs8cc(TtmDAl+2qixif7bV$cw9_;Dl|9usbT?tcP-eKycf(mqL>B$ zjA}@{t^NDYvvE}yl$6cUxz{h(_6^@$1Uxe*4-~LGe_=*L$dt~>rW!zRhLxsXl6>VY zu;iBfHPnCWy+IDfpgeTGyK|PHuIVDKfXN!wa3b%Obw}DnYFy-_9`8QrjqsnzxL=2L z7f6g@r&7eqat8iUNXH{1{t#_5?27y0c93km6KR1Rmg;BE4W9oQWt; zQNlnJ@NtH_tmhUA)s}cdN!&VHDgtS>^|WN?eISVvE1k#(m7*UVD%?A9H3f^mE8K-D zo<2iuJ;dJ&w>-Jni@=<-DG-&)MD{*6`IXj7Hl zt!?qnqyW6$k<=YYrHGuZ7e^jrw|b8$EAH#P|K`|o8G8|2Qxd$+$q@srEGahWz;MGuwG^RKY_*6Li8wIq~NG(_e^s zhpZ{P#f0!j0TS5u-;8W+4Gn}#tkZV!c`w%ctLdy@V7uuXkZWHK9*=3h7h(F3q{#o7 z^qVvKR4FP2CfdI|$9rQ#N7Tjrrr9mVo0Gb622Y?4{Q66$f$hD$>qv~Es9?`QpY_$P z{-ru|mX0rIXC1U!DKAzHAbp7=_N4^9Gj%3^5yOv~7-g?ai5GXR{GB-}i&1>y?d_h* zlJxMl&KGP)BC6Nn)0VbYQEtyor<{WW(qKa4O_%uf45w&!acj1jfAp>C3hWz`uFLp} zTX!OV42FnVYd<_QiraYnW!N0&S$#w+6ngMz$}S)>@0Ud;PA}XRHwjrTdQ(uU`7)Eg zaTdd9WfP*#WA+0I`Z(&nuLO+p8Vpm6WVW9vKXT?L)l!!(ydN1ecqZWbu=}2f`&^jx z4O1|ybKlDco<-6_n#&*%=aBz2*2MmZ4Dux3GO&rGr-OZIIv=ZjX>I`J;-#lw*gEDS$=|iMjh`Gh5z6NSf&&~ve1ygH*EZdFP3(N zE`>Q9ogHRq>j)+c+I$EXymq!fva*S%Or7XvMofvEt}yq>r_!U#(e-GeLLXQF4qe-Ir0Z{ZHn$cSo)7Q`NrT6mZf<0X?^&A;O%ooElanepczmlXqiXt=WP&E0%}Y8KF{jc7|v^2^o`ld^c^R znq(XG=O^vGFLDpPPUi!j8?g6Wj+RK^9tzo`0E|Y+y}WMVWT5}n7uISJuIs&=(v-ey z=-Nk|l>t;!gLfljGpF}I>*w0%y9}04Tf#l^Zv%*uTxfwV?;y|xewyWG+v3kL$_VuP zLrJw=1DZ=8-uFU(*^*XJ;{NcssRa?8^q?Mzw#m|Z{s%J!W``|{Ek*JA6r^2eFQeY2 zM~$1gSjsEbE&xa#_rHb(c-GXD=IPVi+!2ijLF$gU6WTU7cn)_o%XK`Tf>~dSr-U$c z{cYCLtt`gb2FXtxDKu2qAvQ9`S5)N7iF9=HI&_8ApZXY?wr4LKJB6L7xAyk}Juffa z^N@CPl#gb#FwQpum@UbreCU#^CvHS7H{hIy|&Fe`hs#rxUXC?WRbI_Ql6`p z2~SmC8Upb8Oxdb0%|(F^&gbb1@=s*D@^3y3XE|FQIXtj9E$BTWZ`3=TKM$5fz$k*r zEy$|8C~?K;z6q=CS1=9*1s|9*-4ea4z;*krq1R{}Upj7kspv_ofnM7!Lm2V}8{i%c zP(KE)mD!u0FSM10WO{Bfz{LDAs$UC&Shpvisuf*~8nlYonWB*_-aq+Lr|p!Nr1Vu2 z@)eh!s|NmMp@CCs8ASjtevr9>qO~*h+J8z-ELKPjP1C&R_A$X9ehMev2Fm znUeWh(6EXeX9k6S8qcSL%gYQ}&^>`&*#Ro%A`?<_;LhAo=*xyOkO3szUexU#{3Zke+)yQqH_>yK zn{h)^C7l<<2Rq%=`>K`i!k|3v1W!Q|Y0AA8KCwN(5)#yfJNLr-p{9$Yee+!$YtoBQ zS5YNX7+yk8G^e#_ZCDBBDwN=R^~a&#A;oFo(|8ldM}FrUm#V`eB4^B3h;56#k?Ku) z$uCrk6&QPPp7dag@>M^r%M+ekYm@4zYh&2(%Yiq*`L-a*m?Ro_f|u6(W=&7ys9t}c z4U^&-RAnz~uMn5_ywC6QVst0$=0>imeaNFXDV=vW!ApO+i>W+%D3!f)_jR&mWK<2GR#K^@mVmW0>>oFC?r zkc>~<{iWlX7`1+vQ;^*!vkF=apQnrZR@=?)b8xYkNP~3Kz*k({4C^`%JL%-uvgV{tLP!HXj|xpN6_e3Gw}1Za)CKIQVA* zN9GG0Fp6c>jIZ37W#_k=hwXgQXQfkjH|aH%0Np~Xl>lDvjrtW6AX_@T;?=PQQ}}a zI?}dRhis8Jp%vMEL*L$K%Y0-}Ga}4}Tz2d6!DRIW>7;44U*C>8-{gedYN?Z z2P?B)$7g)GJA|3j;L`y@nBXR#zEebV>tkmu~&f7jdK2aoKv4g5P zr89Sq6}Jc?MRzmI*A#lX7Pk_rn`*sxW<(D3k0y7%Y7{nhp4B*oH!j|3{jeT}%-Nfx z(eZkY3(nTCoLS&y#}xI-q_q1SBN4s#K?Efy`P^Xs_@)>z7`r-ugsfx?q6XYhO}i{J zmZ$K%vN8v&A|5rUoL$QAXu2cUOic^--;^{n-57wf^NVG!KKnS-d2`WPmWCS%_S%av z_JayaJX~|rwQPUoER@h%t7!*9j4fzJ-M&UY<^c7~rifK_V|3Sd)>)13&E9zg&L?i- z-)9ZrXgzIflN|-2KbmAS)%XOdkK{Vl_G5rQ7jB)SkrdF$tTOZ#8=GMre+ZK&%R$!J z5;xnv`#u7XrCFLFfd2F%!gnk7R!;+|Q@O=7gJf{8MxngVBJD6UI6_h^A~S)H8-JG{ z|+vr=;7|^zcq=Rzzt{+ zJ`UDa6rh^YT>1A74mYN!GwAA@5 zWbOkf5uLT5oxef9DUo~BUWSN-_eE|B+A(yhrSSJb2R4|3s?)ScP2Ou^zotT1F9|;; zdXOSbE+Wr77t)h+Pyb$+w4PGv(frmOc04{Y79nego5nwrE*Z?Z7Zv1b2ek?8SaaQ__@(r0@3NCqF$P|vA$Gi2~e=t9h-^h zp3MPfR4dQnz;EEw(GL@?Zi7*_m6G+oeY~1Y7OqNg|7wf9pP9bAuJ06CqYyp%f(Ca1 zSsMr=r65L@H@N7MB*m*z0J)cc9Mo@IpD4(c6^GFMF;;7vT5BF5J6#-UI`i<_2tgk| zaOws}p|#F_?<=PV2z@AlGTy|Rw4>ukjQwJFBeWVvzW!UG8hOqfFw(hS^#Mvf02Voc zSwz7y23a(prT8lY7kB%2*5avbG<1c_=jIE?+4QXeIG?z4l)Gr0P|;=U>i6X3du;xq zItEYvg*@I;851o2#32e;m=B~-HD?i+ULELDZsyHkQ;KG@~n75Rm6eUWh z?}|8}7)vbS=lx}y5-NNpUX)E4+l~@dN~g zTa{*m)kG)jq~Xo;(SpL{n_1O%+07~wDXV_7M<@CFfVh$YJt#ZKE`)L3zovHFP8n<) zYAecan zUE{Ex(!@na5Jzf*&GZd0G7x(bq0LuVC?b;H8+rUzv7YoPcOP+)vK8nQwv&<^Li^rV zsa!JPT8V-x#fswW46Neb+1e9&YHunq8%iss=_AkOX7UrHU{YYysfAKL*3WK5r1|{k zv?9*Wfi`&PmLarAI-WQmLX}fkr<21)(UN^&wsFOugR{m0$;Pe{*Hs|&P~-L_o}@fb zX1qzW;ZmBnLRn>!k8zybXItCn(J9S0rSRp^jdRRB$EV9}y@!MBw?1u>(dtvhGX(#G&keRMQ3X}>s-HOSccWFT zowaL5LJlX)LBkw&%N3WrRC@ZYZ!Si4iq)+XZ~b1~4ne8@cIusjm`bk(YNx!EVEz&x zhPl?Sp!$QP06|;5tot^I?Qmx3d zF-cLf16zdCSyf*>kdDqUF4sH{ROzh4TvrBc)rBBH%%)&8x2U0wMsCeHu_$Bi# z$bW;CVKY;M5h|M_BxTb4?+_nj+QHbfqnot#;kH#vPSTTZ`!>{;2(DI66FtyfP-fs7 zbl?+lIJ*@|wVK|=`NHP*=-*D~F6-@WKjVHZs>T2igNW-JYXl`hKRjL%2_7_OS1o## zZ0W={AoE!k>`WeVU1s;FL+vp(V8*#pqBp184p!&r_gCifr*3SY{PUNR2AjPY`28bx zM%3S?gz^5fEt1mEyghY%K9^81ym_YsON!OO#W6~0yjUkoe#>X|Z~F|6zw&lkCRv>m z!w*M9>BIq}x=+Nxxj4#T{*kvQGx+1Y%rzcHx-S-{TjBQ40`>wn>4E2>z~6y1jsnqc zQ%P=cQcaNqW|P(NWHZo%g5bXqht4y(H_?ETd!8qp*)hBi{)_|Ph9=!MfR2Jm46NV1 zDL3%X(U4b3*bZQ-MIHk&ul!@669W8IhGvdY$?aCmR17}1XSU?4`pwR!;nPN91{X3j zdI}d3wm(H$bDHlC4zO7ppCyjap3hwV@U*fH9V)+9Z31?%0*4h6HR{JbauKM+LZHY2 zjF)lZnY|s0-p$d391y6er}ak20U`5==i=!u7Y!nXODJhq( zG%k!mVrdOi>w;F?m@}cR@IEX-6jFyVLx9gSUEu~_Y0Gw)Ds>Z27PY#E5GyUcIQX;M z>A#8Z#lQubMUCA8fu!Hzlfm6avmDfouRFy>3#ZE@JYJQ9Aps5v{zK4wTbUJ2wM*^m z>@eDT8m2*7T>On%Q8lIq_^XO*3}`NNA3OJ#?Gm@NPw|Uq;|HHni90(ZZk>~~!p_}9 z)QC#G&nY?b5G(gcmGqpJ4d@)V1!Oy|dLjtHK%|#T^xFedUvPh;Ut~XKmTw zN2Q2RkH^$|+lKp3*0DRhGa*$KktH&w8X7n<5-0$$-b|%qJ0CrW+fwSh1<`PCR+kpV z>Cv;%l-op>Hxe=~@KTzF^-pok{|dqMS6#KZ9@-XD-IM~%!W4j>qSj1J*zLRTAfTlk zp&w2x?&29bc-N8OXN^4_pYQUs=wK>$4YAIZv{(Jr49zoWyUW;Ir^$*LeRUO>DF8I0 z7FH*+C}#d6QO$El%EX*co9HY!Wh{CYvz;Qsk7r4z6KDSl(v+zI-bh{WxQ5Rk*GPeQ zD9dc`Ty)9a?)LJE>Q5yVh|jp`tvoINZZ`LE7s~pqH-_1TJ7^OxuJYp%`H_c2T$_}* z%DJC=p>|G{f=e7xesW-$I@^uHz6}qv<)UPpnl71LO}aJ)$1M+37>BDh_dpE;MQ-=S z-$ly)1quH*uQ<_0<=p}kBPtuVvPT{UXp!kd_rsD>(le8q?O z(3~N2f)SD{wi5RL#al{^$S}}FDuTrmtRkIlAY$JdhE}2Mo$}*R-dxh!3a)R;s z$!VjaQp^#wpGA@HW16m-fx48Y~Rc6E&m+shmadjwuwTav*thk_nM`3QZ0Qfs; z8VOpsj1UG@WB4S?t4)l-(wMwkufIMLFv|Q%E1pAto}VVr)gom)mdp4AI*Aea3GR%` zUC)g8V2O~Y(59spoWXfkuw*&TCS>9r!nC>Pz4zysB*l#q_B=ISFgx0_t?plHd<;Ok-aLAcPAr}e{cKc27Wp|a!<;$nYNOi}Evjfu8 z#$nkI?ccvP@$DQ5f7}AbZDf<&J}X&1lg=_9c_cbLwbV$QZeaIyZAWWs-dVBmB-!m? z4_7rpRk?GADF@;VJ`_%}AUrV~zc$Qnc{!m(G0zs~?c^yDLaqDP$bYc(`%^5ZzAf>k zGru3pE7wxYc{=WnP`P+?-7P-&A=lYP0NdY>1T9~GgB6luOMedp>S}LvVaGjo>T%oB5Me-XYc)J5((k(eDAOLZweR@#b zI&yS$>NvvYTrKXLQNi@YpFwCb{45r|7_Oyt`ZsKKK1U7_gt~}YaU2PWY^%r23!^N8 zLsYeja#-`6^pYlWu61SkYN~jz<6RY=4qv$Qmj?Ppp#p?Prt5t?V4%whF5Qovg;I>- zN~N=gJAE|qvd+G-4<0d!mGQ{CYCaOBOAN4oWAyimbAi4I6L~@hT4qbME57U5Hte*( z@_?72L5IsNwGRCV%;b0DF;59M|HPkX^g=)h5EqouH^xSj6{s=YI5Pg$=aVRW;U6zu z1GkAZ&`X{b;n;1;SP}XI$o$k*bPvAycI;PU$m1L{-zj2aS7@&e6E}_O;mjoe6Q}x{ zIistkNT>4wlPQzp-AT=fk+di-2l-_YyI$>Y6$^lyRD?aT(|m%F?W%uXTiMz6vL(zT z`)TE%RbHL|Zm625^;qRxv}$fCS>9~LB3C%KZ16L#r1HgD?&@qD6F^kaG>&FB_@ra_ zfp9x#<_2z5f|uxstGnbFakSaEwp*Lv3_ef6FBx-!C==wmcX7O==tvP(2!OjfU9!?@ ziO%>rqb{omllV@_DoaXeY+!mzqS-@n+2t>gvhA>2E#3b@WSkbZJYk9*Dljn@*H%p7 zS{b&tM*)<1JC`u27mw3~7}!8HW0L3Ru@LU%()>)q=KA{X@`~(09r4}%{sz&#w?;;p z9T^eQ>AQ_rb+|jev-4;0cxBn5{HcIPb_^7(!+0K)Gm4~)(lV5Hf3!**e!t}JqKjOH z?gBGu#O3EOkGl77wk=y|m2fnAUGrTtQy90H8|V1n>wTy3w?m^~FTgUE)#YyOC@R3Hl;F{=UCb6EV_>3tAm^x| zFn-vS7rYgI%*Hsea>2&_YK&q+BOmNM#+WOWTN2ui8i$7P%Ne-8{@}avTU2jAbG|wB zF-USBNJA&V@V;YazLK#GvYX2*k36T%|LYyTBBt$NPX*g*+5{-MNqDw_Ek!Nv7Qj`~ z0`@zszYDN-$ZHk5t%sj+{B5gububnCvHCZYV{>QaDDrG=@$}b*PeO^8@dm{gP_+K_ zDKbx_=XABei5BvjT;C0{12|Xb6`#fLa4mM9Y@Hr0{$t*XI9^FC5X{^5t3ObcbBf%L zkM>FQb7vB6qpH+zZSik7RfPr7R{!0|EJsE~BFNj{FWfKS4r-;%srP8NnMkr3DWMk# z6bC2u5Al5&$i)~j#>_Tu3Rq{?;qnR%-jL$1Uxq z6Su@&8t-Q!%D|bm`K6n=?+c^x?>t!xIrxWYkz52`ghxe~!QbopHN!_)_Y~5kcOkq0u^Y&9l6=r}i9HJ<7fWlJAggK?g@|CTV7 zdW%bH57~PS!{%N!Oj{)|gL7YYg2ICGL~>52A}Z})*}@YUL^V{PbWiF)Um?k(*7w1T zvJi%a%Y4fqFkBdf;pgsLBSr9KM@gT97{myO=3yVRDbcx@WXwkxuP9t%U~y6tb5WFblOnr}JX z1ge2Xu2&w`@p{UgPi~b(N6f%X8eSA=Ud}LWgI_c-aqYztdxQOXkyebO0h{dfX< z9w8A0*tn{7l&Q3S9bsj8=b3HY4TgUfZV#T-#-qRL=fP+#JM>@W=H~4EAJaW)tBH?J zBY4>!Z+gqg2o?$&tiCj+64b#Vb6qx!IC1d6^>jY)P zA$pN2^67f>t-pNt4c#PbUjF`7I`dLW9z($XF;sZl_Sy0CrOGMpOZ1(?$d^m+TwsVM zzohN$WlqG}KNdMzu(Z3l&N(`n`Ne@{py-kcPF9|B`0rBQ=Yr@bQtIqwl_3b77&EG-LiruRn1A`(CixSh@EHj~_$yd+Ww+3T@pJZaIlPVaF({)9J5Yc#+?c2Z^B@ zs#?V~0}-_?at9T87WSbyY=3xq@#J&2QeB!?gaHy)x>776 zcSKGPXtBB@)O0TOD8wJhytI6J+B{u2uHY16^|!s?#z!w~AMA(ZlA zXGEm9?(k&!uXRoMFZyCH+rj7u$N2q-6+t`)D3J<@#dyeF!RI3V3(&9&r&akyy6nuu zb|ZuGAjZ3~iAxD45)sn~Ch?WPtUEbtmV|?vqw52$Y+~sth+@PpffDQw@Z|PslLoWv zJfA4k(V&_6mv#&>J6~fLB z=u~pQ#%Zv)=>g0}8|udHw>|RF`%~a{xC$=LU4P&dk)HeK@!4=MpWJBJzwJMNpJ^zZ zJX42EZV*pMn*nt&bOnACXW-hrc&=YOVqvcM;B+vNi)I`;+h20-?~?VZL{HJnL_J8u z|9f@JzF`Ar%2$(?zGl3k{Gy|-?zc(ZewxJaQ{DCSG#&Znl}_e2QA}yqO9g+~wuYJ*U&h`K?G5{v!JusaD1*Iko;Xh; zX}&}&?R)qch>gB^FsjBtC$&<+8&DcN(2Xb1D?V8B9K5ykX6NF(3|s}8iGOo{Y7NIh zXZH3Gi@Si16cqy3sT|wf9Woml^7k3Eh`)`V5UxYH#H}S(tSDyLnMgAMKvQ-Lz1T%- zcxeG~14ZRBpQu>;cW^=(o|COS}DzR+Id9&T%F0|%F!&i0Ioe!WnCc_=m05CPV@by59psiI6 z&zG;A*8IZNIb|wfuksRmp^3G3p9cm?r4kRnb@yL4p;ZMyUp+xShsF(eZGIpra||eF z=~{KF@cX?9)|N}z!vaiys+VY*F4JJf&g zD6kk^M@^)%)CIJORB|Rx)^g}na}F{mPTHQEE_E2AiNA11=#$F$xG?f$Rs7q1BnZQ9 zms7!lja2XMniY$QuW!|tR^rRlQFf9=zHc3s_z)ckkH_755RFKJ2(bVFpzh zM5~*rWnG7?%!i`IGL@+z@8%L~-5mo@HheN@*17mufL+Si)YO5~*~ZyX{prz0KUH;2SNXsT@5z0&In1jTD@s>S$i)3R3Tbykd8AoO#+0V>w|V6h%bcYWhu_@ zxG58RHYrN=fepnkO91t`-4SLNl%k%goOAiqupkE^56j-4hR#@7pyRd%g`In< zDh;}JH=c%B{&RSDcUXW}s@KI83H5LRFNjg_XD@$_yQy(=L`4OH$2_{LQuqW@^Dmu? z3b=5cJp8`i5R_9r`i*8oULak&szkrGxBGWl(fh*#h4(j!$;qJt^fk+Fn-&$|ZWWdG z(PJ4`i*a?`YMq^8)Omu>yjyGOp*`VDulhBc3BzKTd4G6MLQ;Y-z<`J_==4ntp0-9wfmFlk;5Dx?*)hDajaGAeb~S zJ3xAlHn5Vg-?;7U0`{ZcaFYgSS7yCTUg+MJ%m#47g*>D~UQf{IsL>WydvDUDU|n7nG+{RfYRIIVj?cn*ktnTpnh-Ok7%53g5C$U z5tJTTx~*E?wjT^OpW!uRLeuT2OpS1}dy44iJgDPV;NDv5bC-dK%kI_ti1AOGR@Xjq zlQ$WGMC?`OAO7$bZH~++A2S8GCbqGO5aE?Xzqf|ts)m7%tAf}mqBhsrt0C_L7aFOZ z`cs8v`&Rhg|J+7Kla~3z#i;j;(S3^Az}BqeG%65(?+-na*?X-=R&B7{^;5UA4?MUO zpI1TP?qiL;J^9BA2a?M}y_Y=KDX~4hzXk{T!T8!;4!|$`+4}hE*-;{Oq$5h=HfPDu zvdPKOSi z8q0_uzP=(kSodFo-9}e@U6mS+>GVUPt8P(7;6~S0osuj$7R3vJPW*)rNwW+AdYXWb z14`snZ^&Pl7OiF*v{SjM+B%H9y*|_IHlc5$u?|eV-rq8>nf`UE`b~z7o6>Fb^`y

JTON-AGs5A^Km6`zM2~u@l<%VpW&MMtrYgyC)H+BD zwE9lv{3xfDrAky?0CM<@to?S{&(H1Qe~k-XaPr4i{1X=jfqxrJRRt)b{hSkUQyOe${;Wc`iU#<83}h|_D|4e zWqq41z*MC2Td!o%A?@BoqQ`AdiLLOQa=3`57c)yd#IO+HUll13p9ChFzFdkIdVhv@ z)mhLm1I6^6Op6P;#C^J@*>*N(Q|9L8dV?31y>Y~0Z`AdaJ}-8#`UDg5)f{A&B0`3` zC5Z9Wbrr{io?|-TqXYSM$VLZ&6`#^m&V+-t$60^Hh9;I6Lhrhw&^1EpEaSlN!I!aeY7piFXR z{v2O*DuYm6#+TSHh_|zWuA6-gv^3`Qm>zpq0M;is-8BRbJde)2Rt2N&ZKf z{P#8CIyPL4srbRj?F<8=xeEk-3CNL}w@FL$;D1KxN&$iBN1Zy{uU;yzRHcl7@o!$9 z98aE04*lCbz&o9-o>vonGO>$36M@Pr7p(?f432ebMJBO-PfrS5F8}rOOtcbZhI2&3 z#p+Q<$?i#gf0%M+v)cJZX27|wiDn*qTnynNeeWWKbX|To_TTRN%<<}u+AKHVwzJm2#7!PUQ3JkVoKJIJPKjR^*~a^Kn&^Jd&A4qU zZ4%Q)Kl%0VzM{{I3vQ&P24&mismIq;{_Q~350uwLj|b21&+tE6|2DuEcz2OMrJ^bP+lJ` zx~i=}zv_2S!jT5C+2a|5O9w`Odw$G8Bv<(}GC$1mFyP0We7Bb3y2i)mo-JRXFq`?Dk&2tPMt zRJ+Y{X;OEhl={9`Z`}pLw@wd(GQXp?NJ@oy=ux99AID85*C7kU#L1GG*s`6EZ*%Cn z)g+2#vo6SvE$|i}+wEkU=_Pl(o~D^~unxH~{wPXGMTKj^sYa_6TPH&s%$eR&wDlV@ zOZ*r_e?Q}~8}NJi2c%eH<27}tD>xr`3aa#U&6`hhrbKW*(6_hzHv9gjVxymI@0abR3TAk zKli#z2A6#G^Nu3KYmm4c`z~N!8L$K@9zM}STM-R)=%x(@AkV9fjB^j7I0P977)k& zRx_Sb?WHy%+*8lS#`+Nx}h$RrJoT#w*Cs(tA4GHLGp?YMC^TUGZxldWEC7lA7Q&`*Xu ztoC5{q}~%Sgw}E918llYZ>Lg}O=i_kpW6tpf0zAPw`P6aaY3d2Mp1lMLAEpjUZ}w< zvnOI#3b>imJ1Hv1So?eRTQ}?aS|MG!=hp_ZIDK&QG%DhW*aoo+oiL@xpstq+FynIv z(pNANyZTfH1XvWL>%dg^N!9svpn^-*s+FBooD1(hbpCFgWF-wwXDS!3TpZ#)Ut~06 zt?Aobcoa;_#(R%mtcF9AbL1YsOb%m$V4S!iywxehkx~g5jDIKueHrw)-c5!KuG2$8 z(=&!sMBzo(F5lF@D2!Bg3#(4s4o~36?tAA>0GDPryk1cF~Z&AkfK!jcs+@E^%I` z!{6nRDNEjx);ugifQg%E>mE|2r@$(Sw%L@F zY>s)R*jucfWZv|U+R zfx-eTa2}um?dhj%c`KKzz-4UEjS6Af9D_99LuZ8kFQLH`o{lPhv~R7 zLKVPcAQB*u4UhweI}ux3&Gge4t8)HU+2Z}*xv$GvT)uV~YK**iP<(|dxrW7jj_7#% z;^AArrlv_CqBiQRy#Tk&lV9oA{chlgD#p8kF;44t+-z?TA<{{!Nar4jn+`d%mUO5$ zoUk6onO0Bw?Wc;Fg>DYbqFP5kq80sJPp~E~9YxOyNYT2Z%OP4Yy2a7nPdaB6qDA7! zkW!COZl}+uT4ieBCLzZwg(PR1JjTD?6wINwncpiX`R>RwQ$hYux~4}&n+Dv{)lyLA zJ@IjnjNOY>#Gsfn>^LitX_hK1E-sTWD53$^1$~#%4cpj1TFj2~(@{h<)$dUA5E&or zHm+}kEc2`Ubt$wg*rDsNh|9IjcKz6+)fB-C&L1K-%g^5Amj7HA^^ilp9II1rti+9Y zK2IQ-MwPSJPkxe7CsrPCYjUz=9s8~(#`(V2o9)nZ;>_nL@%;7pcAQC*n3aP8aZum? zke3znc1G8oW)>rC7=GOzD3>i2mCxwX;i6-e(#35S*DFx)=J2xd zt+4>9lFO5iGmY5+E_KBcWQlJ8WpBFG_Zn{(1IL&qUF0{`)XQ2~8dq9#&3dWoyV?gz z?z}u%SCh<9FBi;pnXY+1F5aPPmq{xSAwXt0QrE+mr^oT`@Z-gEN^y%b_qtC}dEavG znBEPW$l6vUO}nd;W>HQ#&RXFf(>yX2m@fxFoH3UFw)Wq-LMLRu< z(n@-5kTMfAcSp3Y+{fBnMn;CzkRyKzDpV@YtN;1mRo!zdcFOd0VY=t1Sb#J?3F}Uy zT2$D-!&QJnf^|)QKjKhowyDlVB$52tFKm^E4Sltn2b^OCU;ERU9J@L5b)xM)9uHAd zE5Y&<&|K`h&v(x&gZD5=f)KN(MLH}LYhe%%OD50RE&R~{#`l)rAYqCKwq)Ps7*Oqn zB6Ib+{eQ?T?0kcB(7FL_O0eGCzB=R49yzVzZ#ApSQd8^DWjY&+{jy!Yn9+WOtr^9Q z9HPez2m=v6#;?4#DtUW>hYs7dC@^cGwmC8vawZcEGPyM}GKgcUH z$`1rA`WVfVGwH#&>*CZ)^=1uMfr*DkVXm7cSGxuv{oU9UmiHV?8+10%sHHIsg?fIhb3A~691a4rup=-QHhajX;FFBKf^!eg z>jNHLfr4LKzjt>06~u>$eCtR;YR{5iwa1UlF$^(Q>|DOES8uZ?MPHtf*dKjzdXO@< z>NkA7isQi|_#)aVPMQQ}8LA1(JcyIJ8=_KC-XCoC7Sy6G-SRXYTMQ9x;wmaHr=|S5 zY&>ncUGUL4Zf`RietQbr^oYs>uEn2yR6_LFkJW8wL}mntW^E55&V7}OjZqP#0;JBI zvJ(#q!?F(w&Lht8d&^-62Cfti3M3r^*JSpuqDL?^d9qCbdMoFqKX>J=UPNx5yyfz& zQIh)TX0=|?Z5zM*!bZVQ?z#-Tj6V!dEOYQv>-9TeOS2F@v!$Cx+Un56=|69}H7@qT zyNG+&%Lfyr#;bb5r6uA|;Hie{g~C)*$V7f>Mn_kTe^bPUpwjdA@0f<)4Y)0}7s=dT z1D;U?m0vJ!8{S=M-_TOhl&gQp5HvO5R=kSKdCNN`aY(`*cX#8S8HZXGxaC1nT=AFs z9!lP9ZO@g+am09<6t4qC^b06iGfoC-@})UHoJ}_Cbvbz#tHg5&xe2Kyh2fswn6tGi z+X}P{%}o)sjF1s8ki6xyDFuETW6?pS3#I6@wiGOTkmBn@9O-jggi#Tb%iRl%X31}j z@lq^-U>uw}+o>i;gPKud#u^$YV7@mP`Yw(NpW1HB`ShYTD#$a2-OmJCH*LLIqDokG%RBMu8ta z-g=;UR2&>wfE&e2YMXbd++|SYh6e1DA^Z!!hA>E-QA`@leB-V07L+lyot>{xA!bkNubw$RT`<2(e&`v&1c9WJ7wmD3Deajfj zm_qtA+N&|k_L0ZPYsYj|p<=4HgJUyB;aBIAuNC893XoHbam-c70%x`f-ouww{X3d= zWB>}j#;)$PBgCeZ=BCmae-{k@V`4ct3kxeQnA}Q`H2Iz1J%|Xw{%3s>-HB=R>W3!IbRCRe2{$qfdbk?*(cPNFH8vZ==t;T<1VWT z+gr0``eJ6cA+p>#%VR*I)pm=PY{T}f zn4fCZ{sTE+e6uH%&lfGxSjW4v0%^4y|jGwF@-^tF_qo474v>{d3xm zjwJRkuagSX0HJrCGoChfqah#}%Z{3+U8^t|FjJ##U!V{(YRfv&`^bZn-yc%E1$)}F z^c@q^zf7kk0b;@q9V0m>KCWE^S=rl}jG0D)om{?d{XV?xKPP$`QWv7ZqTxn zxDQ5Vk|XsKzrW%rrnZtN0D2@S8pzuJkB#F0oC<#jUv|rYkxU+&@ZKwG;GAv}2s{T# zd{8)luLx=31lowOzx((V5~&BQIyq020ZPv)Md^qqq?RjX%^kcLj>d1gH!pK%O;(TL zyO)O|Ba}!LGTF3<=Xu9SDX95X2?_JhduEY}MZXYtOB4sbneWL`F_CamBgT#L?!KF% zecsZb)A+p(Jliz7$+efj{n-(qy7||lnBFMB6bK9{%?BmNfpf5Oe<0^ILt?PNoPsSh zBKXO_Jl}@WfR@s9@&{Tv(7fyyALvv?4LK-k$l65hy!>AlGSl0bjQ;)+8S%7{E!^km zP6?|5Urxu+K9~PgLupslf;pD)8mo4>P7xK@KG^%yXsl(y&$sDxY9Bo*y5R8(E4Sdm z3o^450cN$VdvswN3HT$~ZY;;>KDM#{J_D@DT>d!?{X~N5r{Jq2+Ei;wXNgafHXl0e zO~w{|R3Z_IuNmX1FpC(OXToa_IG(bl9BL%~dB^ABsv6xV`SA@vfgt z&!D`sS9Fw*obhp4FM=8LHF45)eZ=ZloTpjnPXLq?N%Aj+8nN~=>QP@HCpA;AQO6-i zTxBE_s#8a)hCFbJccv-2`<8vntcqC8l}dQXnn#zR-PHS;a-x6)faHYJfM9p;8o+n?{~6m<$NCPjT{)06{Y*HN^p}mQFGz z&PQ%JAj}Km?uS=&2OtR7_kM**;9FQu8A~f8Qkh7%Q(r=6mQMXi^kg{_ z399@0Ceo^q+0~k@jI=scHq?0zkJ!vt-5IPkhLllSF$uX zd_5a;GE+vs$p#;=$xH?>vQct4cTAEHhRqP55&OrN7r*@s;;v zB_ZqSe+$U$ELLy~xJHB`=KC+*LwQBlpDQi-1WZ<%!nJW24bBJX!TT-_U0hAFG=3A$ zy6JDy)Hf;FNbi|)OqyFfMcpYE(1e1@S@<^R!tZH)X&n-zUs*T{n|jJ)DZ%^sW!~ch zaV&KTjv+;>`Cp90DQU}Gdh34jv+j9^t2GpnZ9<&?>caLyqEsU`!mXi|p@H~gmK^h7 zqQkCl1?!IB74gqcrw#Z8??7D5pBx1ZpSp%y);bFB+GM%XA8%VlF!NdcBV|J!y4j~% zTP|W=GZz*#O?^CEJ)eA#$Al)y^IW3+T;s*cw&r4JQTc{A{g89nJ6Jtx`NWlL6M=(& zA=PG4ht}x1F6OUN`(PEp;%$O2<3}Z04dOasq>O7RhBucv*C(+p3Sp|Je=869_(@4x z4zZq5GLp7GGnIMk^(-x3Jy96(dg<@DB=cN~hB~b}*27Up2+jTH`)lpQCyfe4%lfsN zJjmw6q~l57d2!aLhkN@WVBeRAnYG(L_n*#~sQB&CCZ^onvCtQofN!NL9-OnOT%b%V zY2O{{_1*a>o*s&v;q!5}fr$C%Z^zpvlSEpQo|d{3cv4Su-X19(DQ_~F<+Is*;?|vb z*<&1~KH$ia7O`1hF>G;W4C z2S+@fLsNKngV;*N+BPcnV(K_@QKSF|8=Tvi7gUCv8wetp2irryuRr%Q6B~awiNrGV zMEEAYVYJc$bnFZA&z=$vR(EEF%BVPd_yC>uq%#}pEQ5!al|e}$KJDbPgqjj1@I-B0 zUE^S)Itj;Ma>}kZ^;jKR#!hf{bsbY z#D&fe@8{C4a#vMV<>n&_-cq;oa)>JA8oTFb>loNBX_LVIO<%&t!_kURy|unRcGRt= zO7i1HL?@5jf)f47sc#8&TrA;|5X?Sd!);9I?_ITe>Z_cU1osj_1}S`MEV0^6(Je7C z67BYVJ{iJU;6@DQ`*p2{4FBHvJ@8p3ERPBN3*pWSlDDr8VQTAWxL@b(9yYwk@>l(Yl< zygC0dk!%o(_vpIfnVtRT+3gXg$?GGFktyUVlD^>CADn4+JCDKKAIe_#`*eRk=3CPf z%j!?Pi;+1B>{SwfJo%tH5h~Xu zKB?M@>&?d3%*QlL77Z^GG+dgL=7kk{HMaHjyez6MIz1Z)=j{U<6?I=6aj>Whz?eq5 zv%)#KNh|^7qLhJ!xHs>kEQW?|7YN1Gw1n$PScY*L&nwnN^ zjfyh-R7F3N6ahf)4&IUU)I#V|NOS3v4UyxMr3FoYH`$f?h?Tmxol5Hmi)yj!#0Y7q zTRYaYsC@ij?KLR@45DLDhq_=X^f$Ql;R+cH!BoR*-d7WQU6`i|KlGkX-^ zf|b3P$}l%mj_}G#ex3?21=7%1q25+O#)}5xpr#G`63G%$DSxO(E5+KyMHL`p(b}#2 zYeDk>V8JM86qNLnKPl;BQrV&H=UY$-u9Y`WsTjL`^((o#;` zq|(AE;{q*vGUfBdr_r`fvtwczDIt;@o<^9<1ITDwFcn)D3h~8-0x2Mc4jKG|&-fA; zHEPHWnndJfD{Q{y=6LYJ3+v4B;!xhDWG)d>2&26~;a~iy10l?PD3|<;cdwHj&Hd5F zT&=ae9m;aJlyy*Psz45Cay&kOteBcVio_nQN@KG^Kj5+`@C~n<`D!PwGIqCzNx$ii zsW}bvOL4c3SoFoU@6Kdw;-gh{p5bqoQl z;76#2V3+)pw-Vryfa#1h#&?})6uB&|c2cARSz&F1Zw|FH<4O*kx~he-%BDWWokD{t z)$or+4i#^$?bh7tbEG${@~I!@Yv<>$=cY6=o?L%rIrK4h!I(g3?G3J(fS)`COO5Ed z3fQH;0-$y9hbJqSg?5FoHIaQivzWd+Hg<&>TX!0koJQU*ZbZPVC$XR1$12t{+=-s7 z)R&0PrN}*m6aVPC0zgE+(%0aN00c4wG$YMmB(np=>(;bTMjW3UG8mZHswros^pd>J zDkwk@zlCS*UJBI#pV-UP@lXtjk}an=huDFV-Zll&_g0#X$U|OtIIomnGL$x&Dj$wQ3Oqr(-{_EkbmTw4)zvyKtdw$N4w-pqH2vEm-$i;1avoXp zT5jdQx3~^6*jE%Oi40^2^}hSlSBw-W{pd!EGG}$h&L6F`YG%rKM(PTe5GciA(mCa} z?U&0wj~-QcTAd&x!#hn!tmr^3gbI*a%I3J@UwAJ2A}8(GpC%B5E>9Bxap}i%$>bk) z4;qorkeADpyonQQ@Qemo4*j}Tl3P~a6+i*PEJs?}RlDsoNUaT|(?2Xm&LYbP!oo%u zZm07x5)P*?e%RFhYBUP&5sr{NjwN)(m2^-oPd1Qaxq(x%p#bepivSbb=f(gk0mISV zZ{##d2;)ql*X1aH>;3&V!N?ky_%e<@>(FkPmz31H?C)MB-nw$pcsq%%LHSvW%^j8R zH_4%;L<6l#%Q3nQ_~c}usCA2-jFDTutr5cd)y&HbR>~rh>58M@eBD}D6FcE+!@y4g zY{c^Ol?^1jjL-_4=^OL&KGZM>2wk>C&w(cEFg1V~xXmQJ^RdVc!CEH(@hS^7qeLbu@bCZH`I(%p|6pdQxf6qzMn- zNo#4R=WF?Oik5Pu8HT89~bMW6W!JYeYu}I^5s|0pJHfGo8k#>>6s(ime19 zqwEY3`#0sfqccQx?0^5~;ft5uvFF{_8zxs9k7G|H3(T+VA`KEPdpb`CWAPv7RU?`} zyu4{ID`?`##LZ2LHPdN;jUlYeTOWtgPYTYbiz&fwu8HnKKUcK~AxDQCBe9qjQ>*}@c($4`DAZ+yG~>Yu#4EVlOZyT_9q&3RK3Mh?&^ zAH%s1vA+{ewRf|Zi?lgbXGH7bXh+9l?p*i{h6P+O+*@Ac8v1*I>fpMV(FK5~mz)eP zR`8*-epT|J$}rkWsH3%S zK%KDrg>yTAM7@%uF2C+>NxdkVdm&9#hcOQcxudOg1{y+{_W?(hhOqO4E9cWd39 zsu2@jRwOVIPb5}*r%!pvasWj z;Wu&7;fnOlTj91WY3G$9cr6FOP`r_)iT??bm!;g05kFnTG@AT?THiY@GEmB%CmVPa zFqluvN4nMZG<%7JLd48f^`1fC&pO{+x%9I97y5~(=nzzK4_efaaq`okj!YcYr^Ivt zn{LHc))=L4AIl|9S7OS{Uuun;{RQzpkhshjNGlFJ@QqZ^CCATfDAU|sWS2{uQfLVq z&*msV#q!#bDvy5e&@GqdgBO(37ZUQe-LXkGQ?mkXv&=dzMtek5oNM|xI#T=Y zNJ~E_EzbYMYc3)#IQGc&wdPCfj5fXRYru*oaUVFzt$6yR#4R~ob~|8nF>=n_T7e&N z-@rYd!|JJ9h_!+Y$I9rABM`PKD**a}0uXu9f*(_S3ehAE&(`0@uqdXC!773*dN&d{=dDE`-ysZvyr8?sVqd9zdt1U)D>*WC!|vt>d%`W z&YetRE_@cIQ1#BQkudZX&?vbyPxwf2(J_-oY%w7k$oj9zq+|CG%NK*o*Oz#X32XPa z!RY^bxfDOa;G(wXcrI4tW7hpHe>Gor#tzl|eSMs7ZH0HZ2vxiCKhI1ZQ(=Z@`7@F+ z3OVroY&&g1XVUiC3V{X??i087r&%nW)>hOhfPXsFb;5UR8zsu}Mx#VK`P2=^q?$sD zfxIB0%{)Vf)%$@O>*~@hfLlZNv(cLvh-4SC-~e?Mmbt`q;3XeAql}rQnG}WSYBu)xl@6m*|sV*kny5sqe~FJvMvKH*|xu?i!Sl9RX?!rsC`m4uIV zAC2zX!9xG~R}xRurd#j8qMc8bLtpRZm$54opJoHVmqpvj);o~8Rni~Uj;F!pz?ZOA zrk*SBCr9HO&dwm zWpCbOM*ngtWCk*;Gcro2j?hXV4Mq1KkkEwYnNK*u3p$;sN2B&tF469nKFocTkU@ zT?=&W;`rA4cqu;CJo7v%^tt{mu{~9d(tIZme1Lt(0CEc7E(@UgE|}tiTM-oZhSz(|7sK8C+IYVXc$@sgci_uTgrL2!Lb z@8uHi^2^=Wf9vypIJNUXR|=BdCM8WraE26=(|qjl>A^yHaj6k8s%cN#$(BSpk)i}X z?)ccFWOOilF(hiUmzrCiCd*)xW<@U5+uJWKYXwnH#D?ET-xvLcp|liYyZCvJTeOGd zyK`sXqtkqA#xby^vAiz^%tbDh_!2Ad%GC7}?I+iq_|LEC)1C$tnb zbSrCC7xHwtI!w5xlybvojZW*e&P&@xg0+&=LK%Tr*5(n@?YO-EV?W@l!FPjIR0YCj zq{q~J)%thZq2LT>D~Ybo2kN&sLMhQY9Cs7HESuPil2vS0At`uAnN+l_&o<^|m}Q=@ z>+i#f6>=4MNgvT$Um@tj0-5C$wa1D*mgNBB^Vm3dn1BfNR9em|H7|mnnN368$x!@U z)~zswng=9=uO#FM&No}vv<2Y+blSJtgULGkBSqccoWGeCH#B^@Blwt#hn<6iW{HvV zB~^9{t)Nf>z-1Lt2I-c&3w}v$;Lv(V>t9v;)m`2B{s5Dn5*;)ljZ8fk>De0N@<>Vm z*Yc}6T*HFvuYKzOcmZ%P=hKuGn2MUxNRN>PnSzi+gF}mHsc+wPcv5USr2ty4$+}>% zPO0~A9#-{>y)s$y{qySs1*xeMfe562pINSt+(aQ0;YlOn)72EAVHtn~UM-HiwBE$X ziigFIc)?s8P)#UMgH#Zh(`o)dBhA%*OXCKOyt_`a0S8s}s^0X}$TK?|9A~dMYH@x- zfn6mN-aJu8EC3<3Doky>14Jyybo(A1@0eQH5B5H0eZPrXNSR$;JlH(Dr8aQ6{Tl@X z3uty!AZ%$Z4LCL{&B|F&R8XmSjp;rP`Sp%kZDmL9O^D&xhY%)5Vph&@E(E^yX`73{ zaDI*%G8UzUmSp>8!3qmpY`tsv1EmpTfw6^(ywhm_jl`P;lBdMfZ%Q{q%E9*&)Z86S zBtwe7E;+bE@20`?eqey@qXlL_t0-gTx66Cb3}UZ975b#}WbP^FI&R*E`&g&KQ_DN=KLLS6HKAu$trmG{f%oG9^8A~ban>LVMk2K~KOxvB>tzl- ze?F@XeR(FcGBwnf4Zg0>6uXTDfkyX;BSX-%UZ{L1Y|TdZrxY{u@W2)CaKY*k&*if~ z0-6E;H5-5N0U=MA9E)0}vNBu7VM9uWhlYELhX{=YUcqglVAIA*b?I#`m$^&9jresb zHYa)pib6)XTxicM(mW`jgyM|ydQQ!^A06ixy$2&M;m1(0Ll&-9-N0e9vS!2yhR!5We4#Und@a?ItnGFh zt}!YMG7s^I!uj716c%Og^W`F)5R2b)Ru12E3WbP+0i;k_704hZi-4iyd>MT)AyJI? zEGVazL!yo8%{#ujX9lIE6eCf*Lk7zfb!YEg?gaQL$}NOn%?aAG_;S;dzt6M&*qm(U z!2rn~*z7C|AHBslPZsA#I?qUN7x(z#JHa^Dg!r2yr5^@_C5n^Wvck&ySi{Zhgv8ea zxajB>pN6X%0Y4gQ8bVe6ePU}65l_%f5C*#k(y_;oe(t8?<&H16dZ7MHN$2mz(Zuut z&1{EMOty6UvBuMPb>qJdbuj=dXPouts&|H!eTX`Gi{dB3IEHgy!;hn$^rh}yaZ(XQ zePiTOj&K6(u|3U<CYAkYQZFN&p`l?Z!ebF0-KKV`&T9Wyge_EvVi9a% zp1PTuH*t$YPxw7k9{L?MQz7PV9$><$(qO)e!fxpae(z^0mtJJo`;`q zn9(pTgPw(vPByYzBM3?J$GK_lq%=_1y|>!X^09(VY^!tQsL#%f>F(*8^9}==F0PJN z%Peoqmp+5)TSgj-xOlvwt_FE3{K3nQAZ>%aK%IsO7--CCA37?|CWI^>7oZNjX+{F2 z>J(<4%>b8Z$gP1$m)5z(k2FjnJJ>Ig9SsAQizI4s`pC1$NyaW9yK9b#= zM}K>?CSry;c^Dds;w6^`W>U?jF}{S4)y;3#BYB4Ze(H9xxA(@p%fD?vxw`p}npuVO z6#eg6(fUtjS2QXtZ1LudvkyDXONP);ACHgwzCZ7yQVtl|Cs9-@*aOVfXYsXjwJ(*mkl76o-`kGSh>bSj| z&>l^=W$#_}e)IRvYcZg!kb25xYs$P$qsym4Tix-kX53?(d2bgc>OOs2Ez!}4S%?HY zRX_76U@jRBJCeVeh&>}*EiDu4R8WO!pb(|XtW`m^=( zB#h2N)6rueW}E;GdF$@`;hA6MOiuo_eQOh{c9ysuU&t}_kb5t88dOxpq^M|p49(X~ z{$Mlg1d8yJb`@eAr>*d`w#@(*$F+ndrasewIdZunk+gw;UeISSI0uB3kqUq{jJXwi z4bh524!2>Q=nNm&CZ3@f*?8Y}X&_?mR?ImOI2^3}LfbXeN^YIecW=En5`e&-=MYG( z>=fk>fh%zdXvHbjZkb&6-DsSpn;xXMXsBqA^m>18{^`~JhfSXAl9GWT<$qd#YP z({se1HsEhzVdBXNB9uVrA9Er$R|TuybG)s;lL0@FHqy2tuEOa{y6)Y)S7Dsot7Fs^ zdg--r)JK?S-v7p$tF)T9IC{Rx+f#?5_u1(Jk}|SUG*p`W@ZkQW@=QCE`g}i5tkstB z*-mubA1o@y*DTNEG+%LoG?3SLiLG=63Dto$=`f5KeuDsnU&m?u5CVTRj`$wAQwP;cG@wB&Fd|JV)j0jgtd@zg)6f1SbHwwX5d{pZHebTHx}>*Ffv!5 z$SBk_KO76BIwh&pmf{0TxNP-u$AsJ#T*)WdxVJ9j8ZDYclE9d#2iFj{a&g6S6dxKo zF)=y(3^8;8GTvqag3B`^O0Dmf8wzMpX{XXbWu@5opiFc7W`&P$Qc=4;N)U8DfW2BF zKcx{0GLfR=H4%PC1%55XzxE;I4JvX}#VT(6S4+o<&q#FT0dYb?uAY0PDmppp)Ea}! zr!Lh&jsn9r2FS5YHylS_7LMTJ?f}xL!zdLFNslQ2tCaiKnHQC-x>L4zA6eKCX}n&J zp=_|L!f5tV7ni=G?d+kMK4Un!ps4`(rC3mQhw!lcE~IRFr%57vt_kHlHXv?6k9 zBo{ua2>|n}XQrkGbz3bDEn;%8WutrjwfP`q8#T%cU^6}3cW=3&?mjAS5B9TOnb zONdsmCe_+ou9M|c(B9iLi*e+yuLYYkt!^W>YMj}aedjmg(eN#Q?|M6X+BUhKb92ia z#Y{3VYBD?);!50(Z?%bo29E8aDiO)HS~{xxTXU_QA)fq|si_^X$#9)STO__=y{1k} zWMRe(isKFes?tA{;4hRYM+D2a+lMhG_mc!D+zSoO?!Oc-=NT*%h=-A4mnvxY$dVM9 z0Fllf7)*n%FDIiVk#uresn*-eIC}MizVTfdI^rMXA8|8(Rv&w!cDa1Ds&>H>d(Km2 zBKf~Hh!F5B{b*ODkxS^;x0s z5?M|hoJfwElYRA-HT$`_#93U_;KJa*VE(xKWLIm^Dj_??%+xDhqZ2747aF(cu`C6M zIt{r#nry}X>)ik1(qQ>$ifx50ygVa^iR*N*>1KrX1Gk4cGtk9 zHL&WnAJR4ymJpH!TlK8t-T4GS19wGtRPdzVgbltL*F=0Ghk{6vL`Se!R=sq~58^XU znoQxBXYGq=hEd5xw^!wvnh+LKHa5X1b|#KzeG!%VPjT)yMQhwV6UlgO<}3l|RqeR7 z4g)Gvz(9|P8EIC__+Vt5M3lHEaG`t}QX`7@#?0|Qd$>C$^ZeO;Uk+SG7@WuGq&?iM zh3U>C20<|@;3pDi9R*{H^Ve=KNo*D>0B9Z-l0$zfF+Q1_M-MHvk(+ECgdYS7@5Ch@ z)3niYR~%+XmK?MdqywlMck|(ACgYAH%S$8UpZWAomnDz8K8Z>Yt}jxD+y|1=icVqy z`ugN?wB&b748`NpBBDMlyvt)}JyVtY|JZu#s3@a0?006UA*8#zB!&*@5(Me)awtV$ zqy^~?5rm-;q=p9R8d8v`00V(PJc-K1bS?_n&`Dg$AtY@u#@4c`4y02eTwH8Pn za@ngBTc6@sSQ#tjG5nrg5Sat+RowuPuW9}g4^_btI!e-2pu8lx)qvVO%^w0Z*~xwh zt)Gu<4xR56sf&Fiqj2l>Z-_j`RXyH=GieGM>wc)9l#p#y6Qj}#CWk@(v?(t+c~wPV zcUR%uBCNd~B6?ouTPif6D(oU)US@WYc#m>c6vk6{QL`}NNIiY}`PRNH9HGs)FdDQY z{iM)!r_xfBBK;KeIYY^pKf&EL=1WXludIoIzaP7%S+Sd6&}b$GYE$v-$x){Z|GZMW z22MwGrLVG5L<;1j=~REFs{LY?Dhy&5*=Gi0MH3bq?r(Wh#|)!07||PcA3}D^5aC)y z>58Mhl{yX!?h@V&!&(;AM8giN1F zpa@t=5^xIXRtL%0KVkSd6t@yL zlSrk(TX5CC#hZ2*zdwRNlR))@i0XAnpj- zJj1llz(&%?HMbL z^_J6Z@bBkP+ePjMe~2GpRcd3nUx%O1I#7o1WN6O7lc@Za)cF@e*7{Y3%(`+4Matj= zV;uDBsPE_wQ5;1$_1`VOl0#H!VX~dkpZU!NUAgP6{n6(c4>v?M`>PC$2XyC2H`YC) z0pSXhA-K+(7p6O^G}uPcFYG`5`1#W&5sdq_uE@;%3yCSKlrqTS;_-%uHSy2S`AE{d zV8GR{lYUR;=y~yJhO$8`M_S#o@ILPNiXgtZ8c;QgBRs4JU;3l^w+oBtiXi=1zB-BL z8Z7pONeYFpuybfem1CdkiPZ2u89sp7`mC~aeZ5b#yG^}Q488K}Aii&E1q-d$nRQ%D z8m?&=sQ{9}VR521Pa`IUpH8_p1F17ZPYD2#F`=L&@C9*+`sFpPCgvwa#@1_8O1YN$ zGNJdcdk$O5_81d%SLQ@No;X#BVyke?bc==`RUNI5FMs&84J&bciS1lRzH*0tW9E<;?_Cez*IyarheFvbsq*u1JPFq=?*%sLrI=^;@h`&P8c*u&=F=KdASPc!$;AY7uGT`Q` z%k%p$7q-RmUkG`LZa8G4MwuhGyOvjFd9fcSV9`oX%{&3j3voSx6Er$%x*Bj86@mpPy^^Ew3IH|5>;5KifqgPgu*#1fTCJe%HhCzd!wV4Gma6 z^lAU?#w5d4QcDu0m8AW%~xJ$ppma@%tl)TV;zAo4~&;HqQ#-|mUTX!@w+ zvRpgQ4|nWd2%*ZmoQuaRM?EToYU+HWaGYP3IUw+6nvH+wzN^#!!sEf6sNjp4{B8H8 zN6@|Ct)uM!`YammyJzA*EYMsIuRP+7xoU%gpCvt<52P-Qa7my8Xe8X)I7D<#Y}M`T zNI))njsckQ#GxMbiEWwLWCktyU^6#T=x>)QpXptRUq7O#Kn3J9ZZ;&i_HjpzXG5%@ z5XoMXCaOsjajdF>0PB&sZvlF--aVe3(BMNSRd(XK!l+m{u7-vNvt7bw3*~8vOTfRc z7sZF${?_K6A50nTi(bgU=%s#ny-q&)x){?MEsTRj3XW)P?F?#fwt9cr6DgY#jV7Q# zdV&o7jY5AcJ+dUfe^2-;D=7@hQ;Qk_Tn%I$;n$QPl+O7p5} z8W+IrSt;+@zwzi?YREEesC09|o7PrcG%OUWr9eu5b`FWe&98dZdW9vdSGm?OL#k=|HSW*NoDz#tAuxlvbQ#2)pylybI8O=s0{C1>Sez$0feSaj zg&f)oM5(kN0sZ2+WBGfKIiAeMC0VyfITbk&-5|@Yzy{VxZs5DkgNzN$7EZMv!8y-A z>#;7s05T6bl0skf?6dqfqs3i=7;4SC_Sc zzRiI$V}~n^(3afYslAs>qj8qI2Ro2}PVySUv8g0xpd5X(I*hMmm&zevt_1R7ZUyKTJ z#wq@!Sgr={JnUx0nH*0>i$4*nYS!CuM z>qL3O=beMS&2sQ3=T2oDG8QRT@Lt9^m$PrL2=P-n0u|~g=_CxRpNTge-x$x=-`}14 zSuU@j8dm;s`dw{!3e-l^pc`L+*@~jzH^=jJe&HX^p%?4>k$5PEC~O?v=Xx=j7&3&) zj(l5L`W3F^Dt>+z0f*Mh5pbYAo-Lp9vunBS$f~3qhMTKP#%~ZyFii4-9!YA7 zAFD+k)BEnT>o;1c%g_sXDS&uIN*bVMn(Ly*L(h%Rmo)Z3f&5k+p#VlB({io687>F@J#b(yBYvc~iuUm1VU zli^$+vgv>|p73EWTiJX4AlRfLDpvsPdW z9Wy=T3ii_NlQDC)^0J)}BZ+wsJYOj`Y2q9CNedfmoLyg_=?l)_{gJsZd`VI*H&Djl%GqdQ*gznAQx1`;bUe+W-ma4 zG{!?Rclu>S^u$Fu8?(<(mP|YOTuJA0J`l@VZ6Y9msOU)y@qkQ*4CAnh&1Vz&*q~!;HsAn?kW?mtgIk|GP<>rAFN2& z#t+&HtL>cFvISeADC$oVnCZMEjY~jgrA?uBUNWkxgWV)!CU#w75|T&RbVlFYb!Hit zUFg;)XEL{P!Cgx$G=}F}L_8pIo`bI-ipk3tr`1)~A^ou>?MvdmcCrR=*>0Wb$ z@v*f}XdHHB4&zB)3a|E*VR%?=CQ_tM;nE{q)*t|88(|)uuh;G#+l$CdyM%ze5Ls^6 z9w^vYvCSzDCYye1YE}ho0b^LxcvQuvrS-c$*D_oC4g2$9h|Kan z%gZwGz<8LNO5b*MMz7yQ_jR8IzD*xl zhwD6v{YD>&LjYExt){zS91{a zG^xshzsc~g*4}HADA4VOX_z^HSh?D$?PJk-Gy2RZ1VT-09{CY>m>=Wm1_3^H42L>1 zbONAN4P+WNlga8GEz_&^Qxwg{pM0q$A(Uw`{%N#g>4L+i?sefQpNSQuaB0BfhZ&kl z=X_%k(n|Eu_?FRu=#i&csXv6aFplb#jgsC!^C2Rd7=ZJk863WU^LJWNwT+&Glh&s((Xu8N%3J1k$586Qn=o zi8(YrNE_p~5LsF-4UDk<+S2HllTEAP7*&Ks+J^UNb$YS2(5(^R_2(8WSmU+ODFYxw zYe06DEqYs!CQ29I>04%aEw&DVs~5Y2>%G9b`dGx6%S-)`++DYn1+nmor{Qz`OekB( zcd>Qa(-rS0AW`9bf)ML?t*wxKw7j?B+81MN1Pig61eUS$3IhjoUWqz+NRpJ0suJ_N z0w`f`nFB~!MWuhO-=mDyRRAz;I%*Fdu~rXimoHnY{j+?uP?16KtCcTmrMzqj;#+MV zhlSm@M(NOP`c9Z&2^}={tGFKWoQKSQW5-Z?v%~Vqh*7h3m36nJV1|&YG=&X+hU2>p z5{1b{Z=v&@zUVi*Z3Bh*r3S-ajU=+qTulXx-*^O;kj;rSb=NMAM~wSz;C+9!3te zi{ggPMj9U-E`hP3xY=i63pdmT`CCF5GCG+w0}KhoLt@iB8Llkp`kXl2F}WRMpKt!) zVS9}wwt0It|G!n?KlQ=)`-(I}=}fKY@ll62brDj}NRikcu$$PV&9C$d8oPkDz(|Qz z_(fRN_!+)zBnfaYsd_WSs-mK@vscQ5k|;_>2c|9rnM3?T)#VQwj3D8G z{2UR)N)TTYHaq)ZIddGON>YQAn#$JJ?5-k2LLsw-qX|CjIri>LT~%f*oK^`1RHza< zBQf~f;;=Ou@Y~gBe@e$1rF!9ioxP9az-LOB|GMkJXAWlvqof=&Gd=vZuQ6Q`1IW2b z=C?2(VejriJd!00v#MID~DDU(Nt?N@8aQds$ePqby}Z+3R|RUEe8C zyY>K0n=c8Coexe*FHO^@c}Mz2Vto z22d#*!=A6kD^5^q<0`Rg3F+z)@u{#s=A(x;&#utaGQ}k7S(%l|QercwS71ZHKuZRX zii5Hj{ULQRt*Os2oS3E(m-;xz6+V=-I6#;N3PqNm6(;%lkU^FM>|t-qTEdH{yiP)C zCY}$_!couW*V4zVX0#nUY= zsT)BdDcOiD%25MsT}_umrq=YLgf7{Nk6aCR?gAtGR#nduR2(%w4a3 z1q9JL*#}=4+@}(Kz+Z!Ww)6~uTX+8b7r%Y((}bd*BK|}V1}}{yfny*$7XKSX8l;vh2Al#iJoirx$t`ts{GNDmnU-5 zMI07uH_2iDP6#o}la0wpIccl)ej?0KED|y+mu*zRa^9WlEqP?jVy18(P$C?%vc`8_i;-5T~b<`|SY zc9uYw)K09{K{z~|W`HCU&$b%Cs=^RBV{HmfMYLks!{9f_p9x=C21UTDd=-o^xf$Vh zH7FYdZZ|WE40Yi@^~>wW40$hpDJi?8;W3vkChE3_j}30jkie&-cWoOl?xZCH9woqf zeDqDu8%S_L1-ei@Umx;{{b1fon)jF?^L8o(Z@GoEn6ZtOqM^p-=q=L7>?5#1FVb-G!TFERkDx!>y5%#&E+ciXsP=aan&>ibccN+HhP*5I#JF3Yh#R zzad=2dY{yLtDY?^M^YQarTF>7f_@)t-3Q9wZZO@g>u8qiEZs?Jx9{J(1YU0KZ;pTP zp3{6UjpF*VS8=)DPDEOqT5HK^lq@7FFZALMXuB1liv`c9z`_lTZbhhBt2P(C`D#$( zkQ+8xa#$)^o<99tYlwo!wEA+ucWJ5OzGB?OR-jl;=JmE`*W#(GJG7WQrPh@F(}W-? zJ(ODilXjQQSFOqt3|}sjskTpE^4CK8ev&J~QGKsdXx`KAHl+zTJew`eF`-AkcjS}8 zY(UEJQ&+sB`<2$Bh9}eom=0pjnKm^27R>wp(62Kl*T*-#n%2D^x~k^Rd*A|qxQRhWh&^k8>vD6k(Z@v0%u!wS zbz*Le(BigN4zO%gMJ}63?8jU(mUb-CoD7;omflBFEUJ^rUk+#OD>Er`D~Lch3PWAN zm>qj8=2opkf+V!3pWvru6#;v6?jdT8*+b|F=K9)E-nt%TCYK2}VuPxbY$&+aeB6kR zh;eLYnL$w!uZHT*X!W8!NQxdyX11P~^%IL1fqe;3IMwNr*TY%nS)A6;mbGOIm`vn? z0Mt%La`uIT2W{KCaqxt5^sJA2LxPbTa&U0Mr}iQh_%pRwtFNAl5-(*fWEoZn*li(*fE=5CT^-c|7*#Nt+N2 z_GR=TB&L8FA>!lru3cmBOC0|LtvM_CH_dwN#DW>JActp3rF=*)sYkic(#@#K+jsdh z0var-4Vx`@=4m^)**De3Vy$03jn{5d;A2?h1M^Nv&gdIx?QU&t`dC&Q?^}FqZ@*EU z!=N_+{T0oX`!?w(TItzCL$%g38zWNh#uMkv!1}4nVQgEW#$z#$D%-~;&*}Vv0B|7?h09@aZ1Xqb1bJ>!YRrt(U z`ZZNG6kDIgi+D|iUd0|vC?WfnPgn?_EGCv6GX(XmitW*#6YVS18F+Eu{gC>wpMT3` zBT}?cn_q@N?9b>6_%&)gY}?%L$5-qz-LH+FZT(nY?d;yOzt|ex=6k|RK>0ZAVEFni zv!lHi(r|q{R24+_croT}ir+VO`zBIeVN}o&*-^=>_f#GfQXV?-aeki#LK2NcHA`f- zF5rFq^tm=?k>fY?)s*tiB(*g;r>BaW~I2-f)suBD&zlNZ;2eF8oU#3Exf7;8Z zHD;Edz7~$I=+T|TrGAYG6S?S@%rX&KYvscQ47u7?A3U*{;q7o8L=gycBaM2(5b2=4 z+)P-Y%G&F6xMJG8G7QJ`NT~C-Kv>da=G~k9Wv9%|4h}rS=oXRCSowpvrv4`i7qI&t zJg9kSQZcD-sCKdOi5xKrV!>xjP=C)d3_SB5@p&Dkbu`8!0x)b)03=A#qAZ^s)XzqO zCxo-R_XDq5SqM&Goy`M1v~xs+FfqxS%%gFoFJ2rX64;ycW$Y)e1s)|0nr=d5p`ihs z`^{5J*;cdKKHtvNBsc|1de=8oxd=lrNPxeWlLueIRxtsj+B;arL?^BDzPK>)1j6YgBL%hT+-rO4pZd8$}8G}H$8pQ(<+^!@s zD66!Y!gxK@GGA&Pab`;TuDcK}SjxoLd1muiJ;MAcKQ*+G8-F(kR^G^sRL)SM`sO;? zINSD&-lxbob>*{sX%EvMEjGbZ2YeEPGt;>U3(( z>cyKXxtJJCTms?-k}@N5Trg`tAK&Q9kI4SXQIsqubba<;_%rY>;mmfpXUG_zV8LG7 z!`1k`D2w7+rS_E2c;cbKt&70fz}~1`+e7W@jJ_rh^tavZ`S!z{;6u^F5tEJ8o2?v! z7h1NY;UL}S!C6vLPOqcZZf8zbC^4to(akKYh;KuBD~l3FV2|C_WA?3Q{%ArbIN{{9 z@I$3+o78e7$Kb@pyP(eCyXyhTm-6?!@t!$NOUg#0ja!!8m#44F`L{}Vig_MWx2&IZ z{4t0DVn;@Ce{Lm4@Van7sq!nTsqpbg;|DX)XTe`;qHicltzL2sbbZwTI`Zqjo_(Y) zVR}lGtZiZEk@7ld{$}|nu7upZl%AU(4(0pgST)++&biTrV9`v5s?Cn#?<0}e25kGW&ccxd1?VPoa) z0R%&XNokT-%jnG1i=c=8t$2mQ*e<87H~uvJuJ{!W3!&D6j7LRueIHnWufdqj&;X{b zwePI>>)?Eu0=usDQF8QFfG?77wp#n0Zz3^^V3TA{UzZw^32NL4jJ;!osGpQ<4-&X- zc?3%5JrN7kj;GN=x^nhH-66yx3s*^FQo>*%%)i(hcn+%GR?HwubueY@%zKTmAyP!7 z&?&~R?waWfeC>TzVK_=YHV`_J9Go@BCVT1@wpSCw9?F(zHD-(4*qWZ_62vHy&`>|3 z%Fy9X4w}Qt71mqCuP2^5m}^~IdT1jDQGLil2`esqt%Q%o+lBVKx!i%jJ@4XK3Qa}D z?+IT$Oo&KLbpsVFK`K6`&BYsMk4)H-Zgo;lc9~vPu3t1sAODWK!PurK z)eK-dngd2+Y|ZQzI+h#+TG2?+f{VXhl_i`;PXesO|ZEn5 zxngQ1b-frRFsafW<*fN%`WWY6y>{E*IhxtH1|qJ*gswIX&11IhKMi3|{ks+`MPJH4 zoP3wR?6klAIuh-Hlzd5a$kZOQ?+*Gova~c{|0s=h-`!v1T&EV_$;;m?JbuLoq*7zj z_p=(C>F#lMrFWmc_gLrY**{ABL96AoBti{+npKIx1O3}?o^MT*S$7wYrDhc-N|H*^ zV~RNW1X=rGBG=9>NI^n95%GLFNuFd%uKUycOX%Ahk;+6hWlkayr zI}|xxR(~)IvCAg3y?MFplT{*wk;s>Lfb+%!US4P3>+HMZQ7-^Y>=mnT%R-s)w*E}GhwYAij;2+K zsp}gxb4R_Y!ZD=UhDy3s1>Lh)p*~^dagFCBTf3Mzbs<^9_~Fe?Jdo6zD-_PR_3I-o z&Sxj>#F%e#jvW+|JUFKsMNojU_H1IPGb>N^!kF5X(pL^ai&!sl9jyT?>aD1T&F_TI zsGfDwys;&X3e`uERhWsSZA! zk2FqxVs!%|;?->;BR{N;{@Xa^oZs%t-O)zr3Ag~mn(O(qJJ*IZb?qFO1__E(8Sd8E zX5MC>rZ_ZpP;6$bWeiPYrcC-mKOnFv{F%gySNXmWQmsph@WKR(qca0-vv!(Bop|B(9 z3j=QkuP`J7+-0lFl zaXuE;6@2$^H{fiiw8kMJ=mpCFc@d;80y{`sD6>3ED3qD`W8rT_^R_LyIf0@Fb*=-o**+wbT*yO;Rnt@4P zZAq%GWw*ZjkeP4()=xClP|U90JjBa8GF$4)lCPjI5a*UL8a(y25iQpIZakZ!ItKT@ ze(zsgB>N-2Pt6a^Uj3ZXex=?CK(GtP*b3r&5UYlkerd5P$ZU|HdpR(@R_-qiJ)hTE1W0uqL70a*F;Z5rhR1F zY%j-S#CU1+5MF)5vtyHi8!;e^mA*UXYBqCTl3;$Ko7-48&Hjh;gL2mOd|>X{t`D7` z$$J_wRlB7#}|R z#CY^6xubCp=y3oz=Rlj8Q{-ZICWoGR!-?(4X6F0L!G@k`cijpsdpF9oXJp`hOl+a~ z+nnmK9_mmPt49Ao$p^n-ZiqZiItr=v3;S*D*#!fZ=TLzLFbfhUwDh)$DaMvu z8@l%IGMi_luZrfU&Yh?MdW_m|)oqSeAj9$48%WFv;E%+hoAtD7|p3_lw0uO>rBC#V~y!Q@se-)T-s#;+)_F;BkW(2S^8DG zV?s-J-Zh$eF<0RMsabOh;e`mDsjrQ$bp$@9tAb$>qefsMT(*dN&xd!CS`{;#s$OES zXD>^!lPVkWG$-Rbz5go?{zoS4etJIJDxWiMdwvczeN4=?j}gMQ<6@-**2VO#3$OxOX(G@B9wJzQ z`A$eSf4uVOQUB#UA6=Q3IDq2Q6%)dK#UJqPayj(NR;Xhwl>k}Wx1dGB=uN7cxhp7E z$PjGti#yS&INm&^@8L?&)$p9Qd3izp<$3N;=tXdwxecx=loVIxYbEqWuhw#mrIVlT z(t8!nDO1fZVv&@lcvwTSYAG!4>r1I#^boa*R;bc2&A3a7h%!R<>Zp3}TCQsDsZj+& zVlLZ1PjhnLUH*6d(-(?Lg_SK&UmSMd)dntpkaA}RZFt5!O#x!V zNqw2Yj0HC#OlG3J65O34u2`mdC9!(APx&dz;uZi$4w;x&YS$Vb33u!Srksv|-kQ=a zMnD+tulBoR&Pa*DEik(WQ4)C(R=Hk%fKXu0mhfju*1wi~(ZiQM$JefxwlrbD4raz- zsCb3B5(PLQ4Mkbb*7%ewd=`_3Kl1IQ%?kR^_d%Onj@!lcu!2=i!? znYSGxK-L2jfUNFJ2Bvu2ipT~~?PEX8!QQ9r3s=rqX=13Pd`1_7hItWWc|Y0NW9bck z&HUK5Z=?8*US3RH=8cP`4aI-rKZ_D$fkvmiN=4!+>W;ZGi}>nlmWN_Bx`ILC?#j`G z$VS=_FyUWF1z}MGKh#}CS1juJ)`CoS?hC7etBJo!%=%ScBjP~k&4lqS8hMc>YL6D4 zI=>|aOm&Oa`a1@^T8ZT3Kbf7X&WzXoi{zmLmf00!+oH7avbNq#+)z0=QA3!$gA|eY ztjIw;%^;>k>8k#bN0L=<_VBXbD-YuE9wlS)-9dqVf@ny2ZU+6RE_$KIadLSnaF!-+ z9ORXQ|FOzI0}v4g6SI(*i-+4$h}X6(DWD=2w9uokfrR~7>I#i*%yMn23iLo*+jq;v zs7avK?JsW(0rwQ@m5_G?^J~FjPmpAMBsS}}q(N>?tf<}OSY!}`epMsY3JpewF08EO zjXk@)#8Ycvg}GauYBw>f@6%$fDRR?g*SyZr)iD1LIm=Iy%-vR_&+5lvb{pn<#}FMU z9dEoZI;>U+efB-bVA{Ft880dIHS-tz19r(wKHsNa129VsstopR_+8(TMfoo#DN%0lIJqAe&SGkRusuZGIz;nGb4%OG#-;*hCn34OP@`EW-i z|8Q2bN;oo*+;#h2jG*G|-?i(MuWU%yp%THH_mf)aSQMR=wOf$%-{6z+2Xmjp?(4~H zsv7q=0|p&<>BBA4-6TuK=KX1Q{@wdy92+*X$fVRkm#eGfz8XeCHCfS)vm6)jggv_ex}>&_?kDqmWRpm z@%it6c1qrE<@3Y)sNQxFr?|-cHu>NSyT*Y+kJKcDC45c9B%GvDTgd-HqhLev7V&ke zo%F2B3TImfTOWOPbV%*PC$i~KXcqQuopOKQ-|u&OExJ>w{)WY3o@*Gp6;f$sZreso^1rUC)2K)TiZ#wMPK*zU=#;G^ z`kFR$t0k=FUzVLuM+2(E+#D2N&h=&QjY@9kzl)b2e^!Q-1oY95USz=z4Fz5h+)8P~ zJuLomxdeF~Ugfj^g+xf{BS30QC8o`KyCm5}Qxq3ARW*GrH&E#{Ly%w3B?3?`lX&9T z^r&Ri!tire-3BW_qD-mA|>lV;l;p5N$*9-6mGg(B~ zm36F&)F}s!F+mny;JQm33cw?C_$Z_p1TWN)X7h>iO4vW$O z^(Dr#ooG~%9mJ?jMM-tX)>k;${4MIk>cg~%rFYvgtDj-7jKY;R6M9ZH4|Z+B6MF2^ zhbWhqv()7n8nq!YVIZ~&!LR~uB*nStUR)`23t=ZjNS#5&HVR`vlvYf~*owyVtM*H` zI%Yml;}(G($&eOpastp5ENY5nGNr)G>O;xu<^64w|@v-WljMf~06c)DPh&VO^5H^XT*;gp#oUFU+M&JC%_LBY2I1#pM%{ zaGd!+^CTb-=4qr9yW~BsI7t9R_boCVCx-jY=A~Dwzu$vs z;&=DSL!BZzs0g-O9(G_QHWuzKoM(|{&B*4d?6Omt-!jAsG(!s&J zg$lsa0uNI`%gLEiBv)e8GJg)6=0HU&r|n=gdwjLy>UB;@P1o%@`sU)XFIN+Mw|~>l z1?_0*?CM%L4f1U?y9g3Qv8dXy);{_;)Y%IM3Rjbs9`1DR4@MpimzKt@Z*9qJ(3K`Z z7Z<^&9Pl4GOshf7esP;4SG>!Z2@)<>;&N5S$(um+9VhvlOdhp_5BKsL$@l2v)K|YZ zl`X6Nfl-DFQn_nr!);IL7TR_kQrs*hOMw6-+2X@TvQD4S;fH^}54%6KYztX+i*jQ7 zE5B`xZx?A+e=$-|O`;A*^1ViE@pt~DeZ^GTVmj2b{K=N^F`zu^=B>ZA7J;yzMWEr- zpgSe*L2%a-J+LrA(CR=A{_m^Nvyr77`MtSR%5YgNgN~l|xzc^)i;@Ao3iv2Y<4;D^ z@4p<$Pj_C+ADmAa?$c)R+EPl#Cb&;EV+_LkUXLU(T_1@r{y3F&`FYJV{7exGpzWA> z74d!`#Ef(}I1k@10X6fM4NJSIqHi=I)bfW61yF(Xrc7gPQE<;Ew!O{97d@$+?#E|D z-`Q%E7y@WacT=e-ZZRG)h!(rH5-{LF$;{f@Zf()Ri4}$pWQStDnk6DF#d?CX7XVz; z3E>_WIfmpQ0G3>oBHRp!O;rHLJqbJh;yOsvkUmBhr@k$#AS%#KoXz%$+{8147`MTN zUBK2L9$>qW0v>;m${L=*HStDLe08S@v5T=JSFI|J(&{AjdF7sDjYoov=2?9=nXh+} z8ZeH@3_+Lyl3Xuf!3!Mmyu=>}xztEtWjC)EHJpjY03xq!N%}x?<<^3LwN1^X<;8jD z5tq=%sRECL+nfxq2;(&|j}zBPdt1ym6Mhpl`JBW?Q?9fz4BN)#ximh0KFKk-^nVTEo&3NIxm6}lBfZi!!t{RBH?ehqcR&eRi)WmN@-&?-o@wY9e)+N^Vp zu3{37wmUC!I-9Y#)qL==71GLaL&9q8zP39>bhD2AYwW^uh?)W7)#TA4nK`W`UDrKb zjiphY-iFWX9fY@OJV`aIpOe9tn@aGH@R}szuB0Ww^@EY6=gvcZ; zJh_AH>gtBnMT87=Sn!!MjX)bjX2?M#+x8A)85t(y)pPV5+pnXDdkY5^c2a-@EL+^m z;=;%Llta>+4 z*#sXKXE46@y^*l_aCSU3!ljdU|L3{<)y9Y*#`kAb+gw~Do0~-qQ&R*^DdcQInaM)^ zoW&PicfQ-DzWFkp0soxO&<}TgoL{i+7vztZwnwNpb~f0nexZ__jvd=u__jSiG21*2-|N@6_e_h;W(?3-+pZoTh3>;ZBO_QDnW2ik z!(aZk@xL4EoVI^$82|a)U7c?@zs~x$dH_YE%*YyDz0DYV3lWW0>SX=Vu~_D=E+hvi zf(>bU6QZ9UzFs2m&jCCn$9RM$HNSbElohaT1Psk>+XhQy)20AKN=sb84JBqxxhZ|O z+AB71ZjS`0}PLK9p{{1&L%)gZQ z(?d6PzYNH8M8(A;=^ZLR+eL9t-Pf65&?`6e`8SfHhENQ1EB6NWl!b)RB3Q9cCaULK z{IMD1;FtL_k_qv1IKrqWF;i@S=wb;cal9UF{!NE{KdT2v_3e0|H+EL~KegrpT@pBMfw$2|V0assuDFry z*eA64M%6-&f3Y;EJj;H3e892DNHE$iy_D*siqauv?$huU%mpo^M|dCz4VMttwi0O< zXyp*l22zj4FYygkn~wZpD7w-5Q||}_EGA{e)D!VvaxJk4FA~EGq6C}Tm);n(ntLpx zgnv3OW{2>Q01e8@RbM!xwm)lPwFFpT!lg*)w?HtK5c-23 zV`mKgz$zcogxEdTFDXL!;O4PD$fEo7sCJDHA#=8{t$R@*0Bdu5-XHkX$Yx~TG-7#x zSDv2Q3WHZB9*KFDrI&ql7h>o@SdLxI7B-_$!7`e)D0~TXhtm*@5!m60 zU19w+*Wkp~dXtrns-E0SDxrDlR_|@}IW}|m+G!wCh#qKZD_e<$nk2zz=1WnHq1R^T z0vWA3QR(i%pVeC!iuTg{0fy&>2AbkPw+W$1Zq1;CFzq@r_Kn0M>mW_Z3!Z3aOCTFIUQn{@dq~Tez@=kPc_tF_wyZ%QHA8`wT_Ubpy zOZz^}c8bq5&rU)t|M@Io#GuR?$MIrBxuaC)s4=3N+){OcAf*@rVeBm{Du?BZa95Vv zo<+D8|KL!+svZgtV9H}QL-kywWS+=>sJLa66%V2en&?lnXT7!mY0>`h4^QD@i7Q&3 z?|&+R^q-p175$mGq{mnY)zZGFMqE_Hp)t-%Ibu#81*Nacx z@0lLRn4;vI?v9h?1J3_m2d>_&yVJM%aE2bPw!=rWsx97GS+tJX+$>rsf|2kC#WDZR zmD|&i=Z7EOd*3;VSqFcP`pGc5dNqj8_59=&-9ypb>Q$g%(3?hcDhdAU)Zb1GTn*F3 zL@V95gA#|I=l&9XxQKqcO%*iw>C$|)d$FcE3SA`F?QGM5ChFtkkL*WrINL6_uNGhV zzYdu69DdAqxbOC-efZTA|9tg9e)i{Tz)nWHiO%ZPFix_sKS#~&AMa}&{TzNu{AOCa z@N$rC*n%V0Y+Iq(zIWT_UNOw=g9AQce#q<}$_7d?k;D{(^w|m7}k%2w>oB3c#cQOl2J_TJ1Y_oDM zV94Yoj?6$y*JAUDnY?pE5iZN{pY-^H7&?WaH1-UTLe?c_E6Ks!l1Y+I@Ykg$khp{c z4aeX2f3AQ(FRTKXP-JF* zAdBybe}LB2LMqoS{<`_bNIXVTyWvTU)0Zv<0DUm|sv0#0$z2qQ>U%u)xfMBoJ;J4wLREn;k@~qBxo~B~`u( z!6c_U(q2Q`Q)=d3q0H4}7P*T^_bLN^xZ7f#1(8& zwrQ-9;6Z}B2X}XOcW;6_jZ1LX;O_43E}?+{A-HRRAOV8I@Mh+{`*Htn{oOjJcI~tF z*;tJ=uP6d`<5P_N`v9l+S+eZpa zb=af~^B>4K7BuiE*p1E}YSWpl9_g9Y9LQp*b?|ihs{_s>pTtA4)rN=QSZ97lKLL*m zZ!=rSbEn^lGa`tawahFH!0r-bL=ghOv?F#b?E}8- z@HicR*%3V(P+6}fSjLgi9Y6!gjk&OnGJV3p+uRS~>)%fT(p@15dv+`v0(@DcIFB+C z1ZOw@nsTKET<31PRLFJb78|T^=_Fb6XBFD|@Hu!*`J9mG>YmIZ>1VQdO?6C090csv zXsq1`#gX>{h{jQOU6{aWR3&=p*A0K}$VbY)B~Ljvubll_$x{D*^Tg7`nr?D@@w2|~ zT4uVueIerdK3DHK_wZ6?Obn6O{m1`*y?k3W;PJDD&?>SqLwJCTa*gy`QWX)HH zq>7jH2xYe%<=Nax8Uop^as79j-Q64Kxsc7*v*!Fdo>O#@#~VaaKjeivyYtOnT_TU> zHlZvQb5yJnhpaNW7;nhwvpv(pqwVd(k%<5O1D=WC>D!Ho9|WPt-|4D$>$x>ej_Pxk zWN6^OgtyJ^{J>5lr@IL&({>ri=b2KKK4)BnA0_S{e6RU0<6EzPIeUH)S%_J7T6#!g zk+mpA(~mWnPzCPHnBzxWANV>2UYEb!2HuYMZ|3Iq_&#-CycOh&_}m>_B3`@=);_$L z_+O-(N5ipuO`CKGR1N|1n*eYfzef@wv_LjCIe2?)xwyVg383sG)KA_GBT{K&N3*&Z z+F=GptX!uG*U`?Z{0Od7rNyi~TwTuvVA9+ z4Fuyd!?D(lHsk6*DHoN2&t&)j)H7xcvrejnACN35mzNP=Rz?f@CfGD_Av1SG)-*v> zzDRc>o^A&m8?c;F%-2B~N3z)PF2pGF;zWKXd2Xw5Mi)<^G?(aiP4XKVFR~e`n5e*N zJ%Q-l)J`;?Nj#)4;E6w-^0H@#J(ihnW+?6EI|Bm>O3~E=_LiN(oHSXYlCw?GoT8KL zg89$k#l#G04>KS+TkVPF`n6L6z9XgW^p9;+@hnf^saH{@H`U1oge7G|K#JV&%V32?Cpw9sf+Sk1e}l>HGy6Md;y zVzqz$nFL~k%ZJfU&xIs5K$e`<1k^(KHUL-9^>rJLmhvv!dn`Ln8WMrc(HNY2Qi~Cj z$=^6EN``5X-o>n2Q%BlGfVrfbiLuB@h}|e5N>7#8j%1_&#*~LFSrG~0z5UiFpO7Cu zUQvx8{^};CBo32-fC~dx6lHDl#|sg*%CSb#FjMc)nMXsW0py}M(E4c0z*TUvO=$8V zR1_ad04EWS(urxGB_FnRiLwzFxtJq&0y$V%6T9sz$F*^>Fn2}&sC}qP>j`h_7$-?% zsl{fF5Ce#0qK~W?8b#HM3#MiZ(q|lz{ zseA#26vGp`pbG%&-X+EYN8&3TV}4UIBABzDuhT)TFkevv`JK|~WBE$h34;r_`8ywf z;GKA!9ZvV0%5zJsI7Aq2T|B;=_y|-*n-WE=oJA6lyVCz^GmBo~+m4h|k7lFsu-EQ( z+zi8!${5MwZc!>OtspS%j5R`SM1s?}b)jQC!vzl~x_zdX3U}b93`$jB^JJU6NBN{& z(^-plaq#9h(ciT7dQCg*BqIEnUcZg;`~BF_uZvfeu-|au{J&jd_l%h%-cOvFy%ff$nEw$uPPD?w?+jsR?{oa5t+&aF@ zMdZJ|Li)Bw-2>YE{@mhq*D25wGvksY&^Tq4In4Y0%F81T{PTxrY3&bfzTdx5yaeG6 z!@I4g$yZzd>cKUqepf%gpKZTu(@9g!*3tc2zF^_8KzSapZ#Y_riivoxubXcs5p}k_ zUsia+rSh#!d0N>|A_JBU=*hn3`}w5KGuCgu7K?P*?>@gO$b7jf7wLFD+;|lref4@c zxmUQ^Mi+kFGwB1JlSsJherVC`Y3$6_>Po{##tzHaHg3_3NF0EA*rAPRSYrk?XyT-I zFKGz`X~uM3!8Oqawe0(ZL&90TC@4^xD{SY!cAXt-Y%z>rSjc}7vR#7C*6@V52 zZUt^A`%JB|)pM_*w^MKa#%=z2(|L9$9`Lh-%?`+DMyCygZNcz4@#$Q<;sySaP8yL3 z-Scc)`0GNFvIoaa$k!D{GtG+{Ou28#9oV%+^B0p3XrKX82|%@i64?!@ZC6u}-kv_q z=VYGK5H0Sb0c9mei6uyg=ixZjh+K_u$v@mJ)b1VlG%(&1W#>~1s!0b ziWqR_h({vPEo6xIGLlOppRFfE{sVJh0^|S@T{6k${6-s2sNV=%1wXI=F+>LxS>c29 zbvQGA)k+u52?a}=x~uT~GWdF-DL}#64(-(gL>G6!4<&;dlp1Y-SR|qXch(klzwqr{ z@v(OTus?V`(QOLbW?+Ocb!B`lkp-@oFcVn9d9vkqMK2a>*Zc8)9TdY2t-i26N3Fu; z)uC05TL+=G(xQdR$RGteW#1rcqm0R2k}0#hxJby zj?f7rwT=$L)Tj@13mc#gju8Mkh8hmq$jKP%I_v9nVR)_$qACW=c3KA3+$T^xE}bLb z4(dQ3jKQAA$;-|y2KSz0h+u!R|8*^@8LN)SO&py_fZ_@bcaXUT@gG+)q98S#sKs%x z8gd59hYJfs3Zl3)0qE*V*MZ|%h=Ry|0FNWjizgA_7+{ly&o`DKel{(>O=k#Im>Frw zm@U|c?^aql!dg?8F2TwC!JQOLHaHn>pQTXW#+$W-YpZP#`g?!9rSdk}t#VTvXl|M& zdV>OX8r`zlz2GEP4ti>ByceAJxa>sZuh7?LL4ytQrU&#P*h}a}0Jdf5iO=)@CsMqn z^m1MO$j@J9q**sB2@<{KgUijS!2M|VBSciPwXjtG(e0;o~B@MWlvnKWbJ385v4QYOud)~}7P+Ewdm^1$ze6i8#^?MMd zmFFk=ux)RrkLT?ROW)&b|7*KNLO?si-uL&2a$~G~?kFDFt?!9Y&vfFAQIBZ%m@>%)*Ks~-IC|o&JloOW2M`DL_{gylht=3JU zk&%%@{xC^#5EaFKOkFBTL_bHtWIOuX z-k5>X#DR$}>m@gZwpk-2HGs%xsypYK*MwC+;oYg94HjmbkUV|J-uTZDhXA2<`DW|h z-;u!+Bc1M4NQtVQ3b%v63~x1+&s2Cv}ld>z{i;*3Yi*e@(6|n7x#yI}Bmh(OlW3bW#@euC(=TAigz-*G;4 z=qokPRSpb%Q&btM0sBH=LRoR~#Bs8a{=}GM(iY7ThlYM?3dt1HpN!j12W5A4zNt9a4%@kb0b^ilCc zTEeRUAw#_IKq5HUb+(Kql|lxDY6A-M>!U&ut`ES7Y{DQ>U=U~}_RFp}K_f3BJ4RDw z=SK;1Cp}TR^WaG+?1U^R%xTlN7=#%rCF=<&D8|*$*pUvEbKF#z+^{n+TsJrrJIO_H zvuvKLu`=J)wa9Cb`f?uUEzz?y&pLb-d(ZA%txYssKqeDokz_t2COt|p5tL;6IsF0# z;cP=xup>7lKMVW=sev10hGJ+La!E;y0y9($M0M8vNJvnMMEDN2+%pqGVdsuU++amG z>r(%LkO_O8)Qtg9-dn~h=e~V<;f*~irwt|qlgKc}m&uWr?rP^#ccQAszVK#y)B+mH z#e%{APb}Nts3@n#s1fH_rk)003Kx1>!sDi z$LC>DC!z0tw|cSpcAPZ8#c!UNC7q@BUfgzpcj`|Kx%65~bDcxhzvr`?^WN_I-iNLD-7Y_{0-uRYgtv#_2S?4CI9 zlk_$EC<|JdjEW#d!#HVkpsaYsRzELoNL0TwZPrmyXO#bV_b8JF6$i2WCfZAg`JAOk zmO!HLH&+`iOtE z*%+zz?u^VwM7*AHRv|V%gg5`ihd4YniXaX?%>s{4um)Gdgl0}`5(N!ZA1!9nO6T7m z9!OC3aFa5Y^+H<0$>_>v4QxZ!Fp&yQCT45__F|&F=B;B@GSY@l7@{&QZh$=2PE+St zI9~pHDar(dmsW${GcMR+>WRMXM~Y-*Ql3F!VH0+h3+o$lprC320zD;IOj9mdt>7og z5pqpJg;wQ~Pm$|l(XzqBGp4v4Ty3_fNGMw1{^6QUx{OK2X>?W{4IWQg3FL;8+<|cFXem@R z94!z6T|_mKH6gdmu`2xZp>RZ^?=;rc@kRiA{;05N}Rm zg>2fj1?Xd_?nB^Gvg7`-eo_PgaMbhqgmWZ4PG?Z$=;4!*HCbwP;88G+ZR*DR}GYUMSMa(}fc-u12 z2N)BDi!9AQDrhRzb&KGg@#`A>PmSoW?mhVUP4SiEk{es6NHA}l-?UD(XwspPQ1{w> zXtz@0pPyz!T_}N)pcA5t5d8csL!vVDTv>9X=d^1jw;Qj%=Xv+`#HV-lc{2ZX`()+u z_rZxzs~)tw*a~uYE){LF`7MJ2GmPxokvqE;QYig>`@dd*&u3wH=e^gr?b=JH7yfrI zGWmYD;|X;E7sWD8Ec4YDeXlbOcFj!P&VDZA<_uzNXv-Jb{^`^P99YdhE3r>5kyz~T zfaQdzgn$m83xjv+N$2xfa|EUIP8cry*n@qVdeista(cdl8f~1#F*kDx*6s&R5^Kjp zGI{c!VIo@fn_{uSdXc8KXtd%O(c0kjINB#eRcRI$;C0cA(~I;bR1cIY9$QX_u`{5hE`4AR7)GMaUw4xHe`qMjHW zt}BorG72~mlAXdYYI$;klmu|2rG-glj>f0-I5%pb-r$Rp@^59fXk@830#x+4xIT~d z;z4`AIBHb(2iEb`e=3L)7vRAy%Iv#jBRBDXS_Q17*-O z?nm9ZFc3-A`Jz+zn-QuRjNR(mC%kX~M1{yM)%?kpHf zJa%XI-=C+u^S+Wz9YL?n|;tZIK(ecFxfc}F&2Zevns2zhbmnI%_Awy%k-nQ-Y`kT zO*6mC647k-49ctVa6$3_i(H$9&h?X+NtYZ$vEq_trn%jnPc4AsQXCz}`E_Y4+~5)X zSic*yeIf8@Fa94G@0}v}g{vIvYcC(q8vV~aYsNPD;~p&UZ5{){4IeCiblrQVH5`$E z2`KPHFF2ClIl`aK3@VQAMsNq)VkkRN`Ebzoa{2fe>P&5>=^({mRpDbGZaBUHhWfVm z;)M=mb$xAL8@+=tVnBulQ3eiZ>|4p1egbMJw9RGx9=!}5rv9G)4cj}v>e%We`G6Hf zMLybb1yf9c9MN(2Og1)q4R8h~)B$J#V9Fm+H+7>9nBp$5g*uG!Va_f$`T!hLG0mV| zwB`}iWPOjbNZ_;JX#C!lTBm?hW>TmVak~;FRMx>^m`%XNpY8VtjD(fR+!3hkMhxEU z?LkdRSk2cZ3QsJb@PZwil95RRRohAuG-_^LMo~&UASDT({XJRlB4-i z@HOA!Ce)yd@FR!&&R+yj0FID^$Q%C6)f&sN%ubTjl^De7qavtoqrI53Bxxdq{7sE}YF5(=CW%C=w`T(&RlX z8N@XN8xofgi6|{$NGi{J$3IkyUl*~Xy{7rV&It#a0iF% zaj=8ZkgZ-C`nB7=L!gmXyz2Buvh%K>I9$RS9K!21%ajSWmh(+cC6F22p68N?w9g;9F{i*Ue`s*&Kah^Efzk&FIY-p!FGKDzeO ze{U;p0-M`yz0njsvJ;{lqMz4ATU4(l$Y{Xa9PM3A#|1|t-mZ`;uZ*ZUcukTQC6~r? z(}$n(MXO=^gkD|UdVjc-W$Pztx_vLsH+&&(Gc5f#roEej-NrA+5u{F@-Qy~G!hAyK zht0*KyEivfqd!V;)MME|*MAJ!KRa$|Gq%sFEM>p!(I(^zzJGG{I8OS!<7i;q&-)a& zORdeUddv;I+lWR=aBGvvEKdEFW6-W5dPbN2uO7?Xdr#UxqN*xG4A_2d0L*N zfwDvwL&4_ejzosgg9D!<1tqG0dedrq7V7^iIXbpgX&g!yWEF7vTr3dUS%F1V;A5R_ z6RGwU1Ej7HajWh4EVfHF0aDSm8ZM&nwu`bApO@b|4VPi19Z7MmMSE8#vj zEXIzc5^`K;*Gk4B6CNOXVf2qSaMIZ?gGhDB{QYxmSfb& zJnI#N#j(VJ59`}}M~E~GUdI8~JgqRYP=O^h!}X_RSUGgYa~L{NCvCN>1)X((GBoO# z!kN+aEi%D+H}oAk?df1Y7e3izlOcu{K6u(x_|XFqvl|b$%1X2Vx3eXZu;x(%fd@XM z6yYv)d)w^0K6^7Lq_d-QOYv39;8&TR^j8@g&HAsrvvLz{RWuEJWD>FNL(uFFi(-HVDhMjL?kGX7vSm6437J2qJAE&rH@XzSiAqwLIDA0hb{g@1^|s z-~{rv-*Ho7T|1Uu7muc>eLatTDw zQ=5%FG&x`eld+9ZVdQq4C{}SLNFsm0*+zD?z~V-XRkhFt8p{r0!~!rsuLKD!%M zH6S@D)g~!z}iYly9>IN zom}MlMwpzeN)Z2WghMrysy8X9;{k%!n5IS}91#0SiEOR_kipksCSKCG(G!q~#C=N* zgO6Wh|FJAw6xEbbB0C1O?XcGO_LonklD1O(!s+jDvPXgI(gFaOCt1;YS}Dfok!?P+4vY8#td$5BpLSfoYC_lK$# z0S;#WI$s#L-2p`k4ZS!xpr}@a+2waFH(tR|{I4SzQp!*$F?Ux|RXWUUfxTGK zFXw~y*m{0b?Q-oR5=k~%fi^$_E52h>FNy>f`@vv2QU7Tqapm)_UxfX34i)>IJp}K= zSE-$L66n&?jvt>L1*RJ6dg$-Mf0J?*AB=c)l#MW8gKHEi!z4?LRXdc?asSzGj);yp z&WymbE|Aq63c|BgzZ9ZD#FEU(v{EwZPLd1FA9bwF*cn@g>Fg~5WWYm0!)%nq2&9E^ z7&IIRHuE{TY<3Z@geO7Sq$WIXGKc22q%j2RXPhXI72b*w43-q%CrhU5MCC$G6;%~4 z1%eS7Q}6-*1|zaS)Y9~2;4)Yw_@t=m(y+)(%vILf0d=m(7{Z?$#Eru3#3z)Poe8HK z;h^9LQa@ik_FG@#JMY$oi-1lm#8`RyQiP*rAfm?mkzH1>LR?KlWf4Av5(_;I_NoFw z<|~^UAUe}b{8JWXmrikKpAA)Ejk63OR+Wej0VW5UiyxdBRV0h-Hip|!giD9h-s#-R zTOVPMCjToEE^VPqO@a*HnQyfZADH2cGa^{?)6+5c3QUxRLD>ut|JiV3Y#KQ5C1Jw?!kjo-}{y%V}AY_WwGCl=F9c(2w-ZEB@nRR=063|H72RoWiXZlBJyk2H z0(S~^b$=;dS=@q}%)aY>9WO^J;adTI?>7PN4K1&v9s?f#bscRP`=SgOijc0YxK|k6vG1$InD6%sln^p}OIdW3j=-u`RNa(iKRKrjoO+YSU2abl>ib{6 zzf;}j_R39!d|W*`jW7N=_5GW7U17$Jp`pe!+tFJqNmZUzo}HOhy#4j?`&J;^1z+T0 z-wpNZF5rGNg?9FQQ@>2=E^f)#Rx-XzuU+u_<(~!X?1=n&?x$*_i;c#X>44TWZ}sDc z>0wBN4xa3^>9&Fzt4lN*uc&nQ9pu=Zk- zL>Og0!K=6)10Pxs^=P*>7uP{0b%3)s^9!Xs=Bb&}zFYsT%_HvmX+J%^Z{I3tssR`@ zR9N8uj4|QybKD#!;--j;9Ju)&+_n2!~2pXLt9?Gm7P!i(G?^Wp?CVS*@!=H-oW#!)SpP|MaBK z+va1O4j#mjC9OL8SUKM;hlWE)_UW5W`_dXWcbg*2+s)2D?WBcI9(suzC%btg()z%V zZ>RQgok`IvgCmT)cIDQjCjGpTqRwY&OP zm;mUQ+aT0|)~AW^ufqTuQ`@Pe@g{nowpKB!@mMb4<=ce0_j?(H7`4*T02*EO>DSHANdxFnEK?iXG^j;qebw zwFtB!2%^e4#AW@VA*!udd7S*Iri*@&WL4yIWEJ;* zRMf+BYFT77tJP3h6a-Z1bfgmU?OZmnG*vd2M;x=kwWIgRgW*MP$Tb$0I0hUrC|y(( z=V0fgBmf&?y=B}b0Z-r)zq}~ql)O!?!$`!0D-+>&VBffLc$>E75a1`Q)?pL1!VvC= z9vSe4i6jPU*9<~3!D z;A%8Rh0EJebjB?L-sENNFRvc!N{5Ppbm#pE&|HB+QxrX7C=knH-5T}fw%8Lh5q8HR z_Vua=0sWA#vKN?BuadwO^-WnwL~&IOZ2C%9bz{8)66z(Cn?PdtkG{UE9O|YpY+CIg z(PW$jtcXOXx&ap9Hf|69j1&L~Y9k6`TO?0vjxWi}wdXaC)>2tibKblg~7 ze~b20OX2J`az#rMm(CtR{N8$H%B(l?RN z6lJc(?tIN093Bo)Jl(Ey1nu?o(yk1i38bV?KPt{j*b2w;qe5n8&T}??+s<(+Gp{vY zm*c?`X#BE&uB`z<1S42ni872~tAw?aA59$!l*&b90mKhbbu|CTMYL(2u58`f(dV zT%#)X2$?{}edVHR(L*a%vgT>|!b3^jdIfAG*vv^(bjT@^l$e7pexf}qqneNOZ|T__ z#|4UJIq3$D&Ph()+Sate4O!2Qv`h`x{K0=gi}P{hGpV8jhj7|BfSoqudVbuvm0aVX zN(F;!>Yw%T4U4Wwkcgy8;<;+8Df_iQG?|iiS7+~rfUWzi-p9k;;}&F7J7~}qKXqeT z$l|2>gkowi!gFmsh4pG@-Dh-K$NDzBxBcOxi1F9kr_*Yr^u3l9T;)}o@^ChyV3p4- zvzh2zuYN?rKX3GuDM8mT!T?G>AVe$?f9+R;oH1;=aNK_4{o1W5P&lV9Z{MBAw)I|R z%TQ!fQO;Q9>SVs1a#s07tkN10FcGWU6=K&SvYstGyny zqo4SKh!_zu&MVCO*T>?}xcfUN59@raa&n`4h#D4++$XDF4jzuZ&FCPAo0CJ%ry&LR zan;JiGE_M=sG2RFPS*gA**TyrJTZm6nW+d;*lYkoAPBQ9)v&(_HA73+BBMgFBPlw4eiclIZ;bocA z8#$8>(nNpPwgZB8W2zB?f8*gfH0S0Sk#n@uN7hn1%;?YPeg+IogtFow{t)2zJ+g0Y zK`2&N2XOFk%<WH=3yD||()u4pxm$8PJ$|MR`aqn6zTWcC(^; z7AXgyxDKZsj)N->BoL;81>q#q*9@FV^-F#Yd0M{T9lhpaMIHR=c2Ml#__;nHR=D|1 z(cML*cx%>p{*fn(1&n{Ez7+7UIsZS~fJo+F?X5ER_!PJ%7_ZZvH3Z+g$?l7-2hm-T z`%I_Jtsa-V!}FEHvzy1zg#q-k6Bp}Wn zNu9d_Z50_H_@sL+_b=BI%a6iezc7EjsC?6pFw@;I+3-I2#tODoc46Vx$J^7hI&~LJqBdj~wRE1R)UJ}^?c*b;w9p(gB{3B;Jj~8y z-YUq;$1Fh{PHl}pgF2KSXpOsBsNA63#=honz@m8ONqgFq3v*a1U%o1+s{n8u27`s1-vr1=O2z9bXL6%umm7Tzhrv1p3m)`UU;782I$O~pbePjy)3 zL^*z~KGo+=L#jagg8jkMS(7eHAGqfUln39kPp&oS4t#+}be@8}QzCcz7`XTE(N$n` zy`a{)gM=IN%L)zI)zxTA#>s-Y!gc-f;}@d-sq8_2I2aLbmhj0=fX-osi)K~ChB0)0 zxbfikpo@Q*i7*pH8?kS_$F<4lZLYadDJ|gClrB8PAjX40UJ}*YnbT0n;m+9LdbPfN zVQy~sp0})QdRn{I-l?qm^lEo<^tSo0AJ;eA>JT4SACxq0C-F33jUAEdJkg{y7&57O zAt#SbT}Z8g>aG5wILOokm4ZujrnHKOGE`IfbtYpZLnkK{+7FA4DKZiU8r?E+Q)?;BO+P zScD2G$QM~T^*VRN?l?M%vquF@$#z7Ts@ttB5rkNL=Q~_y*>=f_zNql53>Y_$7&t8v z`BV!#xXw>yVsF-f2Fn5R^jWsi;T695qkGO}IeehB7XNVbHSrUx74765fI&9)JNIFe zcK!ujS7)|0jo^CRdy0^HxuU!*#xV;3&Pa*R%hcG=Odf&*$z+D=MO&Y;@EpgTT&N^1 zW9l5IasZrz5des4dDd$f32oWrOtzU@`LDSwr|ujAbg>i4-yt1@?-zRX5qjxI+q&U+ z5RBqtBtqaIFxEDYI)zoUogAu0gDJ@Yq;sX>Kwd7??*r0YP4pmZ1QMc(ZSsnuZahiD zC5l>!*wd;8Phy;l6^JN*d9hKvSM3&kw&<$&uXKaycy-E)yD&C-zDB>}UkZ4AlhZHH zlo3c@P?>$6>iB%d5&NIQ{-2-w8E(R$Io#~mDCke$a^UsMLpNa4|L;NhY5DB0+1LGl zq=Bw)d-=Y9V}dpV?mgdxlYzuA13rib{sJ2danN+<%{%m zbv?73VA3Ua3BR&3W>V+TsePw}K(j_wV zy@sI+KR1vhIQ70d-fCIr$k8)`muo}}jNTNp^*f}ZHmm8rE5+4HoIVA2dUw!TBWrNW zy5F(pH}1PR9QyUF2VYuarkM9Z)jn0KJETi{(_+j*5nC*r3CkK=(7`3~wJ=v75#IlL~V*Wvbr zGYwq;+=7@XpzE?=aJzEYU@+BmW#11ZO}Cf;l*~@cml-rzCRD77b-qsmf?F`5v6q{l zE7euy*+PaLtuX(rEP}Hn|2{|=8;T9ZOflx8@c3QQZQN9xM|>SrclDt6I=4klNQ(;^ z&SGU7{%*SC-^pbM{e)&3dF;BcO0iE^*lB7C$Z|`t0OQGYKchy3a9)VMSzR*B5uvYn zt%h6Czj)9zQ-6O33>|5C1Qf8oS-~%ZaP*sSARO|esJIIE2t=#~Bj1%3vPPykYi(=Q z5L8&xcP!fej;heOSfLdppZA4XbKf;_8xAnC22o;)hrw0=wjD{f$JCJUfF#>3F>3F= znX9haCHPHpb2N+{k#o}h)3+0MQls_R{>qXtQpTKL{eK?J!(CWB{`|it{onN-vs31s z^|C9vM^9@v9dZe(QfScL)ZW5r3gm_O&Lr^dte1Z6yHWhLp7D5o2qHv|Bxvllh!3_o{OR?#Zyc zM@nR7t|SP`!~C4qvGjf2eF%ILdGj~DXL-GTv+M|@1I^5`2nRB6{n}7*Y~wi+xqr>? zdwa<4|GE%UZ!An2A;GLNC6*K3J>O(=V_nMJER`UGWM7*^(TQ)H8m)W}Wasex2_3Lx z-=JJSYEmpr32IW}pr5SaL83ZTwM4G~+hwSrODfmOf!ZVKthD5jAiwE)`#l+CqAfO= zo)N;Eh}Z@!8e|(C$0Z3DG$&|})@+6dFE+hzYi|dAv=BLI;LsC3N#~iac+3XGHyxa+ zq`{&&5wpDK;{-kqwhQ-n*_(7jZXWGqIN~S6Sozec+Ul9oONS!f8S-s1GBE<}2}8ta zayCU0xCqB!LEeh#6u|_xxhtA@~!S( z^rg5wv?x&tV?bd9oi*zq4xy&Dk2n1enPT8KLQ2n?nyB zQ%gg!7-&*r5IR0`HW!JF`lQgYDNRp9MT6pSxf``uaNB}tM}LNDQ$QD2_tmVxsQ?rd zLVeG3-8BBh5666luozNYxO===iEg~f##K?7C1cLz{5sLe6oR&qD`RQwrG~#WzWr2q z4SeyAi$%d zA#2!8fi$`hktCF3ci|dyo2c#Xf4UkmGMKb5yLqx2DQn1?{L&AOA}TiwLb)r1ql2Wf z>U6eWwr%7Li}ZB%IsP$1502CKV4GRr&_AS8noO$o2*L*pV|l`kB zMO<8e1_=i{ZVLI5fVOP~+FXER!^6Y+h+BNi4UB{@NEt$L0V2L~r!3khL&C!y|F;c) zFWL$DJ*^syC7cJH!1LSy8iXWcge)Z!|m?h z^q-XKh1{re#9yMGf8;1Oik&z+_r61}=qV;ryObrrd?wC;jc(qv^Yq5-dn&q_uj0z? zgPL*E_V^TG{+wc^OkNp{A61>5`Oi~!wVCZ?9B{zs6!`cXUF7L`XTh4~b-$Z5cF*0b z<1w>d7(aZJ_2+_y=ifQ=3h<`cG`9?TH}(f1tz~#Y#GdQXM@;U)ARM2#?0umnn`YCc zkJKKLnRHdHXNHXN8j|VX6eXj+0_~jx9*%Qw*F5;iR?**X4#oSgFV+K(MyK}zA2;8X z{}&e0m-N8v3;0>mxO^s_Qv*-;QknXlQvj2D>#OB*PskjVpP0dEU3_OHMhTcpKFB-6 z*ZS36KD(?E4}M@{QkB;0kE9UIG;`+IS#PwP`{$uvjk!gu>3~2+n^`&AyP7Ru@bJSmpZJ&)d-80wv)s6tsnDwq&LlofpKw?}a zGi$F#BcO{K{9!diCvrZ?wO3qBC<>uKnqHxDf6#T1vTE@fk4I&;ek<_e(T6DAu0JqP zkk>GEuZ=%y?bH{h^`D) ziwHsFC>#!eDipGBSwlm^ZmCl_N-K+I z>>9~fqtm8TMY5sdhiPeGG&gZaTo42E#t?;KsOioqw5S6~gI%7hQddr;d07lrEGu(z z83`sK^u z@J*gz?-O!a6dns!(=}tq1Mk5XeVpRu-=S!y{L}-Vi1E>*g*KRPQ)Zp(<9BHiO*2@8 zKCh;R10p{iQqY1}i>A^_dOBc~i(w^3r zWRMQ<@^ges_&DW{t=i6__8}|~!=fEKn<;*{R496@*X;b0%68hViA3?%si8<%)h`up z<TA1?3x zUT(Urw_XNc68c?UV*n(A-apJP1)Njnjz)?+)j#slqCI)mEg0KN+dtubt4(+PH8U2* zN4{W1ah*OL&BC|A(qAu7(U)kzS-IAOs$M(%ZmMzI>U(+YT{1E3>FDYSxClY-zs|iI zYkV1O@8d~z^=k0@)2f3Pzi0g z^QTflA?9;6cDKJIXvS@b+BHJ&G-*_=n{`cfnZmgXwxfhMiMIHZhCfh(DQd=`TbVCj$UT_;{M(&vh-?j%fLu_xYQVO&=*J!2pWWV2q!=S zGc`{5V>>N(z|F2-0JdSbb-hr1aRHTtI|ju&zSL;Gt!1f!cxjG1=Toh0q0!aZ$nL?O zenh}Jv`F+f8(bO{mr^`+?;tk$h}YY#0h)-v)y`bl$htjEbE0D#p3T7Df)3PLJ?pSR zTfxgGKP`^z@BhF8@x_V}9t5BG4l&AHN_Vo#K3jN4^kF88 zJ4Xm~Oq1MyWE-e$nNoUet64%>K>!XU7J8T%a!AragLZ9*qKQdH(l?2PAHQ6elfFw- z3wtRkI>`0zA+yD+tP{i$r#gNe$voG2_ZqNqL7iD&*fSy&$jsCe__73DZK730wa*=-#srTF z(I*V034AKx;kw`!2)w)(4)S+~tG(eBY1qw8$%+vE9shBFyEH zNzf3b8$DQRG6u>H*oj1M@l#^dxfdkekd;n=5Vqom*d5MGrZwsHHp9?#(I2Cs-cwP{ zTDXZs(q?LV;H<+>$SsaK4&72&-F5S=Ph5Omq%(`(WL>aK?8gn-Qo*0~fs8DaNM>+| zZa_H39$HFbW%iyM8BhxTA$_Hd9EaD&An!3&4fD=R%Z^8 z!@bEDihnKn*!|By2_e1|4PKsZ6pUX`_y3pn3Q_)Bmt>2P?3k#O<;9mu`3WfO1w#8{ zm7FzI7J7`&h%C@4CfFwyMB?%h_i-BSBZhlB#r`qIU+|6{ijYiko0vVw8DL@s0CAeb zbJO={VRHJQV1zYmLrHDJOjX{Hsgi#=%AB!!ot|t%pAWXHPQj#o1}xVKbI+oE&DXjl z=U~a0?5?2&?_IQSKPSHrhin67tx z)s`WB%B`r$8i9oPV65F?4o{W$=^~zfrElob5;55@B~rPo50hBt=yN5HT!Dn}4;&2L zs5Hv^R?an}|5k!8Y9L13yQ>qNJ$M`O+5Nkdwdcfk=g6avtLQc(^Xo$dA8HBmt0fB3q}8cW7mAJzYoxU!b!4ceRE#JjK+%#PHb%*f#| zj$!?M!IL%&+#610ZPjC|Gch$z-fuQ<)oZQezZ%=nR?5sI;UUyNv+&YFpWLnecZfSQ z2;=nfdRQf0oALWI%Ml;kz+m2qR2ENDRH?jYXdXU7q-A$!l7>C&#`oN&%ML2Se|!G+ zbkFy)Nx{1>l#H+*5rrBUV$-@2@f z*^Xb?HK6W z@VR7&c&F*xAS?(oQF<;OSD2E*9Gz-4<@1;|E7{oSlWZ>Q5Nxr2;}4z(VqT5N#nOV- z+DRcddqzE+zksh~227jfd^vu9;BvCz3^WcCp{=CS7@TFej@O#>yfP!_aI3#iFBvqK zOLu`PePH~NP-Isl)RS(5N3KjB>{Tq8Yw=AIu#XdK8K~ns{e0-YEHBN5O0T@6CWggu zm^ZrG9-cgqBSFV@jVtZ`t8T5+$f`&CH@11lyyx$+kF~2(*<1t6m>iHy%w2|3I%wV$ zS#t*0Wwh%mev(Pahk>V9>S?}+M%nNPO8(Pp6PtoR~E9mY=cp{Kh zn#B2Cx|11pb;c_WPg)Fx^^h96Nim9Ih{qbzjgKiciOcGDrIJSCrZ$T+M{=A$LkrMC z>D-jF4TXTs0~Mj~2No@=1QQxkVB?}~#9deZSmWoqXt=?F$)#@B3m`6T~0 zhL!)z?gquC9|ibhVFq#qFP9$-p;})~Zx5a`a;LVwbxJi}ikalJ9Lk<9pgNxF%Uovs zB75xnC<$oq!cugG4u7gO<$RL9%{ZjL0}XvXr6rxrk}Egd?wa{Mj}vaw?y}wIMG}>o zT5^_~n>%&i9()!eE+FLlzW1M?p{w-nc2(6R(@u{7JyZk)gc|LxfVxPvEWZ(S@n0H4 z0FzbH;@g5}U|zO%^Fx*9D%{+ruxuQ7^aJ;){f)c11(wefUE`*;=z)z4G|@N- zs)C6$3hCLd z7~RY0!uD0n-gt&`w|h8wG*Aiqs~10ivc@4l?F8dEFkGHqPW@uNkdv_?jT!n%s|Zz_ zugusHeG?_`JccCEzl#i)ax}zOiHL3&)hReRC{q0GTYYfZZ*0}C@$}{Y9Ya-PEEl< zO@W36OsJ5o!_#&Pc1K?fQs85!P|3}q+FdK-ugCJNfpMWe_xc?_u|PxwYCo(r9k|DP zLxAHQ!eJ8l!Ne?kC34pDx*U1oMus1bdHN&l8NHhFE

gqp#Rv5scd0e<3{P-2i z2DZBmkarLdQK>@te^I;jUq%+_H_y=>u#3@wjRV%8d}cxs?>fMK;tvn$X^ep zdWwca#{(6Tm!bH1wg3iOoe7hnQM0}2#wAll)lDz6-q|2?Sb+H`a8r36l2dLzc5tzf z>Xv6>Wc0r5@=@5DksNY$6^%i`PB7Wrys*)(0(sf9F09(KdJ%Tf9e|y=r&+i^!;TkA zSnvV*7Ts3M^O>KpPb#-#IuO zJdVrG1iyj8mzYT>JAAL#mkv)=`##?KZ{i<-dm(RcA&=v~S1d`yUmy4RLr#=O7xo@r zawW?tV|7>f&+fVq#6Ph~PE2PJ@Hz-t=pJm=rp^D*I=6M65W<=eA@u-g-9$Ep|J5WT zTM9ClK;kzndI23uR5`YN=pT9X;;#32OX(Qf)5comFKcmml+bH^v;S+)FqraHKPgeL zF>ys{GD>5FQ2cR61crUfa7!q@q$E9hX*6_N$wll%wVRLcyowe z+4zdjBA0RANIs6Kl}X<6r|_nkhplidjEid)mYMBo4Q5Rzuwt3v)2b?!6cHXaHswJU zwo3U!B>t|m4is(B^l=Vqiu&3Hn$QwEkeZSkE1LPzsCBs2g+9e>9dLUwqQP9S(IphR zOvf+Ia2ME3HX5wzw3yYJt@}W*iQdc7V68iUVXg}RoF2TApm_nEyAxz(GuB!guW#Ts|?pC`cqQTCE<;DS#!nQM^?4L z%lWS9(NiXOLO_+n|5!^P3RJ(8U(LgUa9n`ucQ2dh(t3pKY$1=oWy?F=F~y5d`?Njr z1o>5qM7+)_a^4!j~wIhnXS!M>8RVo7+LJ13-1a5~G6kuj>tM zM(;QjUYCn^7WAO#we>O@Xb#|Tem--HW%djS$5iY@HhVddTfgO3A~S$13YSgfj4~H@ zJn^soV2aR@{_DF!-gdhjv6u532-f}%c@9?<3we~?_PdhOheu1*>APhS0o1ApPOzi92s} zvyP6yz#z99;gCm!kFAh<+HfZs%FrnBS8)3~$i0cJ9cY>`!{025%|`+ViCmkw>8Oy^|Z*CL%Un&w+1pd+;>lbDgz5|W2>WYK7F_y9#8U> zt>;2CM@7Z@j2zI}Q{JSlY`8F1pAxC>u&p3}y7He9vbE1;Zr^2re2uM64jVEKoqYy0 z8mYgRGdsl)8AiCfqjF;`ey+cj2an zZ}0rv$_q0-vJNBa@4tc9@`2LM?nS7tQcQ?{WGo}T*3v5Ve#L`Ia9?dwUo)e!j>n`d z)t7>bs-xppi})0UJxcfO(Dlb#Z5v-JUm2k}m*G-%1QJkRh%;xgi4%l*h)lTJ#*6B# z6+Q`7<_?_lMj;&PSw5gCTSRguwC8NrVna~mk|&|P_e$i@)5|TVLRRn%9na$u3KlK< z5hM3C!q$~PA#})`RIq43f?t3u6k5F}BPADrlc045^_HoCWo?IV&&VI{zfg;}ifoBp zN}O;-WV<{VBX;vi`D|U^*4vRfE#_Cp;Gz|^!6`E&hPZR>;3+=WZm4`zK!vSa0skh~ z5jXjCfGyaK=?b7j`n!yWV>EZ!nV2A2r`X8J1+gO_rH;AC?t4^2#?}ubsfQwqa~Y&Q{e!Oy=sJ!2_h`*mhZ%p0Y-Aqp6MNLi}wtNtB!Nt9N;0^Q-&9|;}-lr@FzvnF^ z8V4Bt*J2Wq{V$^nTg$|IRT3cTV&#gH+Kjnqsd<%6->jIf{`$q<72f;;Ce(P`cH;eS zJB9f7tLc3ov5uFYxj{F~{nyV^B)=TN1y0~R6SDSYlV@2Wm*AuI(-AiQA_^spJ3DlW zY7|X&ZI)MtzSWa+GFH)$QSUB1pC{=egd<1#5I1nK2S25JjPq7mg$hDyixJCK;EiH- zPsqnsD*X{V8=KhsU_~;y=o4uB<9*QnaYERo7GpUY;cP#(M4B~zl-eG(EUJ5m6*q-M zY$=WuK)#*e5ec`F`*D=T`{R%kF)y#io%dH z!$J&e!VNtp6_pj!;G?VNhp`%mc^RnOT-l3ih;i2hblj97geqadFl;k3T?Wfkq!+r; zi3=VrnMoRxeIKXKybO7KU3kNLh_45^0RUL8?5j$PiaX*E#VsDOvBp8O0 zSta(eHK*?Prk*;{b4(Ke11DNMBB2o<*knRImYWszJ&d8Oo$0ayFuctlJ_7+UL5=n& z07Vnl*o>Wd_c%prX}69(pBKE%wEc~mr7kEQvrUV<`OrUbuS}n#2shiva$r&Tqe~X` zik<33@V^rAL2V)<@_6r-3ar~fOd$7txPDSR*mZ$OG0r?Q}zCpBzqlN!Gsz8uv9 zSNETm#+TJ7OQ~p{!6{b4DJ1XkqVS@CZ{<*%BAe-sT6(i;hwD1c3=&p+p(g$Y)Aq1d ziD(TON>)|Uj9=RpG2yG_%cLC07)+igB&-RBSV^xemg%Adv9p0GyVKxRF1c(eQ@8|b z%4jcGV@bNBu~|0XY$~ATO5l$}WXWuzASbttrv<< z2+YMkl!p(*3Qqm}Gxs7xLbrYj)SQWP-@&=rZ6Hmsqw>QdC0?ToD%~Ou4qX;U(MO<5 z^E_iV%{w zg1dr)`@}vj0zNPYwgVv^ZU`U#TR8KXHYaGgcF`DB#*8mjO@no5Sh^Kh(C*J@7`qnI z@_e{qvz}?#ahWp!T(XScv~w`7NM(d$7=pef+)th$^%>)bO+rsb$G})mdoYD~OV@7r zw>v)ep8hUW%xt~vlxUm|`uhb2db)eM9!*~?SrE0>t|)5aG%pT%7roh+p~TXdXRwL~ zehBwJfG&Gqz;DgEV37uU#|56g`h{KUq|9HWA$RGJ%;KfJ+a0L=f2!|mC}yOgqyBnz zlWU;6e><<^PfxxVPT{!($!ruR{od{ZMr`|~fp149Z|4gbV;2Hx(6;cIYI`{|b{Bhl z3r7phmxZWaf%oSNGh#utm(H#sYtF{|dvgo2>?VOH2cz*N`@;~8=o?#9PH?M8pSTR9 zBTx%m&oWTEoU=xGw?oLCN)E=_BBqt{)$`57=Vna7T=;Cl2L&vH!Ii970J!E>p0@@A zx*dv-tOKAWU0Q$!M&Ln%Aw}4V{Y3#g1;c*-4zZ39_YS?qzl%ZM)(jh*l2rUoLyKA2 z22v09=H=u^1ls@Yxu$@ySZAMmouBwk7 zMcEDqe@9W3B-}0;tTUVrHVjF3K(&@!?sYkfqq!Fi?r6#>mJTnEwcf5ARpMWNZb4Vq z4v6B#76;iVRZT_moD0(*`d(fgOyB0cyL&rq0kn?IdVWNDXRe+*F%pCt962Qc|G02l z2NKY!>pG-EkqITab<3>@7}V7mXxJh1+l7|D6=N@0Fi!N83eFUralw)}mR zlM-PVAqk&sW?8;T`BTcxhr2ccJj2QC2lF6uo)` zrA7;@;Ho<_gScGMm8Pt$=i}fn2&FUd5%vKmE3j_vBli!agoQhn_TA^HX^hhF3oR`5LNHRRN&`*?3gV}1y| z;?BqN8Fe3hr8O6H4&d)zo7%4Jfy0;(CM8ceHW6_BYPJE2k)-)z^*wYJL4(O3$+8~? z;E2a~8Lo10Wd<)RZEzl-zY0=h96^2b@w)+U{E(o5iW=)cggeY`={#hb!0j87e%a&g7H7xA$L{(b6*8*1&u6ktI_;QhdC$%UZT5 z-x->|g;Vr`_Fz7yYErwKN&a(Fha%+8yylP7*E235(ckvGL?X8Q&D6gg@-U7%nnKQA z!{hn;J~B-7Yd2DF;xC0*XRZdtA-NsL{jUM0{!ife;qljDjNs=tioRT&;0xUlr=8%D z79+M_VjqE-nv4oSSC<@RDao(F$U>0nRFu1ENv5(9#>~2w9C!3+l$HpUoUB0xWDlGS zu{UBO5k!c3UDZV*K@Iawu1QSJPQ7Y;Xo%VwDg2!G#qkoovolA3fk?km$Bhs1&x09K z#>jE)nUF%-X4hyJE}Uk%uUeoal%jq%yLc&o|J&|fv0+;MjfK4mp-wo@?$_+7G~z5? zcbR{vLui$y>JJ$jS6l5it0>Zn)KyD&G!l6BHSbnJZ#N1eVu2HzXO;xUl-_e+O#;=#5-I5 zeRM;SUhz|4wD}RS+d`cDpdeOekey0^>EYm%c1#tUQ4CN43^8&_5NX9_Yeb&Avg>qU zHg;-w!=jbrl%-LZ!GA7?y-WK;TBbR34#Te%j#|_bBwQ}+V<3gy zoJyCK-RyHUCZS?6y_l)ORg)>_`&DlQlpr)d-E1JyvZN z!`r}ERz>r0_5dz~{xE1RnfqWlN}c=*rg4U~Fo@ckV(Fh4TPjf?X^GyvGy$*n|KS-U zYr$e8H|rhz`13s0d7+v4UVf|{$x^Vj9I1{L?_H0DV>H8cwL4q|4d(%jk8FL7E1VN6v(Hr(~vqO;vo z^&d4Pdiiito3q7xw}Wfp;=%jECDqSM>~BHbqP-tGbI}wc{Dg_pIU{A&D*O&L2mvnv zP}%tK536;3C@GujwMNuOWYa+Pdcw;D31C7NBn%4XqeBVF2cV(7owJkW&rX09);Y1J zdAc1iu-G>GscmW&xe+IosgXqKG)X@Ov5bsJ=m^F{TWKhE!~>f*YtXTd%qtOVlQfxv zjDqYJlt_@fI+~q8_3s;|`0vezoYu7AL@{}J*hsWK6@%s2+qKc*<^VR=hEJ4U(L+F^ zy6`YF21&}#SlsN6!+uQp>E*4~7DJdfB{vxRbNnM zze7UlgOtMA4H&16QR4!`fgW>h`9Aq=4lJt66<*9Z`9KFb;o9i5JgMj9nZ0$%{Cq?; zm~KNi+=XN4NJ6y+D>lTajy z2X%QL8H_8Y0X=|@?(69I5ItQ?fIdhPl`otVmbw%5Dt@p~BN}b$zN$?n=T8xMw|cPQq-cQ-C2jgTn_PSn(bX90+>m5QFXjIYw13 z+bY6fhnH$vCt+`ZUP*wav25fY`xHAAmNqBrQ_k<@fao*GyLU5W9yt6(>!MEqg`yk> zYDK6=2quu*5TM>9!%w5-N0&|Sj+Wb%T(L;1=F;QY{80r1u}hsB|Fp+qFk@RJ>0>!I zFu(S@K0%QRJQ`O#O1&wWyVfmyiR4z{oyfwCru1Y)=o~;*Ys2V5dG*Y-O89-Bj0pDq2Ty z_4Vz5l%Dqn-$fD>2#XrCWKO<3P(U6KzuWI-!b)UqyKqHY8-vMwTw8_O%Q%sK;o3^1 zP?3b0_*?|Ho6f@)|GxI@jTd`nS38W#oc+VLZ^?RgYWKIxByZA=mr$)%H;J zeZ27PugmMud0ji7s%kEK$R2SL`7%b0h+LI}<);n<7k6GBU0FpFGu95pg3WH|pZJ}} z4PxxS>EoGo=h)_2D^C?_q*2~?U&Nsr>^ItsbM_#MJMdy-`}v^e*H%w(IRC}rNwX}Z zz44p^QhqSB-n6`J))9t(wT!0#eSt&>5B;$C9)S6%&g@xHJxG}c22onZY<)8c6Zr{W=y#w zYKJ1`M29NmC!{%|DJHpu%9P4=_6qJJS4Qv}O}!4)TOCh~%_3XY3$Zi6%nY^oI&o2C zn2${-LKv1vIvrXHYu1qYnPVkm$^w*qc3N7ig10l+p(dlfF!-8N;${aoR4%oKc`Rgc z$OOqTXTtjNS&`3Oo0k;;8yeA`B4D(%nYT)WJsN-YU20rjJ2H=w=6tjh8%Bz2Sbud_ zg>I;t_RR9JX~9$`5;mzTQ@Jq9cxtOU)s@ts-840CJ_ zK&ryhRNb1bo!7##yLF8WJKu7aY-?FI3bUr|K0WO`7_W{EB4*cCuB$-_elN{jxneLsvZ+@}6+=J@8G6?0*}YR$Ok>tx}}`LC^B%d)hZ znl?M3)}`u%f<(6k**x8E^A?Q;7}1v0Jj)^^EZwvopmgrFmP@j?gJQc@!=;d?m+jH` z4pBe5Yh(EDOk7}OR*L>@kkD#~r?IVbS|5e@mYyUi#EMEGc^w;N4Jeo)TNx5(o~CLsp3)@6|fCGfpqWE{rxKr ziT`HxR+o2vG#P2Qk?_w-LH$^!s2_-C-K!EtMnT+1Z#hCs%?lb8b7n>oYMk;g z-ZS+PN+p|&X5Pl(n-s<|u3cq+PT={2nn9+oiMCieS+ByQxE; zzwwIb$8fAN9V0$I@8?gb&iI+mC1ii<_`eZH$PavxDs~={g5^?WLFZ*hXHRS5$ZGj# zi_rQ-zo{w*UwdGHMGg_2Dh$?2-H&n6uJmEx%R#O4`07*-6l?Tg0=6U~I-jQW)!u$6 z?*t&b_=I}U1E5B%)2p#e;8Z=h3PkMC%Pc;Os)%o6Ze!}uJ1b|dLI8gal|sD7M}^-g zQqr*I@V2tB^o#PZfA*m#iX*sao_tq?(d!8IRXFYLcHPRQ0cqG}3S{MB7Hm)X_} z#Z;7^DAQRlMCt38*)a-w_H=`63L6E)2uuu|GUON7pQA=#p#~%>+t}HiEm8Qr5Fc@~{9w4O zDpcBCPTtqFJZ1WdTiC;@>n0N|E6L5puCK4x}KXXjV#$N&Ucbu>x>ZiK=L+)q@o zggArQY?@`61?(089|Cg^9a|SZ9t?*ZXZXsH%qIw_XTO+lS|f$$hqv)bt~%=nP#GS& zd${_4APhs(5~+H~E7zwOaOxsp)APGWGUhE#5slHX%-_)!9s8>RGMEPUxk7VOF~iUf zoktfzO2R12g#kNVu(kH6=<*S8X7lsVlvMmaFp65zw>pwgX6&Phh%j`qVtQWbIWL|R zJGAqKjVv5HxU_h?{?;&IS@}@>oP6B6QuLuX2|H%I%3tyW^5q!1>{_K(U{N#+3D1?r z+tlSJ;8{bzby&CqWEtTa&lR%tuo#5lkp($pVz9e&JAJBIU?bD}Fd~5Fkf_?`<2kpr z-z1-<(LaS5A>xXD2D?eYyHi_m#AJ~!xZzn-+~`|}3bN~*73(=qtQ7~fHI!wvX28%$ z5F&FtC#MU%Ay0lIt(7^Oiic|Az(obWS1(kr^avExjp)V@z0Hq|xK?J{i+I|pYh!v+ znQ(iRw{g3?DW4gw&K>(S=N8s2whnt;{4du3=z+UQ{ujI2)hW>^33h-Pe!|_(7)b;| z3j9W?pS&2;?{Z7b%rh>FP!*lt?*{alu+SdZP<#C$NzEkw_aF( z@9Fe=>n#+~tK-KAdEF`ue&}P%tWbsccXUGvQ1`rTf<*oAos)96vnlI^z8BKFs$E9HNO_dPuI$SKHHwPonPtvk|m*6BzI^ziw< zx_;U@czqmSvtZJsv69f9y1O2I@#o6B#K5pG%jkCY@C*!0M3VArgz5p>K-r}`sR?ez zW!vd0(5Noq_U5bY4^1$RZWzVEH;XXckQQJ^&meA@di9ziW!WFwPO}ZAMEsHd0)wWF z^0Ne5Wv&>Lhca$L3?6!~h!~yMi=Q=o;`hw<>c-1mxZ|kWpI9sP3e*lnCY-a)$uSgy zukGM2UTCIb!9)#X3Awx)`IXw-HlhR?1caH$Dh20q>(3^I#0DGp;= zS8cZqz9XA>CVA15I3h%(p%J87C(hg6ykZt)COB%K)@FVlPNHm;zOw><9%+-l+qce~ zZkf=RQT&#l>&I>Mwn(S9&FfBn^G5qGAA15-cB4*mPHU3n znx|XLc|ubtg$dZ3X=rLML`s>R`ZK8SsW^gz;{sR`jYFU4vO3`1!v zGj@I={;3Oh*0ze{Y=3xuAmu8B+s$kJjid#aj*8l)H}l>2Gb0(gng`9^2$GbbG|U_s zaOj+^PZ~MO8_W_hRL%iuJ$RFzf%VdY4UJq>pqa1?v%%-@fCJ2m#v*<-%70n@Vv{tA zdJ3j-v?>51#|RL`Ai}#5686%JLH%p--eI!uiO*Q#yXWG^YP(Q5EJO`gYSLgA|Pz^U)X*m3{VU(5P3ex6l{YkDu~0$zk*Vl(vlou zDMv3JIS6vo=DdoY8w zWadG+sWTxUBI7?RW9Wxn)--({RVp`gqoYfaxP(oOhr*(=c=&>=X43^LefJaCS3O?= zS;JhM8v)>_qhVDyfA@LMva|Keo~KMm^dvaY<^F0gI`!nhEJWzn>62sNXWdr)X?ZDl zZR!1MPoYl#Hzug}dG^AB{B#Y4Ig0+5)Q7Ftw#A$HQIcb|*`Ox^lL_sdgsAA>H;@iC zKQZN+`d z9!yNjWS=5`4=<=zc5+Cd7kl<~wCM9LAOTzJ=WPiGzp@hBSJ_jcr|PmpA1K+&P-4YG zf-u|$#^EU4&p3^sG!%eRi#0l^M@G`Ud7aSq0NA}Wy$C4ovpcfe6>GWFUVKz~fEBUs z!rZ_wBf;6?GEaMm=OmgW?gs8B=785(YiCr&pM0w&i;FYwr61UwHKF+kzSTwl^#bTn zi0HlU1pKx+%H986aUp$nV3$=rapuN5V|j~CjF1JS#r^y3O)|qFh(zoT=RHB%|2#1(GQ5c0A1(Y^8M>I4DYW|Zb!=Ve?mvf!6) zpNoD!HM2TehoaR>{CA`p0Kc?lF#(U+)J=fwkj^P68G8mio5u>*QY^ufS4IuT!$Tm% z{KZfuD9sN|WnHe<9aHB!N3G8lU(*FZPVe;v(50%WEQ!W`FEv4<&!XZqddXPT&}#BD zNQog)h_%hOvqceL)YP-2jL}KGmj&_CZ`MUYVxV5h-%|oeT#wS7TS0UY0ps!nD#-)Ul7hM&lsF zkDu>xX2UH^{02GIb7yol{1^D&rzZ@_$-I@eG)wZ@{+jmH;hk5VZAD+kyv$2*^WHYx zHONbc{u$cE^@i#&2(x5nD5`{>ro2;3!{#)*V#Oi14`!r^Y>$&ftkG>rh5J4>{uB1R z?%rndNip~c<#8`S_Y&t?Jm9I_#i^jbsn5SdNWd1oRGjpN{2yxnxx=P^)AK4VCgRO% z$mkaK!5l2UpW>E#4lt2w^Wn}ISv$s8-No>%U45j{FyTC%`0m50ek_PmrKD+YDkh8Y z1tI$9TcXVHO#gdle0+T2>v8_*8^ToczRy;$tE+&qsc6=8dFnL;`c=nVJ2;N=Bwfqb zJR#cAobTgJp`Tahx`^*b1;$oie~<0^gG&!>W&O-Qc4tSCY$dv3Hwz2Ylmr!7gQc6Z zR7vAu{E*k)g?MklqDAA?UEZgm5dS-e{s%Q-L-nwhy69SUlh~u`k~Gs z>JqqWl{wyvXd6|6$#^dtC>8eUw&I^!H(Mur04bOx%$i}*!h&y=CR~LLXb572X-sQo zJI+Lc^;*rx@Tlj z2rPMjB%1DmVR@!OAXM0l#os2NFeW=EH6La@p;qVVJvy}5rC3l^eO5w`Z@bJ&D;P}M zdjsawq7Zj{s|Ft41?rXMkzDc!LRu8|0IqT;C8Gylq`qb}*=5M`5uz_th7E&^(5%!d z2lto}HL1S1B~Fq@r1|od#Y;B}j#>%T+FAwr`v?96SQtU4m+o@N7i-D8X~PebT&}AO ziV$m8O?+w_9fvOy&bln?kt)yoa|pY$lf%x&SKilmTp)G=Y*jJ9Xsy=d9dLBtX*om{ zP|V6&3~(dvMNo~83I+mcSX9m{(+6PSX*-IuxDn?G5N!{VkXULDSiZEV|z6hqw2`$iKI4s14^bP zup(*7sPk$n{CJlU5Um>M9e``l5ULD|h+JBNj;;(})F0f%z0exCMwN_UDPB+0LJ0#6 zhpu)HORY|g3kZBWoRBh803P$8y8pmxpNEKhvV>U)N+n*O@>WOW{KbFCYH;AoQQ>Q+ z9_P^t4904FAnls_NYfppMYWFb`d&zM>+E`ao1aDTGj-Tzjy~HU_k!Y{EF-ehNp5@mAq3)==Zf?tb>U$=O#C^fcP$t4p(mvfj zf$TH_?+i|z+JAS{Q#!PZ{HZV~GYXi<=vtHWhrg@8Y7DQt$AK2xL%56MWJW|EI%Z^Z zK2Z#%mT%#I+*dtug4RwNm&5+}aQqse@&-{>G2e9H&`d6bDPq#fj(3bBf0i<1Z$b zC}Y>@m>apgtLaI1(S8ks7#33`vl|+}fOzvgA~dgzJR`n>Pnbcc>#zPvt)l$ceq0QV zy4q%yM>L&^idvC2bJ?E;Y$}e#@~*Dgo07X* zmm{1eoKDFKohKSVRY3wXjE?*S_)#jsTJnN)nuWqN>9{-i!z!_{u$Y#kwpPO1Hknke z#NH9VcO%md5RHMSIpD*TKt@Z-5(TAOVK|M=@For6 zm{>@5tC*Tca8h6Xe*|Q`R2dS@5BaFvL>> z0b&>3({*b?$Wi=1LixwwgyEo9a)XXuG0ezc`xe&5Gk(h6e>iqhATebdU-oh+hBDZe zmlRcsRaV#wMCV>~X()gGROv_&oQGnJ7^uV?PM@)iUNj%%?~VG7-(fy~{E&$Z?msz{ z>UcP3gZ4?jEI?IBlKrg;uL_Al{m-Nh3d>A31w$LpUC3dM+lxj-2~-2W>~rZ|o#yYg zN}(d+Gg#9n`=Uz#h%xE$!R8X`!z-!xU%4YXn;V2%=)E8A((!GG%#%_Xs%VPmQf=Ny zzAps2xS;n3zpc}oyhRA}O#xaB>M|xv_7_~44yU-YhMK$Ic^DmX*6gNB~W|^(P*ZWmy~Jl{O;0(n#ux>V>w2 z``#Dvj`u1odlCPBhmDkj&7QCJn@fq>@!7x2jfrGl@(^HnsHm8u*`^0$SIDMJZ&O2Bi-3v8Lrp%nt7wm6%+%*Oxx=0KFmxL-TNivZ)wg50)R<$BwA6+wh_`r~YD$p_euADM87`ZO->hdc#$e@1#S) zRhIad*b54~NJq%~Ud27&CQPuU+2XH7D;KSgMU+)^s755TCRfsV9gz@y`M920up2y~ zwl*&zzZ>tTKX^whd9-o=2xZ1NB*x8M#kxDxZmt;`8(;jJ=g!!t+4{+(tU@^%(X0s{ zsH^1dV_G<_M3MG!rG+?_pp9Jk=la5{Og940#@H#7RBBKgj-LRitA zN>s7gH}5*bIVS`!Njvpr1UTAxiqjeLoDZzqwViHQu3TEyIbAv5$ zXW;v(Fk#dn3lNCl2-J0wlQQMF^ar70z4A^-7tsiKJOSv89W7Cq9k~V;e=P2{yi^SI zgVyGbKPFf-i677w|6`R~4ip*gNbUL`u^h74CC3d%aIq-Xn{=OthMoRW>?jRwKKMmy zNJtq%jZYscqB;3Y%!QH|H9Y59`SKF2i|!2Sc|Sk)Z8ZqmpV<--6ciRVc3jS_(Y-%< zxp{KrB1Lsi*HpmzAVsy$NUOL>#` z>CY$EPk426Eo4l*pKEtr*_MhH0DscZdVjN4z8=DBQ)7+4jqfU|k?esca?yVAkE9V0 zaJT^WOP3R5l(c}KAY*l+`VP6>@}r$}`g094o0>HMA8CpwqOq9R9W@>^9l`@uBn?Pm zyLim0P)g>YJaJ)H(^SEy#29D^jd^`>)jfkkwo%;liN)DmBtv`P9D}B_yNz5C<0d|* z@&XniI}7D#m31)XDBB6Gl+#S-0=_1U*lCfZKo`jUAyW$f(W<=CrY*|r-tpC3-P7#n z3kO>OlB!B(>}MX?VWA_19-`|1!_-?pL=|>z+e3#)cXvq--Q6HHgfvnj4Bg!+9Rov% zATgvMEz&&$A|>4*E#2^OzxVgN@AJ$43-;RAzScU|ad5}vb~HNi@$5L^F8bt0K;q44 za5?|YlK(2BcL!VmQh%-eGSZL=@R9Bq5xX|33(HqZ?Zx1XhZhv+u?oS_72Z6Wdp_7U zwj0Yxci!wh&iIMvYhuh49?^_@AkJ?~Z$6lRiZejmEoK))_vpS>1-#-fmYHMl5$}O} zBD_bPNLdJb!SwDNFgM2Z<~QInFpkH0R01SFAF|AlJ57y4$N;)X$Authl$G-l3H%Ut z4Lwf}rf&G_0-`ki_yEO--1Kl0O!P)Q>~FuC8}Kz zj$$Kn3GrVyXwswb_cVV5>TY#n*#<8yRzv!xr|(gj*rPXbjFO8vTWa z0Kr|H;QXelPn46fZ01w`9L7Gv>CIl;VM2Tyvi5vdq&s!yqNl3`w?^;UeI^H9@+}S= z-qtzROaG0#JlylRDslXfLlXAB=4)~GX6-J(*>?h5erKXTd^f<2ihSXebCt|(k3LWO zmdJ*LzY%R``2D6$@SDJYKanStq>h&#^bWD3tDeVjJe4iEcbpc+>=nUI)PbV=x*D3M zY;$&BQjcl6;F`QeOZTTw61e}#;S+zJOSW9KJUXhm+7MOnlmCO5mTn+6=j2KoROFTa zR-YR6Q0{aCaj)?E2mPW#V9!$wK<uFeQ#dqZ(*8KRu5nEmKcjo(p6S z0`r}rzLa^#MVgp60}Z_?m!^HV4IFaqJa_bPy95@6tS_wS#O-ccv(jeuZ1K_I z*U}uX=HVpIY5^}*E~hd)oquf+h@&;*6;Bu$n+wtaT;>kE3rt9$Gn)*a@3gX1NQ%>J zEj&h#Rk_sqX}BWBh2==b z!?AVA{l2J^aQ%(!w8e$eOpmqSKZ($7=aVcuz6-r0;+0%9b?fz`Z*es@GOMWWP07{g zG)(YODo`~Zp6+zqx@OdZ=REoz8Im;}>fkF{i zgCP3D07V>_M}nw@`%yuCvf^;O^;TG#xL6NS21f#^93vla4fj)oJd#9(r2^PR{euLOXv_VG}AV-fWk)D1z#NZ|bP!la=3e!Xo z0?BuX>z`9abK{sww5Hz=6F;5_+Nl>tliWlS#Q-tx| zXFp&nD0a16;`V@TJr@@zFboK8qM`Q5c+zInho7|HZXIbbM| zPU^?yT2sbc?#=O}d7`S0Gi7do$O{OF_9{zMm^Ilkqi;#-E3q}Tki(ZTbmcG7#T77k zZh)UY01*f_QkNpVV|q*oU^ZCDTmAlrbe|-M#|+z6QILAtV(z6Aes@U~7P|iG1r>f! zJN2^d{*rKm&fFbXhBnSS4{r86Jq10x2~&K+!@Kqz=MtpGjW$*L@ND(GW<}S%D}C+x z_089hMo`4a3*gw}yu9oAHQ;FEcII&&K~^jI{2TEY*=JqgYA)fY8-><&LDfQOH8Ved zJOBJpb5h*!#+vE#ia6U@r4hTfcldq|JVvPm+K@`oOmwSdEym z$mlAosw&gXF4KwNEMUr*sHafHl$WIY325dwvBE0LpDo}_ZH)d**k}c%y7ssZ@NYeF zr?E32oYG_y&#O3ityJUd- zW6}6!`;gs82#>9kWGGmJTtq-&&ScITpS+JKlgr{9aCqG3)M_R)QCKrMvsp!Ngg#Tb zpWvf4x0sht-tcZ8W-`mfAB}0=CFH=!r~NjkO6h*BX5012sLrXx;;e~^XxpdBi8kma zxo1|x_Nu<!IgEdmQWUMq$ZM)OO8ZjvSt%fPxtPqlCFHtnS!*I43 z97xzOx=UXegDI(EZn|po^db0Xy9vmAJ|)1;ZYQ|VLGiFD8zXS2?L#l0vjS_!yn`0( z%zhOa7jg7;Ql95x*ydeVT!DBdcU0` z7%`^RBqKL7z7k%LxI<)(Q_~64%1d$irgQ0Y&$BK?!&Akl^<4WEeHcti=T>Wk%gw5>@!y0w)&lavXGa3JmhG=w_#b`sf%a08}fckfA zp!==d$E&ARWEouXIqCKncI3n9TVbE0{|ls}WAlFn0HP6$)n}ev{G<=1sjaHu!krPX<+wc0l?gDCJRk37Hx%?@QQ!jp=e7NrN&kODI1*taQ z*eXJTZ@XTmVy)H8YuVP%y@^CXSse5SH*ddI>7Y0ftkC1rk@tYEyB#CT73tQwl|a9z zUyYTc9EF6L7czYFDqYf^fyQSN`hV z3Sa4V4Cl!D_8Em8M_tZc}45(PW6qL%u$ccg(BVN)Hs(BW{|IVg%Uv_67PE}T)RvJ&FpT~V^ zyB;cIhc@jg`HNCcsA;szGE6`;Df{>3DxvpZ?~O#pTpykmCt#%9%EEK)G-^^Nn${#z zHFiFZk{#mlAbcB!+0q?zDpgXb&(!4zq51MJQG?CB!+#a@YXbP4txwoeH9`9pkPX3n zCj9+@(WPZC+vCkN5pNjhCx#+MWHEot9s%CMsIxhb;&3FCd+xDXJFRU@2uf|6mtf!? zS4L4#PCp~78}4-jq>^g;Rd`%3hbr^$+7qoNKlIpbSROI40{l(qhN>9~U(-TfX{UV0 z)9+;zs>m9Pj=llpmyc>DT+pOrdOFvY)9|SMd+UCC?fu`)?XedN%*Foc`ebQ>nb9`O znXZ0m`YOuQXU-0jOnjRz3y|V(&8CMvRQK+Jj5K8A6B29(phx0hFNkDm1g@e*QgU4b zu9F9X#aG_Zv4dYbRi>>O8O`mC5-TVn*bNzTpI&oXXkt+_(a~yKtu$A5R1OYlL0t26 zZEQfMb&Eb3V4jYF?W@t2%dME`1M$LTne{)=?{eJ?7aSD%SpC`7+GU1lqw4SLDjny( z4uGNuG?iqjmxyuGU~{PKNWto;iUfR`h;(tQEv+QwEm>ErV>tbnAeY>B)~^QG=p04@ zdE#*tTZ%l#ZdwIpdP8ccDEe+7k1)kA{{jO4m8PACp|5TRH}uHBqzVcFAHpztVL3H8%!+G6p)LI_0>nT zTFiyhd@vd}|6r<)*a;BI>QP-k6W@G;6j4(?+Dxo0Or+FLM?ZW1FW7U)#TIu&M|oyY zMWddUgomM8%RgMn6z7=HG}5ufo`-^#JFW4gTio`n%Sz`J&NA+>%3l`f)7kGaN%VS_ zJ?&pR+}+{wfXnE|AHAcu1P<#O_`a9?@H>SN?;6CLdtk}EE-?2uf*=`R4Bk=!I^CcC zy;N{?@Z~x$%G2!_FHK#_&Ou*wQWg&D@(u<@Pv6LhfQT5zZh~D^>0b-C;Iy`myRiM< zHQCWqR=;?c2x9=R<8C*V~Lcapnn(p0a6q%9p=i|sgYKS8H`30(puP`OEqTv;#yAp0hk!Yr=h9az4>_u zne+LovE7s4f1N2m&kvVpFlN00KOdrFecz_!l}UF53eX5K3=(9pk`JDLvwBlE>`bMC z(K!G30VpHMdOiRB+s``9<@lwh#egEK?Ab?;Ds!jM`$#tLXnO(w?VdLXTLH?Ml1XNf z`qQx3%`@#!;7gf5^#bv#nAoJ~msr7;L~Tr82%!|V{0muyd7{3Dsov|8Xlao#S>J`Jv=R<^B@XgrRE?b(!rhGSFfwI{3n^ z6j^awWdSX=#}-Rkln}mxSo^~&JJV|-Y;H-ha8=nDGAC8*QHs`SF;(x@v?zM3nyQ;0 z=3G1q+9I1E z`kAETM#`a@Fu5pgK+bi26~O~~1t5DUftKC+5u9r;3H z!rAoyWC1?#YkjlxHZZnA_4HBj;KS-S6T`$3qi4?3<0-a^fRPsDSffVj#dx=UUFQhP z07jx>wPnbT=(yW~`vFPhV(EWzUh&Nhr^SEwWWxMbZ`aOAn+BjDsoMXaeRE#I>dK#iiIREOZ{ovWZia{6jYF?I`6=!*i}r3?LZOn*hBw-D z0fIyA)8AQO)47FRELqTSCW(WgaDoXz-x|j}{T_~RgS?lIjgKd9y?bk$?w%m?2KB`v z!){t&SDe7npEcX@;YU06bQAkNvTs~euOHUWMF5iGp?<(lF*@^y^^rxo&WER6-k+-d zc)YajWD;`8FeEE`Ql58aJpR<=rfun;8VPe!Og_b#kVg^>FXO;JhpV8+R#A4K{C%JF zhp-_wQeDzX<&e`cKca7(}^Wd z*OkoEiP7rA7TtQ}>-I@o0hxSrOYXA9P5qv+lE_B%fPi17`EQjSst}E1VELRWQbYjD zBC|`o7N-ysB!cL1#>U!F zR-lt_Ug1ksA_EFd_3)zcviNI5g}6UOs~CwaOgmC~YBc6nvI=Q+=4GX%H&{-{IhTPA zXR_ReKWf4eCWzL!S{^u;O|Hd+&SiQ#<#%nMFUS*{Ayuajkt#9vsvCqTkbA)(fO$P4 zGX!1%H3oJZE0EeqFOPox(GvRl)AF)*_MjO<7NDEqv2Yo<9nr-%SZh4IJ#)!GU)uu1F@cLD(Is={4JwnSe94ymEL6-aq8@)O zSWk;mRGEMoUsOjBjsKM#BS)p1U6P^5EmF9G75a5MDMLjYJIh;X0JfUE0ExS|!#%5B_@~^2`AbA`g02V zb-HZ${J^wet}+1wKRY~4c3&3heQ}ls4=WE7JTP2=M5+$8Dt~*w$-j! z2ZuK;jG4*|0*%|H@vI(;EWJ|<6J0|>>pWi+4WR;hbF_0!|E0L!>ZZ1M^tD6VpcD=b z67VGSWN|qJS165w^#(pP(gevzw-}eCtsK?XV{h$WM+fDA4c-_J#+6yMlH&XfTBdeQ zdJ5NPKiet;tYtu(U5a|_`grRmUzeSKmX)1!X?11g?mx<1k-VvJ`3rdyW_1bX2P=QK zdP%=!OYfi;tLl5?kju&c{EUk(=Sxe58jmx)j@6JDf@Yjtv~9d#J@&YA>TMASEL(Q| zicEouLd+lM{jYn6bk3CW2`1Tn>Zv#333RK+GtNe@`BLYBrZj`&XzyLEzD)YzScw zjKw3#CK6Wv19zW*=O;g8Wu|v@L&C`mpoMDTskgIa=FgcTRkzlEE*OUY)~hjCSaJv6 zG=F4Kmn!HlJ8tJLN;bn9vD|Ko5vR?nAb?5)`Z=qj1ifUYNOk&#d@8eOrba~ zPSq}}?b^KSD8k7@<#!dmeJ6F&kV<2QFNqNj_!ivgDaT+4B+E!!#0A;415ip=B*Xx$c6J&?u)}0uhhD{ z)5@^H*~KUQq!q)n^fB_Du@Mx=o)wG~89HD9CMc<=Wp35X!XyE<%*6=I_2JE~#Hgkfa~ zSoV1n7?|4;+}g%$9`eH#g4)wmZG^^AOYl!gh;^I^X+djzu1cTEWmZ51XA~@<4I(tu znmf;YC}I_=ZvT)ND}yyT@OZeZ67>JbuSNAgzLo_S0pc(LM!bh?nGvx315et#RRnN@ zb4<>^TuW>~$zq|);=*ZL=3Vmh>_M0PXPg zajBx>T5(dnqXJC1!?448$sFMqhk-jt_XgQAEmJ+vR2lzQ|rVHaH^m)e! z>8^J>M_ZWf9P#6OdVCnB_Kt8AapFQRBdS2l51=paBt&!kr;8sKSZIU#lsbVUmfRlc zX!lon*JpA)(lc^9Q$JH#|1rAvZvJ)0xD}=!hylwj#OV!5y?u?pv`<4+uBjHB{t^-! zBfWgXWbM`G#-7}pLR=d|>Vq5FpRyuTXlE|JsxBuvl#JLnVU4{0i+YbUMsD!0utf^<>h75wQ;|0%i-TqYPbhA0J;_wN6O-y_PGUov| zyHG{d)n2Sw1)N?GC4YlK=O4lvkSoNA-{{S%Bj8|v*UZH=W}`h4wKU-e#I>1d-kOm!Ivi zyZ(iL>WkA3-@CSdf6T_V2jG!euH{iXi9Gf{A)t}W4kl#yKi3y}OfjZwc$pA;f7_^d zqlP}zf8V83b-%PzI<(nFfR#>U%3cwd#qC3VlCapXZ4ev7^k&GMOP*)4!J2;*>WRB| zCpfT%GG4jFSc~;F=0BFoX{MuW(&SyNSI8zFjK~TQ%+h_QksdS-hc$6BDaZ#m*&2+8 zwbFMr9osfQiTv~mSS2Mt^3c-78ajiIJPjv4`E=6y)|3fkwep@P_im=~XnSB^Vpa5c zseBbuU{HK^N>jV(C`hZ{NXXV5fw`myrefB?XVBL-YHe>v9XaIkO}&hfAB?c&GhM{n z)3>)C`^P<|j*lFXixpXbxm9L`t|`i=33$oaQxTbxR=mDtKqjEhm-2zf5#sFE9y?Qv zBy;UX2H12{b5TeAsXWmq9X3Hugj9*KM8C-&&IQsXIS&w{MGcfLfW@+S34!fY9Dg2&)vQHBjBK+?FYGe z(C&={ov_S9@Ad?;pWi9ISUvF15cavGrvo4?soK%SLRRAz4^J}y-(N03O!gOyaH1?y zKI80xqBW~ig1R5Rm7NH$_|+1F!v2oI;dY$5wZp8N|6N_xNf)oo4~DR50Wc-b4}sog zY(>#Lt3_WraLa^VK)Q6{_ne`tE9<+3nRD8Jt6j@Tb64Ri1!w^ZeCgVh9RDMv_>1TA z4rA}z+V-t+g4DZ%B(1oN1Mb>6ZVH$(9&2$j8{Y9;iF@+rvY#UKCi*HR-D$a^ZQiTT zPn&f?w;ClP7HRmbQ)>7OjP}~W*EfMOtv^kE2Av$Qzch;`2>{tTK~9DDqH>wROe>dI zylxu+n`|3fgJp9{fc#vfT9~Y}iYH^QU#2{LDxa_U$?;1T#bkOEl*9<{g<&spG~=>+ z?olCFxvBnqxZRPM?%^xI^JLkUKsNGf!DCuQoc(b#quz)F zi@-}cVafKkmNIZ>bFkUfk}{^z%9y=4Yy@WqY&$|>TqitsKCY=(r^w|j$6BJRKY(zm zIZ!g@IlA+Q8bRCYW}(|(>|%%pOPm7!z^M)LH{_1XC!XAy3sGAJ??wiWvp$^$P{5%s*AG=^5REEVQ zpG-3zcRCEQkTWQ=3K(^Br$I%E1%TFPw)M{SwvqfA`br?JuSYWw2pptu#mdC2aljo; zG76@DVPmIY+PE1BmoGJ`W=b`Ht-{5oGpX(0Ik9~~l|?j?)~W%k={T6$yO9kY0HtgF zvPD10bm;lu-eVkMul_XJTDpag%Nu-aM3R>R*fT+Pgb_g-p3M9*nL7JeF9Ee|4_i`a z`!7i=1H~f+(@5*i5?@YJH%I0KW6sw}_Vere3s)1;KV?Cm!ft=$ zYC0VSA{(QEqNqUk=Cef$w8j8to8ZO9)AqoF&q8IlY5`WYHzwJ7Ayd{f(mul1_BC`1$#3 zc^W39ZuflVfkBG-$@7G!6JyPYF8K01$I_-Ob~mMAGYYcQXddU2ZmE3c5dW#0<<(wc zWHy{jZY@)iM6nAR36#WcnMvQ`rGE(48Ew#1Q0!%?6llIw|A&CfBW-RlnAX@Y^TwtH-hVYCr9{25;`{?`+vVO%**} zY^_-h|IQ;V`AlHP?}?c~**%b&)wS^w@F0%^1u~wk*=~UWr;VQ0HfevmD<<2s$tBSl zJU}A&>>8ar+9(%pf$k?M#tX?P=TF?-KWSHo0(mOh1~Rry;7*o75s(`LiA&XFPXn?BQ4%q6qv;uRBZgv zS`2Rb9w4y&s|Tx1I~Brlt=kJP#z(?&V+(&H0EUmewyiBONfoat55xh?9YB7;mdKp|$kN-RW!8X!x9?E_F98OuQbg6iAaLz6H)_idEyQ^%WW zidlWD7dW^6`d@UBO&xLNWo{06d=V5eXjpMUV0{pOMt!0Lg@>$HmHoKv{*+Ha7;Z&g zS!EvJIbRyTZr-H5VZ5pQ|5UB`|GvJGakyGn$X&=S+N|8hU_ZBb;S$>Y z<9}UoW9~uV_l?1g-qMchx0TqttDEEP(>)&#-w+F-3D}(k+a=q1WXE+&?AtoLqPjOg zUb`!DYQvV!SZU`>^;QSJnlmS{j-ifL(hRD3ZnEl!U)4q|Z%xKHd(+6+192(bcY-Eg z*#>5E(I1ua=v+nydN{jk>R9Y3U(C4O;oC*?{oJ_G z%%PQD>LfVKV`4eFYeSC+Tye#%t}XZ+2e0QH;r3LiZ72AYs0%MN}%-L+bwQ``t%}ELBN~ z-_mla9nCWXV*l_$o=7}{&rXK`svEZA`i+P79^L8Y%{72O;OzRu z0mF{tmB);|@BG8<=B|d&>FXU1Z}Y`VmpV8h%JgCLsb-dvEHk`u@8WBRZ>{UgPq#AU zq_E)U!)RnRyRElc27iY>!%6DWm!(FOv}nYqN`sc|LnrlAv#^}^T6tRU#w+m-nrubQ zr@n8p4*cy7755h|CPMBzODPp=dG6+ah)Ij(QS)QbFI@%OpoA-$S&tto^B8;= z^J!uipqt_Jcnkt|d19In;Pf-vg7FnuZL0EydvQI1K88mH#rF6ym`O~6hU*QhlFzpO zeh!pQ*u;_JVlQ2+yjo!@Bj@IWqxP!2(KRg={uq2{kUT;&3NS51N26Unb$s`*)G6H# zv@dVe2R6<$bp3ppdRa<#490qc24GkjQ$EZpFH~iXQdoryLOu=E5=8 zS5srlR&l5{*LnwX^ggMo9w7Zz5VB~bRkoFSmcSBxt=UL5~S0_=3(hSA)hCSeBsgOi#lwH%~>ZdA4)Q)J-QH z`sm~lEZzPP+2qu|?^Ty=H%lVUMmqn2ML%XzrB;z$8bq zw-D8L_Z>Zr9%Dk0}y1&@>xD>f3 z4&7cHyUxR1XJOrTX=c%x`|;6O_Yj&YE&GkcAiVuOw#~S7g*K7-8>#$=*=1e zW7B?=3!LqHCk^p3P`Lf;X-A_w=S@+THGpdkgNgSoK*%$TFQ@_dZ4`%n7{mK zgHy1?gxl%Zsq3GJ^tnv%CEn!b@f)H_+o`6pl=)QpS4A;M4%K|;`p1ML>M-hx1cOGv|aC8Q&s&_eKeq+#8SY+2IAo!;ylw6b+u5uZtLL}YhnGk?dsvQWj zd)pgcpo$Q@uI*jc_elHF7U|LV#T~u<6*a1dhsS$9J%RL~I)D*9E1Pd*fF66a9(Jt~{AciTi9WhwlvwYm0_s%efF~cE20M8a zM~Tromdbze8rNqEpQS<6gr+K!I2n`B0az*>$YLj0d%j$^$lRLdZpDw%!_Eg^r?m+~ zilMfOs&_Ly`6QKqgf0x@V6H&*8S=?$w~K}C12hGN|Mt(T1(Mk86gYUu$he;~QJDvE zp5;Cc{kPQrkALv|*<@w3o;#DanZXZ}-ZMg1b=R+FLU9WhHBD1$q9zE0pGko8QVONf zv{k-6;^}u$!DWJyo)RpgUtL)U z#_EQ{wGpEWbXh!_nek|HUL?J>F03S+v)>!ZDBnD-fWdBq&~@;&oj5p%K%mQoD!iXp zO|G?bRrAgPUVeWp&CDz;XlI4qvi0U?(V(}9MJMI^+St0h`uZgUfEnF`+Zx$~6v{_`gc#(5cRKIi7B>@McfwvvcIciK_y zO($wswB3Q5G;#d%+u`cIbrCD0_$K zMQ{>GvV2qyH#tzFiXgET>wwuJKo&jZ1TSyE{)ov?7-xPrUzqH4o3C zgHM3?S4dPOg^gQ8r9W|dp!nEz(o;{*M*EStxmhiE{QiQ#GRXN7qVQ=%w?gH$XLS8? z@dddRD-hDY?d(4L34jlu8QU#-^*SFpY8Z$=u2I8n79Hu2+|8_AYY*T0$C-nYM-U&E z8jh0I7HDz_ZgcE`wp*w6X=QvQ9UXw%RH%c{(ssucL&CEh!!q7?AE=1-AUx`r^kwUq z72)=yF=k7DnYVV{J<&E8YTy*WvG7aC%_iR%rH$333{SuC$RP0accXav0YG1}5v5m( zW`*CKn@uwZYinVpgw_bMA}B|qYU!g4+KbU!yJU6Ze_Vw3^Ka8ymXdNYA_8aaEZ7S? z1$;@7J(Qh(0kCgi&T7-x?G>1sk?2`+d}vidwzqI+wt2{=Q(xk-m7&(eVB_tU46X-% z!pZc^mX$})EKP_Pzs#y)W}zHwS-Le>oshHk+4zJ{bo`I0di98pvCARu>L>5_CKpZG zfBbSx5N$cHvdb~N{mJkqj)pvBZd8Q6#rZ~v;H6SA%T&nlR&%=!{?$o8Y-1c%`3n2K z6=qX`DufxMe>O5~(nQMq;W)Kb0Nd3U4%@(@km@r@1=>1`i#^<&?f=7D$##`4QSX-B zxAc2%zL)V(Rswtud8DesGg@vr=I+{}Z<_m`EC9oqD{Wx`E#f%nIBlkw26WYr^1tT$6CUHh1l2o2U!f8M6%9JG@!hTh^U|!}gCq z^3IgAUG5sju0m*^@Kz-wpK4Z3%#fd#$sBgcup&m-?T3~s5)z?DWldvaT1CGR4K1Vq z1BNdg#Rq{Rfe$y4BesH+bH1}GT2q4F<|+GT*lejCz9&DP2H%K?yljCd=2(c|PoGYD zv_1UY2wG~6JvRZ;c6FbyO&q9moXD7YVnRF&G6|DZ-iM;>eE|T}&?!hgzfP zjTPgW8Wu zl?4N>I8Od|!ivbsg;5Nj*(dLzN-fr1o{~zO*&;|$1kByCHeJOb88l9bsVd%IBe_V0~z zt@}W~ylv_2nn}ay3{49IAd!-(5!iw zO^59`ivS`Qs*;1t#8uDjKG`Rb!t+OZdco*+T3<`kqNmM@?X6G&;gOa6Q8b-p^l8x} z-6qs*trYyZ9C2ue6bac$)VUU}ZAsZu3>e%r^HNTHP2DV58u-94s|5TgG`>>pVoDtO zeoRGGbfZ=#QOF-|w!Q)^`SiXWVpUXZG}E60ZS@^Hm+){imd24a+YYcXD}FR*d*I2> zm8%v)W&Hv6$q||!7M4ie;)9oF7~sj3+dQz~|GJP~hEPMYD~zN-pznC8AFE?F$OnGr z9N8`;e`H&bsdwrSO;dYhYKo1ao%~iZcCA(10p*>AR;+v5UXX~&S8fhu04hn;Pz&x{VXp9MO@u1D*s6nK;cSy@RvMOuQSqfrl4#s=0y zFW+LuGu4A)8GBFw5%ehKaWwKezT_#4oC{BPR|hv0_c`OVD=%*G^3^|v&1E-Db^&KS zzByzf!E+9wmQu7|FWXn0rLP^H;bV16v3Id_AvZ4vdE@N^hRh8E@eyJl+V#{l<6sdg z@c8dz*J+1TJMZ&Xndi0bd)J>=zx%qLa{4Tv-{?+hye<53cCiaDx8W3j>PvU} z9Q2#F&UD#_PNwtN04Z*|#GPn}zXk;A;F0@0XG*|jwAesWS(?lr<;F)hgkQy(za)mu zxOuv@nKGf@{`9!|+$UlY>h}EgzH#2GZNu~=OO>Sr*$J8$uUi`G5nD^pAPacLyN`mXtdp-l@|mu+7tK?*#kxNLBPh}@a|*T zRW`r3T)lA&h6YH?a+tAzrlplWg+3?E#8qC^L?Shk%hPPT4SMBZmDakfqPU$OKrgpF zF2^MjU7vPT&L?lCiu^waR2}fs(F$F%$KdN3Q)<#wM3L9Z>UlcE$h|(q@uygp@S)i-C8i0@3H7pgupk{*9w3D?&5=;HYINdD22f+DCEKpFzlp;7 z7+Jz7EWqNa{KX}SL6Km`W#2?VuTW3D)QT00p%3#DNtjRjPm}G$yQ~ghTy0!C!nTCq z#Xc;t&Bdd6)BD@5LK*pz=Pl?eGT(jE+;vUj|0u^_F8VUFc(`w9)G8Un?lgWAQEQxEqTn^+L3N7 zB7!9PV`>}t4Yns^Qp2~gr6tQaE>!0mQ2|V(gW}G`56q1TmAv`K!BU~-K z9y!7;fqp>_K77z|`@(99Pnuc~kpnJGP@H?)k|4r%*{9<4N+k5zfmS+Bk-M1e*ro)J z*5G<#BlIqJ&-LMaKJ>h)%2{NyMpE(+0Nn=$~=g+6SxT~6)wOcoHu5<%kE z@(^a*QwVYAX6LqC%7}021pH~xT{M2%b$N^5Mk2ddm7;BC=GAVx5^LbcjLQu>haJ}tBSw^~+!l+x@v8ZtAUC}^Enpsc zR2C8s7|@7{<J)XVH^S{#lmD&k7*(Ls~w4Iwe~Za#PH+hCH7y% zk(j0ESY~i$nR+Ya?m+*KGS6?lYh{}MZg57aEl|C>{(txTr`0jjemJ9>0|AJ8QNR6& zMNo+L&p#zk0^z0tBIYWK4od<80%&dzMbLc&N|oK;Zz`u_I382Ao|Cbyt4dC_wX3aj z&9NoVj>3V2urb)(@#)`@>de>_u+x_72$YJHLL8m@O zo*$1WH62mD7cRxxZsU(#AYGzCsE)k&aVQ4i${s`X9B!;Rr`p2oAL!Y5AV72hkEh82 zs{e#r)~fJAZ+otqrjF(dj!xHi>VF*bgz5iq>+fqDEo^N*g3&!#-CIi2!fx|fm6R_) zXEWSn&T)dhsR7I?O;6Et8)PyPV9KETqt(!>7w-?uR97(0Q}MO^ShJ}auh>7EwjXV6 z6rh>g+uQB!nSd!D1>C>Kd+Uhph7V2v$5W%wC*Gey&&PfO7QEm9A@BZnaq<+l61B(1 zBDx~#PhFRhMUSh6lE^E!mA9)i2Q>t^c-v+k=$>KguDLxz`% z6CUG8neL3tjF3BKoi`AvD!1{TGs_aP+a^wImHjq5KM#S^iS_Xp30Od9QP=M8YR*_QMFao8E67T#vK_JtYEmmZ7G56+}##OFq zkq^z)Y0dkIBL%{u7&(;jtb;ka3;HE}S*}4D0sC8Tewh}=s7258W zwlLl6?-##GMlgwW`su&YEG^SjgZf^Rc6&hQmJAxX3lWvKf<)D_{o(H&X!0Ap?X-`z zk)VN>Ti+#u_?8zsiP84WeN@+v%P<)gu~VTP8GRXT;gP9oQ(vd{J}f%@`AfSzAAD$X z*YvzSb9nRP;_L|Vsb^}!LRy@rF$Y8-?BhgXY(96HM~)yhe-+W*5GOCE9iEgYtp$ndPNNxTfK=_sI@6NaVNH9^8xIr0 z&pwt$T1``Qv!c46bz6nQ0+9j29`zk*6dJ>|b487K;$Eb_TrDWO6UY9^)RECO`Cu z7du3y^ero)X6s4>%a^LaO!4Y>@s@-{AFh710u!ICXk=;j?#5f$cR+2={WD~8q1DSN z+@yhQQ;0oAS{`{BX-8%F4{8y3I7ezxbg^4=tZKeQxgi9@Zs9$)j^g*XlIQ;)Rc{p#SD- zr1@+gX5ag`kZ0N%Ns!aMpm{i!*xzfhPXNr4+mbT&k$0B@RdQr71UOeKS;zGTV9`h!s#)50E5_Oh&&BZeRAdeR{x(*Cc$X@jucQevXRwzrNLe zTl;rj^LDZEzHcr_ z`z#SHoVb}jm@A{sj zq{s+e9a>SOTUq!EF{O06?bjB@^c8VqS|CN{`|4@<&YyC~xq^BJw7`~%{0&`V=VM20 zSShNmZhUA7xVfG0lZ6M|+|suR=7;Dkh3=F#I;9Dl;mOlISqME06b>27R2tY6xXf_c z{H;f~#VGKmDyet{ySUZ6h)M=&fY86N>?Z(C_%e4Emdvsw_K1e;+Kw;le(zcYgWahp zO?~YlLry9d(#2CsN#N(pp-S5nJd0S0{K}qXtxt3#WFZK`S1s)qzGs_d@n^nwF(2sw z+|uwdB{jmo*x-FTWa?#ooB{-Vlvg~K6^BhY%i;2gj+Z@ni9XNb0-31JRqztQzkX=Y zv9Tue1&-zmswa~7VT*^hCL%8iAhIIjy%v3vcj%D${GGs-n1sGILG~>XDh1XJXA``i zQ>B^4q|+@Xv0p60#_jP)}MKb&PCYKG>^$z zuJ0EwK>yR3*^l$tND1iQGUO;AZH03sz-Ul+>&KsOwRJucI&aiiv|MW?>f5XJ4K0O1 zMCSvNKgKtL*Z)&PKB`G>eS69baw_gd{fXIMgfoBi$+n1YtSJ{-R_3ocODgLJnW;KV z^|1*TYBuVY$G{9VHg@(tJTVkj83V0Rg`dLvE|si<*`rwqBca+{5h7NzM(aj3y-yAe zzahU#VqD2z77C{(=H|kxmxxF%I)sVYV5q#znAmq*fl*Uf{oQ|d!wVS{e{9j_xlY?JLN~yyO<%_sW35z$T>Fqn(p4#j)acMk)b5L3V|Zt zK*2?mmYn@p;jjP3J#U1COW=2wEXNgdmV9U$>{W%{{yt^~m!&$k-O;3Myg&h7 z$#w_oFXN7H>$jGqf=x~LiI%wp`ab6Wu21%~4GC6xydI=(N#9MLiY_`I*7ZQ!wLC`& zx}SiOI(-!7wWAy>dWabdPfy6Ya)5GKs!_|Tlpcm6>W13f(`FmcetmZVV!aMDWASxT zgUxJ1Jv^FJuZdu3I<=!4^mwvf#EAT_&aW;yQ{dk@%euG-z8ODCznQUb7*seCah3uU z`?s4<3G(PBDX>M5H_w{xGfjRsxtC3H$exk$k{qCyU3)IKwa^Z1~B|S~S#0pBf(@ayi4TgZ_9F=&p zmpWRotw+|v-zZsbQwBy?uazLDk>Ib4XSE$T@bFy}H-cZ*UKZzK@%!>4iy&c}RshnU zqPRta0E&~v=qUD35r-ZQqSP{(^P3y>Ovg5FUw=zKKWvEP%6Q5EUCgb^p~hIW%Fo0- zMTMVr#?4L3IxZOGwRnF;;mDWPZy_K{KD=s2tyEnAI+@DmA&V=ONN7|#00Sv#Ykyf; zk;=6m2OX}_yqdcfDKiL99>@6YZkF!XYsQGb* zLLeSEa)JB!_SWV7b?M2&z|o^OY`sBlHo&!D3)EKgoXbp zLPzcFDkeRtj2s=FTwS>wH37l6?N<-}tPB=PU(c|rv4c5kZII&M)!Bp%U1xYi45DLL zT2~;6Y|isPl$?`fkyi-y7DR(wwdX1a#g#SsLml|klNcYT4}}Yd8fLKH`qkh>uoP4?C}4SIX+s}fxQG#nMGTX6*^4nz8>Dy!9no{9^dLEEq%))LC&$qI1}t7N;(g0wS%d}}qJf4w~#R~DK^h0A@I zRKNKAeWkw=nYrT*m5BD*OB3yQYI!{@#$cx1Z-*FwAqgm+0cV_LuXr6)=>Z~lvia|6 zuJ>;j9LdS3Ve@POo29&dukl7+?S9l{4u0n|{09@7MtNf!kGGyC_WV~Hk2Vhx!gq&f z_YR7A{VL0-NlTu|aCBxmIEpZmKNiWL;tkt3hxQc-lyUq@k*x^grY*FSz`wf$=bEj) znNS{$((D|0`f-tLIPTY%_k0=FUIk+{!w!JOvPJ&rNMVTaGvlaZPB-e2$^N9_ zv}pfP7&0q*_J?qzSQZJ|YO45dyJ!tQ;$Hbj%-1nB@uRAG?xV)W_rZIdKN1X>Vz?|DbL!9a+cbm)jaGtBCH#;=+M|3%gRMDnMs;bg&I+ z3&k*KW=Rv2x;ebARlL|O3S3&cQ&yH6o5r63O{h^N8AZ8kET>bf%+xqSF(cP@& ze(2F(e}8LnwNMK1;S(w%**DfUg`K@=0>_3Or&o=QEDf`Zl`Gf;VYkDvSIglx;8&WV zELx8Fs;Q|Hhq;OQX;*=YL`@CaG!>ZpirvN+f2d@6)Bf-c_+lW{<{M0+SX?z zeJxE$Bl%p{a5)jmx4BOMTnQSape04DP(?o$FVW2C3$H@5a&CGll9opSf1Cr#MZP0JgJjoJKSWWyJ{?)CWFp*q9K!@ zs|~Wy<|j?#q5$=$fSE(>x&HrM4*pXUgw=g)hgM8nM-rNSUeUWy*F)$Q8{39y)NIJaNo24`cPm+oo>zb8K z83*W73i`o@L};A)wtLzF3>o++4O4%L3+*2^Dng9bGE&*_wYY`d_cF<-AY9oO3axP= zUPlfNsRkt|-NU)8y+`bS5H`_>=*XDyij#Y_0Eyt>zgeL^B7&Bkbd;qg_=3r1jzFip z3tCJtnBV1v2Gn;YM9lv?5`R@NG-1XN9IIsh0)lXG? zg!0mXU3|V6e1zOj-d{ZaUS=;OeYug|5~|qtWVBgW%MI8a-+E2!czt4@@P8Qhxv(?j z3%Jf+;Xi1KzbAE5balVz8S{xi`%(O;_EqfiNZHVA|KLsLB9}x08=$gDX!Q6LGtqvv zJ4o`rJD5xS+Edc_KImu^n!RE83^7tXyV(x7HuHUM*PD?#h#qnar-$q9wqgn0%pcLy zG(eC~!#)NqC-Xk=IqH76&7Hwcn$uIu16^S@Q;nBBh|f3oAx%~60LS*L^?;|u5|GsI zr4^sYp2rRj8>P_UlvbTD^aI~DirfwA)0JqFBgJ);`A>9l9 z?}Vgphw84p`p6UOEzUgI<1uwSo=)%L69U9k9dA!3X-tN#PFwn1nk&^6ADVq6eroZ| zk`oJA!K^#bMq(d_S`J~i+@?LoUgZqoFFq5-kdY(JC?PvwF4-*8VCBxuixWKz{l#aW z`okojB-k94*iw6WZEff(hZxIP;(eN+jGuik)jpCnV7rb1%ncrz9W@}d&ul#TIkk-y zAF!dG2GrxvNB=5S1Y@gDze!R16O0q%A@sXZ-hL;$F|1~RuupVk`9$<{0^;aep3_$; zXCGsFcX;@+uW)(?$H@c5`$HQLXXw12>3kOXct|cDg>rY#I!lnsm@ib;490<{bn} zDP%2WO!0No;4z7ER=Z%Sw7K)*vx8%U(UV}mBH2KcLIX?p?as}`>JAA&)CMSY#Wpk1L!vgdvh%Rz~b=fBBv-WMIM28Qp zS?#Yp?A~;Yha~#eWaGl3WR})Y9D)EPOO+*11@;SYA=7=9h}2i?1`*|ojJ02Bt8W~q z4xVPF4hO&edHKHvmGO14T%qB78uQsy@ZLH(W58>PKW)O_r_od}<97=QDGt$>Nd=S7d6zYS%}zs9J9G_V{PTHxLzkl7>&&` zVZ9(`1~yw(Cs;7xC9;4sdcBTfp!)ijjz=nNUazGjj4eaSS~`}5`7TIl*fV{Uk`Y7c z%o?6ww5#QTRGrL&JuV_Ng^`mpS0?3T1f0EmbGS;(U9We`XGxw<^N-vlIjF#1LWtEg zxl#}+vXn-icu5z+8h}of*I0xr6oJeQacYXQ^Y&)}%O7GYF^Xa6Y!SQxBSA7J&qq(U zWf4y&cRyD%aqe(jXrqlapDWsNVIBffMdAF(gU;9C@vv-=W9JvuoPb?Zca9H2qPCPu z=Aj48ud-SWTJY+ys4D5R$*TXmAb?`JyyL1$J8}9x;4TT|zt8hBd>zuO8=g;8-1!RG zDw@c8mosTv?_5F5_@uTn8`Avyx7GqDj6ua{U;=)$2u^`dq@*2A+`lDBhgw*6PEB?? z1n6-00pnm+yNBD}2L)nO8s%PKVS}vdI#xz3ZP4`O{%Md3J&{NyT+FM_j z6;{0`5C7XTXq_iJKKJoOH;u&SV7v+#J%Y=;%HQnc)g~x({8qE^{u(d*I%>53i~+jv z^u5mZ(PkFZ_{gJLZS{LTe`{Y`TN}HLYyJ9N49zpdR&Io07xNpM2fJn*E5iYCY3HoB zSqyk7F%7pXlpUMfbzJ|aWhPJk=H_%r*VB1ji}Me<>8t&)JzRYF=7U(8|C=e{r*F-ks#4Pwjk=-$Us3@8$x!N$c6diTUCqdgYlwj`LRkuQYIzk3^#MM z^Uuek_yu+jvYa9)Uo=1CQT<$*>Z2mxWmHs=BHvFY#rm7nT9yGV)(7`R1%sZ~LP4)$ z$hbNIeG^rZ!(=!7PgD%J9$~XuilTB`O0DaQL>5PUy{^Ce4>4F1a&8xRzA&}!unIo$ zNH(ZxjV-BhbDon(NUuxtw@z(UY%4tsSftZ!*(eb^n?RV>x+blsrqVBQ{{Lr&(b7Gd zm|ZUr(%bCYg#%e``SzR+KBcc#!gs(Z!QM;Gj9Omnf$l6nENeWypVu!v*_4N{(F5^A zM86cG9J^ThaC|_5U%9!Y+%@MlIduuyoQ=eSR<1Z!9ck2z&`#r;I#}R}SGRci<8H`U z3S!+Rtl9MN*0RwCta%dJ^YwMUISy*7bycr7w*D zQ-kz)*Bc~&=K84M35Yp~oDym?U}|gixP8gwUoa&esd6U52{CEsDp!-c=8bf^>=|Dl2coY+ zK++}IQjDJvJdFFoW!7w`#t{3$Ux~OIdx^e?6rN_Kn>HxNX%0SDXKn; zy88R$_-X|<7y;KJloISE2c$2-Xkf>Hiw(OT(lUl7K^d9qhX$0z88)*vx3=)&;SlUi9~zBPV`D#>ZT z8|@$K_WI>tIambF!o^{5?F|#}_!}|_uNQ|3GW)60H|vgS znaaMd^}~a$t^ygT_qOr+d4vMhRND}>w$91nsK;Q;n)e2unj(*Gs7h%$XkLMnS`jN8 z@3)8Bh5?arlNM0DElKP!rp3Lkx!i+6h)R4QF#^=CgJkB-{Q$lK~sxbq9^1HG8@RtpIVXI-qaRW3P zZQ?4Ffs!i^#y5N@J39xP>ha>^$?{k~L4NqBKsDIF5VbVD6`Wx)84fTv9GE-h*xPJV8T&t@oEkH76-umxM0i|S%FRf zkRwT$|El^%7>X~3snv;8d1F~9tZJY?b*TMcqjXSz@31Z?lq1ALU^zT{H-9+&IEL4IcQ;U5ZHgb^P8@?LMmJKBJ5Ry4^Gvq0 z=5t+|%P{&`XqUb#Cuz>?w@bAA6=FGed{!4G^zUZ+)O2?cR-#T%Wd*8=X{)$`_IyV9 zDctSNbc>PD!fV&i?(oW>cry$^@b?RxplbxYOMJICJG)9@AyuV6sydnu{sXZf*Eyzl zR!u>lzV+)%KUuoLX?eG1cE-eYOC4NtXWhECt@COmu>?AX(H;rQSoY%>^PBFb8w(Nz z?p)u1*L6ru+a2Ax!1MY|Qc8#Tb>!2^iT2m5!KcA>9oRnrOeFEG$WX3)&OBJ8JPFl8 zGdC32Ky-X#nYRlB1hG%#2=CqG_gUq*T&fO~=wF|s7&n-zBCq2GfiXZsAvcJOV*SJT z2|Vb2uxY&=aWf*|;W?wf?MxTy51{o&QH!tjz1!-`yrbVyM8IMF!-()r9P|5CZ`Zk- zeQ0aO_A>T6b#=!R*ZE9oBj}SP-Pn$Geay%BWZhHxSvS_Uc83%BgU_cwQre` zdV8AL*VZ>dSm}7NPfpYbSz>p$a07N};}^JN7jYuA;o{#8lOC$lE)>)txpxzc<6rV6 z>2f?>{$~ zGVxAf8Uz8e%1il}=;)2(7I*7^J|7abM8<&Cv@l6Dmdk>X`2O~7{`q*8fBAuoMhbzv zb&rhz_fMgXO63f%c5`9&L|o=Bqqgf;Y=!ea)pDpS9_x=}pt2LUcLx{hv-B?g;)2qF zv4^(~Z^FC}2ntu6*V{=Tx48Ih_$wv`d}Yn&g(f(K1Ts`^MeM&n%XpzI`p**)=Td@- zhgNE`?M{<%K_q9}81gLgHpBoN7ZJs%;7~FK+22hV5w;e&3eeF73aJ?$Lpowt*l?me4p~Orx3fh{e+(3GX9{nY z;~>)aI5A!eOe&G3$CkqPvrdI#EsM*Bgw=yDKPPsx%ODtGc$-i_n<}K320Fpshc#Jm zJI^D#y&sC5LpA3U;rkW?$(L0_GNlXi|pH@4UGh=x?uHkNPdG zi-x&Basv*0{Ho0okt<66M{E7)QO2Fu-c5+1wN}JgIn=Fa|q)NP~QI zH51wE;scU;#CDtQJ5r(U0jU=w=xT+5iBJKm{F&sd8+l66J3;00@y5c8(4K zy0wr9y6XrU`t43v6$twIy0OH?sn%N=2Hbn_pZy9XLtTLDoyx1O;5PDm7FQPbc>Qg= zu_iRv8yrZG*bTcb@_cy^GZO!o*}f(YEgrw$w9)A-oQq(XfK^}J@?#1t0#4DKa0Efo z;iX1=`mPuX^ACCE?Diw_<*P7hOWwtAwV++0Gv9r9Bhm@ye~V#p%CAMV9j`?JtXPlB z+8eP}6Gm$gU+WU=@D($(Y~}*&-;3+KP417F`n0aLm;qbAuh5Jj>S0qr%}}J6S?IId zL6YZ}6g25C0IP#JW4A@3*Yk@`m+^8P8+d5>eI(@s^cs7krLsLh>tz3Ysi6^}gQH_Q z2ry}i2y`}GZdI8QUHWqtTg(lbCLzHaLESz1y@h{xCI_G<4t zHod!qSLMu@ppg&|m3z3!>W3WW=%~JAD0MS^{f9TA-um3R;G%;U44;KJn4i7O0y4a2 zT>ZLQ-r}9st1oD&?8E+z1!4&=fDu)`S2~GV=vXc{TBh#$sgy37Of)o_iK+@&J-ete zv$flJ*zBvGG+<8=vBI>p!s^_S&j9B6$?A0?OX!u!nrttFQ;9P4bmI=qCZZH++OPNC0U3v%WFyD|`thC-So!tDZJnQCr>dZxj4 z5bwoxv>zi0nXFb^rpA8wOUoR@g3oRA)&K%v!?Zme^P>s+qUQ6rti?%%s7xD+53|h| z9h9IhnY(>>o=)xUUvoWysnY5a~ufuf=(XCf; zw~4jpFwv3G1%KPy>S;(_0tP08pcp4ONngU~ld8zFWQ_z({g2ACmrNe<*5QR$SB)*p z=(y1+@<#s^bl67Kt2g-stoB&KG} z5A4U6aa1yQa)D;A*L4&?-{Zl+2%_c@aAyo!#Sr@|lOKmXvk;zT0WTg8+dEporz+~L5g=A-Ps{{a+2O_EC{W2lkKt$RJk`2-?*dirfs zhfl5P2bTbh}^FIyet}3-ZA-VY4j4b!q z(ffRlFtbDJ6EANzw1{d1r(Hx9EmQ8hbmuEUG_R7aeOwl&iHk1*t|YY$Fn?+B>&nRq zA=(|B0)}K9PX5=rTzL`RL$_H@G&PK4Xn;znsToUj{_(bILaB9rdDHpo^LPcbkjvh2 zOMClwY;MQ3Ht#(f9gR^GZg(@(Q7;}=qeT*G^m;ItB8(Z3{oc184$kG$N$2O8$@S}; z^}a*S>$c1;1N8lF1>!T!4*BQe8rU0_wFxzja{SjGSz zK=nJaQVrUM>z`-|eOU?~l^z}_Qnrkp8|V>?UXDHtrC-<^!{%{9Y;WzYq%QY-F_!D; zZEycwLmayZU15%cH?IXMjWYKU1F9IzC1a{$ih)D3yf|>V_3)PM^!C!yCk>QCrx^}q zbKwSY!`F7G%c9rTCOA3K{lz!U#{5o&hB$nF_tXw4X)-iGVgB9%?17buOkDg)qh`J_ zNu;oCcP8L&V6&WzvuXT0VM|vBTO3$D{5SN~lcKAEmYeix5>8QC5&@y?Qg$JSNEyP< zJc!qG{+Jl5@!6`G3xR^_GXle`dz7eo7Om{2M76`|F6u}86P2Y2WR^EbwtnW~JdbFG zotCSy+#E+s6R4(6p~YYa=Z-Ha?9 zf$+)x6D?Od;{Srcn1egGr&Go!aB~9^{B8984u}GeNn^DpCjKjvcBZylILM}qt~4IC z{sQg{{jpuD z>Dr{&;g(a%1kN}|R3kY)u_XaBxHOTFXg*W%e0M#>r><~HyCSykTdG&@`Dk)Q+-gW@ zs-343muOpVh(4-BPD6n=-V&R0!jrBkf&$TZ6D|0=LA(_r<2)7PR(b5&e(N#m3=@3=C=jeYF- zC9wOAc@mD0TMKQU1Kh|0?31`!&#%4<+nj)GwJHO|+WK9M_@}+w&mVHeC^y8RM;noJ;4=KXAfioig;VRSfq$n~`Efu-;kE)#=kYzRfLbnnz$g|^T;%to%pO7TbRX#LU4 z`$I~A+MpN)t&x8NhTj7?BDdAU+7)EUQ|WQfRAYn^vgqr32CY5U`M$IE3fhpNCw5t6 zh{j&_BT9CCoJ^W{tHSrcZCP0UL{l<@dgt^0vNm+thHzV$t5biwea21tt3TxF$x|f^ z&lF>_@p?k=>0cKF-r3}PatNPYP8($teBo5DPv!;5>4e(z=#KIQsz)sCkMmzGKG$)* z?`Q8X4UnXrZ;or8FUz-6PB#;sPtOZALRaAU0B;aTI!O+lC!HE1%z$#8G^1`p^5X+o z8RcoIt(-xUU)TDZX6mR0#@Mr>u|Nv~X9A(n%Ye;>hLDqr$z*nY0tvSM7lw+m@|Itf z4icjj3<#J+skRmweD!D)pyK6jbvd%=kM%8xDH@t=Kh6$`dyE2H4*oGCrgWVea+Qxo zq*1kSrn}6CE1pmh|5^Att=hpp;?a)vqc?iCfB4zPYLYBuUC@Q z4CTJJ*|1kU+ts3*_x)qN6T-19YMi4094j~@F#2PlD#Jj9fClGm-+s!W7vZF7f`Nff z|FY|(rQx#oJ8ndqi*Igd$kb)_)b1j5D>!U(RN`7vm%)uq`Tin{%ax-wPe+ge{+0y? zGM2|wVJcGDSDq^BDA>RNE2nfVNhqf3BH(yzQ1!`~O3V2%lE2^v3_6gqOGtus%ZQZH?k;ak z=$;z6ce4QR>TF%uO;GRttIvH-e*co2>xg;YY00g9_e=cWwC1lP%~kc&Gj)E8O%y}V z&Qgi`mT{tQzDzeLtuul|}W~Q}~?)xJy z76U#o;6Gy@&|UE{>c_s&KQAorN-OMlKspkIcSd#DCSVT6wFnTa6y-t5R5&&vo{zq_ z?4;X9UiD2T-CT;Wshpu9OY5@t$Oj}(ahxZ7nOQ`x7hF=`FSKzqZ(W;)rvy+<2?Pa7 z`m^@!158-EKkqwTmo?tE_Q&1bZoN36T|-q1Z`do)+D<}xyD5swb+Ux5H`bP6omFup zC>VODO3Q85<~v_O{{F1CG&4tzuTPE+g0E96+#fmW`%PR6@VDL%|JWB6B5v>I@2Yd= z_XOB#K1cj6_h`&`f7y86^=wTyDM$xJPc0k&@cR5`txdky1NzTxZ<_S&@}aS>i?_hz zvAK|r!Z2-2g?}|bNjLP@p1D!DE8~i}E`scwz~dpMrcQ@X^ZVj@*jje>Pw8w@ESb5^ zr>dHbHQ^kyjzuOst7VV(x2am9)pj3{qhngwgi9K8`@^x>!pDR3R;Lq_l5VVQymw6a zE~mn{ejX@_cVSP9j9fCqpHkoT`( zR-;Ye6~bI#g=pj_MER9pj}&7#zrkf(XGea-cA<55t@=9!df^M{2rc19f14;>!be2; z`RA;Er=Oz1uNa~za625TOmpBx!NUMIG7376v3v7$f3x~z-*wG^@Z+oJ3MWNq zV$V*rYGpcO@90RsPgGhhW&ppA0m>d*X~d6>&+Pa0=5V}?6Dutn=2%APZ%x&t{{l;1 zBuTe8$7dggUv0xEy4)B-2qhYdjS`*+S_U7GetB&82`h#fyn9iOC%{XOHB=Xo-DC-V z;?!OEMTU^5hi0Wenwis{vLQ_lvzWEIX1u+f?b@WPq<_SmbtjnvT{~*8iI@GT570`i z{x3-qP}JTK;M8f)2R!~cfDY%*ON465FwB-J=@uxPN`pZqGvR3Dfo>fI9uA<Yl*v!^@S!OW;zJYqN!zPWvk^?v2JJhzs6bgJf2s#gRV?rK|+O|fqaznp+iMP0Jkxj9a@1C;lpZn$M+ z_lMco1DK3-kHV?L` zEjT+BXy;Aoj@X2b3QE<#dV;v}nU1v`&q>!IOZt4bYQPvB)i10A%KGiTi%Nz7l8%3e z#ykvGllaNRQbt}|{k;3`s?6BE4MAmG2HuzZaU~=^RJgl!dJXB!9gjW85Xj0kP|NX> z)PE=bPyNY4wY|Lq^ej$^%<1kSa@YVvyUAZzCkH(Bb?PxJL>ux@-yMqyUTafY_Q2qK z)a37|4&b1_v77H`K8`qM@*deoueMd~l-sdjFShIPCWoERDI9^) zPdZ%QfdXCOpL_qs7%wu1znbDz(Gu3Kh^&k`d`~bBDyYn-PW-v3Q6}HNtx_4(pK(#e zzvnv;xoFEMe9EJfOu%J#6C!z48KI}c{cWc&DmIeuKlw-gC*D-6ig5_X#&F;3*tRLM zzK_n|mdytBDy%7t0cuqc5~GOmaXulE7o|oOpr=RWm6OAQ(o6bX&h;@*rE{NH8jr=K z?B#m0G-OK|U=VuA!N)d+B}Gg>RG)_vek~-MRCL-e84U%p@OM$`$|F%DNRl{e4<0?d zRTX4#@bjCwAdxqN@iEDQyPzp+Wjq2}z^qs8$Oxj5vJ#jHj9CiPi@s#1dzW_Wx|9%Y z?+@pb_fP~dA-ntJ+Y4P_NIF=rLT33_a%#mFTrv+$PIwHlgtztMQx&w6z4I?LP8c$Y zOO|x<^l~I|^4yMEXTI}X-?GPlT#!nwN}^P(*CzK2L!r?IMPW4~NT7tXdri;JMn#Gh z(*{RzB0tZ2Rm3W+8DQ392lWrlanNJRh>)>SguAP1v0regQLst-k4{th9aP~1uq6>T z6KVp?MDNnecvtf>m7y~qh0QPK+wi>~j&Fg}g1PJoloTvkUm%XNe+C{UOUH&|WvQYoLxZHuM zF5F}921nko0J9|&0Mh&cfn#v({x9X>$nj zR|RCq8jqyVe8P!A6L{OST77=HW^U7+ApHuz3it$w?KI4vyIiQKkLQ+OgplfOn=N+E zQ5xSbQE&`XBOny9P|fDmZ4;POZ;a&NimbDHe3_kN-aj-IkgN~)`0`~Kpn*PYgWV+q zrT;>DA8y=r%H2_#i~lrC)bhX*Q;gDe(4vI4S9&h^72@=Ds6!6NQYaC_LCOCao7A&E$1e*EfGdD0H}z<7J;c%XzRXA{n`}wC0&Ugn zO}XZ?Lwr+sh`%a!yCE|vC@M&le0YA`gLTQIKw`s14UwjlfwVRwF?6JQE*scU;J zg4A1tbYAW@tX)1ErMJ)hS>9k$a?DxJ+2S^QxhrC=jwkWGABRxk^$j%~kFPD97ZISH zbKu%x5RAf){_{vlwO;z>E!oBVh8uv~k6psw`Oop~bgf>G1I*Q0&U$9zBc%6o?D#f7 zDs=y%{PJMr_qf9Ra>FoAtx`T*PN~^C*vQ98Mde%auRvDS5qze7GZ#B~ ze#O*c|Jb1Ofs_$6Ih4!7sC<#E(XN&0aBf`Qf6nF4>{%OEN?Z1BpDv(4JpIvbTSRMP z88V=}PfH(KSN^?fvR}a~Lm8Y05SxT5#{AtrI%DJ=D^(2Yb{ z@8tUuTZ>ARUvK3Mzjd5$C^4&(nP8^M)8xR~q9@0qtqYG#udY+K)s-lJU5D}sP#x+T zgBS{pfe0`)O^7T?e%|17;Uf2$CNj8Ag&kTY=Pdd`1`9Y}Z?qReAI%I3>SQ2;3w=B?%jgV{wDMtayR{r!lp-kSN%B zFTdrFeWtqc=1qCwxru__BR2{Woh+q? zvsogz&kK%5Qq1;bl>%noPZf_qs@n?Y!U`EVuRtwpm&U^RPHkgo&e#v&|uHbK~vHHqbf@4V9jF=};szUpr;C~X|*EiWG~ z$Gd??!V`c}T&tC-4vNwAI=Yh7Bj-TqvJ&~2R#u_Hu2pg%)jnIhnt<$>7Hd1 z)zo}boDhC-5jSs-r@b0MBUqFti`f3LXG?_dqZt=%kIV6X`|Q_yr{|{*T`4O~7ai|@ zq<^RDr1##+1(|qpSkg0P04lD2-?J*MEF8qPPiI`tS>jPua^*4T8_HGMKub06<|d|U zoDaJ8+SI1|o3;1T(FU2YB2-ksB?+4IVXmqxAu|X2)8H|DlndJ+-)vJL4*YN( z2e&%betNKOO>8}*f6OB$K2)^q0@x(IRvN$^XP_}46aTeAlRsBo8+tsGe!Fr%i; z{JOX?C2jAxZE86#EG^Z(1yIWkG2lja&9i!Hk1gG2iQtL|xDryvU?Ju!Mv3eykXhgc zW@`*7rd`u)Ohy-!me=`ALpL^_?0yLcXEtQU|EJN&?leBic)j6&I8tiAHSHzcEYetgjt^l7E;9ua0I%nE-iI~AnV|0@0~R2-H?gp4DC zj7?W}L@#upby$)op_4i?G=;Jn5R5cgpiv2{M&`0G{TG%}q-%{37Dj=Z#dz5Fh{j9z z;$nFZjxHS`T$Y{`lBl#lBKbVdKM0ysfVWmHsO)vhVS*8y{W3Y&_cq`T5$N!-2+%1> z>h1klca$lY>>Vw=jSNCt+`KStyKj^YFMI%A|2_af0hjuAWQg9**7}UwCG+&jNWblUV{zWaso9R{>>Ld`6;Rve+PIt3Qjx^xFK z;>MPRZ4_{}Zhkp-qHI+40_7^q(*h6p{&omYVqA~YP`!^D7o_VF$T6F9y50>Hc)#Jf zsA=T&y5}E6liz*Szu;iAlEsu(@3S{_etF{9;jwo$x8?MAmqX~2v)t9oH>1wxfUW5w zc~0&U=lRfO1LwVoybUj0#8tn zIxUq?Y9l{%9!m?%E}Ta*7_)f}o2r?zO5946YJo=u9&HyDIZ~YN*1Ev(zcz zf5IQ(g40-ytEB+-%bY?1fLQSrj8UHfDWg^_mQ`P&ippB6LE@45uB*;zA%$WB3V6Bu zRzD}_L9@c7?ux@^qFhE(u!{~AgMg))pa8O~SJeeMf9BBO=4XqNveTxZ{cyDomiUlFHbz z#3p|=%<+ER+n11$wYF!&0>Wp~!eP{Z;Bz;3#jcKJKuc}^2=dTMl;YV8e1vji;IK*# z5e7wguL5J?n2EyAg{4L%+j5%9HRpY)V}?Jdhkj_{3OywpTEF0s=!0U%x9u24n9u8!~9ZSlQVO6Z*D^p5*)$7Q#Q1ol9KJvu$TZT z^gM~~z(7hx7h&{@gz3LK zL_2r+V#^HOU#D|7Nq85-e~*^)Jg~6A+x-7Ab(T?aMa#Bs+&yRr9wfMh;1b*=xD#mH z-66OKcL@YYXe7A1OXKd^c;jxb&$;i8_x9ht$Nsn0sG9ZFoHv;X0o$IPw{zW2$H^*z zZKQb)I4bsY`YbP$ep{5HPA}W3gH zEW|bDkXke8v7#272p)AS!~*m=I`UOvPpCzEX00GQvoXXydC4Y4T|u&%QL(mznmuVyY`M1R5Ml*ApJlcG!J10Q;&Qs8AnU` zz0auc!TbpZ7>6X?!PjYa}_}G!45fP?gs!SJ&7Ks>pT56VlIycFoS!xe=Ko zckB4oa3x$&_Sc;GYbxkrHG6ZWmCN2UDt*Tr3vuyKe`94%^7MJ^`y zE?!N1xmH`K@KsZaC6Q+Jh>5~|?X50r@hmLdy~4p5iIMtHqONiyI5D*XakZ}5IWZQ= z4|QtEf@0*KDUm*3h48%5#03x-uKrih_>Zereu=;mZqu6f)Gr+@4uKeYJk4D!*u*`t#Db!?`i{$<6m~f+8VulSQes4~Dz*`rDyc_gUXMEU9Qj*+7 zl-3p5TFuj`CFI&@WkpXMG0|2X(3f{3a!E%G`CV-DND)gkkN=^S)RTqNE#vjZEkHm_ zNweO1*NE4ZY7{!n0=PnneGm|kgQZ%OO7kfQ`PYzA8WpNI3^1)3 za%W2xeh(M>rdv)q=QDv#VeRN|)$9wx?Apy_48jimg~^0$60~m;OKM|Po39|?Ygl{h zM;NaK2xd&7j^9OHuRf9zR8!m*D7KQ>gyZ||D75{WFZ^8#d9931a z9&bPSpKKMfd|-?=v$Wjrj&NXs#Q5HwZ8W>4XLjB`kMb4sK_g@+T0FL7`1wLOuF28(3X&7%#)G z{T<*cgXX5j)_P$woW=&vhQ`sU&*^*f!R1zhJ1>+*b$(<$abMbW{O$+7=Qq`PK1@6C zR*va;S~gHj^4t%0z7D=E$0ei_pAI>Epgj96#~SbDCeui)NxR{-Q$e%&_&N@o6v127 z9sWXL5xwstm;J52?NaXrS7&Bw^I* zdi+Sr+^4I7DD;C(AFvZ|>^0rFfoY1@+^%>d+9f`y!Kh`(W+=0lSi>P4F4CDK9LSjn zupF&2KxWA@mng+wdsoy}(F2rtsF7}}I_L;gR7}JitqhM2ihVKbBGpurm0DUp>{{}u zAQ)UAQ0Lm2i}hWQ?p3Q=;2ut+qtW&>&k{vJ49PWq!lrZNMZ;KRIgVhdt6%Hv%%WJc z+wu6*pv6JL?@j-vkdpDHX}A?shWNP&gon0oBp>GOvGz%UDBa$2I$uQv$3ZvnU4$=g z$w^IUH34I!{^*$ak1Ti&0+(G&G_f*mKNl{-_`Vh)h0Sl*7kv?IkwbnRkK1pLTtN{c zUjp`4?nH2_n6PoM7xB%yiL30>LnI5POj?TxP3+|Rpu15+6^@^jG>;QJ1Z@9T`h;8fPaMIGw(_)!3SZj)lRd8x*c@|{?OJvd1f7AZdq@-f zBp9}Pk!>2rlbRoaID{AkIRayZcp+ReQ5j7L3j8^-HMnX1iu{yG-{kt?@m5z|67)+3 z%_BKnQO$tVp*a*T5xp7TS$^A-@d=|$3yP`YF4h|Cc&ApBQW7U;lPJsVjhSa@fT9}!+GDeE(3 zFnI|4o}!kgopnXYp5biGrsnB^qH}Zfw1MSSzgb5PD-nC!^Z51dn0mF>eRqHNg;_wL zCW06eOYotaQ7V$a*s~dS8`oexeydnW152T}L^{#Chyqs^iB({;7fa^4I(P| zFHehHa`(5L0n5f|A*~%(b5tK`LTyrm5&wvh;O`TPlS=4Vyw?_^wR#Mq5#SMuGDCjTrzHa^T zY@43xzclY?dYTJ#sMU4m`q1g^=N;Wm{xpfs7>qYUfxH*upK=nES29!NeRYr*LB)d2 z;TkJdwUB?JSZUZ=Qc|LY(t)41VtSKsIuflJ|gFhYxCTvY~pDk`Q5 zHqP#Rq;z+m$p|7X-g*L1sUx5H-d+OtoHSZrpsn`uF%Oq_o%h)dJ!gSCK*s1~y^vuc+!cpAdbyo}mejRF~KNX@*ZDASBZEuTy16z@5R5PYHnrRefd63SPlXDJ+Za z16zHpR~OBT1^b(-2XJq*ww$lO&xrsS3E-GJsTd>Dq=9tVuhg+>YG$&Va*qZKH`J40 zn9|c|DwG*sAPM!6&}I%kxOJ4-YSKbT5C|+pgfS3k!v1(`raqL}C+mTLWm)(iBME^NV9v+kPgVn!(y&DavVtFEuNl^kS zqe?~gL84Y?O;TKbXSlqlibd7eM>dvBgY9le=@MecHWvuA^Q`MIR_%iaiHCL2F!S=ap3xZ97t&-3#JP zyt)`VRVso2^wn;+$|3WMp*4G~$&nN)CS4k;@OV#Beuvvl2COY^^MGAEM$nq?*RDy3$a z4kf%Ijn{Z|;YD--9ZK@h*bQ}N0GBuVXV~V%)qOtJtD2qNQ^Teo9>;Q8+MSxLx%i-7 zZ@Y#WQ#=o5%{k+c!P1$XTJM=GXW8J0qN$}NYfX47Eq8Ky*H6E=f~;|L@1RD)CQv)1V)?+&QBK=-k&2 zX8{Ht12eg-hAelP+S+Ut>MJY|?z`lWnQYI5qgrm^Oow)l#zy&GCJ%@nys!xdzS`|S zZ6z(!(t;$zU!~w9WewVfWcf+wO@VhQt|%4Xf%Hti+VuKmkF}z;b9G>|j_2*S2NXb7 z$xAy-rdACrWX$(E3C_(uZEqj8;)$jHrb#NnVGF2Bl4x)bBLR6m91%8wmTx;>TyJdL zU0fcI^WWyWZ_mevPd1wuV8*fo6>BdTQo@1T7bt8{hlEdmAA7gzP#2q>+&u%IriZs) zc6xU-Fqp7C_?88-@r#3T%v9c zgG_PU@uKN@i@G=M1Q49=t`9tX8&z?hi1Rk5-x&4V)x7s%+kn*Oxy>bBEoA zf3=#NtQjSs$_|o2*3)$c^|F5#5)u*cW;gR1>Ccs)oqyo!EC!PlX5Wm^C>2fo>u&;}l?9NWP$81VqvL7L zUiG7kRWVNT%u!u~Ffnsc_H}-U7$DvsO9MzKa)eN3fqa@5CzTFeZ$RYX5@MubiS&OEJWmTBng`0a$ zS#!IxzJfaoj>c}>$=$80cp2y)5{Wj#Lh5Q)@~_P|zzBr;v-PQ^W=gz||7WK0C>+fQ zCo>9KFky?bWq@OP@xG@?32?dm=)ug}5{6M8zix;y(2c$~`T@K(DY(R-A5tW6oP8%(m}B}9T9P7Pbw?fa(h5ccsm6(*G| zrbU~}P4r(wzO{{we0B(f%wXpeb0@}TMK(&+nh@Z8ynQCu`DU>547^PgIjG4L*l+>G^>d#rcn`Dmfcss2o;!F@7MO#uR~C^F-nk_+Z&=o(=sB z>nUS_$w^N1>$b8w#yXaYA;a<<ED!R1+oZX9tA(Y3%BqNg0J_-`^KE z$}_nxC+N})7Z?}+2Bht@7<#wcq`N9+dme_4M*F;&E`4Q8WNGZnYUWO%Gq?QvF&%)? zK(ASzRlC!od-AP!el3Zf3d3o=TwVSzBf@GXzifcy7H}A|Lz-P;an+@Kl^jCic*Dv{ zG~*#eK}b#hftS70%~(H1_(U;$rPV*EVc=z6JpfVwY1T}K=M>LaQ>4?e0lPI@{U~6; zh!6e%Z3wh}9tYP7dipzZMd>Se@-=j8CBV_1ISw|=&o0}{kB?{VaJTv|lo?fviXXHh zK0!fu0G8|$ly~?Nm{e8`Gag2Z@qp$^D6C$1bpc<$Vd%XYOYg(~d-Sb!^Y*?}xce-y z@E>O5zxc*OM|xvTClg5Vfil-D_3+G)*-Tpn0tlu%HrO|eI=_mgboZlM^r_vaNej(k z4}oEUmJLT77aw#!rJL><;sZS=hUuXxycwjJ1DMkW=@t&TImkd7&k2R8a@X$uMa8&G z@o@=T@OTCZ4NFpbAp}?k9bjQWnqTxX=O9YS1fM)(S#+qVX?c^DXOWv{tqK#{I zvsCSoV8(E`BHy_MV3-d|!jn`|xj}L6R*x*awYi=4eLoS@jue*Ic;}#@XYgZEpZAYy z8$I5RYQj7L8^C_i$h@E4u}*$w4eEV(#@usKm3!yNn_WsGi{!Fqih)E0;ES#ohe>I= zixLPtnQ|NOiMSsC%lC!{EA6H;@N-M0X<|(;uA|+Y$fbMZ+IV=@0OSV97wNu&BQP%j zX&DbU=wAa0`VVRg{Y?bDU^hf9CsHkqqytejPH#a{C7 zCOC{ioYC-%)cz@WdSX5YSH)C>$s9p$mK|T@v9z%2q+I^|s#@r2&u-iyz=3uy7)<8M z=5)H~RL;6tCbD!JwfKEZHxs$I-+`3KIj*Yudwl0K>g>`sY373tep5jd>1UrphN*3`R_|DGvDq|O(3n-P78xN3R$tMWqVQ-ui+ zMJ1=oZOE%)lMzV}9A05*{9xmP(5+7kqz`Wmoh+y*{w#=~>aANR73<85m287+y)wTV zMiOLW1~jFoLL8>C06N0$<^e*f>}`Y@NTbOAWD6i5)^cM2I0gS^g6e?-h>55@-httN zvq7!dWe7lNNv3)hGw6C@EN5ub+zQe5=vh$&rB~P53ocfgGHa7H=r?t9cF$AMm(@=Q zYU-yo3;+7d^FCB!{uAIr?63LctFQl2!B&rHf1Q7?go#-u z7*c!qDU>P^|DAG$wTZ_MNo-v1Gjtx7W)K18hn$DPbn~ThMV+!5KI3_J+3JW3tEZmS zyhL;b>R*`CfBJE2uXxY_Hsbd3(yKlSVlzBtT8%zu>r1zPwBrkV7?DxJ#Iz|XKqX7h z_xJS3J7t}O1n(Ra89yX)k`|jtj8eO^Y#AY_{OX6h6Bx0*$ zLkczu10>&OVgVjc}*V27KLs?QxpihgVfkCk6naSxlM;3q|A2F zC0sL#%k9trTU## z(v*%lP;Zar3L`_I5)C+F#n1#adP8h55qRWL|5Lz#&fc&R8-&g09Gr&jxxAeG13^AmsYTV^013bMZdLCCDcoCvjTaD)XC)v9j5I<@i-%>eO+ex;6BS6jw zlD-1ZGnLNx1<{`(-oL&+Yq06)C^^HcL|op*_!l<12v%!ud`qIeA>b&21uPG)#lG9I!;%x zpPtP#?pGua;Zu^gp+-hGfz*70<50*P`8^EI@&^6-T(cWdGBskMo7$H$7CEHo+iO-g zgJ4>16`ufHE;(FsaX0Yc#|cyN@c2Dj5B>?Zw*{@PLwZA!m$s~Y+5a>i&C@F}p+x}D z6m8&%=@H{?qQsb*>4k+W^(!<^hm+6iFipLF!8Su^rw<)8){R-xKw&1{Qy|)+Svub6 z5~}UhG=_H7I~wmZ*p@r-W40n#}{t=7KWNTqwqgbOXm&N z&{nIlb-{3o^e_+o-g=ZlFb2y08_3qe{fW($V6|G})(XAn^+2A1cEwB6Qv*lleV*nJGrX(|F z2j%BZsUSV3qg|~5Q}-TmH^;cFvg=om<&cEN6Mp!S;TnEoZiOI+nnBiYR|4g zNGNX(q@^^t^SZQjSXK#gsVh@UwVKlUsKpDp;t%q5U2UJOY5M@QDtjobf{*@RJOH$U1TmiL5gNIoLkPqzIz^NwEhUji+$f@UkJ? z_-!HimOp|%iAM3KnlE9cOGMQ~lO|kwcLc~(t-K%2KbFCZ3x}QpXCKV;mE;4tZ>$j_ zBm?=HmL6{g6^{ewi@_(xpiuk7>#=J_R@KHy#A+yO6fIqssvpwb##;03_57E+phAth zNRlPN`*pNB2Yhhr7*($xHnIdNjnf@SyV87c4QkGnJJIjZ6ZVg8@`sYJiQocY8K9Cef&JWPowrzwXcw6WY~P#ptHq*CC}@*y0>VD{rRXW z{V9FJ>$rl?#phyvD>WvBnV8+6)!9G4x00Tk0`n=%*s`Fy0{nAbT2q*D0H`nPtFWT7#+P+|s0Q+~DN z9aER#@Mgf-rcv_If6RnVw)Qj*+ivG4)U(^OOm5fS+B%MV!&ZcT7J$MBX_;g~UPL7lw& zW~F*M^3A{>IO0(q7C1)FVQap!5wo|RMN{$JU8@egdZn7DDk;o#b)McWDrq!MLD}kd z?xu%FYa5y5;rL=Hn-hb44-^FscShcM<GW=C*LPvnZ^1s zvDEP2-1TPv#^oNXgk*gi{8ro{I7|65sGO|XCS!LjmU;Xx5O}3Kih!l&5=@`mWSdO( zgTSgyIB(R&S%6iAVQ(ld$$i|6*=%UbLX+1uB#D4r1_d1>3x;1x9)<%9Wp7N8)=6XCy>x% zp^djmD*biL_ABu>0&*6~ck^CM+{cA}OO%P(Bx^9p;P6CY2=QH!^5+qJu|dBH=|8Y+ zHdHbBqvJ>EddWTx;$g1jR#3>8LEo=j8AZn5zai3V@Y7)K3Fg{Hu0a&tk8)*-=9%m9 z%FUySPgF^J%`|C4-d!myGN`0kA9QHowFD!AoKYW8EhTF+Nl_IQ&G8HAc}LI4oI=i< zcbMN^9#Qw|=w}80;zIv!>`WEFh1D{#YWXjScV^w+_P?~3C@HNdPn3W(+jZt~j5?iM zTs+QR+s`^)*;EmV=G@RturZNCFrF5|i>BIGAi#)f6yW+Y;qPG^ejOI7Us?GAg%wPf z$X*DnddNYt0NxP*;U>OOqq=lCmKLU0uEpQQLyeDh4r&AUryiaZ_P96@nMP4t`w~b zM6oF9FP*&H-1&XiTUK|eqMP32+!vdmS;==5JRvnrmnNhj7ha`#W7O!t z<1?Yx(YJF!&UbgEj!0`qA4LN81Q(<)pcbt>fd{$CJFo;g_P3k-$77YigAja#5KM>l z?uylgfkwZr?r(;YTte*s%oAhQ0Pl#Bj|6%TOwjScEY_DPKSD`#PKAL=MDKN*_8Q`_ z9(O&o^ayP{8r1}^4Xlo+Xf$X`X3MIl1d3S4Xv7gA1AS#SP)*I6>-hvkOl(g>jK`GP zKivp0$DHr6avC->OKw?7E&8!jvtt$7H)gRPT9tlBRtrik#*pZmPo5!IY0x;q>Wku( zq)fG6M4A>z>d}J*n~>fL7u(W(F~2_+*P6bg7Q%*O$FzoE+-2wfmv!Zx*;T)%wT-8q zM&K18J`n?xQhmQ0zwM781j2Tb(Z%&(buZPGan#8})u!=8G4(9&X?I_vr_ZJ(nYZcQn)3 z!izt04glI4KFsaYQ)biVq(W5pk{_Yt^dG8|7C)oMaPT_rt+VskGsO9JO8(v0KQI-=+DnN;^l-2HpQwo&~yt5 z`IYuIS+=A-@rQki;Ucw>f}rEpny(}`bE+8ufVyJf77?+ZZnJlHh#$;o{`F3ZLxmez zDvt>hO=S=n&h>2yX!_d94MZ>*itqM5)@c#QbM}TWC4Rw$5_U^K7(Ql2?C12j!mE*h24SKF_bqR1f zN<=Xi+K(g7LD!!NpL=yC@p{*2WY(joc9`jsQcy2$>^|diCRm$k%?5KKP{#jLOye*d zsF`PNAe9N+{v#OD3v$MGu&I9BIBX+dXD1TLM}S4Ld)0yqa;|3SlS`P2ufK}sE6ryo z6GJxyz6ilawlWiW1`cp_r|rN1AD1N8_crek;AO~6Hf55%^AzQrDdDNaSFRLzmf&oH z@Vw*@j<>Mr%pfb}-|dJ5zI0U-%vAGn;kR-L@C<$FE_=@gcp-BP9_1gMAOpO4R^GJv z{mWx<{1(7rEi(VnrXd|J785g++(UK{usgX-=!Q=1v}cPolY=IP!yLYT{@V+;F%@pn zZ05VFRWM-5Bph2dep|<2BROW}zBAt-@T!F}sN?-=`5)v(teFo|1wwc>p5ly+LxXOC zvl+ifS_g#ceRPlo;+$;d`hd9JTdx>U)j9n}m4`^w3=TAhf}K*RDe!oH%Y{?anqE>^$zB$_H$n9NaAgK$bi*F-g5pUW zk#bcqH2t=ET-E9PI@Ii3V2mY}G|O2lTYLJXsqfWe@vm{+YX?gC+ABkBnLe@p5_jhJ z7Lkzme3)-vx;?TD{r0z>poxB@C~ruUO!8(K-x7M2g+U*TJG5G+Q+M0WH5B>h;5^5k zI<&B@wXKiV-rKe!>p|0Xr^`=Rtv)t|HT74Qc#8BKLwU&|9$d~B6K;S8ttrWvFw)`= zfG%U_i-{wT1C>*@acz85l7=TGB_3wz} znKYrm`Ma-6%3!R&^~2Ir&5mQkV+6mtxQmxkvT{a((+JpmCmkmmjytY59a`pCgW%h4 z+Djv3Y9GXX-E12&8k_N|d=aR2>3Yl|N7yr}^8!(2L>gsNS1Cz!TOoU^Mr|!#Lf5(L z{?^jUK^*)+;wVH~eDKjsYWBkiPn9WLxx0tobgVdjA`Fbt(?F(>%^>TFA9=momkorH zc4j_;=c$^ksWpj#H24u^WIl@7z?nM$9VZ&*!MC~LZprYmtD@%CyM~E0Sk82SXAX0D z%oES!3oJYGf0E;iA{!&UW1T!Sid7KD^s#ctc4{RyO_0B66KJ7o(5Qp-V(y#2a?-fi zd=hrXg4D>zaY)N%>mu?ONt5Cc@HfNI_Fh#0hXN{i6&|3=q7#*2hNbA#Mb3nVN6@`$ zVh&MLi_}@^vnBb+8=R{y57e6loiTN|7<`NHf{PuFR(~ zp#6-8VW7`4D`Y0!*k|i#dpjf{@4A|mAI-Jc-vEu+h5^9r8tm`o#Q|_-ZG@ZWTB;m4 z_rfgz@D&80zU2a9$t$H%CZj#&36;Cyj<(OJe_~ym&Ee=6ng)DE33>(z3G;t>F?IC^ zb=p;}2iPA3Ag{ew^7Odcv>hJEUZd$em4=O(1cf#!~0N{~-Y6Lv&r7N9whiDslANF6xjCNiGzMiJ+ z0_y{gD`2S9)tY{3#GnjHqr;kju&@Ke>C~3XbORuhj2lg6;zQ&gdp-IV|NZgd!wU%T z>Ttpzvb4iM>HmDu*!lY6DRO_G8&Mgj^k~?ee0fnvt;ALvlB_b3 zZZY}x?AFXSQrn+@zgkKu@+cb|B2@b-F?tB`(ed>0T6Jj9*93fN=T^vUUvw1qd)tk; zOCa_-%Z=!~4dKh4rBLTCFOChQ|ASs|hz#8>UlCnB_E)Xlx0d)FI3{plh+YTQFo~0)WmJh{QWLHtgydg{=S(Xtu$u` zp72jf2Gd7AzNj?mXn9>*uAmOZaLrO+7Nsk?xNTLNy82d=or2&mISjoP?-?A6_GNN% z@PvrYN2-0Gh~XH0@&i5%zBXyNq_M>6;6KB{9Kr5P)gjWpSeu@AQBO!RGAN4KpxUiV z-9WE8#5-kx0V7I%^i@R$UW%B1sjMtkNDqIx1bo-GRjg3S-^jeQ$Y_w!TbEY<$03|} z$V@LQH{qOk90|V#J+2*s;!^;b$0jD;CmZLxu*eT595jpn-bnuCzdS=l1z&ey;jsU6 zxZli+JijHp6T1olcJkiV!rp6au>$4gq``e`Uu^4!PyrbWLM%Y7mE!W=uWEgB6$jY# z(K3Z<2k$B=fm*zC`wgvSway%(6CL>2f2HW`ktlx<(0!zj_RDd4FIDBY33GSC(Jvn8 zS&WSQV00B#Wc8Dj#(Z2)5kI&)1#E|sI@ZRvJFAG2_UX~dmG?WOT7xTZmPxC2j7k>& zbH*n*O>L}R02R%E2bxmZK#wE^V03Jaa1$L~oEjx&&u!OpE~WHmbALdgm9ASzm<-zi z&1!2u<`pR(FCVj~vC**Ep;MdFow6vV|Aw)Ff!*g9u+7bRQSIpQoX^^wf8t2N5u4X* zFS1F2O7fixg4h^YeP-&O&*-GwhN&uw(EQ>{SK`6?_hpG+m^`??6lgfQpW$=vUXp9) zzPs^dE-x47T*~f^ihp!Q=c9)4ociqb<@V+F_V)0MW#{#1;QrYw#54H1cw&w3tNg=( z(?#Y)+vi;6tQ;I1?AdQR4c70WJ8~-xwTGvNyX$K!#`l-RulM=){F<$8Z6^(DGL)i^ zqn+33d#f#!04wZ-{Xq>w^C|JbOXmEn35J=&>oCF5{)#8#=Zh)_wu#ml%Lx&mrd##( zq=Y;J@7~Aa;m7ZOTjN`Nq5&>0Jbd-WkHs4ut!=`hImSlDuc>EkOTTZOW_Ygl%o{SC zI=vr%%98O7>&iXytc&i#zj@e9oO=b7S+L|$=y4!|!7s#NW{6i1_gb56YU$8yu z%+lqsuS2QRNKF7w0muU1f608iV zdoAh;xV=&ldi(kN7^2diAX*RO^)qz~Wqktn zeQTe-yWBl_p%-s)AO5Gs$w;AD8y&$@I>SF|le|&!4U=p`fNC zrm+3Cz5IQM1#Sklgt~)D{SMayjX;czrUwcf!H#R_Tl-!{7REL_2$k{VtGTc+LHsV} zo`zHl8(O<)aID%92TWWfp*clHl2ZK|cjiNqyGQz1tdkGd`kTdt1huD-?3E&hx2!ps zao&pxeMMPkQHaQkq+g5*_?fSgjDMqE*(bCJ4^ZZa0+?h6Vq=bax3s`b8W^h-TW9Bl zHm*2`WZO0R+okJTFi_Y6y>-Zu_-C~nBz%`v0w-gXLWmF9(0yf<^2~=_5F=rZREt|_E+h-2lY7E%aW}5+@s%*S+i$0vC{u1)PJ;{FCd}4W?&vtCI8o6z`7Rcorl!;j|3f!yP7xZ-G zJt!UBGYqgM8Tq$PPOfH*ImfvDFHWE*c=&@5oGp z+-|M@Omv+0j2ZmjRG=qNr5VIi`J_VF1_fc?7)?~>YIXIgfc;iLb7&TLq4w95baqr@ zFGpy6RbCiuJV>QJr|#C)fS5^~_-%=?EEYpd)`Cf5&rsZaR})T;$A?`=-iQ{*`CC(S zW^;c(^@w?RQY8L%QptZc@ z3rCKyeyZ8m>Z`ldEG|PH>(7c=r290Of3@5!TxLN;1Q~4r#C@|PNV0C;*yYXM?cvuJ zf2R!`N(MZ77hc+*fN-vq8!!=4asxF3Gd04E+6}PBuJZTT=C71VCv?27TC}Zs2;@?4 ze7R^vsdLKg>rRcK?IM0@mswt0zJak_BlB5nyj&LA1cZr?zj6DY+}EcB_@@WFoI#rW zx0jpX%XHVrJ)v&+F6HU^eS`nB1OfXd$H@dgG46sUXe-oPlov5t|64y`Ul57$9*5g{ zo8A1%2rC5eS_=Ca>rKrrvZ7*Z5_fw%Y~Y%js%!9u5tNxSN*W=00;6P^WrXq*E)j9~ zs4<~sM}SBRx*XFDCB1s6I}Sf>*su#X z(KmOBVGHKCUXle37-w=9Y{pk0I4nQ>xcY^qYwzu^7S5H zwHzFb1VM1($ghi8db}jFD)2`M{`8xwUc4!f&4NFDrb;RJkm=teSEb{jOx5vTf;+pA z9jV8iZ8E%F5S&2BtcyGy!XF@BRr3i|`wBez8T&RI^JbLCp+EjyL=+ z=J^6|j;}&i9EI9@W;CCm54{YQjSl&KuiW_}LK#X)EW}rBU&cp&85;PIw%j~=Ir}!% z-~SlK$@Xjn9ru1#;+QjQOgjy{%YPX(crjBExI5aA7u?U_2V~p>%gHd zB3Ir%EzFpj+NyQYVJfWR3y$>>fv2KFjkd`dq`0Aj3$57c72nle8pVkG>s{oaJ{-$d z8s-)V#LPrqmWH3OeyXQtTT+IO0)uPtnaWa&kO|A~00j`1={hBOGvMFIzux<8!Y+Kd zcF^Gv(d&;CmuZoq{aZ|ULDnOlXCDL%z?D^e$JtPuxaWiMIk#M*;#}F08X>E{%c5)F zkR)>GoHva~sD48w+?<4byjN(rGLee@|DCEjw4;6&HUlZ)a%-*bd5I8!U7lvvW%td zJ%lln9gJZ$%kknG=VrPp12P{NPNNx9*+b7qW+ng7j}tJIO$VtKX4;qt;8AZEqIl9)TcC zey9!@7uUv=c9nV@M&dwxP8c|fRU;|^;SNlYMnulnsb&_x1E};VA%QR12Y@(T}P@ge_-dRSjMI=PO-7*v!un1-c6r ze4xr>m+ZBZ^)+H6|MO4WoVBeuUyTW73nPLeB{MdWYw-J{`Lm2Qm7 zm@O^hy643=@OuB1m%F{AV_rSHt$?$-`!! z1v>&8a}`PV>KWSiT0P{$7+?uc4{PaHTh6*0Zt0e558RA@A8K(#+Z1bSBUCCW1E{X{ zauI-7P6&J=w-2x1m7!&1xffMO9Yh{d43&BrGRh%O6s1E7ik5;tl?5=(RANY$1FAZt{#C{NsP?>>4iBT|yk2dLDx#fTYcud8Z#jRJ{(*{-AXB&PDlsRKrANlV9 zE+bN{8;_|t^5PCnf4Bzs(vu1j2P9EgsWK!Clg+8ER|b4$*4L~_W@lG9MP-|*8H_8~ z-XL$c1IPdlBxPeGHsdZA{t13H9SO9a9>|I0X84_#Ev&Q`-ZwBcTzv%*@2MD`eKdrf ze+s)7?C$xu{pX^dO5vmB|CIP|J^F%3(V0l}zj6(W=r^d;H?YDvA*;40&gBR)8<^a^ zb)ip=mN{?|8bM?wN(NZrf={%X?8F}aVQLI0;j$hx>hg5Xa1<2nSylag;Cv0Ti6SCSVO0txf!BM-6++upc(#4o}8F zWg-8GA;vFM@W8^FK67kKlU4b-I&(f7>``l2!58!3R=;f5ur_1Kw-VqKk~QbYHejVq z?)jz6)BXFv*ck<747Ey0V*}Q4mf&0kIWvlhVVvL162ar8=bX*6i#KI~YK4?L{td(Xq#c?w{g z#Okt%r(93FNuJ|}02_2BO!Fo;+o|Eyu6Z@Vskpqt(i4zOMba%~^MNV?ExZ?V2QHe)K6VITFAj;1e69j5{i2N6@ z9|>w-kF`LQx(svwH#s^7?mt9{@4ysrCGe>O)ex!fl#dH$SXB!uw7l-p?hb++^Dar8 zVRx%*q>MmlnhP@L>gJHr`-MdHk$;()nGB~%u0Jxf+{S1$7vvQ)l<1SpKRd3jjybSJ zfJ=-G7jFxPx$8YzbJ$&PSG)Y3G&~9EU9!Lod-F#}1~V=Ee!*b(f4?Zhc`{S7?FENn zf%A|uD7Jf~o;zb!wjg0Ge3AJ4+6acKSNmZXm9%G6T@LocNXnUrj)71+Y7cLAy;8EA zVm&S#o3e6zVU`YncVlq$Y+uGriwQhRiTm85QUnw8Z)XAyV1WovzxqZ|oq6*zJL~e|+ zUECia0nO&nqCz$zyq~=+n?FSF6ggejM970LmDPrcoKBO=IoxPq=om>pZG$L*btE6j z_k9ZOA;Rw43se&QT@QNZSXO7{R!rV6O+E(_&cIg2V-t(MyzCr}Xj~uK@dZ9ftGryC ztEHN={o2EZ#TzTnPdWnZpcVV;y{<=7w(x|g?R zLtK`Z0z_1ho5`3Danw4TfS-rCc@S0Ccw zptYaQmn>JCqoN^y^jM!Cs!519L3?dwdg zMfO+7A{Cuy*=sX%9VZ&7O!-8s5wgGrDGS`6SF0rLfQs<SwscU5Qo1jnp!UDfE0x+)dh*@EG0=63M3=T}*3l z*3`shMzJs}as7nL36H@mkP7gD^V+R#-+G^&M@*sBjN#(ie@VnL-L#3MQAD&j$RRw2PHRo-PAbzu`*EMeUaZOdi>W(CEj;-mN;Pe64b`2vo$~Uxh z8p?5SDDo0f96I{C7RVZC>E0|G#psI7lj1H=$A)hh_ZGxWN0JpwX8uZ%LPl=UMR8hm zNd2KuDb-=IG|ww7w+YD--0JjK0gW>iSIH7W;rRjcJxbxUkUnN}R#BEq)6>4E_~n8b zZZ6~igIbNrMa)D{oi04L0*r+A2eRbq_Py%bAEfSMzHWwd1Q9m>ucVDfC zhow;s1+M6JWGDR+v_oCbbv(6u11XT6yU^r@-NOs3J7YW$q})c8ww}BM=4U0xx4uwO zDiG5zS_AQ3?MhxaG_HybH`2*KB0O#hhl-D+;fSGwxm3k=O<+Awg%ylhn;os3fIcc3 zFm@jj%f|aI+UR>-a(i8@BY8YgvZqS9)#vh8wi|RLGAe}E;`~^5Z(w3V>Z$L9u-^_b z?;N_09$N}0+z_%#+c4)Aauv=`%aA3|I1Ta-S|A@qy-7iL)Ltc-XZZYj@91ONo}AA8 z(MgEq%#$J#(#p&3-dgYBuKV5o$c^2F@uE=LaAaib-`Vu6*nX=oo2N?a%~})XGma=3 zLV`e(hJK_B+Xm$J@{G142ZmB@)>RvO3j8iUe&+MoYrG61g1u4|Dnc$Hetj?4-19e@ zcA^VJ{@+<~_ie%BYXCUF$LG55y3@{%bmiqaSK9BQ(`uKydX{@d+ITb*ae#o@k}puk ztk^nyF;9t{YA>^s&bPFE;jeMG3>TL^iwPl&oY@ENjx-%Chg=-_c3&K=g!nz*B8GEL zcL^s~`1chl$>+<2<{y1i2?rr&Emq%0kAv6d&M@&HL9p+5rB zkjpB*&i#Yu_3oE`D37I#tz-w=X?d3olGKFd%7FiJ0EN;EFU-NR>DqPiy}zjM@xRu& zkF|a`*rXv;4o?z>N1M*G=8cq+h%+vgOCs)FM-Q!+l~m9cMYAZ>6E*clvQiB#D$sFW ztEs8c5w-~k3i4+;YBQ}f1jBIpl5>G#+4zu(SFt8T2xOF|tKuQg_JR6_akRrFC!J`i zJ%pw2AKnMnziM&vP$SMVy~ap7^^e-5Qv|Dh*TqKV3kKvoolQ;(;$b{PiP@ODo8IKl zlURT!&p8I|53c);P~9@m=c$*kigU{>&{SlsVg0Fdbv>sC{>5#agwFSMq9bt z`L?i;T{uh?+qxQD?^hvuu>}v}oapI7cqmynb86oY(Xt>wN1Ozn5Eem~M$4~b6ERttynbazIBwAmP5TlU zd|(Z?`#hLUu8qlR91F7^sby%1SuSp(i^i?YL8*F+4Ml3^y;$(o5FpD#wy`qQB_FU|Q9Fu_8hW+a*26UzL%h zOsE<^7z_9p*5{8KPU0>eVDH}Qw+_p=<}$iVV&_1JX9Th(o^S6lk34$9G>YzPyD~|p z%Vn_xqSsz}$hVnggtNz=49|9+AG<5Ish=2nWAfLpud9c6} zi99)IPXUn4#^v~1i4jT1szbN7^9 zwSM=sX{QQrxOdrjWIMK<2||k*^w>Q1VB@=Bek_0EDbLM}KK|{?hVkejAoA||Xfb!* z{op#E^cen>-PJA9{g}9NzfEz{adX|CR9#)2K+fNN{}*c{BBH2o%XTupm}w_{KriO! z?9hxM(ASyexWW zWJ5DF#K&)XYzN7z>Ry7DOK7$X)u1_c6OBTg$nY{o^RfH4EA3~z4@j|OYFExk$Xs=Z zER;%nj|hD6-X)W4IgV8xY-JtjLPcQA;CBFJ_5V7J8hXh05m5%aZBfAU$ zT@@pO2a=O=2X%G{tEkK4ZpISvR8~$SNgDjhKo~{k`j>+X5Gf=74V`tT)L}g&to-_k zr{0?`e!&3Yb}6e9pJ?M~(%>nHmQ|)Zk$1t<5;*Z*&P6=V_lNvDpd$w%8=DP1O>=9Z z^R~M^>jHE(x5`B=_=o6dfb~{!9c$z~Hp)j1J28Gro6dc8mtD8&am0G`oK1Mi*4zTO z`#Q9ffHX$Y?V67o^~i0^rD@e?@K5s&gZ*0v=6TDyk60WiP1{Op9M;k4#aRYB_H|tc z!ac(V+ z>jpq*O(yBwoHh-vV)dZ~M27Q(zBwyWJcK01)M=GEYK$8JCU8Y;7zhwVKd>)z$>xgzgqK^}mATdzDmSC zh-#gHfEE+#cOaLv#U_{ftr3dlLjDQD|klvnd&+clihxzWstjrsrm6WJt)cnz6vm0FO zY475~PIElubQ@3l@wDgw^m04DmA|pIw|BNTY~`9WTr4UkHp;q_7cZ(6?--Ua^bmKBXvxAF@LywI;QzJ?Opf95=4h9X(Q)a zo^i^gd&wM)Ik_~fbWjo=MQIvU=!}|`+mcJ~o#M`*(O=hiFwdHb&hvA0-0O0lwIdIp zqteS*!(Fp+%gkgYB_bgd;ZDR?CvsveqG3))sEnVt%E+M%OZ0ZrQS5C~mp0Z@M=Rgrp_wP$tPU#2s}rGjz$l7sk6 z6S6#hhI4uS%}c)JBi8@07ndwwT88CIt;d|8zt^twugdaW8DGM6%&U%zDmz7PAwI;v z&bc$vtHy*d;8!80 zatw>!KkGj(>kC1&Pipe9#{Y%BmIpWP*Z*y=-MuTD|F0Hc2Tx?#+S=OZ;_U{}ZzQYd ze#ctAHzJ$kxA-jK+SZkG_nY{11^Vt^Zrmt&OWqufevAis~br&6?k!6o)HUW{L3?PB;@K4&`0)6=Ot?^p$KP17+^Be&2=4KJy43V}L` zbJR&XhLJPpzRC}N?v8eeVoeQ#l?)Y0^ETM`sxuXHQ=7k|dg62sAxAra?#wXdas|87 zcCnkH0Pu#f0KNy?{B);lvRz#cVG$SXJ=78`pUCb*M5Mcos)P=p*Jo)7xibNa2LX-x zkpA+YTngwhY}eMP7i^4z$Rf%Qx5H^OU~x%@ni^gQ-XG-EV@RXhM1Z~@Vb))Y3#ZLFIUG8)=-ZGno|6OR`H{M z+4BU#iX$s8FAo9wrVuv$D^80(d@haY6Dq8PT|-Nh1*2az zHO)hhW)Qy$)d010bq%wsj=3zNp5x-?M^Z|y;c7?wFj`AytaA%p(oBjDTA8bo>8kCuyW%8 z*xWo5L(nX)-ofhZzU^6NV(xmlUa1O;&V*5lMbyXy9hSkXK zwMN>C_klRU7AmP}Ek)_?e`8ec0~vp@lre4AskxI{3+dLM(UAmK_tWKlvUXoF(m$$4>t0);Xx1J-p62px6$B;dIB5w9Z?Ve9 zFs+_^!CyFgteCOv_xrqly?NuA$TSMmcM~%Jn=<9UfOel;is1WeC^6ulfZrZJWO&pN zwwRD~zNS3I5y&8;Z)TWFC9`t#KQ#43-hs5t#Q6(Df!2+~<^L|Pm&ci-%*3Y~NqrDN zy1V-H*fN$?hYE56^`&=5AULZ=B^VY~de~;9&7o$}zGi8;Z1~n#|M?p%N}ZL&zOo zm_&i*PTB)JdBwl!a_4U|Cf6Tq7y9*jQvg{;LQvL!lyb6 zsbqKwZ`xKSa22(WguQaRCiE-;_-syb>D5y zZ#|rR7fb;1x~RK|AyhJ&nqNH^)fSjMtgZAZ?h7-eJpPK-p{ss}k``J;evnge_?Z;8 zh~&nc*zUw@MOD~z6lUrSh=>{0_(Lo);}}bC71rO0uP2Go!@zOOluCKL-N&=Ev?LL7 zez=!*Q8v!C67W#>UONmWyaDofUm*>8xK2PrLxaqFR=WH+ql+_f6#Y(%y6l6!c~y$^ zPhhJ56W<~}kHefP{dtYGwcZ~VB(OW5AeNw^^&VZ;Icm!0m_Fk6-$* z2k{jN)t;wu&SOdYrQEB4z+ivL%O+8q^jwGbes3?oAoTbzob;%lG_ZFjhR29aMEPT^ zAj{GG1b~3p`W8y)4t2hn^pkxSN#6Id#B9p};^%O0k0@4Po+hx2*X(<}j45@^0Mu2O7>?(3YcDsE&gNA1j7ec0zW`fp`E@Otv3kkcIBe&h|T6XPA6LFwO zvPqYNuT_`)Sk4P8FE?Jo!nYDh<xM7Bjq;6J^vFbj#_Q>0L@}B1*nV z!}^S_ngU&?f#-d@3sS-Fv4afT&gSI2S#efv?&KTzb7F?coU$~k>Y7#ho5)pXGC5r| zK$j_+h!Wm}vbX@)eaL`dD|~Hl&dAKHxcabM%%mR3BVPVHD5)7STd&0YztfN%i^I!; zql$?Wymh^W#v2}lMif!DB*~skav=u#^4cP|bl+JsI!5*7H+h6{EvQqH=2%ic7Plp+ z#k>MqS!*CA#F`cdxBzIDxa2%G@?V9A$H}9U^kCS6wFOxS4HzrR_4-}E@y0RK7$3X- z)1oApLlUgumD@i4?)7!Rv6k5@LjIpPk3tQ<{Mau$GaX6vhZ$&$Q6bg{+5A>}*8qSBND@jQX(wJSXQ~f82C;k2T#*r+{LXR=k<>@Z z9H_^WGc9U!G!hy%=;Zg*OcJUA?=u8n&srOexq3n*MV}~`o4>*}+KyB|WLF9w^&OD^ zknu)}My)^%6-Nk3<&?>BcdrH!*ps{QcM$0H&Ac{aWa^*l$#L1tYxDzpozg+y!fA6$(XCy8qW7|N?baa%>V1`MY54#($ z(sJj6W=)XHC6<$`F8v7OYJrG5nrd)>@L$RpSFI_lq3sO0A&%UwO7H;~%;RWPwASe0 zxIVe|SMF<(EBxxfx%6eX+kfxya0y<^M<@uY5d&)CY+s-@xcj+%7*qLi^~SeiZQY|; zO!u9Z;oQ7iTx+&6qz}bD2CYEiE5BgHL8kfK)u+E-^1jXax^Z3?^bMy$?C=^>ueY%R zr+p593C&FxqWMHAJ57pfHTREgja;sF;-Ov_SoE;_(8RW;wadl%u@%gY*D`|qUd6RZ zYRv7u@3VUZT&sd@xp;(yi8Qt+BxC*w$o8OkWei2p#sN64etFZ!crXOMIiUMpWOr;! zL&i&Msd9Gq&G~3(`zy30H-fG~Tx`#oh)~+G{QUs&KU$v$n=FA=dY!klot z?*0O~I)7q?Jg(%StGeaz791}8e+>=V8BiOEp}7{r`Xs;6z#CqZgwl?CYi_pOoiont zsFS)|7{_`>0tK&mK~g=>+s?0P@lXs8Ii@K}g2-0g?$CwN8gSEKRcE&*c1odH$BYqw z!AacG!|6P>O>#F+k}*(EKt(QW2hPYl@$3rnpxuYgXJ_l{&z#^KR4*EjR#(rGW*#tW zYH}GqIl}QeUolZKppR@VBL@*XBfbh37gW3d3Qf4eLg1i;f%WtAb3!8y5*J8Iz7DRm zvs?ggPj5N?v=he%4!g(%jA;g|Lw^owDJr}12tHl?;h^QNo`(mx=Z&`qL`tm7KTqer z=t;Wr+KqBA(Ja`iTzDx_wqGqa{% zDF!60;Vpuei8wqxljna~AK{i1mkN2joljbRK6}!n;sPE$P)i4TdIos6_-ghJdI-~ydm~YYUarwBs zj5L_w(b4vzvvkW~OL>AM72LSTov*VkA^mC{ZcufW zJ(*{^!`IZ##ECX=ZtR(-m)C&(d&&fnr6n?L6?+uEi#&cvttc;V3Vuaxj#$S>-vhdb z6571lgyfkN#49mtlgXP-k5WbfLk23rsDc(fJ1!Na{w25@a=~KM(aVxIS8N#K9C#|0 zGNj@&WA#yscYBVVZ)XpJJZ2AMXe^GKK>9aN_h>I`6W)9zBL*!z))neV%#=&{@n*LABeba_=N-2j=c(OhNIvJ>z38}5UWoYOohibk{hTLJQggE>O>4Mg4daOn zpv=0-P!g5@3jYn7sgiXE18*6=vU;6vKQ>un;g-415j~5FVl(w8lvkpGl{OlT3Q=G12H=ZI5zqQ#mEO+Q8TB?645)1Hfg zW1dQwnZ=C05i#uDKRg*6?>fWRTu2f(OI9*e+-pvNAM;wV1i9oFn+mpoevBdP7Gs9c z38P#swH6sd<70sYc?g8R{b?x?(YJzl3mT8c_Ft!5J|0Tn^*+kty=02NVD=blcB8Id zO~F*UW?C2&Yn;|(bsPo$JpNL$Sg<$xJhV4t&f1VDFSnbbWv85)%c?tU<%LFCO6~yq zbd|$zX=`IYjlPIJ;hB@Q5ykSR|6p4~DiwX@k?akDWfn_OvIojy-PfqODD9(T#QDTh zSMbAfr=j%oZCcs**Tp-{<@@D_@$cWSdrlq)bJc_Aui((4zRKa5>f+)z;oQiNO@ zpHNmSpw|OO#_DTL#YZP3Kp84x_Wt|F_r{7$L$ju>tGi7k$}ml`!7sRQ=s^Ro`bR)r=abfIK&u#KimBBh5>mF z?qDgkt}iP7@#&emqp_X8J#goAcl+ln+^?<*`4u@o{ghjKt|v7pn6`9A_m5pw`qwV? ze3|*sMyqSzo3NJ87~s7TZ?%~nXS4dNGCINh1B}84dc}a@=^mudoZ7P@B}R$-?c-R^ zg-kjUc>k~Q=Xw~3(?-wq8zH|P6lh*TEbQn@9sRxZ6E$D;kUq)`hzLE2G0I#YYH99! zl?-XE*~1_X6T4sMi6KZ%MOc2rhX_%B*Unx!8s(dr<*%=AuCFWOS-u{<|4#0x(jTXc z1H@(Gfs&MGp9DSjU0k6JHxiQXT2N13gNt-vST@(te`jUS!Q<#l%JCElxQn)83M#CB9(81sDNQl3b@ zKw1Ue87mzQEAuZ0fzRlzY#>ldDfP0nurMDBQSKkAH=>G5IvzplLJe~}{&DGlZgCj( zuvi8KVq);B1w_9_`O{WTRMNX~WC0IbE`QN~i3iXP+NtT&bKu``JXrH1l3S}$>3-{P zBL*zf5$Sx!r5tLQK5S?z|4F(fxMjzv+JGC!|9N6wJC70eB^eU6SZ(hzP2%PI$1`P& z%a@Rvvf!=z&aoHRe>Wy=3UbxfZURawptLZpHmndljnb6z_X~MGyAxd~{mxC&v(+Y^ zlo{aff4Aht-F5ogP=_r+sKjrB&<@k!OIjE&q?b6^X}8{G!D=WBiQ}8n?QIx1by4vl zVZd3c#%)C`Pf%Ul?IuH2BQDO%4AicgBS;gnHBVXsMtH!nYgRBP9sIeecnEEJ_+ugY z^fqm&-LEf?S#>X#9j+Ed^o>OI%bmAu#+Pi2!_+*E{l(bcSehU{U4BNbvA#hX%Iswo zu$a!eQg2$nPzFPCQZTxAB9!>sPaCLY(j|w%kL-baO8NMrn_2wUBWyONA*Un?U2T0% zHcOA%(ADG66X}P13GDgvo6ytiz2Sj>JHY34=wkO|le)et)+9D_i`r)%+t<7j^n{z~ z3fIiU9)8o}Uvf3v*}D*#wdl9(Edi5_QT=h%2KphQGN{O`JEc+;9BRT;>z+e#|vYe?}_CI+RKbhdMPxW=BIvU%#%DpjnwBtkz=VSbkN65MtpcV%FWQD(z zrw#Gkwi1SQMd+iT!w8@OZ?JY?#LBBjvqecfZ7N;A_k=W=MN0PF$=^qNv zfmSU|c{50*!TQwET?a9>3)j1fJ`IZF*=w>&5l_7O?+{&GMN5vy?WHWtE?7Kou;Qq>^SmPnYcY73!m{dDnnk zMvJ$hkQ)5iCIww#MgiVWX`SuVh9%O<&J;?`8y8!y_&0DkkeMXBwe9RzbF6K!j=rxc zk?prJMay)J9xRNGQg16@LArsJhIh*WNEVHwLtak|hxc`QW@M1?#V#Sc%;&+eMmpgH z{KtRgqUxd-xj25s{=I9qM5GZ(Cip(EA&iYgQQk{;ihtU%R>gU~j`@>pD_M+g{jS@h zj5P<;V+TYPcor#LFd*Czj~j^aM*7XVznC?wOqY=p*3s^++}5sUw_`0OE)FxOXnPyI zgy-MN-`!zqW?Jn-QYMU>K^?jjayromg4MJ?pVuREktWD5av*~98cXv9K~=ytCmdP@ zrMjg`GF<2fCb}YJ-nmEy)MPp5cwYX|g*KP{t@_S~CFtExB_g$V3Tr6Dac#sY)480q3zqv{?oO$ommz8dcn!>X< zm??%4F?w`Q{-q#CgGuPN6~Kq@@6!U2D>VvNR}15pNTS`<- zC}uKqa->PzpRVo$O}Sz)0?$^=%

ZvSy!_A!Rp6@1`0QHfU)uK#n5+ji zv9PCqcqFe%hHxK$V_ArbNMPrpnJ#PDq5P`< zb53r0zbsI}N%=z&7}w0OOs>D`GsLS*iy+<+YHU_?g0$r4(dtWNm>IDhLs~ZcZnFad zv45LkazIXSF;))`A)Xua2_YAO&9=4VA368Vj{8?*wKGjOzVSgcOKGo;8BnJKSMP?J zB~aPj3!+>>(5+{P=d(dG_lvra_j<18gjiMPTRXinTlFt=v+gEFqObUDla)YBPhR(8 z2F0JVMhiQDbDpj|8M{OI{x_1AmJ7EJK}!q-ngdRHpF5bbCU-qOecy#9{}B@dP`+m_ zu;p>Cbx5$t%719Aat#NK62AM2G-iDgr%u(WiH1IaqBkn>K8o>6+{e?QacZ0oEOg)P z;q1L;KpRcEfo4~|k4+e8>@`gSG@r}fJzT~2EA7|;>5yoVcgRVN176-U3TXQJ9Nd8S zBaDM5|MmWa7r+#q@}=8MTM|b;_50BA<-h?nCtOICH#g-UVVM>4d*wMz>Qf-NW24Ea z-9fdu*g~g=_vz*B;qCk$y@U~$1!Y*~v6KZ2q{Ruu7@>sV^J9@4savhit@9^E_xtgq zazzXC%>8~I0C5Vt9UdQ#A|Tt*#~6tJ;xyFSPWDGf^I~(NFb>itCe~hRo!2Zj-rdJr zucO8^*wWL?1}r4#^m|Ik#of#6(-n!kqmNHjMQcL}xrMJqUsDb;aBNbQYuQNmD0QgN zWxXX5|MqggW38dDk0K|Fwo2=~Ad_7OvILVR4y>-tB^GJ7QI6!W`1?YNu2c`)a98Vn?sSC7o>XquSEe6Mn>FiLx-3VPF= zf)ooJRspv>8^6E*+mCX=b;WM-(Z$5+;OH~S^8J`2Nxzy7omUJ$VnI%5^q<*Dkyxm`gDXqW^6NRPI7&-?93IrUqFD4zAX>8 zQHCgV2So-_4U@zh){CiF)@?G;DY7mX*8qHWf%+aiMffiYsV}xHIw}h8xRzv&Kc*L; zmu(%t2TN2o6`=gL!%?KOSfGmP9!%<36u3Wfw!>FDDG$M6;mL$P(o>N31JFYt-=bjr(Hl~WnsSc-mJV;f*3Tdnxj7dtG- z|BZ#@ORG*A4Tfpck`l7 zOXTJ7CQer4T#@n8$EEdIE1LVHx_izkk>_XsF%ys4Xa8J+1*33UT~gJ4%fBS*EIUfP zqcq6k%@2wp8bd2Z`eT1GRg>J^%3RTT*-#zR`4rmm=jH0C&*Z4Jt9|O`0&g6bnG^e4 zatQk~x0m%rTN6V-EpxE+NgI4a7lBo7G^nCOhTN7P)*azhhEE&Je=;jTD>w)q#ENVw zY@%g{#FS{I@wA|TLAdvO}#A9!Hz#_MDU0lK-(H@WD>5KJ~!T`Y$; zUft5T3mqO4)N|_*wf`a+s*0v9CO0d$4 zS3-ZTx{vxSLQY<8y~6a5ghP%>?kZaYZ@}v0z4#RvDblC z(t7XWgGS>bQ}m6pTC1HXY<41*zsWEVhfK<$#9ERKYHBB*!Jp;IVNb3_zZT`_?JycV#~8wz>q0hq3m=mj*wQ>1e(#kv~=MUnDLun9mq=g#mEcfgL7ZJ01~g8Z2w4 zmextJ73wM=9!YDG0y#_FaQNkmFvY>=7P>5Qmejmgvvh$4r7VyhOQMbl@))?oU%Z0# zHE3c78Eu)~^&`*@nb%=I0}qPtFZE}9M=uG*v}I*qFCX99v- z{~GH>hg>=m#u2mD^$&mKo3gjIt4y6!JbQS2<+qNj2bK_m2x=Z^f1V z{EV5%{gVbG;UWIR_E(tHi`@*%r;IfQbB?1Y+on{^wAxGhiyrSSThiDc0-8I!&sBf< zkSBOHAyZS-kEi0&cdMM6R+YqnA0S5^El%Y;9ToW^Ql5V*UC*1Bkx~74s3c_OEf3#P zTv9ZHs!iF__V8gV>6#1U-2${f9w+d+pC)2fKJ_{?8GRJ`)l1BwRDNqEIa~Nmse`3v z^H#NK?+uYDk`J~R0|9{J@#rLo=c8VMgx@tq_j7>gyNwaZWHLBhJ)6buQz?(ipWaV& zz>M_Y6fUK|t#goCfclNJy4Ls}U=*6wN+~-6Hx9e1m}w*a8{;ij^Ca=CIIvh=Q~x1? zLwEE%;=zCzE5k7{%5wC};|;&XNEBAzGRuIl719ZECl!WwHgMh|0$I6~eu>v5*Ag-^ zIW96)yhYx%`!usD(6IOTuj1i^vlK@WG;*t+~q_bFPZ1 zxwvXvDXC@=F9U~vP@v!+fLKl+MSXjXln7|eC2A_LjoLbZtAOJ!{I;lB#1=;_G7l6f z5tsclJ{dznR?qZZi4t~husCm0wjK)@y!!zK={rP>4o~S14QYMP8`tfzFrJv{DCn!k zFZUeyE=H3LEAMQ;mhQ_k1;6hsrL2llQloZK0qDP2fUyj6CXD;L_pWb8ZK?caj#G}4 zlux(9)LsM9SW~kU#D8iMTuIFf@7f;9f)4xE(7(95Sjg3vunl9g=l+MWHDXm|rLR z;-4$q*3AB-RWl3O&~035a-s5+-n^PX&=>GFaq;f`=)#XTq@)M5cKjAKfr8_Xu1u^^ zM7+;=Gv(l|!9;kzzj(p8E7dz87cw6RmjEuNahPOv>znu=xL! zpC<-*FjP~x*howTaEiikyIM^1^BiHh_!0Aps`kp@-i^!TCmmH(%%uHE3O#>b zr0#mjP-vL_p%W(n9jhcP*HK|*B*86iEHs93&rHN;$*uOMj=CR=<#KmFDzx62hK>u& z`wNq7?}dn*btqT7@eks~qY8RVyIE0rLy|B!IvdQ2^eMdj_0MzGW@m4vXl{@9W-NjQ zC|PFE1g90+2%v{yS^YVUlO1os6uzkL-U9BUHOMl z|MDDJSI549l2$KWbRtzS5ZAi8$8-jy@{PyICbPxlYysz+$_%pzu)_FpJ1nY$L68Z$m4Xkb{u??}0w(N%fB}I`{1%)}Jrke(ZTpbqAKIc~@&iif7%3+vJ5Nm)vM$bfEm? z>lO$)QJm7De*E6>XSm2{kpr(XpP`p8KLP9B!iJPo(>~4R2gQDrx1JWxEGSGW*f*); zW?>}SsrVjmFw}?ZnO`YEF=;4RHPHK0(;a!Z%8#o{>)vfo66{b;EDub{YpsVrt@X&c=xjmY~s{9BHSHV3~~##utA6*N4)uXQ`l)ThUkE;0LF0nRNc<#b_m zM2cuXjctefMn4b{JUMM^nAgv|6Z&RJ0(d{bBc|{^>HHn?5AfThKDzhCrMl}zqM%PU zRh>3GZ9`W@Go-Q>d1r2iW8TgFOnc|i!RG*DyK zxN*yn5oU``Rj!rWo;q}Nd%1}pfH=GIk9FI9FqezX`e1D{_G%rynrZ`Tv>G4wr3*uT zL=>5vhJbg(5eTf22+WRM5eeLAkPI=BeqKHgq^9b8`Dkb13xR1^*u<9&tBs~+&8ZO? zrqpHV)2Ah5jlMC+Yam)=HJD1Z)L+X8Z=SWZ-y6O5)~Y;*}{nG=x?p!hDIM&Rg|tCfe1c68>yxKjXugMA|!ii zyCZx}#K>DIRyo7GNK^0 z__bY>gic`(GWy<8u#ie&WlvOn8H^|TO#x|U3(dO`$_Vi=KQ_^AiPaqg6jSrx5gjb8&N}|;glxK4O!`eVKr$ltcoOGJ$Jf3zR958QhW4!| zX>pm~lFG;zjbnpV1`3D66yFOaes54VAYO=JHKD>KpbDo^XfKP}OpwLRmI(0X%#*_Q z?j8EQr<{f2wzXTG4$JhMfP?40o`)8IL1s@IVoyaXRM5q(%4eMwSV7*=XOUvk34m~Z z(lC`H2;S_nyr|kIQvni_q$f$7U%}D z5YC+tbxRWTA|IXDxM8!U7~XhQ1zZIfZi~2|u7QXHcj(`IF_Qty<1bg31ybu>AEbAu zC0V|;WTdm?IEN7l()|X#o3j_8sFw=3Jw5X6LjDDSc6{dsmV;Z11B{2SxVf{0L)*wb z%nXHZl6IFwncnC?porQFp`kEW|C+9e4`mE?L$zg3St7O#%8CB*&`dC`8Qp$TO z4*%wW$lm7->w6+&!T6CxJ5I(w?AH6-z~QvM#in=X$zER_ zVG>4lG2(IzuD?OwqVwpdzha2m)kby*f7#(k?WB&bEJfO03O46lg07aDm;^xAd5eJ4 zk`x>v!aZu+#D(WF7O<=3V+{jwX>nnQ-VAOH*d%htg`zt)rExd8q5}S3%X>V^QKU_W>I-8#4o$zS5vc8jU>T94T)m%avBkrQA)W$iG`}%}@n2Zmm8q12 z!T6F{jv}?wc|X?hIYgLHsKi|3Fw{(kNP9-#SGv;U(53GN#6(0oG_1)_o}$DusBEdE ztrG9+KYsZXO7_iluD>j1vV?&kTQT288Q+=>YVK~$B~%?7m!q?jV8vvegl>bK4UWG5 z5nImmk-Qh9nj|TXkVr^u#GP~fUD}QNCdM)B{ENcD^kD8FZW5aU^^uv>J!RaS#6Q~< zkAd)5dTG}w2TYB1*7ed`jd1kV0{qpiC~A%2pLL(T;;8uBx*in6&2Sk~Mh;7-w?3-> zWO{-;-7%+rXYzNNsNRM;x6ZY;bif?Eghty#%y3l&C*uiiU&SiPjY7Xr9+v{-{tr#(+!y)#{{6JsZsShajLmMtZrn|i zjmfs#Y}>}<+HBW0Y13xgc3t!NKCa(ia|h;ppXYJB@WgH4E4P%c{>Pnx6qnH9aanS7 zu{2t7e)gUg_O>Xu?znMGwBE9~E^>f5Tc4h;xf$onQc*!O1djl6CALN#jX2@@!mHk* zrIS3+>u9`N)<2s4b?C$TUv7#BKo;!KH#qFehp5S%&7Gh&iom{-J$O3x!eeAF&nab3 zcHxKLYvExOBHj;ylrNi?Go@b7Hs*fHvV=>Yu||yLg&3OXp04{=iSF)Fnr+Eh++0D| zZ8pJUHVpl*mU9>qYQuAb$?$zyM{PFLgHf=KrGc-(B&LNG6-k_`@h)7%KdV>DS*9=V zme(IQ`p*%Tzi<}8iy?JtS#&702rnz0Rd>hz055#D0xeMWdjIAEG z$;z~pIV}EW8)i5=b|DX{$XNga;SWN)z?N>LZ92sQDHW{^(z>)YCS9D%|0x7)i2GW5 z9V5%*N0XLxGV1o#HXos*n}L;}UxSnGKkoeM{{(gIjt@yO{VTIB%UpXrJ6TRVZsb@0 zU=E1(iOkIQ?a5XXR&3cIIN^4@JrUWib~xzc(7wfO*L}sx_<68`7)bxrpcCVE_L4nvl>xTC;MAy6;eIL1(6tY`F!r{_(IT z$D#?W%i*xvmjuL%S94OCluYq5Ieubhmuc*aX9Q=oSw37X9?m@vBe8YDf&h%HcD3c{ z?HK)Yb70v%hF0x~^e`F}F%bK>0|Q4(H6tar7e1>b%voOnNFsNS%XLywwI#^)zM6E4 zVytfm{r-P9rI9`BEVn=JlkZrougHI<^#6O5iirN7)^I%**&I|{ojE1SA*Z60oREGi z-=CK+nvnEwWp)0Tm3@3-q8^Nwn#K@=oMs^WsUB53f`Bb9R zh+gcr=(BJq2XVNrrjzVskCv)?DKu9O#MY+n6r{XY+rCwR+l)Ocs=I&xx&FFalnVv!)2nO&4+xPVA$M1L_XYsELe5(#X7UMkdn@#1U<^%-!H(W857gcq9SOueUJfe zme}JO5-NU*#;04b0@RCJqev!kdr6KEA@1N?h|%XX%M3~9v1cyQ*xg|8{;j+Wu9Z)- zuxo7ZSn*lZe-gYBJU{D38gABm*;|} zTR`0BZ&Gv-S~fa~A}A^1maXN~7u$)q-zjzXfV2%ymZlJ9+{o{S`QBv7Iyk1gnRg(K{ zGN1lFHBwRs#S;Vryo>=A392$68?=WhtiYwYwi#>VI#^sZ+7Jd#?F|>=Snl}UDeS&S z4dB%q($7h@knF)i{r5keb*j@06AGKt(q8T5<=3?n$Dx0nl}Tu+WhG^ck~ZzD#UE2v z5@^gpGZ9KSzbd%rM%0PM&qQ!a!KmcMy6T`G5ZqIwOW(u+;XhnRN2uevFS1l%T+Osz zL^BX)6&QTZ>3~(#1}+q9wy< zt_iJQ|4vs|g*pg!|8{38R+YIbSC1mmO!t`o&9G}YC4^4<1(jkZN9qrjYphyVhbwwWlVZGJ`qPxIQLRYtf1b7pL71i18TO%2}6*LS#DM;zW2= zKzV5%OUGrR<5rbRl# z*CCjt?xB6t-{s}mhtfJYyYd2919~61$#}BS+%i9&u%lL1=a(Ipb_B70$XYIQbT^?a zoIlaJz>aqPvvpw{QQcp_ca1&8ANEzgHr_TWXE5MssBnlGP~urkHE8dsc=`6@wrcmq zV$g5saE5>0rqNiW=Gd!Ktu&jDhaY5EotVTvPi2BG8Pr*P&Jr4^>vtvpq!$9~&(nBH zX|x8DmxaO8wFf{i3NVm0|Cqj;9~;$RW#%`tNP?e|ULXuR!2IdBf0kNyz*8Yxoe&=f z_UO;Am!WF^xSFWs;16mss{y?hmrtWsR2>d?L+wcCUoPLDws`e5y4|f@o`;@>-sUK9 z#P7BS^JO7B2<8?)!(h(qQ;a@swtc~c=3XUtun9}T{*vA-HF_$*AifN0Q~JCk`9Xb* z*isY7PDpwJ*m}FfAC9y^-;4U(u#%xSQDL%2QSBdG zoUIa_ot!rDV#X}-!}mWf&NQ!kTs&MRj@>>5-cxkE4WY4hx$p1X)N9{EPo=2$v&8Dj zmNT&;5H9bu;munb2y(*4w{w zljqDCyN>&7o%_1?xgx7RXY+55i;szB!}p>degeu4;T4O!rhXoa>ZLk2e{4ek&kMj? zPRRdHzg8L-`6Y+n!me3?_97raJ9Cv{ixQaXA7pdmI>|8W}kNj9OIT zIl`E(5PAq|!F}xdXKD?tq()hm)gF4ry#!?p&UTG=@{aQ{}dCzck^&TMJK46Tt!A>z)!HxQ(umGD&0 zG3Pr=c&a}^qyiO(Tzp2FpeZAmCgZAR&O4%UOEK;f7@gX%YyeT}f)L#xc7eE^EyML) z6@lG#Tv7^Q6IE&pzr!3sq2sIOk!kLbIAH6npIv^Q8KA6U2+L`6waQ_!h+54QWD#`< z$l#+o@hpmuO%DDsz+7ynG;R@bOZg~m5*g2)^-C#@u>C9G2d)60BcIgK>nuGl<3NBb zZiBrnP|^XzM_nHD6}T18@XLU|JrJ*7==bN%ekbB6bVW`O-4?J(Zf<4{Q02`ED$QBk;Y+1{tGz)#@$>-c8dh( z-*~i5U%B`RGBxNE3@i!v-CDi@PMW5_u)nI)1gfNAnIz6;(#$z*Y^CDY2BAg%aWp4< z99|Q0vWbB{;J|#QmJE&~c9cdI1}1lOtMwu{mAW(L+>Yov;GP!qD%6gm*Yu2o4_w(y8rT4{r z_VP2p=qcaA#{-DB&_pXGSMeqznfCOtJ3#;ZTKE0Hc`LxwK29%_xn?~Gr#+G%8vWB z;eBe_1Wk1j%O5Hm~TAgn*QDIxqi2iY;5b^*C3#u@rdL5cIZzLpYxp-ZMXel_0Q9M z944fWe${t3*4(gy^hI0Ryl!CC@eD0Sx+%*}kxmT`rQeFG$>vSfl(wrY!NwybdC$2b z@NtYKEj4@0;Uv?FhsjhNZ{w72gY0EtFGPOlOzrJX6uOP^zJuk;n@ybrZV!f?uAF1= z$Hm$qt*%V>1a-x&i*Y^n)b1FmyJv%n*y*^CP*;v^Y6(X#xL`g1Xzs!~m_BQG;_Mi+}w;bLz#I^pTOD_p?A6nwVbpM4b z{(&w1V0wt}jUYlf7|nqmH^BbKhddOUv?OR*dY@#;KtVwQ73fo0xi*3^KTfbL987x% z@i;`h_S;PRipd5wx|JHwQ*a=DLRcA+6aFEAtj=HjF=2|Da!@^4df2inQOW52H-`zH z^!pE7X$qviyq}wm&R((4BtJ3RtUyeq- zU2p)LuE*x>UCXL|n&jf8r1nDmxi2x?k5Q;U8}Gy>`{t+&${d z*I)i_E@rb$?hBs#J)A&SN28uT9c|uU7EAL(3KWdFNd?;9N5emYBkogf9nBoPUHMr) z(al?TGKL<=wty3mS3By^sAxZW0-c=jwv=xbcXVNUzn^q<<`4=+DAclG=snbNlTMh5Z630qO}16JUlV`3px5jB815= zu+Ey8J<7vSn>Z7fYbuJ~a3n=q)|#hX>dv=$$uTl)KWm$4-vbbtgrUuuu~#4jvk1K3 ztBQzn{{qg@eV!^8kPA-yPg_Z9i`6Q9V-=_mfdW99q1G zQoTP|CEE7)GeLn`TTfrDQy>AL-Xh?xmpxd|;b9Khu!t*nhgH=n+m+AKEGdw4q`X$> zzP8ihv6(h3lHPD35?S1t{|tO@E^xM#Kr9sbxhN$38apsALqV=UG)N+8pO7VmLO8a# z7^nTqh=y{>H%May-jKMGiyH2nWZJO9KY{+KST?Skl_-57i}fEbC0y#E4Z|@r{b#Ke zZ|P&+2nI{>DMIB&)GYtX^YH0|P$v3-QU@P0hf0%Gzd^iw1mqDo3mK??L~EoC7NY*v zb7skRRQdan*ho=jIlDPK09`9_Btm9-h2aT*6awFuLZDGWT)2h7pQ+8o*_N4^xyVFR z1LJf7*TyJR86zR)$_IB$Te*3cv$dzsCl~=eIR7N`S3mYeXXt0-LdgUEJd!q4kxEF z7t9T@OJ(;g_xJ>|ccKjtNHheeU*zl0e42QD-Mr?B#0eujbxYr>JF-hy-U?GuiJHdP zb!%ql^DJoh`qyeQcU8n|cb7=!Ayvd}|Ls-V?{UbB()VH~@V-0p$h#6pcbAEtD$3#a zb>!*eV3QRtFT|hL-|!;KDbtjje&)Oorcy$ml zO*(D17b=H?&__KgWAkWaxQCYs0i%ZH7O^py+k{+u)+s1i391*-Ed=hYO&S2%Xc%^t zX5Awyj`EK%+*sa3{_dTN1s_6SZI}|o6gdrJDB=vsLc1u3;=`8c2%5QZ?)C;=Pxu#d zoP2b$tn74GpauA+`)02HwTHcIZB)^nNXZj`T6>|WOv1+jKs8~|!OhLi%?*NB_iDA8 zl?t21PEZ#mPv+azR@-5Q=0f(WfE5ivtWI=RDLGCd<*|H}eaeGs1HAm!32ojgj&CP2 z5R~ALqa{(R~Z{dL*u!rI|xv7Dk}TNYT;6xJli1q2KGLt6PMUIHV(zB_=CpF03hI` zs+$ez2uRvskeMpFLa21?96b+<%W)7cMi#=QT(~*T$gukmjX?KX+@vGSH;k{Yyp^A$ zxJ-o0mHt<7nT3G=Y(1E;>oY?HTk{ab4s`?j_vjfM?ZYA$?<1K-+;kYxZye6zAF7Rl$yJB{|v^9OH= z@5xrHcFhC$WA!@RSE+1zbW;_nHF^-X+=(3T`<-P`YrhAkRA>w`IWiR%7pG-EOJV~A z6N!xGs-#a*jDh&wN7y}h!tTxB^{t&$=I?}_^kH?NlPl8FkWP=Ol*imIf0@n)CvDc$ zU;k)O61fz#$XI2sQn&0K_;M**jt)7xAIcw*C_7%qn|&W%p}%J9K85RB&2O8c!tJk> z?8qUr1eop!}3k|GQpI@OL2jQDWKZJH?pn%keafS&oxmx=bDu`%u6lxIqkXxKZY z;U{gz0H;5xNRWmM$-en`I$-9VhrS>BJ-(*uKV6OGwz;_SV3&=M9v^qwXcdXK{X?+- zg$>1gkJN`J!Trlh4wGIX$HhRmJo+JNtj0+2d(h5&-g3ftB7f=eS#?9aDXBYB)!H1t}B1ZfH zHG`cpIJgmQE>;R^kfm8_^lYnXRS!VR{PuOcCT=-imOB3{^!x8f?i<>o{+Hr__ImB_ zBiemns@tN5#Y-#V+L2PjajMozwv;Vg^v+TK7-C4=pst_8{)-;VgBu*?+)yo3o;iL@ zSjm?h6;V~)Q}Wk90}^$q)}@YR2$TEA2qqvg8A+QPcm6Z(PKA55>sH1TO;EH_V6#-7 zARYt)u9$Y4);9gDA(SB5CYaK2T~VF{XyqTr_CkujWnYx;^)zvEtr=R#f9DQ0nP}mispVc{Ph>K6TKrZ@d6LzVMvWk|0Y{7Rv;A zi*9fuDXOW0fgbo?9F(?Yk1x1`u!5`y}w4!2jfDWO`j!X-Q6jKXR{xg zcn(hk02xs6l(fm8L?+D+?@o!Dt$Ke2R01p*9$J6%i`CSE@5v z{55i*hak{7x(Io;xlro+obC!X=RR(wio7qsj}Gd0)ybc7LWK%E96+1bKAwjLPgNAi zKtv$R?%7u`Lrl?tkj|VtW{K--BSK-pS6IV`aBo(axY=?`1TPoP8*OJ!X3W@nxB?XA z#grghG=Jngm3s9@0Zoja^Vc!E-&Nj^W4Uj|KWDPF-F#mw*gEc(uKg~dl$Oa!QSYl) zX%akEa=hr;qTj351fRZGk{~Aa4R9=Pe`eyg%J`kuc&$0({I?Mk9xXi@BFzT7!Mwah~ z$fMGJ7c9Yc_~FyAS&iA?77)~i3e;z0hN2OdyGoU55@2Gx5NF~wk18U9f{8sK4zX2( zB(|7_m>-M5R7Qq#WXf?-W%8o74e}zKuvcfYo%@BE=xIcsKV4z4R zuL&s4jq>;PKB0iA1=yB*Q)Jvms$J_9t6~&T%pc;pqj13 zZSwjJgsnIrPk(tg&?gB(Mf;8q)1tL2r?jswh$hjpQ#>{)+_x(?@+vtBDPTq?bRQRk zTn=LV_%U#@Hy|_^kbk!#b+2n^2C+qq+tcCZmOPW6{-@rmC_~BgvHG8RGBqi(ttcs9Y@~=7UhU^im&;jp=-@MmhJT(~|ar>}(L85A`95Tq9-e&cMy5l6Asb)b> zvk}JCeM~J4&_dIQ^H1_ zGcwb|L5c+2QpqaM>n6h>{tv=siKKzB_rtVT@pVn@2dQ=~j|q$<_j;DWCme}_v>(hY7T1oKK2OO0K^+|oD=G003r`|=Zum?BM%SrtMQ4cep{rSDS z!@b!GN7`yC&Q>iJubT)l7W^dsn&)3l%Q)8kbME%FVG?Z}9b995yX7RwV$O@boAf3sE{9E$BaeMGDn8n4^kGD2fBDw0EwLc?fi z^GJ{+;LxD(Xpg5GM>4NLjd-;S<{(?EAf7Vf3he64iwZtGqEI9-*n`}U6h%KW&=>|x zw?U<&$+eCQR%hws7-y7G1xhO7)>;!^MB910o!sJK*{*ka-7gBd#dhEQwN&tXvBOl) z+^zN5_iPL?oG+d&X|gcj$v8|K=4hzx>9GctkodF58h5F+>s8I!^Vz9v%@!5*ljPYj z8KCK&K0aQ(c#}g~$fCsjZ}*O}-J0Fb*K9L?r{z{yglpb>1u8Eq3w4Bvq!)Fh8=O(q z2Byi&=@x3mv@^-leHuplJ_nsV&%^kHWCr$Fb=J6**y3+C@m#5~9o6swI%mIc_l$QS z%s8pMdt{gnM)d_~)SSHPyrkbhSRi=$JRERfKULjbm^*CmZYRi^*%obZXasH1PBe}= z{)bdon7D4NdMA9sm!h%b~qxZq{xNGKc*04OJgqkz`c0pY( z6bc(@cRQ!C$e{TZ3HKQXCu;>=>FjJGQE^bNLN~3|we#vsb&jd-R{grZlh+L^A1H)U z|1pdAiI2t?2jP>jBCgN^^rS^lI}u$9DCIrZxJ6)Z+y-9|ckc40&UR?->_)BJJD`dMhJ3LF;26>5aM zhv}NboC>503e);bmv_J!rZZ;^AdI7twkU`Or)#P7a6?r_=Jq3k2IJkZGAX z?AFRVnbgr*%+9Ukn_`F=Y0Dog#m&swFTDN`W=sFTT>h=|>$Q3Q2j@(KEx4Xph1(4$T@MrXJ#D0qPQ6W3SA#6)nol4t^3(LJp669UyU*41=Lx8Y zX!f()>uJ^P{PiNWy1QlXwqfiU*@RH5LnB%h){>a#*XN(UH)mezuRXe6vXJwa1EjrI zP$vQacMKgxTDQ5y>ArV#depj!Pe7pWx1ubK&S>gqx~Mjaq3^M|0UXa|R#4$QlV*Gn z2z9})B9Slf+#EG&RVm9tZuH;P-&?V19%qKJXh-{pV<|*CJ3Oe{aasvtq@uV(tt9ic zRsPLaEt`#*Vi_E`GX{Y(D|Yd{3J6)?`&k=QJLEc0YQ-bvfM^*S!3JhQb9# zH+&6a>L?*mQZT<2;Cob2a2J?O!UquGID@&EI_i>bL&M3Kb*R^*6g(`)##<@B!PV8; zA3Ea4XK{w3_bV1Y{UOCa`)0s>>;CWIaP`KtT}n|%Z!4#+o#ML zKT0vQ-!@*}-X@n++<+i&$fo6d6Gm1*FKEt??7kZndK>!rP(%pfFFIAndc1jld|hk% zA1uj?+~u_Y@cz0Xq*;hed5-COqf|`#HD4Riv+PA!5`c(|Av`1Gf!+$FIP+Wn_iis_ zg(E7kwuQ7I&Z&D9+FVp*0}Y-J8r2~Wf0TlBXglO#hth}rF;jVJP0phVy0TJd3Hv9Y z{>`|gaWWF#U1>E+K_RM65TM$tc|DA5PZg85ManZO zlkg3PQDydLu&c-DBI_p;+WD@#U0A{Gtt1~xk0TY3-$h|CrvoamiPnAs{$g3|hOiS+4RyCEk74lrPWQSykeim4*T!OXwY$9N1pV)9A-*>akO zu$5==>8Adwn+XH7RAz<&dF~m=6kUq0S1_&)2vR|2LjwaQnANZsjfpd2%)u|32iR5> zh5b`p`4I)R>VJPHx+aNBLt_rWs!9HU=5)=HFh1-B5d3Gv&>)+Lb<|TmKGSf7UOdY= zItiK&;w(N`rohZ)N#RIQ*MM?*DGZ8Ktg}zyU_WVlQQhp7rL4|?)NsG;$%(G(-~4{p zXQXUZ`mod2$NS{Ps55Rtjrf)sk9?T@d4Sax@|qe-i=kd4o*2sX+YAC!=>^gpktMw> zXkXjv{0rprlH*STJ?ck9d;`fW5e+^y9SY!FSg0#mi0{~d4HGzXv4Ax6D+}JG7p1>g z1M6y+&%6Efn#bN+WbVt3XXDF8|M&HWL}+XDM@xKfl-TtTcBdk1ubbWu27ivn5f7eE zEwzGH(ap7RP;`nt;faFx4u?gj$wsennKTJzA|`nKXP|pmx31^ZNug`VVwLv&ISVW6 ztDL^~H1q4DTie`~B^l+HI(}tK`Dc!O@i|LE;qS`oSzl{wKhzT zpFR*VofLkzV@=g}B}3a!EMyr;<6^F;Za$Z~c1l<46R}yH(Tfi{Va;$*K}2x#GkOI_Q(X>gg6y@4*(j- z06->4f!2z3i;+s^7}=n-gpiB%x9!=FI)jLl>Yc83!3K7`q>WGP44K#d&J=Az2?6vd zm{HrrQ79B?C?krz>a_L-Y89WHafW|D2;$~uFa3))Pa_nW#1lVq&j?vM6ZIq@OLck0 z6b#k-ej|@$Q7YWzxZC0F$j8@{Lo}$KIbvH9Eorf&e+|X&7~*m~L&^K8(`nB<++(&b z`UKNMx%L{^a5-^k? zy7HYYpV99NE|1qPWl^xkWR|e7AqVzi<0t=8wETgi{|$~}Xj&C^2@{({xy$5-#LvDH zR)n1_UQ(H8R!sZn`O(9})n{mq>FqjKSX9*S|7!RrmM5ETKI!0Y{Cu?}BtXBUYtw*0+p77DbNT>z!{hF5>hZUvJd-+Ua)A=Qn{>xv!r(ECT_oYg{a97wx6AbIE^@ARylmqIyCZ1= z5>Eii%+5(>h^uxIuJmPhSR|y!^5ZoWB`If+O@MPUuzxV(kT8SYsmF!Qs3UZ~@qZ6WRLdF zJZ9{-Kg8#$u`l(E~BwYi}b(P*X{Z!UVr_arx6cYZd|7awl3LVKy zv##W_gMu)MOq$%WP_zp72ag2&m{Rr}`%$ASCE)i)Xag(9ZdRex@!9G!*m7@d*M)d6 zNSVu9*!zKffUem#dz=VKMtQkWL`Jx;cxY4Nw<0LKNSRUnUZ{^tst5`58al+AkIeRN zh!dNG3psgf()(yP7!opRri;?P;DM;qTA^mZItjGBoxxU3M)bgQ)nlsJ-iw3?0s`IQ zd5Y~p3(vQzzI%LdPYX&18Cy@A5R*UlX2s1?= z>%CZFSyd_-tvjxL!%HT;vb+q$noJJ6JzWlW6JN^9mPb=_m0ZkVvkNm!1JED@369@zl8mi2|Fb1Oow%Q~t zh$SP^g88=URAe{X$wJpQMwjF5+|)(1_PguLEfxmBIHMUVN2gCz#RrA456K*6 zc^3utMH~&L+ca=#nl!M+>J$5bzg*~KG5lDs$YN=z0gf%pySI+Z(7Z=>b~cYfWPx45 z)HD9RZq*m`7*$=vO%Vx`dU-@H0KmS?IxH*-b%Fu0T1>rHho&P?Bs^yYu+ljo849dR zphfHm$VahDY8p&X`bkv?*kO!D~l2M1ySUz%8$f0YBV zVwFU%d7mu3>Wp_7+G=3Mt|D?hcEiI?lJh}Yh5RIn;ta=rZA$^oj?=tO!=y}5I_wlv>&NrpX_aI>oxLj>-oOx{_hcio8MV$A{4Dc~CghWQjIXN!du0~v1=O`AMl6%^v9SogCl97;$a z^&p-V+o0m6a4>33V$8Dk0)=q>sg0@xQ`zE{&SDGxvfeQ)s<09eoxE-x2RS=>J3rrz zo-VtI-Y=^2E}v@Kb+=NCBRfQk?N3%5IQZ#^$u>K(F zKEA!tQ@$8;e}+y5@v}_CjA;re+tFS^&G+i&u>IW6*>zuXc!h=Vr}{E<1F8M_b7=D< zMJ3O?U3>ez$eeEO-SKe6+zff$7UOz-)D%z+R=tOH97Z0dsIPUFD$2b|vd8;{DJ+-_ zqOeMPhPK_3x2JhYFhi$i$J5}zT)`tit)bc&k2qI1LCsOuuL0JY8cT>w69>sCSn*ew z;yYVyvrB5FK!^I7BBKx&1a&qB4{pp#bCx;rsUsMDI1B!*RC z5q<%YqqZM3>8V*h-$ zn$e`+YNRrUp^Hz|K1{>k-}uf8UqqKlL*R;MJu#jXMTV&y7k?rmgU}9NrK|)10 zcY?^fAT*?@;zSo$YmbYgXmZ&iIBR*F1CQ<$IA}P$F89gGz{$9zOk8Dr-~<(f@gXlv zu~vZ-!_BbnGTFb;lDzT4agYH7Kx#2D{LG1wZdgmrhfG6bu=TMN1jYwdXO!2JsIp1V zZ~wnFFWJG;vH{hy^k-7ghtOw5Gj z{)qqJda5+te0+qX$T7cJvod2f3@YjE5C3Ggq6q0&yIX|dM+O!iS5ypcTHuD;w<{mR zAW5giDKpF(2Vw_8@N4yqciU-XvH&aAf{LQpx|>^nF+q<9Y3+9#&jsjjK)0Un^RgX0F>`LNDC!|0jI~!@;$ytQaFZfnC(y>?F%V(=vit;h)b6V43#xzd zBBrr3sB+=ev$Mwp0Ce)SJcw3F)|Fo%S+9hq(8)3n|0HEM< zRpE7t}TeToLj z@Xg1^;OEwKmxi+odyd@k_Ugb^BKU%KO;(F_Tgw5d7=m$ctxn_k_@7c9*uS=5WXUi9 z5ou|~2-SF00E$EHPX!EANIQCxaQ^Uyfee!|REcn9;&~ailhcpi8<@$u}* z^QmH$^_^HR_#X=Z)QszST36VFDS!DT zwuYy!%3UVG;-!B-1g;(!vfl|+T?38G&Zqj-;6i%$W_kCRS@zi0Y`&sn;4bJ^( zhk+2SlJPdf<+aK0_o?0HI5()?`)=pLx>2|DUCBP>qUI6g!jJj7ds_&@VIv5iR(#m@ z0k8C1Mu`3nGi9M0VGO9`vZF`; zWkr1t$)Z6|UtfQxLs+z1r<$k6@7Zg~DrSJ0K#aSh=*l5q0=YI=i=^Biy|5`d%9xMD z#lhXvy@O963;y5T>+Rs}Go_HQK!%ILbw6e2^+s=CpeC;X?e(1F_`vaTBxT1XVh>x# z#R*Z@#iLma*3b8~Yri|Q@&4h|<8hw*Sb_ybiRhS`6v-rG1wzYu0YO}lB@Umy_)#$I z+j#f8{?IA29<;VMUvp;n7H3*%W~cBG$w4q~wnz;be@zaA0xV~DYqS5Zm`|m!7m_4P zWJm!EpyN@L1sK`Fow@IwDJ<+cu;0#x2|gJj_qXG4sFZgFbGT1AT=}NfD}~0iuHWtD z;NqqER~*l6mlA<}&(}KFg@moN9p@G+Gbh`Y1Y~WiQ$o9%0XsLpriu`$8nZ%uoVK8+ zu^H+EGZIE@-soRl)@ZqGFd%4IJxXx+k!)&rKB}ZGT0K9G$wn_{KnfRPq5|cLE z74g@V2DMezo)iw%6q7%`N+pg|N{*-x6LbD5vsCZk0|lV;qJ_0CwmocjM&JPO(v^dw zP&ns$T>4@PrR+Z8A=`3`pwrr~GZUScC~!sFKDebtB=q(EV3wTwx!+#N!Afe|TxkG@ zO}a59J01P+i6MSf71)r`nhCY<12A2(!D?3ID;SV!E$VBaaDDL9_(vR$>%XwFMH%DF zWD&hnk_kn#SUy3Gc&TI7Ald^V7>XHo>xznah-`+&;rlfeV%?sLWih&k!B=$E`n7Qk zJ$lQ!L_*lD=$Hw5|48}Ta`^hnc7RFbHRY({SsiXwwWqjJu4a-1f-wkWu9@(wN{k9E z)YOAtl3CpyBzM_oJKf$I-489Sw5-u;O|x5*731`t!<>M;jqV+*`@JlE)_;hu>AZTP z?C#QFhN%P>pmC>LHBt~FiM_A!<%U{d4yh%KmW@QrQu!}=HvH(*v>{vQ!;lluB6Dzq z`5}fQ|E;L45245)fP+6RI*t=ZySOt;`Eq6NB*UkncsC&fv(MaQnaiS8maX$4oJeFk zs{iRa_xYr0eJ^X>?;IZfb-Me}l~x-#noPh@q}|%b3}Y_m?6axE*7YK$K?d4e?m7?s z#3VoLu@Fs7tk{s^-k@c}yDVfIGERsd(s@1cjC9?v-8^}=+Af+K>u*Xs$ibcns%kR2 zFn5JFUOc1v66eau(t}Q>i^|N-GIgxN=41Ltk!|sen_uKC4ijBs>B?b2Pu2*~(&ogl zXb)8OCpp{Z!`$wXSFj{Ya&h+W$w*G8p;cjF38hs>(?gSA75XS)Z1Y3U<-4R+CCaoEQg{ zrz^oF{16r2!WZNJ-i|p=uYgy__jlIAC8uir+G#UqKV0a&7t?mPdGq|})}!rBO|3g@ zEruZaIbNO)f(hV@#2%3!%h3@AR97Mxq!L$_*!01unbJ-GEdON5BDZ-hHx@vcGjHjN zI20@kXyVe-JQ~(opyBlEz{f2Ej!TAFzVd%*(l;b2HvBm8_C;D!Iq`krEjMH-RCFz^ z?OM~*53HUQX%FJXgCB^3TSgRo{s2)4C1cFLR+5=N*~POFoB_WooY0Qt@>?1uD70mk z^LznQq|33kF5}OsGUx}fCSx!<&Bgs%5f(3L0d+!QLrSBL1&Z>ICcBlB+DF^K zFPsgy-V!GSle2?Hw)ry~(gLB_WNQ7xkmxAt2qxxYJ(kq6rZESy0-3xs?oZ5A*iN{Z ziMsQ3_(UIPp}6>-k0l#en~dYecc>DjR@{v?Dd;|1PtAhcW)sHor3CC+9bR8^xRxla z=1e8;(kuoNTfH<{ri+P}oihj-^LbP~?W@ERAtS9ie?Km97mt1C@utlRj#buummJ(Y zI5RcHQK-t+tHDC!=gbWD9HcIeB(YUZ1zE7uv#yA@1q4NBgc@p8FQfp244|EEccj;2 zb1KY)ls<=!oYsWhIeTmrx?PF4pIAg%8pZvt-*8cGA`$ybLTlj?lpANia3ZQo<9%Uh zL@-~kxPg)PN}09ya`fbZB1B2k@?lL02o(pnZqH9l(6MKUdBlkaPMFDHX!~7Ar8!!y zM2li6ESEKxU4}moe+QT6LzULB5h9UyC@Z!i>-zTg$g=fm+s+%wU%XNB&q!=CHQ_|? zg2?sN=5*gI^Zsd*D8H~?P4n@tWhV~#$^7ZeERBQ~%fj&-H&t)~bXr*b?=IEOcW}U015^5Onw!uEd_QiLz5(rGu4U6wyWA}ad&kljr zRNLP*f0L%aWBT*-=NADZw4*eWvr>rU@ng#}Eb?mN#ah!)$K<|pqsb+G4uM^qi)uAD zmO~1uNYBJu5ae;9aO%Kg-y>s-kdAk|{%Ez|&)3#&ij=iDUvas0^<>Y%Oa3zkBzbso z(St?Qpedk1237y6GdlCM_aqI_2n=vo{^0xnC!U#2w)*1ifBt*G_O__qBNFZVzY%Ty zs{>PecmU21^O`&N8XN-yt759+|b?% z$fsn{@N-W3#(no2=jw+xWV5E+^hxpeg4=w;Mx$B#KgHP6$DAD;K%;jXmNx%;iWJEb z6+vyd*^#-OM+=|z61IUrF@Ig>8%2r!c%#)|_!+eokDW-vDA%Xs{Fq{%BQxfyLg3?f zF-h@QrzG47y}5N5f1NuX*w8Np<7m_4mH1|TkC)-#3vRtNUn_x9DKnF&Rdt=$394!3 zYC}R!lWD$D!9GNmqdy-cDxM!tfV~X(ZgVUt~|DuxNpgw%yveTr8{k; z1p2rn6>-0}em?^~V;=+0ad56Cf>9RF+vDjCwDep>bLG_pAT~Q;`{etVbR)Wu8YK+Z zgERP+b!+BoQJqT+Pf9BoJ91Pk=cfGKU{WNmhLWlw@u26_r#z|dZj?VaPpmHLPK}^$ zoSU4PbiFdKek>1-7-#Q^-Cmby3-(OyX`NcJzlb6H)mR&wMKILj7bw8HE+Za9Wiv!t zZ?I>=Q;EkD&fIGHMD1H*`wL)FX<3_xsRLf|Uz}L>k+$Y0CQc?#R9|(V(ZXc4^MwkJ zOZD2HIDBVC$0O-QGrX6$43?Di3wm)Y`fRO^zoGHC=$Sgo9caWeZpHV;Z}wq9<{!^R zZdAV1jfzQ44e#RN$Lu#jL1@oIpGclAjYE%LVe`*vg|5fX&|@PJAIZ>K|+#s~D|9F8^4md7OR!6A1o1 zc>XRp{`1$6Doi(}%`JATe?LD+KkT$Cf^{~ZD5mk`p@JkB1TF&2|NCh+-|NR~gjv@;ya|Eqo>nhj$W+^!5 zSVZryV$neQ`R9?`_28#(sEk@8Fkk>O{iZ=o%;BeCSs6R~$VevjqIRBCTW6<~m{d^& zI;(1eD0dWRfPvT66{^Yohs>Q~?=Jtpq0vA8KfK_H(XVP$0T8JU^Lxj2>{sr#8B6gI zxbrn3inFNBb-s5q#=NeV63OwaKTEhyTgW}Uyy7{Zc{82L+X~Ug&p$9#H?Mrsx;9?-rXRbdrdkK|opZl-2jUt<} zD(Ud}JLGZ`tohQ#Qc?|Gr&k5?Zn@#RMMN?gxJ3OvQJ&I22}Vt zb7T4pa`%JuZ$pHgUR#XmZcS+N;Ks7VTiTBvso~OKfWrMs^%)$+K%~s1lAT8;5VGqb zC9icjQIzKQ^cusbZOTo1`wJpbB`oLY!3tVIi>{g~&dsWX68SF}ilxuE%PA<#E6gHQ zINddXXO^&LAUWi>kLE%jd4Q$orQCbWmo4Sb3M#1xU7uC%TG$YCwbpzRJ*#o(VK5t(lbH^mq?pd?m45;r#hDZeU z?N@(WRK6>u$G9cJrqa%@c14^7yxD(G{1J@d;D+W*E;dl0(r-G>!&$|;xzF|mPX75B z4J!AUZL`yIGN)91^2ou%&(ANFMYm3iMzXdkJXldyG%dtJsOY7U%N-rOTbGMIi+-d-)7p{$cT8_pve*JRy&G2)+p1-Co$hEIGZ%JB4lLj|3 zcJwvbS0>HvHcH=nKC2w^iF7)9_+TCQ*f-wdDno&Q0iM}g@u1M+n5^Q^u!A~_T4E3< zR+z|hh)BafWkvp`+y;)adBBT5zFemURjI?bX+u(%RXV;nZ7)rDcDXsp>g&HacbN5% zeI^Lw|M;#g5qoU%9kC!E!OC9Fm4vXS-E-%lJJ@w{GD*hx)!5jkorn9=V^>JWaqK3) znV8MCNuJV5v(-#D0VM73?D+p37cFn$Paj@?4Egd?((>AU{i+_-^LE{&18o;WLde~Q zPNK6{ZFF$x$mf}WqP3_$UuT@g7)dCd{H?7l^^F^tt-qhJRi!d(U=#Z-n`Q;kSGm;k zUWKSa78LBK*jNmo`82^%+CMrjGW|{3|Gd#LXQ;1l3D!Wm$G`ZGrf5&0x?*={Pq*Rs zrf$iIDMZdvgSf6QuImJ%OFUKzTPLc(=(9D`Pf+udYNU}Y>xD)9RMYX@7i^?6Ve}hj zM=0Snl#zC9mQDeIzbj(Q#Qj-gQ+$U-6Od|KdVn{)7N3fExXDLe0>S41EgZ9kJYY;u z`Xbglu8Lc$ycBz3nphnI+=O!R(WLld;1HMY*(kVBH*H=K8i(&?bv{*(S3TVGD`282yvwL zvqY=%_vP>6*q4ky^0e1y#%AhGq93an0^A3%$C+@H=u+AQ)jd8Ia$hmoa9gY(p`herGx)N(XqTozD@a7JHC2)~T9r1(2B zcc3~qU)FUMj2ATEb2X!?;wg{ruyWntilqA?9NU*&Kx_oTd(XJ3Kk*v>-N3}Ehz7r{ zHo}M|)j?X)kxu$@X?Bbjt?KIP;`;RQoZ5;uW^*7`yCvuG?P+M%NRkw~i4~6|nQY0I zxaSmqYF0kK`eoPa{&Yi~<<~{`>)ia5yKof!eIo>|%v3aRvoBPL(D=0b?khP9iNP^d zWM4mOe9eEn%=~bHWouV&^(=h|?O316W@i)-v-x_L6(NBUdy=xc#X}_QixyYTkS0$7 zow1{G>d2`Sr~c`B(r-XD>%oANf=$drZ5NL2b~!XP<4@#E8wD znjXibv0|Gvm)Y8v6l;6Gv6*(-b7eKR!T9)K?W9MstnJ(Q^LOr~7d_+*@!_M<+dpf$ zs1fr1QhZUcvaIqy6~MH%N_$4n1#!skb~Eou-@<>GTF+1$=MhwA5fv@yOY9aM!lIWh zUu_Qp>M1fF@#_mN3*cp$8eP%BrFR7IAYmE&5L^7$zP6?EMOnqAw$ULaE)oE4#e%uC z?O(|x4|QwKaq+n5ASz$1w4mqzp9}DO1U2+}Hkp;A>#4=QeanpG^4JlUpP1M>Lvx?_ z5(k-r4?WxZYRAm|#%m%(aEM-s5y`wzXtxQ8HA6yu6bG5VlaT=`&Co|C%fEcAtZVJ)Q&aQOEtCuA=p`&B(>67!l&o_n z1^KYADNPMbsL`2BcIHd-Cp>M(mExP5qv;ubdOOj-^}=c#_x!JRa{7ie6u7AnpEznidp=8u(l)Ge$JL-e zZ}@dGQUoKG!`j)0{%qW>RaHe&sbp{@$oV$*vlkLe*=@(E6k9;aN8f)*jQ&2QX^4t5 z0e6}5E>crh9q#-Eizih=1&8fcjzA1E=onBc*~HRyV(nQzAKx!SV61yGWoN2dz9aQl zUXWX&pJ(6TZvz?wdQV01q@Iyu*Q@obic{AD+4{d61cOJ~D(hYikn0UPxK7du-t zGPf*(2a*yC;~#H>wSKF9*AF=x+Kqllw606B=PhJ7vP5?K@+qH`-^=+t+d!o3y{3XX*1^AiC}}UXoY^?+_G9y+rNZ%tpuJXM8TaH% zN31@}HUpZgOQMhQfdEfXG*#^Zr=emKq!Hln8z<)cM zw#WaYLgp`rY#eId1_%x?hpGO&VuV7D|8L=a!tq8>`W)*nuH$tM^~3Y_N+Ld2W{jwX z1(D^qYH~zn&&O>ZWWbK55g1#32E#)Nnus^ReN#&c_C*ysbP8RydO?y8HUmT!h?&Mo z)fJ@2Q7rSP>{0fPeCXkfTl0fha%^nkybvlay-9qQ{>7MeGI|}piL5Fw3Gug5{e_l+ zp#r1xV)4uuK=NtZg0lC0n&mNmMt}*V|PmUWhF2^)imhbw(55_0O^i%@K6` zDs+OAQnloIi0COm%As_CYUHM30=Bj(>vvgQ#{WgGu4acS^*tG6M76q8R)2N+MX zUZ}M;TR{yURcu7ZL%tcNWlzkHX|lHzD3@C7Ev%+RjdLclRI-RpRbtd6WA^kt0#Gaz zQ1*{klQ87_J(B~!9T8S{5>w-#a6XBpEX30{dWoNSIn!ri+Zh& zXK4CyuLivL;4dv+Xs4mqQ}MQA@aiq2^k8;u#|3hJ>VP zVlr#@GjVQb>%;D+KcylKF4af%uk+o1_P4pNRi0lqRK{r8GgWx^6P@E?7t|G=3f>;O zFO{C0Z=q7UJ+}Vt{n^|5H@Y;23#b^mN_uS)Yeb`XU;|`jWkWZ2sS(Q5P-D^>d~YFK zd1Xa=x$yRM+lwH?(|ZpqWTDe>#}KomL45QRo*PJ2xgBEv@j?^rYnl8QChw&f`&l-Xuk zvV6?OE=e{>X4IZLG7CNsnRv?azGvfk&*sW8%b^399mKuJ+dtW_ta)qH4eUppzS(u~ zsCf$_!K6Wp$nDd}6*)YZs!sB{Zr#kjPCUH}HbgVX%qt)?>?Q1yo6_#^&X@uCVeKLRz%I%}$`duK?9;q zf5vf^7_G^X0YoAEDQzif^>_qicpi?L9fK2~lgii3hCDZeKZ<_FU%Q>(mgRa$uxNW-a)>;>mgf7?Pg?QD|3m~hKh zuL@@kYF!VK%~sg*o)gNPM`$S;s!LrJR`*qLW@o6WWvw&;)Xi%SW-;6L8Y;hJ@3u8# zD}sC%%$^6Yzd_HMq~9(z97y|VBqk+mQ%qO=y`-9y;A)Melnx>^9e)r`6xutzs24N~ zjW6;_TS>*IqaiIWj_lq{giYYN((QO9sz(!FWr}|Qm^oFH7{T>gIv%bj{~ny*-um=> zMb512jhqHwx!k+^dYqjj?Ib&c|6ZP%Glu*-8}hqw5PLW`?*4l}c`+F_w~APuKxuo3 z9lkQXX0J{j~dL-!}$MDjeRgQuX&4cs(e-~GW)QrKGuyH=kM-i_D z7EWJFIM~qm&`|BCch>^`jF2XuRd;u1H>%Oj6A~s}jB?Mp<|g=%i1d@k)TU!H>3id6 ze0$j&r0&1B`6dTdc49K)5{r(o9J5cEJ7q->B`=SA65d0Z)*I1!FNSE?|9)Yvw@9Y- z1bOAwL`aLn)w)lXGObV4r=*BJgkaiv5zbXtS8=n|sUtd1B_n9qqQZggw)a^blG50l zCx7Dr533n=*~SDLo?|7esOgnfI`UpfO*Ufo$`dZTUUwjVT_GZIJ_IlB)VzDg?lLAz z@-ik{;_aQW?0WWU5*3{RuDWX}k=k@3fgLm7o&0=J^!S8W!Opv$Kx#B#7S;zxIo5T8 z%%K-T+&ITiCb;~tM0({3e)d?Nj;{rC_Fab_$fdKbg1LR{MQz z2OYd}_?z9o53@P>{o|-0bYZnCV=^~;zC?yC0L0h%LQv9{u5*@(8{TL+^~+{Oo+c9K zM^2k*Hg4$wi0a>cq;vCNCB0b!kG!pUH1J5B?|q#9tc`=KJguzSahph$q9TiK9|%Um z{KDz%r|H}xv=P&%W^%hJXnP|$+It-DWchW(CJ`F3Fw|B*(QW4U)R2Vlll@}BZL`f{ zf3Ol&rYNqPgRQD#uNX)We}THt|2pHBiwduSlj9O^vXKs{SW(3ZjJ|Lop(AmXKA3Dl zNKig(993Vr`Wq`rM{rt=LK$@|Z2^#w)`9DJ*i)quabU&zB)-A*09{d#59YSF9w8Dt-nPlqcVV+Eef*o0GC;^p`XZl_9mn)Bz45C(X+A)7r?%PC_xHwI(%iV`xQ@JgMa4uUxn6SZ` zD$$ptV1K_EqJ;zS(ft}s)qhmhAnkv`G)}t%J$*!^LPHW2``zbZ?49-`@c43=9IGRI0heyr4j!to)rn|cH&;X=?mT6 zTh1e@$B&MeZ*337M#QJ4&*?WWW%AFBwi6*3|42Ea!l>{tao-bP#GE_+;Q+xGBB<}O z()A+ED+KxAt{M||mFg^0xCTxJx27D1CTm(axu*U0Ht-Cnn0spBq25&Ki;Rp&b!H#F zIWfz<95{dVLRDIte)sl|0}kWvH+l^#!m(=vD%H;zP}{1ITHkV7JAV z^L`C4*Ky|XZIf&$r;G}Z0_edAuB3x}aIz;R!Ay6E+^pxNqlidz%DwWTq8NUcKD0bo1bi%yz6N!#?98-gax50zta}6hRtTFA2pi_W81N1>^ZJ^E>M?1$*(f2LHp{v>rZ|5t8^!k#l*`- z9q$+?K9aTjWF7bfLi}&e#@LRp3ANfz=^r=xFd7_rB{VO5S_B7_x)NOh!7C() z?YAVx4|QhO4|Vb=j^i#6=l}+qi0#mOH-Zm_cp`?00ji1$QzCYM!(>WX#CKVwrlZ3u z)h0OcVwZlvj6QzS-o8AzGMrkfEa8<3a?lZXw9?Wygn_9F9c`OiJA}SW@2@5PuVSnd zZ+sRRyle7L?iIbxrpspC^xIWA@iCJj|4op!L-ZdlWk}95jJ`UdF-m?tw~_b>h|&@E<^>zEw+jgt3zQ980z;@N35B)d5+# zTo!V9oCdx1YaF%Pke*tzaRcJ-O0a+q#M+vxbx-$RN02A#30UsEC~z>VZVDL3#SUDF z=dc+FAK6l7GYxuWFwO_iEf-d`F9mz|h=o`iZEMFpzk9TUD`PMH~M#uIE z`?bQim~4hs(Mew=`p#XE6CD_G_{3Y4fq_N-oHY2?DM=jOiB;3*X3y7)$W9#yTbAh* z9$6cHIICws6w~``Q{f&#IRP>Po{(aHsQgDeDp)j~?XvtWna5@n*2oKZift6ZR$C;s zL#EMLe z)s`@%#x=qjNiX!;XYy`F-9&8u+W8P5erUplh&_1o)PxDM!P?YakJML|cX{Mf2s>u&ZeAEG zMX;;tglE=7%l?~kXS#`1$a10}!M-8%kRC|j1H@@ZU&z15rY2&`?Q8`6x3>GoyfYj2Bd^@lBQ{VvF?Q)=)%+q4N;_8`fd3 zXj1(2O-T`U02JB$ec3p1k@xq)LJ=B7aVM(3^6A2Y_vNqGgbF4mGlVLG6Ki#4nu*q+&`vhEjwl%Uyo@w`u6k zW&IR729yh`7VJzSwp+ja(%b~w;2>Y)#kZq}PvU>GQ>mr0`o4n)w63X-B?c?nut)Zd zWegttjHR&%ZHdg9p|VxvHb>69G^T-;34dvLctTsETB<5|e129Iu9oMC4b^LAq2=U% zXrl6oFO#xMH>=_U++t~K^FwC#8^v=(7ZE&ymZQ(Y#o{~KOsD+!Ix0@5ri~_O-YzFY zs-`dixp~s)|CJ{4_TZJZ|Mle1m5H~q|6!kg*0Tog8&LaC7Qijq%Hl6qfOB{phtCY{ zMkO}Qd>E|_?qQODWva=Vbwk9uOg$>#xV-0Kb>qB`vuo;VoBo>H1(68z)`fG4DJAK) zO=WRi;~BvY`E5>&_9vw&Yq0E_I4tmb-zdq{itzfX94QOWYX760bX;D49vCOE6yC1inw=Ph|36yh0kOcZH55 zh3ZpYv|C#uR*#g)#wNJi@97l;l%k~S`R7;lwLGeHh2NPG4ZJC=HSPMZ2i^-Ww1v6( zB2c5Iqq-$e`#)@i%-!1c9m(23cgt94-H)C{#@cDr`6W01Q=8k7go-7q2B(WUcV1K% zjf#p3DkUgK^%tW%S$fvvup#%#5=l}eqvBZO>-dqL<(w8M!Ps4Ofp2z>u>lWg$`u_i zzL=AshIyKwAVZG_fA@51DIRt&$CbuWwVdKM9frR}(HIEcPkq##tPDnwS2NSc(UvK=5CsC74v>4}V- z+4L<Ah$P`fcLOi~P8~4J+!0u*=xg$R;2}AhY?j?D$4ew9^N7ot zJO^#cFz;e7;B~#?mnSY${^go`Ib%e({$osmq#xLv9l1$NrYcTQ4;IGKt*g(H4;K*g zLi1x4Y-qME+q1QpfAez7pUDNVJ{ zz)Ny11Juw1`A_n_LsT?#sp?Lp3Iw)C&eCXgXIHsSlUGfhWG(PY5)!1C*5M?$Cnv9` zlUr$5=`Qe^;57KD!yLf)us6ULx^D@yUwdXFEhG8xJI%PPEXQ#fW2RE_h)e=_UG8SMG#;$5LTmoCHH9spQBXad1O&vTU1(<#4vL|=3gfxgRUVjp5QV!-W1QN zo4)<+)smXS_H;XDFat|)&4Ean(;QHKPKvGE>qB55C7!+LD-ggkc}^_38|Btc(Aq5E z*LTM`qSUokkGQ`J_v={%wY~zJGYk-NnVEOp##PHC7?8O`h#IkV?V?k)(V^|0Z^?q$ z;pA~h-ndlexLKS@R7|&wIPJnAd@O+C0jO9w0r_!MdS-Wq1h9GAQ}h~IdL~oy+ByoC zD5$=D{~?^E<5=vpwC0punNfl@UFlcxvIR)!z%l~>f>jA<_AQkLBnlIo6hQKbv_AN4ED z4(Y{MA^Hu7kk#Y2!W5+!7Z;PDG>GyF5@kh5MqdNcP~Wj|j_7?M(8#Y7Z9uK*H?g_t z@ZlG|WugJ{4^_lV>i|qz9z|NsE6rZqJ=!$M&YKD*?pV+pdIS8hFqSPI0Ing{Ndk4| zF*FB@BWPBdn=*g&v7o-jBMdomCG4C0_M}}p%$#1C>w3m?mB%A>6>io~m#(M9Nudj4 z1qO=m+63zAvs*SbhiLfLDr@vhX{Y6=s#)d(=FOhpa{rqvr8-nUPEO=gBt@UljNESi zcLjD?5CpagK-uw6Py|ksrmY4s2cwj+dEBbkMpa+37tJQ5!WKYuVCeI#>}U-bo*ltx zwYNiavton-OFVzL8s{XH0~J2ixw=v+c=Cd6bKCQ>EGFb%J1~6nB&J zw;V3ACJ+X)^>$vq!q;|5;k(GAowc558JaeG-nEq0p<{ztzD$7F#|ts7{7^^};<)AR z;X<3&x5H6#>y`Dxve4A}!xZBa-_xN?-%Kd-{=REEg!9_bWJg=tKjijLILmD1%3%j= z$fpD0EJ71tBkGu0e0Zn7DKu^9O~CMylOv3UrM@yF>XpQPhlF>IsP-9lLV~~O)3C73 zoT$}5?~zP~r_J`Fn>zVt3IA-#YXI{;P{0u~Lqj8?#Yoq3^xHWmi(Ir})6ADG=Hh9O zE=<`W3kDqnxCB&-kSe8Soj+VqFvb?4?afq8Z04||>L$ruEdmmWgu1r0tQ?C?+e3Hl zpT((wCrdXl9Jm{K0Ko4{)h}{$^YXs3WTfj&iEoV?x~v^sU9mW_&q{50ymTfVGCOqb z=xFu3Ifp0e`Aob=1}EFpyniuazqWn)5PKSNV}1WvLdm9Q#;G?##SW?dgCp!Oj}KLB5Wy7=wXC?a>emF zbOmzmI0h&wfcqAu;?+)Yh>s}x*8k@M&>0;XsPnwmN`szRQUlxeEgs;9iN~&i-$)_A){JB@rTz*gQ1P7IR$C=d5>X(a9Gq;2m%h5XTvs+{kC zw@U7)?p}}9Ek#)sInX=bH;f}M1(_Mdd#@|%r%mJ(6hQJOIV$J-Grf_1JvSuzc{#BI z$%{=TkQQf~KhI8>k}+&NL?=T*Bnq>+?)-UZuH@mE6gLO5ZQ(Y8r?8lxrzI*%Qzq)R23S`A#FARq(beAFou>@=1wcbAJBy&$ zDT z{@DK`^lt>Op!M~o#9XZJj%J|?TI|-4NnLsGxVcuu+zX6KF!c#f)F(nCvgjgsoCo7h)>RxP;eNBmGWsFRUX^-Y%x1Eqay{*8~48mJTIX`#g&e z?LpHq1&yrM&uc{8K~@%p`c`*Zw|bS~^69u3N+P>bg+RWa^Noids#a0+`X)%AnI&Ml_S_0jV!FJ?#htay~z| zCfXgU)lu_2CNCQyWp8@H)E~SEQ@5@{oHWmwOdKJ7PQm*1mF$q;J=vqe@SAS7OTgOWjo&`(?H8BT{Y`-M!I^VHdT8if6Vb zyWi#)b;4h3YSlEM1Ai9izE}xl|E&0Yg=*Ou!d}&Ep+bydess>%?1^eJM-oh__SsS{%S8PORrCtqhqs^I}PNp))_ zAWCV|56jQocus{Fa?q{9eZf(Qbu*;N$_zr&$nohSU4){rrL7hyNv^CNb&2%Q0MTo?J!D zzhSDvj@3Jink#LpHg%Yk%{8ATZO7pdZSl9*GcQF{31Q44!#_Pta_MX^*$VfREY!#` zj2YiJ8U2_TE7bT1-gF#L3RorbVpLw*7dIV^|3#gYNDx&m5$Kse$X8 zk7tu#8^IL7ZLYrf$XOEDl~w)A@Z2n$SbHj6E4w`mxj^1Zvl zuDDW`4hOeM!WUE7jrB+&+R~m^JO{ zG-$kcs%zF_c$==%3E^H8Y_zV+L6nw>}r!2L*0ekUByK(kjCtCeeA#?#_2chCnD?EJ9jmKMGE>J_Q38O+FD zbl3a(eDVr@d}aP=+Kt!EDCcTC^E~o2=pURf^gqd5$7wL{?tBShEQ>8tTJph;SasIsWy5R-|g~s`B)Lzxsu=6ti8cs$UxiAYgcP8D!{`jclU= zL3hPVD3e=4Xo@Lh)pTVW;?S2^1O){*SmNU*a>qw}i_`%7@;7YZQ90f7eBs&N#OinNxSv&Y zkNFC=Oagd`m3omly71+B$|4rd+pWd}vB{L8)O0HBw$>czYe*)AXmBBUB7etRe?2-` zb|8UmG`$@!Hz3|!P5tIuc3iJZo|6MMXW6RvpwQ)om}bXua<-n9?TP@Ln$KDw1vfu8 zuX-^j7eZdBbnbD@-ybFJboOQ`T>BG751wy8MkVS76*~k%E7Etu#x!Bsa$M-WnfwPr zy3!@*_13riv(*E_}uZ5LamoK%55*K_64&c}lx+`bScjt;}&3Zf^#O<5o!(ws!w-ms4T@s^l4j0yuu z<&x!4{Z9u9jq+ZP!TMPIKGzRqcF8H|Fgql&$K**$Kt=_9LslPEF=xYXnE-}ZlK0!dy^YgWdCydoK@ zw=RY}IEj<=GtdxV8y)-ZXje;)^LykGW)``-@}+}Mz|_Q=@Olj64;S_04we&Mump1eNIod6m2 z)s_utL#aOJmO{}-zi=dr6g`89NN@*J&ihZ05F(AtA zbc`;J7Q{{}sH(d*h@C(+T~O<#tXyt?|q_K^0(zBqQ*jn6G0X4p^xEjz)W zIXDXIUDFrB$bl~0kYCvaPu+WsJ}*#@sHqBlI(<;f@2Hqq6ctUq7*q9>vEA1ne)=Qx z=)2vj&Kde|Gj>kwY3}JT|I^*s4LjeBDY|>R>C@f-$>b4^jNjjuki$hrDZf^__A>4D zli0%Xueh;&f2vEKf_RnS>YTNFyk(BOkej`8GkD`d4dbm&xQCs;c@c4h&N? zfSa6{t*uJ2a+Z+y_SdhgaB>|B-5Z^-O>Ihh7{H7SmBf6AiR!v&pvCq?Io2#u32~M6 zVf`VjdKfi|b(NF9?6D0oyJ<`sVKd_qz9(Qc%q%jGJ*~Dw#Z++dX6H>|IV&Ul=-?oL zt}GX2Q@7L?vE|;Ylsc5j@SRt~Ll^pQIH-VvaZi1mT9NQ*=B8y7hX6A^gU@4iXTjm- zld^=b`MosSU+{~xlEUf!VS63;K<2eg9lSr0k1B6?f+b97z7ux~0e`gl zUc2|8G2!wY!Q#3FR9nBtnZ2{c71DLwD=h_q(B88%dwQqjU|plApBeQlbDx1lHKpUGkbR% zeNEMTjk%>AFGZx@1*7M*PZf??mDg-64(`g-G}zE@Nz$)?fL zh!8gDX|Nl>QVIKK@V$P1Fx1OM$L3K*CO{Pd1_)yW`;y#GG4Ec-Da5Vhr-`7eWA?dP zi`OexqIte8Thyo%?q7ilV8Io@AoEtSZz!+lPis=z+Cs6z3@`5D5?$a6Hcqr+BU)PW zuf$LjV%8+W8ah!aBe997n`3tEcv~cKzFKzaXdmsL4`}&>@mMpFC9gcPEGXhJ?u4p) z{+jRPKe$yKwXd3!qx%B8+@U_~HdssrrXPM0c~!P@h&H9$4ibItxC;0}Qv$wz-gE!A z&T8MHrlz*NaJnFUv=j1{^8}Q@*v&uk?FhYug`WSL-Ea87H?5_8 z+ugB-2sxBo54_(Kz?c)0@$-Xrbe{&0O^HXwMW^v6@~2hAyK^d4S*<&dI6{Z@41Dj# zyg~yz7;jg-Z~7wV;4|LAjH2SCroyVZ5RmHoQm};P_me_?4oviHLo9wnY(1c;s4+-Y zHA}^Cva7OU$pQ=qBOw)lza0<%w}Dc-SjBaciXT`!okYWA-k?4q?f(!@)IEVoyr@Id z$W3(CxBA2NjLv66QI!zqx_4;-XI-X5JrL zUy4~sG0&4`FBdA-F(?_N>F#+n8vsQ*UT|cIZJNCM_p_$8x4OSYIQC-N-*Y}(!4c@;`=DZioxQtOw&4uo$o+J7HZ-OP!==v zR57VJWf+%S7M|4Qz)A+s-8-q(U5^f08EOB&?}J(qpHPzbxx+&j`0by*F&xG&E7*mP zq+yf0WH>E<2BxskvSGP(HK;!+58`ITKWzk;_luZ{DBc60-KtWM=F_2R0-v$=c|pS& z_)W$Vt^%6I)&uR311&EyTYTmsk1uzgKTW>6cjpOv)aBdw_sp{Y^}^Xm=FMy+Vfi-} zG;JHhG&a_6UQ@O+c8i;R^aB>&?KfutW&5i+qB<_9 zjupm=?J%#*zk9RuC4*eKyRP<|5W4F-fs)@9KBlfMP)|D`WK{0`2Pp}e(93@*>j&#M zr=f@Nszk=8eqXPE~HA*A$G#Xu#2GgZm10sb zP`%fKCICl$@xOf&)hG#GUw^d3sW?QnMD-u$a~7qJ__NICFJ@WGDmn4e(%a%x2G=bN z4dcb*qkhUVQE73$ozR3EsB3XHKTXi@(Lx0ENpVQ_cn61b^$yxk!fca?eEt=!R*y3X zj7G`O?nqBIj z%Ld4~3V?hkQ?0TUyL^Ui@&mq4{H}43Fz5NlATrl`o8Iqia;B7|y!CSNCJb?DS^gKL zvs>FmY-Iwv=_gppoYjV@?VoEVf*qS#KsbXFMXBH81x^h6jOf_b5nxXBsbuP3oozg9 zg)up`-ftBrQa$xxW(S@O9NZTDntMsOA21D?z=|z#@#g2}TI2TyxUM&GZ5?!iaB?Pp zl6`h*mlFx?&ERci6G5?xoNQ__x@g!~`U$1un=PXV01`P!5K8+J*P;%fwNf;Jl9T*m z;-5J$T&VV3UbW>-?LE_d**KG*qdRJK0vhJ7ugUuMVoEKWl@+}sC#ESeF3er*g)SQ`Wr-POL5@B$-0FUhD|QJRc@hcqRVq zykIoD&~_+-RtaTzACdn44_y4u+5v;ig{Wt+zH7}D2wFN`mBSaZ*)S*6g9;y8`3P=B zob1{GkQFhrc(Pe%VuKF0F=!Lncincn!D=wGVaH{*-<4tfpTjV7xwH%mz2#qz=GsUg zG!j^hMJbrLX^PcvXOWvblBK6vOILgkesGxY)6V$)=8{n6NpLuzyiHwX+in^=wqG z{Th7W0Bg*&$5|Bmu#)rlKD1lcVykLsxClePJ|aU6$`HOiH=+4fq2Gr)+xv{05yb!g zzO!7ni7}F`*Hmc1;-Auvt$FHSx0HG4ggU~4eR|8tRy;yGI$&mrH{&0!K$6Aj0K2np z^;~iQ&ro>!Ae!m5cAoU@#0Tk%L+iUHRBGb=$eh@tanD75Pr$=1>eYr3N6TD7s|iIT&c>h|0RuekutFn`{r1xKix zYfIA}{O|1mV^298X*P^tnGhcz0}UmK8ZZ9DGe9fX0#MRO=#GNF8Xu;U&vTcs^y~7c zLQqJ973Q3j(m+JEKZNwZritpNn!D(K#xH`*4oerTe-oU$P1ju23WidBe5A3I`d>}6 zdLu-A7)ok-!a7;|RRO?{Y{Do4Nl(yDVWX!|@x>96{pK(9(hW6zU>f21Zdit}$c5|Q~i@@lO;QyiNEd!$bpYQLb8)*X_hYO zln&|6rA4~C78L1{l9m>bl6ybj`~Q1-J)djlJ?G5pj8@AT(wI9E&KU=9ud2}Ls(uit zg)yP>jj}4a^N|TL|0o|8U|*8JIsXae<)bjyE%FVt@$s+|jX}pu$jhLJQ7pszU|GXyQupi4N1tiiqZqC!4;Pb^lb{F@f(dX^5UX`|kBZuq6 zlvo@e3#WL$H#9w*M*J+%dh{VEIuQdM=)nw@CFNl&)AXI)%ExIlmm3?w|apqT162Ot+z+l@iUoEQ`R?q6&pzGFuyHd}i6@4Wr51h_IebK}= z=!%wN9^%vM-{-Ba7F?bLJM>_7<>7Fo&YvEW>C?1qYPNj!9$%3aC7er)wBPuU-u0lC zUIo=VqCbEt^4jm|*Z2-{RCV*aZ7T4;8Nd2m&n5YHCeeGNJI^-Yxx`>S?)dtCc>daH zao2cq|L5Irh=ilYd;RKpcMB(qv7X7m4Fb7V<7-&$Y!GkP&lB5fs(s&VvObpjI+Qul z{5+?D*5*gDYFwVY+cz5UeqZ0);5CE-fDz(tYgJg?Ty^g1vF=vk@t>Zeb9GWT$lWk~ zJxkv5k0X!0IBs>rSK#S%vZU;P?mq6~6;A}{-|?hLOjed|Ui6?l_+2JfMOtdxgK2dZ z0~4``V{2A~@DPSpt<@S%NXbR~W^yo|rfz0?=pxquM^%Q=RJicO7Q&34&}JL(RcN{! zdudX4r^3l`y5u8=UwzsbBGY(?_uCq4+$M@qwTz zzjZ;Jk{H4OobNm0Hjo5r#a%i3p2{YNMfpKM)!0OzwH!Vp?-t(wOtM8UPXjV7Y-f~{ z--e}5Rwo-p=N#6k_~Y62(2Cr-fAL28Td?-EU5-CXZX`sUZyx!msXtIy_4u093*JQ=B8?PlfRu(w1b>9<5#wfM~s zp_mZRn8p;=e+uwys^=raAVNV?@x%0+kB6hgvNFW0c%UR24A)KrZbX@8J*RW#z3H-y zpKGr!7j$2rPHHYh?Y_LT~dZ{>{kHJCr}5qT)LP6WM39VJJU`}OUA zHm34`zWCnZ`jTWzKk7rXasA?PQ&ZEok6Ycx$JL9yUKiJN&qq@Kl%BYM-DyZ+Y% zrE~@s-XoF~pP$9<&;P#p{oivk?LVPJ%Hk&+0^xE84HWLwz&U7&7`=b3>7p5zQb2fx zwtfeFd-o%pHu1auTv=7N5xENRcQ8?MgBX-`@AX6?=ff}F_w*X92HG4APQ+TZ3?JJ% zp>LI^f%r+C@PR-=YG22H4hp1J%JTO;F6P{|SJtdJc%*KsG0~N_IyvRbmMQYpky68m zo1Fk8JNch_P^)Xs8kG^p>V2iAZ9vZc2-%qPN8 z*90C|KcQ2hGXIQu{X%?&_~u9QftXzxRn01)^62sqEpjXho_SZAi0yLtyQ44mMhtc# zOIB)CGL5K;Biq&tuSR%sa;iGv4M`29=&i;Ax`KQLI(=r7R?S$N_|jDZjH(Hs!vW$F zGBy(eLUIwBxn2389@7`K@L$pdo6ncwO*sP+jFv!2Mq{U<@14-L`^-%F%vV=t;ai|q z3M%w|v!dVH4g|h&IjSQ7X_YmH+O@7Er20k3PN1&n=)76ZI|`%nl7Ys-yP?s2DYEij zIzDZ)J|cgT1ai!(?Tg}usLV)40JA!1>^-t=CO_ zh$3yIqn%rYOBRf)SSZV3^}@2XS0$d23+V9MsCT2lsmB$y+M?5~^^mSBK2Bs>_FQkj`N;x2ePfZXH_!cLIUttA zf^$kP>?NYL(Q5on-v$BxX0Oc0=;s8U&6oI~f)Pv(tC2UFX&93Hj0%DZUe!74^Vee& z6Nnt4*S2R8bT=Yysr;PSUzk$X8)NFYylj5@zu6wD6+f=KHt`2^<|r*L8uS4?`T&+# zj>q-uaEF}Kllzd+kb^IoS8fX2gXk*pr7g$Q-=Hx`>)HZdD3+mH4$t#aX7xYfyf=dW zEELoSKLn$&ushy+^{M{+tLpzu?zHI33${DxpbuU}hrCjH+DaU;(zTrZikwMjhas?s zqsf9vUtT^RR{tsZ2q+UieDYyW!%FH?kJg)knTwmhe-E19cirseSUfy!Jdd_^t_E%- z4xT^JJ=z^S*@)#S$p0-+dS~DKWO93>nXM3^Jjxa?tBY^K#gj2#(8}D{jPOq(PWeZeOjt2 z6*Yjkt$GY+jz2H!S+7jCi+1d3)UHy9O@`5)OFazbZ!|+kP`X~Ng|HN*nW^2MNscDO zs27Fs6L&@{IE*?cok&TS)7=fDaHv1x1r|#5@W*nsJVM`ofUd!E32JcPu&%7UCRX)p zVJQShu?U^G2!5YlNjKq;Y{=u*7b9-Z2*fFu6|FW_NZuv?`j*oxY4ufLp%y$MczW1f zFEKen!4Sb8MOAE!=Dxd8-qE>!J7|}nx9Dj$$ZRUpjx5Hm zRu>=dZ;&Tf00!_p;EFQqX6ji~^50E!UK01W{?&&w)>CV+%P7F)cH^*Wt5yOwzbE;v z%@YtsgNUPMN7q@c87QvCuCa+N>mcb9!<87Jo@RY(W9?tYHM4Qnk!eumbN)+T@LijY zHrcqo9FgJjun&C(c0{b>^JNxfeW-t>Apyo6o|+^4oQs=@Bxgk9PTPdIeUeAl0DOvF z@}RFDMj-=tr;k;B?oj)?#mArc$&R=e{PZnZp+B!>>P}Tbrs!ym6gM*b(kQ>j^0}RY z+J|++gFx=3t1I_{M);sR9_;6*s5iiP(o?`!4uu>%(yobu`6`7FLAiFN2yB`gwYuGW zrc%=%iNBrY1IkCCUhq-07o+PpZVw(!X4g-ErkWNy{vUq3@s)q5dEWp-@FSR9Wwf(I z)bPUKDmW$-lcHIWSBm7sb`&o|;wkp$r~z{ft>5vp;2EXxMPGT6_Vp9;Pg2MF$0gU^ ziRBv|&{e(XZ?E5frnMlFaGAwot(GBDh~2WseP^)HMXb}%C(n_%a|-W0E%@!V6JNz~S|8W*&5^M2&G`s6~+D5@o$pD&m-!5x>?kQ&n0B&HT0Q<0+2B~XGdaQ5); z&-~)I*H6k7zi&^E8@^d~U3BD%CtWY3_#7H$8jwWG#AKbX)0wWHN~f)G;jjS0DOacL z=dgnTLOKFq2=1AU&o)QO*oAX$o5vuD%no0Iwru0_>)ORvU{MK)_1mXYi1#zHK~oAn zpCr8vB61-T6D2Kui?7jM>}Bc-{j;4tn=8Vr~AP4e>DaRnqF#tnmif({v&;F%Ez(@ zd{s{!L<6>BxHMj)T#4u;B_qRr%iH{25@PIInj8HV_W?+Q)mEzOzr5B@_)9!Sxe~o` zoCPc-K9h;o_rxpqW;^x|{z4IcnMclaT81hLS5;u1u zq{@>b7U}kthCGOPuc+asZFzV1s>NO?XR7KUW0d-CByfvY>O3aJcimbid zKxf>ySg%xpMkT-szmJWWki z^!{k`ZEZGu{e$1kK(1zMlu@Z_-K@=%ZmEJJewc?Zq_9L+_e1Fsnfh(zd9j$A?G@%*WdN|_rI&jASxuj z=kS3JfD>v@gHC(JAhssxwB#5@ZGU?45|svsP)nue(_7u+{a+O+@85e;wgeT;HOo_e zMwXt<-VEQ<-w6{Y1#)6WvZ&ZnMiM{8BFUl^a~k>vo3eokX2^7-#kU}75gr_#%$Pz5 zI^76s<(1PS=&iT_oWcfHj#*?RNtCg)n$w;V*MPyi#(;3nZ#LA(9OB3sT#t~qn&pqc z`V=u@6%ER3XcLP`dKEHH;0o6E{+5*~kVZCJauTV6sHMY<#Wp9v?C_QP6SyJO*>1z`SEXA-=pshZK<%GBsj|>1{%5dQ=)&I z6ZUUGdDdLb${v;+0O>$ zHJ<6tepIxC=+9Pi5Wx#YGr*p#s=D?H9NgdMlo?OiL;12^6+iQ+NSK9mz?W)5lRgVK z^PS?{*75fDp9mqqCi{as6y|tO0${qfbheo<`H|;lM zD=NXu{R+5o&TjNSVz)G< z4W)j4i=4{vVQMc4nBEa$Xm53*40*Ww{ZKA}vodY_{BrnWJ2bew{A&MJLt7Q_$!ZzE zi`ImN=Ry^E>5G<%K~DS{$3cgQ0+i(td?On?PZMHD)UaG*a6BIt^`hrIg8Q-m`OzPc zZzkT^)3JQw{PTV$@%i_+-Ye7kd<*k1;b%T%eq_2>5~x$C@JMX!~VR!dIy{@wYi%F55Cp=k42Ell9*B3<9+*c{74 z|ILvfN??J1bZadtVOB*m+)W7H$p8)(TCc_VPdge$e8kDwofV9~=#x6LUd9noRm!5o z@{A+Y^wul0gQHc1c?J;`DiZFhjq_f=SVw!_s<7R4fjL~k?yv~HcL)54qFTc;NfqI) zJ!^~ej2LC@)QTAdP_Igt_$)*q(e(3676t|ZSTjj8DZ@5Bvv1+Wy2JzA0c8R{2)Zhr z@KO%1$c?f>z?D{=T8|cT)Z^2QR3hiWQnk!%xKc0N4uqin9be>{88+XJmuR!43!NdZ)u#>HW^8}io0e%6nH-EBl^_fz;adpA zQg??ljd_u{uBN&r5Kmr{2hwjvHl5s2<{>n1TuHStO6F5FFn;?Rn@f-Q{We=90T-&0 zDZZ(^D_CT%n_Ngm%bExx#2l)-DIv1~F z1w>MAs|hB~6Ji*O0ddnRxgyp&HM)>8W~Y5;0U*YxuD+aJqm^95*DbKzYT`i<{T0F` zm}Eoi`4uhjo=MEK-NjrjV!HnzbTBk#gq%~#n_gO87QyzOfDmD-aP-;Ksf)h;6JNbH zJ@)T|4nf_erY1gt$ytv%m#CnCse6{&f~u8ks1W{+u*MTevbU?}Br2%>At>6~)Uef1 zb=cOYO;p8Ggr_Zy_KUO+h9$KkU?*q-imI>HS7}*@;X`9wI28fDNrw&-PoUI!11 z*d(_&KP_qP{d@OW&`ke)-YL*Kzm-n5P?#$Wh^6&yZjMo=>790%bzTZT1ecjPTt)!3 zd1!h!+ikH-(Rg<4tJAmyABPlV9PsgyltrCX#i079Hte>BzA%gNcOw5}XWI_WCvp?B z5@)?_EI^{Oj#UV2v2<`&%xg)XznlF}_L;B61J0Z41Mi08j$IxPKOT&3U2fl$_jbEf ze5T~im+1Dn+l@lf)_)+Avl0^%1aqd|aZ3mzN#q?je|_-0`8FIE20?I0W_{}_>-$DK zCY9WA%imcq5jDo?S{{G?H$f)0O<%hawFEi;!=!#HhH?I{rqXt6S*zh8N%GRl2z^~{ zZ$fry9#~%<6M~&%z?E)<_?-HyJNl`yp?v99u9@DvdkUlu!+I|lmi9$X^*gR!RaLrU ze>G+f$-Cc3WBOE8>0vCG%$$)Jhxb-kJz9T=c{g|6R2z3HxY#5CFDE)n7DZV-Hp)T! z*tz`IsmOj!yAyTt9Kf}5mq-j7%M_3Ab}$KcdY_Qh>CA-S3t|0AUT+GI{j|OPh3$1K zn^eRPD@?ff6#$Zj5)!ke3M`;2OiHWKzm8BDh^0NWREv(!g-4P3QudJn!-oYIa;Z+q zI&hZcwPj%a?dD`aL;Z$tEZ~gIuKWzwZ^Uacu`cYJ>dlrs=AH9UL72Q`%bw8W-tr)i zZn8#EIwE-~_`O@WgzeGY`jy4>C9TKDw;|dAQEpxw#h%W?x)25{5fGN+JJEDa&|eis z{qCxHH48wac)qapG8+~-RL||@$ek@~q|ltlD*mE|y)}j~-P__5sYBq=}e+GG??Yqu}?|bzs8)>;>{#F zd;LkwK=U}S6e7?wrcM$Zp?)RIrpRv2bwUg@7|0||N+M|pO&~&xL{DQ=l+jlY#jn)( zt4~57XuI0w9Q2WTqid`et*iUziN)qKCz)@W>$cz=mt!O6UTs*Z0G`$A3B~Hk$<$6) zP}MP2>&wk@6{j3S!?vG;&>1+<1O*wC4WT@-6(bNu1^eLIrc%Y`nK?*<50Mn>T`Vt! zs<(oHB%z&qwx4k5r*fKR$w^;YwqIV#>c-c6G4_?g@~oDxlbgN)zbb7H=p$}s$kg*{ z>!1TflpldK+@Bx+4Pw23<(vDT?B?X;2=(6di=B0$otNJ4Z}=Tw4DU`|3or&g*Ls5z zdarl6yKauym6VjYyZ=bbXSS=PSex1VQQb4ZAXX~l*_fwJtC=EAl}BsD{Q{_6$cDpl zr8VC!89A`3`o}w?7K^oK*OpP05~8RnQ#P);Ub&jx|BvMl6S8 zLx(uD0784e&vToydH4_mQNV#yL3LHVLqkt9&0>VDnm|@Yog!@K{1pJgT=mv`7$bFP zP>C4bhrni#Mx!w4$C^Z<9M6Y{BN@wW!Og!l}5#44-RlLS% z#8<&Hq!~Pi?2mBNwmc)lv`VHv!d)LVb4afG(tR%7^A{plo2^GMY{72zcVqMyMZ!0l z7ak%^yaJw0vZk0X*MNT^HtdGs_};-&5J}yyY7|y+R3IUC{&PEV4+2VEblHd!bUwhl z2$VfUgK?gcT{gujyrJW9;`Z)rpRr<0cDVX;+-%B|KlV;QY7$%-? zhX#`~jmjP%StMR{J)~{;M4!QaPXi8H;wxo`ScQsZeNK4CP-QFjM};j@5Fu*dV-Vfam^u_BH*b8?IQx>`Ym2aq8@qc)3%3oMT1v5EO9p`?3X@GLcx4Fvt&`UIqwKg~?q_WXr99QA+7s z01yp!6?X)FJ_7Ok211mj`Do6N;EB7yfWod`v%KPr?oNVMyh{pH4~Xl=>sl4~I8(JU zTtPR}?eJiWd=COTZ&s6~*QR(WTCh47%r^AfI$BJ+9u7`UZpQEK_RsP>VoP6wq?4#c z*6TX!+LzUX6L&znYz)>9;#{1r?m@|@fN;6L28!MC0 zY|V_PiAW?A4%dGhK?w2kQ9ay3PKXwMheDFiuNo!2g@oQ0NOZUV3_Rb8+W0%t3Ifwy z*lq;iZ3H;Z#J- z3#wH9dw69aw;!u#Wo3 z!q&`@c>q)^#K&?YaTDTot3+cR+en^A&1Mv-Mx%%%L}xc9SaCHWTG@N+j2BniloQ6< zg;q{oSOy^0^1#4cj*Z4q{k6A~)&vDiG9b#QOCdC1lq&`pM&<5Mj3Ht!CR9w2U8Wp< zUT$A(-)L`4L7toq=OeEA z_!Mi_#O5t;Cm>1@gGA{5en!OG0_&mO(6eeS!?*#!Z}lxRW>s!BNLn0Z%wqSO!DI=5Z}M4{%C!S zVx#g79Zf@P_PS4xDXkLWH}F@uAsH;-sPr36Ag4f_o2ht#2rC?jk-o7WQ8tIYLc8|h zIQqegm~Xg0SC6#Z4R@-W%{ZzGYj_~}22MGYGe@K~t*XW$yJuW@GhD0B;RQ=%qFl=O z%wKH<@mquuVK?0s{|H!qf$uLho7yygQGIg>3ktFkdhd!%@w|Bg;qN#vo;ka?+zd{s zyF}(%K^4kzovP>F7~6QxhnLGFN4$)jO>G`1XMG_=8eYUqm7)09R=;a+4;kIGm5e524>g?>!Y^ocTm<|djH~#vbVx1ie)2i z0Wx!$%%%Wi;#J(7K>bE~Va(G*18R)3{5(iTs@WcvH3Sj`)xQl5#cfnG)K=XxanmDG zfT$a){)2K^v7fWV61ZlXLgUO(K9RnyW>(21y5LT>hOi3g%9?@*zNSPt0PvYxCdT)O z4x?XcdNZs3kas7LXBAjWflSTv@8-fVb0hThV1$QGRFSJsuccSLs^?>+8IIfnhhGlg z00Rtt5jFE;I>02Y96Jpf3WgWTpS8Yc0Y0!Kg6!fq+QoF|A>M?vn;X0L3nSyew`56K zNFZ2k(Naw&(;N}aJ$_umZn|WUkU7+uq&cwJ3eYT)n0bc2?Ebv~gr{dpR}wlq#S6_O zW@0uJmt-W-VE6XcyDc2h(z^ifMhZf$BH+Ov!4PiA_Ptk_dyM>2San%P( zjhsS>L7N+0g7_#Pxa2g@fKG_$Euf-c4>W^9K66)w&3e5J8M};UK zp6*-d%xhdmSl^fYJRNmI>;YbtG6ywdo1^OUxmtFTpwTe-;~uUkrc|MLbuQN6YW0b3 zanQIhj(wVge@R;zGR=*FqW;m89)y=|ETP`bwp!#*n+Lf3?H_+$LY+OO6+x-{XO}28 zK6H8P6}N6ixOhq>^drC08k>x;N$Gw5s1``4{Ub6Ng;54{Eh6mw{a|+U0E3fK0$n{0 zh?9VS@m)$k5LlyCc^|>u;}_Hu->mOyHc%uw(oK8z0OVEwfL%Sd#aWvy4^m)=@LyoP z$C>!S&y?{4)-S8!oTXCS?h%B>y^ARik1bv=LFYt1A?Ep~#xKSl>bpBSmjk!13Ifk6 z&NhDEJl{Y6m9p?XPeK7n`95wB&)1zrO~F&=91{~3%)H&bev~O@&+*5D+8@$N*ctwS zvnhNX{%b{*2me)$cTR+2@BfCw$gmLu)zF zxpr>DAQe@Ts*E(oYMwYOmTKVlsT$&#uW`zbwv0urA{?4yZ$s#TTShcmoMKk&%q+Ix z4@i8j*&M$IkE*;hRtj?#L^!*yB;_zCw1c)MWt)-+1r_3g9*bWx7()%rgcFfkLFDUuXs@8ByaS#N!b zDq@K?R(QU&pRn?^w1PlFUw!&2UBaIh7rMnw8&EjGecMSa#rI*4?8Ffcg}XB22r%Sp zl(J@Hp^ZSw$C?&&akO$*D9*7Tbcw6%tn}R2os#5DPZXIM-2!dviE0dU+l1Aq_B0f+ z>?pwfX{3g@1fMd)8KZc4J}LMu%2?Q^vg||)V)$e6>y;eRZ@KgO6F+>)4!_AFBU;|;g5ztYX1^L?t5qa47I_-^Q>a^l&?^Xb7W1C7oSR$6<^FAg0JU*Gf@ zDFdwD!_1dNREkKq35!6~}>{7*5+HZ}1B` zd(kaxh$(p#;37PV(d%sr`Vgy1B|SVl``78OU*+^(LejB9Ea%HrL4V|(;YGpnRp2G_ z%w=}vO2#qyrMxzuX4Srwq$_#(^1VGvcCY*&rv_bu<`YC17>SYwq!ju-0gW9^VbQwp zXyT$vRdD2ovSCtc`YQ);qmU&8@_r=8ObP{2n)IKDLc9Z}D0H_iah17MPB@1%wMp9o#`^4!wWDM&Mvwh>HD6zG|#nhu?O>gB@m}t@*QzSoHj5WJnl#Z9M{n9$Nt+J@295tz2-;{xg z5zn1V!cLN}bz%qIy;?XAm*sU?cS^jVo5TNk0s5kyL+&SJSOtco4IRNj4OUv}@;~wx zRmy1ixHPA!9e%tBjHIapQFsYYWl-F{J@#1qaqsKXOnj`HNDu#ZxEhU3nMx+yK|f!T z7Cay&Ct_fu&e*WbDC-RMO2WZgnuf=4 zjf$QVNviuIx{>Q6$i|CfJ?eY6%yKvW9GpMb>ceyJgJHE$@y6i(u=r$?aMz|2%gpi` zBa|u4x9DLW@r0axeX6jGuSefsFa;WFUG$YGCBByM`*Y7;&o7r61YB`p!N2Upw0!#J zeS_-Nx!`^Kchh+psQJk(@z-Oj()wF_0(m`!8ef!v9&bx$M|?=pa^^S(=vzZM&ZJ%` zfmy|c-*dnOWvG2OIYdMDXv!Yk@&O>K zJU_L_v6&LXd~4!m#stR7t}~OR2ED6wlwK`Yi*_@B`Jx-?`(n?uUOEgU<)s{|$!@g_pm7j2iz0Z!-#r@S=6r zZn}QS?qn%yctjuS5Dq|Sr(hG$6X3)}D-oEN?ng&pgr{XUp2^u`E3odX7&117@wahm zAx3G;6YVxWxU=l53VC}o#~2p050)>*P|Bw%tETXA6vsi01Y&%A(>-^{54bZn>88NM zB3YkNC8GG;+Q6q{Di?|Uc{tFCp{=nM#}?od|E?8Hb)+^p60%TDI4ex}baA1w=&8O+ z0VO4mVRvLM6(F*v&Y2JX8TM8-2t}ZpvMTz6meqdHfhvCD3Wr>9d>f9y2uBo{#9|r& zF=qdpX}C6z;PCr1z>UcOY#IophI!`&Luoo@OCv)a4Zu}THrBEY zKdzOgqsYuW%op_KyS=AUj8CemqOA>FsvrDz|vd*=D-V_^odo=wKr;yYUpGjWJv zW2~t+3#D<6$P_Jffj3IxyL#YWA-VSygQl{)#L>Z+!j&+ zK>;G4X2o)DogbdAuj|gPg4U#Z+w#iCgH7Mq&DfwAX3kICy9yc(jwAZ)ve7Z9vH3*R zG8zj2)&iC({4(;*7=>9V>sx+`!%>RlMuXn<^^HgYWYu||K;q9U@ssaC{;Q95D49W& zk!DwdrF@Swc_$Nu-we2uG=!7}>;wkVK@h5FjDcwxDSnKr5L7HMRpw4HXf3|{U&~q3 zs`Xu{2yENZU1TWunk_2}0vku=5o90+*WwrnBc41~oJX2vV{8?(jmCbBNxO$z#=3q` z_r=X&g!YJ0n5d4cS^b7w2oY`?OIAv|M&UGoNk8p^a7-}sNgjuL8sVAmX3I*~C7sB?A}&NPal z6#7%9$|f`{f$t_Fm=T}h+eEHfdU$GdHsvcyabcPAqiLN?`vFJUG^dm~gyCB&W@aH$ z3QvNu+u!FZtez)XvK3aJIIK4kAw>@IzQ7abhxL=!eSY05&Vo*>PA#iMH2jpKrhj>b znRH*NKkd_JBlN2)AMncXPMHWOt8!fDDkCQLjIy$p30YXkgxjLSAL13%@}jfI24p_F zw=FYn(V)Ot$3Ik6LWApMhk%-7hzNb{>uk1k5cco%Kfe;h)zh5?92h`C1!Uv^mVy4U z)@UdF$yc}>y?xiDLJYA;Fv}W(RReo14=33zokS@<|66PZ^2Bi}*6)X{6#l#I*fKu$ zMPl=wWbD1NrdeG%j(iz=H#W_$x!W}OMcfB246ORg!*A-#AW?wDyw&+Nd&rR3fu%bu zo1uI_R^>rtxy(5C5EoW|aca}~wCa~n$A|b-0Ytx;4DDx}qHqCmo0(NbKOfL>xeXOQ zrAu4Qn`lzH5OZgat!*lxR+AX_clXN?a(7jG@hajOJ}G&y|DMNax4?ifSrz*X?c~H=grhZ}d41y|0^FV4ISV=V_FJtOKPh(p zn?q9k>Yqg}R{@|WoE8&Paeoi@%ayi|jpUMMuzLJb32KTE*%y#eDk~l$DshdGU=cNM z4iE-jrn+*cMotE4Dx0lSOvBL)^kn#oQe^+S!y#v3bs+_XLuKzi+NoFabt1S(Kpi!? z>I)As#?bpK-5F0!Jr#mDR|rT#JRkIej;QpT+%qBKxjg z`h+{Q+zfo!P-kehbMukD#lz8OL=XDri+`K9BUWo?w^B&!lUL`HiPU4Y+d;kaDDwH~ z{crmr<;VQ+_5WK)uvf!S+Tsq3-J^SljQ)R4#(zAj^3&ZHN0 z^p59S1P|H#rLGM*$8ckT+y9#U31({Q1$*vZ>i4#DI6o>`by$;WgNp3px%E*gJa5EimqT3fVK5VzQInwpR>yiKx>MR1f8e`Op>=F7AKz10Tywe3-bY&H$fk-T9_q4y-d{xBOY z+533@^Qq*7pWwr3RC0K9+u@3_ox`+Ro$cK(yS2@_MY3S*s)f#6IW7nUeUID2JipfW z!v6xA`sbxKHa3a|)8|wDu3Rrys*%<5hM_0&8`Y>LS8GPODM}m<%gPeXNqG$fGU28Z z3E;|eOl%nh1>C)}2zU;A(R-eg_&n8ncfWi%_3!-QuN+54-T$;*3mo6csV{8qr~2%uHUc_&0zj}z`7%3S?iTSIm6W%| z4q8RZG{fgJ&6u8RIMEmnZ$sbmJ1{ErSsLi+?1kFl%;NB+_oeA2&D504d)59$w@}~e z*YY;lVFd6MiojC9+`OHsYS#0P?xZA_wrrr=EvyJFFI@ywJ^)|cP6Po(;3ee07aVkT-NnlClC z+95(IH>Y|Z+@4Nv8L>RXb(=8D=7)n)=wzbV7%Y+_=bkUSN2J1t#W1<<-g0op{)go% zEoE@*T{tMk!}SeV0OOJ&@~D}N2b~#?DGd87Q^}@{_?V`Ri?c{icsFpq34V{I6Ip@@UxFS+qx&oGs!bwR4}R)NPJ9d4s5ir_+!TN zO5fAjD=R`LB@02=q67rT%)wBe{mstJJ;pAXiIOgXKS>aAB^C5rptuIhy*iWTpR^Sv z_PL7GQo=!xU{9E*U$?Q)!)no4RP}M7)Th)HVMuTh01+IzvEA-MOufVfK^Z+u&mtf) z&nsQX-f5Z_lls?>|5NtDoj~qIAsS|l=$|F$#^Wfbr8dD;`vLxS)Y> z8aa;)Rl5J4hc+rGuy|%Fx%0@w>f8gm@a`YE>s*9Yw5N3#qqCId-4{|CBcg~Fz7mk0 z_`l)uGhK2_6kMJ1bAs5~+7{gXdDZ*0XRz^n`0$y#E+O&X<;K660xl_n|2=^2kqd<0 zP#sRQUV_aV3-g46RkM#*Ckp$<|5KZ6CQPK;V(q9Rv1tU=p~cCXu&PKr|1cY8RUhT% z-!4<@ut<}_PB5RUD^O5Kh*TvgY6C6NkV+)r;DNrO61pCnrfiIi2@nboyLS4JV3w|& z9WR(MPm8*^<{;xVPNEyUdD!qTn zs<(jlTvgR|14G2|-&U!BtS1?HQ|&WT+f}xwW@cg-1#(8*y#2+{)^OJQMBY)#^F%<0gMX0xxV0>_TA90iF{Ol?>e%= zrv~E1h`r4yB|Bv^Q6qa^h@i}`d?@Og`)cjjic)Vu4rihP>8Su|x{e(w(7jzb(>TDn z{?-^fw=?I4uXU!%!m&8LMqTw%NiNt|NRp$H35Kv&Ev%_zMyzgt-qjR?DLlDMoOL~X z#oyCaqrY(+z1#vNqbJ$lBvs=NZ5~-8)1n+THuX9D`ZdUNiBu)|t!c|~;qXk6dMCVo zb-Cof@Gtfdt1ns15S(t2Hc#^tK{r)-DqZr0iHeE?T7i-QQ&<}xPwCKbFbQLgsEHv2 zaxoJleC}IcYe7@{kB+E-c1OqVVe8$K>-|ne1tWqnnLT${-rL>KY^#|y9pc(E8sp|o z0+gP@(Ln5RAvjFgl(w#7%8Id5qiLw_BAEr$p-7j_ON|{b|HmJxZkhQ%hNqD2>g-{4 zYkOF4<2^Dg#cM|x0+Ty23I8cmKn1`K>j&u=zC9g?v08_hl0*gpzSnk~?4biv)E+MG z?}3{a`?ue?^9lM+Kr=OEqZTvN=oM84noI!cAcUt zH9|R_vy2*Ut3aA$fJVj6>>(pMoLVx%*y_YLCYpB>E`t6;xio4{eF!M-u*+bZMg2~k zI9YShK9{+bNQ>2&Vd^XYiy;d@rVDV8<38KwTNaR?8)2ydfjIAgg109OQzEl;J*h?= zkDx=y$QI{j)bp4{bDQM)pxx@YuIB$X<4uT<{~Z6FJH~Kv{pT@y#2qv7Y@(h!V8rO2 zmQ8+Py=6rOXzPfH8A~HSWyJ|GqAF8JLU2lsVND~XK0u&vGWiU(hiZKu}gZ(U`V|2}2FvOSS3d@3Rpua3|}#A{{VRvHhgBOap-#! zr+XV6ZVL2m6l02frFLbIaKrC9V#=|$NoEfVM*4t;@8efuoFuNY!%IJp6o0==S#VasLk5h>Plv4ojs`iY` z$yDB^7m`oB7Q%`f3@*(^TiBa79~ok#k-&$mx;BCBS?3r?6}-aS$ZRs$c^*cK4^ZI4 z6_oi+OXp#_e2c%qwK^OsTSg=VD{_ZXZbSGY&CpV9ekJe2h znEdRD-Lw@V|5`B4C)h_97u$L|oI9sjq^^cp5;yRWS3=GPv1CYon8L@v%f%OWPeX=i zjuxv()W^S)+aD*)-G)LNQb=YKJ2U=>n%*iZU~*zyY_n{~x%sDQJj+@4b830Jv8R@x z@^Rg|^Mcu8Ez)k`X}0RsBo_SFLtHc~L5q!6cS<2CJMt|x31^JF+_cl7l z{x+bX!&(z6CvYHF8x1%`Ed=YIALfPRBs&o@31P`+;*HhOQ_>R2G~7wgm2>soL~I}E zs8+3M&M3)T5o~W!rWs9`{?~($g6y-bDCPe%8cn`xf6QcFj_aB)O=DCSdGjd6F_0^7 zm>Dg{K2w9Pyjq%upoJi96JqZ(@R0AN%;qmQeY0z17pq-K&AjypD($Jui!sn!hv(+LeEy>yoH~g~C7*(rCmUfL za&4>90;7;r6f)1#Yy=dBb2)x$!nM_uUXCpvpF8(_3ii zdJo;mg;#6mS#qL-YCaD#XE^Cf^tmz1yT%Nq)nB^#eo|HzXlgW%KbB z_|xFB!w+2NJq|6ymlV|?)~O6SBJ!8X?L>3)V_P5!LB2)kELxVy7(YS{2#T1hPt8K& zJD7~wQ-F%buo`D)S$xeQze&+I+l#!>FHRJqJD)N;D z*yvK9NOZR@%qLGaE|0vh*tgpQ6Nd~k?CxoOv^PfTJPMTfM*#;mu*-NN^O4Z3g85=- z6VN+KxJLSzlfzzK%IALk>Sk;CK7Q)P%>HMHPV4OY+a_qSG9E9PFu~Q$RIHBbOLkGUL;!*l&%1i@ilup~ zfXY1R`S)PZyj02L6lDFy&OanEqv!R#xQ5P#ErlRpS(r%~@c;32R$*;LTeQZ#K!D;J zym;_p#VJm3_h7|~6>V`S?(Qzd-JOykMT)y?DGmj0&N=tqyye@EJ2Pv}F~=JJQO%!r z+<}Okjn3C|wHN!&wR3K`b4d#^fpcT^y!H#i!2uq99!9>M&Kedxr}h>;M}^~=`0OP) z(~cL(!^imOJRjfnvumT0?LYS-R18~&Z2vr+vz=eZJ6%3sY&df++}Bw%1*!BCIA(a0 z={jx~IWo)txFdu*>vLuZYYl4uZg%WE?zpKm^jNDr)2Y(7&(sqyo1Gc|tktQnw1Fxa zG0n#@Q#{N^-u=eaOBVP$Bg#Y2$#`_thdj9h%n1kp^VYen;+tn#ry?~Y>m_z3U<1jh zwn2oFw7chM)~u5w)fs)PB`n7r%>{jY*6xhlyy0Bn5c+yj=Y4(02Qu6Ll~r%t|5X`4 zy_7yxXUoY$lphy0rVTC;zvv|`*9Oz`ZymVWXS(Py5c9ur{{9xMT4Bfbtb@{wqdr?) z_f~(}9hz>P9p*}@nFLnUPtlrZ$LxIKh6qk5JI+QFbNgxcGzWhS$(ke5jf<~BJg>xe z^**(tTyLi0RS`xPW&4s?Fh7&1mxv&-KZUZMRq z8d_DTvf=nA@>Pid=z^_xhQm4*nysRCixk`NY4h1NYIYgqeX zpiEzLHYURS=G$RUQ9mtq&|c(u-%PW_3 znbby;yC!6Cj?6c@hEBL|I-oqR21h45t?UQiJf57q$y*;RlbpSNa1{-7^SRh=ssB5@ ziy^K0b}c9oqZZ{+oirnQN2BO+IwwPxKpH%2yHMWpS&v9lVW!B=6NSL_vm^riP1fj) zGXLwNvCVBbjt0{hAzToSHK|oEg;%HfYFy`FPXssO5Z+C{kH~D3nUD8% z$f9zYz9BCpVvIW$_ppJoY{$TNd6{5D%>o0vk$u8qK`Oqq?ShuRUWpg-Hfd}`ie&$t z%tXWPo1X@dT74tFh_4z09Zji0U)+Jnt_fI+qM?)*GFpn}Ky+*dDyuck<9#3~R)iOR zC)pv(v1JL8)%&c^VO-$u$oB~Uy6^0~`*5(*ZCy)e=tA7+%h!`&?-Dl1OOTzzu5!Av z48by_cOwd@T6_!85W*wf@+wHt+weDOJ2|~V%by!?Ac*=<5)wQDI}aVUvg3GcEN^T_ zwp4y58T?(ewZKCkh0Z3EppAkt(dBab52i5hUPXDGQHqPy7Ez@HxS0196U!**;f6M~ zlxJepIKT6=uT-Q3Xz(&yKxWbU<``Wx!NvHPN55*Fox0OjM+Yk_V2_XU4gg^>5wXBO zL4GM(ZM;1NPRq&Z15UsF#fcSwo79!!v%ZlR$9AKqQoO&f-ESac{I?{7KxH$|s!0VI zTx4Dkai32dyxR*R_(ePH3K|Lw{1N#_g{mi__JZ9f42MP>=18vhqB26o zK*ySA5RJImd4+OY)HEW8uF zqJJ}UQm97r9o*K|4TO_h>4l43Ui9hhK!5KOFtd7Jqy?FJ8kO#FOVZzJih(cP#!<#v zZKVZvF^IP^F6^IzG2bGwV9|G);P-TJq9^Rw}~Jp6}T zp-E+e`C6QMF|WAuXP&uL?ZEmz`gd731#RcY&ZJu3&cj^vI*MMavlJ99Ls7xUs5|_x zh)Bf>5~qKvIX!TTH>et7*EAxiFN@rL|3KIMeZTkwudwwlok?WGUct^>TdM>GM~@b3 zW0NXetqs`?-+s~G>YVCv@p-@!%7~p+3%ngycPQ7A78Cy7X=k8Sw?dMS=zY7T>*ORZ zBGBEVAJ!34_tvjAz3f7iFk!m2=>vX$cqzR880@1&eyr1i|K#6O>M;V_ChDW;! z@u`-o&rAPe#G1=5hvf*{sPOaYM^j)FD7b!z_(;l8|Np!IRO${BAWLJpl~0W@ft62J zG`a^-hud;R8xVLcJ-q6#TO_h*3SzgWrn<;7PM|xD&?%<(Qvp#F%#kXx+@0L@QG)FL zOy+!GM+!HvBoTB_fjO23hdPFbvf_Zmxs(!+g3?uBTg|w}=-m8!#k9g0j6pxw%-q6> z-M9w(lAki-4uO(_&^Zm zs*JAmjw(4)cc|`@|Z&3oJ9CB*MXtdw~s)6JmEfWUa-==I+(h!iI6c23(Qm65? z4U1(4b9Pm6l+KFeb%S%Jg6tH{A-HanhissXBM5A6?svCX{a|Q&D**xU$FU@3w12zo zA@5`ysyAB{hE9Z@u4}_NM=Zui@1pk{*l6?@!m<}AtWlYW6PfMQFHxsu6!q%A=F25= zY?f@7?GfG~dASt}?HpbJdXSkmy`nTPRR&oxK$5 z_VM-b6`?BI^W0v5;IevrDl-lupFZo@{*(^~BU5ZBJk-K<k=fvvnyy$~CI2Ni+3&)Ncjljf3CP84Wv^B)sq=^R;W5Sip9x=bN zvb1i^iN^6Wu%A_s7!yg0*HOuxl$VfT*--^{c71xfJCtgz)4VWOqjAjcbUy3)$?=yKJ4$txTG_885jrdc{9(f4h0ip&tW zkfDF&mnE3ms)^RJy_4TPy;HVg+kOFy$p5iGs2887MVb~TY#I!Y>F%aATxQT%3@m+jxth8 zU{<4+=(j}g;qkv=?46O7xFl&6Y}NhU%4OQ!E;c#3^3XVOvUBE_{ot89H8nL!8730j+AKjBkQZFc4(_ULf%zSem8^EBnye zI?Q}kLfQWJ{p;Tg-C$p`(f3+bzd72UU}q}2r<4@`zsp0udX16Wm|XTe{BP68d1;h3 z)!9{IUn%!}AT%9TZFdhr(yLLAAVRA7lXVFEex}nZ)81Jl@D3T684gYJu|>B-R|r>q zhdYBy%9QB3sbDlbMFMCZD{m_^D3ldyeHeg@D5I%yt1$nxyji@aY7mJ`2CBf6I1obg zU_qigCm@90Rcdjg`;7Llt=84d{X>4_l9=jCEk?>PjQsHM-H-bu<;>x78 zhe@2&hQ`mz5EVk4K5pe>07I!++TVd}(k#)KE`&iHG)G5?xcb$Zf1ID)l>dl}u;LnL ztD3i!xw3R3!L6&Qu@u+VNt`0PQ4J|@{L{-ZP=P$**Z5HECo5ie2>39w6uTq)&dMnN zM?|QO8i7W+_t0uLb#g#q=fTu9Eh76iwdXtR9+BbwY`fh3W|e~Ii7K(5gfw#5<3D^S zWmX42hcmSqbh4~+%C7p^aU^y%l~P^VfG=@&tftT?d`!G^JM^j>RO^`yK4Vg@V0p!1 zzcbN;Ac&wtVZ6qQ-I?`XB()ma$k0FCYSdp{>N~yv9)9bSaSVJ!A3PV?iTIHg__+V~ zbogfd>Sq~4Z324i8`YXBZ(8Em_gW>?m7zs&aKhknA*3g@@4cQj{EZW`W&~K_M)r6R zP;S5%7_0Fm$u|Gy7B}qTB*c9Ejh%7BT{BZpR(Af3PgJe!+|1W>H@EO1ki>D7?w}x~ z2R!cd-fz**11_x2Mwl}ErC3o?)Q zG08;2Vx2B!`37N8*F!mxZNmkoWPK$wtK~uu;K8sYMSp&*!8dsol<+^;3aJ#wUAszUl@8+wKYJdh{f*lso%GB z{P!BRaE5)kHdN}vEb(9BuQ*gDGFn1l`fT#>jCLN<*izW$ju3+SytN$}lZBpwDA`{N zj8vc65|`T=fLZ-s521<0g)Bx%elmFk4}=b6uHk4Dsv)K0f*%^nvCRSHxS{0)+t*wQ z4P>vB;8U(zOi-QrV1!tw7=xoRUtA*)WeAL1;zfY`OV%WB2=TGqYtGdhee?-hW%eDS zpnmn%`s?pMwXVeN)KT1JOj+P!vZA7T6qyNT2uETN%GbHXJfj|s59aPFXM@2`R!O#U zc9UiWOWaI(7EV@Ry#Ja+E0yw^{ZLc`QIwadmR+v%iMhfC5ISjGl``d<}= z;YkRgcM2I*tR;jFF#7;4K7q+fbY6S2JyuUCKH^~ zjJDO59o4ORnPJj4DPlV-{XF zx@47y7|6z5En=Tr@VROb;}chX(5T{C>E_s@A;Y<3o3fSdfCPO_Uf#2FbY>S;BgG?3 zuJnE*5s>KL$o|LDm8=y6(KkEO(d)pNz3lwe3Ak{B!HvnQw6*ZP z|D2^{sHal_a|OYAca(9i35dg~?b&4s#4g2?70#&=QI;KAMN;PgLcx)#Ekx8ZR+$h4 zdjTx~#EVyxzot1AJd~4>)na?`GjXu|Gm-Kr{X2N9t2|^qE7&jNz{jaFMt}8<%z#u# zRn^`)lEDTDiQu8=%*tb~t%`y7=t1g=bi{(pK`@>Ac>O~BKCMBaVgEa7C@p?y zG*6QT>5Q?$+?MS^;yR61P1mg`;%)M;z2gdH!hC)2!fBY5-p9W|?TkM~CKHDV8~UXx zPUKGm@Q}R#Gf0H%k`|N}@ze-ExhGel0w(YLEsu`MV&qIs2flzU-{n8vx1+hT+ zAl@=%a8)y#l1|_s2P4s*`^_rTqZrC|Wx8i~jIfM)GohN!dtB*@wP|70 znt5p~VsVkBi@QOmWO!`0UkfF!$KB?`lApj@E_GnQ-`R^fiH94(jeRlyhnqC%DJ)+* zs}$)0uhyVPM21l5daBW!PT18cWDKlYJhqGQJz^)|sMd<8nL)bdywrYBXr#5awzgWN zvM?>7(fHer=kH|@OjGZeVb^2&1{TxVQLup6_bYWF8FOf0=3ymu^A{WR6IwzBL3%{w zkkOi$QLBB&^N+s&O-q4XpKE)Gjk|=Y61htfi2*5`DI zv{^uOUl}KQJ2$0PERF;6=GfMBHi%`nK8RxQiinPhk^xGzw{h4gvP$tsmORtM=>bQa zWC-}hkB#p^s~mM#xOb^KTs_e@h)ajR{iW%e%WV=lKhdk^PBK`!5G)bm(3pV2i*QmR zprYVL89zLUH9{Bjy<-S5(nr?u$fD%n2$sG@sjdaZ+I^|GV0(23jj}!&aAlS(3Mj;K zf6TBVizPW@Mpkrt-d9Q=!NsQNcmrdeEhliP+1m^Fba9LQ72#viWK=VJ_^D$jLJ{J~u*A{mY)FU)0Tj31se|4WO z58!cOzfS_iU}bqG)U`~PlSsTu`ttMXM#bDS4eXa=u4d9PMWXb5-J%|2uBB+Wgrx0; zb&HReN2w(qh{d5$?W~qzV+V>`!JVzyZWGs}sp5)rqQ0jK|NG6E+14MXGCG%Oh=!5z zcqa?PjW$!cJ%-jqVRCCyByAxD5VKk%oYDnS9LUEjVgzK~U^;GoG~U0ygX*|XTf0_X zUm8S2#3*r})`Y(AcpsO!v61M;Q6DeiaR&6kvv((YpKAm+oGNL$?^%xD_j9rXKzJA= zgwZ(X=k_(M?h(UV@i76@Cbnh>hM$|jGP99mHLe5rvLPSr8GwIG(ib0GWvrkJkZI%1 zxz!M*kTq?7HZf9^FcEob5hu_-*=#I71l}1@Vd$mmH$RB=GPl6vHvV@6sqO!eC7A$q zJ=D-Fh1RWiUXVy-GtyW+85QG{kTqky57jEciz)+^SYC9ve4Xuy5M({l=_X=rfEz?so2D#Cd*y|6N~OwZeOgTh{+ZwIJxtE)EecR_L~e zI!71mM?{I41p8txxweH;Bq)T47*i94@gIW#*`f@SW+m=wO9jc~KCLb6^-wSqsKlx1 zr!GAkq!!K-h~|ry*?za@GvyQdg$xeE`$hkrch;@UTr&}4Q#flFa3iue?21Q4{LwQ_8>)p8I=ns^GM*6A->h{WcG5Z>!;DkUseNNHM$avlz?NKXMP8 zk4qg3kaNgnosq29s$bopDfP+8(YBxWz18bp{d(-p9Ub<(dGBlM)7q=Ym-~w!wGwUb zW2b(|H8NcGudaSDidMf)`D;8{wr>8j?{k`%7R;jp5{ktuJjU_KwpWHy&G(YNu?O;fE>Z$Ja-@ABSZq7uL^pbj6PSKf|n(plGGNAmZbMn7m7o4Z< zWdMKeM+!kF2+~JxThS`w;oe@x37Y5*3?*ZMcCLAU>G1utxqE%RyK5zZJIMWgM=0pf z+}8zkmVCzcqX!&*>EPV^*p0ps{P6m3e&c1}#`i+?LOdhaWK|q!v31A~Q&nS%`s4IP zL^gd}1-;oCb5vWM+E>CZ+OVyq`6Sq4-qwK@>?J5G zp`>cgkID;Z%+x2wCPmOh?q7?-IcLgH)5fbeM}5WTNWzvDmZ!Bk_{+v#Lrb!h<>>)f2a_ZbaCsnoVAL>$M1RL;w} z<|8ZQIFsL|{mCPa<|OE9k*hNUEse$d7=C5xX^pevUzn82{5W!CjYPDjv_zI6x&zA5x?PZ9mD9yr-y%0u@Dq-)HN*NKbc$d9eA{CCDO`#5kd7_? z?wN;h#v(Q53#6vLGFUyTEko9rinaucXSjgL3!=#z-h%4Hko_(`LjeF_wVM{TUZKIQVTI!KKpV4C2QIY$^q)8P_iy)aQ!^Y`2i0k^^YXH@6`k3-n5i{RRg2gg znlo6Wa}M7mN|NFImitnUGopXjHiDx$iE&xy%pUpWA}=(;!WdQ2=sjG9&Mj-kayYQG zXGAHz#{1UBfenxeX~(DSEL?^HKc;mUex}W2RA;?mO;A`SumMG~Zf?I(CBW=GHN-LK zLKf%ZC2aSlLW`QWwNIe2vZ(9iQZl^KEGS^dG%7RsiNG6;obW3qm?0_4*y%Wm++9I# zImQFA#Z6ulb~k$0_b@Y--kd_mCYM#n+juAH%<@LEP*>YMJj^+YJ|yDYD>`XE72{oD z$YppDTnsguFIL#28){wPyL8ZxAnQ#-5JI?WkUl*epDwIpHAhYwYCW6s zrzNE|jReKwrBFoG=Zoj9;!g?kpI%dU8$R9xrhWz_&wp-jmtcN>$M-O$mHl%`?v)3& zF9lMHBfMVK`81Hu#c_7HN4jmBy}(*_>{q`AQz$!_%huJL^rM#y+|e81r$`I?s2yS> z;)v+E9LvawtG2xxJ=WjSIKT(lbnqU~H zAa(-;1hf?k=;lwlZIq!pB2J*?-t6r2(fIl4_3oM%m*up`W;z@)KIh zpLK)ahw!|BLnoTvm;3qq$Km^J3DHM937VTo9f^3z(I+NVTgq*2FYuk18595E&tCfFZ)DMI20`;VSWxhOUKm9s8 za~9k9TnpbQ{aYtoA3HE!S5#q!iW=Y3hGo@9_(+!l$oxnxf>C${TQ!CdZ0sfoI&-Y; z_L;yTjC$-Xw!0U~F=P5}rVK_x-s&zwWZ9w36@w9szY^EkZ_~~1!1If@SqIFw`y+BW zUeq~GY&s%73kqLjC5i0#HFuhmC)U2&+R-zqu}@&VXExV~Cg&o6c-Rz{*0?ty4>8c9 zDijaxc$N#d)5DiNDAu`C(2mVrgyL%3D`En=FK0zTlIz58+7;UJ2ekOFJ~-_k2S`{p z@@Y3Nm}EUTQI5J&j*!p$RYoyHY|zIic{wYQu8D$NK8kq>HXjlwzbPuJz_3z~Q8QIo zO5Aq=08M5#bF~qcYWH#D=%ssFaM3=Cs$rL$2eXHwtTrGm6@A46uqwsTr7Lu%rYfp~ z%PjfPmL+=1N?qJY8zYD;bQsk#XlaT$CXU@K434f)q*KjG;~^++H+*7XPf(cqn}osd zpn*?RE~!Qo5NdyEqQI(=0 z;;^qi7~zl-;tdSy-90_tZ=b@EdvH=fBf5=jTk8AoDG?d>em;N9gi+;{f;yi-9A@d2 z8EFQbrSfqHqZ@7i!j1!9y2Cd-MlS*$0v|`6d*0m3bBRj{VKv?syi&c5)E-n;l|l^) zn}y9@|5WDV;$1kQ5Q|&1^QmbTIa*OM>NiBwL(~xKlHd||1w1m=Wb78cug$odL zNJ@seeF(lJ;v}IvPH~Hz)6i6vm9}u-p=z+Kg%Z4!E)G$&3ot_FOYOl?A?;x-P#d#_ zQlrH;#D%dGA0_L|&#%#Ka0Br%Ng9*sBXq9Qs{|4fmqgn#QInKb2G{}8?xX4s*lAy@ z_!-R!=ma&32*MgDI1S5Xe^=yyz&Ic=eT&-#;8!%gUHZNa9K&Y~a+u zE6UPJ%1#+~Ajr!WdDR#UG*}ak%!$G`WkFJg+KupvHk2uP4x7SBCRc72I~Grk}i%TB#2 z+T&C?vyT}r>8hrKh5F4UT*LGPN!Q%|*}TE za&Uboo{snC*A#xVPl;kduLY8au;9Ox=Q;o!`s@2GVRa_7<$PjCL`z~@IVw4x36@#u z;k;&y%H%Q3xAdaHtXTEQ{dGU-CaP-WWLd+1(_0g;_?^X?Ns#LNe)!U5w#UO{{rkVA ztv|-Kf<^&f0v@UE0-wiThl?ieHdeEHac95pFg)kFB5(ZRa zYP^iX{AAXGk2m$Q5w|QY$iu(5H3a_I9x~2TljJgWapb6s$oRROwdy)R{k#l@xbm=TZ68E~6wI|3WsPr2?J6*NMw~C4qLxw)ydZ;Jo!7zDd3@S0I z46XrT<|C_F_MgZdDr7^_^@cKQ6LlW5bcTWAvInaXyko0E5@*cXIdBR6Se78@E!__c zcy=TB9ic2;9J5OFwly87N5pBxiFH&M3SQKG?su??b1)99;N;0|x-%GM)Tk(oG%qMMzj! zM2sSgu1=CD{6nR_1BVPgLPRiLe)BM5X);>F%~ZiwG#&jN?YB@Vh0D@!pZ4k&x-QbU zsD0oZqN9g#{)F68>O7o4(h|M5P9i^>sCXjF(uvNQ!$axmX~+sb#aArUkGN%)6?GCu zD`20-;{R{<5eOQFh!hPKK=5&r)aFGE``VLBd6>vN%rJfEKPQOUActbiZnifABfbl(& z)P^Em;y%3dH}V=mZDPA-O+R465gvdlGl$@ip9=unND};d69vXUglU8?$v-0zO0wpO zUT`7+zmSm=B5((X5Z1}zTgW(~)OT`R5nS9h3ivJLc8Jxt(txgzGjd}#Xu^IhtifA_ z=cPe-CTpc>=02W@u|#)vRYpZ6rxK;r1hy3;j8RmaD!x=kOF<|~MJ2;d!voKjc1{_l z7lI0f@}_`CTtz8w;j9d2liuegE|b+&)z(=*e-ABw3(geJW@_AU<~W);gWJxnt-(eE zteml-Sq>GhxF7pI!m3w(*#`@;qYtnZ2l#KyI&-c`pI~)x%^HEE0<4z>vL#jG0O9P7 z?}Xz`s!?a>8X1XF+H*AHNWa-h%*>gxvAHs@L3|5nJnY3G(iu`$m?X#*ruKU0^{NYeyj|Ha+mAC1kTD}@^Kq!*=LnT4525a8S|0(Fa{>!X zn!OR%9m{aG!IZYk2)dfA^9sCT#{=w;nZ9_oC8+4jCFg57@T>e&CUt?^kNd$QJh6?&+ zRG&MHe#a&V12sP^vW@s>5M~2A-ueFW+)_pSokjbiZ?PnlKb{jFwhnPOyrVwHkZO7Y zhi94#Flq8@$J*i`kvPiW7h>d-4bCZ3tq*7rh;VEzHzrYmoX=08)tMnA()(Bdd9)FH zCO6^}20Aanm~$Le?aeulNWXJ5lkYwpq7^ei4G-l?-U0 zl%Ch_8~i*xg{FD8 zs7PTOEkHe=dIw2})~JJ>iB4EJG&BzXn^FrUQ$e1uwPA!N5;B7oEgVMto;CUWEy)0K z7ft!6H=_h!aYlwva?6g+Lu)TE$=-&L5!!sE=Sk`x_*rsJ?U6s@JiP&uRR$cEgVgJe zyDYB;>*PXc9T}YuP5uaZ42o(-)}COFsr#MB`q{dBsVUJa&|VJ8lf5_Ys`9>fy2mmW zu~IrY8MoL{FXp=#sH@*?%F|PHF~m?^CYBx1I&!kB<&j4hpS}FMpM`g@v$OZC`3k`M zU9OZslRStwvPEM;nWu7fejpg9MdIKfC&VX)ln?78mVxQP5j$Gn+I{tb{Uy&K;5%S+xgjRWO33+2RtaFE25^Cj>ZFeDZ<@~Am-&dG418xN`J(`Z*D&?LmrWj;1sVS>A6SwlMR=f6HpNAA8=B zW*IYUuYZXU|E|Mf>d}$D`kO|U?PT`$`jNBp=c?I3fy4LZ( zeml5&XRf29duT)v^Pe($m``rq>~~h2>4#;o{_;nWDn1hpT1CSWL9NQlA_063`BZU;mn@7FjtuB{mwB8BXg*63FNhmJ>RZCFte(m$%yoY2b9msn1>ay z`{Twc2abQp%l3|+RRn>|rCTVAXfVbD`*+I%f!eoN`a}soxakaB?!^H1-Eq|^-yx9k zn&>~JVV_2-G~+by`LJ&YC7+n%^%)4vt+K7t%t2sBEd0h4u&9+n<2B_?6KllA;nvMf z_{D>W&CcG|ALokopy=s5s@si?ILG)`H~Y@tg5j<1LkrpZ14pIgo(iGJ491lZ-U+P9 zlu&ehC6{SmwBIZ@bcJ7!xlcWJ#>YR-3aHJ(U}p_Yr7G|pXmj%5OJArvixOV30zmk3 zwq(+D8;|p(q%z>|pV@`wE@*43ymq(P1|%%ZBq^+qVoz84|tgQ{Zm)+ zbr>$0TRFbuaJ}9>wbFD625xQN-~ZdE{8LK2FMrK8jOa!Pm^^_YaAUK;J(;203>PW_K+S2X!{ zW;jN!_doVK#c{*gU!`_GUC>uoNwnMgKX%(K+C;!q(&I*1J2p#*((N2*BX(n9A|B~1 zhhvU4)u6lSFD%zZvWV|wH>bxQ0Y2dA$a5@AMEt1KJQYrmrF@d?^oo7}tbt=h8yW9{3dx=!B{DEl8hB=G6Hh@RU zJ2>4OGxjb8vX9Zt{)woEeK{3!4s2SvKnAx!c{Mzr+B4=FED<$+QYh1tI$iSF>lC9& zlATY0!m+DxELl?`Z=cqFX&Lf1E)XG_wIsXXq-(*gU3s9(00|Q#qwhPoA75@Ga=-}P zyavZAh6)m?24RHO?>Lh2wedz5emc7aNrvS+&`Et{ed8LXTB48!{X#TpR8X~SeV)iX zd!in>2+QO|AVmq!=y>9ey&Syy+=aJ?1X>~wb#<{d97x58=MHygHFk1BQI#{KWDYh6 zif55LptY!LtZc7h`z>|+b5n%YCtW?B-?2ZTPzZe4AWeRPm2i{HI)Hk#8@oVc>&28M z)RNyvQS;jc%jvoPFD1Hdwaqz{5{E|sR9??8%$ly*y$4dzCD$~epmKHA^}+C$7^1S zN(&Y>D~Lq*($h_>$ty2X4&Lqh5|_O{>&^Vp)}88R98KgeO~qFx%Z*UCvySyWHr2tiP5CT7>5pvZ2Yc7<{pVlD9%4(atsITb$^iRi&+Y z%fr+QYf`j?hEYrUz@Kp&r(B3n)kX!;HtJp%TY8b~wuMp2nzh(V(OkXh8)LJDn)q?9@SE%B6@8L;!0 zrf0o7z$EXLOYN0E$TaYYBJ|!N&D3f;*^&4yx7%@5ZzTg?ksQ({)| z9291d)iHVM8vNbRF=B1VND0x;u5vkjF@HHZ0?~9o1A%^mp~unX0WLYfbqDdXMp=?p zxcH#5(axFGh1w^ph#~mZ0#i+1tNkvfQEAaPUD8&v(A=|)U$fbqG@?PH)<=P%)E*_G zt`d~gjQi_2j_f&@HWA2;KCN{Tx-(F?Em=p95P{tct&6YR@8J{Gw37P7o!;NA?^Ir_ zu$kD$0^rkZW|_C7Mlw(?c1mXFX8M-l)<&C7Z*yQakBSL*d!S?|NQzo`YNGl6nSB}= zpBvbkZR!^@(Y{`*A`1?p?PTL^N3)@#!$QLJPL$NjV)V>o(c8>!b72CqE{Vwx4Ge2U zrx!Jsz$RRC8#4f^w44NFRdyzvTt79oT;*={&(Snz)GoHjXE!I6{_9O)S1ebh+=A%P$}~=3Q_NWx9x@ zzFSy%_aGUT!uT;qzsj@If60w6EfVM_^bolpnckd>md!sUQ{I9axtU@g@MmWScAUaGi)UPWgG4+i~u1-g)&A3N8Y}K2{m?^5f#LiOxpz&iYT(78455UO!~;nEMG}c#=0EPgp6O>q7cs0h|g0N zEtdsK%1{E(e;9UVP{U;r2^m!s$fdp`6`2e4khm%>WT$i{vkv<4v zemA(i!tnM2Gl7nncY3e!yW#t9*&Y&aSE@us2*#c{zmw{!@3upM5#(!M$Yv+PWNvSk z3;38AWqaN0bn3Y^o9N_uFeuHX&iC7LPq0$#RB-oGGR4C7tLUOSKa=tSnR?s_LX}{~ z5s_n?5My0EyGI3$ai~5+k)=JR<+1CCf_&i}^L_;nvnLaTmClwYp|tRzN``#tqnER! zp~2ec4~q)@=9W!*B3q`>Uc{asv`?h+2{92FfY9@RrNgro^n=z7Z@#Wx3g_FhUi41a zfcLS1qPT9Jx2M;CPXuR=s#g4o$_%;^K2&=BFd*6at`1ePi6PMQvOdoQL|1r%vP80B zh$aq{q!#P(G&mtLIbEIXC@%PqTV_1bqjCx*{k=jh$$RDI1Upb5yayv#l}xaszY&bnCE$eCa{lvj-S^kg1NW`-Jr$}dJFYn#s63nQmfj5mfY#krV32W3jSmy?j|2Y16EWN-M3ri#wb3t z?Mkdp`$3tBS-eAIemr*uRffqlE$tjmBLlJ_vZ>adaV#b6gnV8XxM^VR6+aPlKXTL> ze&D;31#sUfL}nqg!?3MGk#&e{282EB7ZPkSc!ZEHU5SN|n6=`XxotS{Dc1qgcsHansImCTeA}vCDO(1w&7_*m|rUWk)`n%B~L za&c$%2ckFxx!wJajy)G%656>7+TDYKHy7y&uC1lyHW9yq79z$-X5(`<2mX1ItwZBn zZX!%xm?m79Mr{uAk{?SKUeC6I5AZ6w<(&(wVN2v7?+;!EMO|RcXSBy~#7bwa;YJPZ#7+O$P#rSjUjunj)f*5padF-!JV} zo}IaPoV6w?C!;g{@>5|z?w#6aE=t{hgPRcXQer|SpGL3phJ5sE2F&k0brHI>q6X@) zW4IZ_ma0L{supnzBvpfqSlPi2Ths3%(&07aqdmvFF!c?fn#^71vlvpXY5Y&jEzcZW|#ci>Df5E6yW7%lgACX_tmR zs1xM;3WVu#e)S4l@4Q}2wf^m6IoWr`^eH03{no%;RdB>egp<{f zfIZVH(pTUw8Q|cw`}exwf{>+OQN+A`DYT+Kj}rtE)gZ28!bU(cB`7vYyK@{Un^?8B zu>1^VlH}Lcj&iEuSEO{*ml0egg&KVSX7cePVipmYJg9QgDz!W#E=nzS%O6Kuj~B9} zg=#mtGgI6t(sW8Aj&Y?5*$jIs%kytxKbsj0zYz6hn$I59Eo(v;$>-A#PrdGer`w6S z>q~+T6hB;+v7}7P0m#U~Eu;cfvK?Nz9|ZOaXbl>)pB%HPm_A-a-fFtDxDc6IzHe;O z2ci5Fb!4iN5Cr*U#QYzo-uf--xZD075Cjp0p+O{uMtTV8aE1nnp-YLOLqb|Xx;uvM z7)nwa0qO3L?vSCo9`1AQ@4239ewsgEf8Kkq^;&!5xR?6|J8(avu_}-V1uG2Hr^7;l zfO{I}UJQ$8^vdbB;XLGO4DB=mc0}xKq>7jM$gvVy$}MEsYq9 z6aONuKfnzu;6#uLp|PLeE?p&D{=3Nem$bnI0vZlC<%BOLsVf@+-{8tSZmm*Slf%&5 z`Cc1|J@$8QF1nVtUL4(Q4;;JF9`fCa|D8HGpIR?jZ)+@{;k2Xj`qsHN>h&%nb@KJK zHg?3R`+1g8?0sSFKRtCAVUgLPY}9S+vlo}_N|u3Uf+`drQ`5pEN!{XES0@(P*Z%uNQx|baHU8(Dh^Hg6K6WX?dtu-0f0kgj4)F{qPa* z`}wJn%!X_0-Ei}wLPhF`-j59ib34~?ATTGvf;}wLqVEyZv0eC#eBUDy`$htj!d_?U zst+PubFby=eKBXA>3wm%J=t)vvnF=?@08SF$rvZ_$e6gOIBK3y*E(?p)dlI&)m+z1 zXwqP19S>?k#&i?wWHV3os;EmS<|EFz7Ys1q1LLI?ize}Ofen)R#G!vJm9j1qs3-yp z@yo&In&UF#DgeYP5pf@GE1ySt0UIIfEB0rbMA1YvqLk_^_)~SfR@~Dhz+`3&F)t)Z z&H^*~P|Dya#bp|B_z%qA9Ad3Bi4xwO&skN=D?_q^`D}%{-?J&`>B7}00DpMKpFQ1N zB$~tpMzi5P_ol{ZbUL)kSsgqhqIiKWA4kp-{Z(6+YIr}ynI}WT1I8*u?k<+zMmFrT zckK2VUb|nAoKK8YpRx=>e$V%3n6DQO@Uiu|bPP|#2?=KwA0A`~SPt_8tmhOY#-3^z z`xQe=CvM`qWi4AWV?wwat#X68p!ztFytp8kgZeCk7P)lBZ#bEQ8+?xl0MbXts3Epa zvy$OiU?Sdi^zSAL&fAgI;EJBy4Sjf4R;wi_Qq~Hgua3wUAMcnYCHNF?=MxHAMrAlzHRSrYH{KTB+Wb;?zPd)b8)Q1gy+VCbAb^161*P#T`fNsR)o#*>T@oierqrfB0Yl9DY^= zhaCDDsf^&q$lQ-fCO(3MTa$Fk%fx3zv)%*Q)8Cx4pgGlz_h` z)?-ECRIEOhra$BqYgZ=fR(`w)2n>~~(Qt>tFtL&%Y6HXPTHc|S23zm1e~EcLtlD?m z-#t`Qqg~xD-$%85yXn4lrEYe*-8fz(C4fBVvyW)e}3HPeszUbE2uItH(xYYgwyKwJK(3 zcSt4XRm3{PCZe`29p>T`1Mg0h&6Mi@F zdtp*})?v`wjTfwH3x|hmLLs3!QLStW;n6rH*xne3;sQ<2QT;@-zXR?bebQFAwlOi^ zEtCd1DmXCfh0|w0E-QLF2jfawE1;9xHEv9zK_ljbfEvVyA7oppGn}PspsYzuD(&Gb zI@NR}9>7S_9w8G_g~m*ja(=355i-aPqGK;IIXN%|L{!yi(p#HOr5#fXd~$7g_jE2I zxiE!4vm{J`8@hFHu(<1G_|aUoOD{!|M*Q&(^O-XqwWtW&!1=jfNr}Sq%N<|lCSAr* zY)0TJ0(2QjgMAt@N%=~uNnP%<$=Oi2pL|^+BhT(XmX#T;z_7Oo054qT)lbDrF~mQK zO`nShx#XfJTH5}gH8%E-Q*wvx#;*yTp*BzOUr?`7Stkn17gBy;^=fa={pd77Lwej zM#Nk~pKe@wA&o&2Mp~{(*F;>_LF=?2>BBHqouGm(F_fLRHGMC6J7EGN{X~;zZ9n`q z2Z4G%b4sv_0h)Vo$#i0mE8fD}S3vSyyX)yh_%sELqgXmL+_zusIRRDi1X-6z7SfGA z7D+79!9S9>QzZ-G;z$SPXc`nV^byo&`rjXyp)*?LR?H%qhj_<<%ioUKt1lLlmT$+Z zm$BB`?h+oQXxff9?LDr3iQU!}Q*v@#ZFlaXh)ih46BDWKd}w*)Fz9W$3gxMQ166E2 zojcEBR@q#Lf!T%jqM1-L(Tdv&^#3WNr-$Y7^Mil>{<-})rA8k9rFF>W=I$E-voe@7>&->{TJgLOxGN3(~`SH_8t@^imLJ(#WD&MU$Ap zx5)1AT(;rk=VHlWJbVucf9X_1R8=9SJRcz#TyTw4orIY4C3BaQ(FhQF6p|%RKmoSG zT7a%?rAGoB3U0mVI%>p?`h>P-C?A zYNC|z0K{-b_)8bfKW(eGE~9=e@atE7k}B%u8KC*wIYqQqg`xLRJC>G~767hKFjdC5 z`E#I52oF%5NqkKBVyNF!Hy;Q_-4gvWCI8izqM@nnE@leLuzrxppN9=IW@gtB@W-)x zr3%y0JN% z*c~$LJR;+gd;K*JB}{P!;|I*IBrtEYdqqKK&Dk=yoFXR=I8=n z?pDK$+`k?#t#_7`3}nuqIC0w!JdVwG4y=<7Jq%5_Iqs7hEg1hMq?OQ9{M1>ZKd!6J z7kdg(#Gr3$@HCnkmrw#vz%*9SJo+KN#a(gB)I8^<5K~1|hVs2G`P7-BdVRIkQ)`hN zxwQC>erI!RD1ecXeF7ve%h6Dwle)+3SCWEFllnHXi&?tKv!f{Cm)U2l^Hx%gXvoY| z6CvN5Tp52vWzMfs`(g=+(Sp6pMb5U&Ui-GI;SwxP@wU6Q>#ozs1JB0+`_?<_0mr+g zl0zs4lBw?Q+ga6=IyPcmzYH2dZ}84-Y(5>1>-k7E@uDj|Dn-`V zQsGe4w~iMxaO7>pio^RxVXmT=MJ#IJaICEl9jUbqwldKX7&?(d;KaJK@z`0#q&{!D zl@?F;z(!8Of~l{#75QE4PqSzI~AE92PEr|tTT)hf_c2%(2?gk%G5ez z^)H`6my(gX;6QwC_iKQzwJ8vCW`jahaz6^>ikcl2m zn0mRZOKeA*<9%Si$ahdRq?-c9@i=Yxp#0DH^4aK}jxGQG#kr3PnD4 z7{Ad>!X1|NVX1bpa%Kcnoi$4Ciu33(0f$`(UwKHu{6^%+&6wH+54^{We?lTK$kLB_ zcQMspd&Vr3PTv&e>&OQzCjR#$Z%5*bF9{QHHK~QzoamA~`p$&yB1hWn++G>fy0>L1 zg~|LuLzRm9q!%BtFGQwKcVgr_s6Fz|MS|TcW7IS$JOlX!^M&w9!5_%IDzEX@hFj8+ zHd!T1gCG}zeM-?>Z`J>s;&6DiobV@+dQ_+YLbBR5BK%JpQcNSd&jq z7Bv#sf4{(&^oQWCOMBx9M)m+Po|@tgVYSG9lbMVh>~ zcZVi=1fuBlAy4@Alp&A!S_0gCq&5 zu}Xt%%`_Q5Y#z%3k#gm7qJuM6UWPz(puV$dGuDhJmY4KH`XkNS^+BxXQ`)IJ&yd_w ziY^`#v(JM4J9ghtm^2&I^t3@d0$+xzLC67^1_a&x+RwDErSQh4OEJSR8`hN|tApf` zgl_P9BoyKwmK@5VP(szX=V0o{?LNs0Em6%k2Gw{R%PMK;swXV_;) zk~obPmzEZn4BBr0%^kbpkLA2GOD3;i&L{pU09bS$`x+dK3&~^oqd3Gk)=a@9&|oDM z!2=d;BogiOawGBS182waiihn;g}RsdXl=Q4tT!Owu4p5y&%6@WtOMn;OBOyEyauQg z@n>6fOeFXAHI?6)y#0y26xccT5kpngL)onjB3TJG)9r@!QzQq=uKvI{O5EOAQcWVf z5o6haK6Foy>m+veMyEwK^L$iFNK)(WHY)7lnAO=qGR!OIQSeoGM1=dxFAZ45ElR&( ztmtsQkef2+cXh=mOVD!#g_hE@=#>*Rem)5~7-3(>CL|1?*eQ>5M_0&=;hE<4&?l4p zOZkyEu%G!CDNJ1>sgnoQc&jo6)qtcFC9%f0U9J_c?B3$F-TWIfSMbcfk&VivOw8oK z(x-g5u@q@J!2ABivui>uP=Wr<4cWc|pZ|oImXH+&1mUW|9u#BwVW}ZVlPRzOY@!nqNAy1*?tTG*U(`-Dg(~KTvZRu0F@U70GcrU0@=MZk0)*6Jk3~_Z z6?gyk#XSyXKqt%JPTNBNRD8S9%1mE!|N4zIe|d9y~XTm~obgP$|JX3Ta!L$H3z>6r-%Zo zr|DA82`KzHSE^DM!m+)~?SeW)al`E(vIr5I^7MUeBiMR-hK-3BG{L17Q=ID5nQ{9p z6Z+l+0!nBGZ3oKt?-@r#d@2g%mCZwHA{o+{DZ$xFa%$1V#=PN0wE>37As{WFEhBQ3 z3aESV+2&xK_GKSuxOd374jtT?8_3D0&0)?M!|lRN%15~Ff-k4aS1G3Hrfd&keWsv% zGah)_L-N|H@yY>jq_;D>7CzvJZRZEIyzu=!QT=H(5wXynRKj4Oj|3~RO+@vCbpi(* z-R}2@myd`vo^C-?Ahul&OaN{U-Yz0ka?(vvnNVbc3iSJ5GO9{=U{DFpv+OAntt~oy zV+_gXS+cV3Yj7TGsoIjYGKBP%Y3#(d@kVXjC}-#|GzTK#C9yP6{JR&s^39WEev9bW z)4%*>wyf#^_|sS_o@EbBo*U$F4G_H6m{@x0oh$fFePu%fOhqAbsd6nl$vO4S(ZL{>x;T~}6&=UiUq_){zlrpU%) z5udX6RR`oAoIvrFXNP+qwReBibhU<)j}27E+FMd^tOzr_^JWqJ8oLE92zzBS=X6;X z0Ca9tQu=9QPCh}$46Mu;f$*bg&s0n3T7Mrz!}2=0Svzft60iSu>2WG5$6IRs`HIDheSvSsH#WoruNLJwYv=L$96nT&0DEUaUcILJub(y&z)4nDX(L9W zt;R)Udh?vKGdz4t7dT4rW6qtSeBVtwN+cwlb)KS-#s)Lt;o(-z>17pVd=WzJz~)go zFS58ugvDoULfi59MAAhh-Ufb-{1Ic=|<_4;uO`~eB2>%+Nu-@jdAEF zE4rQw-r4^sVE>W99v+j^rT_d)2U z+C1#OiG^#jNAIqdv9qoXpESRxOk^6#DAI;EyPp}IX34KGk4#PFt1e#WAhV2_Vz8#< z2z;{oOh*JXqSzp%?fd!N ztYO_nUuVhVgXBVUCa3x%@rZrebWrA!m?t4SCHJPDRircc?YtTVKkb>x)m?N}h4r>~ zj+E_K3S43`W$!3h5m@uJH=MiKQ%0GXgU4rVX73CpX$rP|ilnjoueRW6$y(^9geLQ8 zyhZH}zmD#&kL55zZIeFWb0D{B~i;>ca>gu6}xQ@L5GjL;D;sGN0gR*>kVqRB`Whf z5&2kW-G&u$!f!e{6W=_EAs%B`*&c`e!IOUWpW!BR>@H+yO*wb@sTWiFvR!a+Lc&EW z>H4cMENsBc60aOjBJFUxHVTl!hdnu%yf^lK`FgwXDZPF=S#$HRKB-P_3Gs~(Qa~i^ zHUDafXK%13?0M`1qn!j8T?$kSc=J5@CV&^bXMo!t5;d(D%0P@-N(s@))T^pv)6mDp zj$>J1w5xo738@THwaj#+(pWPOGnBiI1te4C2XB0RHK*$*tNs>f@_xnZ)Knqh78_;w zp{nLh?zi?jzL+DT1h^)GMVd^5JFO8{onP_Om?vK#o~x-4AjH4c=8ejWkX1U7DT^m< zkNkjEk7oESzO52wo_ddWM|>j3&eYVDw)Elt(18KCsk#11FK=w3=UMa8wZB)!JpT7Y z;NvxrDlt9R>y3__&Mo8#%*Oe6_*=<7xvF#N~Fv_BIPPAIStM>wl z-=(I?(sH<(!>f+xq%q~Ee(f*XFVf2t!_EKV5-lvB&iV`5-oc%cHT zDg0Y}ml>xcQ;hirJMDojM)O+JivGICIAicrl_vW4!6qg+h%2gHX1I>*IuawN0R9Rc z;(?(92c?XC(Uwm_TXJspI!3v8o?IQZua}IZ-sx{9tW7}04LB0lS7&A(j=r|sbS>6K zp|?O`=)a<-EKXp#k`d3x<(Zqd^|E#O2+NYq8_nMj4sR3MJE^B%)l!NjvkU|9a|YDN zH_lc$P$rOWuU-qBK@z^c;LfUg3c<_Md_QWDqt6zM*lyvtM|$YGH>Mk!*1}2Z($3i7 zyiGY>E%|lw#W|@j*uY7h9TaNsK?asqeBcr$s(0@p>~vx`XCDC6-)>f;mTp7XZ~nI3 z{6!p>WIn9SEec01iS*;DN?L#t;eI2muIaV7!@YO^D=RP&B-CZw#WgH64 z{KtDKq_MZGhLh~t8@31<8tPM$Xs$y&=o15WY%sDA1X95l9zsU?hOt?Ml1#GPKLK_u zP#;fIzA7CjSAyClbV<5yKx|)=Gg6m;sw=zVzS`&%u&I(TcH>^epF{mUZH&u{DSaX?$)^*iZO&-XE8&`o|CVl#Vtm(E zWxXRfNDh}0pQGh+b+%km#enAG_Y~+FWhssOZIaqO4#~k1G9xNP-q#13e}cs|ue#<% z#-kWh4CqX7IlmHM{3groXCCShMQi1V`>ePZGVIt(G(W1g@sl!f)8S}+AgRL6&TgnQ zzj(ez>(6!bc=YLA+{dSwR7H6?m6%)d-`aO|uI@36z%U6&dQ>qIqV@Vhlr8xQ|t;yyD8QEi-WJa_|@ta z`4n*$GAAH2HJ)?ujGSF!^0$ao{8#tr+?r<}YbcWjHgm%+&YMn;mBd^1lRA>1Ajh}nn&fAzh+->vAPi3iN7!(G z_8LQlI1{hXUxxoPS#>#MrueXDUU(>5I;CuO(y17M9S*@=GuX|R;_Q@x@~;jYoiqm> z=vR;(kXJl>WvgRDi}NKu>ZhrtZxIH_41|8239aQD2ww7p{N#_ttx^ngs3uw6q^sd6 zES5j|K+RZA*JUO8X z-tNgRNrJPo#s=6d%kEJjbEY9KFUiZip$KOyyaN=K*scLRGAL>lH9a_}3nn&@5lD`$ zZDj+b)OM~qeEBlwdDzmXvuwIG{yHeXSO>((5os0iMO^)rEB2E&xB7ZM9r@8ZB9U9& zz*9@M<3(`xuP_i6k96%fIq)0q92tx@g1Vi>#j+Go6+0GTZlb`A_Q<`n7=l8H7Xs!i zQ>|2~UNf`SVJoU*QwZ~qs?0cKEPq4ZP*js2LczMRvk`wT25}JK=oQIS9#~C&4y262 zLPgv=`E(3v4jNSErQGcRySe4$J{N;f<1{&9r>O-(83Yw*#M4E2ZR zWZ6G^c&_ST6V3&6F0#~4PgCqNeJ7-#qwd&_EgLJzqTxhb@EY2SvS5_hvKvvDe5f9l z+{qHJ3y$;#sMun|rfL0_OEtwCmKucu#%5`=;qQ5i3=lDCyox>(GC&HwQi^lq^GozL zVA&t68ucnEQz?{rMcyk<4o8QLtZsVciFCD@U0cNGqXWs0ZuR^+=1N~>c_^Evj%xCc z-m)A@-l!dGv2y3cTLeCRp=;pivabFZo3Ycl(W|-myHCT8E%$_r!D3J-k}qnw=3+9g zVHQH%)7d`H(|vOqXC@Y!WW;^Duk~_C+zWo(1sbW~{C2hC;k`Wl+ZC&I={9%7E~Axl z3yt7X!^Q2eldiv|5PJNsa#R#lPboGtQ#`wHdQ6Hr}dHW z7NIr~o}Y<%8D4Davr^AZLP}fo=hgVoeIaLL;S0##aa@aSmwZOy?v*aJnBM5$j@lhl zq6EH2V_>vz7VRrmruf$dRwkm=)gZuOXHfN8wPKbp@IzT%ANP1lLyzCg%*^$1MY#Q4 z?bT4G*HO^wai-Vfq4(yNwUOZW&Giv69&1$Rds?q-OpqPYN{6S zGZgt}okBkB!sB+X*R|}b1~3e5-3d6ZN!4c+#XeD<&yjF6HOy=zoSel+CfW(l=lw;& z%Q&3?Oe_u#4iN$bZ_?O%)wIXbx18;N{{`fAei-t4Uu}QJpfng=S+5j8VHU~^f^HtK z_mGm3{`&RHsMV{M*E-LGh53^T1G$)CTWdp$aJpw(YxC0;>YC~JD<%r_WOMnVJViSS zgcw4_Pxcwmk`APmUNq@owpzUORq%f!Lw{!{*FoMv#M8n|JDbEYCu)CHdX%gUS~@PY~>z{TIB9h81{qpuJ5)BpKI|O z87O*m+&=Y^x5FP{t(&RBYt*=1;$|UST!=$l#85=Ej#@-m{M#3gyZ#E$LeHm%7(NQC z6d(&#<3<=QsK$1zroow}MFV9)0n zI_h4?mJ8h=^M2l)4JJW#nw-ui{2A~R1dFQC>C-#w{2OI6HqeqLG^uCTt1zDPa9`Oz zAEYiG`hnsvCUXJRC;m8c>kHr6Zw%1hJ$_np7v+0(6lec%bx&QmB7Xm{jCEw4`FPW` zeVLK5WO)?R5V!ds8sIdV|d2!p!@B*NX@H z70r)RGI-SVAOm~5r*`HE8bF2SsFmYHSpAvsY{mN!2+s&1GtA3n6*XBX4nayydW9E> zeyM{4g+w`n6|Ir9K-FT_T1fdmMGTcFArgDL99gA+n{o{BcFU&$Ltl|s0~IBH^KA-- zsuX32*&QwVfqa_qT=%R@H(qAp1788=8ldnb>V7pe@Lz2y1#k+mhTKwEwjNKlnpyRa zxmDmRA67%g0_L=GyQVxfVY?JMEdc>qkSF%zbevv!`UMBiOV|1 z=TcGI;KvV5Xdu@r^k{U;M4tYKP`Ib58+RE@@y#1zxY}JX`g`hIuOAw|7 z54g@WlAAzz;f+S+D=$W;#n=4|0QF4xG`Znlf)EMiIbFV+-{SyQKH@5WsX49&@`-7e z{QSwuI_M$!>c3x#ECLxPj!iU9ioYmEV#1en7A0iJa3q5X6P-i^(>WvW?~2-77ay|A zl=Q^)?}k_1+`k-aE$L9ViHTot)bUw_DpDkUb=B;LgKn%qRlI;s0~(;%Q#SjfzD8wt zEo5R-jW3HrP>GZt75xP&er~n`P)AxB=MTp3pdzKtbWyGpFlF_ zw_a%}@uUpqXoNij>k#iyM@#)-f2+J$eHMRa1Z>JFE8fBpFE>0ovUs>~I~rg0ZD$D+ zdT+RyU@{*tZS8EVkQ(|&;QR5@X-1<~kE@%Yk#ASu4Iajx6u3Z7eQ%GJN7kSJ6`;R= z-u^hc({`u#9q>QT&D{2*!BXf7ynZ8)EH|oE8tbT9{ATXsx05-%Z$3-Q`(iw6r<{hZ z4F=*jTQhB!E%v0X5cU{TUMKq<6uBjPiwM(;-xh+Zwh87$&xw_$z#1!^A#HvBwQ9v6 zHK46dR!4{0zJS$okcucy&d40k8j9(-TZm6|U(2HomOZG1ni@^~0A2&PXiQK=1c&-8;P*MY~F$8aD&+ z`tAv)!inpxt*!HY0r=N1U$Wu&kibys70Ua&uA7qqtpQ`wB(1~d)3cv!f}h8MpSzDT z&s)_V`sRFGMJP4Q!o`|j!bc<$O93~9xS-Gw)j|ozDWN2)IeAJ-W3%TaYofqIx(*Fq zli)h2&8Jc0uG#pM^H#V6pSc-{0paUfjMBHDz=B{)8c}^3>_J!#hON4~&It;!|NMe= z$J;x=)QwSZFVAyE1t_RbIdi&)QcRMQk7uZ;;o4&rbpOl{G-a51>3$y;aF*lCKc|Gk?R2)33XdK$xEadL)?)#$&%J(V7{XO{}x*;}kNz&{e z`B2l`r^`pTm#t<#{374-dBkMOBBKR?rjT7XYic5L_pcf*;AqBxf2+K&3I53NlVifr z7CKFe>>O^2Q73%zf7STuO1<-)EejN73ub(mSKZcwl8%eIe$n2jpfWbidp4^-+-Blw z-CPN^K5QUwXFR?i_6RJ8k%2zNbnK!csi}e~_SyP|32j;BBeXRj6y5=;`y7P({jE}6 zHr_*uk{g2P7G)t4lU1cA@20BChSf9>W0BatNkzqhgHJH-Pnyc|?WfP>UP?|ZwtxIv zH9k1D_E2)jzwN11jg2{Q2VPJ<38B?y+Hhg;N?b5SPO`SO+N@YaIQt66Q1?+w8@zA<`zreR=ZO3t!-*MZ;uYNsL_dI@jH2d^lUHhA*bNT-W+mBHu zM)Mr@U;d`fBzoJKNiN0z#Et0kavirdl znvD1$Q^1#tsL0Q50SG~%%?T$L#gnKqp@e~4^1`>N2iS$!`lvRt&NTKjrxfJ@!+AeF>rll z1e-Z^5*%*hs2i*glPsgA0s#*4Eo^B8{FR69$)WP(MY83kac+sUys+=W$z$lA=(Wu#TT z7!akaf>c@p!>W9arK4Y*R@nKtv&EOgk#@REy#_g7Y^#^!qk>xpjx6^Y4xJz?OX2}K zA7ZAagf>Nr`TvAgBwpeIlb??$HLKxhNK|!cXehx*2Y+r&hv~equoBW^Rj*Mr74ZcM zg|SQy0)PgQSoDT2*J}e6%}!q1i&%&32XSAoQjH%ks_sy$S8d-Gp5jO?e@A9q;WeXB zUULC}cakodgd7XdNTcUSF_U(#KfDStsrW7=d3LQ5mq#d7FB_e^dKD$c%!|aX;F&B^ zXZXQRu93d0>=K1>t@{;6gOE7STTsKyG%r|oS{(-X zU87+Tl2t4H()9e9%JF6U8{Yt?7nwHPl5SQyjD*F}QDXP9kcx*(nYR0bN3Tb3i~lQ* zizDHPZ%_ZO3w!k#r6$zn41SZfT#nsJe8PO#AvIcaJ6_v-VS)=NOGhcQ^1z{_mw)>7 zjbhsk?^sm1`E+5BYa`LL+k2Qgp&v;%v}O-`yAF}c<}c&>iHp#G>d*E$H)dM*T2o^7NwTm|4WSdEjS&-=rZKgu!wE#@IO8-vsNX^Li{}&pUHx^1BzH%2DoPTXkH5%Q6E7|V z<$hcAh44z{uHO%IlaAmLVlMcrh*`npduFHm*I0yvegiw=D8w75FTff|PY0|wtB zCq#*YIU|EEmps3^I$iD!rA{2|y1A?VW7rdt>qjgsETlah)*V{iop5~`pyJaLvd_wV zVoI zh{e*Jo-9@_mGR{1KWo5T&MDOzMR#mSs?pM^=zm6%Isnr!9n`CUXax73e0@g4(B*8S z$UCUk&SI~+_|jK7c?S3W50{uXqv@=AFNAoRF*V3Om88-a*~HN&B+>e3T`i~uv8Wb( zdkz7|0Cgp2;+L>2Z@gUcLp8tF!D6_jm5(bxdDuWgq~|JeI$=>tF;7xY_~yo+&v58r znTDz+IODD~Z-Gc4ox2a@@rCx!BySAD=K1fI3qxlyoCGt@vR=mMS^&iVTagZ&1}UN@ zJI}b)ge4hBdtxlw>UI4tYCaB&^szm6f7yPZ4ezcgN$c@wJZWbna=Xp3N$g4_vd}`l zf;@QeWjUYH`aM?GT}JR+a+cseF`k0^ao&c={7wood{t#~gpR*b2YwP{1~P5pFrJ1$ zP324v{eJazBTa0}ldcqYmAaz29I^LDk{rT!hlxzLj%Ydh%AbFAIf6TyQ^t!6(TS)< z6pxd~PKD2rqymo*?( zuKoHSwe4;*@t5>Q!zJ$TG4HqD%^uf#7pSu>=ZCc^x1$wNz=*i`(4i$j?E5hf`0qG> z=og5@_@s#6MZ|PUElFpm$rVLRSuM6Jo^>~e2+J^W3c2n8Hjt?sJG9`{?`vl!m2ct8 ziBO2N5nUy)YB8M(^e)Zo%MP6%4U$_Lt&Wh&L}9hT;^zHjYi;Hybc!m~T(-LFp)66nZ|M19 zjloawYEsw7?TIN&x}Z-OhbL|R z_vibmGxkd&?su|Ny4EZr8~UE&75h&N4z;dznD zx;{0&fIs9PS}>nqaILN&q>HaAt~opi-_+D2R-S~%RublpK03(8{(F*{f-vZp>cKHd zg+WOicMlox*~DH)Z2MpqQGwOpv06A#@^i|cdvZ~FJIiX(DFtXjy+RAVk29X%F^`!9 za-<@U1W_ACpYp6S|G9#!Bu!_Whe8Zeeyn6m1BfjtZzzpC%G$<8^#8>_oo_Mt#-tIK z9qlk;*&1h=7E&$=`uwPsvUqcK)$s8XA98(fuaUkXzH##0UF zzkS6MBPKs%9xqI%2R5!VjMyJBWV@cLK>NO((-riw&ElZEb_S2?adG`dVESr$m!1vp zy!WUq-A@`E;!NVJwp4~kj6Y!=QdhlP99M|D++b5B43Jxe^phy(4r0R%Hz0?}D@GnNa^VJH^^I)c^kw=Y!)S z=E$W3=odaJH)?67^)>YuvGi{ba|7pI9!?!(7G)7=pN{sge^H5vkO0Ty2b|);KMORA zEDLU6^zjZ~JB(j@sHnfgdoA+(UPjf_EH~HxPzj0K>relGixN?&`B z=jhW~-r{PP@4rF|`1DrW?R^)II=hYQbE7esuCqp^l@)Xg5Rot&)kbhKTq7rK|-{t7rpT}GqCY~%e*y^z*P%&|2^vcX}lsUIuyRe>y$8#&a$oi zn;Y$}d3^8>Yy7S%=PPD36MIIQ)lIpy{;S#Ca0fKJU zTtfn{q^$ar=|K?Q@%$S0h+qgLFT`w7#?1e?uWuZ8g=7~ ztanvVg4(c})+CHs6Tbe8a=w+{o6tx6UE9#&au0r0pP(TncyA@=ARGWq_+=bsHmDZ! zd>2(~0ZGWm8Y~}MV_N`uBZ6a;kA&~L z4;44T1ZfXJ-^#hXJeyu)ZP@LI-<+inFf2Fxi>jb%uD|c!-d;DoeP_xwGczysCmT81 zt}Uj7H^_!sb->_~Hkug@(>j)(ljo`i<%g7Y#U-g>{u@<^iPZoP?<4O7H!)1dvQH?H z79d87ick}GDn$mr2d>~TGpzK2-o2x&do2y0X%ZUIoXhr)ENr&@^{R=Yh;nIDwUPiD zsmWx_?M#SRAQcG(?ohl7v-g3b^~s{0688T|%59XVAIEnt{}V2|V~G8Qva?^5F&f#Q zH)?AXu2{bwAncxP1(01XPmBWmvg?olwFKU?kk>h`0rhF22g!JDf2w%<1!^qLT6w5? zEyATN0a@-oG`804F}t5lrI{FOg8z|)gohVlC&X9NrAMd#+jeo|f+P|`pJnm+nuHet z)aI(j2P1=?we!~O<*hWAM-0c8mEq#&HRW2|_!W=|nUM*FWs#2kx8 z(hP$1fOU}FI)6dy0;dlO(J5HBAcl!!l6gwANcke0R#vGAa@o9*{z3FPGCu-U1?r+J zLtG~3R}R#%Wkfu`Cra8JZ$h>PUet`96Z^yDMu;$cRDoPpXmG3P9X$l){Q|C!I%_Pp z>KqZZO@3ni_6P3YOc<)Rqs-rABnJxU>4XNbREGO#eu_})b#Tc;=asj-DR3o(7Wszx z2Y)edex+`Ij#;FvM|w**@b~>b*LA3){Y5+ds(s&3M61!S)H6X$(JG)bd~xnhcTB{?Q9=BP}wEu`NEVTKc70BP!){L9$*4gXCKaj$~w z$yL|T)V6?8larqA&$}P6bN^=@`NI?cfbg$1CbANF70MyVD2~|`)FsY}s5Dy|;4XfF z;>FH}BQPSI?4O1Tn1a8ZvM#&1k|G3V0VZrGLlBsvD@#!=$OJ}mtK=uJf>exmQJf|% zJl0%qAkclysRM$oe^k(7Cj?OC=66=Xok_pqpf037>M5W}ppZ|VSvD-o22iCTX!t*w zi*sH7ZVmnS?z_T!*d5q~Lz?vC_w|7Xy$V-_C$s-ffy4g(%zT95v@2DzYWmIy-1z>v zMA*lt9fd1yV;mKU+=0yP8gnClylHTDp6S+5Y+;;Js>s~1DZ8molQXfjubisq!6aYa zQ{K*Nl`^sxc%8pM_Ph8aVq5dA250D_(@R~6fkF-<-8;^qW~-lm@HuEFc9{SOtZjtF z_TCcNK{gyjc$$M1@q#{C)}_A!=R5oVAv1|knaF>lR*M{4@L?E=xG~&;0&$yey9tHD zM*8|{Y@b~9JxW`&o^#M37xu<~8xIYJQ~5Je02ddZQU!x)x@sUgQp?K6)E3vpN*jgp zQ)$Rx!^N;dx@YFrP#(<>0*uh-xU)YWXMH}42mDT2Q@CQ4<| zdVgTn`Xw^&htzXYP!rD_w)}EvCdv>Yp`OVUDfmv+=Oht*?PA?zCRm@W%J@`0-Mrkq zyd0vow+k;1Gcz(XIsa~YxbEr+s0J@wh|*J?9;W5@teZiT{II|ZqM~WtecNHd3sI?} z;Nt#sM^fNKBtSAtP~kklugz88{Rz7K80D^=4 zG;k^K(Y{(!fMatgAj`B$wU-em)2)YCk)m>$6?)?wZy1KjOvXiO(^M9osU`@531XWe z&``UtzcbWcuF#`0e2S44jJnmaJhUdb?vh)?ePXmBl1wWxpV(ys-oJk6BJMT9pocnKSK#Y4C zKtv-e7LK@)uV(Vabnt2JF7Bv*MK0UsKf>a9c|#kZ$?H~Su*neiOGObzvr~x!3(cW*BbQ);7OwF6(dt1qdSTp4Ny2(65_E6}&ooQ4Ir?+nro z@C3e{S1gL3s&C(X9F)ry-#%=sI&DqI%6{EGV%Vmok#!&pu+h^ahv4Wb%%SUAyIv;Q z)!DZ6&y%1G{($`UlO0D!fpk3G!){6i_;Sj+&A0R}tq6W=W0KW8r9xx@`eYstAskbK z_PY#>C<68ttoQp$usf@>BiER%L?)7(yljEo2U)_&-O(wRU^nC_2b)(M$NpnjnrSeZ z!UvdOBL6!S&fr|6;ZZdHY}3chpRampke6i1+CA51ShA=^s+M?2Cchr4uSl?9-{@$l zA@z2o#@PvD8R!dnMaX$Fli?OVOd7ah%hxq0 zQz@9Y5X)8^gIVv9n%?Y0(ki)fTw0I86=*9%s>Y!nSz#HOtgo1#{g z+G6h!Td5IyZ>?F1*jr-O7DDY^YL}o^)GjS*Q=8(;`@Qe?JwKiwd5$B$?)yIP>pI6Z zf^dQ6PG@avGi%7<4F?PGRhm4p`JP#U1R=h$@@~A~V`ZcF@QE|Mv^^E;^(<^4FPt*x zY$@uP;a8Y!Az?z=#0S~=jRu{rC_Y-Fbm@hRhKWE{k`BDB;4_ge=8P7g|1SRA6MvJA ztHHe|#S2aMX~AC*CvWqkHv|wev=)+%r(3xv7n&B*1sP-xup~nVwLoLONaxHFb3)tF{X+rSz`T{lwtE2 zGs>48L+Vw`w7JktZ)iVDv|xwAaom|}5vXYGEiz@E!9r!{pyf6*1ykKp=5)YT30gRwq4)W5iJwqz=@B=nI;aUVM*flVlhh(s;A)xdaJBPl zeCB}Zpk)Odb6V5h6+`rOch24IX8(BYc(!UNN`LgjiXz!FaWK{M;emrijOmk`gny2} z1iClhk;sXe*~AtLevN7A;7gsiX8N1(FrNauZi?&*qXogOpHAYM5Df7C2a>$$dNVU4TN5iu2yJY{L?X)unsF3{;(O`n!N@-b9knC-i2ZvUcWu*4^^r#pB zACXZb51Gn$itub=u@9dwbPSnh=pQA;YeXgIvbP6#sl*_N96xvy4pLDUj4Kl&PYnZG zmd?ADT7mstIq)W}hVqKd!h7O~Fri0*A}cUJwMpP~zkyu|@lTi6wy#mPWk=zafH0P! z)Sx7~LySP@wA+N35U#LyQIGXaO=3Q{*<-toGS*a+~ztvo*=mC!uIRBdjw6+-X( zJszvC59Puqi!At`FbmsPE#=Zoa^wDPUB;V#XQUegjYI}Pg6GpB|WtHERHtzJI-308`V&7C&ROwJ8*=!I99xxsU z1mN=t+wtg9Z{X3%GJB)HV(P^?X~R?Kzf2Ega`mLx51z(&cmhR*2@E~+f?g$iA6YoX zG6IW=kYi~6tl&LRaC;R6iV3S1rk^yu`JJYHaCm@=-e!{SygxtlH(TYOODONS{1XGX zzq>i?4!!Aut;nn_uS%I8)?~Q~3x~6fF8m!Bo<*2A+jQ@@Y_a24z&zMp#ww&@0o3fm zUCa5J>A?i}dL(n-HtI%A1oA6r6w$y8u3v&@AePE>@hAk$IqPWu&c&R!wIR)?I zA!3P@CxO@uE^ws1y&{0UO##02ul^Z5FV5u%9vg^i*0&kqbDWiZht{5*GHFHY* z{l`j`1-54TkXS}=54HRR*4sEv?ZVgO!`;yvwazG#Kah520Z{-%H{?pL<>Ui{bP5W* zU)ecBluk4XQL}Bd)Zs>j+LCzQwwr$Q$#&uWQ;)qdAweS^x+()ycFtLBmW-7wRF6rXl+(byq0VClxZ8^_ zhq7(7n2Lz?N7A6CDB7MctF0dnSGvTeQSNrQIpSNkIGOh`0j;v7L_%9%oCK0lXEBAs z@%B1n&7%YYfh+&HXkoY3)lHfA@ouH}ZG_$&y@ljfZa3#&8ft!=(JpMGbk140vC8BS z3cVnsh3ul1Eov4qwR3l!tNbCKczjNm;sCVncHcehDJ7%WdNEgRWqD&&~fBUtGIBTqe!OoA9_hLFIw6Dd65Tk8_J+oyv&lXH7%MM90uavdp$#+I3+Hr>|7jHloPucKjrhw*`K(g{ugk zcu-3LVOXF#ZkltD(SzB6%(=b}t! zXy`ouq8+QaSrlGoi7g2GL%Y;r7TMw!)}VB`1NjT1(6ki}!h}Umd=st$W$i)+ge>%u zW;=x3cI+t7vNiRZ05;9SB{5zc^KY_fzgg{wk}H6KWSZz}hCi2cvm)WS+yvhUs{p4j zCIR7Edh0C7Di>%EQC-RswRXnkICAD3STsSY)KiOxisnfVGA)k#&I}>&tnm+p6r*x! z)3gS613%fXCY?{LYnC^^Z5*WEA{+TS!$yf%6{5I4An5iZ;W69EtiHxIbunQu8Yd~o zY!GLh8YWlk#u!Y%S=E-&?m|QShV6IZR@Q`SSV;!A48J)#N&Qh*zkkE}I`Emw+Zwo| zuQD@xvTWv|@3OxS)H6p)atSgjN-XzLhk$LYAaL;*?9aj+1s&Bx=`pu!*(wn(p-g$k zT*QBt#o#jkoiHhCf9h>p$gMCRCeT=fgsCx3`L&u96X?%iSXo8^ncMLC{0DIE@9}g# zm=uSACE!^#pis>>aGE+qx1ZG^Oc-K9+K6dEpFX-f`ILb-=r@1K*67eiHSN(oAbi_q zuzq=tY8sADf!7_rW_rz=A16-eF3W(?W0N$PL7U3RY)kz2ip3N;?h9%Uk;^0DOt{PS zzN;BEqiW`f14x?ZnC#{(Th^e=oNv8c$4n3R@9qw!9`&3|?@w#jUqHt|5e3Kk8RXPq z&@zwa<|;zH1bSwTg1RCd^K%d2l&LdHS*c-A*1*}Kia$XH(W`frB<*Xd{>y;xuUH&F z(N=<0_ZyY1XAl>IYIy1mW=5lM{CXh5-TsA8+E3GEuqG8YpdwRn`{M0$*LE{{55smn zpY{*HuNsv#ZN=C*qlxkqc`VOe)BoyCzWJ2$xe2U9lO2lU!d^~*dtFiG2q#6~r#O?) z7!_TBWN!?Sk*7AxTsiYHbGA#ADhbKJS&51M*HiKobJLISfStJL?1v*2+_g67@cjpzH|0d?u7pi1(h7-goAKlipY~$r9!4 z8KG#^96nh$^kb^u$6T8jX5qIm8HGGe_#Ah@1|qKVPk9i|sq^_wv75avWTUEbSL=)ZyVSlj+UY;qdAr#4Z#ZhUXxNMS)#RF0MbCK1 zRN=I&yS1}_aF@83e%O6~RnQr7;(mV{dRcH6y?S%KTMM>}|5Wtu5mFd!T4~x}LZc7n znuaN}Z$52$M0?F;oCFztgnW^rWkBNin%;5H7yg3lx7}@o!(}c`l)!Q`V~SE{UARX8AkZqHh^%L9;h5c5ym+PPgfCRKkTLu1Mx7d z3HIS)WAzl}+ukwQcF?v)Y79Xj1pxPEv zfqiLP#u+6{kQoIbo~?OI=p1bG!gcQ*6i|pM#QhTwOaTcEme?v~Gvm2T*HdCzb+X6N;9VtG|3o<> zjzCY5r_}CCw}wtm?2@Wu0zLYf;`~K;o+^>ANH19BBP+pjy_b=Aps5)(%aM3%$;lwq z2Syqf@dl7rpZRCJUJ?n(Gf(H)TQZOCa{((CX4DX0mfe;-k|Ik2==)3$Pj6WSH`#LH zcgWSrh(1#kUL@MSg1nbFhDw)<|hYhnEd}d1uNb6II=r`Q?eDX3VLwRF3x7|&3-fBl-M(BtS)XRcg6Iu zOF6Q`Oc;{m-A=|+P9J#xy+c&0FZRDk@~>~EO$$6HAQ_sdbbn5E_snDJ&%~9PpJlgH zXt~8-%)s7)sdH;b_nR8C!`r(cS7dXOy8B{tlUvvP^z;d~4R*J2e^y(tb!Q)XetYlL zQn}?=P)H5SxKGMRY#*(`(RKDzC1oNyYj40ys9F1Y0%}zhf*ZlCP9?8*Z8Ss zPZ({+J&YRMl#YvX?TB!fq{uaMV&sdOw4Bos{QojjhM&@}N9lp^5pv}*Qa|YFM7aCI z0rrd!<$hrMwdMgG6K=GkkCTqV9Irori7jlWP-L68Htc<%=||O#5FPCm=8R0Qf}4{m zGi&<9;}*($gSO+D48Jm(s5>Eb1U>zuV3isd8U@0jou%)>={_awQ$x8$L0xY`|5aIb zhhD7pO-GBZcHN#%8}X<$MQk$jr9rD}J zQRpg)RZ+-=$D~{-CIAE!-?3D2Qu%OSr^~~$3_tMf=ua@SnNtyK#_Ex)jS-Zx%np`C zdC6r&G=^ELAgp7eIc+L`o(380@&Q!~LD2L79VBUD&-$eJXWQn}ZIgbt72^@EBlS2Y zP4#$pD7BQ=lgQ*|uRFV-NZH&sy&Da`j4FHeO@e6NuIWm@`l6Td!hn^{vd0mMHr8$9 zqA!#8XfiQ|WkY^9z@CkMeo&&;i{wmInzS1>ZRN(%gg~acc9_+bOTQ-PD+3Dcb~S9Z zurQS^B5^LDLn=S}B*>7uh;!GD)o$$KnVr^ILQ`XGQqMfHit}`pYA1S4L=AIW#rFSku^9d^RKGV}(gX zT#PBm2IWVwsrv`2?~3ZW)GZj1ypL1=BfV} zDnVGovgV)<1o{dZ5Rkp6L#_Mznj^)f^&X&WfQJ+NLYk9yj6VK05(afj$;pnR%HD~m zXT(?^*K|!JZ_iNkRSXl9X7lL*7 zA0OP2ItN>Z2;!=~4L#p)>1r`5cz->xRUp8Q3ul2OsZ>!R7Q$^5*w5KMTNR(z#Td&hXjQ8+uy>1#IVc*Rd_(N11_#}$d0#pwoT=O4ms4It4L^a>_ObQ` zo+a(L+@7P##4h?I{VCg{A9xG4r4zG&%%iNFAZuR;vx?|8{Auf1;uW(G$7-a8F%m z?|R!6pM_IhSypEFyyco$7+z#&qGDnch>jBwSX&!$s4Z-w!3_SWbmxBl*x(0b7LgE~ zginEL0`sr|Pqn31^Uw3H_9$c(`^(GU9=x0JZbu5{9(_T#CDGbfnF{MeBXG+D1#-76 zD{~18aDa)rNsmyNmP`d`Gzs zA;zS@)`{PGn47}zU=I#zKq-Gvf_oU#4i_g3)^F}j`Y;T$4YE2eh-rN&N#RfiqG2Sh zebY8&sb-peAZ`&O%=DnAb>DRtI)=w8`N4~>a+fCpBXJg2K`NvxY8x+}U*N7Jn_)HH zmYRV#{AE?8Lk=2X?CkIFuTgdUDqgU)zrV}>39=ky0+*pZmz!7b@>UIjWcTwEUji>q{DXHbgU{GINMk*VqFh&p zuv0&=vrAl^&yOyTHfSy3CQ1loGo~dj^A4A7GxuOzUwfKd>Z9})U0^btl-gy};4yZ{ z0>^l3xWLn^4RR{fZz`NmQ?Wi|DYl{VcnB6|jz@U004R(1@!=9Hvc6D64FXQTRLo=l zU|fU8g!`K$7E!6np%PRiL?08p$_knuO=XR%%YWqe>7QA$N&vdu2+Tqc_tuh9IV!E+ zSPy#k!dq8%mNb**Ru{Zit_0UiO~@z#`IoQ z!4VdR=fPX{)Z}OJ&_U9{I3Xz$?&q_I+H{v|VxHc1qYUuWoOcR_^!gSO0a$T-p3QF#2-6cM)>okCk}%c9}C< z<+@%j4TW^Q(P`axI>amNNikn13Lw zpr}wG7o$fTqf&hMLC1CyZIG5t0oR##?^x)3bC^uO9TSuM#aGv^k{(=&1}aYEQ*JkM zQdw-ikhLor`YoU3Z0)M{@}FtZJHFa^C_nLrOE6&cqm<+CTmXXCF%dLsDx>bSH< z(#ey#4;XpZTZn%ebHn3HS%3%h{G;k})xH6AcCTlB9vWz(t{*Q;neJA?RYK;7{+3t# zW&ZP_*#SMkgxc*7hZ7;{Qoi63 zeTbPbRv-S`Q{euMcyC2w%#^rsy`JM!-Xf#m@Z{2(QUnL656pXN$o}C}Dr2PK?&DLP zYW6L@UWi3FHp~8fEbi3Nz!+D9zV6;A9T)Y6K98t+(kL}asYdt%LIL`ae}}2~Rg0;? z;kfo55V9xP%u;$8;!D2@XV^zqVh2c)qSA^X2P#(lp*mNy6?NlLk-sP%*%jmv+0_Ba z25CW%&|$= z(4^4-&8BA04EjlM^EhBtaSzJJUV1RCk$a8#zfD{$Wv;v_JNe+p{kM>!KlguGmDK0% zj{!eF`{YT?VLxh)nq6QYGNT4R|F%7EY&n11{ZHn;pykjHr~B;5{g{zu$lVpzKY3eR zYh0DJZDO0#Dz$oa39FK;sWYe?=Sn_(7?^&|4ie-ngu{vD3kixaF}Yhpue>T4zG-TZ zhDTW)fG8@7|GEK&i7u=Tpqr7yYYdZ72*#TP$Fg*s7emjJlqRcm9sEqRayJH&&mJPx z9*pydvH2`%pbb*OXG{#4V*!LLjxyhHrdTMxp1~X5xFwooM%Ix~{fTNtq*e0h9t%pX zAN9t_YW8{WeHfh*=S=Qu8vZQeVWZ~3b@cL9oW8JtU5LH@a>QcF26zV4RTWwIB4h-D zm4E)J3r_mlwGK-m`I85*rCjExP1>H8ib$CPI+o$tAw&(BCpB27Mx8*!9}^=p;*I@S z*g(tmCeyncpU(V3LoYVR{IOAQGLkZ($5-Xy>-DpcGFell_xC4EZY?<#E{g+bz1^j2 zIwoo*Xqf_{BJv@t35M??;>)of%XNZfn-hP;JBuDgQZE(gt)*+iI;rUD^W2#fDR9P_ zYSZI(ZHA_@cfbwB%srL>Zm_w0J`9XZ&qFffy!DwJ(iYip z&9RZ|yQbG` z{gNpJ&Dm$~Y3fvU4b%vz{J87;^)DUN*d&F76HK;CUtKHH)XWxU?Rw$u=h_~&@Q7QK z>Arbz`gol@lJ|$QZ;hmNyzO6pUN+Ob1-%|jia|=)W?c5L+rwD9eRJd65<(;DgiAzK9lo#jV_bx`EDC#9!W}WPD#a0ASxB16c)lb!{%b=z6LP>L=o>qpE)NeI zRvm;eA>4I~dOdKbDvb^>j+i)+B)12>N?7{eb?YPxeIC6STXfGmW(h8qDURFvN1Nii z(sIJwIc$ba&{Gw@-OO>no9({3I9%CJN?HuP=(ykWYOxTQyNQmA$>yTUSFnmytjoE( z^2?EyOs3CT*~Si@02ft5vJWak`1yr$QZj*uNOAPBE z*PY+3u~Hceu4e&q!HkR-);a9bm3E~#WyF^UNnNQxiD=p#&pq(8<37&O6I z<|?1HKE^zo7p$os@(J3ABz?v<%C+T_LiPI;s4eYU;fTKKBtyO^^YXt>1~z~!NqedV zL)oAV{5*n`5s$=#5p_YULJe?TL~PGV=P}^^a!3Xmx_aT>9eUqKrrolLJxjj+`s|uV z?RZ1iBKW2|FpV+gYG<}eTju7p-ZjM}H9SU*Fy3i1y8$k`3u@Z3BYu#5L`)_sY8+sY zUfVj$mQDY4ogPkH^aapP5sqMXb$n*m0#943Fo&zcnA2k$FFr<=ZxOFK&Pp?$^EE;R znutJLxb2Nd3J25U+<;#?VJV=PIX4&&UN};~O3w?pzW(B2<%p2NM%`g_+aC`(#uxQa zLp>|#98z-_T+=5HZymYQQ4+^NRU+*+bG2}js6J!j2>?)HIVB`jv`i)^uP`cj+93;8jeMzQeW+|cGz#9i5O)( zi+`4w4ry%NlZ48X27y(ayIL^UU&xZ^;VAkOgo{cx{-T^g=^1wL1j>NJOrLRJJ1QZq zZymONP&u;U^$fkm;fxCcAzcj{ObWcA8k1!BWfA=k zAFo&JnejRJ`fMG@xL;g6zLCkztiiH| z0$lFP`EH?qhwj(zZ^c3*9(SK4g>KA+oDFsV{Z-r6FX~#vm8S4n;yGO-u6peZ7|+4E z$!u3DwaX;G6*>GKXd5X7nv*PPe zUL0+A3WYsMmhLOBibYrm&=#H+|`7qBj&_#bv^9Z|Y1jvWdL=g$peMPQO{XFmU&4sIH zt32yW!DN4@QUGt%hwNgVbP72>L3iXbJ8Mr=Ia7zQuHll{@17rh1P9as`dsIXPw!`4 zjpfY@(}j$wKJO^Y%4@s2GWciPYP% z2un8Vgel*!Mpc3%AGWIZRi9LLnld>1Q^4m=*qr`fENPLN&pl zR3jz3+A7WP@(20cZ=y3l3QcCJls?Z2&-ya{Kh|7)D{J!qHhy3ImqGma8&&XcTl-7k z?VVW2ud2|~#qP7CqkzyBNOFRl1b^y>S0&_4QGV9N=77BC@cbHiX|ZP}B2KTWYMmZG z#kE>|i4%Fpij~2A~oInE6n>{ zD}r5Y*n7{3PfA7NVVPx%-&VmrwO8Q^kIZTv+>uobEV$n+x&RW zG>mu)QboxppvI*}Osm7GN0i6@n}2!GBE;7hg`7mj41}ky#iJUUcF#l%f4vPKc$VD~ z{CCIz?A!V}XD0JXKAfH&DA^3Q6a(5;a9u>zW~Zin0;S+$hFQwXD`Ksd+}6Z5pSA$E zqh%^v_?>2+ZTdJnpej`ZpkZ&QC%`4fMEn)mX4wd}*t~k3(=y^{S<}M|yHOmgW$Ah8 zSo+obqrQ%dL*ZXRUCo$)FDkq?B?ni{tLJlTcbAs|{{9oQ@7e=2gmTF9-x#Um}#B&o$FtV;NTtFJs#k@K)^C9oD8lVC3{XiJG_+ED(0VC9eBo$M|7{nqt5hT9r z%b8u(e^izAfA9PpJtEiLiHHSvG2qPWWTVu3_{`8ZL-`=8W_@D`4VOr z%D!;qeRvkTvl3n;&;@$R^ShEsRde`j0FQ<5x6ol7#ok_f#x0O=7HKv&J*lXP1QR69 zL))J!x5l_7g{&=#4W5>0Qa~F+OR5#0}{~l5rgw5II@x4ulK-i}_^lPZfi+)~o76qfx z0RJ{~q4U3|cE}i$0qFd@U1^9bq{|fAnl+uKHS3i9TNri*C_PtV8~oCONhY6#KK>~F zOz7P%kmU%B%yzId&JlIw6MCNr_9heWjMj)!4gueC0#_S5!&ymN;XF~zdjF_sW*0}# zar6MYjz}F>fsy0?Aw%xTXyr?iNyWTfEIxovwu<8ZvlH&kO}3(ib1zdm&kp*g?=M&H z53(#n%Ak!_C7i9qFCS!*uoXJd6G3a!X~@8ABIO;i9|^-{q3sibTam-)ywfTVZRX8W z=z2yb1%!XuY`3WXumcwJ^ZXxrViwi1_yf|9;JZ*m3re1NwPB~vbVo)iqvr*3Dii7& z4D!PVF&gqq!SPpX+p6H8L$gB=66&3Zk7xo|HuAK-#_tkUQLy&+M=I)_)@>_9I4PPq z43h{8b2sYop;R55Fw*Y>YC&VB&Uwz8!v^wa!G^fS0I(w;#qj=lZc3PoQ_3e7_J)eV z*G)e^#^TW3SmByLvz_!=x2oLt?+*AWBS)t5e|h5pCc-O|F=j=ov-c(+JEA-07T$a+ ziVJ7$@-K;ROWO9<@ONKk<|}JKU0^CejnJ-(Q9FgRuV1U-^C$al*2)};J;2E5m&KX% zvd#(73Yu+PrD#x3_B%rG*GC-Skkena-Isq!n6XO7gYE5YY%8rhw6(iKN2r3?d@%QJ ze^;#5vRm~h7GtW63e0P>cF*#Osk)3xS!7}UO$ZvG>I?D>3kVDClahF08bqUr9swba zK6Qot_v(IAvC2V-OaT}Sn;wRQFlRYYSCfy~=AtlHPNo5^Y@S51ve2M!Tmxkj_~xoC z^+MkT-y8A6N2rlVdA3}5$8+3`qr^{OIOfSf`i>Hp^fUakKjgS2J`2w+1cO_(?J35J z+j$7sF9xSr(Fk~=I6=mN27;@qMo{_LdtGM=)ttAL6+m)NX%sA;LxhQs>tB(lNvtK~ znhjHfEmeLs+Q513%PT{2tL9&(>eQlRIh} zUD*=qeJW!Qp3>hGG+|B&A0AE~HaKqbFLc>Iuo=(R@-nsUiAFT71W^Bn=qPb|{7ik; zF5|6(6jY9^R$KW)O_E0T%hG0cyO7+LttYkkPHsAaDdL0#BNEpj;8%OZ%dVB>GYkt> z)#a6iF8unE(n;bx7QH{ExM*FI_y1re^qIt5?4RpWAAX#c&||l|&FN{T_uf0^SlMp@ zyZi0Q>a9K2T-Lv*n5at~LuV+DZ`G3b;QLW!(YDYKscypq-CTN|_NS6Y&05R}FSrpp zGic6t*We6yMOs!F1gM12naWY z-_2=>wgwujKZSAR`&8O*$||S9eBg#Os25VO3PW&vn!}?%;vhqKXIO(5Q{%e8tIg2I z8ZhF`c#u-v%oHWunu9#Q82lgVms^0vYp(-dH#g;Aqb}k+H~P|`%|{H<2CIDOjDK%g z*UTOQjoiS51s;$R^ zuWkan%gf+K<2;V%N=P=cB2dbTOm9DUsCV8VQdSZG;*C;%sE=RLv!(KuswM2wTkluR z>xe~xaE&bL->hVBAnfE3@kbtrg2bIcbUf?^a`NH%X1fEPVXM^B=FcPUL9b+8C=*Kc z6CV=AyfC_8?x|V|1TUA*O|s(e|GFNX`kVIRN@F4@KKxYH-;zC=n`8i@x|JI3m2q9? ztN!(R`^F$s9{Biaiw<{>0GiD*bTVs)z+N`~&!bSN;YgC0AHd=xpK1?KHe@>24Ztq!~B!k_GQEMeB;MAmCre3f7t zW;r|&b0OAu#o5%x)R8G#)dE@3DE&U-mw}V6a>a^DBKld^@y{Z%=2L?z{b1PXq@2!JQ4Eq#>*$)1ASoI)~PPo^Ab$Xib5duJUVn4vASa}=U{5Pk< zaF-$DnRdHXq3K$!byx?d6|xKy^w0}Tda=7F$6K;_Cku2lK1GGW$4-aj;`RF6R4lRe}cJhxbiV0 zTZ#?3;O;jkSyC;w4Ssgyq5X_6%c0*YU0_#;&{DvkC;Jp@SJZ&0Gm{ou z8$53;R1q;fo;BOWDN90+>U?H2SBRcaggPhblu2wRp+JbMCFl)-3O-i#C25 z4uwx)=Lf*{KU!@5m8L!AMzLJrYLgP$fjoAcuF7cT_%&HHJ-O)g@QAWaU7utww*yCO zc&@iS(9uw(p{Tqp6Q!5w8_H>*IE7>v7Up`52t=D#oOulbIgQYL^5vDV7zuM8W3$ia z8vzPbDHhcxw{~yIWYKlS2>f1ySqYvmBcU8@Q-K)OB~z3AuYOV650qK#LA~F0cTskP zggQhQJAm~tBz^1c}652fBu(6Te6jHAGZE~%}=@BT6w$f zS>sV@N}=PHc6*48A0jl4*ctfuBHYrML%3iMJ#U)UL?3f{ZPPg!u;O#t|H z0Q#JP<3}@J$aWu}b^?TiB~69NLPJ8FP?e^KI|q%r;A8)YVZWLX)}`fltJt9U@0>z? ziaz6?kXlF02;@PF6s~Ar_Q59(Ou`*Lu`JHpBY5)7&1>89m9cb*1-fGLGq@T;S}_IB z)MlI;k9yQfMC08qh4tw|o|I(PD82 zQn7}kuUp`=UZ_i?wVsoYllIE;QI_4{esk6z6oltT zJBuKvkj>}l@QECS&5-6>-KP-8EMNRQi$Yi#jhsbldjD-srwbitu$J(0r2d zb$5eeEsUdpt;|;&ROQ!W6Rg7`{mjF;y}}HbUv=<7-caQbuY&IO9naLw;1F$?;Lypm zH)h^GUx)QQsX(9+KAv-eF8G38n7P%ZiwMj=Z6B%ak8Z1(n9^j$Q-7&gmOQOI|2=J% z(upvfY!2!(nYpiPn}{0@e^zntfo0iIAZ_v@tNUmeS{%)wb^iaUkjFdbSP4pPp~=4i zk?a5XLvp)yR`7^Z9!RiHeNAnJeM}yvtjGYP=~sgp_&q6o-$4u!V zRM6B|@iKd~;18#!Gd?;By^0=0tom7K<#`#9Hw8a3IwmGo)EUJ&Rqk$P6!F86CR=*T zW!a$mV$gS4Wg*ZOU9SVr@UMKOjFc{}JVWWOA$?1QE+0e%1aY7Xk=}%1E2dxyuD(Hj z>L#ddKU!Q-5AwdckNZ@NZujf3R*}9E1Uq|)4y`cTk1+H$Jp7Sp@lU;P+%?B6Z7Q>64C_@nQ~f2m zuZVO(=(KWCZaWx$y@rw#cr*GPO{WYAWsOp8iZTyAGR6T@I56+&&m}aqth!V*#4p7f zJh-waDHhvAWb#ikF|wD+IzXL!KPIaa;4YIzrWzEb_Iey?@h{NT$) zo0t%5gOb4~m1KN5o3t5+`Vd>03x)g0m$%$^&*8Sq7$u??Bh`u#R-XuGlD!9|-gUf_ zdA=%!=iv7Q7tZ!*=q(!s1nB>&5B1k~?%Hs*`J_@l39gD_VHX8n?ajw+O<0C(y=GdG zY!`PepE75Tt0N`m;GH0bxS}4c0lm>TQlW5uQtH;>T3;&z&v z&zI&=$g9G*@nHbvny>UwL>w-Rt!q#E$2YUp-B~dSUffz)CVB|7VUqs^@h;KX*Q$cJ zx3W{e=518Y!2RdJ0^wR2YMSnwppqk<3~hW&)DvvmT+!;Y0Zx&(Sn>X758Y{6of1acHjih0XXJ(Xu#0K= zqVopw)LSD9_ab+f+)t2~<~TKLP|PEKw2-8tv|(T34P$oU7E>kpll0YG8UQ%Xk!6}wRI$0oaxDQO?V zxGCGFn#n2Fe~cE(_DU|ni-M87ER>0$)4v)Q7}Ef0mB`o%Hy%*0(PFdPXI@i4l@cEW zk;$mHdQt^@h;Pl2pKfKHI1GwvaWmfprRMq~{F#Y9wNFx1f`I(6M=pzo8$l_k!sU%q zxwK6Aug*bdk7&L*)!*t&bJk%N404brt+fe{xgEx`9~uZJRet~C`d8SN)fmOwic3RkRJR!E3_qRA-?Ginyq=#Q3AuG_{~xYeg$S$ z$~(BdSP9(7TO8Ut5$EbMkTg^~d+_DFSFn_*Dd=KrbzqAC!m|GoWpTtLQ3fWFnetfM2M#?rrZkr4*6x zT`CM#g`#xvtDm#09hf4ks+qn-r*f<7a=Q!r8J#77mmZ3{&prATL_={h^1e?ZDnd=M zUT%^#SqF0AfKuJA-0-UoV7BoX_4STQ9NRWXH<(Y^;^4u%2vdH3laVfA=@TfeWv6@S z=}2`i#A;ZP)}8^rlpfsKo zXUz7a`~%MTLaa|I(s~W5C)TPkhK`18GwE)+!0OjUKg~6`Y8OLhWox1f%Qe81Y2ZME zn{d^vqo4i^Ksg|i!8V1_J054MTF$D-I%wl!uDpBcUNB8Qtu4uyyAp2KW5ZudMeTcD zfOVyO<$cpoRH2Iz7A?9oH^3(4H+I}=rt_H9TV#^&@vtnYEvC=r0z{o1S#;E3BG-y# zGV#BeywQR~PqDB2XZAM}i{VB08UM+VAY-@{9Qs$(xiQUZUB93~6(;}fsTUj7_DPjM zckubY`J~Y6`TeU&PNvW;%iB?zch|o|rSsl-?CQb2Ii{*L3%nDL=)ApVfzhVpf@Ur8 zbT_0G8e-Ec*J?tZ8Kgi*Ous?;4GLVMKjPT}eO8~mKbxzfmxdUO&pClpM3_9NhYJ=P zaquBHUd;QKjYTf;D?*K(v0n3OVIUsSV_Xn(+1PjVLi6$R^3qZOzEJsVrU2)yC&KDT4tD4lQY}w`Q3Vtx?M2Rp(k_c`+S>R=Hp)s_q1{ zcao=Y69JQ6U^}0{dmo8+0S%e4vZpI%&Q90Azo9DL92`jBZqwTAEjCNF1?S2}QWAsT z+O1l41sqfSHF3W^KR>@ElMX{T%)4ec7I1^x7ew}pWrnSC>`mJ6+`gEtA z`19lXYeI|2j1-(<5#C^1izYh<3fqtT&*qB{7&2|}AX016tUZiqRLi6Ix_6O$M2-Vg z>d|(`k&3=I$A7b@v;Jg)tWhbFG^T%ozW`mw&|C$AOT!@_sK0ACU{pB^t6?00ZF*91 zcopmr7aQ3e<#ATa?hwtc%80(k=8shi0I}?^Gx2A|!MjvHhv)ys#6(6SvrWOq&KqJQ zBP7!=A2M&wK#dqoD_^qz4v+OJNc&rdeDP4q{`uWp(E>|_`nli2$-3~4oXQ@BQ2ozo z`tv;$yy=Up^w#d^ZoG%LGs->3q{DngNQ{T-9IiLAyd`J@@ z6z;+Dr8dPq)vo2!xi;PLc3z=bc;QODXtGvt>=Jovi$;jiDql&`~ z;p2ZfTLP9}E@keo-9P`jC0o5Mz~0yMmsZa8jl%p=zmp3{_y#t&%D{x|egWyGqeuC( zM(wo3gdy|SP^chf(c|ocG7LhoU7{y707*AH6Aj6aSuusy?Jto-Q zZ!CDeMDcdvo4*rO#~E6r_nfsbF?+b_GliylgRD|3j9pMFBQ}kgLP_aWQ77kVFWA-z zhAa!m8XY|>xJjIrFTDR5kvuOxGw%M{b(oFydJmml3>8sFf6_uO;N`<(YNn6JTOF>bGd zt#v9CvRc`(=7GkB$mI?w z8IZ4Hdndu8R;-KE(iCC7eR%kMoI})ddU5ze!=*QcM}xZ%rcgsxobig6xzyJ)Xn{U0 zn77zkw@Fzh2>JT~yoR1H)UnhT<)t_AvXTY((uI(hy)F(&N{>6^f2ahGB%|J-#gnlY zSYx_;Q%=K1FEuBe&hxU&YkCE8~|6}zn=whcr>Id)}rS7gOnhal#xmu7{} zXhS*tor^1+Y6jU9J{iDpNMsmkkyB>epB;^w*8i(#iSI3_?F0W$&+@`72JyYHp7g>?0xwQdjDRmY0Cus?Im6hJYDn60kmc;XB9XVXuWQeELB4i z5MwM{j(9MR-m&Ntv6G1j@Sg^`Ss}pzX4XpbHz%5!8jOPbWsGxmlo@saX{=7=)3qGk z{w*9sb?41><~8G(N-m`QzG}LEti;xlHz}z;_G9;%#2<{5T{k+eI0>8I^n|KnW-OAK z0P-O{?{TB^ysTFOoFDGcq&mJ|ms~Ir$e)45(`a2XflNx2dB zpZ8gaX8D3(ES*8*KY8Xc)qv7HG^lBlRT7ILAcDB`U$|8eY_ze5y*?Rju_^?x*yLG- z2zH$zTQgw@+6#xPLi9V{*OL>zTaizY*0zT5O^~3&F2eZ>3S_-_`%tA5J|GRA)v74L zQ8Sz<_;~(~rBv0$ycKn^>7*bBQ$nZ#%ai30gYB*iK{p>~d<*{k-uSyy+xS7eQ0pI6 zcfqHYs#`F%^qaG-xmwY;ZVbWupH8a)i_DB#UnNv!Vc*!cPIkRNlSR0*W~O72cVp6w z*SL&sk9Nohd+W8KDMhR@(|Rs`i{#mc@|#?(^*}AVC5~b@QXN+2SOYeZG0wuA5L!g! zOaei@TrK+!A-A#uipP)tp@33P)|s4WIs6gw!SaAGJ2k0If^%nQnFNBGFV+I&^VTX- z1n1JiK-8ANbDZ>%ZYttS8epI8h5Q|-?|6fn_Bk;7 zu$wb+{F*MZFttOf0wMLj>XiF`u>cbJSYlhbZiRnG{vInA$_768IvMg~?ZZv#>6*-K zyt1fh31MVhwjAM*4&=Q=E+~456YgUO4$XXku{Q^fX^m z-z^c4_ev!AF0W+xk6@t|@!M*DKTs;0znhdo%TvaI$=^J{`ZkZHF4Y?Z*h`F4#3CNo>Ahf#*h8OasjL3Xr5W8oIEt@m(_H zJZknpx_B3zZ^byX&arD(F{vs(ibA=dKBi9J4Qnupp7vdy{yn>{#tuHa&2&3G(YQSO zZlinnC8$WO`g5&eBfqb2@Adk<1K-UN)H#)mQt=`koYgbV(J<{yAbxDo+URGDX zHpvrJ)q~zl*0q^5%IGo&*q|VF!>Ea3g>rS?as4{AT1gIId{b%ivAN;JXI;bkUuL)C zIPn$4VagmYJkrsFP$@wY&6Vyaq(jNvmyvpDn7qW|aB=`i;^UTKGhWw#A^FK4?#7>k zS=$UFN(uAY-}6+Fe^l z9~M>&1#dif2gk|EQN|-)>wV6*saqyuK~pY8#HJ9P?NoudT!%~rzPUZJ^Jw!!CL2wX z7YDuLVa^TJUJR)0P4L(IbB6-hg_`>!7;7m&_w5i3d=1JHoK{zIVHm(Gp=krOmU>h} zY9nea$2gr6%T=qufk}57rr~mDH&n+d@{tG=c`&9Pd6tuh-e0MsW33XbG?RSBoos4G_B>#?wtRfpnBnd=wp z#1R1jSsttNOT#lTt~Ebz}*<@%bkGOQ+GiO{&+tQxR!&+4#=S zfm>dxrjSxLR|%r&9ge+V?D|UW;wut6+opNjOX-J&lHq;NWUM;hYddG8^GDPukx0Xy zAVB$TMVlX;J3FodKl~j###sA(A-|7yYk%GbNfffQ2!q<>CN^gstGPmMhcZRqzIw&5 zvA(_zSA!>I+lJ0`QUL6Hx!$IvX(WH@U{ChVR1R>&}){r9AVH-nVa9Q zEzn5{0@(2l=HkNvN?%4tA~;d6x+OpArpj7|lyu7;gcnnku_7J?dqv*GgL}i$_ex9B zT(}=J?jM_u?t;khe=Cz>oA2@b;Y*QW8#CKf4X+xIR%E()eYz5;8s=Q)1268+6knySjNs;bO|KKFE-U}S^A!LTaVQPv`6MU&U4UVLs+K5 zjN@b`ZNyK7v1}&9)dBnHvJxy)Wj`g{5}rP}=r~pdu#_(N1#!0|?k{a?KdCYX`u~~t zABMdcyZ>D6jOLnT0*ujI1-N( zM43~)p{dKHcR;AKsRo~KpYS0^FVb<;EC>EP1WpIY=8L>CpRw1luFN-gJ8olTQs$nf z8E265QTDuTiTn!aemr1k5lf^qAr7!A^UNR_^ZcR`&T0blW&(oB&m{DIv}k16hlLJuLdB1O%uQ0=>0Ld}yM5ecSiAEj~$_UbxrO z>tGbTyDeH{imDZQi?`z~QC;=v0ga6x_=ZCFJ8d!Q9rll&Jt`z=ZCz;pH@%lw*_#tz z(-8_dOLd7&@rb}-y^ET5ZECvOoO@daTx8e_VSWATSu$=M6~Qe`vMfwLPVA(?V9a2~ zT3ystyFe!R*UnW-VMvH?SK#kGbPPiee~lC2z_8%6%q@Y6`?Zct!$ymcgwyprx2$(h z7^N2D4%EeJd4tb7peLLL3(exg%_=gPwr`%RB?)0C!gQyUs6rIt2p9|{q{}oc#ycrh z^n1w;s%s8{H%hVyz$l@T)*&8)0OY9-nMT zM*-pNg+Iz7xJRDm=}8)|0_rRV%z%dSh4T!c8!m;RhGouuLI=^DV4!~TCjG7+s^lwY z8?yl`Ptyxf1g8S&S=I3plzB|@ZBLD1vINDzSCC$LTL$1{D00i50v%15Ju_6>U;u0B zwA-buUo1kzN?7amS1rvMZ;j}tf0++#S7Z4E=zc1PeSJupYAF-SaMPt`ew;wi=p+1g z?CFd`Id1~3&lu!NkH?*cb)bT4St=+=Qg^qQM|jCRG}tnV0Dz_?{bTsD)jFYS`XT7B zz9rPBFrqRg^E!gwNTi(5r`9Mqua3Jsa-Tl=>wa;SN|i{2q^yQJ|J(n+6k;YWO=TV> z{>j=P@IT&-H^i8Zx73y)zxn@cX)~-9bj&z9Cz@*CEniR!Sy>>-C@BX+M1h!`T@@#} znv%y1ClQXE$C`Lt%lE^sAqmA!r0*Z;vnVwD@Tqrk8k~2RS1WVm&ID(S+a$eoLN#jo z1`y`79j0>1PUpeO^-__b5>w`Oz-k<5&a-U^H`|2(D$KW1M(aTh6tkQ=(9g0#sJNNm zD}9I!yvcLh9}32VI?s3PuI)BUF*dp8X1g|5*VL@9N&%^U4gK7AJLQAVYeIY`1onm6 zW^OAkz#s{RFT7H^8RRJO+6>ZKDn1~1xG%mMv9sDZ-mM%EX*?v$WL?wiM!G4ZdcxkO zTzoQ-FDRIsZXXv5DLmWzo_j&(g=MV?8%k)>LdFnuXb7hd(xm3HgZF4M*B*$Ed~KSv zx-4QznakeK6&dLm_nYCYwKo94Mx*cGJasxC%4{zSKI(vDDK;{p;Q+J0x_G+IPF@q)KWk?7 zWE%Y1ILPyzT$2QbWq?cv^RwPb<0YHyinAjh2>*GA|GA0Xx+i=XyF-?4qYk#l-`tb` zGNsFCunBp#Q~!5c_ScW4Tv1GWbDMc8ObD#?=g}D^il`ZD7Ivp*9rmLTX7j92zENtZ9v#&9Zp_WAI#y1Ftd)$s!)MX~B302W_+JR@`{3QOWwM|Va#i9;vtR*d zfv0=ctv9l5vY^|+)xr{gwq#8h0K_u$US)VFruyzST+ya`!Sh7xI`O?|OEVKDQm&b} z1UZL7sdVe6uP@(Dq3JMjmO4I1_1OSCH0=|R(0yImQ=mdK0&+4DT3F3uaPk63%BJ)j z56B2Fc&Rq~F;)ft8H?Q$S#FKaV-1ckO6Y4 zt$z?qjjjgR%N&1Sd;VKq7vgSl;oa2Nh8X239t7)Q*@AxWq@GTQ|Ksnz6y3-=x(#~u zddovNzyPIGp&U6P8+3QLtt@)lbAK|!u1#J|V!@Tv6aI-@u75Esrq<^H<=T5E;-boE zkDdf08A&X?a*rL!HJd}#MPk8v4!$3MA0fRA+XTn}6NaKeRvDHRjK6D>LI(qC?3=iB z)bX|YTPK7db7WaXL$wO93Ym8boG(aI@YUKp=dx=wPq|`vpXo!GGd(y#-hjl6PqhjW z<0)PJ-;H6R&1IjCFD(owiG~o4L&RY=48*9 z<1+1?oTNVFsKe)x6-YUGXXW?4A;G;c)}7Y8Wtnl@#6XW(JK2HK9U7g>P;MRcbT{UG zBRQeViqfb2x&+@y5LtuMXFY>Z{+ILA=Py$MI2xa(=V-YJz*r*dC-$ zbOk^m62!jaS*elWL`<^2*g))mfD(*<_nGX6&;tqY221&U9QWG|OSEjz{Z(V1ls9H6 zMC{ft*!-%M{Tp#D`>RTHn~<;VjdDO}36|lD-iD^RnBg62T>jO%?2*{K8n%jFeTHhv zML=oXm#_2K53#uWSsmy53mO%0Jc!EsQ=x60-erb(4xN(+tq9jSl?!Ba~ik5Z#nVNoF;M~sJT)*J$`W?Qp$8;gAg{}n7J zM#h3GCYMY^ohjb#(cCZIx3@hlOcir_VZg>Xq6WU7-_Ijm%E`&nwjYjp@2(_Ri5n)j zR#{~NQa$q)OvRh~L**4va;cO`yD)@rSj?_X)^s`)`bg(8(F#X!?;=4+f+3PrNC4){ zOA5$F7Nn}X2gn`iM6$&i&Th3jCbgpd6qYKKp5tfh2+zS^FY#Bp#?NcC6>0(ax;_1~ z*)*z=Wo#NcFuBKBGZ5R(+-i|=!ArRzLT&hTo!#DrZ72zs%9R!y-u}<7YfTEvH^0BP z?DNaM&}%*V%r6RKd7|dF-WMF`n~D6_p#mgUQ!MOL#h?Hy|@L^+S0 zIAlOplAzYe;cYheW<3*6PqIOFEVzO{^SS3#9hq^j*8+8A`uER0z@4hcDW2NLS<$#^ z2Xv{H+=D6t;aksVqGsthbd~38(^+M)Dc_s%yUBlS$paVZYB5$*Lef~H4vx4Z@o{1a z^DH7harYd=U-&S*F`#UGs1WjN7BsBb%gn%1k;#83!%*p;&Nx=TjV{uSmG-=j|3M6g zs|QRzj*5Qhs>vm5?-%5b(5T<4<0I7!=oh znp!Bh`)rV_e&-{G%5!e_Gx6>q7m$SI2DzI~&3=%40s}jly{^+Qkykc~I|^Wigh>5? zef=+V9+C_HFH~6m&z#7u{4Ue7&G;*?=kmkv#y7Wr0#8L+f;WboO4+>Ez%L1-;_QYm zb3?GBi3@LjwS4I95)c0I@qXns*%SC6cn-sH9!Zy7^*fKkmK4?sKCy8Les)iC6`#%Z z`1)0RXLOk$a~dh-a?3%>m*9;qM~quxaQ|DrYcMV4N5vcn*v$azX0B%5RGm@!NEO*mB3>Uxw$q)S)?C-MJvBLWep6El-8m*H8 zp$U<;BzuY*DS<{HF1%pLF*>f_PkjLde#cK@n@+vwzF21>!(8fxg$+cf{aFc0YQU$P zhu3F%0?W!eHN*jK7!+tC7VJFh?kP7)OoUZ3J8=WIY|Vo4_krl?lE$ z@Bpu`^#)&V&Hc>epWN4X%g+$!p`}?fl)XRV=KG5A|4Ij+Urd!MSFHj7ucP9ayW?5m}C75+$Bd^@>F`qjWZL93(~+BNtqQWu+r))D8*0R=Zx+&XM+d zzesi^t)K4*CPHlEB*V0SX_Fj-uPNow0%4CAN=hBoZb$oBiUP&aaf^^Ti>XyZWv0)& z84CIFU9-+MxX&M+1XkFjYZ?^R={EVsUZrSF2>oX6xre5 zg5xnNnxP(DJ*-QDaji1Wf=J1<1)(!j?^`i3LL)=R1wiuEtT)Hk2op?#Z!V5tqh;p4 zO9Wx~Id3>gQc{G2x#VNi;>#}k5}V#@x9iPblZOVP4uAD*8Dfz-!nufLK4Acm|64~J z7WqVvN{$WZy4?R^giq2tOx)DI#2W*-`Vi?pw&%As*VdMG8I0(0XXXYZ#5FvR$r-^io(??^KIpbQW8S-bO)0ih&9gebq z^J;ZNeSBLv1RKTd)iSJ!!Y`xNbso(lMT83dp#e$4b7Bu$vgQr`RA?B1Dl$4t1)q%K z!$41ZYrIO(1E1{WDw@_UAQ}%+PP|UQ52rjBarDX&Bh4x>LM;s7QfD=oRtshWT5;8s za80~^MS26WnUG&MdqG}55B6pX|9F4f#(cdP+9PWo|P`uKipXndh@T`J_)fh0rl zposQzj?@tVL<)%33kQEi>J1fHJ%l-yeI!KNiGW}RSJ)-$OU6}q+_|+mM5VNpPnw;m zvY+wV5Ha>h0$xUexdu3UDI*S@tW73AzLH*VvJ$SD{;gD_Yi9W=&V0*4n^Tr8P)gmh zC|Z4e24vrn<(B@b)s$I7&XPuuqpl9SpZYn!crZpp5hs-E2ZH8t8UwjRDmL~ z;G+|`hA<4yI?-fotyLorq&1GpqR50jd29|O7u>%f-BS(U+z756i^JCH+-rP8i5cgdd3&$f= zW1@8KunAAS8NQEsF5(NaF?%B6Iwz5BymL7DWvqta@;baZa` z=8zGH!g+CQxI(|Ms&O@lbk*i-jvI)pNyRW-zbdvK-tBSAZ)F@N>&gy{R2rbIU^d4? zdhGI5x8t9#RO9v8*(+MB#w?pYOVx}we$DR`fd6_umy=vWsMQae(IQ;x#+||`l_gyB zc!r&|?1%XNEyC=_x+Hy3HPV<4 zI2^vJD*qX8=@uz4GU`y0fOqFk4WrzB#w50iabkT0(KBz6-OFIuo^V+uXnlqW^Wv7O zBMIb{6d+I%B3$|x&QfSNoQo7{7w!|1z1h_6lj^!s*YViEDLMy-jG3yao_?(o*YEsd zjNuwn2HDWEH|XqWsMhdwbsa93c-Zba@uGnS&}i`?X;S9R`NiSw-fEq0R=N2em%{9K zY(yC&k@o|(ZxprpP_Ec2b-R?95~{ftpI4sg4-M8Vz|!X_Ay!=3wWE5->XM=~@Jl2R z=aP#@EOQ`4rU4U|-d|c+?PQzSh-bE|$*Fz z45p))^@bKBIdfo~xoLCZJRk5(Ew}%87rTJF>U7H@#NP`-$y40J9tJUxhgOSmo1p`o zmw8H6g6J)Rgl4lT>vNK7dU%8^=AJi)AS)J+xS{0wRujRt3W9r98!uTw5Z>vJTPD7r zZKGCAtR$-@4oRs+L=ZGJbMN?GQ<4gM*kc*Mh6r*e@t_SZZQTK2t9s)_8s>>2-F-DLB10Bm&1?76-4~uYIjjqPdvN0rG&WGkWHB-4K05;9qXMS$^mQC63 zjAFAiMvB`b>nms6$>=L*L@?!fs6WnkRFt`-rc`XwZ}z$o3u+ccenHi>t>0zYBuv3D z3IqSA9D&Qj6MXyR&voQpa5()~UO_c$aAb1AkHcd5H-E0s zD+_KGwQZH!Zn*%~==lVk&)yi^>vG(%5qdd=Mx(cLl||oPdh1OojgSvi)^fGf!r83F zuL7xcs-4xCHFOxz*`zFXQ*K5L`7EQ4U6{(^pn30_6Vi=Xt>I*`0?~wa0xW(=dtliM zce#Ouh(Ik;N2ji23&JqlQ*@=G=R_Bn0Xj{FPx6Ewm@Oa^dOwsKO3;(Il9v^2tJe z3kzQOEa04oK(5tRhxl!i@`QIH0{GpM?_3VMqH9tb+Fw>$WA#Df+x@QRuiF0qZ8Awm zW*BAbgVw&a_gT>t!_Q+@H}O)Dk1tfSL?*`)71T$j-rS67|2<(Z4Egrcu%;oO5r;*a;(5Wx9c-1x$$}|m`!H_p{{MGwg4I> zzy{vS8f|?A$j-3QBFzHmZsWva90O@P(os&RBz${N#i?;3mutv8K;r)Wj|^ z>`)I+2X@ZJ#&U zwpJxd%Bgn5o-nK;-#xebrA$dPv(i<|IIzkt4bmEt7Z^!!H(4aBMw4+e4c)56BI@1r z*#)nIS-`N#eR4>cc&w71v!+IbM%6A6U7c;SYZvqc-(wW9kU!s+S}+U6 z#JTGAMCTrMHLRyA@c#Vr_~+p+#trQ4)i*VNFzMwd&=ZD$`oujL$|khEY3Cf&m|L6a zRa2Oe-U*VJ8W*hOpR`P8Pm!sZgJqt}`FUFItFe~OX6u2ofH)~7exHYr#HYg7K^ zR)6lMcJ+{@hJ>nu3?Ssei|h2It&&yq{AZoT_C;*$I?H>=-9KkA8~8q^!{zc317 z`1|+j!wLXF`dBBZ(KG|EgY6a3$2Zf1EF%`8F`%#2NXL?C*YSkr(g%#j!cSd_8C|(= z(2yE+B|+zB3qfUsb!SwcE(=ML>)mi|eBYAgh$@^0Rk~M$`OclR@lWxEDY2!!Ro|AA zY-Ipx=?#Ui{(nsTS|0AyWo>PwviI4W&Z3`p_`qKucIvl?Z~@hDWNPngEWS)ksp@gJ zzThiS*}Jpa;J+s^r+<#$T-kTLWw=H=HI~JPMeZQ7voYpu&7KIP^^zW-(zI+e&GkwI z#Qd>Az~<4j%-)1ZMkQSrjYJVvy(;WjZ_+5+mf=Mb0s$Fz0yE&!a>Zf!3MG*SwDppA zX04Y*)`{hH%OOt?Tp^bekBu}8K`0>a_^Wy_wI9S=Dk!U>PmbiM$Ag511HBj|v-zEJ zYvzkbNgPo41jEN>J$e>gM63@hHan;7UB_SOvR46sdf%>`(bj%`VmL{v2f`k3m=vMohBLxvTI4^9jfayi|0D=hsq7QyAC!}H-_AtkUsXh%`-jSxL;@Y z^}Syab;Im6!7_!~mHJ8*ooxmgT%KoP@86GOc+Spl&d`z=FYwLP8O|`ffNi$8J>JxU zp53EgcFl7Hi|kVgE;nXxgg^CqdX=NTOhb4NWLQV!tf@ zC!ER}4~Hl=UHAHS7HXxS{4B?U_0t+$L|uBR8mShIBykdk#i|XO;X2FRS+dbQKAH#? zjB?*h@v_gJp295FbeFPRi;J^bM`cW7TsrNf;R~Kn<3k`CcpaZb$ZMtG1XGmBmciVUu5+pG|#ODJOi+m@(E2SVF4e2E`EvVU6RM@mmmsfCB%K3-mN&H@=qJ3i{k z=@DeRTu7#zGH=Tzbgb7seOB6Mx4Gu;DzP}?0B@zM5f0F5`Xk>zV;%{@bG)l5sgf{< z($btDW#6d(5AqO*nfMo+wM-{;XA@$+!^=mFz09WoDa6Fmo$u!IzquOP_*MB~ZN2Mu zU6}zxfqm{)AQkNCls^~8h#Mc|FemEkYwE@|@P}7;yQUPUFd~VdVi#Yc>;3y}wU^6K zR*YOFCPos@+jg4deu4;Gc`RLT&Da;w94)q^bFeXy>W`<(C-z$u7|DJJusz4!pIN%4 z?ETzlX=L&t-z_L<+KBLx<+o$A?{-{lq4p?o?>IR=o74IhY98wGyaH-afN(1S+?p+4 z1P5dXV(B>FuRVW@RW5~yr(Bopx`xDYO5u#fNh%C7vnAj6y%mQFsdh6(YZT3^eB0o6 z+owaS`bJ}A29tf8MK9m704u0e=Zz5ueWxUjaB{EJCt<5n-MSbMW1mJw^U_;l>N(Z7 zZGFH!#?JeW*|cp>b63aNSZ%90qIk5kmf8xF;#-A@sGUXZ@y~-~x*lPH)~?MVlcM&8 zArgg{v`zzGQ%+H|5K=~38befnW)nDT>q9L9s)GA53X>d~o~F@46W?RVXcMLab7h3l zYv|VMSQWy6+8@s;6^&*pBGXts6UZNEl-?&xPQfH+2?nQ7M)z(KWtsQ zdWw@P2#Fg1a3AysBgQZq+Qr@!2AU6Xn8&m8BMnpCC8fl_j{Ig5YOF6`JPgIK@AzjI zWNTRNc}tAX3T2AmOGW+sf&n*0-n@FpL}4ANmtTh6ozePA8SCi}W;?*gcXxCwpgO<<>Oy_B zUTxJeJwt4Hu5sXaz%av%k43b0nJxvZMV)Z2SAbN}HZv4PA>}hGaeBhX(_3U7|CCP- z>aF!bO_x5q1u0J2)AaN5Pi$RYO&r2 zNjKMH=6~)!!KnBYM|ECajDab+X99AQj*D2&J#pLU;|%s9eGGeGV<8L0&vl;1YC_FF ziS2MZts;7M%tn?2;okv#h(`Z^=a)^0{JsQ<`G@i;37`YG7HyWTwN+UnC~;l-$Vf!2e*k#4W=zPEV!Aflqj=XqIsJ1m8G#o%S6HwV7kA=(g)gtB*1P zIaiPnv)l0ixz@7@>@sv2!%(lJk()_<*~yKwg8J0u`Q_MNkGqX>085vxL8vT%>K3K* zk7f!bLZcs#Tdpw5?h3oM%-?S%pdvknBe6q>!A;{K`ZpXmdHSCg4ZuzqC<=2Y?^a8RkhHJXchJ zC1=rVem}DK1QW)MCg!1eUMOAFTZd;(+O6?;D@n}KaMp?l`Pcp$QC0l2v68=_ zKT6}vLQI`#^N(*NLv0qI`QB(B;Ll~w*yA_qk&0-%Yz&K{HVsZOC+XPaz?@ZR@HZ)0 zQVUUXS(k7Kw(bspb@!s);E|GfRJvT9zHz35v5d_`_~+Ue=i}O6)39t}fw1UNenNa( z=lUpZ`iERiJrueYhFzyZV*m98W6}{Hl<)16nqz`f#wYl{92EYZdxP!%^HfHnB!1+V zXj+HSb;U#ZpxYL=kekxK_ik^_m)Hw~_WA$ZO#c0G|HjYD%L#5h9E|FsSIVir7jh;T z^u|eG9w_r5?g^`NR$wfQY=78JP}lX*5T z?qXE*HH|L{59fIVF;Qui+43y7^`=x3fyi_q7^=$pe)7S`y4WMS``z#P?QpKlU|T#A zo5;FBP1xlwp$8>tUX~N-6Y`aS4mj6vuf+I`jaN4f)h9`4xpDjtcLvgi9Hf$WqSedb z*;A!5Zt_x@XC6?b29F3#H!<@4O#2L`?mS*b;{o}?+>18C7dYO-6v{mxQC0h3JX0bR zN}ome=n00CzR#GMQii6uY|kHUKX;OoVBcLG7gvT?0(fFXIK4&I!!;*lK$o;-IEaGr zagZ!`2AryNP6lh;g<_qF3zes_r(*(EuGjy_ep~a+quBlZ=*KC_Wuv!u{h8VB(-X0z z^|BR#xO8h=O(9aESmCBzhuJKn6ieufrZA;`92HVLJm^l6q}b=n;mhWZg$}gT2U)nA zbR)L%imA+La?fjfxczl@wz(if!T!B>Yc9H8Q&W>R(V$*;9M9(%XEdqy$!YfupWS$3 z&#kP^_T}np7vFm|L^r5tJyqO&87WJh;YF{g>S+O=FiI2{dr6%Q;`My0wAX!aq0SIAsSw`9Pj2?r9VYBBhE1FI{hpz+AsYz+b_)%U05hjd~E| z`LyJ)TRbKHiHB5bpiOcS6kqBzui&kK_`%d6-muEMmEAxtaW+OJ!YIbf83V5L3C^({ z3ABcuC!s2zHghZ;JGJ6ILM-MWS$SSX!>WWuHD&G9zQ4uCpIqf8woh}{nB3_aNvfQy zQq3N!GvRB{i?FJZ*%;K$F-fq*o_V@*CiyNt57#R;sHqdlMKgJdXcg;>iZ)QiLr#)d zV}#G~<+VPNBlQY03bw_8NIJSRPX@fe1^nkqsFxi}yJwP~&piuRVp(*_X1V-r%U2E2 z{=U3qHYqLm-Ge{FrRvKVJxVy@JTo6D8y54aHYD?@_VkbYcK6FR6+=1Gx%~Uo#h;O>xGz4ZQzm4sgw~2}fmK_L zc%>S3s-X$7QX}dqqd##x%Bb*k({}!Ns97A)PK*(Re{~lFPx0aRwA>CZeG}2$$uFe_ zknbY1z~TK%-xJu$SXHa_mRv>bV`P%Vl4cxQ38TXIyCx>IbSWUiY332`*&I&Z-7oSB zNLx&J(CGSlS657MG;LelwwU}7cN*aolS#cuS4`;~{LtYvISV`(9v(hN`y>^dQulr}fl&=TK}n`xC+?H!d4--Vyy<3R9YrD4g3MB`{eaXXwURXL1NFI39UcFRt|SXX zqj^flvx%d7sS$lcSp*%WYhNLRxKH2+0SxM+V`{g>NmW@m_y3!FNhQKsX~Wi$NKdS zNv!xj(rys1fEuDo9~k==lhK2PRhjNZs^=lZQePnX+?DK_&o^lL z-~UdAj7zu~Si2`w-a1|EEyTx0%l*4lMCiWBOZ3GG)Lj1k`zKZ4$R>+CYYf^b@~72im%nq=J#AB5eIk90&WtRdRWzDc>afxEPb%PaeE&`mhdDvr!Blyz&lrJ;CsPa`a7BWg{cXq5 z(b0#M_l1ZG%>o)aIzJiN)xO{jN1>c18}`S=xH*M|rePxWzqEAC zU{MWmKV9p{-wFZPKp+q7?8;qT>r+?`y}RGNL!_lm?NSXhcrM?m>n{MReXE%tBqs`JD=fTWbv)Vq6o=00;U zaG8Pg-B{nh7Z=T9KM_S{ZeQmseE0Lkze$iSsoLYiBl`ECNos$4+keFKXR0zwo_A#m zOYrsDL`FsiDRT-AZUmyLyc|L?35(22_2Q6~73Je&;^Z_g*75fC77`YIDzO4A`K(4^ zi;YE71J+IZ%O-&V`PYL3>qMT}pf=rI*4kn92E+_9L4yd=a7L9Bgw4O1M^Av6KXLSm z)VyA(E7tn`5_Rh4dXW8>XB4;_Om%-fy{=i0Kdk1_VEEPs`tQ+b>Gj3M7rrNU>+3S- zWR{k)3o>4w&Cbrw5)u-#PM1G6n^aYqcVU)6O|R$cx`u|LFeCc%butDFo^IQHnOnT97b<^`~9as;V|{#x|_ehDs=XRVf$tLxB^LnQsL$&8y^Yt;NaiH zvfrNIkBQ@tKQls-_7D--ma{xO8|i22vNSY)%LoijS7I`?L@#gb^BJrmoaT5os1IGB865f0z7(qc|N>~Ea*$%cG$$k$rgAYxT@a(0eS{O zlsk@)h-l&X65g^z>2~OS*V=j^W4U{LynlQgME6{phnrhJWOaG@===8-`-a)+X)_p1 z+sM4fhEyTo@s#tdSxUex|^DcKTM)%Fb|9AlUWG2w}1HH z0Xr)zIVtkxK;)QdyGvbt{Zj&hPp}7A?k{6YB4}(<25DN1c%&wMOeA7eDyQ1o+QwM- z0VDbEnSTCTv9HEqaRmq$0+F;51|h=<2zVainp8D0v2d)#y|2*jLxmAeA=~xnmDi|j z@qFg1bJ_J*PJ-l9N#^(T{s#r(ph~y(_U$`oZ9$OLo3$(#k(DMJ<)b5~Z?7ds&ZyKY z7hU~SFztD{W6y0KYO$)onMJucfH1}H5ZZNow1qTo*sn5 zc!uWM!j<7%ZBx_c{poc@d1AhxT_+>{?yemGaK8(C7*YJe!q9WcstZSbL2#JH%e6>{ zL+iH{0nUc&WUpIXNRvHg8_{9WWl>7u7#?TP_+SQO7wAN|oDvuHFW{i6CEi)7I697bBKruaU;$_}eh|wD-RK&($+hQkYRz zVOEyQi(e(`^fs6whksin@N8#Q)w8!BsSd(O50iR>V=j73hTi<|-p`-a#>dr5OQJ9R z(%-)2x2dZhVl>1wAy1l(3t?%sS)?vg`*^Ie!u?36>rm;zg z9vMVs3rqUjdP1QTq-(w#!OEUVgM)*DN(otr|L7ZEGcnts3!sR$_u3g7volGwnV_#N z0{(A10DeYu(@C-oEsThVPcDqy5AD;xKTd*xy}$XbH?98qbCsJWq}M3=ZN0a&s;b}R zm0)geO)a;xQ;m4i%;AOS3zj%*0|R&=lZjhE@48c4ds`bBa%|QJ3jJzANlQxw0OTXj zW~NGGo;`b(lZ*E8X)7;h1=|V*#6(5e!|5GdTn-KnIJmfY`1zj+01wODDrXMSdlh@| zmLcoI7HtEC0Yr54-S)`awvLWmv?hiPKVs_OIc*#=_Mcc)q9d;%@8?7f?+Z>|U05^dBWBG-UL$D`5k0*%hFfs5I5kF8~m_bczUQ`?w!Q1L-nY zD0aTPFmg3`J>tBVw15&5vyWFRKk`qE`+szO1yoc`_&55hC`t*^A&np<(xs%dbc29& zcY}cfQqr-6bayPZAkrWp-Ai|~bnJek_`c`=)jb>zv3vL4nYr^kzj$WSYmhy?V0Qv; z8$B@JV2d~_wl}wkKW7z+Sv&)Oj2bHj(aXr&I<@6qjLh=Z1mfTz>=D5VrEn71Td;_m ziYh3OUM}8w?@jw>%v5IlFXQ9xwdEJm5)u*+xljQ&fCk~_hbg=c-6=x#x>gJdNxHgZ zn##($nwpQlq|0Ps-M=4qBIvLXogsw{7CRS)^lmJhkcs#jiHi?Q&$4oJ7nhY8uJ&zz z_*S!3&g^A3x4J6gbN-V?3Tt(R;?XUt=g*&VabXV8-$bkVCs)5)mOu|+>s#5Ljg)lK5)U4#oO3}7+8hLnpBIWT@QPJ7e z_G)oKn8~I3FWv={oJ7&r5J}^~&IrSKTwUmc9x8tA#NG*X&fXQ%g2h#2&;8>1^9Qs0 zk;I%1;~*uTqkf-cg>zWznN}RW^U{&BcvLHE@!72k1Unh0+S#wLI?=D4{Cl zXXr#^U{=z*GSL|xv6CGe$?BM@MUeBMkqg|F_$PC)Zn$WXV(SOkg+D^LElXEJi z^qv`TI#1P%lHP9mgG$T8|4#XR`;c*9xtcEyVx}{5L{zsXJ+g-TFE)Coqq1BuU4egv z(_LLh`etnb=YM|c=Q~iQ0WR^1A_~C_5~2UvoXE%%AP^K^oY`A&#)&Me+$G%@&=i{nJmdx_%u81H#EA8_wBlB`belpj3T4~;k9dE4z!4lOxhu?Sv zB-R*aLB$B2FK`67h4TW*-D)vHAwf8Qv`cArIW<2${c}OxqIQ-7(g@lvu+CJ5LGJUs;zIU`9^`(PlptG(YzmiG}>q-c!kr5v&;Gd2gpIhyE#vo9l2cL6u8AByA zUNhc$`St!K9~qVsJ~>uEo6(b}Ox?oHYu(JOfJWvu|8rYA(lI6cG0MN;chBuS$=$Mj zf)0m}_*NoZ4kI%Dz8aqQgbG|;o)t>&Ht!QChS1XE;&M2{NvLxkeBUk^8XPPK`(b=+ z{-(<0rPtC&N%Bdw8R4y|srmBdOHuEexYrNMyRZ7>_lLU1^jaHSsgU-I@xiW3fIup zEjQnP7}e#!iSzrW`~FE&c)eTzSOu55N5bH%*?90$UzVC0bm*UuYsz;_QrX<0L&{_0 zY2LQmFV=&8B1zVdOCudgD@`p)RwF{OPf#Ng#zAkU!!QxHh>y{Rrh-v;wlpLW9M^z6 zCl!iyb9SEgSRDkvC*|huHMD4`svZs+7_^(*`qS*)*dyR`g_|(2DWd4v@_M_u{j~UM zV99Uo7ihwT)d$8{MuYv%5L(uQJ#0$MOY3YKI>SHQvx?AdO4jAJ9)BS&*iRa&Pa_#pv%CWN_~FAHV3bM^ zkWblqfD!!Vi?B}pPMH*CL@EI23dzq#dfxEbZL=^j_4W43lSUCx5UglxYN@GdY7UQ% z0)p@6&C95$$V%<)?`-QkFC>AhHgwbC#f$Gt(s+7`n;V-I71*ErZ{=iXKG-Qp^kA38 zC$BK=yFB|xLp?Soh6h^7-u~c@kFGVysTgsC(lvE;m9^AH;PB$tj190*X_`pz{c2k` zGLzExvMjI5`$$bAMMj79aeKUS-qKl=v(GZGLY^v?uBz~}XQD;wyOXdBjWOLt?Hc2b zFbkEOVx1;<)!WTcoBF1U;_Ph6Eaj}s%%?h@Ig%Mv=^FYzTu+{Ky?y3`y29p$u+Y=5 z^aWGKm-fUCUXVl6~hBKU~lbRr6h z<5T1C^`rB?zCJE1VZN^s0|NuNxD>wIE@NSoJPL4RUsexAjo%qmz-?uTOsQZbLq%n` zX3@1sz20#--_C7^HXS?}I0Ie<>gsB0O_$xwY^b9wDE!<^-xvA2@4Sw;03jAGtnYJq z>Od{?>Xl}LyV6_nTgXQA-y^Jsh*3l}HOifto&B}%-10IVBfeo%Lmp5(rrfs1OARw7 ztO3@oJ#T0s(=dq90^?x~uJGIrzD<8XNWP*l(eu-&XnBYisuma^>wK zay2_iYS*BjrHpwL?EY@>AT5n5T==QF zf%3)2WQ}dYV4>vXoR zJ-sW49qj0A)!?aiBXX*=kKA1w$@KP!!bHKN+B43bnyrqJOyA{ZaiDj0V@P! zXAF#Agk@z`9*#7@Tw9LDX5D6YCnqO`FV`~S^v^fJ+3;|2_YVvV>g>+0`h_k+1bH3y z7bLKYPQikQoEKzCH4cl}y*kyG$8awi>K~lg6yA%yJgL4LU8kp~jkcnE?XLjT3K{s7 z$X{02;JuSHQQV)D6n!|GiuEeQL9jpGiR4u~QHO(o+xGF%5wVbGCAx0#KjL3MeES+T zT3TBA{oT6`3cvKsOj-_(2#({UmEI}nEWH z=X0Xh+}sQz;bht3R8!M2RM;!xa=nXT))Rp#A|gV)!5K=I4!V1Jbu}j|%VxZE;O(3lF(M16lz6Fq(K$y%f@h-~Ettl#EVdbW$LCi@{IleDZrv4=QGDk30J?-^_ z(qvlcp=^0Qn5n#if`X+b6Ryo{<5i?=c8}fsGuJK6v-iz!h=lm7E}qt}pX2Nz2e`VkQk;;KqY5eW%rTbznLB297n{3U?b z3+`{S_aUU0Pjv61i|b6apRCL~yM1=Goyx)OF__)-o=sZ9=sZ;IoA1@yYllk2;?51F@-DQ;+p5}0m1Hn3w_GEI=?#~q}w2&#PMg*sfIUQ zHoDE~sj2Fc5t2Gh70KS25nBC$j((Z9a$B5M<{_@lMBNdhze%&&+CtabT0)|&o>`-+ zx{_6^eB9dB_bQa<_mBefFHk(ehuyewW5#XJjO}3@a!|9jzi+;U&$a#vc@al?`1`qn zjj)UeNl;NWgRcX+86S@qFWw1GJ{M-~Gb)RYj+K;>0^^6Gkf3M4xC4t^xKNqN=ju|D zmcG-N)P;ZM)WKNs`~bN}#$#*EkDEYpkzCnlSw%qbo4Wk|{T+PF31kcQuV1H5sO#zJ zS!hjwY4hjGii$|yrs;fQr(_Diiw$#!o73n4oF@=evzu)F!GlB_i7vso=1s_ z!Vz(rPh*irx6O80q|>R!y?Q)?*Uo>ENr8;0V0c5vPVaKp4gSa-c|2u%b=gyrtpG_h z&@?a8Mqd7K+HI(CTrHjfyPr+qzz7s4$tCgIy1TnUSSH8EkB>s`JS8A>T^}KP|1=UQ=1QSAoI7LPbJyDS|;D*8y6OE5Q<>H>xF^)6?ZP z|7Ll4c|m>wo%8{iwVpc|oxIGLa`Uz-(UDwuUJE8uU6ZNvko2G%o;_LAd*eN(pTSIOcU5$$(zXd#J&}7A84ZccdCjyCfNf`P&dB=Y_~02xS5nU@mLg)rmzI~8 zHy10mA=@r4M~+1&Ly<8)x#fd=qy+_|UVf2LQ45QUPt~o|)J9TZUJUYyYnzKSC5g{G zA{oDIlatf6(Rm&3By+o1p5Pf)Okllzn;AkfV)n|XdeU)p{m7F~Q)Jz(*Ql)1SR0*y z6c3M>xOQ>M&JCor?p+HMR@kdcnK|LoGBS~=qoX4!GQ`h{)UB#C^%M*8^Y6e~N=tvG z`kr@LR=Fw`e#Q(o4FSnqt*7rY;gXc3Bv|l&Pf%o!4OMD5Ff$v*p$@Wb)Y>)Qbhs+$ z@`;FmT<`VkHBW5=gW0#-QW6r~ZUP6PKF|xw;{FRtaC~fj?T~J?5&b0RYs_9qgsyi% zKOBAMDK|H_NYmV4tH9P&$mgc5*K;j6Y^5OUnMpcb31Om zA=877j*gl?VOF)Qf)1>8OPzPh1qHq`dWfsXZwEiL7&_jXxd01M73-kRR1}e2sAyRg z?4)+Aq>YrI>4t{U(dzY~>;pkcVq7I1ow$ey4yTn6m7rIiDtW-FlwVQdgi|6fLxStq zP2MqVSp_&=q6asSNE@4NIy$;WJwtzm92#miwvun(zk|F&T}?yEjZ{uUO>G7aPXSQw z>Ib}LeRDiMJ~I>7tboOgkcI#kS4l;MhVbJiTd!dVM>`0r)YQ~O$qfZ#NfQ;bsJVYW zz7#1gV2YJ}{pO9dbkK;UTApgX+b#f0qyW}QyAcr**4tj4(@2Gfk?@u0<*ip#ZGzqc z(8T9xuWt2W-;VtF)r^~Vk?G~>zBsuzq3s_&+^i)a#a&({+!Lh4rC=2qv8;;ggYa0b{1g$q>`W2zT5kS4!ih1^y{x5<5lwr|6myU(9nfM3o%+KR z@i{Dr19@B5x{x-d0kSciry>kiBU<^HAX<{ZVOO`_4xRNdJG;WpRm~sB0Lbp@_#a|o zh8aUk%Z*T;>AmBr-Er$`G(XfCVs&hI_3d=ZbbME~mYzMpA`grsCQ@$|v+ z$<=N}KXU(^6x>)^TG|QRsXtR1Pw~8Yr8gOpYOwdSqCZbHU&Fwo_T&zK@=jh(%H>{0 zc&hJ;RzM3bCFRLdD$-rshv?5^JxA@FvQRWWJ`T#pw!jFP1&h1oDd)9kX0hluylRZV zyJa|0o|WoT?RpVLKBmiw`n*|UP_q~72G=_S$r6~zP=_51b-QNB5e+M@M4MS_gNhYA z56OlpyQZRkw=I$+M!;e%d{#vj)x?k2?`j_}YmknXpr*&h+~!%JazrSEW-ahZgD7%^ zObb|&luzYn;c*+e@8>)4ZEUvm%?&9EUf!~%?UGtkF{Q#N@!9_Vd3$_(0>By? z7^L3NA2fePE*Kxf&CkWo{_Cw}zFjUh#slSok!|wr+772sNn?BaU*GLK562x0D0kuO z^LggaAf%)u|J=OfA_)bkGdK5nLL$9<2t)dpFET;WV2Ckgl~)W!8oYkYh)+dDC9bNf zs;jNeZ?o~dN_)hoFkRP2H-*W;-i8mGDC*YBc<_|@_=ss~CG?s)Ia5(f5XQ(nqM%4g zOr#D1jy|8AZmvZtT#$5~s24d4g@y!bUhPXA7*kTFN>QG*-MZ_v@-voF@G?Ne*&ro8 ze$Dd{uAbL+Nu5+(@s`Cqa^xyZ&Bu2*H#fI~(yOpTG)AWC?fwE?FyRTjvBS5x{&;e; z7^d!9IJ6FS$K2H`02#+g|JEh-ty_YJbN|5HNbxuuPTK#(Xf)@Ief5(IJhNN&BWfB3 zE@~%qpthhHjfbjBTDo8G$~jdamET0>WdAcDH2i$$&yaBQo#|SqddY3fXrDbt3y;;g zR;sZa3-D|&)=Oy5tYdy2LmuaE=4oft?z%N0-dXMAn<;GVbTbzN^PtsOQ9(fgK-no= zR@vS$2Omn^`r+Zi=i|0e^joI}AWy<$kXzfIyz%$x=HO_dqbC<|ZK$YF!MO!`wkwK0 zCDRfpsHHFbCRiAvH)bRb{w!jT=04WAv*Y-zh@XW7`l zrv^G*1uRuZ2ogm|hwyD3H_NNtyKc7}!Y8^OXC|rM=XtAKTLG|ok%@g%-8vrJM-k-)YJdZt!zihV z`d;q4_R4WT@C|6}Cuh{By!97;}coi!dAn(iT3W zX9?8QG+%A5%9Ym@e0MiS|y|!@A)S2|?_j@O)j*&iC)k zCk$VV#PoVg<9W$`+sA$%ym}O*cI%k>aADu&EV>rsMc%_1N8^yP@<<~}1HX)csgIB@ z2Qpmxf$O{wjrRhdV!FC>%`oN>0|vtB)7CVrI>d zVp=n0HHN8b#B#*ah4;v|xFSO=WAyQtYtooVRFDt8;352ssV-xtsj;y*yKd4Dy69bx z9kzJu(~q9HN91^m%O;0g?HC_^^z@ipTJIrfiWFqyJBH*r3fhdGaebB&mx&B)xo$mn zRYt+aPy8^TlYdY6eE*C~g((ycw+zkh8vZq|8UD{g3U8Q7zN+DT1V5~K{sjrvpSx#w z-l=!E3pn(!#Y0b6TpVHA!z2M?;5K;s*Ptf`Y<%w!;`l(``O5R>Eokp59soJ<9mI2c z7qz!_r`Ub%Ws=FCfAKo~mTacSekO4CPkC)mR&5G4k@vCv`Crl_L9FX51;0MfOPTfR z86JNfpQ>SCU{y0GOEgxXio7-90wVkAl0e#Qt7h2}FelN6e~oY&W8lgP=!Gn<@Y zH)`!P+J1g&;r&mQ{BeF{`c1`9C=d((H{}fqV-om(NN;FF53j|meCwxSGU{&Hg(36e z^=!dyD}?D!_*|dMrOxHq;7dqZSrwF|HmMi15WAUq!rrf*eLmM_D{=o<0T%nz(XPV{ zDJq&N929qTu3UUx&m*0sq*IiP70_a=!zj%S88N_n7qyM7)Go>^d(X~|`{$P4tnH1v z2QTur2ND^t)i1+|I8tbo@P#hqINI+!a z+i~A5_P5|VAw*PglAA;v?d%%lfB*5|$5}8`-{VM4M5M_?HZCO$lSopyS17uxmCb?{uSTfSh%t!Q(dY5NSQP6UZ@IYtF zMXo4{10G4$=S#jYqSUutko)ZwU zbpDlF(9SmNa@vx<@iX^(1Y&U45*mNM;8~!#<$=5fN1Uzjo}!A*QT%w1Z9KBIn+3bt zC9%C-Z(?wu#&oQLN5Ri%xKs=MJ`dhN5{K*w`Bml61f9Q^n1 z-;3iD5%GGDmkN0u1C-HIu%lbIRcn@dW_l3@^EwG57dUong1P-ab&2(|7U0Y)^4t{( z7e25zGNQ({ftQ;i4~Zb@8a~L%e6%UJWr6 zZYB;#&8Y{C)amW9-8fA(`}Yv{nXqvj)*Uo1?Y;GUmleeidz)i8s4Oy!S9XLBEWWup z>$io6NYilzhg6?~vJhLFSGAu4G_Lmxxfi9IZl5?E3 zH#H zIJU<}YV^y&j)Hel^g)pq2A>@7PR!1UM|D+t_9iAJ(GUc;b#ySWa=Ug#wly|3ik;|m z5cTx*h$txmj2Cs(fseX< z3021@NgJ063J>_J%4P-^JSS}}2;8$IEq>+0f^s|Z1HZp*&n>6&bMK6&q4P2l>sU!S zHSF#rm9@m$9ELYFZpgQrn;oOyjzOQkL_5^bMuH9k)R$Y+MGW_3psil#hf)L*-r7LdfGrfYw}_mZn;VW+A_%4vxWK{XdBzvS5gQeS zM}$K}NtmO`1Qf*+l=GY8!UWjGt3MtJ;5MXHcmfC1tnXn&Ku|6WM#IB)0{XncYGN=? zC8yg;Dksd<=1GSdFtQGhkLSK-1ggQqhYxkFNJ&VL$Z$Wo#ODsyo^=hGUDmd?wn+D* z4X#vgYPK@Xr)G2wYa1}STBlu>v6oS(u_GnEg*uTKCpPKGC9+o=qm1o=96{1gY21cJ zqT*%+PzEM0QVPT5slux(Y6d9Zi5Nef`U^TG$EQhG!;sWj8#m3F!@IAP{a{dQZXF=M z0+5!Kor$C5>|D9I;ITZS5fvHvQ+{P;)~CZkw>wt}NUxC11wODRHcI$nt2GG2F2iAT zOKS|dp>co&p27_-tK(f1U}@Sr+GadABRe}^ozV%n?VKMJl*rMmh>N$%17dn-Qb$>t zgp!i*;X^s`CmE6>VJ>5N!#GgP!JLUU#C=P+4i1CS#M$`Tp+ekQy=fnir8+A?`R}i0|Ej8w%7y8d{uRIk#^Nazn{l`79r|~ zgD!BE7x;PEtPcuwWM-+Ut2ZLsAs8>?Mf`+uVc8RTC_K z#4?;rsLpXDA4p>INxW&*#XBOXvt2$*YcH?*8C&c%?j-id?BCy7Zj=Fee`|Ghm7o6o z`y1(ufJweMJ9C-+X<79Ux6bx&-rZ)+-qt`T{qR;=zgmEkiOel|COtFBCX=13No9I^M9WCgtvJw!dLd@@N4D)q`m7L7Y>u!{D4pE*?rR zY4j8WZs({&zKAPXTjp79TA#P&e~s=w|FBac9~i%ug%Gg!=8TGO754y(BpW47aT^%5 zp0lx_zF(b;jf{xw&4~eUVxgv{cA^GC#u%F>4jCC4V4|!i2JsjamR48s2D0T16hVc; zN(eEiwCd{Wsxa-HzM7$+&d<&51Oc|UWH&4@a1Vi~KdRONM+G)HbvjTyvcbyq%P|_K z7Z(f+bb3v1n)%MVC#<>8O+FW>=M|~T?)DDPR7XIenqJ3E0x6Kq-QC^I&5yIsu44wM zvRB?^QNov}$HR4Tb)^vT_3lp*($I4;N!7V?`%Y|hv}TbyfV9A>GCkc8K_hiMZaR?u z3CKi1vg`*`M#$>f8KOkL-ZdE-?l!qLfEAFDS@~S>sUW@SDKU4*DzDMOSCJFSBu3P3 zKcx$*3=?Xwzj{v^ai95Fx|n2GSn^RD+>gCIa2#n&nw>RmZkfkXr5Y;RFrAC&|2ehc znI`(Wm(;C8;{yJWE}*tbKU$np>?>msNmgT7?Vu0#ZR6I!-JD8qclU7vONLJ6S6#FDMXDiu4LebJ`T-v<;ngUBO)B?c<|Kz33-n z?9kDhsR>*Yw}GF}_@(lh&L@>Yt1Ee|;i#R6bl5@uu2bV{jKl)^nGB^(D|r)2JFnur z-Ceo=AiAjt96Y$zw?BCl@`GDaQJW`q3>xT!YnR>UU)TU$ZMM6CAv zZS8m9;XO3%OOkdJDrdz~qNO&`2+twrG}GnuL$Z~iM>2a0p{6TlI`}r6`KgUU_GjwC zpTvA|8rBSzlotmTnOy0=EGzQ8Fgw+(hSdvtkA^2!Ww)n8I9z!da`N&lHlo3VOCs|2 zx(V$$1kQvmf#9MK#LTOrtA4M7I+3IOeUHNksXDdcQ6|BTHzG8!T2ryTB|6FO2xJ0echovXS1a2+l# zu30~nn67tHNl8hs3jkmx}{K?kLy1toRoXN3A- zcNEmmWC5unb-nEVC*8~? zwo}KwHT#Psq$Hyy27Wt}0)nRQzAxV^lyI&cWo4Ow?17*EOCX7S_DA%JLCGAT;C&7V zSY0M0EiBw3S9n23&Cv38ONaPC=iQd)jn)ye(&HQk=L+6@I~Z! z|3`~Q7;TwBc#dIYSGN7Y`$9}WkeC!LE-r8CWNb`>yM2K~AHxcjTnv%TUKG7fo8ARS z0bmJO&XOZXP4}=xT3p-X+Ep9MQG^KlByO$?*r6`SxDpm?T3h|W7d#Z^3>O?z0nUwj zYwtHNzF!uU{4n`T-OMcjeraIJ%-vmC1#vHHfOQhru6Ca;ccsv@w=~c_qojYmF?PQ7 z-yH7{U}+4@`?6sa7iYy=kF(UX7Rk7!#VJ{#KXCgalv&0Fv{Za9DseOZx%tsv^)IHF za|WDK7LU7xKV~Y=dVBB1sQ>5NPeKV|B!2+DK+Y&V843XeQFcK#%a;e?93(IY&Hvu{ zM6kvtVxYzSREb^r;_&|AnQ$iL6=C zWH?R{&zxM#?N&sCa#po=k#-T5R7BZI?NdwU4bn$L|ii;Zn8STWt zdtqJM5G|HudKKdruS;ozc**|0^wUl7$|S$uXqgNsR6E1s8P{{}(ZzQ)z>FNtq^9Yf zsbFW%%N~0T_}{EeyDj3NC87U@>Yi+DYzw?(m?v%VjMAOe*XR3809c9DAjU80fmC+( zp03-I%guJz>X5zq?;2Qp15UF(LAzZru8R?uuDnfu-e<4w?%QBuY0dbvzo4W9)MWF{ z{vR&v2k6%{92(l4j+VtDF)ei29!D$w`=p5lll;A6W%mTx*0}V`aGw}QnGzi#DV!{6 zrOT(bSLlb*euiv({WZ+7{^9Z5{lAPVT24>YV$s&mkRNyfPTg)7x7Mkns`x+lzqbBF z%TeE^Z{T(bV>{6oKgbanSg1-T9W`Ghv|j%>bUG^z(l4vXWx4HN=~6q zI9|)ZfRKpDf0y>U`OuOG{x6ovX^q<-mqwDnDyLa-kufFSB>|cZW>5RjwY{YN-dZ^f6p3&dkxPcHr~SHO8%S|1`#Gzz%DxiktZDu$-tDqB^0!u0Va z$gU}egL+1oppNe7vy5ErCX{!f3X04h0-gUbPMy|H&2ue{*c?Bcp zRQ}d~quFaKP}n8NWsg{mE-jG({0GDuhq5x+*r&ko1w5FJDuH_F3Cn0M&{<9k{YjL{5Jhl_>x> z7cfG8mmwT8b*sli{wN#?&!W5>YeN=GRO4`}-7n4ET+vgO#0k5ZO$*u5s?kp}8&jmB?| z*LEA2hF1FIDWi^oZnhv^q{Cw7npvZ){RKE)wXkUuZg*BI4u}a_P zzB%!aqtLY42Dt91vB%f`($4QoCruui*?F2dLyad_JpzujZOMxEFC>A_Igf2d*`%D`&-2L5*Rq% zoK&)OCuSr21yqGw>b}w=E3$WHebv_G6Nf1?_{wWIU*VAS4}pi&YEK!N+CIFCmc_%t zX}&4LICwiV@Q_tm?cvSLuPI;sod>IvYbpCoD`=_i5k+94R-uH7Y!$mte|oL{ynYnW z-gUh8@k_vl`-#vj!qF)e;El#oKx}T|7C>F>l68bqaCL(*0GO${cQ?jL0zmyaN4u|( zvpM)Rl!U9YqGA(X1ZiqQ0eJrjMr6D_S?z;7)A#lD{o$@$^~o_Br~R(s&u79?CB;*2 zhHax!6@F(v9%=M;?k66$SVu%Oj(O#pQFhZIIHF+3SZ)!v@P`Y#tAxNQVUO~)woWPu z_XL{qm4VOl={{a+Z+z9;_41HIXPH1cA7p*n@>ubO;Xa|P|GHh{)o~7s&fd`9x%SPI zd`d4sy*bT)ID^vAD5mlYT~!coPeHwmFWnp=%M=!d%1L3WNFTwUtgw?a)a9N%QJnUMZAai()9J=z^nt|^cvl5G8ivIte(vJ z^?xwhH-tf}ZD#k!4E$KmjLOb_u*H>pm7$HIA3+V#>IG^{F`#pto$bFX zl3q86pg=3vbg{3!{ngxDqtAsezmF%d=ZzKX_1JtT0yc7$964?Sb2GEJxHzf1!~$Rg z_wyt99^h29n7mBr(57wR8*uy#XEI1isFjwnB5d!xN++{QP_DV(&iSMB>f*%4=25gV zHgZ(-=#$*%f1;Vt~dw3%=^Q}Uwl4vV+7>6XwRxzcY`I*eD-iy1ysI!((VFoI3 zGL=kU0c(Uzz4Ok~hcU^X>*XfEIB%!mE*5Y5>)T84^QZfM z=2gEF?=s`|cu9b+R<_^UpXq;bdh81!_at3is~bb zSBOOh1yfTKJ^{W2I|4$=)r}41{@GNV^w;A{D=Y9?JmyU3!omVrf&**_cb7_@gr_mi zfsKlTgO~AclkN2o*$c^~Px~4hTW!`4FWuYATv`H1)q1+}clih{tv?QUKcIc$;^X5X z5HnB<W8-v=ViZxxio_0o5R#pPY;I!J`(cXTw z$s_s1(4W2M@d7Oy)T?6*76kh-GBeO*5P%)ctq^BN{x-y9g}x*6^31V5D5dYc?Xj=j zgR|C_85o%A{gvmVB0W#KN36hTqlrF0J*Q=0K!milwgU=oh?`)4o&tI@+WfHz%+s6x zJaEmUk?z&h-Kvevl8lUuPikO&pbSY^<3>SDsyym&v`D83>G?{t@qBXx3>07C3k0ec z!b}hh7^IWZkElz8ZIC$s1wzYdwQpe41=PS4m0r5OT>^}U=keP9a(R|mz=JafA9G({ zq_M8It!;|tQ*KN_hPa+b7?7l`q%V*JhK3})Bqv8FV&hMrKJh0PPv>u8)c-|4!-gY= z@W@xdD$danM#;v=SXx%L4=k7a6Nm5KdHR3V7xI#nkmyekP-Kc>)u|Itd;K%z>TJ|z zD$b`?7vQO>DX86;0`IF?VV@;+bx?0GTWwPhn3p`&45{#Qs9lJ%jK3KkOWH~7dm?ew zOPK&^Zgp3Q#LLW(PM3=ulhvI2RwpT1`$kjuXgqtf{ox_VixzA+p@WHWDsVr;W|@5+ zabt)EPU?)*scoL!Cvb=kBRS%yb6J{i1>G4@B7(yiQdVsW~Bzo#`jI_zb#Kft^U%J{%iff&PfgvYc1erUi28s(P zGb>9;1~~ELr4ai{g!uUCp1@#clUNN(yF);{c|{u; zJv_{9qYY6%J3k-ZE&m_Nr{0#$JV z5B>8~;{K=0y+K@5)AzGn&X^0L#i^A%ydZ340lk^J`}GT+n{+4G>T=QcgY*rl2-=n*bl45EtjR+Luf&;3lO1jR_w^LnCg} z(2$R>7SsaxA&;O%ML*gm5^x+>6}Ez+7`RASs9IXpaDfDtsPRKsodAM;_f;;0oRcc@DeGx!{;IWFstud!F{2c)@S)$ zRTx<2$_$hWPZ=3stFM)-ih*(2JlFiO(V*US@PhJH)}U!`Vi>W|dG|=c4^|a=#fch= zp%0&eiHv9JT*(F9zgh?ul2}gH?2mI8A5-#{8ZJr#!>h){kT-iyXhMD z^@mig6J1X-JvbLLs{Hq}lCjCj$h7_a#U&+X>U?x;O-8_FvneVXstNh|eT0KJSUj`| zjEPf~wk9?<|Km=6#d$WB`gDZVxfy=~YmPShdhD)K>Ww%Cag~f6-1%riU&}bp7||(y z{xCNAC!DhW`#@h-n2#2q&*(Q|OZ?s`TbQLm?RViYY~iE^`(|(8K>lJC9E`D>o$cSjBsC_=He&YcD{Hza9xN=15olAC*vvY#jR=sOXC59W&jw>$T`egMdg_oMByWzj zh>D7mk&`Q{sQ68mSDEz0x-cc3k}5`@ygn&;AdYq6DyM_WpNJCP&B@onHgVw-G0N3wrkY# z=1D8#&3AsVL}^+X0fB@VH3e5w^-&@G&Y>V>rU)4!nCd7u224KyEa~<8D2;dJ`GPig z?_2aFFtGypS4N3Mk*)oKAWC()S|L?fFF^77Dqk~yh2L}+eQ@Vv^E)Z{9Ijl#B^Ac? zIlgHV{aG32&k3Ir4gR}m8rqv?@SZ<^1>f#}KKyre2Q*FgOyIz}KE8jT`p<%bMj#hL zo%;{bB3OjS$;ruCn?>fI@8z#$+NdL{evD2`Bq(EX!B%cxpY!nx&jMDEtwwhhdV62l z*u*emqV@c6ZxmN?^YYqZKWMNM(exBqm!VR4r1OnYq^Qh5gbtL~9~JA*|1(CVR~2?^)vKYO#akAduz7 z&3+2;yYn9K;m=DRDXShsOla=U{ACzaU#Jv4A9-!~<1j~i8v=<@gIamA5L}zY-re)G z(-I7ow4#fHKq)>c;H;2ScOS*SNV_3Oyv+2?L;mSzp{fj1l!Z%Oo!*dD*^BEdm-~I? zA^VSF*%9}KQdd}{(cGy=DhjdGb#Cy5EqaK}6t7olKE8gfNiRD7`>aI|W2Z7BvrrlI zrF_ZP-Y)r&R)%RIW_g+T+S?_Od;@x3v+oG%&Pdxui97K@g5ZazW zo+jQC7M)jl9xlH0mggeOI8k8ciB+`56_uMPuI;q{GscE}2)K{cK@@3qo9*rED*IW@ z0ueOXh$+ypIx7|AbX|Y!kK0a>R6K9CR%)2jpJeJU(b3v4+2m)czCyE&^cN`@D@+iu zD`tloEq5QKr751?%x9!a*|%##^idMBjb>Kvdt?jylUSK3IpA`df)%%e$_O-uyf#xu z4|6JB{JfvGa$DKOwnwl_Z6{6QPh01D16ja2EiKHwZhv{dfoSZrcAM?Jc0PY`d*deJxTt1OyT3?go8CB%~Fj1*Acw8$=!y zq@=q`q@`OxK)Sm`y1VNv{64?E&mR9C;~(cZ-r?{yp1AM(S~1t0b2YIgHaUDrKN$4n zj{9s?T}uAN6*_a*SqcxeiaPVLOYCAH@I@9y(nASMEA{vMg$s#TM3-0M;e@iQlW9w@ z{`~;wg9#ryDSZQFWgu=SW}fD;s3ghz5woAN+mUfE@1@H`6XRj;qVB0yLaK)F>C*D< zYTm%HDsh+8SQX;qZ3N2B=H}sQ;ZoX~wt-0ao~t1e~ex2b>TE<~*0hrL5_72zEhHxYtbF3O_i zGQOFfuAU|N_w+vxnd~(whB;jbO*QT82NxF?wGtzR(T9f6-hq5!7C2{SW@cKBX%-tq zTKAAhFR!)nVn%xU5!uYu!Rj%%ji{ct0`Kykdmhln3E46Toql*mV>(#06v>`4XT?wX z0IK3g@bR%>o? zQ39nL2KjOzldQ1y#m2?Q=hFT0HmuY>jrTWjhK^p9X1bmnPzdaf1+x;4jf~(RO3X%_ zj#|TjmeD%5y}P?B6T>@IVXMwWSZdUxJL^3SuCdsP8X8sBL%D4cdHDGFeEj^?NAt+z zx;jpS&dZ`FKj|^D0n{1hN1q5{c+F4G>b-1N+(3BO@YL@C(uK?11WLbQOMo6phYIvQ zGO&p7@VuE$enR2SWxg|?fEyAVDy1K|KB4VeJk`KS?V{>iQe^n?CDZ=)E{Cg9sA9c@ zg5?&BG+8w(o`b|(G4m!S*>JiHX`xNWwWruLii%3SZ^nsnaKM@n3II+gV0ePbNOz}Z zC1NO#sAdEjGmTm|*T+U*{QWU0UjwBJs24l)9nQag8c1*A zY;OLDo!qy?^Je_;U~eTVDhfuKDtTI-H*e$H0mh(J`etHkC{Ox9@cKlhb?i@@*&FCY z0>fia$Od6^013&sFCBp=%sy?MHG?Is3x02{nDpmdee3!TW%{r&wNa38(B*%tS-CMOF;FEosXR_g5RKwBXJm2D3;0+^r8{&&^ks_C(H z-^#Lxwq*ng$Td4YpH-c>8=*cwVcQHe#$^9*GVi&l;tKpScJLf!ItOdnt+L-pI9 z4EuUgcq>gnr0K`D2?IR6x;U2HmL zH=LgYsF|wjNIH7A5f?fk69xuaH0OzRkc7+O&uM^nLF@B#q$QKa{#uflf+d-N-7&6h8W&3j3JcTKNPTT%(ROkjzEizgDv zmA5NaRbcOV^otv@lbN2@VLOqJSnc`oiXo>#_RE4QsA)w{5A|FSRe5<9l9G}R4rQL64GHdNBVeb9 zka+3faIiknF8DsI@)ty0XwTbYc!x$uod7hoUg%J-J~l1aU%-Y4<7CD(a}U1PJv6KRbR2~Mvp6uBW9+ESwmV-C^KXe zN(u|njdAKx0127`)C;H;4}eEE*E+yjdunxldQ?~Us6GIIYzk4g*o+LrmoJAQuJ((F zbO{gjRVwy3Tc4!&`9L0g0qa}qk~}B)x!Te4bm@ghf-D^%vR;}nhR10LMLK&TFK#6 zFER>>jXj-<(1w$I4#2;IT~_+Pi{V#_XL?Q)RTpmJO@A6ZXcQqJ^nM_`7_<0zvcJ|> zt(usbtjTM}``FoVJ zryI4_WV}xObWfi?g-`2o?WRU8d3a1r#OKd%sqX*oK*d8KqMaQbOH2lq6L!C4?*G1XI?h`e+0OiBuXl>E&*LJktT2wh#obc43NxK?0uwcN>9YkKHec1c<(0e{7;PL$Qy({Txinxy2iC(WVD>N zE-hAI$RsKvaz5dMcc<$s%ASDZ8SwAA9D>2S;O=;+3c8$i>Wca$eNiZSWtW@d1Jy_Nu^t#)=V$0G$ZIIlHZwH)I%IMvEdI`s7PCSg)E zVQ7V+z2MUTGcYM$a(3M^<5gzHa*fEhR#qgylO4($x_-T%bB_jGWPf&axUQ_(Kl2en zNXWjCHIYI~dhj>)~M@b4liFJ_Wm6h(hJx|l_Am-=S z?I3(eWhT@n7=M|EF*ay1NgO;2h){KeW*nPPC@+7erKZgsVDNdaJ4(&Q#>OHNZ|D+| zF4NG^02*MJ@38V>p&IvmYy76KZDKpRqB8{P^tlOvMY~0T71iVBrbZk@y8C{VYDyd! zI&Ax~GBH6l1jsjlg7w z>WUb}k3CsAD?>KQtR^ZhPE*QCN(N2JG(0j3QB0(5toovLIOFl6KpirjI>ftiQY#)X zR}?*=wC6vGIpPh|rch=8#rIo4<-R@L?hqe(*MG>^)(^+P?u8%w8e^~Rt9e2x7zB; zJOTrq;HjCj!{!CBRj~q856B_z>8;HYo|@8BOCp&qe!=}yqEXFrFsT4ZDGy$Bkc+YG)5zVeEg(NIv9J(^gOgF@ zqEVO{lmsc_nA{{CK`Br91JG~ZP7mcV9pqYd8us@lm5JfPDIp@sKJ~1suD+vZzmd*A zJQgFOnA!h|ZM+Ppr_c}!vUmIfj8v5EO5U31=H~hpfXJxtQE+gGm)X6popeEFd!l(F za7WC^$CKx80REvcEb)N(j=SSQnTufaD3r8y{fJ znpiUQtK@tRo8w12#>U193Sb_`i%RLLwT?$hTIuF$q^qmzFShOY2SxJ zN#bv?7tLMmv~M<=+ER%(RSrGQ(M~NM;(wb91Ir(RFYq-cfYuKEIP`*wii)U|Fh$AL zJmKVI^u@NK<=LNY2}uvBDC2`CLiGGFB{4Cvtn9FWwZ^3WC$Asx-YwlZwGuyY0EySq zVpc0U)S1A7zP0mbnf>fy0nC|edrR}`zLR1gux=Z$p&Z@6&twL5g9gjR{MZIAUI@J7 zP##uCN88FsVMN{cw%5vgr)RLlp!YruxJ}qLDLWpYmpQQ0(w0IoUcc_g9w!TBnb9#M zR3~R=UW-BCfZ0NqCM(@lW=*^Q-NW->0}Ljtt*jvL4z6Ir?Ob`x3)VbMoSq&BTU$9Q zd6QV8xq<%v(sEtHr56ts6>)XiZ3sc|Ux7Z|z-cg=4K4Ty7FiiNVSGr4^HJ+S2!v2& zRQm}KFFpR~*0*Gnqh3lc%(2v$(Uqi)b@zDft(24rLbo@na6wmhJ(Q8UugQS{lNga6xZeY&v)j_v#!Gyt*DMF^jmt_$Da6{zOugn8 z+U}Z)$(i^28U1zSu;iki?T<}UAHErN%t$kah7?+xX=rG;Anfb{l(U?V(js7@ z=YBZdTy}_rgEMq~y7IeGx>)hvzrq;JfKV)5kOVxQ;A^J^YB4>%nUxj6nZhM_K2RtD zqyT*p)UblIw9SKqcK>1@VW6SKo-fggZcK7IcWPXY5Y=l{j+I@}fTplD)4T?iz)DGu zRNBO*&f~|tX4x%ikgVO$kFq;N&7*`3bG7ooF*B0e`UBgd!;=^ua~_$t*WbGLMBj{; zNiq>)-4zfk>%^h@@bS$sHa`C1@-mnwE~uB9Ywyolf%Ag}00NqVI?cvP8E-}^Y@yPD z+zAB-9&OEIlqKM)^N;WY9~Rd~Oe;Q~>ZzYbwSj-W>#JA4V3S0dWuHNg^2zkA4Rkph zk)}qKkV#wtHq;GvDj|B(-ZM`jTCt?4?VNM*Zs-^ypfg;|LgStJswyEb1P(s_aLQ9& zsS!boT7n9lnaYi7#t_xL<&hMnjDRNT`>$I=vB18r%4q9;lLWNIH?c^F3CUTqlhYY_ zYtd&OaCX!T)@n;y_AC!*n{tib#9XdD?e(p6J1;k5MO4_VmjR*&^3|Vn97<8UYdgW? zQg*9{Tks@Hrg4O|I`4iNY70{w;Z>OCSX~R_6p5*^T`2)jilYe>Db`)ZY;PW;rnL_a z8tg9=0*|W3#fyD-wAl3EJA2*lJI$&Yq2l6CEJi9iUa_Gtirw!)@-}5XpA40sKC17< zSN1n`S|VPbGZ9D&l@AUN-`}E5h_s^+F*EWdqy*#nK5#gTi@S@e0|x5}=Occ=34=N5 zvd(4b2Iha&!MdQJ-MP!`Pn&c3ZnqJq(UXKiancuwyrSkIg(887;!Akhri`!4G%K2?#Y?rJF z0^|rC++t740E2~25fe_cLO_T_>c`uwYm+-(hNe|QKcQ}lG%Cn<&{vK;@n$94$IHq8?n`Nt($4q-JtKkA< zG)}3T@%iuGy@Pq^>TtRBYGeDHfN___-ENO)coxp*XXMLEIUv5eD zdv}Qw0DLhg^mw`^x-^fgdm?9tR0U#+YA;YJkqeGEX-J&&>Blkyb-gaWC?Zg~^;40Cn5x_s zve|mvXB7XLob{>`%F%>CDyPFQNyF5TqD%2ZvryvXxks=6%z@%g1KZ9OIbte5Tq%AA zj2m+N0g+nA^i>ieicK$J_z5AHssFzXzEVq>;xi%`cmyi+S9k>C0%rJTD*Iu2uJ30V z8_8~9vY=Z;|BkjrsQCwRQh%A)7oSkHB{C@#9A9eQ`rIrRmlZpiyvBbIP}v?iwf!DI z$Ea}G3fwX5x_cLoL@iDOhvyJ@)%@1YBI4WXlao#C$D zNBb8o`}_4JW?x!dAGK2R2y7zI6}Az5@>RHZCEROZd#pU02sF5F&L#+`WYndKWd zIidUYW0%TglR?2rr%!9z*IKfA_ccnl37=7-UfK8_AmQVBAE~ zz0`I2GrWFy_i_@7=fu8AP*IH{jl5MSFSYs8QlF4#4k6*qMQKbui$j-|{f&$eu}jg~ z);0#Z5op*@C_$AAh}LI_zn{|V{(brWd~I^={m%i8&RvJvg`(4S-9Y?Bt=3YpBqVPq zihLTxW)N=aL$B8;D&+bO+f|5^_f0g1zLb_$Jln}kps3q+3vF8jD}}HVK3WFh-&aMD zUiicr|A&g%fRJAPl~)UEI;3m||gP&m1;!hzOkIexVufT-FLx4T#B|3(V{?s4wA#3pOoqI=;R*G@6pT zzT{eJ3^0WTT(yXvyEB8VdFh8E<@EyUCU0z4e4rG8Y?KmdHeP0Vn6Croc>oBcJoR4& z7g|UL8PB3{$;oSMT5$27=luA4LkBWSLBdx5#5W`)eM_fjr%eHOSLWtacXn_Q>yyKU*U``Gow+vc``6t^{-sf7GIO(l+t7`!-a*utY-ANO%xYMeA3 zI{O?SUt=_l0Oa?wS~^%4_K}pdDzAdM6--|W3kn>gYwN$U>koTACJwXpXXiOgw90N( zrArWYcw5CpV-uh0w#tk&>d-8=3d8O_@ghQUL~&cs=TA3y8OO8|>5tq_5+*1@E6X=3859XU~EtZ}O==N(g&n)+5#YPzKEioe(Q}A=;MF^&_%1jqz zubZs>C(aC{!YO$S*b91>=tVweh5ZK0vm#KN!_b?2JKP@064=BymUd^ zRct6vsp1aWM+&J)I$*Xy9U_HFInxwS4YdP2{|z58@pz2JN@Sp0Mx|t7VS!}t{VBj{ zc+c?lYnK9tAiyOIE}_{ng%lO-wWlbS*4EDUzkk3C5EUKW6y}>s z3fraLw7eQMe&b#+E!CEjkvY@df>EVt1$e$7-@%ERI7(9yJO<3ABUhOP*=uZmv zw)cbRXlb8jF_V&JsrDIQ2~H-spF7Sj_JoE$4^YgJRoO3->FA6J4o+6iM2?4dr=wzE z0Bp-&wihafIAHl>Oa)NNLqpg5zIklf~ zw^LBdYwjv{N#lTLi9->h96GD?7DQVv#u<^lryff_tV%IhntET~eZcL5-Mlz{xdx5$2KgA{g ziP+1|7RAPW^RP_eOlxUneqNac9sDl00E|bxkn;H^3O|jfzD_Q69$NN&I?EiV5M5^~jP0uclPc|GcVy5z@7-4u2`WeRVK@#KH zs!BkNhJ^&sM*thEBZg-vzj5yOa&SZfHc2{<`+nf*1t=76sk)Okv)xh@Tt70ak-Zy_M4S825X_kl!@WQ*Kfq>69cpM?I zft*z1szrl*=CZKX-Ho~N%teJJWN&$(@NyQ*um5p>O;1;MzC8{qQ-Bm{WSlm9S;K{T z9RVE_y>Jpaogb+~Q!YCan`YNl2dN+~6X?d?$4J-1 zd6S&B-upBCt2D{$Gu`58jQ(+j)z)(Tszjn?s>`{sUF=y58}X#~BSNsaSrGZ6ZEkQv*ZJGB*GDu;K&Ur%26% z{jDeeqk^q+^6*e$IomoZ=k$0~w;r#Bj1*q+V!C>2Jzwxzgo}{srswqe+3DsA5iw^! zI*Qo;_~$}F68&FgDv@PnqIp`7N5nm##)Ei4`YoP2%(^Y8Y{32|UfrUj@t~MqlB&P>zhu0j8w{AVPx5r{+!PEhb9RhLvBxm;d;Le#x^VuW8LFg=MB8!MJ<@oL%M$QZi?CK=Xt3h51H3$uJTiBH}HtI_1;2 zD_}G4c#ZM_4-XABbvbOnskb5}z0quW`*y(LzfA$ITuCJJta}J7;d3Y~7TiTMdQ9#B zczph|hl(Sry{jt^x{CWj5p);1RL&eHUP-FG)EB~$n$xBSE7upM&G)RE5Ki0-B zeEt0q8ABXRur}7~BcbEtqg_IkHzKsOG1$E&=3`&GXwB}Koesa5#3=n13|HHw((dlY zqzu2)F0Yhv=^J4|+vVuEINKcqWWFkR-hBBo2GVCB0n}W*>H&|#&(_u-Dt{^Q@)5)s zRct-g>ZO#P9~NzIR%<1Mg=I4L+$Le$EDvXHGdEDIIS3b5LZIL@1?Rob_sHMUQ=&5? z^PnQ9Hrg`u~ke`1> z{okbfD_=Me&>y9d#ck9weG@AC{*q8=1y%L9aP-h zM=+a$F}&k&8_3XcVR3~dy{-Mh;icS;giJ&9{{3;-A22cDxo{L4OO~d1be+TW?b$VnGX=^893uM#%0TwN`h$0A3_T=o#K(W} z<(duKH+i#lpy@ zoz9#xJHnCXw?I}PH_PXj`)pAV7v;JI*NBb{nHa*^tAh*_k>rmP#msYd1px0t3GEe z^{KG1a7I@T4INFML~gB?ilC$flsxuWtWxx7*Z=1~xznqT)xBafq6+(~#JMbbdh2>n zZ*1HA#&i)Ece0t4i3%HUY#eySmiP>N&D-ue^F1S+&3Er00yr2@R_|T$e3TGLJe8{I z9jGlF+SJ!R*`uJ7Rfc0X(a~}3B2=u1Y80pFUE-7P*Zv`gEv%{^lIAF2*<0P&Nxjbnn;YeY!CC`&|AHT?_{EpHVjal})4HGkD3#DcsSxIm#Je%`9-2QVg;MXtkfi zeZO(za`#GNVm!uwNoh=^vIfXugbCjIS#ThcbD`@(#HszIizj^LaKENzS_da55Cp=mESrhne6l~^ zT9VQ3&IY%*Ev=@xVTQKJlFwHVF2GGs_K7!!CPF3U&@b!IOeO`Myc@v62lC zb6%lDDt?uxd;k9Zhue34&&?T|Ov74+<=v>l%*@Q2)srKQY34CJuE+a9VRql!Iy)yT z%+(zZ{ey#Xot;nKIqiuDkWK&k^-AEpIl%?&OEtEtU^UX_-j?}L?u5Hy4N&){Ty{FV z(22N6WEwtTPC;D!{{8#5&Q=F66h7*O1~NdeY|8=YR=wC{0LWTURKT|Gn^@%I8FCbT zK`OZ#j&rR9Im%;SUu4lMrSl02&OA*fJR8F?bwdl8Zuqzd&gX5+Mc~8G-QA5&!~$S9 zsDD9{J3KrLT3PdniaikSLLU8ASZF%%b>N2&9;`<+)lxNRkF?xhRfUVAUZPQMMGd&4 z%h}#?)#+&zrwC``z98O|t(BD;+l70&xk!R=b6?-iTIr-qm6Aq<%TZRI@(T^H!EFOG zJp0w|y0*TZ+6vdEVc=@Q5K|C5^MTG88D6{FD-8+--j15BCQ{H<=l(V<|HMbM+&EHb z2(Xi|kPs*``t!7FdxaX0U|kA54NX&P>sQB}`Hkv>_{vH_%2_DF^qTzGYh|Z5P@0Cp z#teKYDF_G}iDAVE)zbjjvt60r0aRZei^t4b3K1(PMSM0iR5jFyvi0&gDuiyvAxHoK5Sz!mcWt|SmtVYkd{L&J~SDiEJO(v;GH zdxJ6^J{+sXg1v5}@5^j?I=HX&)M0j$$9W`S9nm~tZF6$zW#LS!#{e!|`{$qYH9X<^ z2A}oy^#qsGAT5hBdse+J$Z|}o-(UvH5#@)y-BCIP{Oq*>w=)udCrzfH2M->=#`qer zfar|kR3Coze^SDqz&6aR=j%VaV?h3q?fN3-mo3T6= zo8#4Y(~E&>z{274Yp3*}3=E284NTU$yH8d*iik9M2!WYR*12l#{Z264mIorf=^&H6 z{Q-6ig5BrTtO+b$mA9<4Sz5#GbIah-p1kIotqMQeP29U^|`=}kAoc_qF zK}fZ`oRtT9kw|Q-!_7+xz}M$rAprdR`4fIE8z*pStqFq%c#8x$vtU=tNXGo&!E6JT zDAU=(^Er1Vq18NsreVK3oFLIgnxQmXUL18}$=x%O5%+hh2CYci6T=Y;U$^0|)p{>< z*sx<<2y}K<)o-biOPc6ky{jQGT$I{RU6o-{zxLe_4}qF=aJ!d@PR0zMzRJ#zYpBy^G<*$Av7rpF=J*mK)Bjo+yLY-YzRSQrx( z5>?2koDJyt%VHCPj}82e+p`d!pqP?L`rc6tiR&HDHH`<7Zk#1v>TiIM@<8$varIuF z4Fd?4FQTYkC@Jl*vs?cDfqL=1q=u@Bnug|sV3wL%G!%c}^4Hbgx@=~048d(EPdiVw zy0y0#mo+mZYYce4VeS{MFfjlhNq>KTn9sn4Ymj*+EG%rwm}S7IqM%TR10RBPOGB7ms6a^D(H2~~|KDXLw4>lFU7Z8SZ zNtv1S2qTaj!R+a1bK3KTZ^J)sU#%`$Nf?Kb=|3$Q$!;%vt96G)&)7K1&(AMq<~!<4 z^Gw9NAnVKW?YyUf0o2ho&E>cusrY>awIHB?0qPw37{}syc<*983t@YR-!9QreuKIw~pk*{%$7 zJG(7*C%vb<0?j{+Ex_*KBsT=Mwx+@)1y@QH|Egmv=I!X?5mHI9TAdn*jKIYj5yH9PNb zbavX=l^hnVZ0pM;p{N)fA3xcfCfy9q$)_%olBftsh+pTVMk|E?Uz~%vO*LF0h*Gs=ACGoaa@1ZZC{WVUg1K{YX6DGZPH9O=bHZp- zQGn^er$gV+kd%}ZKx}CV3BS97;rCF$OC9{^pxZZp0%w(xF$<SYm(Cn6XzueeYalnaCg+n+^Ef+7u58?n!OnzCefv#W1@c|0RpARi0e@eGtS$MXFn8~1;Yjg237_uF&C%YTSHq=lE5RPcx6y7 zjzfR3oAQ1%oq6NKw~Q06CnXtO?;GmtVQp>1dHL%Lk84&|+rF>z_)q?F0nT3zQ<^)F zeJRM#ci6m_n4SGhQ^x#j-*Y(8RaI5yV-x&jo#8oS*oYMIfJ+e#d|jtCCp9&-7cau1 zzcOfTC)~E+X1p@4`xvDf9c!q!7heob$O{GCacL&EmzA*_M~-a|lu?5kI= zU^yL(az^_63}5R>C`)nwsEdk)L3_R9A&+uP7;L8k9`nZ@$}V2*Cmp`3~%e zg=NO_^76!>Q3Q2|*Hqig7Hpn^@+AFPRPT9+*8^|@;Q(JtEG#T|%0cAFs!=BIfb!r_ za(mmVqM~BUa*I!K^W1g!OAyuY>bAFcy2K;kIe}iJsE7+80im}uc4Smd4Za9`n(H@j z+8z#P!Rj?wsI{^xB+9US=H*M2Q0oA>0SWmrH9gJInSzsty<}+wk8*a&wy37Yt*;5w zM&N9JO|bG{RoG_pU1%u&BT9KeHPlGB;J|mtjjivB2oL{#?helfJd_~Pg{W)!EH$Ui z%6XZ;$)Hd@P8$5&mTUw>I>9FwtcAdX8|1j4gNkL-srM$l76f?+Qg>>0wwa!uC-ygJ zaq#d2p*4XQf{+TNMdrwVRMpf-$jLz_W{u``X_F5{D>rE*)v@UujD&$h9v>eM6a^wY zJSd?Ova%R&S3XR8g2GPR3qx+s#eP&uo8zLuyo9NF8Pb^h+Nh}4y+HdE78yAV?#2`L ztK%C5a%RxbBdOAQk8sxm3RM$#j*@-FqX;Hya`S+3X+}!p4r9SXK(k``QM!*!R zl2yC<*xJVz9uWu#(00^nB#&uMKPi<&>eWn7PeUPxUGUYwHZLg&_Q?JkCcKR_HZlUT z>m!HDz8~A;fh39len&3hBWx~`HRq64PGUc57T*KM)zWX@xVX54Tt{I5`5I1matz&l z-FqlWz_pEujx-zp^&#fv-LVhN9wfIv&Ma5NQZk?2yVrg4r8Hv!2Leu@t8)aiz3o(u z3>&|Knp(xvgY~}HbSY`+TQ_gOJr=Y)efjYe`-Eybhl6MAqLqM|nOO-B4~gyj0-Bfs zD|Tj?4rsH;1D~cTs+3ib3%a>9YBSy?TfMuw#_fJz0X?G4HeQqhYnT+)Rj6uD<*1kZ zn%w>wLBKd0XsajCs}B@a30*6v1NjOVpmw;hfcY}zB)Z3HIT3N;N@$m`~2O;GIgYtiavV-T<)k%^NMil?O>6mcZo#*Q1>DbQ(&^%Od8~lp&_$ z&Awm`?7dqL^w6Fj8W=u3b(tP#5gadFSzhK*7ymr|V{{Y(7B{WnQ|!raYw)7AH7Jz& z`g8B!_mpmogTNBDyxx@zwh@S{dj;WJs2%yB<$Gdcrcyf0;Rq;ap;v`U1013K{Qb47 z(Vn0%zx?G#OUA6W+uW<)wskzFJqFttAV=rID}&h=JipK&0GB1G?$xtMwyTt(adFje zrx8Lo%wWz2hQk&YEeLF6Mh2}HqRzMq+N@Ie>fng2ocHxtb7ahccfk2O?ADGBup0@_4ZVh8?+BgeWa9JE{FLiSnE)D ze9CKplLYdxJ4<(XfWJ962is-IL~O9ND?med1|qx2;o%zBV?XdNXkQ@n63vF1f}ETj zh~Q8(LQI47*$O>(xpjv3pTmn-gn=)FvJ~}I9atg>=`t=h_U!{#&{2zvi^EcOh{sTV zz)OJa2AtzeD&$v(x8R80{-|eQUg>u2ta@(+B8|%P=g@t)Lu=^pN9aO8 z0DFt!H{mJzJ}|HcCB%D)@Ox#0gF`@q0>)TpFtxOD_RBim0$899=C{-9>*u11#?{q< zcQazY2SNj&T*hKi@(yOizi!Dn3#!+Gr{fr@@A=`ikN;d8>ghZ)Gc$TQjNF=m=K}i? zR3Y+o`1;h;Rd0t^hVaq!*JJtll)1qXv-(76v)OU?a0^=AO$&y7J3BB=f4^$HmbZDI zrLZ1!D8N0q-e(nKT)e)w*wfI~w$c(p`}pJS9N1b8orSpg%^!cp3q1;qvC=idZNH!G z-2Y%vJetYH$w|s%wg`-zyLWFH=o>n(j-7PSNU5`9pRy1T%<)?rTqN@dA-o%=%b2wM z)QS2s_@Ogl5){0J)nsv}ij*%uGmZE4&(BaC6n^@&tG1isZtlP+3Ou5ne?$^s^&b?L zBV{^|Pi~bM85^%p7VjuQ!e3w==P_Fy%G;>Ffqq?-z>Nqb8+EUr3usEQUB#q?6ZItc zwX3VJzj#|~CyQYr5pzHzt0iCTMu*vxlpf$MRl8rD!&9x0*$*8i&;$x0fIX13x3@Pn zUFn%J39f-Zuk*b1XJxhtX#V-&V1h3IH8r(luvt0h=h@_jvuoVSuo%Z7y69Cv&O;fQ z4oKJFEoowE3d>4kItV*I-xo^x(cKM3as^-y)j7z+%-vz$AdYUmL;3jTj1c|m_BK43 zZRh7Ixmt~Fu#j^G&!gq_^70}|@Y2t=wu^^SuXtkov8`-vi(#4hSqtbN;L2fqEal?n zK07^yH|p!_>xvVE>;$8clKohw!xwd$L>L$t(DQNtV}5h$&DNEAH)i9!hoDhL_`!5bAWwavY~+r0w^3Q*lYkckpeD;Ma8wdrD>^)YSH!X zQqxn{0Q12?fB`E(m00kDO1}w(lZQ$2*LfeXb8!L13+Vc~g(J{cnrnuSDRn(YAfSUN zhX&W6RQXG0CXkTucZAGp;Hr=W zqD(73GT2Tl5GMi-{eb*v*Sbx7|9)jbtb1U9;75n^?qX1QI3YH6H&Ye$Z&R-hgFq5) zw7?s1U99cwCc)wA{O+QAQg3H0|Krcj(%*_tGr@f%FhQuLi!~8jjOwFj-#Z>n*}2*4 z4dXu=8*Ph<(b3Uy5YiFnj;F(0VFd-(Zeb8}{ZxRbe`tAod%KZEdUM-Fgo5%1i{VUv zq4)=FtIXwe7GbhN z1G)GS+A9UR(9w!f<j*Z_8BX z=B9_o2lYt3O-g(SXN2#5_eg(HVJ0|#=nYnuM@2_+#o+eJb||9wdI#-Mbh~HEBf=>p z#wX!nhHeBJ%^8g^+o!4SiA`>t2ZIV5dfWp8?s*!SNl5|N$Ib&L(<+u1 z8B5CzbHCa`pkM*up(&7ph>XnYM;{DXjn<+E4tYpnlf+7IdEqZ+zSJl8gAWCGj;~cK zyQrbkx~eEE6ZR{T_-_CWZ9^20lUA#;qh;wEH?+GaK!B<+f z`m3nFxbxY3$5Nk&HcQU~Z3ms(5sb2U&DyYVmCTLe?iqCM&IcP8#kyYQj#$BBP-$nK zYtf$)f)U==uO>)ZO0*h2H?I7{j<#$tVn`5iRh#^+YBTW|1x$vlW`72ORYcjD6R_u$ zoB1v!3J=S=yr?jeXD|+VC3@}_l?a6G?d`#O8pygZ0oC5SKW3Ed9pK?T`7yzwL0Y27 z)J{iJbD~qT5)zzUnFTC*hGksu%b$vF2#RA&TPnh1%);UedLu0taS`#i``;HYN6 zd=8zZ`j{K@P)b@_=9e!oH8i%RO=G|n-M}C`8T-Z!FADWA=>EYZ0c2&my1$`MDk?69 zx_RSZ1o9aU0#em52%hGrJz!yZV{RT77UqQw*FP&WQ&L8zk@a#d`TV@y zk&q6iO{jZyQ}BZ$xUrBBW`+qP+L##`@wDy<(mvhfW8{>Ecfy{74dixK(G?97!cbc? zGs^(Qx$f2M+&rp^FoS_^(}{)Bv#Mc$)Rcg<%*E<#bB&`+7jBwt`r730%*r1=rzM0&tL!b# zEga|)ptpeH3kw4cDoqGpaE$!H83{^32cGL8Emf{3AhdCLqooCs%_DT8P4iB7V_Q;T z6B}{y4|#dova+{*8;>_BX@u_oV}Gu4UcC%G)S9X!L|*9rjg6N=XypKN5f3CcH!uME z8v)e1S~gQ7qhBxIfnDj8`-MMt@6ga?!RU6%7t)fQmE{`{0JVrnd~R|^#!!Y_0u;rr zr-$rdbkH1d*U8C=uYvK9z)jPC&Z_(d0upy^#XJr&I2eu)gJdwKzdvA#7U5S;fbX3* zRYk8?2#DlAp6|smC}gq4bQKk$QGw3}#Y^)K*tq!O$rCR`5`e=3i_;BH11UJ8+5s}@ z&d-O8jr{CcEgaDXqYkixp@S9R*?9@CP+IH<_EifFE(Zy4K$r*_>F5>#G~+AYhkhH3 zQmw45Rhb3>LIy>r83zCQr3%~9RvT9Ww?$RGkjj9W4YC_JYNZ<@o zP=HtyrK$>yYN*yxlHPs)PT+oNadaBBC+e{I3!WR8!GYivpek66P9o|iM2_7*sIMv} zENZtp49)FjB|fty;@Y&Z1JmFLCe`G;JW+^u012GBC@A0{7Gc^2C#fBfm(I=_hppd` z*tan4z)=VcqafQo2OKvl%JKIPAJBHgdaL_LfT^IKf!V$~z;zlLtDx3?#Rirkqfi$@ z-w!1Xc+P@t^2T^M3_ei0tg|ySqkvNaS5M462mG&~rf_z4p0VD98WkR%bC2oviykRh z2yr7~u^wSisPf|Z3kC+ptu;P49SP7+XLHY6&p(4FR8q19T(9Zz(PR-gyPG;t%9@)q zYh|Q=xQT!bVBsv(zy+O#4-M!QXldbY&+K8`5jw2%dvcWdpMMz#(b=Ar?W+0(Asf!%aS|zHyCY)Fiox;M&ox(arlX!vHc^jWdy!rlzK< zYG!Jx7`B*|6&m7;UkCWksoh$i#+u}}gx!fj3LAk5eC7H(H1F@7Yy93mJ=!5+)rLAU zqIr%X>kH_Z?b{c79JcZO#Q|P%K3-LY5*j#0Kxk^hd;=%7wx}d3lDINQ+kR(o4RnN5 zpnvUe@;4_*ZJybR##}IMgUl@?EDT$`0qCuA+_`>Gfa}q?jJBnfNTvl>T@Nf zl-yhqm{#23H2BpBBSTOh27%wmv{74=KPlzGAnTs52~$W5=uC5db=~1i4IU>+XcW z;NZ>=)@7f3Lz~~)1wDQGLgc+{r0<@Qp z!MA3R_sEeyV=eWF(a^GBw9eq+;X(h@S$IDuFHajg1H8RJrKCdaXuPjozwHt~%~urT z!06qm5CH5Gxt9!5xcFi2Lx$x6r}t(Ubm_`HsJNiHU6s9bVWv z9ArCJ1D6gO(1n(oUvFz5?)1bbfjHB@PxPEjmggP5UPf7|Fx3Gvv zSEkWLWN%IF&%HVUzW2FeJc8mux#9W(H$-4mXbrxsXq34zT6&z35>5wMj+E4US~$Pm z%fy6N9R@Xk@p+fj)KL9!`n_NESJUoo-vexOVbLWx^mDd;F%}nq}jwRNwg@uUuGdcG@?X`VA~MDka-Rj8iUQ?FqKu!~`pY$~}Zdc5il#0$T%9U63mZj?DZ=>InocxyZ{_h)8@1ADZ1W=Ai^~~F@ zKQ-XKtHz$^+Uhg}$FNv`<2RM|lJ&_SyMh^bf4M53xpvLUs;c+w_L$NwALLP08hf(x zaLUQb$bPP>f+QY$10pfN8AMn{)eNF96bRM9)OZ-o)zzD7Dm+;!GMvkHxvX=2wloe4 zYS@!ta>I(1Y#}GhGD8GA(#GRKcLGag!lgIa*{hFy70}FrX~~UdBb7_iF){+^AN>|5 z9$mS-NJ(`j3wkk%e@%;IWLb>Z+ak4O{NBA5CAhaXJzA4QugfnG$|;`t%D+?gwHVXmr8rg z_sxk}D!rTj`tu&wf?wobXZ8m3#>d4)6BvWSgX+9=_OGNaNHAx<>p81NN;lDzWO+ns zD&BZ6F^i0sA5Wu)!ia1kdRuNzk>mm4Fwc+>PF-I9!OH{rEmmh-F7Bc75U6|iZuCuT zQpKQ6&x11-UK`iz%xe!SnwO;;rT=<^1-BS^9f2ITcv5`4AH`c45cWMpe)tOfrHX#fBJSxz9uKYuN@-o{!Soa{=(wc+{%9LdBg?9^ z+^b4E{=J@#E@k?UpihHvZs&aq)GT*KGo;oX1Ky4jko>bHOI!a5B81 zbz#y)*^RY4QSH=OSuL#>tlAeJcB@KDZanF)$Ak5Q>-FrsH|o~D)YLr<2xx4WP7Wc)ewb7;_HY?xTL@w@)>;CDX3o0Rp6M2y+DFPy3}`$Ay(x-X^FdKpQS z_eyb(YdA9jbf+3O$7QNuZEcOs=lE&EhZDMtbNQn3zM9^U`H&e!jnz5J5v$tLdP(iC+J=1cl+tQYVC zPNzRj-KTZ4b$Mc*YXWsu|MdU9y9)~?i zqh9KhJw=wPpTpwz^hPv?@hjFw4}$az+y5+=uh-F%ZE<%4vZto6p9UYCrKPBKDY>+F zQc+P?OT8f9`0r_h%7MW_ZQZizer^Da@RpgGn=ddL=p-%^pkS;K>f}( z)25-1&6;H;Q$Y(%ZiMl@|NVx;WU7;Kib{$R@yaMt<(1@4I*j5ZK(SQ@L!HS;SEV1m zgSY*CTU%Qo5Eu>dgUV$!NSmq9gM~n(OeY!W9xU2kmvFc*Mu)R)&wOeArnrA)j$~w~ zzC0dj*y;~NX?0*Ev!K9fWoUVLqhfAoY4G)VV)45WC4H{bq7czIe|Z<_D{@K?9pbe6 z)m3O+wvB})+O3p`t#P`)0%>^cqzi!s_b0mm{jV=4`GEi$=W;$-fuRT6fw`xAde})8cgWx@_-Aweqb%)d{O*JfDdb=)Y|EZg) ztE%dlC^G0}@r_{Qn`?FLaUDJ5A>mqNGHaN4^sh_OQyd$UKK-dC6kYWO;m?%t<}&!1 zZoYH*N84Ri?@j&ymfBrZw?6YaRX2~7gq{x5uEdSLjBi;!y(BJnK+0MOZ5!JjS|+Bw zd$XL{z8iF%Z%Ng%Ffce9qjGAVLwJ87kf)VES!M`;yvkmjvgLJAjQb|s*tGrBDL)p` zRD(Z|B>(;#d_*VPyd=j&#?8S;>_^l5rqlOU%E9}fsMEd5kaI@|j6=f3W$c4HcVb;^ z-Qw&_`U*80{T_P9Kck2Gp5U@lx-dk9ZlK>Nk^pn=g*FIcjVU4EDtI=ARR<`g#FbZ6 z{FB1|}wpb)t^;`zdo_1PW@u+`soPrIj zg2Ri3GV0>Ri`@mcj<`5g3<*anr=`A0MT3-*xRRr+yUUAi&)ig9dk*Z5Kymi%8%0tn zYR}tx>Mm_Adby6j0EQIa|E--~`d(}57N7+5nozDaeQRE$k1l){kPCDj6z1>A$p_Jg z1=FtN-|l?O)PUa_ccUO-Vr^TGVplE8AI8G-NuhnRbHiC1TE_1C~wu>7b(EAWz_i3~a$^d-P-eys$;s9+QOhv?qb7aj-{NHDE?mfR zN*nH%9r2EXkK}_v|cLTLBZ(4ac$2Wnem}|G{?S<>qW7#MCFMZzCq2H zm>DW6K8CRt-2!3ZMk7c|r@z03=*Q|oe{EYPlnidI48-B4WR+XDUQ7G=fy>fdN&Ap* zSveRO5D@VE`9Qj5^so{-N}eM}fG|O=g`(faL89{E77!RBw~g^wpMIsHEjXc>MzriK z;^!9RW-n-JrbKDEp3c5@5GyLnuKsq(e}(+nY-3m-wt&xnHsVZDcH6;IPA2w4di^X z;|V(X(z3GietRDhk}QosSoM~oE5oQ>MMcG*_0eew30?%yqLQv_PV%O_(e;{|n$gFc z9ihykC3+~v0|CBqgFRUO*DZtNNYUBmj==G1AW`fj%(W&F^7QK;O;cHF3+bU? zU}eQH)oA4eyO9ouAHv-9^pL?cUQW2!yY*_wid@_`Fq(hF?U>o-<~#FqCcCgm78au{ zvXc-C*P$MT{TRs$v^crcJvOxo-4%idw0!hlYb>O6e;xkv@cy^KXmAILc;P; z;2|iX7x%ct>$@873a$O0~SzH83`AojD8O2#dkkI5GVB^YV&M&I<(h zG9ADdp#sauwq_&Ym%x1Ln7Fr*p`kez`Qlz>Z5g)viN=jpPmvdOE&YmSnl2V>a#GTz z%j%J%!c9LukE$Cd`qwit`->X<H8smeqTgs z@^OC$RqvposqEzs>zZ3x@7zddI4{?H;h`>@^me<6S4KC#j?AGa?yb6eoh`Fzzq?3#J#fo0 z(c2YH3o2UbhmIUEyWQ3A??D}2hzXLK3C>O^)I=;gc-YvA42A@@xu@Up%11w(dC2x| z)*((#y#l9`x5uxP1R;R$UUqiQ?QRB%2GeT2qH&g0wxynjf^)%-sj4Y4yawN`OS znp5;T*XXjf?2`?ATMgD9R(N{CW{@qxRh;;NmPmu2er16&ysr7{*XLr_iD`Nw>_w<_ za?w@3H|gI-YdwGt0Y~m(UY-MzPTsO{pu~oThNx*STfDzYs>!(+-KBTFaQdh~THN_U zKW1CqBEI3?ICT6ZLQ&OtNBUV^U5idf(e2xp4+nAQbUXo%h6Lu<@$vii@9#JI+&WHk z3?Uc(E=%JtuB8JYfns53;3tSa00ngs$8@0zV%tO5`#dV@m`(XqgQU?FzUHXT{P$VH z{|{}cHnW$8FB#jjr%&57m>;Sqx4gRo5Tr4=B^4FT_>Wu;)}t6RH82(9zQE2fH`SYI zRDx2Fii*n5Z%d^glY7p7yb}gJUB5mJ77R^HUf8}ORt^%VX2Gikd+6w}?QcPXDqr^)Gt*l#R6cx>TOShtGMRerJzL8ru zZ#FhRd&x3yJHfv;bXSLBsJ+zSgOw29rKyXGijQjsdnysKUR7OfZPz_v+o+(VYmuLS z-$Iw)r|PU1P4b)MgQrIaM;wrIc3As|HYdB8sTpv$l%%9l{3CJ&QG9O9yrUiI%fJvc zX$A%cKs|ZR%ORv!q-)!!n$OkFo7d#q^+xHPf1w!SURe0_X>YsTs4z6URnk(s zo-KAGqxQ>}?1F*==NrJ)9T@+$l}@R6^lK4xG6;>>Y8OmP#HI>&L3hWK%p#YTRDD5S zUZi1cOvy@rG-ZG6@tMST@2u*(oB?b>9J61z3Mv4EHsYWUtG@Y2@3=HUjhFsU6E+Nh z!TbUOMHXWr2PYc&H?K|gdEF88zsIV3)*n83+-|EhtS=`@NQy*PW=5-=y&PZDepb+lu(lU;zXlPRT zkR92Oki(kYqzH=b;g;=~j0mI?$mYo91P^^@2zQbFl9ZH$9mwE@!P&ECi*w3#1Qtit zd5Fg4Q@w7gp{NJL!op&u7_m|2n%N=ULf5(Q;loV`Hk@84{q&GP@DbiM^(aBMsaP$%v3w%%EWd&*SdK zEa@^szCFq6=qH>MC0#{LiR=E6@1*q0F^t;cvH8-uPX`Hvy#&HSWvPc=)OpWc2m5U2 zz~`IlupC9zKOZUX%ecyRW0-+R;Xjg`l;B}9)O4}y$YBIrf1 zZBGvyYAxvAT2l1XRRW6bCMD5h7#jY}on?$yeo=iCE*izEIY0kAbSHpZVkxu{>1Wj5qzIOYUZ5Hy0&M%he#T*J-_?rC7= zmTQcPxf9}HlgDPzA1R94%}b5~miHm#xva`cOP9=B==eK22x!lFS&J9_Gp}+%PJ-Eg zWkj6H&}fJvr`5yjJnAp;lS-Yv6U+#J3<+sY7hnH9%pd4aU|+m>*~KoVK$Fwwf@Jle zjTFYydwGG^c|H&XmlI?fUFZG5XK|1q=7bhtX3aUvqS(du{d;d2p&d+A9-(b3k!!9T!CB2u?BJ`datZi`-oj%f&Ly+1z!Rd zH~0|0Cr`#25=762P4|{Y1`Zq?k*ueu#i1!)9-fb#Ba=V8pwxk;fSrW% zs(pUUi-1Cdo|#WYSNE6mxIL6KfY_&Mu?-ekv}@dBYX2;+cIoY3HaRaeW(y64PQR0i zVoE;U!n`ptVwJ<%3WOe@p=gUJOGA}8+>gOHwqjouz=rV#U?xXKpz*_9D#*pP%??84 z%%NJB>6u&5dI3TxnogJdUfLlc!Oni@g8kSu9SNJEA9X||#LplA+T}R~W6M1llaZ|=D7gOcyVJVlDM3Mh*|=Yw znL1zrIjbRnFG&{01U$Ch*7SaI>6Q1T^!38o@7`U>bPUEayJRNkyWmt58TocS_{jA1 zG{yy;p+J3GTT-H@XiN(84m=?&yn~t=O_vNsp~I|(w)T(j-(y!_a|sGc8O@LPb1TDR zpsl4vS-j`KOo680{u1Lz2;E5%uG0e$q54NF-mx(~q0xi`WE@gxv=~Q@9KmtLeKD-n z<^>ASr<^7)(*lq*Q>Wm9gHzGV-yUot*CFS9CvTKvoI!tIKW-lA zJGay9YkbH(Ue7p*{>pByl` z-L-{HhCYsq>k#^^-kOxqAzIq==3iMWp%;b4DqJ}M8x~j(aq)TxuIc&itamwQ-tL6< z#cM;+t+ND@{_TpmfWVj1(#>qRo>`WY%q7F0K7M?ODx&}0%ZP{$d^Eixs)NT3Yg-ZJh^*E$DbgNjXW*6p```kybI44kluuS{jPabNZK9C>FTr|Z^meU0wh#3^YgdO z&2Jvvt8n$IxrN1|lZ&h&7qQBsY+Fp#HZAQ-r9-o!`FU{r2``m-;g~>>QHkzgZLQ)x zhg^6$+`6cViCI~YTWHwpxT&iWh~(0N1AqLw`ljsxu~D$CA3-O0l~$sj*R&8126k0+H@o`ptx(bfLRFbNYNd96@JV37QgBMnVWk*5X~b_t@)R7ntN z8OiGtl-Z!q9rNYFCIRXj(e`vDD?gwwoll(`8m7fw(QPI3P zwT*&JTHgLD`?%12jz6=1d$L{Hl(+ZP6a}OP=t#j>!>p4XVkD%saJk=ybo#zF^&d+G zd3gfS+3`=ww8zBhyqtYqyH)#O?Ex*+CzT)mVkeW(hY=ptqBLQcJ7|g9wk_F9QMwVL zEUWsbB?|pux9%`gtPCwq6o_3+_0@Lb>!nFGcEehfPJqQd*R1%jDFGS9{ztgWW$ z7E3~d$s4?HAA_N#5k%0%$&G=MhmP%i49;w6$+5%;NRW@W_m!O6ze3GO&s%Gmj_+bQ zdE?s4$)0Q7Q3mQb2+qH}ASd^$JwKso&rc6UT*Hpi1OC(LS?`RQx-zn|%F{+iMsX8n z2k%eSqJqAZJ_`kwOdh()M?Gzrk48dsJPu!8cf3NA*bZl3l`9!BH zAZYvuw@gfOM<;{bu50|_3yp4hYo-aI4JbtWbkpRBOG`|sp- ztgLL7h)_X{V}PF$h#q20V{;QbDI)$PO3q(c5D*?=#BkI1@1&oMf88d-8_KWv?4Kwt z=!1jzxT##$jFxct?%iAFYV#i6zLR!qL>CvJ8hucy*5=uk6)vMQ%ecbl#tK!E#@i*G zn79T)PT+lC8O~_V=?lDp=JI2bFbRU%8yI+oS9tR#xtAN5y)*$1Q-U%V=D96$b~iSb z*VN1cqyjTqaOV%qNom5OqC-KiqM{~7)940KJ)f|cP@rAt`ssh5Zi$(RlRP zVMj;(ibKwKHixmYKcGwN*|mG(#NfcdO~YHx`p=%!(9J#7)07+y7BcAnKOABxJHQamL6Or7v3_EKWEPM;#z zn1Tr}FZ7=cBXa<(Q)*L~fe#c5=UOPHmhxcV|n8wEF=B7(zt7 z*7vCfmIhR$rPJcHhafeH_6-$)iWM#RO+&-A-15PEd44Vtpbb-}^X(2!&*j;V1hSSj zCVvHbbf{P7P~UToNaaaT#^RRGd#+ioSF%uxns+=44_`*b%Y3zAhVLu|tv7-Eo3=pN zwWB}id{a_WX$AUNB(J-w(yr(ARk-V67jJoe$EZX{n~S{s(>^Aq_jkPRC#Pk@YKR9K zg`eIDEg-UE$Rreo?34!I#|kVj5*X6CmA8FuEqcgk>&v#s0TA@=gj zjGScj!0hxEQb0jON?1}-VWdTIku$t&`$xy*B=yhhgmcOnvRwu{J#~?I^+0jxnZ$(m zzke!)L*cT8nLNO$2r4{jX*MOr6qD;Hptf#>{A|X7TzYCzBCwu&(SD4xnsI!`VxgV# zt4nXh0@YQut}nibiHU*WaP0g;d1;ChPR!+;7o-PW7Xx$tsFGAJnwgPQU=09rzBO_- z+pwClXNpcPke2r8!VBE0y<6cl&qK~N>1*!n(AF*F_@O!CVizoA=G4^Hpyz-gT{+GN zl`XT>o3ymhpztHlFF+LzTWG3ZDyuf<6&>v0sNEo*pRzxtq53V<{Y(snrP_H-FHSiP z)u*umA&cL14zaNzRLG7i$f5ryzZ>h){I4T7uB)F=C#gUbtSlZG5WsrX53LPF49z!| zse}tF2R<3Q`fLcQpZ)wU70SAy03r~jX;=)Mcez51;Bvf;NuaK_HU+Yqkk^OV1d1#t zqe|Sjoe&XmbadFz+q&7a9E1&l@5X!2$Ww41l6yf+MB1^h!zn4!JMcBe#fhNfEuy}^ z`lG6f;NNd%^ad6E!a~H0W6pW#gZs|87C6#B%H(4sVQNv}=bRnFPAzq3-l&bnN-^vv zw?5srMv@4H~6+`3D!PhYbG2lkF_9D<@3 zKYZAl&b^7j*A|}17sm~=hMEZ5Ug8L7I|Fjb8KJlWvq$KLo zjY6lzQFOmhQ5(A;&E(SM;@Vb00Rh9%(6Q0%wPS#sfLfCL)oTviWPj8%dnoI-#O6Iz z-$u{r0Bpq(FUF=VFTWvUZ2oRqUnwdibTy;=)>=WX-9*>wBIiGGRV#FBPdtyjZWHWP zip#dL@`1=^Prv2~F$GHhgJF=|pIT(_dv z>cZ}e&&=hw$hw%>+?eyC!5Er~^=$LbM}$(*p8G2cJ`fLbD@S$Yn*D*Tru`8U2tig7 zGAQ2x)(CIk)=Lt9URVeRxUO8F1ZbkzPXfsrXOdtiDFZ4wIk&TQvpa3hc_9l245)g|D|=vCQT zmisdUZ{Q%}3L3GSa5{HxYthL_ut_kkpnwCm6&xH45Sv_@lRJTx1V{?vC(7nGv9Y!N z(;LdQzsQ$_gk&?MnD^h|65`!}YL6c|a+HUno=8Qp;goRUdCbJEOQc>?y6`wK=;2`oGn_M*!Xtez_9&fm$QI>d*-=IoV16038UTJY`A@dgs2keh!j3N zC$75;eK9dL6+5*{h63dlh7>Mk)xQ8Wh*Ocl*CXh&Z*$bCYsSW6=EEw?{&p+nJ{1gf z*QT36SU@V%nrkLn#B@X4#MqRTbi1PfS9yXXDvFR)T}M!8fHK^# z@UZ(cpI$>#>s>EbsrC#yZi7~H5tz~#7@5WIDW193gN1X;{2n^9CbO0U2M_AVvV~Jp z-^aFfRbBm)VI~kItSd^l1xTlm>Vftvruy&Lak5NS{lwl*zCX=F-*oiPg;+i4xs!aF8|1^Q{xo`V!Rme$FVYgMd)19Y4o-KpO; zI9NQ~1Xy;ZrRe5!0q(>tjjAsqBBC%-S0`t96mmHm8+oXGH8es(;tgv)@$C7W_udT6 zVpoC7Wk@|Ww38BFwPq&NiPHR`(rgj8o5WZuM1pP5UXD5ykZ?kZjwz-Q61G2V7llsi zcJ>7ZT7HScDZqTfbf7J>D4vT88!Xu3BKwh zR*Y^HH=KDTN6jF%VSrhGRGgC10d2sFB+aJdc(Ic<<l>Eyp>G1+?{WQ<2OW<1E-jEPfOml8{*WW)L)C*okrzvslh*YnO*vSS;(#|6w_L zjqHn2qj{V~Fds1yBjxaX0ClDP{Xck5JVfIJcgFJk1nuLBFyQkyZ$69eK6xzc`IEZP zS2OHc3AU8kX)RG{{Kaoi|N;@xu}pY--6 zTT#nS6 zlc6F`$cjF?*50rqIVl;Nl8@!M*^L_+Gime-1^qMj6rR?9DY3{N1U!5yr)%-#CC!D$ z2PDng=YNS5I%=wGkR+UiZN_Dk4LG6&_ZEAQ+o{MXi3*#Kx~?fM=hX?AH~a{%!eUb~}7KOlq>bve!x9!6TQZ5sf{qc5m`i{A7 z&za;{`)0>Dqy2fv*{5I0k$qfe0Z7Ows4Mcd1qPBgNlA|$KO#mC#crNjb`#|I8^_R^ z)tMzD+Z-S#BdxZk4vm<^ZC|Z`wA8j|4IwX8!n#kUkNEj`%P2{w*4H_#=$DlFjc~J) z&YMmzdb1MPFO+j%An`nlx9A~jzu0k-mTc<&B@IK*>}--{Y%h`rBPQ%qcDBW)HlMua+kVV;?S}+@srf z)}H#oy8hf<+Z^*Q^2)z24MbSWltgW}?G$Xh!At6W7L=6Lf!}Yeg|_e6?afLd6W}dF zF3m1OP@1Kf-a*_X}#ww-&Oi-NDa70Lv3;p?_P*xjTBZ$93_0 zeM0L$F@!5*hSEiQbo1J_lqB!z8(aQtVrqg>Bwvkhh&?_R)3eTj>+8XqsD|PzMukU> zH<>J40xVYwz3CNzmNb`C3e|`qC9@l`W zh;l<30#S|kcXG9lX9XASWS3{5qlvj`(nGqtPopjG@Ce6_C09ztx9zK9Fyo;0uS`x# zdF;FTacFj@$Gv_3z7*NYr142^ReKwD526!&SL~%Xg-dgFUustf^waUF6WyJ*R37Z- z62`{%-xCsYbNlC{!P6I_*`1=xLuknDl)+w^QCXgoB~cga>!dYU&dBY{?Ets;e(6%C z^S1xKRrj2}PonqpAReco^7v{W+!O0V@_of0>i_#E>#6H1GUv)8%G0>G`=&J1Z+&u2 zJ-X(*yyM?LnVMW$XH<>3l(->@eQErkt4c=p(Ums5ZcR$grdMoci1XFP6Xeb*%cK&o Gx&0sM-Ks?Z literal 0 HcmV?d00001 diff --git a/rviz_carla_plugin/CMakeLists.txt b/rviz_carla_plugin/CMakeLists.txt new file mode 100644 index 00000000..ba6c616d --- /dev/null +++ b/rviz_carla_plugin/CMakeLists.txt @@ -0,0 +1,48 @@ +cmake_minimum_required(VERSION 2.8.3) +project(rviz_carla_plugin) + +set(CXX_STANDARD_REQUIRED ON) +set(CMAKE_CXX_STANDARD 14) + +find_package(catkin REQUIRED COMPONENTS + rviz + carla_msgs + nav_msgs + carla_ros_scenario_runner_types +) +catkin_package() + +include_directories(${catkin_INCLUDE_DIRS}) +link_directories(${catkin_LIBRARY_DIRS}) + +set(CMAKE_AUTOMOC ON) + +message(STATUS "Using Qt5 based on the rviz_QT_VERSION: ${rviz_QT_VERSION}") +find_package(Qt5 ${rviz_QT_VERSION} EXACT REQUIRED Core Widgets) +set(QT_LIBRARIES Qt5::Widgets) + +set(SRC_FILES + src/drive_widget.cpp + src/indicator_widget.cpp + src/carla_control_panel.cpp +) + +qt5_add_resources(SRC_FILES rviz_carla_plugin.qrc) + +add_library(${PROJECT_NAME} ${SRC_FILES}) + +target_link_libraries(${PROJECT_NAME} ${QT_LIBRARIES} ${catkin_LIBRARIES}) + +install(TARGETS + ${PROJECT_NAME} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +install(FILES + plugin_description.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) + +install(DIRECTORY icons/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/icons) diff --git a/rviz_carla_plugin/README.md b/rviz_carla_plugin/README.md new file mode 100644 index 00000000..c1db4887 --- /dev/null +++ b/rviz_carla_plugin/README.md @@ -0,0 +1,64 @@ +# RVIZ CARLA Control + +A [RVIZ](http://wiki.ros.org/rviz) plugin to visualize/control CARLA. + +![CARLA AD Demo](../docs/images/rviz_carla_plugin.png "rviz carla plugin") + +This plugin is expecting a ego vehicle named `ego_vehicle`. + +## Features + +### Provide the RVIZ view pose to other nodes + +In combination with [carla_spectator_camera](../carla_spectator_camera), this allows visually moving around in the CARLA world. + +Currently, it is limited to a camera attached to the ego-vehicle. Please set the target frame of the "Current View" to `ego_vehicle`. + +### Visualize the current ego vehicle state + +The current vehicle state is visualized: + +- Vehicle Control +- Position + +### Allows manually overriding the ego vehicle vehicle control + +By using the drive-widget from the [RVIZ Visualization Tutorials](https://github.com/ros-visualization/visualization_tutorials) and a [node to convert from twist to vehicle control](../carla_twist_to_control) it is possible to steer the ego vehicle by mouse. + +### Execute a scenario + +By using [carla_ros_scenario_runner](../carla_ros_scenario_runner), it is possible to trigger scenarios from within RVIZ. + + +### Play/Pause the simulation (if started in synchronous mode) + +Similar to the [rqt CARLA plugin](../rqt_carla_plugin), it's possible to control the CARLA world, if synchronous mode is active. + + + +## Topics + +### Subscriptions + +| Topic | Type | Description | +| ------------------- | ------------------------- | ------------------------------------------------------ | +| `/carla/status` | [carla_msgs.CarlaStatus](../carla_msgs/msg/CarlaStatus.msg) | Read the status of CARLA, to enable/disable the UI | +| `/carla/ego_vehicle/vehicle_status` | [carla_msgs.CarlaEgoVehicleStatus](../carla_msgs/msg/CarlaEgoVehicleStatus.msg) | To display the current state of the ego vehicle | +| `/carla/ego_vehicle/odometry` | [nav_msgs.Odometry](http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html) | To display the current pose of the ego vehicle | +| `/scenario_runner/status` | [carla_ros_scenario_runner_types.CarlaScenarioRunnerStatus](../carla_ros_scenario_runner_types/msg/CarlaScenarioRunnerStatus.msg) | To visualize the scenario runner status | +| `/carla/available_scenarios` | [carla_ros_scenario_runner_types.CarlaScenarioList](../carla_ros_scenario_runner_types/msg/CarlaScenarioList.msg) | For providing a list of scenarios to execute (disabled in combo box) | + +### Publications + +| Topic | Type | Description | +| ------------------- | ------------------------- | ------------------------------------------------------ | +| `/carla/control` | [carla_msgs.CarlaControl](../carla_msgs/msg/CarlaControl.msg) | Start/pause CARLA | +| `/carla/ego_vehicle/spectator_pose` | [geometry_msgs.PoseStamped](http://docs.ros.org/api/geometry_msgs/html/msg/PoseStamped.html) | Publish the current pose of the RVIZ camera view. | +| `/carla/ego_vehicle/vehicle_control_manual_override` | [std_msgs.Bool](http://docs.ros.org/api/std_msgs/html/msg/Bool.html) | To enable/disable the overriding of the vehicle control | +| `/carla/ego_vehicle/twist` | [geometry_msgs.Twist](http://docs.ros.org/api/geometry_msgs/html/msg/Twist.html) | The twist command, created via mouse | + +### Service Client + +| Service | Type | Description | +| ----------------------------------------------------------- | ---- | ------------------------------------------------------------------- | +| `/scenario_runner/execute_scenario` | [carla_ros_scenario_runner_types.ExecuteScenario](../carla_ros_scenario_runner_types/srv/ExecuteScenario.srv) | Execute the selected scenario | diff --git a/rviz_carla_plugin/icons/classes/CarlaControl.png b/rviz_carla_plugin/icons/classes/CarlaControl.png new file mode 100644 index 0000000000000000000000000000000000000000..4b659fafc804ec2c606f37140d210abf73a38ce3 GIT binary patch literal 16301 zcmeI3dsGuw9>)g?h*1<@+v=_o#n+ry3|M4H;cj%74;m{;wgvKBWm4h?OH5UPQ?fHRa9CZ>`VeATwo4+w)@YX$$=!l z`@7%Y@7~Y--8=W6tWHjv9mJZ%f*>d;K2D<}KiSlOU;z2Qs;d7syvn`=vc;oGHJcDE&XYDr1p zjyp|X{9r#*{!Pw)q!bCxzG{{K^GTuXdHu)~=*!_pu2^eEK{tQDw)0Hebl;Zzuc~GS zy=o}@Yj{v%(T~>BRqSw8*R1`M>fhj(tf+`-^4TZHuBjBz-o^J}RoK~=L7`#Seu^oC zOqZS%@^3++v+w!ybBMqDERC1zGEb#&4{S!`Yq$FSMKJ}HPcqu0M~&O`$BNy%dF#7| z)#*=vW0l)0m!>bj_d-N&jc9a9zWkm$x(K=pkq(j-{p%Y1%}&0k`lFBd$kzPK%A?4MB=%rwuV= zqXb)zW@6ST&V$;|Ic&@r#aSTH^0hWKnuWy`*wK`Nq*Oyewn1j(L@QYer<@F6K?#KI zw3w|9xigC6iYq6-Q_V1k?dn2gM{#1PgzPkJGFy$?QMQC9Wm9nxJ)T2EaX3_>-dFd$EVkZ6 zR!28Gk|OLxY_NdGhX)a9we&KJWk98ah|MKO(mk^Q6FO4!Z78fm9e9r2fX3#cR$|&f zgRu2%n1RFfx(A(w(a@{3<=D+Gz(xa%no$dx(?RM41I~fKOrFK*GX=^sXgbu14I-mF zZkekT+$*FY>rbw>qX>c9Q*qp^bXS?@m>^FHvZ^FJ2|IKFW;Nn@jxYrbiaaasiHB+s z0#%aQNG@N*6^c>?VyYrVlIeVboX__P;_eB=(2~_}Lo}PVU zXtnZqtAjwS1~guyB5WTXj^N%Rq7Az$d4 zWM6r|&>Gy3LsbG9+P(FSxPc7cTUc^agiMCYq!C;pD${cX0yL5vo2{C*1q2^*Flc8cgA2mw(Ttuc9b0bA!AvZEYD&1!x@l@*D%z$8MkY3BdQd6%RJ4VVR)&?D|fQ{ z#@)S@b+c!&L&@7#B>7DB%+afxR~Vx~Zo=&rgivA@Bol>g)=UNLY4qwz-4EpCF-;yB zi0gP1DByl=VE;7gxHadv`bY4o7c8LOyQSW4P?}CJ^>%|&k8++BBb4NG%r#J;*-J%T zV&pE&Ddc?{RZ1likwgK5&7dL~bE4)n4Msj_9n=FuL}qenK*xZ>^udH)j&7m5u)J=@ zuKnX~CGXwjl^^cC^Y`0Yy^pD1^NVLjzh+b*7Lx=3LT@s-==lI%1{VN?-ehpm^8vgJ zE&vF<$>5^r19%x+01$eU!9~vp@G`gnAoM1Ki=GeQWpDvN=uHL}Js-f!-~xcqn+z^` zK7g0O1puKp8C>*y055|J077pvxaj!+UIrHcgx+Lu(enYk3@!i&y~*IB=L2{dTmTSy zlfgyL2k?d;l+l z3jjiIGPvmZ0A2j32326`{-vU9eOTzG}>vu`h!@Nk|^OVw+^{SwYB~b1%O? zri6n;<$qGl2^f8I(bQ0gh*Wj5+UOBVw(8nEX;-YQ!&o`%} zefQvF->~+^5{0k$16AOrnrFuY7GLo@!D{r0AGvw#>g_(e>(r{1^B*>z@}0A7{F*a5 zPIYb2j8{RS231h!4+}0l|8%~iCZT#pQ*mO=%u(VOuU5th=kiUg6Kxk*4|g8SNbt+O zq&qWPU7k4pw6?s-|Kjo^-y6QwmmN?A)FO4Gb>*v5lWLleHGFueG_d{jv2C$Qo2P`I z+kQCs?XbH04F&n?@JC0Z=HIWqSasm*(fG0C@JI#xq5Ea*o*2rE9xX`h+ zj8_(B`sI3JbJ?9KqRHZ~=84`j?2EY2QT<%pR$Ceo@-WITeJPUm&W{;SzfF0hH$IXF zorHd2?Kpm@w0K?P!6!Z=l0GWk^K@BD{??YRB@+WG)UhFDu}_CPStmPwcX?R5|HaN7 zA#1i}PIzPZYgc#vyy3yg%A>2kycfNH*1F2J5uGBa!|&Fv8wbt9sGoz!$0lj2W-TfH EHzLJYB>(^b literal 0 HcmV?d00001 diff --git a/rviz_carla_plugin/icons/pause.png b/rviz_carla_plugin/icons/pause.png new file mode 100644 index 0000000000000000000000000000000000000000..f486019f22b91346854cbc49625332b85fac67ae GIT binary patch literal 184 zcmeAS@N?(olHy`uVBq!ia0vp^1|ZDA1|-9oezpTCwj^(N7l!{JxM1({$v_d#0*}aI z1_o|n5N2eUHAey{7~$#S7?N@C?M*{22Spwi$MAoD*YEkyp>&Jm^DhzRMiI~3AB&1@ zE%)9l%|H-~Y6L@>aEsE;o|Zm@XC{!xW5`iH)|4@ixttDnm{r-UW| DRkbrt literal 0 HcmV?d00001 diff --git a/rviz_carla_plugin/icons/play.png b/rviz_carla_plugin/icons/play.png new file mode 100644 index 0000000000000000000000000000000000000000..070787758f0cf7a3bec112727393c2087c5f5e6f GIT binary patch literal 433 zcmV;i0Z#sjP)}CV><-!_5Cb5C4N#&hQTR{`=oB zvQ6Y#A$V1Q3Qz$mKrjGFmy)(3E6@WTBn>2~G=Q4k#F7>tm;lGNZ=#-o4d7bRSkhYL zLwpFlOX^3n&|h^A?Av~e8l$_wtE6F61s3aRrp9B`i)?!qxuaB(n_2-x_DVmfC+G9`!?D#Hw8w(X4k{#P$29F%@1&9 zdne`asT61(jinUmEE-EF&}lU01V|E%IV|)63{pj7Y6Y%p0l5h*jSS1c00000NkvXXu0mjfO%d=32RJ_7H0;1s^Xb=^VNI?-%P|~M8i6|KwBcX^L->tm|yRs!W zv-WzvJA3w@vCNDvw-0o@6@UUz06N}2=6aE&0k9410|&q!Fb~EHZ z%`B+{Bj6aYCHpZjN?t#~@nJ*9UjrGg6abh2^9;^E_c<_G2>@`I(eeNLVXFWwJKqRm z*=-YB{5LQIzJ>_27Wz2YW?@Y1J(H{e;lRfB{CA*Q;9XT18#@!joB&?5xdWyR&eAl@ zt&L7$oFxH-IPW<>P6);02!!PT@P7TNb6&my*T6r|iSSRf0{{%XJ@3q0&WXsGNCB8Q z(WY|d{Q^#aodp3ZFFJX1V`6T<#(rjIkB+|Dc_H!^(PNL2&VZxba{8dge$j$5K5Zi( z*sHPMwgB+6k&O4sDw5{F`YVqrGyAh(p70#Z6&vGhF}0r1B<3V)Iybh39%}5HUCD`W zYV5mR0l2KOf648Lq?sg>bS~+$q%BDslC~P>#0ej=rKExLA^QP*dKXe60^muB!OF#4 z16l1#>MqOaQRfqyl2Y~}sqaNur5A;*UX&JlQQUn`<#pw{Cw{974wZ}U0#E=7KmkZ; YPkJ<9GN)sk?*IS*07*qoM6N<$f_wk|#Q*>R literal 0 HcmV?d00001 diff --git a/rviz_carla_plugin/package.xml b/rviz_carla_plugin/package.xml new file mode 100644 index 00000000..c1a0d791 --- /dev/null +++ b/rviz_carla_plugin/package.xml @@ -0,0 +1,26 @@ + + + rviz_carla_plugin + 0.0.1 + The carla_ros_bridge package + CARLA Simulator Team + MIT + catkin + qtbase5-dev + rviz + carla_msgs + nav_msgs + geometry_msgs + carla_ros_scenario_runner_types + carla_msgs + nav_msgs + geometry_msgs + carla_ros_scenario_runner_types + libqt5-core + libqt5-gui + libqt5-widgets + rviz + + + + diff --git a/rviz_carla_plugin/plugin_description.xml b/rviz_carla_plugin/plugin_description.xml new file mode 100644 index 00000000..42f236a3 --- /dev/null +++ b/rviz_carla_plugin/plugin_description.xml @@ -0,0 +1,9 @@ + + + + A panel widget for controlling carla nodes + + + diff --git a/rviz_carla_plugin/rviz_carla_plugin.qrc b/rviz_carla_plugin/rviz_carla_plugin.qrc new file mode 100644 index 00000000..1ebe3370 --- /dev/null +++ b/rviz_carla_plugin/rviz_carla_plugin.qrc @@ -0,0 +1,7 @@ + + + icons/play.png + icons/pause.png + icons/step_once.png + + \ No newline at end of file diff --git a/rviz_carla_plugin/src/carla_control_panel.cpp b/rviz_carla_plugin/src/carla_control_panel.cpp new file mode 100644 index 00000000..ce436946 --- /dev/null +++ b/rviz_carla_plugin/src/carla_control_panel.cpp @@ -0,0 +1,411 @@ +/* + * Copyright (c) 2020 Intel Corporation + * + * This work is licensed under the terms of the MIT license. + * For a copy, see . + */ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include "carla_control_panel.h" +#include "drive_widget.h" +#include "indicator_widget.h" + +namespace rviz_carla_plugin { + +CarlaControlPanel::CarlaControlPanel(QWidget *parent) + : rviz::Panel(parent) +{ + QVBoxLayout *layout = new QVBoxLayout; + QHBoxLayout *vehicleLayout = new QHBoxLayout; + + QFormLayout *egoCtrlStatusLayout = new QFormLayout; + + mThrottleBar = new QProgressBar(); + mThrottleBar->setRange(0, 100); + egoCtrlStatusLayout->addRow("Throttle", mThrottleBar); + mBrakeBar = new QProgressBar(); + mBrakeBar->setRange(0, 100); + egoCtrlStatusLayout->addRow("Brake", mBrakeBar); + mSteerBar = new QProgressBar(); + mSteerBar->setRange(-100, 100); + egoCtrlStatusLayout->addRow("Steer", mSteerBar); + vehicleLayout->addLayout(egoCtrlStatusLayout); + + QFormLayout *egoStatusLayout = new QFormLayout; + mPosLabel = new QLineEdit(); + mPosLabel->setDisabled(true); + egoStatusLayout->addRow("Position", mPosLabel); + + mSpeedLabel = new QLineEdit(); + mSpeedLabel->setDisabled(true); + egoStatusLayout->addRow("Speed", mSpeedLabel); + + mHeadingLabel = new QLineEdit(); + mHeadingLabel->setDisabled(true); + egoStatusLayout->addRow("Heading", mHeadingLabel); + + vehicleLayout->addLayout(egoStatusLayout); + + QVBoxLayout *egoCtrlLayout = new QVBoxLayout; + mOverrideVehicleControl = new QCheckBox("Manual control"); + mOverrideVehicleControl->setDisabled(true); + egoCtrlLayout->addWidget(mOverrideVehicleControl); + mDriveWidget = new DriveWidget; + mDriveWidget->setDisabled(true); + egoCtrlLayout->addWidget(mDriveWidget); + connect(mOverrideVehicleControl, SIGNAL(stateChanged(int)), this, SLOT(overrideVehicleControl(int))); + + vehicleLayout->addLayout(egoCtrlLayout); + + layout->addLayout(vehicleLayout); + + QFormLayout *carlaLayout = new QFormLayout; + + // row1 + QHBoxLayout *carlaRow1Layout = new QHBoxLayout; + + mScenarioSelection = new QComboBox(); + carlaRow1Layout->addWidget(mScenarioSelection, 10); + + mTriggerScenarioButton = new QPushButton("Execute"); + carlaRow1Layout->addWidget(mTriggerScenarioButton); + + mIndicatorWidget = new IndicatorWidget(); + carlaRow1Layout->addWidget(mIndicatorWidget); + connect(mTriggerScenarioButton, SIGNAL(released()), this, SLOT(executeScenario())); + + carlaLayout->addRow("Scenario Execution", carlaRow1Layout); + + QHBoxLayout *synchronous_layout = new QHBoxLayout; + QPixmap pixmap(":/icons/play.png"); + QIcon iconPlay(pixmap); + mPlayPauseButton = new QPushButton(iconPlay, ""); + synchronous_layout->addWidget(mPlayPauseButton); + connect(mPlayPauseButton, SIGNAL(released()), this, SLOT(carlaTogglePlayPause())); + + QPixmap pixmapStepOnce(":/icons/step_once.png"); + QIcon iconStepOnce(pixmapStepOnce); + mStepOnceButton = new QPushButton(iconStepOnce, ""); + connect(mStepOnceButton, SIGNAL(released()), this, SLOT(carlaStepOnce())); + + synchronous_layout->addWidget(mStepOnceButton); + carlaLayout->addRow("Carla Control", synchronous_layout); + + layout->addLayout(carlaLayout); + + setLayout(layout); + + QTimer *outputTimer = new QTimer(this); + connect(outputTimer, SIGNAL(timeout()), this, SLOT(sendVel())); + outputTimer->start(100); + + connect(mDriveWidget, SIGNAL(outputVelocity(float, float)), this, SLOT(setVel(float, float))); + mDriveWidget->setEnabled(false); + + setSimulationButtonStatus(false); + setScenarioRunnerStatus(false); + + mCarlaStatusSubscriber = mNodeHandle.subscribe("/carla/status", 1000, &CarlaControlPanel::carlaStatusChanged, this); + mCarlaControlPublisher = mNodeHandle.advertise("/carla/control", 10); + mEgoVehicleStatusSubscriber = mNodeHandle.subscribe( + "/carla/ego_vehicle/vehicle_status", 1000, &CarlaControlPanel::egoVehicleStatusChanged, this); + mEgoVehicleOdometrySubscriber + = mNodeHandle.subscribe("/carla/ego_vehicle/odometry", 1000, &CarlaControlPanel::egoVehicleOdometryChanged, this); + + mCameraPosePublisher + = mNodeHandle.advertise("carla/ego_vehicle/spectator_pose", 10, true); + + mEgoVehicleControlManualOverridePublisher + = mNodeHandle.advertise("/carla/ego_vehicle/vehicle_control_manual_override", 1, true); + + mExecuteScenarioClient + = mNodeHandle.serviceClient("/scenario_runner/execute_scenario"); + mScenarioRunnerStatusSubscriber + = mNodeHandle.subscribe("/scenario_runner/status", 10, &CarlaControlPanel::scenarioRunnerStatusChanged, this); + + mTwistPublisher = mNodeHandle.advertise("/carla/ego_vehicle/twist", 1); + + mScenarioSubscriber + = mNodeHandle.subscribe("/carla/available_scenarios", 1, &CarlaControlPanel::carlaScenariosChanged, this); + + // //initially set the camera + QTimer::singleShot(1000, this, SLOT(updateCameraPos())); +} + +void CarlaControlPanel::cameraPreRenderScene(Ogre::Camera *cam) +{ + double epsilon = 0.001; + if ((std::fabs(cam->getPosition().x - mCameraCurrentPosition.x) > epsilon) + || (std::fabs(cam->getPosition().y - mCameraCurrentPosition.y) > epsilon) + || (std::fabs(cam->getPosition().z - mCameraCurrentPosition.z) > epsilon) + || (std::fabs(cam->getOrientation().x - mCameraCurrentOrientation.x) > epsilon) + || (std::fabs(cam->getOrientation().y - mCameraCurrentOrientation.y) > epsilon) + || (std::fabs(cam->getOrientation().z - mCameraCurrentOrientation.z) > epsilon) + || (std::fabs(cam->getOrientation().w - mCameraCurrentOrientation.w) > epsilon)) + { + mCameraCurrentPosition = cam->getPosition(); + mCameraCurrentOrientation = cam->getOrientation(); + QTimer::singleShot(0, this, SLOT(updateCameraPos())); + } +} + +void CarlaControlPanel::updateCameraPos() +{ + auto frame = mViewController->subProp("Target Frame")->getValue(); + + geometry_msgs::PoseStamped pose; + pose.header.frame_id = frame.toString().toStdString(); + pose.header.stamp = ros::Time::now(); + pose.pose.position.x = mCameraCurrentPosition.x; + pose.pose.position.y = mCameraCurrentPosition.y; + pose.pose.position.z = mCameraCurrentPosition.z; + pose.pose.orientation.x = mCameraCurrentOrientation.x; + pose.pose.orientation.y = mCameraCurrentOrientation.y; + pose.pose.orientation.z = mCameraCurrentOrientation.z; + pose.pose.orientation.w = mCameraCurrentOrientation.w; + + mCameraPosePublisher.publish(pose); +} + +void CarlaControlPanel::onInitialize() +{ + currentViewControllerChanged(); + connect(vis_manager_->getViewManager(), SIGNAL(currentChanged()), this, SLOT(currentViewControllerChanged())); +} + +void CarlaControlPanel::currentViewControllerChanged() +{ + mViewController + = dynamic_cast(vis_manager_->getViewManager()->getCurrent()); + if (!mViewController) + { + ROS_ERROR("Invalid view controller!"); + return; + } + + auto camera = mViewController->getCamera(); + camera->addListener(this); +} + +void CarlaControlPanel::executeScenario() +{ + for (auto const &scenario : mCarlaScenarios->scenarios) + { + if (QString::fromStdString(scenario.name) == mScenarioSelection->currentText()) + { + carla_ros_scenario_runner_types::ExecuteScenario srv; + srv.request.scenario = scenario; + if (!mExecuteScenarioClient.call(srv)) + { + ROS_ERROR("Failed to call service executeScenario"); + mIndicatorWidget->setState(IndicatorWidget::State::Error); + } + break; + } + } +} + +void CarlaControlPanel::overrideVehicleControl(int state) +{ + std_msgs::Bool boolMsg; + if (state == Qt::Checked) + { + boolMsg.data = true; + mDriveWidget->setEnabled(true); + } + else + { + boolMsg.data = false; + mDriveWidget->setEnabled(false); + } + mEgoVehicleControlManualOverridePublisher.publish(boolMsg); +} + +void CarlaControlPanel::scenarioRunnerStatusChanged( + const carla_ros_scenario_runner_types::CarlaScenarioRunnerStatus::ConstPtr &msg) +{ + if (msg->status == carla_ros_scenario_runner_types::CarlaScenarioRunnerStatus::STOPPED) + { + mIndicatorWidget->setState(IndicatorWidget::State::Stopped); + } + else if (msg->status == carla_ros_scenario_runner_types::CarlaScenarioRunnerStatus::STARTING) + { + mIndicatorWidget->setState(IndicatorWidget::State::Starting); + } + else if (msg->status == carla_ros_scenario_runner_types::CarlaScenarioRunnerStatus::RUNNING) + { + mIndicatorWidget->setState(IndicatorWidget::State::Running); + } + else if (msg->status == carla_ros_scenario_runner_types::CarlaScenarioRunnerStatus::SHUTTINGDOWN) + { + mIndicatorWidget->setState(IndicatorWidget::State::ShuttingDown); + } + else + { + mIndicatorWidget->setState(IndicatorWidget::State::Error); + } +} + +void CarlaControlPanel::setScenarioRunnerStatus(bool active) +{ + mScenarioSelection->setEnabled(active); + mTriggerScenarioButton->setEnabled(active); + mIndicatorWidget->setEnabled(active); +} + +void CarlaControlPanel::carlaScenariosChanged(const carla_ros_scenario_runner_types::CarlaScenarioList::ConstPtr &msg) +{ + auto currentSelection = mScenarioSelection->currentText(); + mCarlaScenarios = msg; + mScenarioSelection->clear(); + int idx = 0; + for (auto const &scenario : msg->scenarios) + { + auto name = QString::fromStdString(scenario.name); + mScenarioSelection->addItem(name); + if (name == currentSelection) + { // switch to previously selected item + mScenarioSelection->setCurrentIndex(idx); + } + ++idx; + } + setScenarioRunnerStatus(mScenarioSelection->count() > 0); +} + +void CarlaControlPanel::egoVehicleStatusChanged(const carla_msgs::CarlaEgoVehicleStatus::ConstPtr &msg) +{ + mOverrideVehicleControl->setEnabled(true); + mSteerBar->setValue(msg->control.steer * 100); + mThrottleBar->setValue(msg->control.throttle * 100); + mBrakeBar->setValue(msg->control.brake * 100); + + std::stringstream speedStream; + speedStream << std::fixed << std::setprecision(2) << msg->velocity * 3.6; + mSpeedLabel->setText(speedStream.str().c_str()); +} + +void CarlaControlPanel::egoVehicleOdometryChanged(const nav_msgs::Odometry::ConstPtr &msg) +{ + std::stringstream posStream; + posStream << std::fixed << std::setprecision(2) << msg->pose.pose.position.x << ", " << msg->pose.pose.position.y; + mPosLabel->setText(posStream.str().c_str()); + + std::stringstream headingStream; + headingStream << std::fixed << std::setprecision(2) << tf::getYaw(msg->pose.pose.orientation); + mHeadingLabel->setText(headingStream.str().c_str()); +} + +void CarlaControlPanel::setSimulationButtonStatus(bool active) +{ + if (active) + { + mPlayPauseButton->setDisabled(false); + mPlayPauseButton->setToolTip("Play/Pause the CARLA world."); + mStepOnceButton->setDisabled(false); + mStepOnceButton->setToolTip("Execute on tick within the CARLA world."); + } + else + { + mPlayPauseButton->setDisabled(true); + mPlayPauseButton->setToolTip("Disabled due to CARLA running in non-synchronous mode."); + mStepOnceButton->setDisabled(true); + mStepOnceButton->setToolTip("Disabled due to CARLA running in non-synchronous mode."); + } +} + +void CarlaControlPanel::carlaStatusChanged(const carla_msgs::CarlaStatus::ConstPtr &msg) +{ + mCarlaStatus = msg; + setSimulationButtonStatus(mCarlaStatus->synchronous_mode); + + if (mCarlaStatus->synchronous_mode) + { + if (mCarlaStatus->synchronous_mode_running) + { + QPixmap pixmap(":/icons/pause.png"); + QIcon iconPause(pixmap); + mPlayPauseButton->setIcon(iconPause); + } + else + { + QPixmap pixmap(":/icons/play.png"); + QIcon iconPlay(pixmap); + mPlayPauseButton->setIcon(iconPlay); + } + } +} + +void CarlaControlPanel::carlaStepOnce() +{ + carla_msgs::CarlaControl ctrl; + ctrl.command = carla_msgs::CarlaControl::STEP_ONCE; + mCarlaControlPublisher.publish(ctrl); +} + +void CarlaControlPanel::carlaTogglePlayPause() +{ + if (mCarlaStatus) + { + carla_msgs::CarlaControl ctrl; + if (mCarlaStatus->synchronous_mode_running) + { + ctrl.command = carla_msgs::CarlaControl::PAUSE; + } + else + { + ctrl.command = carla_msgs::CarlaControl::PLAY; + } + mCarlaControlPublisher.publish(ctrl); + } +} + +void CarlaControlPanel::setVel(float linearVelocity, float angularVelocity) +{ + mLinearVelocity = linearVelocity; + mAngularVelocity = angularVelocity; +} + +void CarlaControlPanel::sendVel() +{ + if (ros::ok() && mTwistPublisher && (mOverrideVehicleControl->checkState() == Qt::Checked)) + { + geometry_msgs::Twist msg; + msg.linear.x = mLinearVelocity; + msg.linear.y = 0; + msg.linear.z = 0; + msg.angular.x = 0; + msg.angular.y = 0; + msg.angular.z = mAngularVelocity; + mTwistPublisher.publish(msg); + } +} + +} // end namespace rviz_carla_plugin + +#include +PLUGINLIB_EXPORT_CLASS(rviz_carla_plugin::CarlaControlPanel, rviz::Panel) diff --git a/rviz_carla_plugin/src/carla_control_panel.h b/rviz_carla_plugin/src/carla_control_panel.h new file mode 100644 index 00000000..646b96dd --- /dev/null +++ b/rviz_carla_plugin/src/carla_control_panel.h @@ -0,0 +1,104 @@ +/* + * Copyright (c) 2020 Intel Corporation + * + * This work is licensed under the terms of the MIT license. + * For a copy, see . + */ +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include + +class QLineEdit; +class QPushButton; +class QProgressBar; +class QCheckBox; +class QComboBox; + +namespace rviz { +class ViewController; +class FramePositionTrackingViewController; +} + +namespace rviz_carla_plugin { + +class DriveWidget; +class IndicatorWidget; + +class CarlaControlPanel : public rviz::Panel, public Ogre::Camera::Listener +{ + Q_OBJECT +public: + CarlaControlPanel(QWidget *parent = 0); + +public Q_SLOTS: + void setVel(float linearVelocity, float angularVelocity); + +protected Q_SLOTS: + void sendVel(); + + void carlaStepOnce(); + void carlaTogglePlayPause(); + void overrideVehicleControl(int state); + void executeScenario(); + + void updateCameraPos(); + void currentViewControllerChanged(); + +protected: + virtual void cameraPreRenderScene(Ogre::Camera *cam) override; + + virtual void onInitialize() override; + void setSimulationButtonStatus(bool active); + void setScenarioRunnerStatus(bool active); + + void scenarioRunnerStatusChanged(const carla_ros_scenario_runner_types::CarlaScenarioRunnerStatus::ConstPtr &msg); + void carlaStatusChanged(const carla_msgs::CarlaStatus::ConstPtr &msg); + void egoVehicleStatusChanged(const carla_msgs::CarlaEgoVehicleStatus::ConstPtr &msg); + void egoVehicleOdometryChanged(const nav_msgs::Odometry::ConstPtr &msg); + void carlaScenariosChanged(const carla_ros_scenario_runner_types::CarlaScenarioList::ConstPtr &msg); + carla_msgs::CarlaStatus::ConstPtr mCarlaStatus{nullptr}; + + DriveWidget *mDriveWidget; + QPushButton *mTriggerScenarioButton; + QPushButton *mPlayPauseButton; + QPushButton *mStepOnceButton; + QProgressBar *mThrottleBar; + QProgressBar *mBrakeBar; + QProgressBar *mSteerBar; + QLineEdit *mPosLabel; + QLineEdit *mSpeedLabel; + QLineEdit *mHeadingLabel; + QCheckBox *mOverrideVehicleControl; + QComboBox *mScenarioSelection; + IndicatorWidget *mIndicatorWidget; + ros::Publisher mTwistPublisher; + ros::Publisher mCarlaControlPublisher; + ros::Publisher mEgoVehicleControlManualOverridePublisher; + ros::Subscriber mCarlaStatusSubscriber; + ros::Subscriber mEgoVehicleStatusSubscriber; + ros::Subscriber mEgoVehicleOdometrySubscriber; + ros::ServiceClient mExecuteScenarioClient; + ros::Subscriber mScenarioSubscriber; + ros::Subscriber mScenarioRunnerStatusSubscriber; + ros::Publisher mCameraPosePublisher; + + carla_ros_scenario_runner_types::CarlaScenarioList::ConstPtr mCarlaScenarios; + + ros::NodeHandle mNodeHandle; + + float mLinearVelocity{0.0}; + float mAngularVelocity{0.0}; + bool mVehicleControlManualOverride{false}; + rviz::FramePositionTrackingViewController *mViewController{nullptr}; + Ogre::Vector3 mCameraCurrentPosition; + Ogre::Quaternion mCameraCurrentOrientation; +}; + +} // end namespace rviz_carla_plugin diff --git a/rviz_carla_plugin/src/drive_widget.cpp b/rviz_carla_plugin/src/drive_widget.cpp new file mode 100644 index 00000000..2de48ac2 --- /dev/null +++ b/rviz_carla_plugin/src/drive_widget.cpp @@ -0,0 +1,249 @@ +/* + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include + +#include +#include + +#include "drive_widget.h" + +namespace rviz_carla_plugin { + +// BEGIN_TUTORIAL +// The DriveWidget constructor does the normal Qt thing of +// passing the parent widget to the superclass constructor, then +// initializing the member variables. +DriveWidget::DriveWidget(QWidget *parent) + : QWidget(parent) + , linear_velocity_(0) + , angular_velocity_(0) + , linear_scale_(10) + , angular_scale_(.2) +{ +} + +// This paintEvent() is complex because of the drawing of the two +// arc-arrows representing wheel motion. It is not particularly +// relevant to learning how to make an RViz plugin, so I will kind of +// skim it. +void DriveWidget::paintEvent(QPaintEvent *event) +{ + // The background color and crosshair lines are drawn differently + // depending on whether this widget is enabled or not. This gives a + // nice visual indication of whether the control is "live". + QColor background; + QColor crosshair; + if (isEnabled()) + { + background = Qt::white; + crosshair = Qt::black; + } + else + { + background = Qt::lightGray; + crosshair = Qt::darkGray; + } + + // The main visual is a square, centered in the widget's area. Here + // we compute the size of the square and the horizontal and vertical + // offsets of it. + int w = width(); + int h = height(); + int size = ((w > h) ? h : w) - 1; + int hpad = (w - size) / 2; + int vpad = (h - size) / 2; + + QPainter painter(this); + painter.setBrush(background); + painter.setPen(crosshair); + + // Draw the background square. + painter.drawRect(QRect(hpad, vpad, size, size)); + + // Draw a cross-hair inside the square. + painter.drawLine(hpad, height() / 2, hpad + size, height() / 2); + painter.drawLine(width() / 2, vpad, width() / 2, vpad + size); + + // If the widget is enabled and the velocities are not zero, draw + // some sweet green arrows showing possible paths that the wheels of + // a diff-drive robot would take if it stayed at these velocities. + if (isEnabled() && (angular_velocity_ != 0 || linear_velocity_ != 0)) + { + QPen arrow; + arrow.setWidth(size / 20); + arrow.setColor(Qt::green); + arrow.setCapStyle(Qt::RoundCap); + arrow.setJoinStyle(Qt::RoundJoin); + painter.setPen(arrow); + + // This code steps along a central arc defined by the linear and + // angular velocites. At each step, it computes where the left + // and right wheels would be and collects the resulting points + // in the left_track and right_track arrays. + const int step_count = 100; + QPointF left_track[step_count]; + QPointF right_track[step_count]; + + float half_track_width = size / 4.0; + + float cx = w / 2; + float cy = h / 2; + left_track[0].setX(cx - half_track_width); + left_track[0].setY(cy); + right_track[0].setX(cx + half_track_width); + right_track[0].setY(cy); + float angle = M_PI / 2; + float delta_angle = angular_velocity_ / step_count; + float step_dist = linear_velocity_ * size / 2 / linear_scale_ / step_count; + for (int step = 1; step < step_count; step++) + { + angle += delta_angle / 2; + float next_cx = cx + step_dist * cosf(angle); + float next_cy = cy - step_dist * sinf(angle); + angle += delta_angle / 2; + + left_track[step].setX(next_cx + half_track_width * cosf(angle + M_PI / 2)); + left_track[step].setY(next_cy - half_track_width * sinf(angle + M_PI / 2)); + right_track[step].setX(next_cx + half_track_width * cosf(angle - M_PI / 2)); + right_track[step].setY(next_cy - half_track_width * sinf(angle - M_PI / 2)); + + cx = next_cx; + cy = next_cy; + } + // Now the track arrays are filled, so stroke each with a fat green line. + painter.drawPolyline(left_track, step_count); + painter.drawPolyline(right_track, step_count); + + // Here we decide which direction each arrowhead will point + // (forward or backward). This works by comparing the arc length + // travelled by the center in one step (step_dist) with the arc + // length travelled by the wheel (half_track_width * delta_angle). + int left_arrow_dir = (-step_dist + half_track_width * delta_angle > 0); + int right_arrow_dir = (-step_dist - half_track_width * delta_angle > 0); + + // Use MiterJoin for the arrowheads so we get a nice sharp point. + arrow.setJoinStyle(Qt::MiterJoin); + painter.setPen(arrow); + + // Compute and draw polylines for each arrowhead. This code could + // probably be more elegant. + float head_len = size / 8.0; + QPointF arrow_head[3]; + float x, y; + if (fabsf(-step_dist + half_track_width * delta_angle) > .01) + { + x = left_track[step_count - 1].x(); + y = left_track[step_count - 1].y(); + arrow_head[0].setX(x + head_len * cosf(angle + 3 * M_PI / 4 + left_arrow_dir * M_PI)); + arrow_head[0].setY(y - head_len * sinf(angle + 3 * M_PI / 4 + left_arrow_dir * M_PI)); + arrow_head[1].setX(x); + arrow_head[1].setY(y); + arrow_head[2].setX(x + head_len * cosf(angle - 3 * M_PI / 4 + left_arrow_dir * M_PI)); + arrow_head[2].setY(y - head_len * sinf(angle - 3 * M_PI / 4 + left_arrow_dir * M_PI)); + painter.drawPolyline(arrow_head, 3); + } + if (fabsf(-step_dist - half_track_width * delta_angle) > .01) + { + x = right_track[step_count - 1].x(); + y = right_track[step_count - 1].y(); + arrow_head[0].setX(x + head_len * cosf(angle + 3 * M_PI / 4 + right_arrow_dir * M_PI)); + arrow_head[0].setY(y - head_len * sinf(angle + 3 * M_PI / 4 + right_arrow_dir * M_PI)); + arrow_head[1].setX(x); + arrow_head[1].setY(y); + arrow_head[2].setX(x + head_len * cosf(angle - 3 * M_PI / 4 + right_arrow_dir * M_PI)); + arrow_head[2].setY(y - head_len * sinf(angle - 3 * M_PI / 4 + right_arrow_dir * M_PI)); + painter.drawPolyline(arrow_head, 3); + } + } +} + +// Every mouse move event received here sends a velocity because Qt +// only sends us mouse move events if there was previously a +// mouse-press event while in the widget. +void DriveWidget::mouseMoveEvent(QMouseEvent *event) +{ + sendVelocitiesFromMouse(event->x(), event->y(), width(), height()); +} + +// Mouse-press events should send the velocities too, of course. +void DriveWidget::mousePressEvent(QMouseEvent *event) +{ + sendVelocitiesFromMouse(event->x(), event->y(), width(), height()); +} + +// When the mouse leaves the widget but the button is still held down, +// we don't get the leaveEvent() because the mouse is "grabbed" (by +// default from Qt). However, when the mouse drags out of the widget +// and then other buttons are pressed (or possibly other +// window-manager things happen), we will get a leaveEvent() but not a +// mouseReleaseEvent(). Without catching this event you can have a +// robot stuck "on" without the user controlling it. +void DriveWidget::leaveEvent(QEvent *event) +{ + stop(); +} + +// The ordinary way to stop: let go of the mouse button. +void DriveWidget::mouseReleaseEvent(QMouseEvent *event) +{ + stop(); +} + +// Compute and emit linear and angular velocities based on Y and X +// mouse positions relative to the central square. +void DriveWidget::sendVelocitiesFromMouse(int x, int y, int width, int height) +{ + int size = ((width > height) ? height : width); + int hpad = (width - size) / 2; + int vpad = (height - size) / 2; + + linear_velocity_ = (1.0 - float(y - vpad) / float(size / 2)) * linear_scale_; + angular_velocity_ = (1.0 - float(x - hpad) / float(size / 2)) * angular_scale_; + Q_EMIT outputVelocity(linear_velocity_, angular_velocity_); + + // update() is a QWidget function which schedules this widget to be + // repainted the next time through the main event loop. We need + // this because the velocities have just changed, so the arrows need + // to be redrawn to match. + update(); +} + +// How to stop: emit velocities of 0! +void DriveWidget::stop() +{ + linear_velocity_ = 0; + angular_velocity_ = 0; + Q_EMIT outputVelocity(linear_velocity_, angular_velocity_); + update(); +} +// END_TUTORIAL + +} // end namespace rviz_carla_plugin diff --git a/rviz_carla_plugin/src/drive_widget.h b/rviz_carla_plugin/src/drive_widget.h new file mode 100644 index 00000000..e0a6c7d0 --- /dev/null +++ b/rviz_carla_plugin/src/drive_widget.h @@ -0,0 +1,91 @@ +/* + * Copyright (c) 2011, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of the Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#ifndef DRIVE_WIDGET_H +#define DRIVE_WIDGET_H + +#include + +namespace rviz_carla_plugin { + +// BEGIN_TUTORIAL +// DriveWidget implements a control which translates mouse Y values +// into linear velocities and mouse X values into angular velocities. +// +// For maximum reusability, this class is only responsible for user +// interaction and display inside its widget. It does not make any +// ROS or RViz calls. It communicates its data to the outside just +// via Qt signals. +class DriveWidget : public QWidget +{ + Q_OBJECT +public: + // This class is not instantiated by pluginlib::ClassLoader, so the + // constructor has no restrictions. + DriveWidget(QWidget *parent = 0); + + // We override QWidget::paintEvent() to do custom painting. + virtual void paintEvent(QPaintEvent *event); + + // We override the mouse events and leaveEvent() to keep track of + // what the mouse is doing. + virtual void mouseMoveEvent(QMouseEvent *event); + virtual void mousePressEvent(QMouseEvent *event); + virtual void mouseReleaseEvent(QMouseEvent *event); + virtual void leaveEvent(QEvent *event); + + // Override sizeHint() to give the layout managers some idea of a + // good size for this. + virtual QSize sizeHint() const + { + return QSize(150, 150); + } + + // We emit outputVelocity() whenever it changes. +Q_SIGNALS: + void outputVelocity(float linear, float angular); + + // mouseMoveEvent() and mousePressEvent() need the same math to + // figure the velocities, so I put that in here. +protected: + void sendVelocitiesFromMouse(int x, int y, int width, int height); + + // A function to emit zero velocity. + void stop(); + + // Finally the member variables: + float linear_velocity_; // In m/s + float angular_velocity_; // In radians/s + float linear_scale_; // In m/s + float angular_scale_; // In radians/s +}; +// END_TUTORIAL + +} // end namespace rviz_carla_plugin + +#endif // DRIVE_WIDGET_H diff --git a/rviz_carla_plugin/src/indicator_widget.cpp b/rviz_carla_plugin/src/indicator_widget.cpp new file mode 100644 index 00000000..ae160a42 --- /dev/null +++ b/rviz_carla_plugin/src/indicator_widget.cpp @@ -0,0 +1,53 @@ +/* + * Copyright (c) 2020 Intel Corporation + * + * This work is licensed under the terms of the MIT license. + * For a copy, see . + */ +#include "indicator_widget.h" +#include + +namespace rviz_carla_plugin { + +IndicatorWidget::IndicatorWidget(QWidget *parent) + : QWidget(parent) + , mCurrentState(IndicatorWidget::State::Stopped) +{ + setFixedSize(18, 18); +} + +void IndicatorWidget::paintEvent(QPaintEvent *event) +{ + QPainter painter(this); + painter.setPen(Qt::darkGray); + if (mCurrentState == IndicatorWidget::State::Stopped) + { + painter.setBrush(QBrush(Qt::lightGray, Qt::SolidPattern)); + } + else if (mCurrentState == IndicatorWidget::State::Running) + { + painter.setBrush(QBrush(Qt::green, Qt::SolidPattern)); + } + else if (mCurrentState == IndicatorWidget::State::Error) + { + painter.setBrush(QBrush(Qt::red, Qt::SolidPattern)); + } + else if ((mCurrentState == IndicatorWidget::State::Starting) + || (mCurrentState == IndicatorWidget::State::ShuttingDown)) + { + painter.setBrush(QBrush(Qt::yellow, Qt::SolidPattern)); + } + else + { + painter.setBrush(QBrush(Qt::black, Qt::SolidPattern)); + } + painter.drawEllipse(1, 1, 16, 16); +} + +void IndicatorWidget::setState(IndicatorWidget::State state) +{ + mCurrentState = state; + repaint(); +} + +} // end namespace rviz_carla_plugin diff --git a/rviz_carla_plugin/src/indicator_widget.h b/rviz_carla_plugin/src/indicator_widget.h new file mode 100644 index 00000000..2d5ea19f --- /dev/null +++ b/rviz_carla_plugin/src/indicator_widget.h @@ -0,0 +1,36 @@ +/* + * Copyright (c) 2020 Intel Corporation + * + * This work is licensed under the terms of the MIT license. + * For a copy, see . + */ +#pragma once + +#include + +namespace rviz_carla_plugin { + +class IndicatorWidget : public QWidget +{ + Q_OBJECT +public: + enum class State + { + Stopped, + Starting, + Running, + ShuttingDown, + Error + }; + + IndicatorWidget(QWidget *parent = 0); + + virtual void paintEvent(QPaintEvent *event) override; + + void setState(IndicatorWidget::State state); + +private: + State mCurrentState{State::Stopped}; +}; + +} // end namespace rviz_carla_plugin