From 1899981604f0bb4f1ae238809e67e64c76355691 Mon Sep 17 00:00:00 2001 From: Bernd Pfrommer Date: Sat, 13 Apr 2024 19:26:20 -0400 Subject: [PATCH 1/3] widened the ExposureController interface --- .../include/spinnaker_camera_driver/exposure_controller.hpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/spinnaker_camera_driver/include/spinnaker_camera_driver/exposure_controller.hpp b/spinnaker_camera_driver/include/spinnaker_camera_driver/exposure_controller.hpp index 6321537f..4aa12702 100644 --- a/spinnaker_camera_driver/include/spinnaker_camera_driver/exposure_controller.hpp +++ b/spinnaker_camera_driver/include/spinnaker_camera_driver/exposure_controller.hpp @@ -30,6 +30,10 @@ class ExposureController virtual ~ExposureController() {} virtual void update(Camera * cam, const std::shared_ptr & img) = 0; virtual void addCamera(const std::shared_ptr & cam) = 0; + virtual double getExposureTime() = 0; + virtual double getGain() = 0; + virtual void link( + const std::unordered_map> & map) = 0; }; } // namespace spinnaker_camera_driver #endif // SPINNAKER_CAMERA_DRIVER__EXPOSURE_CONTROLLER_HPP_ From 95b904cc0d594c59c024b18603ddc51ac1b37a1f Mon Sep 17 00:00:00 2001 From: Bernd Pfrommer Date: Sat, 13 Apr 2024 19:28:27 -0400 Subject: [PATCH 2/3] added follower exposure controller renamed individual -> master --- .../CMakeLists.txt | 7 +- .../follower_exposure_controller.hpp | 61 +++++++ ...ler.hpp => master_exposure_controller.hpp} | 19 ++- .../launch/follower_example.launch.py | 151 ++++++++++++++++++ .../launch/master_example.launch.py | 148 +++++++++++++++++ .../launch/synchronized_driver_node.launch.py | 95 ----------- .../src/exposure_controller_factory.cpp | 9 +- .../src/follower_exposure_controller.cpp | 102 ++++++++++++ ...ler.cpp => master_exposure_controller.cpp} | 30 ++-- .../src/synchronized_camera_driver.cpp | 4 + 10 files changed, 499 insertions(+), 127 deletions(-) create mode 100644 spinnaker_synchronized_camera_driver/include/spinnaker_synchronized_camera_driver/follower_exposure_controller.hpp rename spinnaker_synchronized_camera_driver/include/spinnaker_synchronized_camera_driver/{individual_exposure_controller.hpp => master_exposure_controller.hpp} (72%) create mode 100644 spinnaker_synchronized_camera_driver/launch/follower_example.launch.py create mode 100644 spinnaker_synchronized_camera_driver/launch/master_example.launch.py delete mode 100644 spinnaker_synchronized_camera_driver/launch/synchronized_driver_node.launch.py create mode 100644 spinnaker_synchronized_camera_driver/src/follower_exposure_controller.cpp rename spinnaker_synchronized_camera_driver/src/{individual_exposure_controller.cpp => master_exposure_controller.cpp} (88%) diff --git a/spinnaker_synchronized_camera_driver/CMakeLists.txt b/spinnaker_synchronized_camera_driver/CMakeLists.txt index 5e6756d1..b63627bc 100644 --- a/spinnaker_synchronized_camera_driver/CMakeLists.txt +++ b/spinnaker_synchronized_camera_driver/CMakeLists.txt @@ -60,7 +60,8 @@ add_library(synchronized_camera_driver SHARED src/time_estimator.cpp src/time_keeper.cpp src/exposure_controller_factory.cpp - src/individual_exposure_controller.cpp) + src/master_exposure_controller.cpp + src/follower_exposure_controller.cpp) ament_target_dependencies(synchronized_camera_driver PUBLIC ${ROS_DEPENDENCIES}) target_link_libraries(synchronized_camera_driver PUBLIC spinnaker_camera_driver::camera_driver PRIVATE yaml-cpp) @@ -111,7 +112,7 @@ if(BUILD_TESTING) find_package(ament_cmake_copyright REQUIRED) find_package(ament_cmake_cppcheck REQUIRED) find_package(ament_cmake_cpplint REQUIRED) - find_package(ament_cmake_black REQUIRED) + find_package(ament_cmake_flake8 REQUIRED) find_package(ament_cmake_lint_cmake REQUIRED) find_package(ament_cmake_pep257 REQUIRED) find_package(ament_cmake_clang_format REQUIRED) @@ -120,7 +121,7 @@ if(BUILD_TESTING) ament_copyright() ament_cppcheck(LANGUAGE c++) ament_cpplint(FILTERS "-build/include,-runtime/indentation_namespace") - ament_black() + ament_flake8() ament_lint_cmake() ament_pep257() ament_clang_format(CONFIG_FILE .clang-format) diff --git a/spinnaker_synchronized_camera_driver/include/spinnaker_synchronized_camera_driver/follower_exposure_controller.hpp b/spinnaker_synchronized_camera_driver/include/spinnaker_synchronized_camera_driver/follower_exposure_controller.hpp new file mode 100644 index 00000000..f05a4903 --- /dev/null +++ b/spinnaker_synchronized_camera_driver/include/spinnaker_synchronized_camera_driver/follower_exposure_controller.hpp @@ -0,0 +1,61 @@ +// -*-c++-*-------------------------------------------------------------------- +// Copyright 2024 Bernd Pfrommer +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef SPINNAKER_SYNCHRONIZED_CAMERA_DRIVER__FOLLOWER_EXPOSURE_CONTROLLER_HPP_ +#define SPINNAKER_SYNCHRONIZED_CAMERA_DRIVER__FOLLOWER_EXPOSURE_CONTROLLER_HPP_ + +#include +#include +#include + +namespace spinnaker_synchronized_camera_driver +{ +class FollowerExposureController : public spinnaker_camera_driver::ExposureController +{ +public: + using Camera = spinnaker_camera_driver::Camera; + explicit FollowerExposureController(const std::string & name, rclcpp::Node * n); + void update( + Camera * cam, const std::shared_ptr & img) final; + void addCamera(const std::shared_ptr & cam) final; + double getExposureTime() final { return (currentExposureTime_); }; + double getGain() final { return (currentGain_); } + void link(const std::unordered_map> & map) final; + +private: + rclcpp::Logger get_logger() { return (rclcpp::get_logger(cameraName_)); } + + template + T declare_param(const std::string & n, const T & def) + { + return (node_->declare_parameter(name_ + "." + n, def)); + } + + // ----------------- variables -------------------- + std::string name_; + std::string cameraName_; + rclcpp::Node * node_{0}; + std::string exposureParameterName_; + std::string gainParameterName_; + std::string masterControllerName_; + std::shared_ptr masterController_; + + double currentExposureTime_{0}; + double currentGain_{std::numeric_limits::lowest()}; + int numFramesSkip_{0}; + int maxFramesSkip_{10}; +}; +} // namespace spinnaker_synchronized_camera_driver +#endif // SPINNAKER_SYNCHRONIZED_CAMERA_DRIVER__FOLLOWER_EXPOSURE_CONTROLLER_HPP_ diff --git a/spinnaker_synchronized_camera_driver/include/spinnaker_synchronized_camera_driver/individual_exposure_controller.hpp b/spinnaker_synchronized_camera_driver/include/spinnaker_synchronized_camera_driver/master_exposure_controller.hpp similarity index 72% rename from spinnaker_synchronized_camera_driver/include/spinnaker_synchronized_camera_driver/individual_exposure_controller.hpp rename to spinnaker_synchronized_camera_driver/include/spinnaker_synchronized_camera_driver/master_exposure_controller.hpp index 200a7a3f..dbe0d861 100644 --- a/spinnaker_synchronized_camera_driver/include/spinnaker_synchronized_camera_driver/individual_exposure_controller.hpp +++ b/spinnaker_synchronized_camera_driver/include/spinnaker_synchronized_camera_driver/master_exposure_controller.hpp @@ -13,8 +13,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef SPINNAKER_SYNCHRONIZED_CAMERA_DRIVER__INDIVIDUAL_EXPOSURE_CONTROLLER_HPP_ -#define SPINNAKER_SYNCHRONIZED_CAMERA_DRIVER__INDIVIDUAL_EXPOSURE_CONTROLLER_HPP_ +#ifndef SPINNAKER_SYNCHRONIZED_CAMERA_DRIVER__MASTER_EXPOSURE_CONTROLLER_HPP_ +#define SPINNAKER_SYNCHRONIZED_CAMERA_DRIVER__MASTER_EXPOSURE_CONTROLLER_HPP_ #include #include @@ -22,14 +22,17 @@ namespace spinnaker_synchronized_camera_driver { -class IndividualExposureController : public spinnaker_camera_driver::ExposureController +class MasterExposureController : public spinnaker_camera_driver::ExposureController { public: - explicit IndividualExposureController(const std::string & name, rclcpp::Node * n); + using Camera = spinnaker_camera_driver::Camera; + explicit MasterExposureController(const std::string & name, rclcpp::Node * n); void update( - spinnaker_camera_driver::Camera * cam, - const std::shared_ptr & img) final; - void addCamera(const std::shared_ptr & cam) final; + Camera * cam, const std::shared_ptr & img) final; + void addCamera(const std::shared_ptr & cam) final; + double getExposureTime() final { return (currentExposureTime_); }; + double getGain() final { return (currentGain_); } + void link(const std::unordered_map> &) final {} private: double calculateGain(double brightRatio) const; @@ -68,4 +71,4 @@ class IndividualExposureController : public spinnaker_camera_driver::ExposureCon bool gainPriority_{false}; }; } // namespace spinnaker_synchronized_camera_driver -#endif // SPINNAKER_SYNCHRONIZED_CAMERA_DRIVER__INDIVIDUAL_EXPOSURE_CONTROLLER_HPP_ +#endif // SPINNAKER_SYNCHRONIZED_CAMERA_DRIVER__MASTER_EXPOSURE_CONTROLLER_HPP_ diff --git a/spinnaker_synchronized_camera_driver/launch/follower_example.launch.py b/spinnaker_synchronized_camera_driver/launch/follower_example.launch.py new file mode 100644 index 00000000..688770b1 --- /dev/null +++ b/spinnaker_synchronized_camera_driver/launch/follower_example.launch.py @@ -0,0 +1,151 @@ +# ----------------------------------------------------------------------------- +# Copyright 2024 Bernd Pfrommer +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# + + +# +# Example file for two Blackfly S cameras that are *externally triggered*, i.e +# you must provide an external hardware synchronization pulse to both cameras! +# +# One of them creates a master controller, the other one a follower. The exposure +# parameters are determined by the master. This is a useful setup for e.g. a +# synchronized stereo camera. +# + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument as LaunchArg +from launch.actions import OpaqueFunction +from launch.substitutions import LaunchConfiguration as LaunchConfig +from launch.substitutions import PathJoinSubstitution as PJoin +from launch_ros.actions import ComposableNodeContainer +from launch_ros.descriptions import ComposableNode +from launch_ros.substitutions import FindPackageShare + +camera_list = { + 'cam0': '20435008', + 'cam1': '20415937', +} + +exposure_controller_parameters = { + 'brightness_target': 120, # from 0..255 + 'brightness_tolerance': 20, # when to update exposure/gain + # watch that max_exposure_time is short enough + # to support the trigger frame rate! + 'max_exposure_time': 15000, # usec + 'min_exposure_time': 5000, # usec + 'max_gain': 29.9, + 'gain_priority': False, +} + +cam_parameters = { + 'debug': False, + 'quiet': True, + 'buffer_queue_size': 1, + 'compute_brightness': True, + 'exposure_auto': 'Off', + 'exposure_time': 10000, # not used under auto exposure + 'trigger_mode': 'On', + 'gain_auto': 'Off', + 'trigger_source': 'Line3', + 'trigger_selector': 'FrameStart', + 'trigger_overlap': 'ReadOut', + 'trigger_activation': 'RisingEdge', + 'balance_white_auto': 'Continuous', + # You must enable chunk mode and chunks: frame_id, exposure_time, and gain + 'chunk_mode_active': True, + 'chunk_selector_frame_id': 'FrameID', + 'chunk_enable_frame_id': True, + 'chunk_selector_exposure_time': 'ExposureTime', + 'chunk_enable_exposure_time': True, + 'chunk_selector_gain': 'Gain', + 'chunk_enable_gain': True, + # The Timestamp is not used at the moment + 'chunk_selector_timestamp': 'Timestamp', + 'chunk_enable_timestamp': True, +} + + +def make_parameters(context): + """Launch synchronized camera driver node.""" + pd = LaunchConfig('camera_parameter_directory') + calib_url = 'file://' + LaunchConfig('calibration_directory').perform(context) + '/' + + exp_ctrl_names = [cam + '.exposure_controller' for cam in camera_list.keys()] + driver_parameters = { + 'cameras': list(camera_list.keys()), + 'exposure_controllers': exp_ctrl_names, + 'ffmpeg_image_transport.encoding': 'hevc_nvenc', # only for ffmpeg image transport + } + # generate identical exposure controller parameters for all cameras + for exp in exp_ctrl_names: + driver_parameters.update( + {exp + '.' + k: v for k, v in exposure_controller_parameters.items()} + ) + # now set cam0 to be master, cam1 to be follower + driver_parameters[exp_ctrl_names[0] + '.type'] = 'master' + driver_parameters[exp_ctrl_names[1] + '.type'] = 'follower' + # tell camera 1 that the master is (camera 0) + driver_parameters[exp_ctrl_names[1] + '.master'] = exp_ctrl_names[0] + + # generate camera parameters + cam_parameters['parameter_file'] = PJoin([pd, 'blackfly_s.yaml']) + for cam, serial in camera_list.items(): + cam_params = {cam + '.' + k: v for k, v in cam_parameters.items()} + cam_params[cam + '.serial_number'] = serial + cam_params[cam + '.camerainfo_url'] = calib_url + serial + '.yaml' + cam_params[cam + '.frame_id'] = cam + driver_parameters.update(cam_params) # insert into main parameter list + # link the camera to its exposure controller. Each camera has its own controller + driver_parameters.update({cam + '.exposure_controller_name': cam + '.exposure_controller'}) + return driver_parameters + + +def launch_setup(context, *args, **kwargs): + container = ComposableNodeContainer( + name='cam_sync_container', + namespace='', + package='rclcpp_components', + executable='component_container', + composable_node_descriptions=[ + ComposableNode( + package='spinnaker_synchronized_camera_driver', + plugin='spinnaker_synchronized_camera_driver::SynchronizedCameraDriver', + name='cam_sync', + parameters=[make_parameters(context)], + extra_arguments=[{'use_intra_process_comms': True}], + ), + ], + output='screen', + ) # end of container + return [container] + + +def generate_launch_description(): + return LaunchDescription( + [ + LaunchArg( + 'camera_parameter_directory', + default_value=PJoin([FindPackageShare('spinnaker_camera_driver'), 'config']), + description='root directory for camera parameter definitions', + ), + LaunchArg( + 'calibration_directory', + default_value=['camera_calibrations'], + description='root directory for camera calibration files', + ), + OpaqueFunction(function=launch_setup), + ] + ) diff --git a/spinnaker_synchronized_camera_driver/launch/master_example.launch.py b/spinnaker_synchronized_camera_driver/launch/master_example.launch.py new file mode 100644 index 00000000..a2c8cec2 --- /dev/null +++ b/spinnaker_synchronized_camera_driver/launch/master_example.launch.py @@ -0,0 +1,148 @@ +# ----------------------------------------------------------------------------- +# Copyright 2024 Bernd Pfrommer +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# + + +# +# Example file for two Blackfly S cameras that are *externally triggered*, i.e +# you must provide an external hardware synchronization pulse to both cameras! +# +# Each of them regulates their exposure time individually by instantiating a +# master exposure controller. This setup is useful when cameras are not facing +# the scene, or facing it from very different angles such that different +# lighting conditions must be expected. +# + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument as LaunchArg +from launch.actions import OpaqueFunction +from launch.substitutions import LaunchConfiguration as LaunchConfig +from launch.substitutions import PathJoinSubstitution as PJoin +from launch_ros.actions import ComposableNodeContainer +from launch_ros.descriptions import ComposableNode +from launch_ros.substitutions import FindPackageShare + +camera_list = { + 'cam0': '20435008', + 'cam1': '20415937', +} + +exposure_controller_parameters = { + 'type': 'master', + 'brightness_target': 120, # from 0..255 + 'brightness_tolerance': 20, # when to update exposure/gain + # watch that max_exposure_time is short enough + # to support the trigger frame rate! + 'max_exposure_time': 15000, # usec + 'min_exposure_time': 5000, # usec + 'max_gain': 29.9, + 'gain_priority': False, +} + +cam_parameters = { + 'debug': False, + 'quiet': True, + 'buffer_queue_size': 1, + 'compute_brightness': True, + 'exposure_auto': 'Off', + 'exposure_time': 10000, # not used under auto exposure + 'trigger_mode': 'On', + 'gain_auto': 'Off', + 'trigger_source': 'Line3', + 'trigger_selector': 'FrameStart', + 'trigger_overlap': 'ReadOut', + 'trigger_activation': 'RisingEdge', + 'balance_white_auto': 'Continuous', + # You must enable chunk mode and chunks: frame_id, exposure_time, and gain + 'chunk_mode_active': True, + 'chunk_selector_frame_id': 'FrameID', + 'chunk_enable_frame_id': True, + 'chunk_selector_exposure_time': 'ExposureTime', + 'chunk_enable_exposure_time': True, + 'chunk_selector_gain': 'Gain', + 'chunk_enable_gain': True, + # The Timestamp is not used at the moment + 'chunk_selector_timestamp': 'Timestamp', + 'chunk_enable_timestamp': True, +} + + +def make_parameters(context): + """Launch synchronized camera driver node.""" + pd = LaunchConfig('camera_parameter_directory') + calib_url = 'file://' + LaunchConfig('calibration_directory').perform(context) + '/' + + exp_ctrl_names = [cam + '.exposure_controller' for cam in camera_list.keys()] + driver_parameters = { + 'cameras': list(camera_list.keys()), + 'exposure_controllers': exp_ctrl_names, + 'ffmpeg_image_transport.encoding': 'hevc_nvenc', # only for ffmpeg image transport + } + # generate identical exposure controller parameters for all cameras + for exp in exp_ctrl_names: + driver_parameters.update( + {exp + '.' + k: v for k, v in exposure_controller_parameters.items()} + ) + + # generate camera parameters + cam_parameters['parameter_file'] = PJoin([pd, 'blackfly_s.yaml']) + for cam, serial in camera_list.items(): + cam_params = {cam + '.' + k: v for k, v in cam_parameters.items()} + cam_params[cam + '.serial_number'] = serial + cam_params[cam + '.camerainfo_url'] = calib_url + serial + '.yaml' + cam_params[cam + '.frame_id'] = cam + driver_parameters.update(cam_params) # insert into main parameter list + # link the camera to its exposure controller. Each camera has its own controller + driver_parameters.update({cam + '.exposure_controller_name': cam + '.exposure_controller'}) + return driver_parameters + + +def launch_setup(context, *args, **kwargs): + container = ComposableNodeContainer( + name='cam_sync_container', + namespace='', + package='rclcpp_components', + executable='component_container', + composable_node_descriptions=[ + ComposableNode( + package='spinnaker_synchronized_camera_driver', + plugin='spinnaker_synchronized_camera_driver::SynchronizedCameraDriver', + name='cam_sync', + parameters=[make_parameters(context)], + extra_arguments=[{'use_intra_process_comms': True}], + ), + ], + output='screen', + ) # end of container + return [container] + + +def generate_launch_description(): + return LaunchDescription( + [ + LaunchArg( + 'camera_parameter_directory', + default_value=PJoin([FindPackageShare('spinnaker_camera_driver'), 'config']), + description='root directory for camera parameter definitions', + ), + LaunchArg( + 'calibration_directory', + default_value=['camera_calibrations'], + description='root directory for camera calibration files', + ), + OpaqueFunction(function=launch_setup), + ] + ) diff --git a/spinnaker_synchronized_camera_driver/launch/synchronized_driver_node.launch.py b/spinnaker_synchronized_camera_driver/launch/synchronized_driver_node.launch.py deleted file mode 100644 index 2826b04d..00000000 --- a/spinnaker_synchronized_camera_driver/launch/synchronized_driver_node.launch.py +++ /dev/null @@ -1,95 +0,0 @@ -# ----------------------------------------------------------------------------- -# Copyright 2022 Bernd Pfrommer -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -# -# - -from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument as LaunchArg -from launch.actions import OpaqueFunction -from launch.substitutions import LaunchConfiguration as LaunchConfig -from launch.substitutions import PathJoinSubstitution as PJoin -from launch_ros.actions import Node -from launch_ros.substitutions import FindPackageShare - -cam_parameters = { - "parameter_file": "blackfly_s.yaml", - "buffer_queue_size": 1, - "frame_rate_auto": "Off", - "frame_rate_enable": False, - # watch that your exposure time is - # short enough to support the trigger frame rate! - "exposure_auto": "Off", - "exposure_time": 6000, - "gain_auto": "Continuous", - "trigger_mode": "On", - "trigger_source": "Line3", - "trigger_selector": "FrameStart", - "trigger_overlap": "ReadOut", - "trigger_activation": "RisingEdge", - # You must enable chunk mode and enable frame_id - "chunk_mode_active": True, - "chunk_selector_frame_id": "FrameID", - "chunk_enable_frame_id": True, - # The other chunk info should not be required - # "chunk_selector_exposure_time": "ExposureTime", - # "chunk_enable_exposure_time": True, - # "chunk_selector_gain": "Gain", - # "chunk_enable_gain": True, - # "chunk_selector_timestamp": "Timestamp", - # "chunk_enable_timestamp": True, -} - - -def launch_setup(context, *args, **kwargs): - """Launch synchronized camera driver node.""" - pd = LaunchConfig("camera_parameter_directory") - c0, c1 = "cam_0", "cam_1" - c0p, c1p = c0 + ".", c1 + "." - driver_parameters = {"cameras": [c0, c1]} - cam_parameters["parameter_file"] = PJoin([pd, "blackfly_s.yaml"]) - cam_0_parameters = {c0p + k: v for k, v in cam_parameters.items()} - cam_0_parameters[c0p + "serial_number"] = "20435008" - cam_1_parameters = {c1p + k: v for k, v in cam_parameters.items()} - cam_1_parameters[c1p + "serial_number"] = "20415937" - node = Node( - package="spinnaker_synchronized_camera_driver", - executable="synchronized_camera_driver_node", - output="screen", - # prefix=["xterm -e gdb -ex run --args"], - name=[LaunchConfig("driver_name")], - parameters=[driver_parameters, cam_0_parameters, cam_1_parameters], - ) - return [node] - - -def generate_launch_description(): - """Create composable node by calling opaque function.""" - return LaunchDescription( - [ - LaunchArg( - "driver_name", - default_value=["cam_sync"], - description="name of driver node", - ), - LaunchArg( - "camera_parameter_directory", - default_value=PJoin( - [FindPackageShare("spinnaker_camera_driver"), "config"] - ), - description="root directory for camera parameter definitions", - ), - OpaqueFunction(function=launch_setup), - ] - ) diff --git a/spinnaker_synchronized_camera_driver/src/exposure_controller_factory.cpp b/spinnaker_synchronized_camera_driver/src/exposure_controller_factory.cpp index 2619926c..40f13cf3 100644 --- a/spinnaker_synchronized_camera_driver/src/exposure_controller_factory.cpp +++ b/spinnaker_synchronized_camera_driver/src/exposure_controller_factory.cpp @@ -14,8 +14,9 @@ // limitations under the License. #include -#include +#include #include +#include namespace spinnaker_synchronized_camera_driver { @@ -25,8 +26,10 @@ static rclcpp::Logger get_logger() { return (rclcpp::get_logger("cam_sync")); } std::shared_ptr newInstance( const std::string & type, const std::string & name, rclcpp::Node * node) { - if (type == "individual") { - return (std::make_shared(name, node)); + if (type == "master") { + return (std::make_shared(name, node)); + } else if (type == "follower") { + return (std::make_shared(name, node)); } BOMB_OUT("unknown exposure controller type: " << type); return (nullptr); diff --git a/spinnaker_synchronized_camera_driver/src/follower_exposure_controller.cpp b/spinnaker_synchronized_camera_driver/src/follower_exposure_controller.cpp new file mode 100644 index 00000000..88153449 --- /dev/null +++ b/spinnaker_synchronized_camera_driver/src/follower_exposure_controller.cpp @@ -0,0 +1,102 @@ +// -*-c++-*-------------------------------------------------------------------- +// Copyright 2024 Bernd Pfrommer +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include +#include +#include + +namespace spinnaker_synchronized_camera_driver +{ +FollowerExposureController::FollowerExposureController( + const std::string & name, rclcpp::Node * node) +: name_(name), node_(node) +{ + exposureParameterName_ = declare_param("exposure_parameter", "exposure_time"); + gainParameterName_ = declare_param("gain_parameter", "gain"); + maxFramesSkip_ = declare_param("max_frames_skip", 10); // number of frames to wait + masterControllerName_ = declare_param("master", ""); + if (masterControllerName_.empty()) { + BOMB_OUT("master exposure controller must be set for controller " << name_); + } +} +void FollowerExposureController::link( + const std::unordered_map> & map) +{ + const auto it = map.find(masterControllerName_); + if (it == map.end()) { + BOMB_OUT("cannot find master " << masterControllerName_ << " for controller " << name_); + } + masterController_ = it->second; +} + +void FollowerExposureController::update( + spinnaker_camera_driver::Camera * cam, + const std::shared_ptr & img) +{ + // if the exposure parameters are not set yet, set them now + if (currentExposureTime_ == 0) { + currentExposureTime_ = static_cast(img->exposureTime_); + } + if (currentGain_ == std::numeric_limits::lowest()) { + currentGain_ = img->gain_; + } + // check if the exposure and brightness settings reported along with the image + // match what last has been sent to the camera. + if ( + fabs(currentGain_ - img->gain_) <= 0.05 * (currentGain_ + img->gain_) && + fabs(currentExposureTime_ - static_cast(img->exposureTime_)) <= + 0.05 * (currentExposureTime_ + static_cast(img->exposureTime_)) && + numFramesSkip_ < maxFramesSkip_) { + numFramesSkip_ = 0; // no skipping anymore! + } + + if (numFramesSkip_ > 0) { + // Changes in gain or shutter take a few + // frames to arrive at the camera, so we skip those. + numFramesSkip_--; + } else { + const auto masterExposureTime = masterController_->getExposureTime(); + const auto masterGain = masterController_->getGain(); + bool parametersChanged{false}; + if (masterExposureTime != currentExposureTime_) { + const auto expName = cam->getPrefix() + exposureParameterName_; + node_->set_parameter(rclcpp::Parameter(expName, masterExposureTime)); + parametersChanged = true; + } + if (masterGain != currentGain_) { + const auto gainName = cam->getPrefix() + gainParameterName_; + node_->set_parameter(rclcpp::Parameter(gainName, masterGain)); + parametersChanged = true; + } + if (parametersChanged) { + const int b = std::min(std::max(1, static_cast(img->brightness_)), 255); + LOG_INFO( + "bright " << b << " at time/gain: [" << currentExposureTime_ << " " << currentGain_ + << "] new: [" << masterExposureTime << " " << masterGain << "]"); + numFramesSkip_ = maxFramesSkip_; // restart frame skipping + currentExposureTime_ = masterExposureTime; + currentGain_ = masterGain; + } + } +} + +void FollowerExposureController::addCamera( + const std::shared_ptr & cam) +{ + cameraName_ = cam->getName(); +} + +} // namespace spinnaker_synchronized_camera_driver diff --git a/spinnaker_synchronized_camera_driver/src/individual_exposure_controller.cpp b/spinnaker_synchronized_camera_driver/src/master_exposure_controller.cpp similarity index 88% rename from spinnaker_synchronized_camera_driver/src/individual_exposure_controller.cpp rename to spinnaker_synchronized_camera_driver/src/master_exposure_controller.cpp index 4e043a6d..be772cd2 100644 --- a/spinnaker_synchronized_camera_driver/src/individual_exposure_controller.cpp +++ b/spinnaker_synchronized_camera_driver/src/master_exposure_controller.cpp @@ -15,15 +15,14 @@ #include #include -#include #include +#include // #define DEBUG namespace spinnaker_synchronized_camera_driver { -IndividualExposureController::IndividualExposureController( - const std::string & name, rclcpp::Node * node) +MasterExposureController::MasterExposureController(const std::string & name, rclcpp::Node * node) : name_(name), node_(node) { exposureParameterName_ = declare_param("exposure_parameter", "exposure_time"); @@ -35,10 +34,10 @@ IndividualExposureController::IndividualExposureController( minExposureTime_ = std::max(declare_param("min_exposure_time", 10), 1); maxGain_ = declare_param("max_gain", 10); gainPriority_ = declare_param("gain_priority", false); - maxFramesSkip_ = declare_param("min_frames_skip", 10); // number of frames to wait + maxFramesSkip_ = declare_param("max_frames_skip", 10); // number of frames to wait } -double IndividualExposureController::calculateGain(double brightRatio) const +double MasterExposureController::calculateGain(double brightRatio) const { // because gain is in db: // db(G) = 10 * log_10(G) = 10 * ln(G) / ln(10) = 4.34 * ln(G) @@ -50,14 +49,14 @@ double IndividualExposureController::calculateGain(double brightRatio) const return (cappedGain > 0.5 ? cappedGain : 0); } -double IndividualExposureController::calculateExposureTime(double brightRatio) const +double MasterExposureController::calculateExposureTime(double brightRatio) const { const double desiredExposureTime = currentExposureTime_ * brightRatio; const double optTime = std::max(0.0, std::min(desiredExposureTime, maxExposureTime_)); return (optTime); } -bool IndividualExposureController::changeExposure( +bool MasterExposureController::changeExposure( double brightRatio, double minTime, double maxTime, const char * debugMsg) { const double optTime = std::min(std::max(calculateExposureTime(brightRatio), minTime), maxTime); @@ -73,7 +72,7 @@ bool IndividualExposureController::changeExposure( return (false); } -bool IndividualExposureController::changeGain( +bool MasterExposureController::changeGain( double brightRatio, double minGain, double maxGain, const char * debugMsg) { const double optGain = std::min(std::max(calculateGain(brightRatio), minGain), maxGain); @@ -89,7 +88,7 @@ bool IndividualExposureController::changeGain( return (false); } -bool IndividualExposureController::updateExposureWithGainPriority(double brightRatio) +bool MasterExposureController::updateExposureWithGainPriority(double brightRatio) { if (brightRatio < 1) { // image is too bright if (currentGain_ > 0) { @@ -119,7 +118,7 @@ bool IndividualExposureController::updateExposureWithGainPriority(double brightR return (false); } -bool IndividualExposureController::updateExposureWithTimePriority(double brightRatio) +bool MasterExposureController::updateExposureWithTimePriority(double brightRatio) { if (brightRatio < 1) { // image is too bright if (currentExposureTime_ > minExposureTime_) { @@ -163,7 +162,7 @@ bool IndividualExposureController::updateExposureWithTimePriority(double brightR return (false); } -bool IndividualExposureController::updateExposure(double b) +bool MasterExposureController::updateExposure(double b) { const double err_b = (brightnessTarget_ - b); // the current gain is higher than it should be, let's @@ -194,7 +193,7 @@ bool IndividualExposureController::updateExposure(double b) return (false); } -void IndividualExposureController::update( +void MasterExposureController::update( spinnaker_camera_driver::Camera * cam, const std::shared_ptr & img) { @@ -206,11 +205,6 @@ void IndividualExposureController::update( if (currentGain_ == std::numeric_limits::lowest()) { currentGain_ = img->gain_; } -#if 0 - LOG_INFO( - "img: " << img->exposureTime_ << "/" << currentExposureTime_ << " gain: " << img->gain_ << "/" - << currentGain_ << " brightness: " << b); -#endif // check if the reported exposure and brightness settings // match ours. That means the changes have taken effect @@ -244,7 +238,7 @@ void IndividualExposureController::update( } } -void IndividualExposureController::addCamera( +void MasterExposureController::addCamera( const std::shared_ptr & cam) { cameraName_ = cam->getName(); diff --git a/spinnaker_synchronized_camera_driver/src/synchronized_camera_driver.cpp b/spinnaker_synchronized_camera_driver/src/synchronized_camera_driver.cpp index c915e8bc..c088921f 100644 --- a/spinnaker_synchronized_camera_driver/src/synchronized_camera_driver.cpp +++ b/spinnaker_synchronized_camera_driver/src/synchronized_camera_driver.cpp @@ -101,6 +101,10 @@ void SynchronizedCameraDriver::createExposureControllers() BOMB_OUT("no controller type specified for controller " << c); } } + // allow the exposure controllers to link to each other. + for (auto & c : exposureControllers_) { + c.second->link(exposureControllers_); + } } void SynchronizedCameraDriver::createCameras() From 1b5a9d0eaf11ebfac0402c1c3d713d2a0d5bce9b Mon Sep 17 00:00:00 2001 From: Bernd Pfrommer Date: Thu, 18 Apr 2024 12:12:05 -0400 Subject: [PATCH 3/3] updated docs for sync driver, switch to RST --- README.md | 38 -- README.rst | 1 + doc/Makefile | 20 + doc/conf.py | 52 +++ doc/flir.png | Bin 0 -> 538630 bytes doc/index.rst | 88 ++++ spinnaker_camera_driver/README.md | 269 ------------ spinnaker_camera_driver/README.rst | 1 + spinnaker_camera_driver/doc/conf.py | 54 +++ spinnaker_camera_driver/doc/index.rst | 397 ++++++++++++++++++ .../docs/camera_configuration_files.md | 49 --- .../docs/linux_setup_flir.md | 42 -- spinnaker_camera_driver/rosdoc2.yaml | 42 ++ .../README.md | 99 ----- .../README.rst | 1 + .../doc/conf.py | 54 +++ .../doc/index.rst | 156 +++++++ 17 files changed, 866 insertions(+), 497 deletions(-) delete mode 100644 README.md create mode 120000 README.rst create mode 100644 doc/Makefile create mode 100644 doc/conf.py create mode 100644 doc/flir.png create mode 100644 doc/index.rst delete mode 100644 spinnaker_camera_driver/README.md create mode 120000 spinnaker_camera_driver/README.rst create mode 100644 spinnaker_camera_driver/doc/conf.py create mode 100644 spinnaker_camera_driver/doc/index.rst delete mode 100644 spinnaker_camera_driver/docs/camera_configuration_files.md delete mode 100644 spinnaker_camera_driver/docs/linux_setup_flir.md create mode 100644 spinnaker_camera_driver/rosdoc2.yaml delete mode 100644 spinnaker_synchronized_camera_driver/README.md create mode 120000 spinnaker_synchronized_camera_driver/README.rst create mode 100644 spinnaker_synchronized_camera_driver/doc/conf.py create mode 100644 spinnaker_synchronized_camera_driver/doc/index.rst diff --git a/README.md b/README.md deleted file mode 100644 index c213a516..00000000 --- a/README.md +++ /dev/null @@ -1,38 +0,0 @@ -# flir_camera_driver - -This repository contains ROS packages for machine vision cameras made by Teledyne/FLIR (formerly known as PointGrey). - -## Packages - -### spinnaker_camera_driver -A camera driver supporting USB3 and GIGE cameras and has been -successfully used for Blackfly, Blackfly S, Chameleon, and Grasshopper -cameras, but should work with any FLIR camera that supports the -Spinnaker SDK. See the -[spinnaker_camera_driver](spinnaker_camera_driver/README.md) for more. -This software is issued under the Apache License Version 2.0 and BSD.\ -Build status: -[![Build Status](https://build.ros2.org/buildStatus/icon?job=Hbin_uJ64__spinnaker_camera_driver__ubuntu_jammy_amd64__binary&subject=Humble)](https://build.ros2.org/job/Hbin_uJ64__spinnaker_camera_driver__ubuntu_jammy_amd64__binary/) -[![Build Status](https://build.ros2.org/buildStatus/icon?job=Ibin_uJ64__spinnaker_camera_driver__ubuntu_jammy_amd64__binary&subject=Iron)](https://build.ros2.org/job/Ibin_uJ64__spinnaker_camera_driver__ubuntu_jammy_amd64__binary/) - -### spinnaker_synchronized_camera_driver -Based on the spinnaker\_camera\_driver package, this driver is specifically designed for cameras hardware triggered by an external signal. Images triggered by the same external pulse will have identical ROS header time stamps. See the [spinnaker_synchronized_camera_driver](spinnaker_synchronized_camera_driver/README.md) for more.\ -Build status: -[![Build Status](https://build.ros2.org/buildStatus/icon?job=Hbin_uJ64__spinnaker_synchronized_camera_driver__ubuntu_jammy_amd64__binary&subject=Humble)](https://build.ros2.org/job/Hbin_uJ64__spinnaker_synchronized_camera_driver__ubuntu_jammy_amd64__binary/) -[![Build Status](https://build.ros2.org/buildStatus/icon?job=Ibin_uJ64__spinnaker_synchronized_camera_driver__ubuntu_jammy_amd64__binary&subject=Iron)](https://build.ros2.org/job/Ibin_uJ64__spinnaker_synchronized_camera_driver__ubuntu_jammy_amd64__binary/) - -### flir_camera_description -Package with [meshes and urdf](flir_camera_description/README.md) files. -This software is released under a BSD license.\ -Build status: -[![Build Status](https://build.ros2.org/buildStatus/icon?job=Hbin_uJ64__flir_camera_description__ubuntu_jammy_amd64__binary&subject=Humble)](https://build.ros2.org/job/Hbin_uJ64__flir_camera_description__ubuntu_jammy_amd64__binary/) -[![Build Status](https://build.ros2.org/buildStatus/icon?job=Ibin_uJ64__flir_camera_description__ubuntu_jammy_amd64__binary&subject=Iron)](https://build.ros2.org/job/Ibin_uJ64__flir_camera_description__ubuntu_jammy_amd64__binary/) - -### flir_camera_msgs -Package with with [image exposure and control messages](flir_camera_msgs/README.md). -These are used by the [spinnaker_camera_driver](spinnaker_camera_driver/README.md). -This software is issued under the Apache License Version 2.0.\ -Build status: -[![Build Status](https://build.ros2.org/buildStatus/icon?job=Hbin_uJ64__flir_camera_msgs__ubuntu_jammy_amd64__binary&subject=Humble)](https://build.ros2.org/job/Hbin_uJ64__flir_camera_msgs__ubuntu_jammy_amd64__binary/) -[![Build Status](https://build.ros2.org/buildStatus/icon?job=Ibin_uJ64__flir_camera_msgs__ubuntu_jammy_amd64__binary&subject=Iron)](https://build.ros2.org/job/Ibin_uJ64__flir_camera_msgs__ubuntu_jammy_amd64__binary/) - diff --git a/README.rst b/README.rst new file mode 120000 index 00000000..176d9c26 --- /dev/null +++ b/README.rst @@ -0,0 +1 @@ +doc/index.rst \ No newline at end of file diff --git a/doc/Makefile b/doc/Makefile new file mode 100644 index 00000000..d4bb2cbb --- /dev/null +++ b/doc/Makefile @@ -0,0 +1,20 @@ +# Minimal makefile for Sphinx documentation +# + +# You can set these variables from the command line, and also +# from the environment for the first two. +SPHINXOPTS ?= +SPHINXBUILD ?= sphinx-build +SOURCEDIR = . +BUILDDIR = _build + +# Put it first so that "make" without argument is like "make help". +help: + @$(SPHINXBUILD) -M help "$(SOURCEDIR)" "$(BUILDDIR)" $(SPHINXOPTS) $(O) + +.PHONY: help Makefile + +# Catch-all target: route all unknown targets to Sphinx using the new +# "make mode" option. $(O) is meant as a shortcut for $(SPHINXOPTS). +%: Makefile + @$(SPHINXBUILD) -M $@ "$(SOURCEDIR)" "$(BUILDDIR)" $(SPHINXOPTS) $(O) diff --git a/doc/conf.py b/doc/conf.py new file mode 100644 index 00000000..24f848e2 --- /dev/null +++ b/doc/conf.py @@ -0,0 +1,52 @@ +# Configuration file for the Sphinx documentation builder. +# +# This file only contains a selection of the most common options. For a full +# list see the documentation: +# https://www.sphinx-doc.org/en/master/usage/configuration.html + +# -- Path setup -------------------------------------------------------------- + +# If extensions (or modules to document with autodoc) are in another directory, +# add these directories to sys.path here. If the directory is relative to the +# documentation root, use os.path.abspath to make it absolute, like shown here. +# +# import os +# import sys +# sys.path.insert(0, os.path.abspath('.')) + + +# -- Project information ----------------------------------------------------- + +project = 'FLIR camera drivers' +copyright = '2024, Bernd Pfrommer' +author = 'Bernd Pfrommer' + + +# -- General configuration --------------------------------------------------- + +# Add any Sphinx extension module names here, as strings. They can be +# extensions coming with Sphinx (named 'sphinx.ext.*') or your custom +# ones. +extensions = [ +] + +# Add any paths that contain templates here, relative to this directory. +templates_path = ['_templates'] + +# List of patterns, relative to source directory, that match files and +# directories to ignore when looking for source files. +# This pattern also affects html_static_path and html_extra_path. +exclude_patterns = ['_build', 'Thumbs.db', '.DS_Store'] + + +# -- Options for HTML output ------------------------------------------------- + +# The theme to use for HTML and HTML Help pages. See the documentation for +# a list of builtin themes. +# +html_theme = 'alabaster' + +# Add any paths that contain custom static files (such as style sheets) here, +# relative to this directory. They are copied after the builtin static files, +# so a file named "default.css" will overwrite the builtin "default.css". +html_static_path = ['_static'] \ No newline at end of file diff --git a/doc/flir.png b/doc/flir.png new file mode 100644 index 0000000000000000000000000000000000000000..9bd8af2f8f496103322dd2ed0eb10fc2cfeb23ce GIT binary patch literal 538630 zcmeFZWpErzwl&&fX31i-n3johcV%QnRCa`lvJ46$0U`hZK#`M`R09AY7vC>qc-Z%zT6t_@ z0DyJCOGC$1&BTMu(b>V=$`(ZC`o$4M2J*Br2LL>mtG?+beCA64y?u|=gUn4!4N@)i zm>N5GF*#G@PgK>VngK$~HE-gR9eQTRo*nT+{XYdue z^v$dJbpI-V{F?lBbIorQH<=UH{&F)q|JpKT@l80i=F^%{^Q~K+WzKN_g6PTviS^EA zcXa6=E&rUTbAMg?(_x~Ym+8ruU+y`kjowQ1n7eIsrFeR?k|t($>h8zYgmFLTD72n4 z_=#M+xRh6JP7o9?MG#y>u=%ZO&A!p0zRu^6a}Ogyb>9T-e~PLM6wi$_@BXwWl%sq6 zw7=cub2gIhRO6oxtPmlMd-0BZq`~f@eu!a`b~(rC{wXYWkMIBZ(BhjCcnEJuwYDLF)*W{MBj%I1`ZI2w`oUXr-hW)`wM*ss;qm##YnbWTGvBA1 z{H;Uf;T3#!efj8X)8+p38~F5keQ9*b`!2y!#Dw)Aq!1mmhNp z#S!RuU2P9$>AV(_%*UST)yEWp_m3H|fA_8^?}GmuK+CSs|9&SY&i^ga-~XHDcEmb$ z&5K@RjsyI)0M+ZE_$jGy>s$Z!b`EpHtDlW(^MyXJxds$_c-`VF=KL00u=UpR?xtKx zD9^(v%`f(7mO{q$if0(QGY>_!HyG*%B(<&e@B0olE=}Er7g?rnn-+_Mex#}*>#l!p zdXRH6pI#ppYObzP)+haYQuQ6yS?k2_UjlN_-*TLO`+UcgcLiNdj)-`S&i#>8M9U(K zv(093H{1C72(x(Ij3(cmPZIp>H}#qfd-$C4;lYR@eP%&_dvam_G2!<3M|UTAO%0Ea z%yZ76x}Udl-VmG*vxdK6shQ9j)a4jf4j z0PyZ9!Tf0(W*hC%9xchglf?C8U8H^8b*lU7Bo68E`Fj7un~(3Gv&oCMy&mspw4Nt& zidPEym7E_o`$h_H5}pAa4>pJXKXR^6KJK1>3Vt5mzT^>qJ`FlO9?HtUx}%Y=d;F;B zm&kW_=Dscj2Vo;tlf=UHK>egWaw!f;Hh9<6cmCro-GAYZaPLa5dGN|X$Mnj(cLTQg zGp^dANigBWlQ&Gl^ayvwvt1Ko*RWnC`mz@=`H#TopvkS+m|Z=0qQmt37Xk&(oZsvF zRa5sn#GYj^%pW|*L|)zBRukVc*U#2&Mze2Ignd3N8iv9sna$>OM8Z7e-X#uhHm@6v zy$K{m=npz)>9c{cW;zw8Tco=+E$!a#P>rgvDs zyd=3E34M_kQa*8dS=)~(NR)+vLLwOSt4Z`Ee7cP(j=HJN{Bcl^!i=Ik!4)lLx7H-O zG~=GpygTJE{mUxEMLvh-iwDQ?po(qWYTAjPX{N_IqEM)o3$%(i#4UTjsn<~h%-Wz_ z(r0_yp<)FMM#+^75bUzNY26U9fc!1ZCT9T?9V*`1gt5e8}nHpyczjRG(@{b zpR~i(-glWYrWN+M`Cc;14?oq~_gSk2AQ`M(u4GK;xo^EWAX1(;^%&m_pCW36j5APK ze@@U}@RmZ~kjQ%M&6(1-vxJ1@M8$)Ne3lsOS1rb>vzFAXHSgMOOzWIi01Jy8ci4o$ zdYM&=Voa_{SHD`wD+VqOt+K~$uU^}* zE_Fv?c9}VKd4}R{xcUT`cV)A#V@~t=u7{*CanIQc4F)McCw#Hoqtm9r)9whTeRwAtd@k7GTnNOiG3s9y) zb2qPL(8+GY5t$r;o$Yam!wZ z{^?m_TXGb2C@DfrV>*l6Xs_6tzNOLv2QEi4Lu#FPL3m}%BABI``4LmrT#cO$0E^hxB@C|C; zy?#Qz5S}F|#{+`f}OSj%yJ6)ts+2!CA_Mv4_)naT~9pINi6plKpXIIP| zCxOzg^GJw%D{o9~s~cZ-PF74O=tjrswlwD%d{5Z6mjGC0dpedgE*>gek1!u((M85! z7Qv8UDAwt3R@_MT_C6^_ty=L6^9Y?9{@^-iCWGz1vIP6j=@(Z8&M|s-M>LIHKkT%w z1IaRu+a_I#pgrl8`cBQ4;s6!_DqVrhLOJ|#q-_!25W>H_)3GS}R;^5|N>>(v)E8)(;#SnSkyPG?uUNCmn=+Rh5Ds8T+9znUJJk zgt0am?nw6l9l6{ah2qSpgHs60{S0W3ajgI%jD>ite)h$bBs3bR6IMFeuVV6!qwYtQ z6i9|Dh^hKfaQQv07@|DI$lc)RVE9=co;DvTNHkdMLcCyZX>%_%&KCiuOg~YegdOBEHBz=+5?l#-Xp){4!Na>&0 zRXXpb^YhrLn|dD)HtLIwF^UL(qd7g|pH&_tKt*1Th1fH?&zG37LOKY0<49t9z={{7 z>3D|n16e7>eMsrQaXrK3N8IFet#1%((AAZhF0<_j1cuu!C;|rX39yE}cyd*ou=yiH zRF*@)B-hBcV}Vgo3MTThUq2$^aHv8e>u9_%MF4o%^Tvn9%-ieH(wDJ5gV3N%rKw!m%PZZT`cW##T<^Yv~n_@+^Xe;zqXo#0x%0L4E;1`^RPytX8ox8 z_%Ngf%nedUpc_R!?JL9JJ^d0Wf{wQW#E*ycfE!LA1Aergo)Cky2abM&|8=O+V^u(EEas_pi9C<#!w|vbeet6bF>uc1 zT!S@GIkAImR?cm$6>igSr59K(sgX9K7cdqiFNUorNq_t+w;wp+x!#J z_0#R*Pc|4h$t=rROAS?(@)X6V0oQN(vdJl)w}7n2R*mTJCD04g0-6%9K3mj0z(lW) z7o*=Q3V~3M@emdY4?w*$;(Jyo0BQ9Ue;c`@CEYt1co4>zF7Pd+l?&!lunSJ?Gr=S7 zJjEj-bt!d9kIqViSu+#i0@}xe1kcjVnJGld!`9zlvpT>3P^9hV4?y*$=%W&z4k93E z{iY5su*-kIC6Bn!hx|~D?!B6js_ZeHXniM-cqQ#o6^NV0KgCfpP+!54+cva ze)JRvpG%Q!!GDIa)J0CC+VF(r$3Ik!LGPUYZD=VhNgjoNEA<_FGz^M7Aa9#hDpx-h z(XEoJA(RlN3E>CIA(+}Kpwn_<_UAzN1rtH(NAHHsFCX@}4-;s407%JkA@P0|A85?g z5l~LZK2g*SB@R0xY!>fY99m3edEDbfLCp6VVfvG|@q{O_|u;|PI& ztw@;D9bGvXV~7byL`Hhv%d)OV+<=UhI6oMi~uLJf(XUvtN7 zD6N382U~$m66+TQ2^bZ52D`0f6?srsER3~=<{{uEAZiuU(h^N8w-=0|9+9l#1`#DG z=@FI~^a!tPibG-pHGV+TlNA;%>0_K%;PY`nU4sWaH)6l1<2QGveg~0;egwpZW!s zr={->TcE0dAA7cp%4nsW+Mv4Sk?o}wGDb`Dvv~e!E(3Kb$ zL=y3|id13pT%VTv4C=8U+pFBrmZM7*EPB>pf?I|vy?q6q>8cwwLI6t!Eb|m{IJSg` zbO(oCG?*ko>mXya76F`_B#9@6!2XIw$hhIGA7~NN!JUHv;ia235@lKwOa%!HK~fjKd$f^3(gl+L)J6&!WOo{J4CIuLt& z-yN7peNY_UNK;v1UJUILlDQlbEiWIp{8Gtnl3IR-K(&-3mbS99igeA1A|8#8x@rtKNO!1 zDEWqLyU298sTKaP)v=RjmDiw8i+En?5Q9}rH+$pMSd1pzNRkw7l8Z(-OZRYbEBc#R z73K7T))JJ#sca#>?l8v`4i|+(-b#B>y?SRQrX-|!$bCi>qLm&z=Rts^fsU#u#m6*? z$QT$!S%#SaqIFt7E38BZs{yT@SRD{J%;(RddU8H13q1L6gTb~h0+F7(!5)5aJs1>gu}# zU%&o=-rh)I!vL;8(nBiM(X;f01)^6&W3wVclA|?RU_!4DDJ37$*-)*9d>R#g)Q{Z~ z-$Lq}VAKiZE%_t+QA$O?3uqut^iw!ONQ?wY05TMDI}E&X^_3(dn1(`haD@THyu{~&`0_#qn!suwyIeL|6x`btMcjdCJq#7qo1N&x2TW!s)CD9f`Mcb#KajoH8#^ zoPv}cX^mOEDE+C(a4Q0ybPFNCQ9SLk9u4J3UUI>4KyWhxO`yU&5lVR5#u`zSp_x=D zdzqte1W7<5UeR!Q%4n``A{Xm9u6jVnFdd)|d4$zS8q$r^jun?Bmb>gx2TCqj*Z`tz zO#{2v|4AnzGI6x_%e030=?G#^XlTy5Cra*z{05_mzNJR4@cxG_(} zxivjAFNoVD&Cjx!^`}9a<+45P<-5k#7vEd8K?u{ao}u1Nkzo7ga41=X(%WE8=wUTF zbFp>L$fJ)o3g(c8#*7L?Q=}LM=&hEE)?}(*dwwS9Ha9u`8k;>$ix|uZxhkMK!}!^a zyU`F!OPm*^1arT!1km|<&zr>+B!D8mP?d)G2>&>NNtqxK!e@$RIBg$Nj^IcPmO04h zAQ)TvUOx&@NGr>it|es@c{7J(v!F!Wk)*Y(w;O3EQ!e=g=B+d@f6cFh#}?$$c1^tztkA6>F!73Npd<)FMXYr#x|Ctv2?5t+TFnsd{q^K z2`6N2!wd}JrH1j02a21~tn#x-jxR++uLSfTNonK}rJWRcVLYCwdsz!Km4i{mK!p@I zlWv+cLtGAa4n4^bWojek#khu8%Lceo)dFR+U{@KUYANU~``|anZ4%8rT)LbR%!=LU z;VI@%p1%>pabP|>St>ezxB|Svp2L@$;ksd(fJfzVWaEW=1SR`UO!f8o7l~%^zKQC6 zgBO*NaV`je*dIygci$mq>-s8d`4*ljhDqp&8xAau**K9z1R%ALbFhvch&amK6a+H` z?Dv=<3lZSs25<`G3B8dd+m&`lpvuBmV>o#{BS%t9)M+r7nja0|4i7dwbEcut)+q*Tn1amm19tN}{psmU@YCMkV%xyz$E)MXBso+kUb zC%^+?3P`%J`~GPKNO5lPuK8@RLq-9E!E>XaMto}EP-;Gn91KK*RsWrM=mnPS7v?Ev zM_q=BLa58GnC>!&jU{?u`HZdk0~l{eBzIDGwq~fRw-%y1I8jX|_7cinRv$~##ihRj zYr_EPSDb;&_+4~ikYPJh0Cz^lClA#Gd=v12DB6B>ss12Aa9pWUze+pC?(c?f8V#TJ zq!xx?LWc2+bR0|Qar3LZQZSWvRC#Vo{xRm_@`gDOW-lY>3<5!e8woSN0t!YB6(@uG zPBWZ9rd_y{odVr8yuA2IV(J-6L&@C5x`yP_F#-j2SgEmDj2Kcdq%q1+`z)YPa)!r~ zaJvZvEf}7o`NE932RjIwImtH?qFZ} z32D;)!ZZ1ruZ27d!7@0Ki#AmnZ?k0nj0oD3k7R7*6k zxcg@_Q(lS}_Snh{nsyLTU|LFFj!J9=Vy`)hG?*gbLt4#S;H6Z4*y0l=BuT3) zMj?w6FnK#*TevxJtAv{%db##?JOTZ+09$pw>m}vvK{I>PG!Ic6gabXfIV#L$Qe(=IvFdI?w zmG@P-S6eO$kx&Et0HjAd=V(4*YvMWXkJHugPbcie8g^ZY!IvWsj85Uo@@XxFDKMN3 z+-F8rVY^7^V{%`P?aIQ;@)_@ zb~^yR5gFjXhmF=+^l){F>e6;-wVt%K?J43KoY2DIJ4493lV0eJAixaxHf#A@M#97L zQ)aNEOYrYtYsXj?_Wp&>_VgampY5J(*=u2S;MS^(**HxNtczNuWGh-R)VBB=&4vmI z^6heSOM*@s#yTi(qA0BdU^mt+mwVB@gW#59KolxM@&~-HH{;I zMMYH&qfFRt)|(t7n1zDhsfdv^%i39#jbC`Vdgd7T?dgGVyvhZ<*#O7$_p(TF<^x#I#o99r8BH zMelSA2xB{Qq!hTX29kcG@U^@j@0SWN7RB_BQVN$6h))c*JWZa8sr}gAc!T5-=81li zOXvFds576$Fc1rg%_>qJ*us-UY@0VzN3bR;*U;tZimC0058vTxgJ<9ftoX=SAk}<( zWpo=Rfi4kg2@4+v1B_N}52SV0g1S;@p|1HrPOIWqrHyrD$#ebr4^U#eD99;3l*|mg z%dU~F>W}Lf>&Uz;Efr4nYfW&^R$v9L&mZ#-I`Rm#Z~Opqt1vQI4F=NU&j49Au419F zJbr@1z+g@M4aQ(C3F<$cvfP|+;tL6$EjtySFwP;)pLnP>=~J`?AoU8IaC!az*bHd9 zvG8CHL4Cz0jXnCPBEill8 z_(<_lo+x7zgVpCKQo=I#mqt6VrBDZX9D}V8Hm|U{J6Cyjf<1{*Ne9&C+Nh%O2Sjoi z-ba~xT*xJgxuO^Fr9h!W&eFS`{&S3M(iV+8Eg7lM#oWf`10c$!%rawF>k_YV~V&m3oAb;npt9Uh6^CLMbnF@mbNQJ9Mg1Wa7} zqe4QXTsE~0z`i2DzBDth{QC#HaL{lqg*+Y!w9eGGVy$fVZ<1&!vyOoW$fiV}7_;<^ zwLh2>C$d%7U=FmX3V$rC`ef>Yg#g5v>b|6)XZ%COR!-c{DLRzz=To=aRZag*Z)WXn z3sm|ngoj0s0Y1B0LnnH*`)Z>QhSq|je}tQ2Oztz)xjgwp!N4*3&auDp<4VOASH2Xr z@1td9L`FFG8T=~ebclA9Zw-tajooR%#9S_%EV*bZI2&Z14g6%ZK3!p6M*9;Tkxrbz z%sNwvAWg2I`BnL-&Zf0l_xn!X|JPPY^~G^6 zyit=`q-q|vF?0v@;46C!6=e@VS2wU=6|_eh=u{qwi4Zldc<5;V4O#x4B48nrC){w( znm$2Q$P2owvEn;tpb2IQjB2@F6+u7+sp?Di#(=7k!#>GES8|;6QsBOIb|{TvRihG& z#|83XvB=lqO1%jnf6sXPOoaqdZ`|@WydKWIK=}8alvvAL@E_4LUjgv4tV~BmNG1O$ zp*f)<6a{BgQOQ{<0=jY@MFAG9`B(*>arw6m=V#wbM1D=hu6cc4B{! zCVO+!JUhEsR#I)OA;g`FkfW#7u^VEVkpYP9bAJs!x23N;Y3h%4%Uy;cwNwp_ZjMh& z#~*;u#kX4njgESG9p+4G7v(UMRC_5Anh@eFeUI?Dafrbjp$j&ADx2j`v>J1b1+PHo zL7N30Ut71<>V*frmZ=|77_fNAnsbnPZ~}wBtyv+cP_b~`-K41xkF4RXv&FVhM{wcgigik^xULMhG~QYLg;HyZ{1 zS>$Q5D)b;wG? zaVVEKK`AxDG21CQgsmsO9rsl|a=d$-gkNoBqUIQZDR;_`9c-0vh1$QHGGIY_h7}%S zNR%ahbk9(AQEVtv`1>Vxp>;!_kLJFfh_XdoT~Jd#1?Zuu=dE5hkZ8FX$kx_1(m}Q4 z6S!z-Q&>~}Y4{cJX!5ntl@?#{lHSjkz>d-YJ`Rj84c!ups)2%zr{;#M(ovpVahav+ zdav=a=$EIP*j%pcqCv=hS4u8VSS2Twz3Zvx{iB#!GAlrZ&$ZkPCRdgm;kJ{1d^RpA zlAxF0+OUxXdX-!qoE!n`oRY}RAj-wCWRsbv5W#)Qg}Df)Az8lWD@H*{#Teh<hm;vopUu;)NJBy)fKeBTPO3pA#9*%qZd3Sx$kMgPV@8 zFTR>k8H+ai5#U^^8abN;FB567&@bxY+&Aw0IX=-mfn~!AGELw{)0HLI08A+Ox>i$;A{I`X#}7o^a+|#U~JgRm}tNK(IL;wYnR{= z9y5S{zL`2XdY}{2z7}V9&8-n*FSpQ57n>C_51_6tApC6^A`7W~8II z7D>qCEu#ZI3Tl+d^(O90W>mccVlUAW|nxe(rw+TEoHX>zZ+B)CjQ&+rsWh}n3f$H3stBBB3hf$j%&+T(6#J^zXQ^y zdGHA=it(ea!HbZeTA}^t5y3TwHIExYnGCX7*4$*+f&siGZiWUa<3dd6TT$ec+&F1o=Ty>aAPoL^#{-Pl<0+N4Cg9t4luin59$^h3?kE{ed6)o!Vq6BehwZQ7`_lBf?g9;vHj5c^3o=<@XYF{gz^hcs7G z4Qm@`ZFZ0E5#Crl@6MhU@fVwyCPIAYKKQHEkAORcYLpwHg;{iRRedHv%8zd~Wq6`8 zmc2kRw;+S5sqot(b;JYYxZg6Q30P_d+ekc{Ox5Xgp`Rejb+POk_otiiQe#4|lo5$o zzN7rfbS!m7C!?5Bm zMUv)}#dx*6FU`MEH!UG*Vlij4$gd^k%v!S6U2nZ~bP&ZT-iZm9C1)ibsGeu^A@QJR z=QK^H5xXGFdm0Lphe!H*RIK}1aSf5!9haSX6ztr7S)E9N6f;Zieb|EgouDLlc1Vb{ z88DevuuZ+)a8dN8&iLCJcMZ2z2p6Te`Uk363ESoENvFe=WT*;FGxdFeZ;eL8DF-Sh z+eelej|`5-99A+eGIl(DUDo{21n5lsIvEB0`LnW6! zgJo+f{^8%S3L*Fu90abVr*Fp^$R=(PGF&Xdfj454xd(W(m&LL8oD^N?Z4eT!k1`P8 z(I4c+W5bG0^)eE$qc6=l13LqSiHR$Zno;BJs*UBtR3=04O2pfmMs}jrUmx_7bFz<| zma#gqrWM^WL*W^SF+KOG!|kDe3!kUmtA3J1AQkUkq3Ej|%`qjff0Pbw!j)So6*k3x zDYbz}j)`)I%wFL-^N2^eZ4>#GAzO*lt&#nERPk5HHfw|2*&hak$q7LgY2#v}F%Br6Uc5^Im2DCStN%>9Xq@ad zS|Vwn+avy%udC6jB?HCUuc--!WYj!mB(=wml(b+%q2e87vLi`5BE3K*xIObkAOy=@ zxyIk$&L&X#x&YKvT65-(secaJ!R)O+Jn4}lBQnbx5LM7)ihm^PA%~jlgm;k`=0~|# zR+)F7ek|wC_Bb;M5};&q_{i479F5!(0@%%wLAjNqq1lO3Gb7qjw1ph_q|W;&tJG4H zW&t;tG8c9^Ar5=9W0HTb(d)gVXH5)>99;QGd20Dc)><5D$t6c_@0KS1!w95@@R?X8 zs@Orzn6Kf|2cv~wzw7`OmAgs%bn|xwMUnj1iK@mz?i(ni(OE!(X8=S_H~Xhqw$JJn zx?;5-#|on@eogQ;|JKkGp%;a{caK++3e(K|byq+}huf^-%8FIp6A1x#K;&!-HZZ~n_3GUOxRgo(I7_X^gNgC4siL~tcD|Jl;w_e+lB@hU z)*$zvw@@MYL0UYM>R~&;49?}JBn!p-B`s~iAMu3Y2tLfB8j*OJTh^b6SgtsavZC)K z8D=m683G!xICVOvGq`P1`O_|5WQ=Crjj^-#f9a}a9pT(*+xd~2e0RV7Ecwk(dA8Tf zIs{tYmAj-XP#~S*8ndw0S&Hv?F_T+w8fwws*NM2py|wW7Q6l$gm-R7LXn^S-UplgT z>l%+&cxR zbY(BVLhwUc=jC2Ik`;9P`jZEdRe!`t192PM1-806B{h{jBAh>bu0H?MbBdNV2^g#_ z^dNYkY{_8^rZJuWO7^FC;+~AGU2k3UVEXQ~R7<(fHkz4PS6I#KtQ?n^6i4%CJF04~ zf#8=o;@R1vpAwA{U|q1)4Ecw-=uNS#Gx3~}#(dUID&#U{u*K(ZkK`Dzo|Z(JZBU7~ z1&txG?uo3Vp6)Zi(YtcaY6k+u;sTUp9^yunAGzz5LqDoXoHa+kQiipgM5?T+@H+Ki zTHK(Zxw$V%KU0viuuU9XfFxq-l)@m0zbZKH=1C|Y#h;WP)L+G*-(o@qb3WcU>sB_A zY3sOYw3X@)4;K5#MNf<%LsRF~&N&V#ijp0zQ`mxfLq$7Lg_UWYswXx|A%{$%ye&G0 z1YN`X_xqH@GUe}UBjTkpiVBpeEoa9oWR4Gf+|-}Iil_mi*hE_*wss}Q?Syr|48scP zNplkz%XS0~(LPdejO?=-3xato8k-DjJ>+u^9KAGY2-6a7P~uQ=;)dY)2?}GWl7sY> zWXlbF?!T>l;$LJ!`=IIb%gJ|6DZyHhzFjZN%$DXv11V%3Zy*{`Q-LY{XWiYW?|e_a zBAQGB%R+Yyl2#sjx>D3otwJNGvsCeJYZOAPnn{-aMlxF$vx~;@s80DDZE4U(yGC== zWrWk|^WR({p~gw3IAf9S=%xmHWhp)8ynfmEQ7K${IXGk^xs!Mr9K0Hce=l6#SsL9u zcU39iveG5)-svieo{jk3bOiI`rl2avBa%8k)%tpmU{R6f2`ScCDnKi_Hh$IztoSsm z?k7F^67=BHnQUz>9VRZw?}zbcl?2j+nBe9+ZcZB%mWCjm%(vXC$v?^tw=^~R+~I0d zDTf+_r()>!wu|GD4V(R(f6_`Q+F{_sIq!fm{G{lHM;E?AH+Z;|I7xzcplbF87sVN# z!v+}`l@?eNC=d@3rTSJ$?B&tP#Pz4_@zio6rOaLaq-GNoJ0v;{TVK1Qgb)(7LZ()FsEzJ!#9w~*M>HwVYd0T`HPv}-mQ3K3IRnla_TV0W|CZFM2!)U(sGOux z)+GT#wR*gN4=U5(VVu{7X(=D~!Dcy4bNE8l?Mt^F|6(PHVNF4j64g(k#{H6tr!C~E z$T`xR`CQ^!eR`~~74(94jY?tBakuTQxwp|?Jz8b5)67ZVb3%L6_;sw0Gg$+Mqx=Jl zGwIO|CKT1uXvZn7E4p}4g}}Xl=tOttwysdA^^(F1Rl)*f|KxcHyV$N=Tv>$XT~A<` z8YYY+%EYlP#7MrKfN#mfQ>>^j9MXp=r)hFoP_bZOO`38xmU~^Mp%EQ;(30NL>Is^o zd3H4q6^fnmH2x2hO_d9|FV1J}JApW%vgG#4ImtV-{MPz%!J%_=JA^I|FW+tm4@LP> zRH?PDbAm*5f5?{Z8bxrlNDZ8jF@$fC>;O;hr@bEAlgb*G8CWjc0+u_7yFH*&7HV}g zb^i!|c>~xgfCn#xv#W^|$+Jvl$kfu?OC%k|7E=oT>%HL&QQv3AbI)wXjok zGAQ}}o9ApH5~hf=!R397%P1(oVrbmfJeF6QF@;~}&{&I`YfEmcrTj37Wk*np&%tTF zoNK;~#^0ncmxaYCYY$ybr-yTw-62^ey)|b)+c10#Z8mi>+wT z$z$)^hKEDd)<8=twj87ZOYAipa@&+y^) zP`C?rN=s189^e2P32u-!;tY1A)W%D67aiK4bx5HK!*#uVUSB}nY{efGM@RVRBwFvE z`>U&2zE91?bKRutPtLae_XBzF=T2U%-p`llC@J!rIoL6q03A$0%$|0R@8?ed06`H? zM-wv}kSm!f$im8Ah~m7xn}W;=C`6&nrNpY_C;_sxlJ#;1se37Fn0eWl@c}7Bgb@Wj z`QHibK&~cao_4nOF8rQC6o2#bzu*7W%|b!;H^kLOh(bq6g-pW18AQg(%*o8kB;{%4 z&Q2kWNG9kEH0M{7l>R5hdrOGI($&?GpM}N4!-Ls_gW18^f`yHbkB^0worRs9=^er3 z^2OfO#FNS1<>Oxz|KN}WxtKXyIl5Xo*pvOmX=3W&<|;%%@jg!WU;f!SDk=So-rnV( zD!l8#;%VZ@!p6+XVrR$l?-nkuQtt00|8(g8XyKyqeoTi&4dmkB=4=L%atGPFe*AX| zpxM9d9o?L5{|*Oe#sabh*}X$u-e+a|k11v3lvMs@@s|V^R(6hmTfK|@A4pd#^Zyp> zKYaUZECr z;pAXtXW}q1HDlsr=ip;9VFmIrneqXFKrU_|uPH0=->Bs5U0hA<%|L%qy^}Lrz4P#} zva_0*vx1m-Sk3vEI9W|Nn0Pr%d6|H0Y`mN%oTl7BPVRrB_~dN$UX>=c|L)aaRKRyC zE?#aEE)Fw3CSER65ECbeo14kh{QZvmy~)nW!2#qj=lGinXvQz?;B05|o=z(}6AKWF zqrJu71Aht5FQy_VM8VF?`rkb&wkEFT?*>8?idOb+p8q|dVPywWcQyG-O*S4j4o)r( zR*v_Jmz9<6zd>3cXP5U%{EL%~m6_uoynm&I|2>#@VNL$3(|3ZuE#70{mv9D|xH>p% zI5^k}QT*i+*j+Gv*y)7PXB2A;}Nj6`g@3s?C-MWH!=Ii zBrYcIpnqiK-R>VlW|k)Q7NGa%`=15%U;S49hh&+7xPhkT9NbKt9PAuSoSdfSOne|y zP9`=EQy|xS>VUkgTz`l0FLoCPb5{=&XONi1d!+Btycf{l(U8&pEhXK5qCG4@f9b@^ z&dJ33&dRI7#>&sd$3=%?|20H5{`V+3xc)OlL6*N3uK!A^Aj|(N?f(G$+e-H?%|H6ySJ3wb zndM(A@;^2Et5W_i{{C5R{}*R?r~cnb{zv-$uU!8t*Z)X?{}K3qtLuN|`X4FqKLY=6 zb^ZS)7vg`v(}C>YH+mlLZ)}0+0|M`Fd$6VoGLnE>z$M_g^H4DPy$8WjR@VgpVE*{m z1>spF;{M(V=PIWp1$O|AiH1l)4Bi<50LTDxl42U3%PXDwlb|IxV(vY?Cm$nCH*HOi z`cdm~(8YknP$V%BJkU|R1Xf0g? z_8f)V$3dG#pt>!0dwY4;7@v0y-*qjscU9wpT~0Y55{cIJ<}Pb&&8B87%`BFW+IMUH zEjIU32Ft;Zx~?lEZ+o4xTN^;8;oBV!e)cYXei>hB6J(|JA(_4vlGM1jk9=hsTwt&7 z6wcrAdpYi#^psnpp+L|3d6zPT3XqKOjsxd^|0AM4o%NU#B0v)eA7Y~^FDBXd!cf%H z(Q-$NUbV1mw7;Hcq~AiF@bmoFLeVysf0u7Jst5<>YQ+;iXnXT~(2qLoI9BA>1g?B` zV|nywJ7Tx^O*oA{QlLx4G}31te?3V5Ai|QKb9|meVX3!X z!9~R(Bh`JqjTx6X&;QW6?s|12az)dHX1;df@}M_9tZ761dR)Ww+T5*Nq;Y?I&g6e~ z?0a;>wUr&_>|L=uQRB(n@{=*$;_@jR9zD4uCmcX6a_`>xc-=F()Ynx(xg4dz&vR{~ zv9x_*wC}H&^}?59_E67U6>=Z<_UhTS+&vWg;(9QSzxG+bO50&{Ab_tU;RX5Y;W5Xc!Ax<9nUl5TL95YNdoyg1(KOkiZA@Un@(rrx#Yvv?P zyd%4LNJj9C_n@*IgdZBQFf^JVB2@@gv;j@4=zBkR7Dn$ff98(|K>#i$8#t}xGnG+{ zn?Jad0CpD|{AAk7GJUYDKI_{UIyN0x|1v~e(0F|HVS9KpLIeo=GVu)4`&n6C4goqk zxJ$3jPla%x`i3_7AQP@pT3u-y_Rz)LdTG9c5tPW(VJByxi*A=SoMRvZ;oCP7MX^_r zG~n;Ob3J|0xN|?Q$LTHLL#;heu?XS%qm0!-1CpVv&}tR@UE+!TS-$E9l)=$0V?*dY zuRpJoY%IPx{~^GV4Ze9@Irda&kc9!WIzW}qtbHR@P|P$#WcSo*x-FR3O))Y;&G3d! z$m#Zb`F$QWTqF45L67+q;~{$$?LshZo03<*TLI_p>oVS#z!JAE+j)JfN-0pT;}g&( zM=a}_9MEy}8h5is{G~ber~IC(1!?suagj0gLo;bNEuQSW8PxXuOQ%3rRu2O@547Tg zO#?k_+p$f{T)R-f9A(yf46<_R)|WRwB=(D{;b$6C17wwGX2nbfQJ15 z9G@pGvtJ`f>ZM<=?$c-8>4PWYp0a=`wSiP&+KIEMNI(N}mk)GN`Fc)QPE@7_iPIjq zy(^%UUUZ!1+OkIlQWC*tEdowK)yL{m;dL1~ey5(N79)9Kj@$F?*^R1?DuW-;K50)4 zi2TJ>g2=$uX_w46eR?N%%{Rxx<_eY|UZlBG_63MbPUS)aQ+2WF>-2YRuD5{@H(n|V zBhT1SHY2ct4cyK+#66pCPEEN9Fk?Y!Y8R#)M8!W?2So+oj`P0i+|@vc+$OYKR#{ZSco_nq-Xa^>Q%j0lEZ!6U?4ObMyBd0qGNkxRw!l|!G=NDz zdIpf;Hz#mjAwFSe+#NDFBJoKj zm!fte{pjNH;5un0bD{Elmr@EzZ`bDVrM*WonTp_ZIJZ7~u#mU2l9wwgd_`4MTJI+l zdA>B;(^kTzAa5;5uq4;5HG~7|#fj%nK$i%|);`&X!(y`F=U4ebE{?VjdXr91y5-LD z#Q|o|>51iLQ8R+!5GC&TGepnyF`KRVY0KWCA2X9h>M4-2U}#5xltq^@>5g*~zXEhL3soP#6^<68zZmFP4b%rN*R~P2O=P~Zb9Hk+MlV#Z1 zf}Rld&i&9lX6vMdNuy`*AX<3QNN&mp@ydWz-my~J@o1+n~>(OvIVlGGoJGm0tc>ip!;d&ht zEJ2Z=xk zBOM62e66^a+c`@QMZrm!-U@bkcBEw)kdN*-aIJj=p-^RC%$ef0=Pi)B{h~j}qEfUi z)TSjePlP3ra9aPRXQXpuWQGwA2SzR2pz3ii$DF{Le3aLB^< z-*p|IK{X3~&9-KISOM<$OUH`b;5It%DLtCD<}08bQK>jWX3LU}>`|EukD@gh7c?k+yf4VAxDiX%b78K- z?_y|G7^A8npO=@WlX4hKeYJ>;*YAZEl$x;dLcZoq8DI3qrd-ERP>xhX zHAcgR*MzOg(gugUHL-yD-@GusBjW2)yoRAv+5;@rxLX1e~8&*fP z)e)?09wY>2qE-y{173ecLf@K4e(p;A^S2jH!=d|YH$8^fNIs08ri3{%Ykp`5u>*)vi_`BPlDMkE`+ zsWPyVgJZ98PYcyNfL(tU|Gsn|Dv_yJfF^2nKu~U9nIe##0v6Sr@5MD5%_)-hVcXKD z`p;^!fbn%n!h`1Xqx4-Zf?_S`%f6Fkh=J>ZpXl??4FG!M*JTJ>*||glHwK=z1%GP% z>@LVz6P86g1Wj|NLih08pIgB+cjM14++x#^cP)5UrX4u0p$jb6E(=7|h1N7!$O8 zaGxKi$Yb4gT=duqlv>PnD_HMkH)3Gh%1WdXk?mSxmS#r5l4wz}w($(>su5O-Hb6OL zh$sP)Rd&1}EAh;f2iVqtL`CyAdao+5SkTQqOgn%RbjkUC+sKgg2p4N(sD^{*bnf~& zr#C^=h|5Qk0pEbBEhsFpw?2?6F|X^I7^@u^*`vE-xr4P{B~_G2&3f6~e2;4pCe@&< zK{{>s`TpE$J!hrVQ!)HC%rXkrd+s8VIrHRmG0ChHH85L_Nba;tfhrp?D-uk)!}Mp1@JXdge+}D*(#Jp~Rw9ivkCv z8tH`I`gg|vW-(5~mwxUPp5N47bP0pHevekF$>QW0mmUDB0qEWa+4G^Tjcfe*CI9MD z@VC7`>Rw-M;|=$%sk5O|72K_BF?w2&gv$~^8G9ZfyVysymI0ZjDIBb)2vi9Rm<>)u zm?niow9zW1EQ8Ae(N4w`d7;M@`cgTp{NAxL`AF&n1a*tBn$LJ2lx!LERpPc~$X6?| zoCwfioK;keXDv6=`}KvBrTg&bfKpSTxYEf~(0U{jOC+H!@N8M0O)O!Fsy3w^C$NbQl-mo%5&n z>_$`GBT;?rv!&rhEzr$p)YtG$yBL_>=hj%rbJBYw0K6qp+LMLo{d@HO^Y`_NJonfY zwl?wFd*T44Ri~kp!XW~@8}E1#fY*XMaav@>3QEaF%Pt}?l)7yU-A`kSZOO8F%#Hn< zHfE|70o4nq$6bPQ8__k;)DHamgGm)@d%|;#*S4x>2u6y(it8YglX%XfsE2N>i`Kd+ zxyg*~sl}{P=l5xbf}3`dIf2ugpBo8J#l@zy{z`jbUL>BAD0?*6#rJjCPoD|)DnOF{ z8W`C-N7qOXTa+@iz5RTY<>ebgH12PUWDcHXlUYZQp9{5lKtv$S)?tO% z5|FH-palt_S4!CoL!52!1;g&&%4JNIEBNyA9S^vv6Rh?LoM`?~XQUf8iz$^Ry_!`4Gv6W&42N}^}3@us8)pNDB=k0aE8rA%cf~Hopl~Sad zdL`!trbt+DY6SLs&$GQ}PYHKyGPum$fT(v~j0BK1@XuMFj7^}|cupf{N{wLZbx<8W zXGWO#QGC#AI#~MrsYH|es844R;yK=*trXhO|GR^)Hs~XMx#zQ=6cthSqtxy9Mk%z~ zHIWQ2-kj-QePrwJD>018wPw${B9k)h;kUh-F(-h8};~dc2EPIEX2iRI`9NlJVoGv?N;jAwz!)QAzDe}Z-Q6RRu z_);?vvr|jvJJqLKuuf- zmZC8s26?MjMW8s9UvL>pfaici%Q@M+eqkLA?|CBy^yggbwlR=GY(u;D3-A(0Clzs> z2zE(M2G)NmixkVGY8l%-8t%Q4h*U~af6dc)n)mkly*8br?CR5!8TAHTGW1MFinn|F zcPY@{`&>qCJI@X9Y6a$_V?J#siFmibECnOyH5ne|kRD zY6zf>Fb}zm+5f-H|8-wHV znCR%joDqT2lIrzb%30XzhLPEzm4Z_46w$R()%EqXIxxicp|z%2o4FgY)7-ItEFFYt z6CVLF!?-}i>aE3U-yxt`qE3<%ToPdoKoWmqN?b)Kw|U8fZ|t|S91V_Z&!TtO);jX$ zYde-Godcw5okr6Rit#v5(rI*bPdf*gv@&cXnY-F~+`G==cb$<*+`HGGd)}28($PI& zlz=F8svH5nBWGBxkH)5*dxr$+Wq!^Dw_`=Zg=RvKCVpzkq&GD{sy30rT67u{@DRgN zv(c*oY?T$6rwNRTxm6RHIvv5Un4 zfSD$1=jRN9uR7|$mas6yGYZ4M58W-<1D(g#W$@TkkFJ~(HYFFJ69BbVw zG^_0?={;I^DPKgl-m8Juhs+tqUbogJ2?Ao*77w-;Lb222*6I({cI?T0C{7`{s9hZr zTkEWp!f&n5TF1{38`ml@C5|~T_utqpBelQu4l!M6;Q%;kIp@@VS6h?kWV1&0aC*vp z`kZrNkDRsSveT8#JK@r@7m5K-+BStIqoWP(Q7V|8wngs!NioOaQw!_ zL0?vEzf){)IkHI=TXV(_Q>Q=686d_^2ErI{Y_^WNMzd7JH{yHT)5O*yv6iF99v#yN zP-^|Y7qRYLY^{_}tB9@DmbwR!N5JO@SZi&BEheS60qjj(Jq;U@gONSK&K|Aq$i}(1 zz56-$-@3-U6JkEE?_6A9Sr#k+mb|Mc3m6pi#lCrpU}ayu7j*oY$#*gbKubzB?IdgK z08PlCvo&g}tW~kuQ>V6}ociDTB*)`x0~QrA+A6ea_pT$cEo0t%#?#!s2(r|+UMVzf z0CS(*xK+C(_o;^WlRX)>9+6Q4*}Eln`S)?|;~qD)Iqx1v*IO+xJolbP2%z5ixOrZg zZ}^PHq!PStpZwEgKFdY2Wyz{4N znl{WpGVy9QeYCce?4X*7kXWtn!F}1^JB)abDYFnDK zo}YBDply^z+|zY&L|fGYz~?a3Jw~>t5iX^$_ewNIH z`)T!v=Q8-`tgn_od(AhxM-ib1k1ysD)bLPHf z_2r5BTs9%T=yE^~P}>u8OU2S2RNHsX-6N8p6N&_YJ=fw+mF;f0HE>b`$|W!9(mE^w zsJ-{z0?xzx6-yGDmKe%&h>>TZ;VzMSHQ84S6FiL+W)E>vBT;)<?f z)Ezf(TgiR<;kc<*{#ldX(CqsKdFN&Wfo?=us^hYdd+|!%fQKoI8On!D!emofqf=x& z6%`H@9bk4%x2Rz6&1Bg(zgzo<1uD?PtQA~L$sl^U3! zF!rOBxi#I_2mmV`kh#xytyruzcD4Vnv5B>;PAij9DuyX#AWA>$RilqcHcBbrXJPl& z%5lt#v4R6cH>=HbO+0jd4sW08B2xUqB#Ca>rLogjTC&%29g z5g4S!JjSe_XH^Uevss`?C3b;1XlWf<%CXt$c*q98)`HZ$g>a1}ZTS!P7~GOW${yA) zZ*XOd34nT8IV(q9Bx+gCSR-HTVk(vHo`c!M?U~Gl;!<=oLnGr_ zA|Oh(exupJ7OoiG%lAC1T9&m{Lso50mg7U0p=izBnk?iTiDt=0wsw8fvrOrhUavvh ze(!0kreTm>J3LF9M&3eu`#*Ki=3g5-Wt^LGIH!trZ<=Qhvs#K=NA*lkdtbxe;e+?Q zr!8-59+&)~dscCypFILdOPk6VlSpS58}<&t5&OM8`$EeHbB>7uk)>{aX5V)WKkV z?qjlwTB_UMyD=t_ki;N5?}}y_ZJicD@(Rj9Y*V|+Ho5^3SQUyQjrf*~5VZwpalj*7 zcN5uT+j&kaa63-%oHgq`Fog_83pDgHeIwfIb6RMRX3DDIw;cz%_R?0*hI2I9qcX>{3ke%U-6&?*{GL{jT^j$9>pBNu_weM@eQ`na zN3o2gwZW3>khT+eHv8W1m;}}dU_FRO81l{G(Ahgjx=x-O{qF_fd)d#L70w<8c<;T` z*vt{&T4E@Ahroz6WQi57r9RIEvMvAImcDV%7>+V;y^W@4-P9{!9AW)yMa*$#EOwem zze^IfxwUSVP6}R(DKfnt^!aPCe*vwfx`q}pAR%bAw#VkkM?1ei@2(Ltdz*2H$A->o zv{EXhE@lP?Ja5adt4=vIsq{8zZM5e9YZDX#A+rJ6w$+2vkBT~LA82`OQzgSQ>NfQ(i-cld{T4z9czI#134Xx2$?}M7haxPEk)!DRY!XleGJl^&9 zw`7KEQ8O2TyM0ezRwOVy8Pgj#Lnd#rCyOWgx?JxRei3~%ikdM(UHZ01Io*WN-I zVQ%+E&87e(t`)BVuif&yj8~2`K@In|qhim7R z{eK<;tt0C)UL(0@b}a}#rz7t6S9?6#r5jY#G|T5^S5hnzVNk&{Z4^|)9X(0V)MBVc zS=5ok*t5_%XqU`pD0Tr5_sp6HhNR71HrJ@A$*@-o_8LGk`Fx}_vZAS=1h>~U2YwIOO3uM*Y6M8yLn>APx);hQRvp+Kt!#xFg zQOs<6&AbKO1W|x7OR+H0J9IE-^Si&{r38;gmo!MmHToDUVT!fkoXrUu)~NQRUr!q# zpBvowWHjAQu+f0UouerOT~xX6k|UK5q=wEt-qwGt`h9UtVI_H{>ucIzc#r<~{BDOM zYkhw!_@o1La+Ywo_qbDZJ)^&mIE(wGP~rRIz`@&D_A)1XSnIs7b{aisi#N}b9B_FP zn7FtoPQOaDFodO<25Cjew)3Mjy@7Q!^?8-*6gxteiXdtSU2Y>*1wah|FyhM`Kgg2j z>ZoUBZPV?sk*yS2ull$bw3Tf8TGw?>I<(a=s3&C@@hWdwF7;T0(SxT~aN2r)wPK;3 zcXlmpJ?bSsDv8ROjr<;cF=1&=);zCA)|$5-HI=cJ@cmZD>w(-n&$f9?^xUllo^>73 z@a(j<1(1=B+ylk(LB9Z)Rvk4hDYi#S*VvR?N99s?6dfMP#25bK_YlH6o zGe}wcri)8MUer5NYL>ro)<9?*@bQ{t2AUzl}1%)<%aY=Oyw>|WY_ zQwYftiUUbe+XUT23EWCQaHrUr1SSdwzd#nRX5{US-^537^mNx&c8cSNbm%U9_TJ}k`KP@}1 zywI=b4V~CYc5H%Tw~iW1-*X9Q&A)sD9Z6C4*u2`@ucmYxjhwUtf*iA=(Gj5BA*sBP zbetFsoeJ$3O_Kv_%YtQDtaYC&fDB`-1(x=-#cvD+f%8NqWeEYj2Ir|?Haph{y{>K7 zk~}bR&aq_Gde+@hVtGwIUvuyG+FYz1Ocr=Hic@``fKo6WeZR`aJP&SFb}+N+j>*Pg zA;RP|@~OA>Y6E!TTtwJ|XFUN*pp*t_g^R`AlU8=zi88JBy3djbNEBFNjkb=8Q#t(C zJ5v~w1rPbY-wA9b2h`H`N-kx_T6@$;OY@=(F_Yc4fMx#q@m`b%Sfh-&*X;@;a^fk- zC_qX5R;duJ^u4vfZw;xi6*J`o0hqfepIgTg;_)=hwwAVnVfmw;Q zUfpg~LcaFgy7ttP#6I%rGg|Lkk*b~{abv5}nCE>+N&!+X_sna5rg($zX^)Brt<>cg z#RF9U=$z$l7ySvL=w{Mwbtw|;caonC7W4V{=l%r=h&Y1*s1>BgA2Q=?3pxI-c)LX!N(`2y=#R!-ikxGn8IQFFMav%2I0eEg9M(yC+^^1tT^ zq!ly)3X=`8gt5Tx@d^?e`B;`(ZJ9&Y?1&|n)=BbQ;xnh`Kt%<*uvf4?5=`&igZHfe zz1g@{jn$saQ)`W{?j8Hs_u9OS|J(B^?~YgJp3bS4smT~eBzq;sx;-xK;HkAQ_nZDO?Nb>~$6mzboQ`$X%oOb#GwkHJU*Yy7#Md1huD zw6>idBS0MLFo+;9j>*sw!)bxEQnIn16X7JVw(Hj0^jUxBw0R1b3!JcZL}&#dExFBz zE6ixnGSX;j&%BCl7GqCs?@FR$jkX-zIIntbQ3^^tOEtS|($MZqqg>Kb9Q*QdXC{Y`x?)d@%+NUjQj z5^2+e==JAZbNGlIIm+u+lId7m<6E0k4%vSHb;Zuz&*0C9gkzMLD~*5gbA-AWqxHR0 zZL)_5q@W>ACU1UyEJeR+|2xzsyz`;#Pnbx*EfRXg%g)VeWWsh++tt?e9 zvr&6y`TQzrsP~TXNN3Ti#*Ye_h(YGBbU(RAw$~t^yp^A!AQSP8R06vT1+CJ~l-}~s z{!P=|%p6=$*6U=5sP;37*1hT2nC<}{dz(PD09y56L|TAa3jkJ)?dsU#&npkEmt{#< zZC?mEX$?hA?lb8mgJl0QL<}@3uy)#P(M738l39>Mcyv}KYNTP=Ikue7V*gB^6LlN0 z^<0=r4DtT!m)-j+qNl_IbH2AfZuZm+OjnXMZd}xcflmYDHWny!#7QMz1K#M{E2jjr z#ov`@dU?RFdL;8zm4O%@GNq`E(MU073#1e3KI`R#??{~? z*$gyo8LZ7=8bwKrveZU&GT16UG!Sssab6;#n1g4xS!`{Iy^dVxY&F>+0@(X_tEP87Hgl{Yr`l2c zIzj@Bj(^Luy>}g(_Z6YjSWw{S8#7~BmcVKUt3Rc{5!fb~l8%x@1WgL!e6s-!7zPw) zP9qwU@5#nJKgFvPN#tC{w7=_W3CQi)OU~^?w|D>BGhd$8>N7px$_4UqjYz(KspxDs zJ6w-OGC*zkU!1Y!fJ8Y)S@t!7*~mv|AE@+K-IAY;xY4vEf+M6?T5wv%h8~};uPexR z2QW>OiB?f9qU<}n0AQlrlv~xCH0%Wf1ZPz<07_QyPMe5j16Ev{TOVE3!0D(BUX7`W z?Y-6_6WT-*wJP8dy{uBYDlw_u!>A6LB6cUA9V4=nJ*@J%4EWR9M(t&=_X6EsH^_5R zk1dnC3j7;hzs%Z-RYiFFR@apFajhaz|mmNFS! zK7%kJUdPpB!RC$twYN9+?#s_>OJ)|B!0U*RmfXWbrYTiyhR z1YK+yfBv+2I4r|-_{f526$w=Bav~f{0*KmLhA}fl0Xiy1DQ!x77VubsNS+RA+b{Kt zAZXKZY7~Hu6ne2w@lYAOKW!0ODF_;2C(dDHpN3hfy?5mOEv@s@_;HUMeyzf=5lvbz z$g5dPmDnI3J48`_( zi7f-FXf13mjdNau!OWW!aD4cnFfUa;M}l9l3^f}WP33O>zoWrFC(~7WO?-c}eS;k{ z5zH>b;0sl~(@5^6&8!2^j-5fYQUFcCO~gBG5eZ1NBa#?Is}qSG6HdIf!#EMGwy~i| z(rfMG)b^N5P;H;+xkHV1l&yYu@3B#*affs=W~wt61c?jUS_{DtBL!K?mO*Z>{a$xY z)7j5dhuJQ+qK!WN>6&_J+LK{Wg-elk#*p-`&d!_Ha7}`=9gE`pL%Ug&f(r({q)D>q zf(C-E_}-)DEDlnEt{bvT0!JIQfXS%0y`rcKrON=9zIgAK~m+{ z);lBZ14yF*K~19@ig^nDsl9@`(R5HRN^B;`8tq+20=>Nq@+dIe1A$AgNdUwpW6*C&N&>{$P6v+q!&jhNYLGiP;=4L#WAegb56% z%Z5O^pNW!p|yDpCI4PsPO4pc zRgVN}2ZSYC#l1{tORL%{NE{+z{zKqrE;LVpeJ zoKM8f^M@g4<1f2E@y_#2bpw#379rY~O6NiEeA>%wlhg|*N4iwES6BUPMlFc%%;Sk8 zA8G1hV9i9wR+7^B* zo9s4`QDp1WEr}srnMwY0Hfdx|!7jxAd}T)RqLki-I|{B_>__amn}fyNim(Xggc7!Y zbFFG;c12Q!r_$|1qvt|0O;dAW)*AKHz-g`-k2k12Ufrz#w8oO>&#{-5_Kl?CZMoJ= zsFnTL1FSb7&)dR=`HctJCo#~A4zdw7X=t9ImwjcPRL$j&nk#0rLhbM9qa z+;>=#wbrVC$^l|8%b81MV*KE@Zf1rUn~?x7X&(<+=c1JqoFb^WHEhrkK<4Zax96p4 zW^7EthH`<4)fHgvHN+;Jo11a!xMVOTU^u=O0>C^D35zl-mHX09i7h6SYo-T*@M@Sq z+7*KPdbvn~oIHO-HDscqg77WBAJ6f%t$mwdA-3!+C-Ics6LMmU3vgRy&qb)*iM&Y6 zLfS=+txb5;5^NT(r-$4{jHZoS%*M#%$(gNDhl^tRL$(URb8N{H_C?TiB`FqR{_>qBZ46x2|eXjJ_5ItTm?F5X}Dd`R%L$;(>vq?+GzeqA0ctB!wnYv1Xy?C}^8Tj|Ke z3@8QYi=<6^Y|*Hc3KB&L0Gt8nRhp-G1==2T5*)EYFrq4~n7tH z1P5bX`O4#JgSbu0aISNX#r_PP46*9$+lz3t7uhBv9$Z^MoiW%PpN%GmXoY#sTb!C) zXxvB(o9uKT&54rl^1RQ2rQ2<_v<|z(LzJP3!F_svoG{YmJ+Sx`I`>bXWkLgt^;P=CMLedbm9cYAKo6ZuYHo( zalnXnmU3)-0{)Of&qR z=C}kvi`kNa05{q22a5GdO_KHkwUU&kwTAa-Q`7k+-FcrkqDcU`17k@F8^EO0rpc7b z(*C|NO`HjdQ?nkRq#$y?i%4_d9%<$k?NB*+v6-K(`IU4E&UgZ#*;Jyb^KBL~DKPu- zHGrYSRRmf#?b$`GE+ZWD+d7()j==^2tjm%su|=*1OJV`ImF?IAej_t6k&T#t5B2w< zA(;TLWKDbyC(L2Tbt;SnHq?1~$~79%Y`_vTjIlKiB+juXT3eR6=1it#nt{6pRl#+> zwpF3)p=Z~Xpdu*GI-OEJH+vG?ajAf(!v2n4Es4R1ZCA+%Kld4>%u`nwL1RDKNTYY{E!o96jbCb?-`i|k%;BE)<$+z= zVSkB^TwsJ*9tmn%cAcZym_+VY34oH;^{}oJmhI8OkJ-0Y_xEgE8e1{JcWGa+Hb#ky zA8SDv08j+%V$JD#ALRgg1^XNY^ZT2{P-CwQvIZ$;&xf;-c~i1H16B&!_hxd!Tr}cz zx)K^`#I}s_U;CVN0M|aaN_@2yZE7`QX`EH?8CVG)Rwoj_2T^qRvlP#PSWXk4vjo~S z%IE>>+!B%y{cN)@q1c5vJV!y(b)g0zlhzr$2B6HwvD6F9VuAB)mgsv8#H}&rrD-AA z!yl#nOQTSjsXWkL5mz#&xk5+;sl<}b=Z$36G_TWi18UX59@5OPif{s~?Yy6$H9;wW zu)tS&TX~y6)HK$;mDB9ercia{?DHFo)V=3x7OYi;0!M}5SOeXWwNz*{6D<}gZIbOn zHZIESRRkl84qAX?wBW4ea!_lO6Tfy>a~F1LkU{qFoK${~iRl5L5`fA#3l5u(wV`^N z2zj&s(x+qM!?5RYagO)vNOz?ksAUrur*)(S9SMuCqHk^Rt!H?S4d5tAIb!PfhXJ$8XjpLnIZfKH*`7Cy0NBEqB;j0om=PBhT|b>2RVlm-j}Kob#YF-7TA z45B@&$pLglDOVH;}l#FZ*v^iJT;p=U=Bi?d7BK!j!(#?B`Q+@ED_e4a5w6YO1e6w-=hI3vLXuLGJl6bx5jO9}qhROGF~ty+apG0`dTO)p(~FoqWF3@QMHb zsqcP39k7?als1ipR6RQ%9RMTjMepFH2E(-1=By?Q*$bZgDpu;+?Tu8KkEXyGlmt|x zDfQMt+mlta?j!dZ?rAbd=0{780Lj?%e1qch_*Ork(KYQqcWg#%822*1`I>0?YHtrC zY6iNS;JW}|doDP==UYnc^+0s3o7{+nq3W>UNx?C5+EN|1Aks71-oh_F?2R!HB~XYu z=V}cl0?h)WmS7WS0a+~bN~I$!ml8rNr2YX5>91e%HsM7gqE2TEqMy}W~-t#Cho&*uKvSeYNb4a_F##_7M z+I*cdd4Ow@04&xLZ^vK@vQ-4YdEmK^O54`ajfx1d&76y|tTelI!)~07TT6!LsNUfO zBbMn7&)+fK$@j#1X*pE)6%Vd*20J;wC}W=U3{nPmV?b=bvrV>5QKP!j9&K=b1GAnw zVRJ2$BsBE&Btao2O(%!Bl(f7H)y0)R_mSe3#tk~zb=KK7tiu~3< zDN9{JiUHx)nlawo$`XMdQ`=&UYe0EV(Ag?7tzGXq&11@8VmZ^&3IIl&MrtlDt?qWU zpkPl+`#t*bmhGWuI^%;Yp7R{JAb?aNH?Y7v9s4w1kt9I3pss%3ThNo%ckHp(YqPDe&^MubbkQ0>rpeWZcLmmW}u>ksfIKIh^XWDd_Gu zMX=sYLDAX;S)J8Kz|2;5Wq1xUEMsOc*uBOAZ%JeaCRiy(N&G}A8onRpMmnQ=uo7Q9 zsm^BayQH72MTJ`p7FU61tI^py?k?LbOZbk9i`lv5_#m8dPzOLqEU;S}el37wM;nBo zInGRYCOUae{@z)dL3lC1h~*;Q;xq|-O|a7B5_uENhxor~p?bf8UQ*=PJ8(-63qUY$tL?1SIGDF9ubb_Csms%wY;cX>vXdQ8-Z0TlW4uD(cI(OSy*by zu=4pI?~z0{peb4W1qRU-foayz&Ldm12ipdk;vz`B0n2;WYAWhJsZ8uckn2Gh8jdSCD(As*s zIA4PK>LzQIdpQc%?fH_8QekuW=TUxZA&wlttu#3s9x7lfF@qx{{8b9HF~KR%!}bb7<3) zsKR)1X>LTd7^(tbYU_h5dqn)bF_@|8YHMtB-s)U(28}3a0b9XYt;xv>A}VzcN(Fnl z(BMKVXiN}tYg;0#DzU-5y=QikfrHa8!+ILKw5WBdNCAMoS09wCuuGTcweF^g?LDt% z*tKlR#udozEnyrgMf0@`N3t%mg3A2!yqv|pPjASeT9Icy&$gM8F@nSvYMH>ShGs+V zTp>Mywf*dc9kUJRBTNdX$@!cw9@G;woOW9&m}u_4N~6UtQt$_7?LzgO}Utp6as&X_J)Pa@6cWsN4DvV3)&9Y@tg; zFdUyxCf%E(zVDtrj%73=grv_&mSqNjgJvfiRd!|=*NDk8%wmK2!v*1$SKg1=obb>* zz~OL-yBBw%CIy)$C|<&xBPC$bHW)kzv=C-qJ8O#A41+PoGUU!K*s!}2r2uyw&=IB) zJG%_lqI$}h`kc)3`=JeRCp%`mvfK8 z0e1ZU(IU83=dfgfKvf+wYIAJu62(Q0^j`a))|}2IE+y93rog3{R;q!{UVzhM6npm+ zk9W^LQAJ>KGziPrNYD3muS99r9swkcK8PqZjj2hKYI80Jlw3)-E*ap_B3NR*I&tbQ zLIN#-h>DsYxWC@Dk|{{Nq_OvnGKa0b+WwrA1FQvzN7rU8L%NZaWSxY!azn}Vk!p9b ze61*UXl)s;%67T{03ZNKL_t)xnOFu4+0^%>bZ8bNlL53!TC)53U_ihUr=Fd~BdwZI zBil?_45C-f^|pamc#qQtubrCLj)%f|@I#esWI59;;B*eiD(l%~$cVSLssXSgvDNcr z(LB#CYap1N?s}f*@YfiF+v7E!Jb8>qj~?Ob$s^p}-oh+yUWnO{ATbys%t-;XFf~KB0T^rZDK!mWc?}{l2Q3ogpF%E|b zckeuhyO+1PnC?Q!1$Y8ZrxREV4mdz2o2Bt?B1{6zwviIaYKLje3>GWtF$)1IEpUvz z(NDLxs|U9O!3JxGR7ItXdHkFiT2F5MEl^H>t(=Fs6y}E38axq{DCqgZj+tTz=>XPA z`^-|kQJZ+1z7}8|1(+>OWK+5zvG$EpHxo*AaYevM^+GReF3#dmZqGnp)(= zpQ@im+H*M8qzn_O;AD|}X0Fw&c`eG=HPwnad&QewcL?b_IFx;vxmqP&lLl;>94rf- zTwUYQ<11X>&iMA*?_pjRJigU<=e;L5ole#+3YICK4i~s{=Mo=$=^hkr@%-}-@Z!Te zc<$aEJh=ZH?%uuA1#2}{e*}ECq!W8A7F((N+FDRR(=)r*&9RjsI`>a$e&zS6h=z(u zYtL)lYp}5@+_EY5@1!)K1)3BVWkAcSNrVUtIsaKvpd{$AjZA`*1`(J%YrC>1t@ha? z&$JTyK}4NB_N|~X@4%S%F=#oqFz10#KCjwqq}4gKB{y3&Y!4Mx5VxjZjML+z#(qHqc-w`+H)2$ ztIu^PeCx~^o(nQ4#^RXj#jTCgZ2vp6m4KXPD*-uP-{8@sM|k($cX4}tlSonlV45xp zvYZG|2{&t9MjP4H=Zr39AkuZG8!5?rZ1V5o1UQE|t_X@5iZUmU7%K=MxMSBC3(R7h z!-xaCB;qvq23jis8fF3J6XS>zw3=|3bm&*8A<$X^$Oep)C@Cnh;NO@T$7K$Bd9$o* zp2=N@D_pf18LpBYLT&$Sr4$a6?KpWbu9(#oJbF2d*N^)E-2>=@9579j4S-l6leR&F z)9i~`K%@fm9S8jJbC`Odve$(z>4Mep)ZJ?*7Hg186|Frf$oksScWeiw$6)s~*fpTg zEe=z3HhAzrJ!TLG?^jpX z_|Cge@a=c5@W!_u;m^PD2Ht&g-2H6+xX92EKJw}d_}E|nFkX4-4qkfUc|3f0zneDf zf$P!r)&kpmq*XDC9W%h7{m*|C0JdaBtxQPivlPnhcSo+T>!eZ$GD<$y-d9;fpp3$T zyl_(jxLjPbXa&I}V!daBGztN5ub?_!PdvDGN3)YD;5wHO7?(iRn}m6t=5|k(Ow!U0 z;`7>~mh7*!ZghOWJAfEVl(g1Z9Jrp8g7InP$l-tkOMTj~+8#8O#v?7jlC|J+(iT)Z zjd%H3m`tKU0bu8Vp`ST6L8efC&b*yh!kdOmL8r@%g(b*Aj4@c4aXj7P$@ODgUtiIyek*P+%yYYpw?Hd>c~wUY&S-|D;*V+j+K*9PsL`|W*)tKSma0(y7$?Bj<`%S14c8HGReG+ zgJok3Zs%KDgF?2w`m!vRiMO^(;Q54kIXVfQ>Wn8>0X7kV^#ojALbM6NiSh-Gv3yXi zSsz<3@N`{LuHm ziXZ=>kKnZrJixtscZcN>#cKRcfLmj6TN#jA{euq0Kz%7nNkY@oW0&6Bn>#g@zXgWu zG#hsb=mplvwG;qctsqZDodB0**#Hd!0}O~ZfCeU3fwj^~0is}B!HzF}Oj|i~b-&#+ z&)4hESxrT67=bpp8yU*j!ojXn*5_M$t z#s&ar(!t-}7=dA6nHe}39KcwJFwq1>2f$4$sD6fH8abHGX$mpg)vr`U)&uqol1QU!8*Eca}5UY8d!t$wK+ z%RIHsSg@oSmM2%&_~u`}i@*4PzJuTY%$IR{oQGT&p7kFQ!Dm1J4Se?V-@swg_?tia zVSM}tKZ5ta@8NK(^j5ZMkNZoH0k5sg;AK%5KW?mvR;@q&1v~jf9tO=D% z9AeOo021Je&d7bH$rx;I&~ZdJm5tJ;Ke+4VGmIdUvI?lh}C4lm-bB z&ATr!?Pa2qEKTQ3sP#dJ&!k$AH7PLe&+P?(4ybg<8%0~e;;R;vXbTZd8=NDdry zHCwbjT@pv+BDEl3wB`Apu6mnR;8yU|41k}eb#@gHlQh}fz*16;neN!A`ALsTwxUxd zB9L}_dT=y}w}3qqfq;XjdA^xlU0>skufK&q`{K9o=|6n~3qL!Z@3Z(bF9yH;sW0QV zKlLU2v?*5GpC{>O6>@a_Xa4vY}g*T zNzK(JX7NYCqGyZP(l!a`-mvZN@ISbKWvK+HA_6Q5q795YurxHZlsXxz;5?$#c2B8g z)%J}23bNy-G^K2q?gH=h8PF#4lLiJD@^LR^c3MS@C8kj%Z5>|v>wjk)u=a(i8*4E^ zVtwXcLylpNTd@0|wHWI>Ep6=p2^Z4@Gb!-lfJqZfR$OU6K!-HGIF}V8)}>=+6N=F| zDme4RO}KaRp4lpqA_)v&ILLPtrLHUrkqw&&SbVE-*NJhFAV09~AlEn^XIx)j~#sSk|f+E3Ud`|!Z3&9wMEC$AD z^TBDSPVYM7pX=>+-o^1a<9M8L@9y)syu8H4<%G*gV>&44!y!mV4u=Eo+_{I#%S+t3 za|fUc%!>*I!bDcCXNcAYKuWg(b{;Xes{HrZ-<3DdHuGDu3u_hZlz@F)iRO@Ef zlLPb$554u{DC<{Fv7>suIqTb!!nEe^s3v_O+;Wv{-5^*tsF{ zYn?>EPBs#XAA!X3%raXBgcMxooe#^7tK&5+?Pq@enkvf&xhTQQzpqFBjMTr3SjAa< zCB;_GK?356!Mu-e46u#JY7h~*GZVgZIz!GOra5mEuOtR zXk1)ez$~ZG*4=&v5>2;OR+?fQP*~VtJ{cUB8O(rT2J>ozX8qc?wN0^B+j2-g17n~; z&lR&88Q+Yk07}8`W<7`s8ILvFoz@w6xk79;xXwe<-aFZX zYHNd-X3wk(5^N^nG_T!C1t9>sd&lbDFD~x5;Lrx$z6L~;!iBcl?d3Gv?^zf(H#fMs zxd9(%+@5A!J+Xn5Z_cFwFdHZZ=UuJAVo&?U7!XbnCKz5^QKfMXC{7k54ofUYh!E!4 z;K||Ie)dF|Cg)H@7Wfl@J9qBj`RDHA;lqb`@xhC@ckdqL9^rx+ca?_L2Vi1rvk9vD zLL>lNN6~V;F{NIjeTJx(sva>%-+MJQ${XLt*T3}y@4ojQrfI_a-uEKD_qB)k;QJro{qK7rG=T67 zGi83far1(7laWLgBisQ*tRcRb$!q8Qz0hi3=D+vR<12ja&G+z||Nc+$);m}D|KlGP z!LRS@B)^x~;%$#?C=Vw3>2@EW=_0`QKL1|gupuibw>({28+)6q7O*K_lSCaa zt-r0;tQuhllLfO3%~>wpJ{iEI~r^3r)@+xE~W3ut-4G3sb1giV7B ztq;X@9l9E_)jA(0!gKd7aR2Td+`D7{UR+#2A0|xG!4;?xpcM|&B@PF+7Iv@&naj*L zE(WLLf|IKSAR;Vg?Mk`M_jUi)q#T&hp%Id0{uzcCYKdecp1EeL!8JT%J{d3}0BdH( z>A2wf`r0zsC*PE5m3cq`jK%tj%LI`Vv^J4-oeFb~M8Jv>7sJItzAdg(o8rG>78+Y4 z1BJHDtWa;i>JXL=oR$L05t3sL>@G#5WfY_>j!~W??`$^V+`c(pyWo*=ns4yr%HZAa z2&PHfz$R*+9v39~>(km6bZe4OSjxN-0b(Wq3a4cWEV3~(7BRTExWK(T&*T0J4{+kEdwUVVta|DS&xAAaovxSXc3gS9Z1m871_t@~S+1z-H?Tli=H z`qTK!4)FVHA9@M@@W1#tzUxEp?=}b_HJ(aOuFLz6!UrY`KKI2p@qhj6*YV`$)cnjJ z{{C0-pZ$&R!-qcjz7=S9z)(#xvb!}i)tiF6@t2SBzx<=$e1-+2e>ML6!r%Q-{KSv^ zwWO6BFN zi%0<2-i-tRCh|6L4w!|)xpIMA&9fx~nOCIv-S ze>zPTFdIL&X2xlOwZ#(-?b=CCi6!9r{f;>&1Ie3p$qeDe5>8Gs61Ov7=3C6m5zDgR z=H>>%6r4hq#o+q-8n^BY3c)&bVsof8oVDSU*aZ4(D`op~g36BHI^R^n9D51ewC!_2 zvG%@P6S983X|9pp{^$d&1h@){T_=kSbw)tOKG`C`yewG6WhjI!c${5lOrCL?4TKlB zM%HJlU6#P`oHFUzpNorwbIt({dI~Nthr4zE-ohAzkeSuz4QT` zmIZIW{Wcywd5kAdu5opB1#+71*_;B|Xv`b}2wx;il4hqk3W)9XO<`;fhY7EI@csC% z@A?ql|I+($|NcWf|KK6+-o1;vckklj;tnn^FEJf1*X+=Av3g?{_Q`3Zv87ZOE7Cv2 zd(6SpHjn7N=XgBfU;WN!@jIXT{LuTq`sRE1U;mHa#!r0g!}$5X_Y=5#=T7&Ul&m0I z6?D_Jj*Y&s?$`d!>-haY{@PH~`Q>kX2mkZ`{#*DvKlLBsXa437VVZO`N(Q9UI<=CL zB@eO*kDpxQmw){a@h4w=bLjd$`xkHGvw!g>e&O%`C;0Ine9ay5sTPfBt6?hv>{h$* z;P0QmWfzPEe3pp`><*%p|tg?6&IE`qYS1Kj>sBG%cl8O7D(v&#vElMUV?Lg6 zy0I+Z?d>gY9~|+3fqVCWyLS(kanlx5``Uo{WWA-0v4yk(3&KeeNGm9c_8Y>cuYj$) z)aiHv04oR##Aq0?#gj%1P783H1@o=JJTG9@I2p$A$T-c6o0}7!Jh{bknlViWXvgX+ z65HvIR$|F!YfgccOy{jC`k-$lMTBApNG5I0*{77k88PzJLD<}GrhltHL%M1)WO>DO>`eS`nzzx-)DckfsLJCAR6U*G@vFMki;e(R(7*`N8bz@*hQYE}-i`faylLZbk? zcd-A5^yd?=e-Sq~*ZBFL{f}|y@^T;zJ_d&Nte2L>-#M)K$Xai+k({)8ZUOB0o=uoa za#jb)o=Z|KupQ}i7=NZx3YUii7GD7A0JUYZy?cNKN(&goz6H8%B}^hP2F}Zti=N!I zAgQ&-r}v^Z>GyM+1+CV4+_l)OojL9AQxQCeYuUWmL)L4f7yJK~#j_pfti9ODF|f-D zu7q4sASbM^EedmB+WR-V&ossY?BmG-nJ3rF+LdteQV|V6yH?qVnx@I7nB6dAQnnSk zV8X(L#R!aOKwUtQ{i~--%MOxt6%l1WTNI!~+r~4RprC@oh-W;5o)uePcX;iyua#HU zDvu7<#lz4H!2-nq7IqqKjT0*@qG61}?dgcyBjfsd#-k_KxVgH4F$Rap!nqh6=5<** zdG-?ACTg`-8xX9NYu6p!o8chM%K!N8i2gGUS&`c|`#IF<{bIc)@%!I5{iCdf&I<*!D*U;l^&4>WWwq8gyZpqi8L;!3(R`KG?~a>{(#eI0U)?ITmU>{ zS&rbv)EXJ7d?{^`H^6#lD!_|rwX$R^;3Z!9hj#U>Ge(>&vs{^cLy zD{sDg*0m7M~-ralF2{#XtEMzl(Ps-<)}Ugx~q} zm+*mCUdB)T=ts*3a#VB~lOH8bVZPwTZT&*(yvgNNXvy zqj#OkoQ~UH=XRf8{a*5WSzoJ)p7`rW#obc5splVeXHo%Zd+lf~pvwVF`57wY2a-hE zO$)3Yz@9A_o@b~3oln+bV>#it*upMZ*0le!uw#I&0|q-cjCo#M8}B&;MT^tBdbbW^ z1Q1)iC8BJx7Ob;|XBw?uRJpl|z~rw*ttZ={L*2o}P5!d!D^opER4Nl(_7+Z9!c%$OGd#8!8` z0JpQo;v7S6j)EswGafy<#^c9VxVgCjSfJEwXF}xhp3g&-thx0$=MuIJ>*#;)>KkG} z?E$==2yDtuXTGSA&0J(QgGOEJX6CCT(@M|JQ}Q~Mz1DDfzt7oj+dzdwU52*<4IMM* z)qC8NheQg?GDp%IH#W+FXj#iu)21&R-IEHLe+$&tqFxcfJR93-(G{v1V*pW*OE>@7 z$%E7ZA~!CRH$iCzh_M)U!Pf+kl{g)br|5dk=B%)Lr`uQ6{}wIKCM&OS+*PeAH4ns{_H8hzyI@_zx(I-zK_0!kACC>P!dJjQr`3uKVDj| zJ(mvryHEW^XngWCe}3`Tejnfc>ih88D=!pI&u7r7vSy+5{}Jf>tNiDWKL1TzUVa8Y z_qRWe!!#8;j6Q2gR*6yWfztB=Xp?~Ka(0b3LFmXIg}N8*DD!G13F&+C;?i15v9)Km z`w18*HNhAw5Ai_TABGa`MFx_zR=1$qwmY@YEAKVA7W>5@d(XT{$8BYwdx73a5G_(K zqK}_{TOwD`Ff#?m0f>TOn;AIH2B(t=jPmKUvew7>gxlNOU@x{TtGkOawm5KE7MvFM z{*wbR5`znNgn&OYyk;JbHS_WfKbF=5*a)B~w%Nlf0a6Djt#EO956|6y5ih>CuN7l+GB3j##LFo7mp2&Ns#WC);?ZO{@iec>!o{%7Q@*PMjZS-~OJF#BLo zt>8{8!lDF3HtS+UVPShM%oCp6T;uBMh(}Lu@%Zr#-h1x~r<>c=@UdaByK&+0*>d7y z@Ern3j`lH?*OR0mi@6>g*BqVF0A*>eeI=dlrh3}EFE4~`?#0pXV&=Fdf%91dMXqs@ zSnwI{*GR|~82IytlX11a+N&+1adXXEK+a}yE;yGih+i#Hwd-dw&okJ#*UvMS**3g6 zOa~Z-4N{M{m@Y4%1h~1m!u8D!=4G*g2sB7h#o^7$)`Zt4M=;igkX`X>(6^IB9`CDT z5Lki>X)OaW^$x?@CRpoCmTQr#k=bC1yY}9z>s$QdzxX7c6>k64-}nRkz(-%jbD18S zwB0Bat+J2==Lw-iVPD_Q_~qaDgJ%Y;e)-pa7yr|L{||6E9fGf9D>V@|Nq33yIrUcZg4s-)}_Ei&H~QX&etsYhAjw1f|g}dnjEm!8y6J`t<&8z&EY6%ic zYx{;E>G696k#)f`f%r;`%*c(QKtX(wpY_Icz$rvNVGr=0(rXNak23%oq!BU%ifmz|V(Yh$NZYOyxuR1J z(xH$+GVA(N@Oo|Kq$swT+vVjY)N}wtTUnB<*XP&4VY+mgp#@h@Zj!A1G);h>V1yyF zm9R_)`~I8bEgoNAIY|gX$UaBo&1+yHNu1jklqDp5U};>Tv%rL=R<&Yqs$@U&b94%Q z5JnZ)ZBmep@e)U_pI?m4wv|QaT_~KW;g&+CB?+Ke) zxHs2PSw-x1*860mPWaSkzW7X8)xZ4C6~6Y3xAA=+{$LbcbL5LFWshMuftl7K4kE%Q zU;n~01$|%m+S~Zn+mG?u2VWclTP=^_1S1x1U)c@Tip(V`N-=54Bb zVN)dmN>+4|IT3_0D-}@f>}Ff^;Wr$0??Yg)*8`ZVR(wICRbh-v^TV@u>;0jsGb|T4 zswB%$TIVC(F;f=4+>@cz2&iPeYMZ63;My`{)}C&jjnkpdxIGpDUOY!C|^c zbjSHvPWl4(A3ne0A8Ve?Ey??dV(9;w=qXFAogsjgh zm`qa0mu3Jc@l^J#wkAm&d&ISw(zH5$7-OLI1fo+U1tTyNm^|L2IimwpN4^S;JZzL-?Xqe|$K?$={dC&rKE8T}|;kUO~2BS2XEn zJ9O1MlBkVy4oKZ}n9^fV!BmUxJb;b^_5cdK`wdxLx3KLe!4POAflvf#M=G)_99_Fh z+U(l4VPE)85JVX)N5=6qafoI&jIU-G|%qe(*YAP zuCK50=+V2lzP=95GL}r396N5MDIxLiyv}XeM6`#gHIN~jerd~h2L3z6mE^?@6LwG$ zFFZmul}M^xyw+kRdsbHQ>;LdizVyu5%HR9+7x2S>{ksDw6%lAwYlk3zjjIWWn z0d$MS+IXCslKyjRz4WwyzW>87<0pUYqj>fG_wnKj4_57*P@==yrslZVD%+;I6kdAq z0bY9X0e<)gz6)=D^V|5hpZq-j@Xz0TCP4ca|M~CZfBf%$2KVmW-N6|5!B+fNwSpF{ z69&4thGh-Dw-OKQLtI|_rRTj323#^HV!qdw%$AvBSL8>4{(otEw`N(A>pbksm08u@ z`*O~lnK^U89UzDcK@uDgBnV#2i)oWIP0^Mu$_j_WHZ6x={9yY*Kf@1xbA%P)2ZbJF z%T~w=D-=PAq-{|qX_1mF3cSc734$Pi!OWb?-rZeQnQQrBWoBhvyZ4^KK_KQ__TF7x zot62mZ++|g%m8=_re4wGdsc?LWVjIlyouC}DLQw(C#sovFE70pz4qzaPHc4#HW78X z5;eQ3+qH-`RdKjcha4G5AvOXSG0`hq+x7`)63GNqCq_wM+s}MHw7_QbB*wffj={ifxIJ`u z{`>~F`y<|Y=PBNL@+79r+32sFz*?2h$Dt#O>BmA$ys8vaEtEh0Ac>JRAY&&*yap_& zG_f!0dtYZ)Sv-FH7!O}~30K!Iq1xzfZ z!?`muYSYAZGAzo-Q~(i-jaGWWqCxNJZOFx;HwHMsN`>0iIGQ8a_qt%jG(j?6-9x0X zVNBoNCd_i{{Sn5+9`J*NrWj&S__!YVn`LTAm|2S^B!e;fVkD z5B}^u2e7~Y$KSxs?H&&wTo!C-h(xdyNV9s{< z7CHu}_S&V^Z#l4}z#z!*|t&0V9VhMTJi5S1fL1@)X z>ZVb|0$>=lmG?wp_*4Y5vZ*YD5P%RgRjzG4nq!B3Nzy}lJawrTIKoY2~FfRBE5Ug)q`tXKYRg~mzN5x zlS5Y$ zJDi706TA$%f0cv0c`#T^wrnir0_C5bA=N2QNB}*Xxey5iW{@!m1;{R4TvV$+bl4fs zSB>{cmeJHjp&{f3m9^wVu9YB?fKT9Q;K?H}x0Z*Sl!;>d(qiNc>fAp?OLMkuPAWw#{>5KV6 zI;#PjI3Gcr!*-VT=Ku}$TI$4&&kVP;xi7I?r&^!)kq4~(``l~Z9-432P@7u5Ou@mD zMaA5;-rjs`5(E#8$J3h|JbqNjFw*@Gy`N(_h8bcDJoT2?0G_LFiDvnoXM1$9GCfDa zF$j(+4-uROPkC?PyMya5zVU7N-p_mhufO`@#ENNhUq&h^WBS)lJm!+m?p)i>T8oc= z^mY7~|H)6{@BYd^$FKj>KYVvmkze|4eCH=#$D@bWX9McHq$8ed{dWpnpDWKf_jT`M zjknwt3psS;+}By#ALok7bKEqRz}no;={;==fZ~yv?DRcd*9}}q(qdLdl?E*NT)O45 z{bxG-!-{>LjZP&ijw$))tNdp?ytZULngN?6Hv`GwCr3a-5TaEq=lxK1vmpRpNlgR~ zbY9?tLE90U7T6ydH^+eeZHuA#j{?|JSf%p_Hob57fB zjmyhR)Y~1194tAw46Yf@xeU4if*~Dr69#-}Gc(=?aP&Y|Lv;irp*zY}O>&q>ov5;q z?(NWMuvV?LaLz@Wz`_wD1h5Z90jRP@vPuwj!f=}%9zJ*x*AHJtwY`K1$gU{a!ZN7+ zq6-0R7_M#5(k;XwyYN_NvjbP3N;yqv?OG4AMMn>2l-%iut}4dB6yZ0Bj$eKMt8jpc zNr$P?XNB^6PG`8aRUZ@s9;gkL_HIJYcuVdS#$)@~*ljCtEPT5*;Lvngj+yTHR<>|;g|=0l zb#v_S{PqSxO*wiWO&h*tLw8;0V-AzngTgobE^7rSw&Kz60RwOL3Xs43=hOaq|qB*x1Sz?~&fOuXPELmc9YQ4uzXKGc6TvZe(_PTd5tN=X?gQh)9lH4l}mr4ry(Eykb7+u$(X}U}h zv{9nuNaco9>}#5>!MNGqqV?AM6RB7_heIO^u&A6i&4e@A7ZXx^Ef4-fXG`UCmus zdH$ANU%$D=4O+q=v1&ZrR2r(o0K`Cb!bADp{Ib@}8uTw}u+3>8v;;o##*ov!rmg;q zt;5g#>u=x_AAJ=MA6(74HY~A_=N3t8k}Bq9+cM`Ie*A|&3quBf`O}Lo&)K`{4)KXUpO*LBg<(IZKo~QzW1Fw(&*Z^zb*`N4)b-`>iQB3a zt(bE<2}2*(Ve(@s%L+vj;Fyuq?@z;vTV~MKm@SKJwgbb2SOmUUeL6HeZx2&18$EVH~R+9Zw|P*IpFrt z;@Add{3HR8;aZYWV{-_ud2o4S;5|-C9=L5JX9hN_44Q(l-Y(FPs1{ua0uK}I2t&}J zwQ5sE-`-vx#6^U3X*-x1>=OiB>0lFt^Y?{l{l^0qk&2FsWJyfdb?VsCw2zrUEuNS@5kfUK8Vf53$QK@a*7VTX&8`NC5En5H;K@Jx(ebu_^?Ij+8ipAHRE=Z zBfRtTRah{>42#v^TZFa)B|mgyL6$+$4?6+F4A`wx*A!zQWCwPJshBdBdXNo(eaJSP z>|01+biM(1EkfwjuQ^DDXOlg@Zy;pNwM2%#EN};fZo%{po;5bAAdsINc>a-15MlJee22d8#wAiaI`zb`F@BP?Du;do2I`mGH_PqP&&}6>s;6X z6~+0ADCNnX9DVnI^1c;2Y%+Ck8jvFt?T%B2^A6#OZqmjcrD!eLcb$6xo;u*mhxpvX zbGxzMGJsgw;lwsek_DU})UnxYzGc>Nn_7ogdbb2K+hQ!4+kq7s0gqpN^ewq}+q%Mb zQw`d?0?uwALtu+ZXJBmra;Y6}s2D0MIW#i(`JebKKKET8nG69g-K#mq@h;xZchQBH zfB(bZ{~dVi$q~Qy+xHth6##$qmACO-pSn2t+}%ggbTY+Up;}3opHfYI6bW zwy0bUj^Q66sLf*6bqHODu4}+PU~5S4m2csFn+qQsK`*R}jB`IMoCa%4U+fSQAY19bR}K|fO-aPm=USyQJ_f)Xz&@bsT6E1J>&VHs z@TQw+-0d1MN2d4Pwqs(IvsGkb!L`5-|hqil90b=b47rWiC)t|IV(gVi9 z#>mr!{P5~xff;*uzg~a&0UlmoW=)trP{T)REUB0~2sagfOA3IGf9OS2wJW3=J+M9n zJk9}rYip_e^S||DpT+ll`h9ru(Y&L{c!=km*Ek12ExB@>>h=&3e&)x&8(;p@H}REk zJiFJu|JDEdckmsbcpoecfyt?O^io567Y%ed$W*eAQx=%+EkRi;%Fj*uoNSn5mm2o7 za+XtakTtuywGM$9{rz}|aBQRBZjr6lq~_h*Fx9Rcf7SK4_Zo@Z#q2PH@Lk$Vt;6HY&vwlPouLiU@F)}PC9S92sF#eY2MqMGXto%&t-|rurpvM z#YPWQILiiZZ*K7H={tDg;WZvUxCF4te!|Y$9+*@W00Yl44!dj6bqx-On>-wrS=!8s z)2hZk0~Ah{Z4`$Rqn6mJ1jR>>@W5%X)JI^g{^I-n9!=8>5;Aj3ep}mR`N z3y-ncUE%8T0jg>P1co>Q2bG7^F&f)@5ANFhUIKfB&`l&@MhJC1-wn?oSp;1K*KkKL zT=qK;rc*Z6In;GMV8PSpxN{YptKsS`Y*oYA3RJ}?ZfJsFDrUs=@|4hO0aaC+Zb-*N zeojK{5c?3+#i)!%M?WWIM#X5lr>WQ>>TLvjk}9&oNmh~K&oj^@uu&%t3ju=^w8H=< z%&d>H+Yzk}3)dBbK>*;n^sSfNmDdiMjr*WM8$2uo&I}{uovVwkj=;c1Ae}l-`g18J zJBdNTbYrC47&6&wozb~{zWjSPnHbItcC26xFS6O=_V+3F=e~e*{C#y*;S1mMQT)np z{Qi3i5Wn!*k7Bpmjvuvw>A1+yrcY)7$@TRW-uUGE@ms(9mG}1g-uO5+n|inwXbPmt z7RMYoc=3g6eC&OX@Q3$|a9{fM-Jkx*?CY(ugKG`}OR|k6;QP{}Yy6e}{HO5B<43cp zmgRvw7i)W}^RhG}a4svn_TF~e4SwP0zKH+!ul~Jz-TOcK>N|M)>=ut6UM&K|c>uTm z9!~>cnWbZwhTHD@%+Fo>U4Q<3C;-noimXdW&KqEy6p^W`dk;6JQ|oZ>tQD4V0Y$`d z)OIGuI)MnqZ3>X2cs{JP;B0Zn8s$CXp45ZE^_hi%L}y0+GW|LXlLZUib3bcRx}%uL zVv8mPiohF(z^aAzY|t>H^8ts>| z-6Y6Fij+#J@%kdNgCZqD<%O<*UtPZ`w)yS1-^Mq;`As}{aD^8hTw_~1RJMkxEXZ!) zoC0hR&;_rWVc(){k7$~M0^5On2odmUIv=xNObtxyB!m##@Lep*(lca0=p*7&I%d;^6gqL4^9WTE0GOi!Ih|7xyxV%)yl-d#4ckpmv0-R&mAgC+uHPOuI zxS~K>vjsV2V9DCvhdMrwo_lcWTfI-A^N`NjY0kJgCyLZG&gNHxn~m!P8zR*7nxSqaAwaGSwH zKi(w!sm$pVb*^Fxo#22yS&{`9gU@{X`|-=a{(J8!3;TU<^bmKx#TmLZ7fC#OW;`m-A{T?gG9z)WObd4 z-g9{XY3gB7fC*4e`J2(2%!O?s7qBJELDRuYD!N~oNsY9I<_9Fx%*4$79~2rzCV@mh zTSqRpV7ExlA|V2VFt8H?r@f@~{Eqh_^g}|)51H8)g_X^%W&KR(>>^>w=5DZe#UZ`^ zd`iC8ioBUqoVYGG38EH!LI?&BV-dVWpKC!AfYw_yO~C#b&~)k`LdLkCkQ51pF4nqJOhQV~a_ang(|0o0DdH1<2k zu8W|q9lrXu2wJdYNG`l z5E*rb4>U-IO|jtVGivwG(X}mTa|tpIPyJJPOU#!4>W#{-meWQq44 zE`nrhd%&rhc2S1ANYV@p5PEQHq6>=dFKUZtqZ}>EnmB5;qs?Lh=^S*)!foDrV zZD3(xjZ?pRU=+M%U~EhnB{Mkt^PW}A?YMD}!qPy{e49@kvmd{~zY zpw#cKwXQ$*;n(q*kG~K9;{SVZ{II|K6Yt0SUwNQWwpfqDEJ4874lG^Yw|)2(eBhM_ z_|rF^y(icA!=L*$Jbvlnq~JLPj22DN0y)Y*S>2qWOo;ky~etp z)BP|at7EABeKG~ZBt;c#=6-0_04=?|HDl%$qpzpcYIm%S{oHqc_}-nFKl;iy@rjSU zw%DedWfD)^*YW;vSGmWMu6~>pc}k8mNmM*@4Ve?No;mOHK~iAha$}?)%3IQLr+vEw z_-j7cbN?M)EEl$rc6z_b%h`L))?ekTiXPlQp7(V&F`>Bq`#8qdX?4nHhu$o+U~?R0|t|pzC~=5r_zO^#7L!(K11LRh6J5&@b)`z;?au_@#xVbTwPsYSMPK!1RfMud2RGDjOtuc zte>$Z44yZf|eVwQU5sTELJ| zFnY1O!o|e}cDo(6+ijL%xR{soQ*RF$qU&MoT+knPkKLTAUN*`UXANt0 z;I0I_`~5!Om!koE+rbgx`uZB1-6eLL3ft`#1i|rmgzX$)2~}NVcXbVCYg91?-Z>Xp z?&M(~ftam9&SnO@X*#&N!PZ&qZ=a)~2F4M#zQG|h`SVi=NpuAvnZVutRFz{!h{A5TfjeoCzUe{08b`w&yJWLIli49`<9!tU`001BWNklwd9IIv$)K?{!5el3R+{Tnm{f{fm?J zNp2I4d~c1V+3#BdKNGMc^FFpjgrEO6K94W`tH1M}Xq|uRM?V`sbh(p@!BV?+v#Ig# z{p|PSzxyA5>0Mvjwzl}uANcgDUDI9L<=gEBfAP=#5dQnW{`cSY^*y}Y;QK!Nk(2l2 z6wqD+*o&WmF_R|I`NL|bS#o2}U}5hNnl$TQfAZ#?KZh^<{#Wo5 zKlrI(ls5DEtm2vfJ}AKD1h_WqKiABxqs#x8D33cDoHOFLw$|>m4>5WllG4gL=0` zU2j#F?OfsK%rWlW3~cMHwXxOiW&)a!*Fq@VOv-f_4A8c1)Lgf?y}iZr=eKzB!+wD--^}yG=mp36N4>nyu;0~S@NQIcz zTE3sb+GLZN)2dRYG{v8D04i!BzW>a-V*^_`RGS)?*AH?1@BubejjFQRt|tR(Ey&f_ zZnv~Xf&Z2=jiUejDYfx=!biU5-E2O<| zG=w{c73Ki87e?SH4~q^VIUUy$Okq=;-O5aVzY{1ObTvo|1&yQ+1AlcBS?TnBso+Rm zokS#*%7*bd+duCNayII%qa`s6M9t9=r+AC!)n<|+U6ZbZY4LRm1DoPGH{#<}lR2Bw9^7L&gV~&6uGa=_6;y}C&cwKANgCxP z5H>f5V5Cga@+Sc5bV~V$zVDOw0@z=B=YYeZ!EU!%1#N3Z#W}WXgU$K`KsJ-1xCzW! zT?|nON(OBBATiJxIMJf%cswHb7R_Og{mm_^+Tv=b4DfDu ziS2faO?QdSrcbjHW2>^yl$ROR^eOeRYUQiafYRFDlp2|97~(y~XXV z>aW|jjo#HVXt6uzP;YkF?k=#|D6p=g+eZRobzQ^N6-=NEGCT`}4rsax+t^+tvb{@4 z8P1eD3l_(tc5%x=MF3#SXaO)^<^fJvLcP^%+FV}X;_3>Us)8exhuCU^%2;eR8|-#F zP`!->&Njx>6GEuL5?Ovp#hwF$V7e9}9b9neTD1Xmn;Mn(=$fFfU)S)=IF8Am(Pv|3 zq%ng%BHB5o{b9V%5LuY04L9iL(8~QS4Pk?a#aBLGNiFnPM4fzuH965JfUgXpi@70V z7Z2@@A-nKE`jpLn4uWz)D%2O@COMbc;@%LcO{Gz9bxv*~Y2Ja0@Ho4zW|M|0O^(*PhNIbeUH0-}R{v<1hckpTJ-J8^3%nfcTew z?g#L_pZ(aK66eZmpYsYW-_sY~_ym|4fAjDC_Pws}KmPMSh;RGwD`#7Vox=c^*ZGCd zegxh#{`X(`CwIQK+FAVKFZ>Wb^nq8_+2$bA);U(<(|b3nStEks)O0ve6xx~lMH4AU zk~xjPw6v=l>fAArg(T*3z|HcUcX!`rnp<~|AMNht^1{q$nhuw{ZLXrn1FviAV-}>2 zJ35fF82rJ{yN9><+_Q9!b>dok@7;QSpZm3U@w7hqvoI&Ep&~xntcHA*1B-Xrqx%4- zUZXqLDN0OJ3AESO)riuMmS0KZJG=yCmQtK_h;9^~k>@7_R%HQD?X`#li$M^Bju{@J ztYDOi5IF?^V2}VUSvVmCCa?os0I<=6m~0JrmziP(W}4nN29kXT#SZ>1a96Oz{ai*H zygF)hoLlC3I4=TlZ~VXxZNgrQ#;;p)u_K_tCUsq5Th*vsg}PSRgJ;H}X~0m{S6HC{ zgL8-p8Jh?GGMKGu2xBnJiD-dlU|?b(P1APhx^7T3==)T+kOZ&~2PFZL27H#pv(b6O zDd4T#231w(gh~^G(^Sr}QK^eCLZhjrbzNs0x+=;(Qjt&wv#95_fSvB~o2o`#*Q0@W zl~#qI)_TdUVz=Aj^7-?fxJWJlhbAoMjjpz_hE9z zp3X@!QvUsSeewhNZ+`Ko@Ynv={|n!E=e(Hm*IvBDfAH`82tM+Gm)BWTW6qW|%)KWf zgCG3-r|{}4FXONMFTaXsx9wTi_v(w+_)9iSg+@P*2be+dte;pe?oPu9zcb#&uSn5#C1?k)+FzR06 zEOV{Gvup_Etk+nw9bNn$GiBhjc6eNnn9)5g>aW56H)HLFVrVplzzk)I=Xtr8EzlAi zd(Y}69a-7jItIgm296_1GD0&}kaPc^GCwo6S0qK!TGVtF&uo&daBS&v^yXDwBZ6u} zk-4@AY|sgz4S)}Vt_$dVj4ZcChf2XP@%=jk1cGXKtpLuz8I>SxD+32J(z8Y>M6`G0 zk%iuvVNPGK*WTOURjq>Q&T^KJ^j_5Q_tD#V?wL&guc!hHM^@JKe6G03Jk# zF~tZdcsOQF0+i4XE~doa;yqYv!Oby(Z9CDyM%oviqbwt|2wu=}DAFKR9@2FRz+2zx z*9&KTIkH!FN+|B-19jDFuluyc7>FZ+ZRO&efsalb1miTh(HKO{wt`ugtR{;GsBQXy zoy}&WUmvx{>F<5pz#9ebm)jj0PuT5tc=+%kE;l;`!PL)lgb=XZYUiNdY@;`}7HXDR z@f>U%rYu6=qC-g)0d=T6IBWn`kL~St3-3F$hkfjBnAOPiSq4@p&&Q3iUSePoXofQ&M9WdUfc?rLniAe4zSux)EcC4YY!9m8zKTZJCLRfGDj9VbAx+1 z`ggYuXw8rh$2=P})=UrOfx{4+Qw-EeR$N95Nd!e7`oLrSSAY4Z@%w-HCjS2a`Ookt zU!S+2`|#^8;D^8Ollab0eh?QIyMaB=+<~>mG~FeM^4mW2GXBbc@w516zxyZnKYsmp z@wK;ZX20)4uRp?1eDPEG_K&@e%_wp4oWZVjZ`NgS^NEkXhX49M`$>H1Uw#As;MaZ! zPj8#q>-+RaU%?l@_uKK&5563yeNPlcqZYQ9s7(<9jM9eomu&pWvO@A+|HR zElVLo=X7h%EjX8~$JRh~xs#R+3W>h&=j;pp>zUEM+ONLhf5$^hl;t8z?sapE%hdOOhDYZe1XaIH5z zo)ID#?KtV;bqJD~u?=DNz9t6U#?Qeyhs~zO zcC(2Z})mIdy;gB7oLq?!{5t%OQtXR$fvJsF&v~N0FDUVShA2bvPl+X zp`OdBfC0lfhuuy!e;)AVmitScfjk zTTH!;R)~zcZBRLf7J!Mq-^?MUbu1D$xhRsMi9~vy)bm^aE#2#?s^D|h2xa+)MBTF1 z3CZn)VS?(POR`GWi#m^RNKABJLcO~9z4t(WJVbSQae+5J^I?4Vr#^tU-hP5NzxfuL*25T!$^tLG_z15&esMB&KQ}o# z_kNaarIrqs@x8sc*x?60_X&LdyFZ4nzxg)adFKg2(3B!;fJZOBfX6RA%A4L@0QK7M z&uwQvxW2*{-nhc|eC7lA`ZwOf&CRXG?2>MvuRMMUFFd?nWGrXzos3#3GPboUHUO9j z+jjk?ePC^4n(JnjGOVRRzO~mr=XKW@!VE@+E~8oRXJ%5$g!*`;+4WJ*=&DF? zv3RjY7NkvK;A6hzcqAA~7)l-MSbNDl{90xn94>SI)oagbDbreNt)|_4X)T5577_|u zO@<~^1{N^upIMB?qf0+@*Oj(&6hVZxVBxHSJI56)*YNOw6|gg4b}$qm65veq?Tzc8 z^Bx@8QX+L9N#PXmtLe3~K8;w6Q2C*K6ox(S1l|4V2lw#K2l> zQM(G8%?2zK{m^4O-}Vj+&Jj!+ND~=UkY#lDJU-yq*0-<(mF6(Rh5(Kc?;ryUo5PLr z&q_brMt6q@@IV0^B&QP+p=Yk+=W0vPIwyJBtXwr&+M7bRfCSLiRmxdhOV@oH6954P-L2Q zQk}B^gx+0-1je*rIJi<19-WC8sZ(MyATG@?^xjeY*?p*$kV-^gWYTT3e52Sx=#xYq6GTev?)&%#m0oKRX$ z{NZ_rk(Xb3gqL4>bP^!U9!d*r)-X-0zdl+x%*R^G(nIvMS6;$vue`LVrJZZx%mX5x zW!=ZYDr2xYkv0_XapNj{=zXvC748Y(HD+TIgUkyo@9@y>{h52i_u*!)i{4J&&zeQy zIWhzy1H;pSyu8*#jqay|kF@yS2h-Fm;5x4*G7~v~h~WC7!hL>;;A|k7HiR`W%^X&W zn+W=l$W0m7(%K@#s6L-#nnx|R>oEnZ?nljWH*)e&$J!8idE6li+`u?%lLS{uL5 zcvu2zGUx=@xDC4CA%;N}q4NQa@36hNifc$iO^7Ulco;D-5;PRY10lqLLF+)|2j2e1 z^~FVy04a*D6gA(rEu3?}ZifItWq^t-d|(6#2*D!+^^6YIs-uU~*l@OS+*Xu5bz;;n zItVC4*-@UAh}{f{8g~E^y7*iQL_8cZ0;!(bI)mD55HxQ+QuHRvAX@73Ggb~6mJ**i zcb~K_t#gnNvXe)d9BWKJ&RM8q#$zLsDZ2TM$yk-MfTgaJAc16;Et02ta5J0BZ?p1VB zsjNzgKt@wwsh8Ig0w_ka3shc3OfaFJEwTNa^Z z%LQlI+zemOF9PPVuWnh9rcLXdj>^(?417CFd>CK1WSGxkapzutO(R=QM3)Bj+v?q0 zPcAXYOCRtlE$?zi2@`GlkjFnyJ~Ah7O7+=X2kAU-ZiA@{QK@m}!LaG%^EwfDbdKA| z+znq#W}NH#ozsC@m+z(fFpUEqI|!t8uLWQ~P&c%!96sX=4J8?WPP20sWpSSO@V@Ib zTyxPeM0zI;HX41dV8uk%TG04_&U<(tAdyAV;0GOWvPpXi11mc41}h*`ph{rGs3(Du z!smJFyyB$?z(`*wGu@aOfSt6~o%itC*B&t0%nZ*cejgUsS=uvf0eI`WM(wKnnX>I= z2|*Y}RNK6*D^!((t(D16ZXl`4QD#$^)U`KiRag!UCU)96f@6x-jj_|f3^5)~2ri`d zI|^{FuPacZLrr2N7lQl!J`ah82-H9V={ik+WWvt4e67B1a5&teZI490%bsR)9kObz>vP>d1 zF&s>?i%cnvQbN}DMYWCVH?rr(4X>BUp%Q@@io?tWc_n}?Itx@>voTs!R4KRz0ur4Z zv2oB+B_d&FKQ(cHnxnkMjEY8rHTwTj-mLQ>^JJ(5%no?FyT}R7IVjJISH{_zVM1vj zK3YU8;UagHOWY;=WDEe8ii|m#$gG^90C$5>2lNcG9UaVlI0T&)II{+@ms;;jfPJwz ziF(GN@SjfrYy#kNJL!~0b__z2m*rBCBxaqVHIP-XbV?gO7cz7geKN{~Hq#FUH=geI zJQ^8Fa7-^182|a4>z(gTm7j^sfI*&$mCul-%-u)Ny}cqP1Ac1)phzaqBtZ_}6BSaX zX+c3}da6&IJ7{68oZdeNK{pFN=4&Bb=iKY`Sy}6fL&r=K0|in9D-`QBK6@cD{WR01 zDW8A6A3SJfE2~8@Hk$hR3@!j|bmr3-be);zAn>dfeSr-+R-fxOCKIMLV-0~~tG}`) zveOLp9?@VK=L{S}>D|rD2;S#H$v6uqX)l&MR6CAkS1E(daw1(P<$l<~`y<-s0N)&O z+~4A`-@`XYIMS3t5gxcZjctaL74s0-(`;8Z>9otvv0iTvLUnksk53;D_zuo#xGd3{ zoyAD@p+c}^@@z?xz-64mGEKrIpsF@19}68M*ys>sGZ|1OE})f6aN!P7al#oy_LM zFc+_1<5CbtmWLR7);;T!(}q@fOYG~Z5Sx=0ZBhFc*180VRHHt!bb{4R49cBaM{_>a zv(f~S0(^#2t8gbkbMCquGJ%BB(N09LZ|}E0t*tTi84f49H8hYUEXhuKHhn0cRPNBh=2JvV_XYV93c!FDICjX(WkR zDI<|Vq`2hdNoIzREM><5ff-#l^ux{pIwKpvQynB@3>?|)n33MYV8Bksg`Be2L#3eefjw;g$GW%)zQX|7ThwTiw9+! zzCOWQ$qAWiyv;D{VF<7d$k~2q+mw5*{=FkRND9pfvWXCI7R0RUDZ1roz>Pi|X?sht z?v7HJ4MVH|fpW1h4w}iXhh=vYoP{83gh_T0(e#_;HuA|s>qOgkq!vC4kc`3Inl;^$ z@9NT_cxo``)N9U37;+0GvCLE~^zqLc5Ao6Y(v|*w_N)+(hLEOdUtz*pr6M3PeC5Ey z;9$?~pwmp_6qGDW5c*it@d~0TwaZ*`c_Z6kZMm z`!EFPW0trCQswL>=|Df%VdorK%~IjS3lgt$ zrE2HOW#*slp^Tyg;A?)?YX#{1znR$rZdL|2+OzDas7Qb2h5hN&{?}_Yi@%R8aqDGh zn0v5{PI9Bl=?tJo~~qB>Kq= zTIo=WwX{b&f+Lq%LuN*U0D~&~8B2UW4Z7@}L3xNgu32kxq0j?X4HyDT_P9>(nFAxV zT}+GI>%FXN)rIda5xfFyBLN|F0IN58Dgf)`N&$eSg%3L0rFM)ANC3g=x(gnLS?58Z zpPPlcUU=_wu$ZLRq9QAUQy5GU<`Tn+xWB>e^Jh5RK8J6P zATXREv@$yDW~5m|Gl!z9o*3%r*h3}LTMYV@40t(1mVXXuXOWE61Xkue#M#SE+`#>) zPv13#p+moa<>!Y4&Q>tqXIsLtx4$I|V}jy@1m;=4*94!Pe4NqF4LQp4EfcL0^{IBb z`!np+@;s3zL4h_Ys%4fLQVMW$0OL*o`;1V9!O>-=8o^WPaizf6@cbkot_#_!AfSM%(YXC>;b!|zdA!HO_JF7!>n>wcaIRocXn|j#M$!&F`KeGhT z*1FZRF?Hn<$gY#aNwnk(h06%1c6A{QSsI@2K@bl>kx5d92(ZgwmGm>bFoI8D+X5g| zA)vAvc9Pj=wllIH8oYiYB18nn0R%g+)T-SG$`jLJHAt3bXCLMuO$RJ4up&zRv( z@|3ZQNEseA?1D&UriCRJOiAWp;w(k#kWdT+G7(U70l4*=?W7n8dA||BXu-$>COyi( zvI9&HIMmKC7D#Zg$vr21p0)zO=wcV&ApRVoMJvcT%#qIgIf?U04fZ*MJLj~@=MGRA zF}MVCmcDmYW`N~kuB9}dv){*@ghNh)&AUiZmTbjJ22CfGN&XCr-u6&zolb+RjrprSlHAvsc8t?p#7zp2K!zyEe-uOo7OtCrS=ZRqmr8EL^}gvdwb6D* zbyG&;71jkV3KC2TUa|%h1F?pZs@@4DlWxw&Muk4_fP*l@53bXUBwh=uju}#I z4w$=DP0opb8+%Bf!}t!);pjSXj=$|GP`q?~r_&)%Xo*h%rM0jTn$bs2Tu#O|hQ$jH zhw)4vJQ-G#v<{FVQ`tuR>m@Do5->R>%Mq%)g*ADLNzJZJN#fH$0EKhwnaxy!Q~{DE z{KuNM^juiRBIBxnQU<#3X-5XLNnCS4d(IahkkvhDX$Uc057E+$#Cl3;@00F(a6RY- z&P@HM{*Rd}rg&D8Vn@tXc94LwTVmSGW=pU|3p}m|DF>n}*f^}5h-zgIO>bFg#^g&H zrlV1@8;}BSbns6>nX=X~r7-|q=cDFUBH$~7P+}2a05U!Jwic)zX?o+#J}@5s%F+;- zenyO5QyUCGT&z!yK{!PsoF%J+ofOo93`MlM=|e{X&Q0TWd974r2j`*Mj!nbLJO^0T zL`4qOz*=#fN?Ee$DYo7e!5rC-T?(nuXbr3MMS+)v+RaJ)xBc-L2M_yTGx0i*$UaPL zA4`pS2q8-x)AiL=6|dXla5%u&3Y9e=6L2`}@%-5n91aKgP90jBuFdy&v)SP4Vuy>} z4o0@948Y=*S3e5SS9=EcWw6_z$U3#RGOr#)#&ooR6qDhBi@Lo+}(KQ2PBI8MO zorA3BO$WZqmFKWB4H&qq3^eX0w${tFKV}fkYAbgRfR**1$%&gC&D5Fwk^xl?55~o@S2MApQT@X?r$p9}KTWI+3zs z!6peef&n~RcrozMXPYHSUl?SRA*+bsC@5=f1&~&U9i3of31kV*0j{#BsTelpzOZAA z+;e1p9)W0BKy%c8>$4-U#%4A=6HBD-3enwnQKF{@_j)1EMeMaT^FcAgpRL1)4)p-M zhM-`KlTBO^0WUN5i$fwrW{X?ZNUJ8BpaWut7((h_Y@h(tw;d$j2OThM@$}hSczE*w zFEkI)G&=;og69pKRO)-qM;#grL8G#x1BXN@Q}99A%FuwS3dg3!)2C0+9*@!c`WOcz z_c$K+fCw%xcc9}HaB&4(J%ACy)h-6z1ij*IwFLsuh8E7&DmUmFbe--)DOu4afEm5! zz4zGfl|6UP;o{-~o6QDY)uF0v-vwfwkFspAp$gsr)&_`a;C+J-Iv5hL?-1Gpd}!jD zn(wd*RDObZPNuG-L}nPy7IH_zX5+HLei6b*?H0|7}&R_)ad#@N^<)pX5@Ow_s?h!=EL z@3&(ux|x$UU+s%%+-)VJp6u}{7id?_EZ{dc2DfuS;4U_P;XVT}H`n5TOQ+t4k2V?pbMv{;viB;Kxt*R;?h{{yb zP$Qh8pW_glbCiKxh$(v%wTPzBb@pxvYNeUe^$^`kg3g!a)J8xD92sbXx^JlGu+dNs zW3ufWkq$K(%lYqX&0K-C6#uJ$bn+~4(Sa*izf*gEzg%TLNNI%tS}VW}XhM7q&(|;* zK%5(zUOLyy{h|LnOOiu73F88G_W2Yu+bL>W4>pVtc3=n&jYW_nT;sCbpuC2}Vz$Qy zU;EluVe1PJ5iT#U)$POw_^r={yETNaJ7yhz*L64?Zqap`ghxpsk_Z<$+0d3o6 z9em}RUeoSdG{;-qdXMIKi>s?ExXlr@Q@Mzyc&2+m2*H4*MF<_d?-a=UMjcN=JHR$` zGPf+_nhBekU297=xx;?$3J#l=@Dw%kJucSpww{R|0{j8_A%d#j<=KxAhZ9SHUA|{c zz_e=RIdc3-9UdF)Ispr&0Ly|f)}`AMxNE^VY3`YKceA#d`@NY|$R*3VWRsSwmJ^fx z=MG<;`tux1Cz$%&me+eq$GhtOkr=%b*S{=Lm>z(049Wz!ju587vS06*VO^8qEHNz1 zcXNrD6cUB4R>^E-eOP4K=TMEoSW;w$@)ryzlXbHh4l-nbI2aC4*rP3GI!m53h~34! zfAnmcPhF);!i2tn@+i$2Q% zs>Aj{5WEgIGK*@hE7guWiUW;?VJ+YwaL%YzUnK0DbFfaLj+j=!GIC<@N*S|yPgjTj zS0qalY0qe=Jrg6bJ8-Vs&(bVHzXy-^3%e+X)IFBxf0p!;0WUFboHuBFk}UM{6N=1a z@*=LRgJ;IGCr<(TBR~SGs=|vezlQBDC_|jWbXefM+8=g7Wg&;dEt>WS?^|$au;1_D z+YVJ#p{n)$G);r!@raw-8ys$KaXcRI%o*I=Uf|(z4>18^JPz#vo6RPso>~Zi&Npb= zR)+}VP$yz^`7tu&Aaz37)i$5AZQJ5-tKk2*uh1TEV4T6G-od#V&eb5}0C3hQ!vq-d zV1Gp0+@jgvqB$PXMrnUL;T9V)z zxE3>oOj(v+TKa^r$iOWvurmO}KmrKq(PI4~?RDx-SNnt;j?Y>c1QuQPy|?yZ!gWv0)=x*zrQ`B-wPnX{K2 zf9B@~T$v&b_FOlvIRdAjpO8#kB%8rZc$hI*PZcLkhl`;FjI{=o_5Yl8)9DQELda}n zNt9Go1@RuY&)&hG6_M?aUV4n+eU5xLtQ`)|0f*xe`V za~=xiCephn1Zq3v3_D< z^TLdV@?3zh=61pZ=4=?aaw@%Vu@xW&G0tomR4%wHoO6h#7W+9;jrn3|3{XphYGriC z?687fWlT7BNrh$Nf*_H3o8J3!v!(@bfB~p251gerfHfv=ZVe0=7BP2|Z5UZ)f0uNL zrz9(b1qDnb7QAj_Y6LM&Ey1%P11dP5C@3WyYk-;46Sh(SoC4Wq^w}=$qioa#z8{Qo zsAEy%z4|Dpx5&(B;Zcblyeaia?iZJ1Xj@jr){&jknH2#c2qQ>^AOtVaAQ@IWx6UIo z*GXbw9Y7W!%WxvF#Bk9qq!Pdq;-5|Q!&S|y$n;)o0%9+DGp6ry@<>3M9&hmM=@Y#3)|+_y8(#-|l@7e)Tzp>j z#l80mW)Wg~AJ82RX!m6*i;Ii=dH`^9ql~z3T6E1(JM8ImiXknh&Y-wGi9%JS5?LEE9E(tM5dL}R5QwyNLVx#ctq8}PFL4Um?WHH0-{Y}R~a#1 z3YI~DIEN~B9IUk(xI+$xPK5Z)m_$rmL?$e>In7G1J@6BWLmKc{I1H%JV$QtK$td)5 zTVa`v5GjD<`O(LB{WW_(WH|LYTP2QJ^5_MNLT9|#`bKgP=-pY&W?Aswd+ilz4z0N67mA?NHnYuAtl@(iC2l1kI|3b2*wDH9IM^_1Nx zsDcpSf)?z|42~V7U^Sd36)-BTG2j3MBayLYuvpb#Gevto6mjJ-`nZbvYludmlQPsB zr=YqrP^pO3B)9Q?HFxhasbPlCh(+(yUOpoyU3Jco=q&lNuLaGN*E;+9vJQ}d^ZeJB ztWf9rT9Z744603^vKh7XK@1$3!e%k~$0vgU?S2Fn+&p=PugV{zJsk1ki!bBy;tJMQ z@Z!;RDi1lfE%t{S+&+7To2PH#_W3iIAlQ(DB?}4Cn-W-pH3Tc1Wq>(#Qv|+KCzHeB z>)39$*laea+(xz1;^Esa>#F;hd&!cget)$%-0u6&xUhY6&Y=q)tuYX}QD+WYr23M; z(PfrA(1P#&+P+eDZI{d|*46;c6ijoVa$FP|Gxd;{Y~g6nQbf$Z$3CNADVt(An5!~R zN)hM<=5eI^iX)vJsfuDirK@(HWS!|YEuA%P4Cv%cHvAmxvS}47XX%^oayXR?sgxE; zg&uclJ4kLIOL4Sm=%Xi#ra&T1ag&@23`PuwjJ>VR07MI9fnk_GKivBv|wvo;xtsbf#-SbZH28DMq^g^QbZ(_3YIJV8n2ndB%EN<)89cUn|_kKkv(5 zeH;JJm;Ur#0Q+Zu;te=A9@gXm0KSU^;x5nrxDY*M<#^v;=djwdE<`8f7C~eZ@2<~I zbjq0dx#tuGNw3KF*h@>f$kM$`DQe>m++E})i!(5VWhf)WAt_PoJ*t3;5X8WsA5I(l z&?X?$`+!@J>s$Rk?V0)BQw)&d9Dm*hj*MRn)Dx4LF^bQwBLZ2~@j5c7EKrd}Wuqk@ zag6(pLsS&QYa+pLSB*4{@9mkg$fbW@a_3qqfKLrt_l09@pIbVsmA%yQTAR&Tdj`|l zmcV&A7|T!%eeP`gpkRh{j=?z_nOXxQG2ABvJbUsKUDsiMbE_=2b1+t!;>HIYn+9!j zz;S2a()o+O{h zH71ga0jCmVF9OzRO*lZov&`{&tG}!oXIb;&$1f#4Eq(vs{nNZhY<`Gjoef$7zoS0- z{JM)tORMa)>HTSQqkyH5C?)!zPF!a>*ip7V=Z6JlEgpJdntzr>WJc3=_@Do`e|Rt8 zd3{milOKC^^jgbm1^8uwSPbT5$V}#BFx31Tjm)6%B4IFp zt&CEWDtBP9%R+8Wo-?s86&d*1pEG24&OINzCkha;xh+j8Ax|A*$qJs#<0Y<$xO9W%MIMmbrAlXjx zl$>HvR7d9jlx*W%R{PZcdv4P4M7D&}1N3YAz~C^z{r03a;B@gQxWq)Yc)8hplQfU5Deb)#&=*LCmO#5NxG8VvO2$&gpBj+R25` zMes^mk_SC!z}+vA*jU(We5l_@l*<_V<+gl04#T4E}M zn8A#OrrYSQ{sV2+KcYYMm#Q|ZD5{~lTS5$lC z5gOTGXg{|}Cn|mH>d-H+2G9ntKbpu-K@3SoVm6SyU0(wBoScI{H8icuF}HIf@!q?AR=5jJI6P_b06-# z?*Vj&1BeNyr(1if@PyNVCaNTv6D#tx-0gfF` z#x3Sh77!KYpe_+wmhQ{}dfluamb^6Pg}Tx?(6|W^rQ*`;K^x@(Ae9Zp!*FhcC+9YI zoOCpIKqKa7X2@+bs|gu_EY7mFWW5zCAzd_Mn>e?Q4E|nhM0QWaAQAxN5H-{m^SpC} zgV$`2<-G-Fq?Uh@yfnnvIRge16B#37heX!U4%0!UfrO~xB%lj+4OAS07ldHIj0qrT zgUgQ8WFb*|y(2}_1al6cklh1_qQ07YeeqIJXGzU8$VC8R;7=Mrj|?6=+8lR3*U_y7 zt}Ui1OTT87Azwc4m6}5}5@V6H>wOX*4akYP0=Wjl^9<5xwkUhE$7eSAQ}eEY96E>q z4K+Yec)(cpLklO-CtHjA((=c)}eiB-<#uI^8Z}J}!I2TMx7S{%l zLW32jO`Oj3p|b*p<9Q8zw*wM!faAfjW%5uJ5(Em5AR!m`M*2CB2)fQ&$AQ)C`C_3% zY?^&>iUvD)5$yLn>`qR>ZV%#1P};%q4g>$#w|DBxays&yqx5>HoaR8Dc=9!L-^oFKaaou_!n^A`ug!*cY-&+=J|N>^Y6mV zH{H02C8_;?;sj6>L`3y;z3+VY0lfc1pT%E)@=Mi(L{-J@H(!T0zwSl2`#Dd_g}_?3 zV6l>xH964=YeGB$TEjnITt9yiImMDhq6W6U`R#l0_IH2$Lg4zA8&2`;r#*I6maznC zOAYPV!g4N!a;wgF={&5x?yvwTlN;xmyMWSm(*zELx(;>CBYTsB#}Vtn-22Vha5AK# ze-FKmb>_aK(cH?CxBd9fTxrebeQ)A5hXh_<*++j-owY^0j z8*?eHPZLz@N?Am*DL$Md(^#{^juq@QN=BlM9WTo=mOyRo8m2Y9>OeHJG7oAw2I$(klW>qlP2Wg%T(TVe;IG^(P( zr^>EWwNB#XzhZY-b9}jolLW{5!;OpYwa!5?h)Fmu2V?D6$BZny;W-;?=W7z90V`Zw zQz&eL8Ll{YT!4Sddrs;Uv~63Y!VXO+Fp$oS<)E5%`Z8v*gCK}EcArefLSv^B>tR{J z;@E5w-99IUrc_7gI46k0vBj;&B96%c>_*!2;q%|DMM^JeIDyg4J)^~)n^vwbaN`?6 z7bis1_dfmiU&jCQ&JW`(dI-<8!mgZmc<1{*g}=Dx@9+yh@k-qN+$ZHUE&{JE#A|KD zntsiDkB|QC7x4CXeH5LS<>NbR@dxku1m5-j&)`?z@(Mif*>}yxu@7BAmajp%2#?uK z?>#>FkC)+{tH-gf9KCW!CmPea zZq7wyCfnFuTMC!1!90NF7-dbze|qVH)&Kw?07*naRQ@9Y&Me?vu$G)Vm)!d;RgQ6f zuAz1=nChRuXM<>QT_NHOu3dUQNA3f`47AV?LtKN7dltJ5egd$2;8SRHBPa|)IW#1Q zB1Cr)FKIon0pw)M*EnG3%rT^48(4B=dTjH;9<_NFY*E($%Uq1|lG8`+e$|a_{P}+@ z1%So%54}ZRmImge%Q*?44!~*tD_3TOXy#dq;C!5KQ0`4CV&Ormxl<;EWT+g5tIp0~ zG;p8lf$_dOa*G-m%EbU^SDd}Mb!BxnX<_Z-A}^11emzNDsr2RIL1`&#qpKu*3T$61 zgp${`i3Z$6LaIJstUaRAbYWaTCtq___yBNon#nq12aSYIw(lznahW;Bq*SOCpAtNR z3M9JJ_|Qf77PWLx9}svS*BJ}MN-`Bv8%sy>=H4~YoyP3?gaB}p|6^iM>L`q#Y3WDh!=R<#E@EDr0{+Ir=e_a5(l-zV^AAN>0xkFUeO|NlOKpZn2s zy!xfj?oHGuU}t@dDz`X8(jN8?(b?HK{_s5?$KQPFi$@*by$_z@|M-vZ#&7)0D{=Sp zpRu_BnFHFj^SIHjvGXJm8ciH=|-ninGl} zK7&gGhqW0Dsc13$Ob285JsL2$fZIELL!_1E?Hr{Qp6kQ}&W(imH-%(J}L zoTuyIuxy3riZtrHUUR>PTAHi5$oSynJ?8tcnGj6#O@i^#YKjR;@yLnQTym4T}hdm0a*(2G`}+e|X0|_+L&=@a(5Qaj{)E2WXZoZni9TOJHRSh%Q^!B(;fC zU1qUm`m;6WbNuziuY4PS`o6!t;C&0c`SmZfY5Nu6Co@(?r7UDEv9!jb4$t8{KoQJc zkACK%zCrccX3ZPfGQ&K6PX~ffoekbnz-?{m&biEN0p(M0jl~vq&o0N(hAgOMuA^0Z zc9x!($*^U`CT_eBB)Ld04Y4ACc@O6lB0fuzQXF;&0V?r#V3F&haYjw!e=)f+(t44- zj<#CK)0z~-Vj(gNFpII*&a~g`sM;;7?Oz(tv)eeJSY2x*we__a=A(sTody7R`plI) zEa%_pXC;c`m;T?=(66XpbZinGrr(aAVL#U$%LG|!{mVetp4=t6V7mDbOcK(??u1u~ zR*&WxEg^YeV~~SU?R-n2i!aQ=s1o?r^eyqxo`K3Ug-wH;L)KaPu5j+Qa=r$ALaa`h zbeajG>Wf>-1=B?&Dsx?$rI{!Zfl?Rm4KWS)iq~^`wo@`A10ZJWP{bK7DHRcp;WTRB zH4JC9M%KX+hs+aGtg6{tKZF1Tfe#+OJH(+;fr>8(V#x)|xZp@>&y902NwXOwIx;gT zn(Swmx(Ml`0)!7cEq(FXjG56n4e=}(cJ7)mJX=_wvB&LKzxEyc?jQa&uI7sf_=ER+ z3Qv8?t+(8`2qd-unkCuAk`M9{Gr0)5Y0PY3hQ+0- zo!ht{R~w@n-`n@z|1f^%9T&fE-}1&6;kH|E$Q$sul{y5ty>DmDSw=;UV(!ZYr9ao{ z{8j8KdD~i$Sf+82<5fn(gzF4YUih(H+O-8}uUSkkg&3`EfIL$wEe^S9NCKM4+IS41 zaSVtot<8uH_}X1LJYfW31XTnWfbwFl3zj0;-)qU9 zk2&hFNzo)p2x|(sQ0j3kk zb=ent{HP>3O}+-os5Ajq?^&tHB$DKOqD^0UZpJeZV~JJjE@hC+JXwWkHN0h;)#K87 zI%c#3dbvXBk3L969M8k4qG26$7$(n3wCJ=>fsch%(=#tD5OHYYYjzUQ=pNha|Te0;r=!La@l%t%7o@M3Q4{zgU+x8H3B!B>U|$l5x2B@}hX< z${F7FCm+J03l}=qPkZ8Rc**xadBT8gIo7qIr7>_!pKQr;a5|j0t;jBFk_p2wc+Hg= zkacE<7Qa6ZQrhaKRBN%WvBPs-?mU~BiK9PrEr{e82DS%PMbVS4O*tsU@!nG&4*!7$ zzO=}?Og4Knl_9VcV=%p1S2w64L}t@m5+!PuO9o1_*L#XOCJKY^C#gaDEK>QXp;*i3 zJ7{iF;FS!hFFKyqZjS4ZQ2u;LmXg4)6zk#GmUQ%o;(1yibK+c23jgT`$~3xQ=p^FY z+(m}>uS2C1orVZY3*Yh_6#%|`eN|*|9VF`Q)kTSj0ViXuDKgx>RHOvMqL#DhFgJL* z{ETQpEP&&+&>ncZ)D@V0winjS*j1S@m|3IDAeKR3-q7XBT-Jtb#;}XO=Ek)4<<&Y| zO?}%mO?1Wu)4jHf*JTLCd!XxM$WEX1s$dQfaZru6h@pjq#vDPsqSL;s)ez^w^>qC? zSrEp1(}p6)X{RA-yB&gWqZ}<30wSjQkLi)ByM8@VD|%JUVMilaZrEX0taW2hFg@S# znWEllD4TRpdI-=*r7yX2Yy})OpX4Rq;H9?X+9vSjuY40<`Nq9h)jBD^zVx+w@z3A5 z7f*S@WAX`BXtoh7tE(-H?B~AxE!_9em1_pDKlQn9;2Yn*4^Q~M+XrC3ERg1oCEH6C zwtS!byD#T~&};Ga{*Qhhuld1e4Y#(|Ipfzyq7Vo(wmx{IUsI_%9 zZSXv*hX+hw`n}``g%I6{M$8Q>DC#$*V78Kdni5lH?P3*; z*#SKODL$zb^eb4D22I`&N54oM|$zRVEG3Ng@X8Lk-J72kvE?yHLti(A(cj zJlVsx4#bz|eJRO!OG56LkV{>baiQ4HP++jGlor6HBU&C#F8-W;zMRK!47BY5Ay|k@ zPyuxw5SQgb(6A*qHqK@H zQvq_Cb9q0xC=;>5o(9xft$Wxku^@9T_$@c!TF^#K54y(6lz;#GFMacxf$Q}3(NBE= zPkF*)1`*ia`|5+c_W3^csn6qDe|_q+U&iC^ygWFbE_yB15*5eCm!^3|1owR63)l46 zhzMW&%6IUX2(af0uL-~?9@^o9t`kqr+Pyb6lCRkfjjvlMnYht$hSA>}tOTKuAMaVS z0Q;VgeGY&9@h@HYzWtTAyb6!G{npuqcf7I8xkL=C*=YD2=Zz*Uu%IXlsau_d#5A-SFODI^)F1lqM0Y>oGjlt7qR{Mk3XB2Vi|4B zZt*!eCg5NTNSt&j!osylauA&-V3NPMi93eRp0QUcRKgh>t%RVFu@;T@A4f))5CTC| zAk_3hL6#0;~;5kW(dh8ev5KBvD%E8F7y6%Z{JCX`#+ zB{1qW*mKS(t|(IwWoDW?92vkt(RE#ZgiHHEQAOt&USc$Q=+8md2DD!AXy~Ah^Lc2B zq1m83=)k06qNMkknp{xS)+LndlTKG8WgTIhK1rF`iVabPQa^wxB47=sKj&#j&Ym4B zrF`0dtj*GE-V5-1tYoWZp*-he;hf8sbN#wixVH#F9YIxMa1Nq0HcYhYt?%;nO#_Ba zV;)KF#y;X zouc3Bk$JUo%(dTd+YTT3D^DY1vc>mx^j(4M&8xB z3eLw2#M-sdQEPUrNnE<7VH5;7?&!L-!qR*g5ny`!KYH)qUih59_NC9nv+lZMkyX7K z4e)H|NSBjE1v;3{9v>Mm%qtAyzT-blY^|6U6X>=`CTfGWYj&Zzz=~1EOKYMlSdYnT zh}|2tbi27VWQ)b+)=l|XU-~8XzeEulK_McLB9+O!PG*^l&Y7rrd1uY}K(pVcUlRIY zoiQWNiOJ^FZIPb5jzfPAG>Dy^V*wo)VQeu6EjIDkwh_w1n8`>{qkMs*yoI8xr9>UJ z5=Br+eM+(xKF^XEZF5!0tRX_L@hk`Wq=~q}L1PF?=exdLjZ#nS1_VQ2Ak*M8GRx$? z zpmi>>S20uILnp^GSL_>*A0{WxS@5oP?bbZktFAT(fV#ms?Zg8Tf1dkJD@JmWvTGhf z$oFjsUAElpZAQsD|B(PRVvl1n-k&4({hvD;hUIbexn{;7O_@lbQO~cc2oC7F4qa#m zq)75#Z{l1}O2Z5)eWiRvrxL5~PIWS;SzBz6X=_{!u-*#Pi3krr@(3O|@2)w3^`baC zKMVp?){d!mVIF?u%2iMP*1qn2@CqJ$&+R>jMMwpe1a`;X?M+!4FLZ6TMwf1 z9{b&{uzOl*wd+(epr~B4#YL(2}~qr0`*8eEr)G;6J_N z;`0Jef8u4l@iotj@zleInRS@dHajm#Drh>~@a2AgaDR2rwmAcPol9c{)+FXs*H zKEcu*MPq11zDAV2fkl!gobzyAfDLDQ$I8#W?y-xD zeV+j)_{g5CrU6GDf;=sF>;(r2cD>62k>(UoA(K(M_h~`%syb_Q?iJvrL3-&rSDanyb)3*bGO#w3wWN zH4fTlQC8nw2t^lLXmGyMdXnBF9jiSPg>y+TD`YQWplxRm6agVn;i%;&QePnt+Ik!)Rry(d^mL9695YU zZP!&Fx+T_XyitGmyZ3%ij_uHS9DKlj-!tsnLq2+zZ;PeaF)4yYM{$+Co?K%+{$54_ z48D8s1Ne8p`(6aO*fVqEbvyj*kG%}nT{>N4sOLZ+uM7e4%(Ir+9FnTdQ~!PiBT;$% zpx6wsd4(jXZb(>Ozt*G@TW3pVJ1Dh3=W8t^fFrXTW9>Q~LuSkY;H4RxIg86-!O*)^ zREK%B9|j9ChI;(aCEpQdfpa?>bOXgS``-81h9oV{2DMoT0a(Qn@=!|SOx?_b^)8|* zUeMu>Kpm9f;-|EfIL_xF1WTP2iSg|srX5$#g=qR2L}v{mpq1XfP7pGKZE6PwSSQ0{ z#%!8I!IxThHE^vS@IleW%z0zhlY2=5__4FZG+6@&1Eb!8gj^hq9BA=L3cwu)x@ZV| zgBpF$PP0tP063r?Xj{USgW%B?IBNx04uUIfz*#3a1j}YfiIUT6G?#{2XMK4_`d4Bf zv+g`%0ghlA#MAWIkt^o(Ig| z!g1i(L&XEq#F>vi+$tgKB+tr&(#32C%@yYhKKNAzd+SEBcHy@S9xeM!E;Bem1mCN# ztQo{{VHAUhi{1C^_%N5+rr5kO>-X^diAc7&;>tN(S~zN+-CJAY%L78|GJ{!$cWr%J zh~d8ffrs$hZ~FkQT(H|h1pNBXy#{yQad|d+yA~rmbOylY1-!Ok?3-q}&AxK}+ypD> zp!-5A=W_l!Y0(HTzDL!^rT5mI{KN5u|F{D%jlk|D3%zw27T4CfAfv6Z^lR($F>BcH znWYS@*VgQGRcPTFrY?+90D>Y2!x2Hqfra2>@QiBQ9BbBXu;ECG?OrO5FB;`p=Oxb% zjP6}oO4hUbs1LWX=w%;_LG}XpPRw>rfmV73FZk&53&|j+mFTFF2P{M3#^E69dwr~O z9x63g20{qE%e=B_P=g9uFYrD9F6o;kCM1%1Gm{L4Z)?R=d94{?08ELZRD?qQ`{Z7Q z%_mUmJXpP8@!LcYPk8h|IBywO4v7C5$Ud|IomYfIXI|L?1htOXIFfz~xK51qF?!~; zg0@c)q-qycLDUh zGf$aRxb$E8{V`Uv27msU-@~;&$x5=o=8LhpxNzK*{ih&@|Ig~{+^t>edDm-xycf^WP>(2{?ep#g@xSG z26p6ZainRBaLWSbbeVaTna<0jXIJpszyDYG)_sp&_K~ zwclIwtY1nuUAi}y;=PYyZnn6@tgTmb>&_MyDWuP-y+z!ZHQN#`KQ55gj(>|)-`f4K zbYEqcBH}@SNWQMDBZgZCgRsL1K?hOkaV6t`Zp^<0^{5Zd@wfqthM*@qUgF1 zL58zWpoCTfd~Qoe9cpfe$79Pfq~2@ZIeWCcd32Mh z`mFVXxqV`C9&66QDFTshDuIdsh}8y76Q|_jFm&I_7o4{NXJ;N~X8~8P1U!1hedHELKwu_r}ZO*4#5|; zf5O?##$MiKb~%IG*aZsSLqf7Y%t__%qF!J2+sk~afNlPE#M8;U&7vTY>{2tuidU${k&@%^9|Qu`knyTo31~> zjW=9B!?16wbcqNjjebuGfIDxy0sF>{76w|ZxU~jenX)FE*t)pDt=tBkRpz>`z^mlceKxj%>J#6wWmx`!_p3sxjry2Lw2XxFSWq^gUgnj@r`FsbNt|=-7qt^|R_6&fgYb|J7kMr{m=Vu+x&ppo10}khA&8LB)JBJ&( zU8xQu+9Q~u1#)CO6uq_KxHXh%ZWwy_UQ$hkoMYR|blQt_SI3{DOeL*>^f3!9(e=pU z#l<4Vf$TZX$%j0I**zfrZa);MLrpd+E?3+;^)Nex(8c#N*CDcm7z?P9F!(&FJCc(e zi*96@C``-{YT`332-3m(giXxtM*`5WkqGH^<__j8|&kACK#t|>r#!80F^>#w_1bs4CIM9h8NeA5kh`V%hW zOJBeLnjYVapZAoZg9zrG5ymZ|vL$%y%{SokjhAr$Bj?xj`0jqrlP1ZY?CM7Py}pU- zi&bQLn3kukbuHvYip6+C%H4#~S^##r7$_76=Z6FS;JAY{1 zf^1>4jyaF(U51q*N9ZikA{ctn_A%ckn_-@AQvErNvWooK#C&H(vbCCsjX-mznR#`+Xk>AsCPj0-Sj=fbA_XrSnlkeDKC#dk^0U&f5dd4xP2N zb9Mr7rAt8_glIaA;QQg&rXBh0I)|naIG4Z(Kv9QnAES_bz`GMG$*Yyi2QfjpeIIGlML4j%s8qdk}hw!H=0 zkYni6_XtA|c8E@_EVn!xW2GVKaz}mc`54bD=xjLA*#BONjf|)J9&s*e<{X-~V6Ac5 z^wM#cpEm`sq#;5PKgerHDT%IW;JqJwZVP@v)J{u|G)IBel52^Bi>a)ITaDwGa0)am zalq2$=bBT1j{=Q0=)8xhkDaexqn%Fs_*(aFP96ch#a~d#*Fy4~M{h^!P^8o@Tm#na z>vIzdO=N9@aiFUI>souU#$MN|ps{Fuj`0~k6fb!8lkkzx{1dJv2m6CBeEPu0Hr;$< zE1kK`u>AiIzW6!#(%0{~wgCI?XH3pxlgD3Y7>Y^|&2G2Dt6uudYZBvLzV`P&_bI)` za^)VWEoh~k7XVO0y^rt=Q##g%O;|ZMoz`EPT-@Sw&V^TN`JRVEi$D4EPvUPr{nZPf z#~*v$3-H>PKPN9_>uhfrRMf`~$6XCLU6NU>b*_$;gDeHO)L$bpdAy17AN#3mvVc$NWl-Y1=i%A)YzgWV|&S)%)uyIkW%lw0P6MZWE1~VBs;1n1n1$npR*9OU@=xy zi9l>|;3@(*&i6zH)}b%LMG0*%UtX^cZ3i6M4u`<#JaFg~=jR8Ux4wf4ISG){DXG#}?#_d4o#v-~Xo!K{xeM4w=#sn)2mopQ{3pnK(5*tg- zl`H@VfW{;oO>$VFJTFkpIpQFpcK`uH$>cXVIZ*-vDTDy!eKB7US@=vuL~BK7P{kS! zgo7|T0S>L{t`8o7Hc-#a>_GqkAOJ~3K~!`QG4J9Ky`m_}`I3*cBNtQtk^=<|BC3b? z-)K+PVTT+u7JSUjXz+c?b8E$;zb6Jl_22T`PXxfpuF}$rB?D^$Ep{Jk#7^l8J!hd> z?vLgAImUNw+h%WaiI#e)`xZpt+p~T>QOTBt8U(&;p|Mjja1$wtu#UR;nUf_Yvcy9~ zAWZ{O8?M!01D4DL3cz`L0J#>VYKfa6z=tqFyAqNes0}fuR%P4$Mtf zc6bpq*kiwMz;1_-i~bn1t~}Y}RTY604P-hnTp>=H)d*r;*ZUpQ5*`Dk^1{z;^0kWd zsZYAySlEZpt_eWA{iaK}>j}5lS*#6#IphC7=V_0{>3)av_S!g}-1Yd&c#mJUp8Z&}}1#!4%587*s;AzlW9eVE`%M>mF zQ4z%lKKwa+;G>_r@HzaES3VnWeD(7u3+VE(Ob2Q%D)+jYpPOTaE;2Y+yFa$*nCtJe z&Wta9{tGhywc}m0;9BYi%%8_lZNsKN&)-8sZFPNvkZF+7_?)fGsZ5LB(Z9=dcxqaZ zq|rsq1B^lnPlO$t>?DK`Tf@DTn6-jKZVMy2ct{qopf4h%jQ3V_fzf)x`N5mDoCn%Y z@#vYyqvsx1I>I3U4;~m^JkG8Jbl!&E$O#0D!@=WlUIdjn$sse&IdDVRIrIFrFc8H_ zLpa$pcA>GhHC)!Kk|YbVwDtwC3zKWeWW<=IXoehhwIfam^v@#ej0{%abS zKK9kl!=n}AaXf%HXNh`|wR3zVuHdJ?%DNz9qt{NkDD*!!*009m8@Rv#~C*Z?*S7+3)ezH~j#9>+K)7CR*aRyy*vU zdU~?RC@ltZjQ)Jnjo0Jnf8rJR&wucNYXV?@`pqxLrQN=NuZE6lnT;RP%eUN!xBSRU z@kf9D(W^c-Cc?jY)5|9Ekc%?mTV)NK0A(p5sW=kw*iV&4i}9KSCB{5|;6s0lKYs7u zUifpr@YzqofA`wE2fm+MzJiWDJ81x7+>BTF)mm+Cxh}`N-`1kw*lGKVtXIkANlPK` z1<&2QW_`T?*=kEUeSJnUX}4DD)GBbz#&2xNx0(z&^Ex#Nj!3V?PNz5l&+2hew8&FI zK(Hi8Nv?ItwFB9fPF)=GQ-O=@D}lg*e&|mP3_AcKY#VMIZfpbL;DLh|oO{BRR&dq= z=N<6Kx#Gbyvzoa<3P@cppfV6R{Ty4mjcd{Ar8H#tci*p5nj%Z*%_ykoYJ~)FBa5Bv9nA+l z^g&7Seh^74wcSUphz%IVKraK@-e#Fa2E~hrw*nT;kU)vfLYc{KC>Gise5=rt4#5{L zCKMns!IenCaps{Zx+7`OvL?G3CrmF&M2^|`wy?}=jLw|Cxd!HI3{3em&wT3R@a9)P zAAk12&t4Tsc*Dz|gJ(Vc2~{?@lmpDQapoS#7d`h$_}mxn!iTR?EB>=@`T^Ya#5<;; z95Gt-qH)Tve(5vt)vtXMpZtffUDfgZ+RyzE9&`D|&0t{*cv{ls&sFDJn6yb7U1gau zq~-fr1i0s8|A2S=`KK;i=sowTkHydZ#7ogM&E$SxeLhj9-~pw^G{qHP4M4nFrhCpE z$kzC)4*r$kOA)Q>*sQsr9fD(oKnP77T5=99dNv2yipV*4ECq#^(dBY4S99_4c`>Dc4>+_^niEb^KdSx-t5t^Oor z3q6aLj~;|^o#;KEVjR4=fJ3#3df4=@n%!K?_Cp2*8z@RqKyWG2Qh^{1d~gWrqIH@v zhelXRZs{Ai3m57tu6KF1IYwP2%`^eo0E&B#^5AH)Vk9DXmC0u~COGPt^HKurteuu3 zK~qxNWAdH1;s99&S#luKQpr0Ux z1XM&oLXgIalO%ylpM_o810@EeDZ~pxcY=;PKn29kI!WXJCO9VSn9#W4EW}drH8)^e z!-ma895c2sOI0v4qobSy-MR9gIR@t(UjM4+q4fdp`|v+r=&^Y9i=KivzwU1A3;Vk< zs2;a_wla6jjJN*iOVM^6KKYLq1F=8+%ID!#KlrT7Vw9LKvpdOqQ)%%Uj<3th#Q zyr1@jTk-S%=H)oObSbjYy`O7p2X6z|GtVWijU;4?xBXgSJr`WpM0lpzH1q0a5p=lZ$78HQVnYI%>K+UaSQ3N#>yHiCggtjw_xy}n( zv0#@@E%-$=hSE5Pee_AuePom!Kok(10t{TYS1|XRzW@jtqKiso+KCN#^RCxhNuxWsa2(<2#n@UrAC0eS;LV}8NJBho)55^|B} z$N;-TjHQ-#_`^cSZ%JnrDb`CtxU_^fbc-O*Z!WqqtS#QPi(UfPrTF2+R^;esE}fp@C*SxI z+;Z~`_`~;n?5LCT6K{ACUjOpvU>CtP)%-5U13nx5Dbv^W*I$oce#>ic#|QrofA&|O zIqLX+@yB0^m%rp$aL!FEuU< zu1aUzZ#@05*RcS5?L2PvV?O5E9y^pdw@%bUB5(nJ>@bO7UYk+5mfe8b>#ynXRp}^i z>#_8slyDHKf$MTeYGv&o0|y>iZ?4~OJi`dZ!M5UgCIHo8=)z=LjDdohJm(Q5s}2 z9P2*N!n#1&Ms5lGN|GR;P5_u?ASQ*jW+!W2-LICO(doX&m^z9q-2b!;vgb&q*^s*# z%+>#n4A^W^>!M^v+lPUsI?KysDw|Dm4?*bD5u@BBy`BRNk{*S%ilc^_bYs4)(08N3 z>;7JDz~-YJ0uV!wf~vWa5P{hWRdYeHlv!eida-+Vx5KV6EYnoL^#nRp2!pjbnx>RR zY_Zo{YiHDcXDv1EnD382K=R*w{VSe_=RV_c_|w1m1U~r>|FQ^x?|#mB&@A1=bei>f!f~Vn+-}6y?`D^zsE(|~XvS;FzKkzJEzV+r9 zvAO^&&`~ zqT*Z??0|-VX2%FZ*a^@y<}2-;4f!!R5*9sqVrpV%Of+oswIM_Y4$k8R$H)0}z-%E)Gk2MoSEBs3*(Iq39SnZjtP)n8kJQa?zjnb}TXA%q+zRKp=9I8WbZbLpIxD(5dL;k_@Bi4_$}du0tcSyOUg9oZ-fub2c{- zWmIKyW$k{P_r;zeBFA!wtpI2az0Xx9b8Y}N=ZLKp58Q;C{e*E({?#I0kT*1Q+-VfL8aQkC!$K@M$c-)=0;?`Sk-pt;u z4QZ?nZApn?X^}atx1vk-UoI?hD8Ih?weR4!-gfcf)$31p_|0E_9d5gP)9n3Idebh- zZ6I-j;$a+k(ygulSzhT99dll)f&-CF8`Bm>e5^@6c5~dezSxl0mSoJW?{_tuc)3B2 zXGBuVw7j=#Qj!`AW19(}(Q|eflT8zcgSmpKX5HF{G)+O1m_`B!h)HdI7?kNLQ2^}n z+K0?|1|K7m)!P7FWa3;LaB2d>3$P0Tr>71L*fiNpU@(+jeqO``CuT#Z7Q@Wkz^P)l zi&{-5Ag|c5!Z$twfyUTvIiL-SOO6o;;C&NY(!k-=wBe(Qzn8iw0c2@;q67hhoo)U^ z7UwMR=z>XBhyf=a!n?>|o8L8&i*|ElHhVCa6()kDCN=dMZHd=f3Jc1TkVuk4f`d|* zE&Buvu<5fCIiZ3)EJoxbD<4c-Ep~r}SRj~ZalBt*LTCxDr+~)g@RPy)Q?6f?xv4qJ zv|5s-toYO)3%L8|!$5WyZ4lke-Zcb_G+@S;2L5Y%`I2R7`FaUln+9I`a}dGy;Ace; zXow+7>pz9h0KL>or)v{h-&^BWFktF5dR6PvWWQ=Fay7Bz!ULb~{C+WrCP|&rn%K|p z#Q{v}?Eymw=Cl)wao42vkkAyFA#)P9HF;zC^G!|TJOF20JcBxJzlK}^6PfyI0u*BH zoR1^fYo=-BapGCw%S{AGkVV#J+M*#`zU5Y2zU9_|&-R$LOg93PThxb|z6aF_=dA!^ z{Mxr&z6G~kzGWG(OK#Xz7idIA0u!HF3@X++(2~8U)5DUzs2O+Mei@Is?N+m13Nq2b zZvn@tkmOlIjNZ0uUdBMPt^PFlBn!aIuK(~Fj2Xddfmt$5qt?+^{^eWv_rLd-@Zn<8 zfYZIhZ~pS@@%TG$w;`a)uv__G@X>CK>I_I4+NuFsii>7%LsW*MYy;D?4DU?WVXo*g zrm%0l<%#+Yww$%|v(8pg_NlFHXmj5Dk+;cf9rG?PekI$VTIXS<^JYv|`R~Jpa5d^a z4o)FzJO?Ze6hvY0NDVt5RGlB`*BCMB1Wl!TW$?+$3Kx&5IId!d%M`iwmU)0e-HB-? z$^4^538Jni4pPX9V~7TbZ_$Y&ga}G~Ko@+x_d7V}aC)-CsRGxLgZLKLH9L?1tycsG zzzf{2i8}Kp`uYL^Ap%$1v-bNY+x$6Jgq=WTS6J35yzFrj0RPi z7zm<-uImg)r@|z3$&Uk$82iR#B%%aRgH{xW^8oJ^USN^vR-ag;dpJOw)A&0ETm|ON zAZju77TCiU(asJkaY&K~tbP1>sjpJRupZh&Vi9jgIdp9a@YqqmKYBF=JE%ay0Z_5Q zOgM-zv@?w_OMs|102Dk(JqQXCvqn>A+V$)mt-XcXn3Wx~jl=bytIt)<-R77M-L}G+ zdHK-rrtqrf8x*RW%B-lJ(6Fgu)`UBL~_ z_0V8*6dLSaPx`PRnrAoqq9J={fy76Lo#;9wgp-pKhy;6nMWL;t+3z8w&;~d?-N)$w z#h#O|d2}z4&=-?z&x_G7Qyew7hBvk9XHZFLm}Qep|EB{s^;+2MtZneeRF^evutwe6 z9Jm;?Uq;*F)|U2`p|4}B<*hb{$Go;IL|>CAcobB#H4#v!SatI~v02Bvp*6U6&SsMe zEAR2OZ~QC%umAFw=z?76e%$XEzxj)=#p54)`$U5`2X0e11Z&+osMa|e++#-!BG(ek zYAnk!&vmKhn7P+oeqLR5AS;J^jDCj204$02EJAr7NWGAfyn#o%Hx;NCcpuPp-TwL$ak z_qy-uRKGJ0`lvIQYd7uHxkmIF!%9LQX&<>cbAvL`<}tC0gm@fdbvXB0Wt(j7p`5e- zSp)oI(7r|AR$jF+fz5i{!nnpPlr}vjFf3bRON(Z@KWcX!B{oMD|9bDk_;d<^w&!x&*5wO0$?q%RN_n|AVw}&s>47zFd%naE<)@ZAh?gA|;i&B3peTz8_7iuAOGMhSN&9YaZ4ZwM4n{g-R z44`ljcz_+momkr!WKJF-7S(EP`~9URzOD^RrWUh;S*=28g5gFAsuW($5VgbfaN^bubfg2X(Gb+9beHwC#(ZA@{8%MQ%qc zx5Cr7e0jSTp}LN3*(a6&&{F4W3+`F75#9{WXFz%hWW&gJT5^YdUY=m#L_7iGgYy@s zddHnniLM{%_q_KAsaPz0t&wdT6K=9@l>?Qxz@@c4qD&=ic^F*+021^%Zr;mwoUIl4Ns~eK8xFoE(V$5xhHDG%Y;5i1#O9`4a zt-18GBbk+1k}S-5KF%`OB?A}%H|ur=KR|~7ZDB}d&a=J7YHu1+i2wH8`yRso`Jdi{ z)(2el>o

b$I4okKGJN>#~f>eL%g8D6>GLmg$yO)_C#WA_19Oe1;qL@b?_ifYU93 zeBBRuz33bR1fUMow`l36KgSg&dfjPcPNSTjg}EWZNwGUK)3UUVtaT99f_aATwY)}U zsHP#WCByh?SV8B29T<&s*f*}yMRA3!smX2%X}?G;dX7KO(j3H8NkGMbdpNzW zkCBE#n(+XigBJ`WBhE3p03ftDgbt28+9XSo)?%Y!fLVfvVuwZ;q8ue64Sclm+c|== z4RMMZd#+R(8*ov$b6)oP$Z>{RLQh=P9Z)#!C_D%PVMd~^RSZ~*6!N^Hn`Ss6%2HC~ zIwbleyOntjT6HeE=={XmjM-W@t-8;POb9xOT6YKQ#Du6L)`@h5v-8U_q{duSdTGli z>Z4_|UN17;J4yyV9NK(+6ARDIIx7Is9Rl30>5Hj&T!}eu+jhX5hah>lGZCao zqA?}GLZ06kn>(Q5a+KIjTi=uZTjrlPHqD@-b!k0 z0pxQ<>vTQ0bhTm6rMHZfA_*|W*zHbWG73?1#|XAnN{DHSnxr5K$CN$iZ2(H6LxzK( zfkNQbk{4SKI02~jV0K^+>_xE`Fit}y^`vS*y^8titOfm{EvicYLj2Gg0JRZ}4k z(-c zx_ebXI_$tu+CxbZI1YD_IsTfwBe{vBjsWGv(s5CQqH{-}!lOJ{(7Ajgi#Us<1{uq( zIYnn6`%wW9LUyi5|Bb!=9qB-hS+n2VD&N>{6?t`j_s4dVP?YQ?>%LvPADS)V{xvP+EMO)z8h_z+w%Y1k2P%rho0le1L2S@+Z5TaOKc}Ie=ht3w9k&yoc)Ek_;VT*8sbHgVTM3lg6QGkgYIvw5~=t z9AymU=avEhP-L!U5c{6NLNJ5whRX1?-olL8y5tmf%*t_a)dQ!Eg2}80Jv;0=#jbJi z!3vYsE5sRaYE{ANt@wbmRyc_T$}rimp&$mnpjxz-q)L`2X_7e^6H6LFwk8|UxDF|S zr~#!x(cHP@fg=TCVk2pY^FJYyMInRy3?8AY?qX|e(y`!pt0b+)bZ=qI7x&Cqs1eC} zhj`4)Zjh1nButpjQ^oI-xg4_`OXqC7fX`{Sms+e?^x$(& znnFcE%@b#VV4`4~;E#iQtygqj(FJ4hIx$wv3*dtRSmClzAKrfG(id`EcNP4nrUf}AdB{vBJ3isBOHG# zNkyD3&K(DcLu4d5`}bNcO1b?Vpg>S)6F~|TdP?9{On;4F>S+doBedQMn=bkkGd!FU zly-0`(VW0T;<_&&h%kamPK@kJ_##}0OYdfh*UxTXj;F^!x8(IVh;_?2y054RBm_u^ zk=U{Aj|j3U4#<&)I6NGeL9VRfit74!Q5(@?*(*Q5CIazA2FULT2R zF@$W*D%pXu6P8KgC8sso`;K(kQG1NJ2i-zPoM%f)mlrMGhf?CG znk!EBzJ|g%wn7Y}Jc0!UvApl%?lIK5pl|ctBFWl^S07w&4y+vA8lggCORT>bT1DNUG z$FDJ8%uGF`CjeV}NzYnWWX}6}?paOXdQRpt7hbd-h=v?cQXb#ZhL<`Gn0c;5ba4Y8 zpZ~dG-YtdIG2pxZ_oThm91Js%)DmZ#O;yT+eu>!)+GO_+F9I(CJ`lPn2T=vOAn}z0>V3gU;r+QuRq}OA(zJA4n!L%U1VK-p63ev9O9 zElF|9(Bs-H)e@sw-Qz23ldZ#?Bk$Aw;T-ikL8Iep9y%Bejy1MPl3h*SaB1nxme6? z$hC)s2NfWVJcG@UUwdWoWSC4xfN^qTVt7;YSh{dT3%9-j%Y+FlahVWiTSm2(N*Yo~ z!w%&}E+PXfxDr5&bzLPuuil7-FZV^AGw0x{iA#EFW-LP!r=N1FMl>(|MF*Izu(P*o9X0!-BONW@vgHBvC0ga+~0zw zck(jJ!r57h-B)k_d1@($uVc+cpVpe`l9MR~?x zor|_)Y{hNJ_gMeDImdv;02oeeYd`!*tWa_NaFr+;ZZbHv&yfZtnyj~Xjl&)aY6AiX zkW;vQ0|!ETB}8jGbDnSrQ13y(;iPF0(BUkF@bDgtJq}%mP8xJ@5SUKeI$^*e>RnS% zjU#hU$wOk?8DQ4_esu)6c)dAB)+c8XQA^njQOoOm2NjPHI;d~qx(?iRpwPl`)c9z0 zE)jw!fDw99jK;&q{W@7IZcBMwVnAy%NXK@6mcaO&ylgf|Z~V-vg#tOpxobo@tE2z@ zo>?wtI@lEKJm&@OVxW?kr*>%V+61ux7Z*GrY!YXqgHR3TXC8WCH4{HWIK)krQ%|JSJuuKXQdoulA^hjyqg%3Ji(7m?Y`&1DQ3 z>RPX!uyWKbjO5dwj{$2lo>VF%af^8M#~Fvm2!&LM<+EXoXG zON-0WNEtF>LXi#bqbdM+WBY-e&X}XO*g>@eq_@CLf)9o>`3l24yIG;3g@^*)0V+@j z_^yLjf)8Zi8m$Gt#GsjU6cPa~icm3*jv)jxA_AIiYg3d&pb(`VV#RO>knRl9ode+< zzB`A60~7}^JQSV%rvVT@>Bdb{^u~k)Ux=;Vi82xj+^7sFDn8n#QC#p-6Wedqzj;h{goXQf4uhlGtMxX4rVd;GB>x@Q8-ixgmP6 zm&eF7vQ3R$b&3PIH9zn|O!Cnp*7_x7$MtJV@{R=S~U*S=ZP zThGZD%9DAFPwOVua&^<)zR`@6+$L;h7{yDEDonxhFcE8gI~up>=Pt~ehI>tWI(M3D z`dHR&?T&K!7hrkFOjj1A%=jRB&kmVsswBk?b^EkBh{8*SKrz^m2;y3+@o;GIC-3>%?z1y-u}F6Kpn;J8S@-Mht3~x-tKT{8Rre*up=}q5K`<(0PG=7&`3>gBZXux zCgpKISe!Ovi2ypWXG|OuQ#Hny^90ly8;boKsblW0gwY!I*=O3R*YtX24Iu0RP>xOy zl8U-vm(eT-DTi!nu;*zk=PNbk`Pj7wRK1!4&IL>7h{gh zLXuoxoS&Ya;`H?IHFt&^#>$=M|ko`?4~T;r+>0(5ZWPol=Lwm{XRmN_wj<&!gF z2~*|1rJFH$C`vZ~S}!Wj4+s3wyZ#0r`t(0v7+gQ^>5s!(e(Y5^IoTIQ-7tAj(wdcZb$IWP1G?z+|q^XwD&st2EsbEO3i0mM0Y_%x5jvzwD zS&HKP0Gvm!>hsP3r$AW0Rgl^0|g0Yiqj6-OizD9Cka# z$>|QR?a(kGgbtxQ;QY~modi6r9W-3RNw-6L(qOkciS2F+ZQ-OPo~$d$MMSdOf%)b} zKoDh+p=sb6V+osvbHGc}G{!zhaM91WMCOl;1h5oIje~%IvJHC$C<2kmVN~G(c(t@h z1z~@B0&NJg1LTT_4;>ELLD~aaPtZ=lAndS%OJOl-O%_1pP-Tw$WjUUEG&U}iTtN_` zHaBYYBf~DCgLY>It`Ap0asY(`G@L`aD?oP!gbtj#pNcAbU0>r}m7uCh#f~Uiw_34H zNGsVeAcSRCFRmPW*`48CGmwasGLf=Fy(FbABz%$G7KqICx-Q*C(7_RKg2w=TC2s7&Uqpy zjV6zDx-!d9B%jP?JHXa0z(NM+_w4)}|MlG;!3RI}l?#LGXFlal{MygH7T2BZ^1X8` zdptXws>_S?8c^OM8QJ26T>5IStqF5&)rwx6w5o* zD37&}<>Eegf<*K81`gL7J98Hq*gZ;;#2)>CdjI9q-^J{$Lh^c67vq%`A;yLWF-MRP zT`G*FHXFM0u0=ZHU3H54}k11J{CzG-Tjo;S`Z&E!jx! zeRoSzV$f1AbfO`I=$hit1%eMTkuuo14c>-A&%NTxd580ZX;ghD@Bs)Ky{)-{*9M19 z;5+LSNKj}1c5Y`L+00NnKtS0U#0ZoEK=4$Gp$G;n#6gI2>pufLp)3zEnYn<`LG%Dc z2Nn-fk1n)8XrUq46esuZF`ng_u19Wjck7rG>Mh{9YJ*qIg5;j8j-LG)l4H!cF0GTs zWH&hoCEYU#+@|Yu>{^`eV*|`Zz>Qc(B7GoL8zj#2PQ~!$c-<={Cj;OeLz)sxZSx2; z$gF6ZCWH30zhvp=2#5B>)yx`7k_{+&fSsO4D{S{}hm#^;rY!6xl9OV#i;w6Krq^hO zH&Wk{Ut*`X0kqL3N$YK3DN=&gZkoBlrDOC{)t@2VWbrcwqHC;l4dB$YR%;sB@nTWa zAPruxGI?9x++eDY+=V-`XmoEQbZ*KD%E?c zZ9Ba4y`RMUKla571C*yd;WB>xXJ3sQu0QF|?MCSXfIRRqxko^oJ0VNO=Uf8doQ!Bq zl2mHmYhKT@%rxq3^?GM)*s{-?er^-;VmEE=duvg*DZOv4dzTh>6`dA}it4kp1z>OK z791-f8LsaDqIdBCSjF>dEOnHHsDl@RC}r(+=S>RY1JDYg6&qSS?-ap1JlZ*QBDit@ z+RlFdto1k?4j>H(P@Fi2(}uwRKYQ;MY}lU?D)DNFXG{ z)e8wpNJr~^Cp>DRt zlV23zVS_Iq);T1XOg@nlHmw7b2UCD1Uxw~_iyl{k=7bmlPZ6RHECh`Xna%OaIR{q~ z79EVm8h}t?t_N_T45kE92PG=9l=93cAg1}fOT+^p8uZ!|zv1i7((Afj(8Y{CTI739 z#t!eh9$f}5cZKy&ij)jsD+LP%VGrU4N?dHxJOX(e&Z6N5ZiNij(e z1XC$0F{Cz{aD^;8Z<4B~6iZ!c!@N0XBuU8LTqHyjRC;*HPzZ!_saq9FS|l}e!fBLm z1Y~Yoyg$nCRX}}oZmdLipOcr&WD_>qSw83dXAoFtYR8$r%vhbEVKg_Lyw^M~_AxkRr|9NLQP<@ouN zQ#3)t56Rl5T^&z=HH{UY_}@U zz|l#7v5){93kA8&^&Kpjiri!hq?da4wb#lx@2x!EOSw((mHue(m=j z8C-wS%bvo2{(W!8(@#Bd(AHW;#M@piXA9L+i}Ul6JKdm2zDb9tre+P=$%&=faNkW9 zrQwQ;thRNRGaQF)&dK#78Q;HNSM@gntT!2kJY|`A%Be_a5zrXCj^}_?&!!~aR)>BL zY@gDMj+-0?aBT^NcFZ#PTYDQE6hM@bgp8>cMN&dcf|v`aPKBXPK-U8?Wju@)EVJv% z_i{qtXT&~1H6ySB0dV9X#iuu`*&$|i@H&Fk3Q)awXe1z|gslcR+F;`uopZ=BnTA{) z94nlwAi~MjN!cLPpSccH3+9^>h)HICxlJ;tIlsM-zk6u_95byl-Q?E8d0b?9Udl070KfF8ge zL_HiODCeT_m!r>Obu~Iw_@56RIX~;MmOQ=oyVGZU{+jDL@%fB{o%^ZHWnCv}_CJP7 zDQL^yo-{)f29t;Z%$7exlXH>KJT)>HW5?r6PBC=|8YLPEDT9j{8KH3yDGW4OaFQ|A z#->lDqti7k##mgScmeYDfF!GK9CmBbq}V7jl4BiN9-XC#M?5tBSuSj8NYPwu_GdUp;WThFt_r#7jjv}CHSS=}VaZXU+@ssGhw1(CvnMM-xOeH)miulEdoox=L0U51;Ht1c&WKM1+EXI2WPJBRI;OG%G@o6B$it2 za{zIAyyt#?ZIN6u{O5FS^)pZjhgbtKs*1P$#{2Nozxd8a2G=it<}Uum_rC>CKlQ}A zmc3YT5l(;pn>yE=8q~Xu{_mzkiqp2>G3kX&qP&kLqn0iMjtuvn(_>E;??GxYEt*tr z^tsP{zGI}pO+fc>%ybC0Z+d;sCA&VVOyn4V7~W6Jxx-8^ijOtX;AoM`5Mq`ZZLa90 zq$(=VDjnFy=(1oRO>f;N;C`QxGhyFl^hwN%ISC|DNnDiTeO;o^vzGYndcEC2 zi@mnEz4ss}94o{dKo)0iAF2#T0(e0nf+O4N%`#2^W$T!lC={Y%YMyGXHzdb7K!HqZ z-6pm7;rhF|*z}bFDk_7CZDy#8^&6#6v z6ME=FzwEBAnjx%!HKID)%Y(*Or8=&S*j+@>b=@k)ns;#z*OV!6oTUJl=O{-5(+*@s zna&fO`@SEZ%}|`NoO5W~*19sm+hA>RIH}cJ-}i9DND71y1_{XW^H0}bdw%HnI?E*# z4%57Y`gdN%Kb4qaHqyX*M%xCHh?R9@2CjLrkDu|wp6*X;d$lKWM?7t-2;UtAgkuoR zq!NWp+Ve%ZQrmpcgLXf&JGgOX4+0-gjw5h6A#?yBA6{PK^70D%EwI zf!0~f<6upO3b0mzL;D2_FYOX^F}xm)SMmP62iWcRxZWo)DK54xUhwo&XxnD?!Hz8~ zRmZqwE^n*J9po&~LtoS7BC8`)tT^sT`u5*?AO6`-zvGd?^~EOOKl{G7-~~@Vx$2T( z!#Dzo3T8P9?oM@Ml!{CwuLr@L1IhKXW{EQoSz|lgusAFM=5k-6Li=|0SwH_9rc_oNtnjE$aGFqO)V?jG>Y|E;@ZB2;9LK`#?7Cc)Uk2xQl z8rnWs|0bVlX>&Pmxe^2k%;r-)#1^vy)ES^E5yA=&DXejpu|pO!pzugwNM2xJFw zllx3F967Y1fvO^SkKlmhGIC64oCk8bpOpZ~V5g&A+o1sMu~>7C%RR#O{uu4LEZ9vZ znrgs%2k#jn*v9M&NO0`nJR^jF#)s187C6r{Yr%SN)cY>90Wn7OFLaMzBgi$_3%b~W^%BT?jDNGZYl2F-R0@61&v zgn-RvV_lu1Z)O_3^J8aLnYnz97$dmKk|rHcff}f;sl|C*TOGK#lxP9MG=P7{&gPxU zb39z{;;Zh;Gs$WoI^}El#`Nq>vqkW&4I_hW7K0p^oMB3$LAt~2p{1Z+hK8*XP|L#0 zFRPzpQ@pF1!<82NTrxoin(ku^Gl$Q38p*$UDO^Vg@Kq5ll_juoPAH%Qw`tReN@BO2L zs_f3T!8g6}OYwDI^(wsT6)!z0H&}*=oB|c6UguOx{w5lzC6IgjJKu+Y{4f9ABZKQr zzr#6*uW&r6^1wd0sE80|ppS}u z6zq}>Gwvdz>jg0rVjqzuBIjg4Ruv=}ECS&)M%&Yvcvu2Hd%XN4O%S)Y_pVG4FgD2^MxJ1C0)z508!6BplOLa|i*!@t{$4 z!4Keie%*N(!U`e4#{`!$LR2^}2)z{js-Q`X)YLqQqK7YFds-l`x5*VdZxXYwdLIO$S^v$lT+KHhY={;XY_(cOZM?s?PU^J5+Q*}3FVrLY=6 zSMKeUWac^&f@zjFO*`Dz_P&D9G{b$IY5`w8t9eYOT#{`=7rYh&6L}Sp6}~hDwi9{P z^s`pxyuO}uc5fX4%kg-!P-$-tZF`2BK7?r>t3PHvn_ ziN#!GPBWmfCLVVSYTr&8pVULmHsm5W|Ky+C!;k;Wuj5_s``AgK_4ao?hqu4$IegV? zUxx4fj<3hFFMFok?@*>}F@L-@x( z@#x^X4Gw?v`~O3{;@M{=z^oR7r8O(_c9F>GLO>TWxJ%#hV*q$)S4xYaG>0S~Tr)4qcil>7$ z5N=|SZtL$but=t-l`O`j6%dsqLvktlOA4bF%e5>(7P7KYEse1k1JEfm`pgAj6M7*$ z>>Ro%*hN8KoI<*2GLT$0&RmyQRdYQeg?9{MM%xgACj>U;Se1tj)7Ij$0Zs#2^Y45B z03ZNKL_t(qNDw@O$V2)JVF7##*5UvHfujaQiiXVn!#hQARKj8~u+-I#Y#ipwGv90P z{UAqiG|E##0RVG=P32E14p>14z8o5(~P@h+EEcVXs4wVJr$&< zJn66w+U`{DK{B2B?Ae&yr^B-$6Kk@nGd6}kB^_GlREnU2%uNOm2pSW1zC-dI)F&WC zC?_~1C<#0(#E}(4Z0{n)h7ed!JFH-*+QOZavYq?hF@k3;<+rl1lE-1bqab_L8K?qd z93&mtzUz+i*U zuw61?XAVyWlj6M}_$Yqp$KHwu*Zqyb(z`$K$9Vq_{uKV^fBI+eC9iq;!3}*|HGLR z58{XZ*;{X=fBX4=_kO(R{U5`B`Tc(eFMa7Vw;m!p#n#@0&Ap8-RaNmjzxNURZ$I|d zM@m;TaLxFe-~TOm^($XCPxm7^0+gx``K0Pz>iZYEv~j_-&2QP!IaNR$Eo^AQ&?*Cv zlSyPZ*}%?$?HOUKH~+o$fCK*cP3n(i-*TSZ^Rs-t$BJWLP z0AwB=?#88)!T7X1AsY6B&p^OXfa1}Ga zutYuYOp++(d2TbNbTs4xWkEFE^V*9fMm z7I~I*m@}ByvC;Cs>m1uLV0g@9+&MR6fn4dnI5N4DZyegDf%mTbJi&W6hT;^Lp()WS zMT^9wfVeUbB_K(I@q*U^)JqgRIZU+ub;wfC`VDf9Ljv>EuiK8-&FnKnaPVz26b4=$ zHk$@6Fnl1q-~~_N?%liC-nl^AY(ahww1tdy*U9s68<(wv@Bf>h{Bb=e&OaAdzE+(t zfB!ZS&8LoMuo5bN|G)?T2>ROHpHDiZTQ9E5^YPw4_z3>)55M(!-6MbJuf7?tdG)i0$H!-eJe5x-5gr?I zlQYl8O#tiAepklh_&ODov;@|-xxS|grc=+>Ohb5s!t1PM;tj6TvEt;`c3)H(+tY3# zOghGs9~mgG;AyHK9b7=v0#9-RqS)q_m60+bXCRX=0Fw)Y&FHh`3S}i+XB5`jq0fvc zgf0rM`iy-t#|s11mXWTSp^{2`wnCD?%;6FODFOjZ8J-f@DYjnFwgKC~*fxYs>u}LD z*tEu)1$Jdq_k&KfGPp#9Kn9rWdyoQw2*D|w2Z9%P=MdNc6F~|?SM0@N(TGa<9GYe` z0Rq5H0%klj8t(^Y+Yx5W9y?2p8@@+=1Tsvkvc3vVVl3X^B~>pcL6muSqdKh&gWN-b zDWfE+xb2YWFpM|_Kl7nce=vtIokN;}ZxKO`W-pkcV87p^>w$gjad~xx>-`@0FMB+^ z+N0|QyM4ris|WVEiVi=;&Iaf5Sa?iz&{Z0-bh4W6`=>~pQ&PlJPGZZ?U9abIFmHIq zP6n9Kq(i@0Kir~2J^|QkYfY8F5zV8@SLJYJkamh=Ebz##S?(jcZike68=mcZq_{_n z5&Qi$G)GYJv8FPd$ezlqL+#}7U>OJ|K=9w4b*_XT+&%E%3 zxY%saG+VT7J0v=K@8P`77jW>i=l7VC*Qq_&&l#;lp*GQ>u6N3%Fwfhf>umPz0u#>r zTH7&y`rdu~gCG6H=M5bG{*V3={)hkiKf;S&^we2B>A}W&;v;?h6Q9Q4`=`J3ypAm< z#XtP9U&P=3>wgYUJ^93~G@G@Bb&SRP&__S{yudX8^hxl){_xM?@BH;Yhl`8N-0!+D z9jAsIZ^VS&G-+?;zd!ilkK-TwAHV#(KI4D&{ojUHzv6|fOtNMSgKle)xcQvR%Hntz znR-Xr>zh1ZQ}57YVDUB)<~Nag=)$$?obU4*NL~78pJb3vXv1$~V|Y^^>QkTNHq6E- zpxx8jh4t-KYG5=c0il~Yx)z8{M z`c4@!J9L@QCm?0>YThRcmk}WwEG&r?qyS|B8%)H;WdqbK2&8aOkR|{f90Z;e0gAxR zHbX{{b0`|NAz>yPKxDEZEo-fpO`9$8(G|U>2jCcJypa=Jbl1c*Bxy1$*f%8yz}T{8 z0NDmOlN2DC(s=$wphSp8pIU=*a?Zo%tYuReT_Pfw{8()BAvv{lX>w&>W$)l{cz;iS zK8e}F>SVTp$PJy7X}FOP&d$RuHN4Y;CMUKbGFY+VJkXM*RCX+AoWnLSa^nFc9x6EJl157NpB=z@dHJv012^9$ei#d`T_!p3w$B4DTAGp5%BGpq#T6 z);6%*fW0@MUY&mePwX~5ny|5A##+y;=>fBUJQ`%T=x>Yg{izV0G^<`>?Hzx-W)`e3T~rU5p~uapx0`A`4) zV@YBA*r%`XYrpjYeEXZ;aCm;Ji-D}!{>>BcroR_s!Vmw%uRIoJ^N&9H0PlRyhwzPG z_a&ngMa>o~pRiE839Efm%d)laeeffHj34~bx1mq+$e-=6eeav_npZq^u&}MCZ~?@N z#re!VlTO%N9$Qc!MT35hjlF3xbIwOrPdvl71+jw!gD`UkImTk$q?NZ;;w(vl={i-D zz;1GWPj&cCvES$KbsmmSCOU6{7RK7-9V*op&J8kxP6#T-JjX=nMUk=?IL?e+aid5X zh{A}>dH96e*eeBS7@YsCX^m@C6Y-6qPs6WeWa*zx` z&S|v3BpMj&HiR-LOd#^m(k0Qt>~bmonHfq_JogO z0~~-RooB*Ng%+KXpgc;^wN{|4x$c}}o|kOcvRiSk+jUA(a%w$106^2t7A6JBLgiUE zNr#GqC_{vy0(8asBW6VwAZEp`7bLM%!fP?GowNP^UVwcDI$;CY{T{gh?<4}v_9six zcw-OLIARjGBLDDZ5UCLbX@*CHcR(N@ct+E1&<2KQhY%c^;IL^twryiB9PHp7fxWT5 zOqIr)GMm$IiQ@bL6fkb@@4;X~33(Zl-9`=Gcx}D+NLmKGoEuuxG4@E4aE|G{;FxCM z7;pnCZZ>`l5<+(7?+u=B*xu4;AQLw(3)?ZamXYV{9Z9jEv;nXQ1{>2CC-)K4IDkI{ zkPK!s1eS@`v;zCVVZ@k!1CEw2!%#R^0WXAYZozCZ@7Eq+CvaXNS0)eX`yTsl z2Z>{%C4-^RqcYUxkerO+odP;a(eT<7o<^ z*nT?zYUNcsw?lx>tLw>Hh}GKqMvG%0B9J$zFCwF5>4Gtz?!&A=EFBvccsQ@j_AJ`9 zD6)rO4jZb99L)x_$~`Km4Q*r6FBb+tZ64Gunj-&d+ZL{Ehkv(V8qBUkL>dZ!F)n^2 zJ+|!z7Z(@UY&H-XKfgV)_NDI=mmQbNjvE}0`pr;1JpIeT1- zLe%2St3yZ@MwfvUGxicJUR%Uwp|Swk*lMpPzhEK+GL1E{fF!~r!6BoiWOjF)vGI!S z)?@^&1H2~$FK~_!92@gZ5uO`_K=8hSa58og=E3dMbk3QzFuQ;fLx{~ag|h*DwgIyc zjIB22&A{O_3SDSqE`4wa6=V<)NswIij5qg{ECSWhDiBgPWCc=&7lAO)I0k!%eXg<( zXRNwSa}81SX;|MD;IddJ>d?Kg7;C}_%P^kY*QLubn}MRmGa%L>kV%qn%}c2B4Sn3( zU}FggO2t!IQ$&otd7yU*`=x=4B)tGsn^z>x^LCbH(K=7IPuAPCUZdNh==1g-G3=4l0X??2c)FXl&x48 z3QV(2WM=CuXaWa^jcdTg1Kunr6`@#MHm-cv$ zt6vileD?lB{KFsn73{kB$e-gce#@8R>)!B12gTJIb1o}3a<`Leoc42F(-__~Ui~Io z>!tSZ7(2TLN^MaOz{yg#c2W3foAucFI@S3)_5D*m@Q2L!>3=`sUBhZTh z=uS*iopRM!+rP(@(F-Aopic?0&qD#6b1q4SX1`|A2tn%rMuyjD&K;USl+jQ|AjQU! zNkBqC6M#(sS_d?Nu?ZfbnRw8`+yopeyaUK(3x6PnsDPD>NiM{OAR}kYm}IEwM~#WH zqQ@0LMQhBH8#i@bw1k-%h!G+VA_2%$+Rp}Fb1nr|kpvFKkt0M>Ai;v#h>CW6I@l)j zpf9*p7c09BZ$5`{)4g^XB(-Ltnv%Jpq?C|jLP~-z_Evbs9$go)iwWI6;(EWw<<$&Jwj2^XC!E1>Pn_*q(a~ppZCzRdx3$jh?7rajq{?w0)QKF%hGM7D=zX7% zOUEgM07lVjq|!gA!r0xfoqL9K$sM-ZdcSOQu37Kz7ttH;u>Li;WEzHXcpW z6yN#=7Z(?Wy*7|7B!#`6cur$v&y@t^d|3zT^Gxu;6)!$!{NQT*nyIHC@+@-s232xW3-u-oyQ42e9|A zdOUb|i5I@$>62~sCAgb^k8uCNHB!ot9l*Z-BcH+j2bXyAi92W8;Ro&eDZsw!AN#QZ z!23V^DfE3mn7G$!^Hedl9AY~q7ddRt^Q^+Z|KJio@-N?xPknax$e-aY|G`({jbHOc zGbRNSm%T~^)kQ}%pS-81#{P=AU7t<*pOXlzY1rKn*@iAQ=DPSUJ2E%`_G>9;^Y>aS z0M-|nxvZkTcE*}zr^xf0QMk!$#A%7z+V|>UH|7z%D@l?{I%A!eX{KO0Ij>Uh<2P!}|U99#xQPWaqLZ=3*I|25Yu}?ruz-0#dY#!FJ zM2IIf$%u%;Rei8#ILdHHaFo!nB9NkS3YG*y2M+-w!8>5%1i=9pfwA2pWZIZGd~)Uhi@qz?m08;~A=c=nwm1F~;icO+=xUrDPsI6JvhgZ1w*@yV-y$5*s@F8+mv_%H6-oc!E*`JbDEs2-Wd)%S%#WHb9x~PI$KU}L^ zhGU(x1WqD?REByASXaX5*4DOTvbOr%+Ry1k+HyGD&&+4#2FGUFPGhDL>;o&XwP?z% zXiCGnYx|iiTJkbypac~{g4sa2;IZAdL+FxO;?>X@DH5C_C-IC;J8CZ=ylIiPm@iGmO!Ow6v{Z zEX$Am>)*sjKJoC8kAKrPc-?Ei0H6HSy#ooz@l8x{?h!h6E2tj-xw*5?lwIP}vI$~5 z`_gBQK8J^k`5|LAm2wct$>;KbT{`IiBUrQAI`-N(86r96Mstn@Uz3EaZR7(`u8?Qg z7%_Od4#mQejZ*nE$gh6IS!)o@Xh~Lry#e(GAj|Z=AXuObnRp2u&cgff2lEu3PWSO0R6(7J>tSd>Py%?6Op98PFPCT%MgF z5T|NN8HubEi8TtHO<$_22o9yiez+G25m+#D0AXf0PY7_c&D+-fXz(|u+4?KuAYP#6 zkuveQR;cpu2Q@fnkOP^W+Bk2dGXPDvT`t3^efJa_mr_EKJleSR8GVX~eL|Nqy1qz3 z_IvEQ4iEPouCMpFy4vC4gKK=|GoQt0?>#`@o3zLK5wsi2Jf2JMy?KpeDuY<854j|4 zmcQ3)YJSZO*Le6surgudnlW~U%<`~4x4wY3BF#`Yvh`&!bxi_**=l?Wqs%35JXsgk zettOsIgedm!C5jVnWjUOYaRCbnYifDr?!1D_DCti$AFy8sU!Aec8Vg>cx%#@^bu)lBwEm7RXvQpAMJQ#G znm=d9C!%EorWva`9s>>kJtlX}AMWd`tIyf-^+~av`Kq3e;l3&G9<*ZT!YpmD$B*^*p&6G&A!;8rVM-q zR%=p@n}CC{y?>;D=iAFn)-;bE77aXldK9*7vL@CDbLA0Kt4!>(7GA#g`q}iu_4ULJ z;UA(lD3ztWqnZvm7Yn_d3`}=f3{)$jkA##NdsXzA@vvva1neW5Z*_*X^?OC1N?f{# z`B-Z%G2^N7 zntIH|YZ_`I872WqCI{*Jh;H8_#)vLuW3Bf+_Fcl&?i#yYhkI9hbX|wbhdbQ6cOMTP zTtc$Kho-F0W9)X7hSZ_Mfn~1kA^@sswyxxwrBDDdu_ACl69Swsc7aqZ-+bu|xUtQj z;3mG-9>fkJwy($D*!c>uD`P*^VlSiUXR?tS5CH=LQ3J$Qq%h;4E+1So1`V@EWHsfC zA&215<)k`%z-HixYv7P|AhPH%N5HH_^KI@!bcJtzHP~#! z-~w`Idtu%6O#|=j`xl!QPu_h3Pdsr4o6W{F*seO1SO^q5408b9d$4x{kyPz8r)%iY zF=Er4lbd*RAL)K5aryl+3|;)Vjji+M9-rO-WlLvuraBwt@Vd6LKL5906*^901$7BQ(TWI`#xdUb-23T z<9eTPb+yCw^)(*udpvk>i3blZvA^0w#PqJNh|@_K-j9;O8Wd6s6rK)d%e)IaTI@Nn z12iifJ2Xu|)A|w~WT32V8?>RB2l^0$!ls0XG{~a%`MQKeCQoS^F6?>+vsn!09FH>E zOEw#43LBcNk2JwMYlKFPs6Qq}sO$1F6laQ?hK@%Cp(S+jK_?% z&f6+PYAK8CO4v?$PRI)OoD+H$bSa`~8Z?c9xhs+Cgb=I(-pKv{03ZNKL_t)$bmz_; z+`W5&yLaze*h^C^`#20zQf7w09wg@+9D7^Y-K5}H2G+R3{sZvNx?)`Jv*COe`@mX& z+v`;Km-+0&Y%um15xf#Ac+Tq9p8_XqChfWypkw8e6?DdFjj9%wZ8>-`)we7^L~x%w zFy);qaj^B-ISmfioDR0zi_giiHIA{}v`77;Pg%*$(xcFQP6~j#7wtiE=ds29oX_&w zu}L1Isp}2TiqC`VBa3l$@maHm8=MpT>0zU(KkO2KR)%T~WRKU;osfX=0Yx{}Fs|8d z-K1T2u46VUINVaQQ?#~Zt|?rYYf=RZz$N9Z$_%)&SOEf5A7EoC?YkauuQaFh{{5ICZ7f{i!%#GSUq#uM%|#Tg_pLSTeo zVKJ>IG>wP%4xuD6GPALcOmN=A{2gr3HJ5{NP|Fb)5L(M?nh&0_h23anxkbV3kjs1n zXEn<$DPRW*;&NTotOeJ6qIm{Lt&nQGpC$9D3RHuIX=O{E%f+e3e&6H=)^Sh-Z_Y2` zWE^(XVo#=1yEdKqDHEn3yLvkFLC5c$ZRB#_ART$j6aCNoE)zuX)_YwC$`vCiWUxGUvpt*P=+e0;->!_c*u2I!;ZH_f~^79$0 z&LZj^BLrirO)*$V1M@gmXWlrFuT{K$g({&LBI2(FI9_D?_60eyM5ey#~ty=7P)lTnvhA$fG zDX}RcaLKxJTpTvI5(GJ0xKm-iK>;exWo#?RJCBra@@D4LBD4cJOVH z#o4TuLI!|6g#Ykl@0tK^S6F`++QDv-ebrJsE0iZO@G|5G$dGnAy*@{!%XB_Xc=~(G zj-@J%p%)S~#Ap0_C=;uV(T>8I|Z@y>>t9^=>7 zeEG}aox2s_JvNwmaPta=Ad_k#_4%*$uMomPS7><;j7~s@&)HIAT?a*~_MK>yAn_Ck ztUN2H!(R*x9RmZ$*zI%c)lFPL#-Cl^JjcJ6YFmo!p%hJM)s#yvjI{?TgP1_b$cd1- z+ALPdhpqQANnngns8sof0q-n|oEcFv5(F`t?5r2UJ_E6MUZ+gh^@@Fh4KymS>w#TV z?2>t4?^A+`S)OSw1Gg%GX44;%n9ngQ909=@z;;OR5O_}Ttng0JIz{UpHr}IcOh>(K z2^%JC0-<$egGUX+y9~#QP2)@Oi)ldHHdxV>&F(I%KqVJ|X)YpK!aInI1dOKkj#KaJ zx(?(?l5mX@w}MAter$r`WlptBM`3^l0yMU{>U>SL*aJHKYsd}$My`9N2F0}9eeEeJ+7{I*eAvH zZimaO9UfloaCy~Xx9f5F@EVtwm-zJktK#AkU_<9HDTuR_#NgZvz}ELPHh>eqiH;HHc5s+5mH;8$D*4Dp^IrqWHx3zfJ(Q)7l)4|)*0CEdN@`zfw1q} zQ4WN0Fx596!3B8d3yW<&(;F&d4XBPjyD~&t))vXAFE;Sc1EVzF zbifJRO325sm?RL{td6j&;H8qKi1>>>Mws~G4Cu7 ze;Jffndr4<@;yS9bWmkA!Qrc4_j3Hkdp`15kME1W@LAK!(NrR|06I!TJFsquGj^T1 zSd-Z`&(#@&hW^;>oDZ!Z`8=>5!N91?pSECU)B00qkqHxW_*#<+pO)=UI_ZON6X7yR zv|O$O=7W2R893(#axS7=G@WSYnUAhk!7r7eGtEF2P%@uqrwX4k8WFghO`BZX`(Tjs z5YA8%c*n@>(L0YQ9)0f1AR>^G8(8ZELLx;F^QTUUA;n(Ltn>((JW}MMOU~GfL(Cp~ zVf2X*g>aoL+I$x?c8Rc0V!)xKnLz_oV$oL{*HYtcYD5S8EGPuW7 zVu(vr1Wib$ZD`;Wa4Lu@01LFVyZaQ29vet0Lt}(C4F;RaY?03)*zi{BV=0IMAsgNU z5!5M|fh^I0hE{MoKF5_^U$bRhW3JbLZp?yIJifaavD@!W60+~nbs6{f9WEd4ae39@ z^18>>)ioYmUg6$nAK>A`Yd~}Wwpy;M3d2d!)oW!NrRaL4IJ+3@SP8ym5mT9Z@7vMY zC2(=4@Cd~XqV=%g-*ui4AZLtK@5s=9;0Ls0<1@JA4 zm>IcNhujq_MH0=t$1(9AA3{ywkW(J4C1uc57hvow)6G@@Xw3*>FflU5Zj^{1u*0?u z*lrs%0cagVJVT{?4q{~Wh&iB%9tn3A^JK+Gzc`NcLTI`oDM=Z9*MTI1SPO7hNR9vl zeTw+hy$-v63lQOnC!fSs>fx`hp-dKeUe-?CD3lbO(>Ul!qr8sTHYq9I@64_YvBHuU zEB>O9Kq9z7XRWMd?e_z)o=Xt9Ui{63{Xijsb6c!)x%4cYpY?$wZ!c`VL0-VeH7=|Ae%Ij4`cS&A7$o*%!w=cZ|k z07FZH8xxu5YLOr?%5;0Qm}p3bns?nW2*)M03}Oj^AcvH)NdO$mZb%Tv$m)>AWCK~* zHhMK69fi;(8|V@-fZb<8DnA!95XGTOgnhQy@?A_w*#LIRid__R*<#J5c6&5~lmX3P zNpNJ&AjBCB1fB#Q8N>pXh=7cS%?%_F&^SUH9NNZV+bA}Huni8aFK!?W71rB4ts4&n zPm|;}4@I2#)UG>D9m<<5d`6X#qLeFQn;{dISZW>G;?!^^G=HQ?Y4z5BRB_g<1kx4KDX)qu7Q9o*lYQvCrlW?HXR)-w&(? zk9h6ZA@L=>v6iDS4x5hwGt=v2{@%Rqdc-C*@e&Y%!?xX+1tvQ%Dca2jAvh}s$}q0U z*ch&9NByy2kO}Qep%t5cJ z$2+`qX8&A*>*ZeOkHt9&!rLDY$o`Ap`bKOv z?a-1KZXBhP1BJ)h=g&NSfv@|@FT`*C?uQ=B@qN#Cd?T7od+_ix77LKB+Z3(ITaLL? zEISBh+Y|BmuTm@$5ADQr`s7mp^fpqTqpwqKwiEfOOtA!U!O zYM#|9=%q!jpgKu$2_ftKpvKYxHVoYIOZ^*)H zKmrvE+V55AAM@yVQCi(Z1SCr~Y|1|AMWAf1EIE%rJEdgjDkO*x!+eAzlook_r)taNoB6fYmb#I#MtKA+~S3SCY!u3^;`}ZH<-u(yY zx*kjpjAn=@tplCa@uK2}2M_lKj!V$TI9OdeoiWbX>t!fS?S6Rg;k<)u0zwHX*=`zm z&*gQ;f&MCyFsF%tK1D!H`Vp9sSpg4-BV51_)`TOoU+yf0vE0jZM)|BP=N$1+r9@$( z8@Ij8Eea}2HIlMs%{=4F@~Hq=1-fI%wJ*b~pMBz>{bcPX+$iyGS!ojy z-uw+;f)9N7k8%I<`T1gh)7O15o_)!knd8LZb;_sxTZcte4>h(n1Vl%VAFxHzh8*1I zk@bpJ@LUkfxefYU?D%cK_-(?Z9>vw^YzgkrPT1XqR=2_e|vU(|mQk~GKaFcXR?mju6Y--=nlD6MhWxu}jJbz37y84S~*C>fLRFziLDGRWPA zmNwI1_vM^}6G6^g27{$Imt?3YkP}>D@=oHK+>rwuoPN=b+7-Z`)M zQ#lnn={QTuLy*jV-(k1w%-?$7c8q}b=c zfwRhz042#F2Y64|c!npFhBQrsP<^kn0@(&_L(^ijxquI?Jtuua%sp}+k&DXStJ`pJvi3vF*NRyFk zQB=EM%+Mks;an3J1yBbEw|Fi_HxQF|m00!J0IHkG8cf4SY-k_dBwSmVEhl7q~w)vop8qR&fzb;k> zsSWPwGBS=Zy-Zd!cTpZ!|=&_DlGT<-cuI=+{@@Ckg!x4a(P z&8BQR4C3)UxC|8@3-UST@%!{scku(?{ipGRKk^Ic)1ygkUia!}@a^CH71&HBmZ$H- zIKzJ5a3QFV7CR#t6i%bfZy9NF!RdGnrSKoWA_gJVSQJNPI->_L5miwP`h)=;VVT?g}Ubv_h-UNPAT zF*0TJ0_>C!Gou$aySTDKqR3gS#j6&MQo&!f z*z?GMCNK$tW3a>lV0*Tpm>CY$$85~*uIsVyJGkJnaic_( z;6RYca2QPpHJh`k1J|S@fo21Y_6HgV=aA~Kb4+3pBV*r13qEpOqQ12ZHI{@yAIw@Y zi}{+n1_2GS0@6psJ|mW*g1ar>`-iBS1AWBA*@&1#lj~7MCuuh9|0ikxhZQJ6BC!WBaZNPThV!Pd%9cQS1 z*#T}c12EicF&0S`k13CnL{;ZxaNGgQL4E_X&NS>bFp5j6s+M8W;!RXKE*J(*Pstu> zv@JSG@~m~-eO@rIQ!)2|+7BM!xsT@>eLmb2QiD%qRfaOQ3PtFja{H1UIT3l>52iHi;hO&&HJqD@#s%Y; z{_Gr}y$QHJHZXmggt?ovT+hG2GN!$B)!17LRtco@seD8MVnXhEXrI7c58g*$-$T0| zE-RY57eICf0viDZ4;LJQFBqL|bCx1T>4kAE4m&Z8b=PMkC3FbbWin8m7+1Yw*IPoG zz~mn_&;(+Dg$uAIB(Mk^`jWDk;he%zE;Boc}a5j?PIJz57ep0Noi zX^R#P6C9a`b+JTiebL00fA__`8wwlvL*3+#O9E#>F>0W4xj)b_yrghsKU1ChhW2<( zcT_+MK&uvZTA0S9Rex<7Q)LU}VmR}}RWU7Qwd1QM0|h9~+xJzLHr{`p$7prQ3g&3V zMt$y5hUAP?oEahjU*sktf+R&l>={j=vn#MP4f5y}TwC6!bk*l%Bs7t5EE5dpshGtl zSt7h=T-@0rCmH>>YiFPYl8o%E4GddINk*=nYMG>>4xvj{bP!5`IZb^vhX~UXNq*C-sk?f@K_L4%8r&HLbUE4xTJ9MMV&tg*SPp2&L!^jRTbk za}FNt0z#-@*MR4~PY`9eOz_$C&q>&_5fn2}KNOLZPL7H_Peg?6w#CI}V<9xb;o{-~ zZQEkgw&noi#`D2&U}q8LO2tRM$nIP=M;m6wc4LKr(*{n>ImUF_BRN~sLG8MXV80Ty zRW35l^iSs2;EwK@LovD{T|KtH9RTceo2KNr>Sa4TQ0J1Qv?L7DafWp&8CkZojMe(@JlC6Vj0` zh<&fNdX@m&^zA(OAs@48qwxv&Jepo(vKQcbX>TZ##5kQewhVnG(Hk?%r`YthHua+x z47Xy<^_0)I@s|plXxAEAldYwyNo>u}fb;_F6ZE=Axa#2c2`&koFn9xCOW;h z4vx(gBk5F5s3(W+>NJ1-JT;n8Xnl~mIy%(5)e$2}NmnS&Q>MRmP;Y~YP%iy+w91|&wZ5pH*F-D}+4}*0K;9?sPoQK2&MIKni z)Mp5fnqk%=3(+(tHP&mLWu{}!rRcZ_cZYjtz!WlP<~dlz_0Uz$irua&UF-%4Kq~j6 z7eyw9xPV3-LQ~`fIe<7pxdDZME@q@8*zbB=US8tf{m)>x+l}1{iGxPnK1-Ugt}+1Z z+F(DPWa|&u=eo~Ta?GS^JiAu*+A=WM%hz=v2wOs=9gE4f9J7VXI7_Q!6$k+hs&!vL z(`<&0@2-pHlQ0>~)hy+D(M0MqI>6+d5vw^yDVn`^LsH|m4QN}Bi%p9V+~9%F<(Xi1 zMZ)7I#n$M1UJF0F4xRa{hXn5%c%R{1fD?e6Ls9{AW&W#&xtRMYx27{>%U3&+yaNFID1AyTqn(;@!O^@lgNP#WV+9 z^!W3wE&u-hj{pAO{1yJyU;XF!o4@@T|Mq|XfAN3(-~SQUo7;H(ldl*2^}qb5_;3E| zpW@H|^e6oE^-GT$Z;Z&<`O+bv;4@b7%#NnDr2gc0KjDA;AO1D|yMOi1@$diRH~g>v z_TS{@#pwwfB6@9yIguT+u3SrtkiIPGzf!6Z(+2y zTDY^B8W*8skk9e{Y8&>HBL2;P{pTpn+uQD2(4T_0!w=hM19(Hk?{7!JIGQoTc85*- zAEw9BEdaxWKZetc92T@d)NlY4ue7KaGX|) z*1i^CbDjup-Qfv*M4;wvElt|v=gaE;(Ihk^sJd3JcIIxOhZ<)eo8_I6Gul;aOX>r% zK1-?hotXNOWYw+#-rCi5K&vu|S;dRAE){Xm9dq!6K@o@~A2^)1HaQVtDT*i&TEjjX zAQ^`OKYM<>xx1Ke!F;qhuUG73D^33Y4wL!D=?FR z_0`S0t`};dm3YcQVO$2k%Iy~o} z&5B`hT?32=A0IdT;pd<6@$HK1^@=6mD$w0@;HnDN;={3RPit})seKotr{L_q`{Cem zhcV1L!0wvyx-W+zY_Bul#K>GRQizC&-FB{OoEsDF-HD8-5k^3$_gYyq77@sru?i~w zAw&u&)b?9bHN`U#4D=Ik@IdN^w;c4=>=duDylPv7t<9001BWNklnO}=hx}Eecj$+tu+RruI)^97AXMcHi0R`&c+8)1PB5bm!GsjJF79%>iTsuse0QzgLk$E zjeB4_*6a0(>-D2YjxWoCER`v)lz#}$G)_~(+kEjtC#D)H?fb!Hn!6(gSMTS&_LNTu z9^LH;_XLL9AFk_)Z@0ydce&yF_YZvgxVa-uQ7p@foVnZh`R|7=qik{|05zp_Z-lTB zS8Y9#+Be$np$OXD54*LJ-9UcZ+iIYXNG-0UpHFvXnZPOb^A$osYHJ!hqFQqHxb$^J z&H{yOYg`eOvi2gYW117DX2dXk9&1?Bk8+Mt_A~z7EmirB$ZO=E4xZV^`2=Q0gjIJM z#$`%)yF|QC6W)?D>^Hq4#Tl2&1@G@)@%Huwfs-f4ir}W|_h!|me=I9LR@dT-8uGgI zd;jC(1J~;nIWJY&Krj|uE*E@xd&k=}W1blQ$=7%Mr~l+9{O;>J-rpv?&DAA@y))L% zR|uQU<5-v9ls&=a*1{lHzV;qOBqfonPvxLW>6-C@El+tb=%|n zPt%0A#!Y?#pdRU$kBie$Bc+2~*J(ILcx>bH{`PkIy5q6%6NYgd5*)$MnO7zNP~^Lo z=P@9NhG^1xo*vp3KC0Hw25(-mlzL@g=M}B-J#hWwe9}+n1x`9O_n>v-p&v8w^y#^{ zXW++B03EtMI6d#5+u-r;bssU!=R-TM>Fi%V*H03&&bwXJ`?y)Pxm`7gHgDN6sn$C# zt@W9)&AGGnkSs`|JA>^1ttxoNeAZqYoqhdgD zKW#yVYQ(Cswr9}+Hrke}hG;7S6l57>1wqvZ8Er*0*Hq7DNOgcQMVENI1($@(DdI9Q z-X_;lU!oI&Q`1n_O=*q+X{sQUeYSx^aEADq?jF^pK=mmjbqBJ6yZiHzXYD>jr9joS zpN0%EhN-wC2!%f6)JZCK@W<-bc^o{@1?GHvE-nKRGWRz(@gzIA6`4UcJ?tZ=Pa= zi6DiD%jME_xjAT+DVV2F3U&bfcuhwi?D6j+4Un89JsbA|OL6WpgUZa7RjRB+QPj2j zdhnB8*A-aTZgc3)F4Zxmx|I2`gwCi2_NPZ{4}5%lAm?R|{~}?E4tnP~;p(`z@AWQuSjHHLqd>UkS zC<-4+M20wIFm)!brAe9@ijF?Ls4hGeG{84HDhkU4WP^!e zQulL)d2(Pu!p#bT1tbMXBB(Ip;_Dcxn=ltF;1Cc%NM=YPh*FTuFoW<0#W#dLO|Moh zx1imrV#W>81a9V+k<1W~5h!CK1*zg&Iu$*rwSAObd#5L86Er7hxXsLqrf_ zFc~noFk~q(3jh&Ppbp%6dD*qu>;w0;m_i-k8}G-a6+L72M*z{13MudbSZwU5T7gLD zT3;Ii*hUgE*2__iiKmq4D#UwukPxOG|`s!PMLuh{3cXr+N%!|M_XKIy+w9 zGk|RfgWOX3YqY&ntn8ek?$;J)dau{Tqqx@%6H;`s- z9SIX?DJTjo%Q8f_3;2QL^U*!(!l@Plvq?seB*i1?W|M>{@2!lr>F|fbr7^YpE_m^d zMFB*b#ojwOCh+W%HBrKC5r7JalNS)xjmI&TffR@l_;O*)7eW@px~}-UpZ@_L-@n&x z%+h5mQm^qPIFOzKW1b?ue0j&0x7oj!YQY{t)zI6%APKzd#6BZ9x1n6^p7J3C%=3zr z66X007NtvwtW@c2ls*_a;>nJ4>vQbn4nesUse?-q_=oVw&gqT-goCkrOZ;iEAAA#dXK$||%vVO*rjtuY_ z8~j;C)belk_!CD;Ky&b z+&jBw&CLi^BUl{~%%G)UEv0Xu+h(<$gAkL0TX@1Aa{v_pYk{o=Ap<1?lXycLC8#@q%rzJ$I)mMuKwIo63crg{(9Rl1% zztbV}TQ_Z#(Do>9MZYecJF}X)DErjwjexVBgxdyG zugeYJt{?dF{#vh{I-6{L37WYFdO#60a?aT zLo@<~rd??*%SX}HDW%gEAQ9JU>!?}YS1qxgh*O~Whz;I-k6)G>oHB&=8mNBUrhYzg z`b^h-pL@SCmX8e3pM$0IW4zbW5B`qF_xJ$~?JG%QVA?FTUKxxV&o^ji6Zr~Iy9d_% z1Ay(3E`#snCP$F}Tt~Wpt=&0m=Vv_U$6or~=MGQX@vjsWuXGFU?*Z;w%Flj(Y$rcH z&z~11N2c)jdTrpY>poRr)go+NSFF`vwG{1P2hM_4#|R1z5-2&l!x5|u&Ys*D7eQPV zAp^*OX@FIB%t(=hz=(h{q8cW3hB_ugARrs#LW-|IZEp*%1^9^xLJ8l=@LfvZOaoO} zNM)^q0kP_<16BmG9%()?@IEuX%!KzjA_k8)4^c6(VTx2iwzIY|5$5WX%j_0&RukD^ zE^j&NXd7-m0*NEQKI=%Kb_DwV@E|R?-!CW6kmxA+sY8=c51~;*fq^RP+}9gM)n7|p z-!@Pv?g<7&AL@f;XRfGqJpia%@u?9|0dVuiW@sI3Q-nhf!WK*;gVRbv42BpKg|y09 zYKmk4Og8;#DFULkp4%DIG(Jbu&e6eVlLTf{wJPP^Q21wiQwQZyF<%lw4k#)h+h&2X z2uRPP%(r{wkPbRuIDruwWCavMz60x4Vc zyQrVvc0irI)ZyHifm=7>EM;`3!QSR~M%_COasu0`J}AMh^sLELxywF#@Z?=`vF(Tw zQV0Jas!}DFmvyI^nn0@L1KUf^_3FF};)YXg=hn)pLm)#n{&>^Z69Bsh z`k&GGpUDEA0hCu|6VI%kj)PvGRm_jx{|wL{7u+2Kbzq6wCilvu>@ybov(NcT@o={3 zzM_-fuK#Py=qp9U9vsU9@cl^Jtaso0V;JAhwdeHG@BOI0eP2wC;VtsCd+}Qc>LZ}u z5?*nq+4cBrw_kInY>VMtmKB-{mfV62P#rm_4`q4ifICQVaD8$xAY?@l!ITYC0ZKM- zsY89{!4N_L#)J&QRe@-VHxYcbfEkJqJV9_G;H`!_r~;W3t15s3jf$U{PInATvJ z#|eNfk?^czq3RlV-!Jr3mcU%w?*}kG4yEFWWW>O3^IDxMsOBXwRcl3U8fjFWuj?!u zi|s?(0BWbx*F%7WfZ)YZ8w^x+se!ZC@C*kX^u{KeRU**6p6@}Y-2sDf@J`e>_@at1 zvcYgr>-T%L!AosEYilv*#UZYv>QCS;WwdIV_lRLmr4H*c|dduLFg z-hmm1J;%;&3mrMzS6dR~uAnEl)Tno?>-EA0xOa?v*lVtjP9eJ;qmnCr2<&=p*$+AD zAXyp<03Et1FveOuIa6T;skabqCf z$)iI39$+l^R$MOc8{1zy2p&6{U_Vv&Z8aONy!=Y&VXv?Lq?l zrrvaY$DxcfuwjGs*{gBR&%syu6bwCciulYi;uY}sjOpciT}B^R9GIk6HPXL{VSdOy zVb}6|c-}vY<37=btLn?wu*aD`=4{dYAGbPkI41k!K=$kICXD;XYb^HoDKLJ;wdA+B ztUS};H->m){7>d2Y=5oqULR+R;2=3s{Y@I|eOF~a470ySgKrG#P8@6T*6*^cSe6xK z&A2UY>6MEQ0|5=}dIFju0t|%c3u-VRsUoT2YspAAL0ko#4VnSuYPCj$Rk*&U2fX|Q zszY*usRGYL0%LJKYG4Qj6f*=BkQR_GC}#Mmz>Ot?Y^~FlhKUGs$gZ)TBj!Z7M8cFD zIKNMdOC3z&=z7OQK#H43E(NLpu4-N(Zuh0~6ks#OQwM`l{vjeYP;6N1D(mbzV>|7v zG=RNhi0)>1unYJA(1T|@BHbS~?{+ba#5)WSuzF;<1y8(dAlq6HjgsHLl^t|f8F!a4 zMb&l_4AB!m#Y1%(x#U2}PUU6CwUsMt*v`#b3aCm1j^{v3v6k$~dUsLHwF4ss(Aag} zn|lJ^?`!1iFf)6?9e4{*X5ViEM}VaQA_mAk(hdC3Nnw+a9ll4ykYgXkx?l560h4<< z%ed#1)z5LxsmnUnDY_1q-OF46kkx-%Z&;RPkWv(v1jUF*ykU!4kR$B7@9q0Lovxp# zVLuXxG%Yb7Y!hvl-Jp6;avgoiM@!$nhp~Iao9aWe09Ey2NHe!Cq`f?g%rLju_fkL> zyznyh;3^?RRHi*lc%Lu*GnG<+vbukJ$*xG~cGBFFK#$t{cAOz@jPGV~IPRA1#c;<^ zk7|d}z3NOg5UK>J4b(16hRClF$gxBR)pXo z25joi9A?n6BCLk68e##o7+9RSHUd6`P^3UuaRF6{hk$Px5*S}%fsr7vAcllDPFPs* zMHSfy-&e(?)yKMlOj9rwASk8@m;-PLuC2aIj5#r;X!R@Mk{E#%vDyZPKwtt=Kuv!X zh%}qIEwm+u(3vD6+F5jNKwuzHY_pepxQ-qEtB}*-$Fm}PbpP01A}g5+9# zxQokZ0oZ=8v7BY6kGE}LH}DP!w*PO*kE7zQ4?e;_uRDU#UM^UHwN-y*Hctvf;NAW| z%CXD@qI|keHjr(~n+sW6t8LKck4e#Vzb-6TVFb*VTnmqa+qxjGo2IvaUeO-;-tN=B z7O6lFgZ-+y1qIc+YAkj}SFZgYxwnPuDWHeM!=C?fxF_1ri3pTX{pI)jbR*m%#o<}G z2b-p4xTk?exHrq=vgU0DL7fY`wd(6Pt**A~Hy16c#BlqWKS^OS|G2-i2gH)#+)GkL#+t4VQ zVgtbkKY0V!I=tt8zD{}qqWzuIG_+cq}ku_S3@v-CuErIj%w!yRMQHnq;ckTc>s&TWkE zZzn~X9wY60z&k3MsjJze|B3TMp#wxyP`;<5HN}c6lHwpfRD-yzbT`T zB2$J?!Ji4h8W8b;!V7Ggz<5Kj3qXp36}Q452ABjtYxY2o#0ZIDZ1@_=ws!q~T@H~jQ|bVMfhuXJ z$#vk)3}!8e!q9bvSi(H|hf{L4zA$1W7zwl(#H6xylLIuh?yOLB^kv2%@vu$m#eVIS zX*W#Qq;bsD!@+=bFX7~E%^M2`8|<=1t5`yMx^Hoa!1an{iI50Sy4?X@8ER(hgOj7MCB_J?thB27?1cb%5y%`dT`maK zN4`leU<`qxtgB0=YU*g*`Qp1pC!|2j3P|!nQF9=BxlHwbVQ`hG@KBr+JYeSxYaH)~ zv4}j~51Z2)1t6;y62BkMvFt18aUjrtqo@%B#i1 zS>f;$EDz_N9!U^h(49ZJFJ8TGUP^s>(29Ku`0Y7^te-rCP{QT<;AJ>AVM65aEx(b$DKnS>e`3kcP3P4I3krN_CXOT@oa>X))(7X{LP=s(m zQQ(>l-ZUy}MALyV5Lkv^9r-AWDBli5V;W~vaCI@stD(v+)92P=TM!J+mH zbh!)ld4?T z?DvM`KxyrE6F{_TWfc+%QVOo6ruLo%Ax415AgM!lK^5E>e;m&JFr#y1BcBDYbuz3D z^~D%YWs&1hq#e9Wck6pdAQ;M;L8d4r;b$+&M0WUM z*Wsxw?OGh*Sf+?|olwfO zlL+}t06-S*<-rg3^rQRPu^ZnD)WCPM9Q#CO#<~`We8aS^m};DRrvaD|EkZT)MANY| zv6uJoP-xb>We6&3#t|dPj^946NbDg4Aq1olJLNz52xf0>O)HuMEFej|Dyo-Mc~q(C|rcdtq+9-XsC0QRxC<#C$jD}%B6tQasnEh3IKk!L@rYNy)rQE$2b`_`^( z8o~YHjNattP^HPk3e^@o_hBJz7HHK@P?~3TedAn!QW&`aIU8=P;&u~!TovCx6yL6f zB{Pa8a7bVQsbGO25#qG9?K~`L2UA6KK>>{+cr+F8~ z#0a&>sP`ZYO2H*Wq(1yaTpdirrw{79(Rl9mG4X%}8bXfZpcj>%gt&9Tk%CO@Ep1ed zvO36-8a@PLa4;Y!!c?CxCWHt?BgA6hXkfM8Y-=oj{bXp)y0r7*N0$P$BBZf{K4XO; z6>-qgR?vJG`u1>cW9*dFV*1!stuK?nD8Vo#M#(;y#~=?kDgwz1BrnjiqR3hY-d3P> z*;^1>3(B#>y*CU8O5KmT|1$f`cQ&* zMi#a>^l_;2D7)ou@wX8q#D>VuMo%#!h04O(wpNQs^^R{rg9Re@snv2TU{j>%gQ%Mw zYN;uVTYA`M4s2(#v$htD&(#=I*lY@S;2fb#(^~P;*1#oa8@S$U=RMW2IgU^tRIOH>-@bkG_(_>?N$w$7)R}^{zIcnM)EN7lo|&GXd2aH9 z7Qj)$(fE!t5ODv8cZ=W2_?Gd_Y001BWNklOERn zY(wx#dNj}As-4Ehl;uJwt05P{vI4i&a9ePADK~Xf{;QrLNEbgLI^W}fPfFE zt?nKn1tnkoQ$;~!!?%*FwU?r3#?1^q5DAug_l?kH27Xp4F#+R@n zL69H_mH`!zDP}JC8fVOLMq~woYpQPyXdqBhggIiKY6p><-JX*m?)<>DIM5o&z2dg6 zxZM`qmW+?v6(6^Pd|R+AxyKHV(ZctPSn=reIbxb7ywASbT&4*W_HquYUbs!047f~a zyyppzgTPu2LIb>QJ$KD`>HfR!ctpE9kD9c|ypS>S;Xt4O^qfYOg1?*z2IN4vmIkMqp>@Y;FBs!B9+zk@Hf&CgdEEmmA{yENQPhLYm(QbXFk3X}4+`HO*QY7g9XU|+XezX{Q<^9h<^fR{oQ9J**Am3kK+5bL0 zI#%n>0Iju8L?|ZJzSAl*O|=zS*)*+-QDwHZw%D5GXW`HpYcoP={=`0?4p{^_Gjd_v zR>t*4xGjp0Mewl}6q`WF0jgO7+k{9L7{4JGLYihs`GBnfqTgXwd}u8f6cSt^^%`a@ zvS6};MA|LYzNz77GW=XT3H=KPBnkM_5b+TbzDdC(Kq>}EL3(Fzm3m_pb0|OnbOJ(T z+?bF9fQdnG5r9^L!yO|+^z1kvX!76^DFrz%Sl0#XT5w%%`2Mlt*I&Nlmk;-|z1>_( z8GaQa+0!_R7t-Dh60^dQZ3=1GEmCcq2~hLRu}S2Rx^a;A+ftQ%xwJ}uWZ z)6pbDs*9EnO~tM&*g`}$*ONzyiq7nL5X;8UIh!3|HIxQw$o(_7&mbNZUkelIpLOogEg|h7hPdaTT)|nPr-qhVcv>Qe_jY7 zFak#yZ(W;Etq@ysq?1MWK}<|j<sE4TyL zkMca)deOQ9-SfWb%T;%dM7xfdaZeNPNxxaK$_+VZSP{(g3=!#8ni49uCGImu%o!BJ zps$a8t@LA!yTF=Oz{g*|e_)CUB8EvKrqs;b6;p_q=HwBhridJn8P()|^BEk`d}BqP zr5gU2lz{Qa{CU;6;zuPVkHTUefw_nB2KsH9=0~!S&otX)d(dilERA_&-S?=abE-Rk zLF;^WyqyX7#4q}2fpq-51@^QXa+YMd*C5;T0%mYtFtwe=yRiySHQh`P9T67bu=R-_)2zp@BeN!EOgLE5OlZwZ;mo!KN&V6Xn!MCEB_&2+w2CxZYVbjkQ2iE?5 z_iz>q5UqA=#bqMvD!45Hx2xfL6Wp#Dw>6`z0;2%q2ji27 ztN~M45wQT}1FAQetyr|cG-D}O1T6px)C#f)e$6XBK)4onD3a*Y`F}gj_-Xor7y~9U zL}VWrw1R+whyr3k))g}|zH$Tw!zBbPfgw|bMh3^!WqKjDE`SZ46RZBuTftbe;`*`R z`}Zrpf86~4Zwpjx$6!yb}wLfD>cE98_xjmgU zKyC&CA&5DvRuqBNHM4Ml9aBQ8vk|OSTvd-no1~>N_^=M&y30jnJAF8^I;YfiDpZ8i zK$tq(0Rf%C-R3i@G=m=Ri{Tj3#fQC2-LqYbRCfyjR1m9tgvk&CVU7W1N?7L!TGJif z0>+Dr(Vx08@|y%>A4bzPxRLr$XQ+dnI@t1sK;7p%aFe@qagbZUjiF$6zuy=(In-u; zumQz&U3aq#e(#haNqgEkp&UVJWY1L^*N2n>RNoOJS0G6!H3?ItKtb;jD#Ne8*bwpZz}TAWKjdsm@JH7M*;d7-_?r<0`c z4!kSY+PUFm#fRK_{JPIE%t)y~b*`>D+dUC2!D84aK^pI@IH~$&x92|o`pXs5lu^WR zDG50VrsS;k8X1$M?jtx=E5B6SdvhuUp|&c=w&T%5@|lF;C{eH%lLU{9nw`arW0MG+ zUBu78;6JuB;uIX6OOLmo;m54xLk;b4E{+ldvIlYueDe2GE#2Oq_B=QsJpKG_i2bz9 z^8lP4lP7=V8a%6=H5z-{G9^|3DIKG>2C z>%v%W0kUsoY0eE3K~AhBJ*l$4A> z&9`~R90^ivXI-|F2(q2(YsX=^XY(OPZ{VXXmdeHkstMFwDqy0A^gC2`a$|`N3giVE z6|u@cj0#M=ovY;F+og`7o@Z~nYqectqUtI}-3yor4%RDE?y|q?HErAM$aY<<51rky z*-htKZ4@0$W+=Ps1E)}3Mx?r@Xb+c(%$PV}V#ZVhJtk&M08%?Q@F7jA@$ZqeYDL@A zIphb}Hq1+vg?121ZsygszLgyx1}8^ytu(8<22N~GC_E!Pcnqua7lTOwNdc=OnPDbE z2?3HKG)1H`V}2*R2gVySJ}wD4XB5TG{!mOiM3?_aKO`ukTEi?XM1PW(YL- zYiNOyB5=YKqDzm4u0S9|(P8H_Kt%hjM=1q`oZ&AeZ7G^fCQ?>}!aF(f7R+SWhL0Z~ z|DC<@os>p)t>RIi{VdR`4LeIwtd=2?Ygf;s*XLP4At1HTok}W0w*rir5oseS`ntu| zB{cDNyCLV``n_pFN&)kn@c!l^@GKcAxE@bBh3+RZ$B0x)KY(^3Tlfrs?#p@Si}(O6 z-2eSCqwIq!`jRL18L<8gygwVxdF8#H0prik!!!2#GgflZGW6l+^Va__RBK zxc~h6e9(@bSFb+;fX`+CnndFjE%Rvs!~C2%wu9HW*)|MxqWyjpo&d1hbr=-xQ{ zJg;^jPVXgkfY4+ceUqpgl~k)YGwsq1tw7pa!`xe?1~?0?o4>ZQGqT#)5^$epH)7-p z6tg+oQ;bnSDB^nV3_;0&WX8G>)|)|Y0$l{Uy5_k^hUf$h&dy3?q-nzCEh4P|%>Yk^ za3%2a4Tc*^aYlZbB1(1!M9jg%Dg{f)P%|Wo&K!Ci2?`V+BKU(4elo#N>lI(q1@A$S zC}1k=X^l(>l51L;!a}U^EUdD+CnTUh^xnC;s9IN!-#|kjsetz#&*v3|k$R8Bbdmx*~}qs0eZ8MaBxdPi_0k=)hknB+;F`3krA{_82O9<=$1DY= zh}&TE+d$LE7>AZheU>*tE-~32&afM-^a5*>PWUlZroOJV4NsY!ORe}w;2hX&5$!|| zRY0m*pp}6ZkuC$?=5h$!&eOW~A;~u9(Y{2)_5DnEyG$K;ce%*qZgjhupZfd~h5EU} zQ+ze93nP^1O!#PlX!mKdBk9|uR{s37lya#vELxLG(SIh!2@qOW1eS}qSYT! z5kf==iWq$mD1?A41*bzg}- zkSM$|GKOnHj_3{Vs)0f}jZ4QW*5NL+l4PpsO7i26bl#$8} zB`8*nSl3)_@2aLxq{}xNSenS7OU6=wzg-vn#hma92w#oxR)DvgB3?X-PytVJ+^}j zMU^FpLQ9<;ATM|TfUAZwCNDfls(gVJhNU@40?JUCK{UH)HTZ0hsQ6yw+6RE71}6r; z#$8S(J`hU^nDo!XH9*Cs8ryjaw8rVbp2s?-=}??MK6+9q@KHgpWowLr>ucdxKe zi`{)u9#bpK2!RQ)>e7>mJK4y_jut@yT7=q7aU!q+y?K+jWKr-_Cxf#VzAS# zLy%OtNvksgXYBPD>%IT?TFf`kAyotuByzdm%m#}A92jA~Ac*0O7&i{cIpcSe?1%Cq zL!^Q0&B;hrQA`mKcIFBc{Cc<4NYtTaX*QvUy*?wn1>GcKD+nuD)2!b{HoICw zHa~6=0hI#ERceH4O$kN_)%C?ZN&9@gKbNr{F-eODpF;$y#-0Pf$=CZed*Z8_50k36 zTqWlW$t&`5^MWu2NLf+V1+p%Xyu$3=wa*G@5oi!tRF5!FCtZlyhi%$gN)N~%YZ`ys zvC~aX7HStyO}C)Lot#Dw`>*c)KLo0?617txhU>?QyeeYMc$+WK2xtaEa(v6F63wCr zb6pSXaCi&}9An+5fvD1|xhqP}2;qjeDdFu>BPMkM(Si_4t)_q&xm%=^80*585MoB4 z>NpZ&kB4nlm}^=Lth^;c+L76Cmq@nfAsnv))_Vi<_R!i?KO zuWGwr8c2LWbAIOH@=S|;9LOVmJsibM(5kJoY2jmn(i!02WpjSgr8paCJr1ZmWX-F1 zee9f!txP%@7PJRJFP~}KcjsaR)Af_`;9YI_+#lZM80dpRIt(U?v}thaOhvQ9Q>C4R z#p>VHyp1kKbz!VOSDEWvo5QEj%c9u*qyS|zjY7tp|)9?P>q%d`0CMxdU zVL+A&>@7kU0j&nghENE>Tow|bh_=>r>4>5N{g@CC5TYSw#)KK~Y6 z+t~4#7)ew2>JIfh`Ex5UT>(l6RA9xqZW70Eku&E8UatC|T&6b4rj>crDX zY;*?J43SWE)C$N*X0>M*y8=gQy7FfKR|zhyp5VlLYD!Cg5weYB*+9Q;4lILoyGd%I z8WJ%sF#=H#rU{`k^be;NtO^Gi)ue=>{tiToQt0s1Rm$mM0lNQ6U5$wju2u;L74ioOR15{*Z{U#JqIS>pq=$~7Ml>*y1#fQ9&7{DWIhZT$n*FTF;chN zGX#ntRxlf|R$Db5V#RHg*o9qz7b=@c*8HOD&ov;+)V;5Le~Z<+$2N|FF@&z@Vde)t z@Wwjv;F?;kiJ*7$QD!6mu?wf8VZDoktAy5DNxKiXU+V=xGQv!RoC5O7K4e!lz#_6Q z&=Bh|sdOfJTt5^t?6I}WR=wPvAc-46VfO@0sU5%~itkWdb3u`+KaT++xPe3wsju(; z`J*12DMDFyG3{O$N0bo2lp&fsDJ8)`0;uJuA%3rf>^$Y1`~5Rb6Q;=% zAf*j9TJ6_xEwIUzAE~*VeEIs`H8t%9%__ic!9puy_G$dflrT+hO_Eba%#2(LY)ar1 zJ5wEsCqbs@fICR>0}|7>i`LP?y zX#sTr(sHWZ-h5*DICL=-B&IfwmOnX%``6wNL3NSR;WfBx__l$<<7>7+7OIQ6OIl=j z4{c!FxNa(qp{^T^u}eZK1EWmj%1RT8 z7_tdOxw?h;=USw_;HFjeSpxrlV8cWU-a^I&D}pXiT~W#n*=~S%3^j#_KoP4FQfAC7 zxX^-&e&8}iyiWn|RYz^1piGP`5#LwB6diFW5k5!(Ey%K>)Dg|D4~8MYL7Jyb8h#H$ z$_suM1AZ3+-Ynq)A8NB)5Hi5a>b86dh=nSx8DXI^w`SGj83Q13CX$LFh#;AuFfcJ8 z21cZ6WT=A31PQhc+*OUT(k2P$&!hM@*nsuzcEe>3m4r##XYC-k?5$aecGi3&;1Qfl z=XQ)y`%>9??@lSebar1}GoTKa%`x==2&lNS1_%TU zh7eWJMs0_H3rL6hMAf>Nc)})1P9a3C_rF7n#SWgW8K2A zuRjOx=P`VT$33ZmrGs@FH%3zp5!Jt)8G#8?ipUH|3dn(XZ0ivyiER2^88o_$O%_Ox z9q-z68;906zy7m1p0Wy-Wx+RDyod)p_FfdhmG+fTOaKL_0l{>TkWkh6Zw0N058rZ> z`pgn6yWGNkx7DNUErNnPBnlmX>O+|&0Ia2Spel{&ub;J@%TNhVzv$XTpZz_6bE{i9 z*zz68v!gxeGkimgod)|^KFMd|nr-V7C$}j}P zk~;uDI*z2Uh1ZM=^)`X6eFHd)dp(N(?^_8E2Es^pQ0Y+xc$Tj883-SbW2ZrTVc7Av z3`yPrP8u}qdxiAC)b9V`A%kxCVPGx0^T0zh?e13JVv0}BD}nA7h`Vc~hYv`b1cI=) z+1qQuYa33-jp9UaPI$`L>rnz?IK4mbT5Gib{?6KpHjOJKb>hqbxYoVd?~Mh0 zz$P6zBRu-rTkR;A!ft(6*pBq+di7(g-Zp6*lRq01A_@V83$j!lb(NnU!S#Nq4!a`5 zi@j}Tv4^Nu zR+&SnDTnsZP~uUi`!gJKFVn=XXgqt}Q7ZB%kL4(hIYy(8osjW-sVc75Ysbi!%LOdD za~WwNYF5{w`2PMCks=Z&lqgtYofHijwywzH?ZGvd3cv+#>x|1qkxGIHA!bj)iBS-v zy99_B5)*QEeM)YOb{ob?4zMNq6zj-vw-4M~z&r26BOv3az^^fJk1jlhs{6MLBYx(m z{Y-=XTcXV$Nl3=U^=#Plk>uhP7mBCSlrdqAMjh|{kf`?In)7pTey*Omwru#5&xQm~ z?~na!Ytv9xz-b3P_v7n3g5{&sWGGzPF^q056fnfIoC0*T4Hsp1TrCL9I%_>nuX9gC zY@oehZ>Og&A_&}^lK=o907*naRP1tqZqL>LkrP-Q;O6>Xs&3O)41*NJy@8F`_XJqA ze{)bSX0SqiVHOo+b!((jf$4Si*DIwUtGD91oPh!+mabQ1a&R4?h$LVb5)r-x!xv<{ zl^deo5FnuFVF0%%xaJiCLV@{ElPpMi!9@*!!teNr3%-KzrtVarP)y;5Io|N0H)ve( zjaRquvuf2>1R7oED(WB)9BLqgKZBvNf1(*zVSJMn-vaQvm{1s4O)%vGTNi{IduT`C zs&{oAVnWL@5ZOpu9lEWfZ0>g84dJf(MX{_K{WxR8bQRn^jyX z1^K49l7hoF+~h!85Mx1zgrcEGYd5y~xS?%{cK4EyaS&;gh3vtR?Vej^msEh#&?ELg4+7yZBHhH=xZ7R)G<_4Vwl}Z3JNI_j}GB8{Jt)EeOQ!OD+*e4m+pF zDC$~y3RQ}s2C#FPkqME2xyeI_L3MyH!u%d0w*zD-xF(;DB!^Nf7EYv!JCcPrjrV<> z{!kK0ZJ4Zum#FlFMx{Y`jYfKHi=E3IhP1+_eK$L-mA2PnA6jpQO-j_fT>>)_6EwKj zd@IO`Om|V*>O- z%FAc$^yvNlnN8^U-!Y;5$S|7uUiI6s0LvH6j z&l|(ZPqovJhWqY6?XlV%7*nRhd3o$IV%GeWaq3Zi1oq9?|CxMdWAwH^O-Ctst_A0T zVc%FC9zbqo_fE|An{=Unk2kBn`=MFd7Q5Z+Z#vlSVlxy4iY@-vb<9=j0X{j$T!*^2 zOBUKYH1@?Cxi&1S41u?`eUPyFC0E_9RN$oI-)~xJQR)MqSmI;X$HDVFgQvNXCa|d^e`T6m5+N1BE)n_toasny}{p6uJ@bX@I)!@$oTigRN+f(+We z$K935n$otpG!Y&sAJ3+CtzMyV+=%DhB@uxpffPaJtxjEYf8X+iPVtq7>0IEB;7q9T-~dC^MciDQfl?ilLKMUt zz(Q`f#{u*E71!@S@crix{QUV3eEabS-rwJFxm>DsWPor0lYmLQk*&c^jkkSvL3!q4 zc6f;FYX-nG=d)){Wak9Pw#T$0yA{-pCmt&BTXI28rStITQlKsUTw)i}h9EOE5MTn~ z0>$c~4#tS)%GHz-H2E)COF`N;tas-Jy>QB;`4%`12R5#d;b$;`tK0x@n(JbAO80Qdao7tPpBa{ zMp*y5-0@eP@K>UVZ2HtWc)8VYNIRGQH)=D-vFy>(&CURc}d(CBZI_=LI-ff%(&Fa0&!L0E<~I@;rGtKAh_ zyViSAt?lp43*(|z!!BmqkxJyI$cT~t2)!zsT|s-(47LJbz@0d3ly!%V>O8_ zrG!#PaHSMTDIm>mO{LijhH70#L`dQ^7PI1`Z>h<3C~n^s?wC2^BEW?TCN7xSz`UZA zI~LB^Cc-WGcwJDivAG~p?_d=~3Rsx1h#^+QBH0a$6@d)G1{LVMeXWw zuJ%`c@GHVBm4oRK)OXGJG{K4lHsE_yA!3mjmEbj^NYTIi&xL(y0mDfepWgWzaz|5(zfjkf-Qg-4yWs zZ9yT%@B0QeMIeJ_11CYjiVQ+2dN={R2n&!PDD2G~S=Aj(6Shq|jY~{mA}C|fla-ge z=I%!Fq*(3$Ml0~hgczec1l2WAN&!z!|6^uA7^+Sa_B2Pq{PqpszP;m*KfdFSpZ|ex zKYn;&9lYrr^HD}*xJRc89UAY)^V6OiQIK`|=T{~e=fv%2-y7+?qv)~GOrG(`+xL9B zw_@Awn5GHKa>YCuq8XF}LYNmA3zQg|5~2ZWf?@)~3{5M7Wh7f+Wdl{wNUq|DawG7% zVU8>2Wx{2ONGakTR|FQsa7BoOY4Qgq#fVrGA^S)#6+na#SrCKtfSUGzMbr-%@K|g^ zupytqKnB5$?FCe$CY-Hpp553HO>AS9$D*?w)Zx3R@Eqk`o(G_`-(Q{-nEISY^-Kt7 zPeJuT1%F~;+e0x-hwJ8_VK`{%x!?Exu;MUkI-|NexLiEzr1O9T54-FByVRaEBG!)^ z;zyP6D}sp)mGW-%k3EQ^Ej+_M^%xTK{2sebzp2~1gUR7C^T2_phsNSS3u#f|Qu)t1 z9E>E6s8#Q1Z3TrmC)W>0*~fe|rm^|&*TQJ>vR+(k6EOy;W@MGxYyhcL8@=L%mB(;9 zlAel>GLvl`dLX5XaxJ|(Cl$>5sm7OH}xD)`A77!Vx7(JAw zBv6<^9B>CChJYIjmYi`R0i}e^GSoIiTQFtd_E|750U{X*1tg3tgajZ@0@BG-*AT%f zZfT_rKyXxj4(@1>RInB}?MRzAZUwP7FHX<#=B21&O$lKW+_PXSRhP3Rs3a6NPt!9! z03rMO*{3pN6!ZgCq>kXV(uB;ca-gXeh1!u*w@o`1h=kJ7?xS|6MpzS{4(V|ZZtIV0 z!O$8%#hUK8-!|Ou_j-tW5KO5KB3n+-Z3U6xGF`AtGo}zgQ6M}a8ZfEhjTC_hvl&A6 z!a8sZz#v43hXys?H$1{!S%FHuY6!N}f=|h+=QeqhOM5=T;V`OV@6L-RuI^mJ9y5p- zN8j-sAPVl@Ll~|tcRfg}%c&LdScMxL`YqlT} z(AOXr<1pw5gfN3R z0$~PEu_k1O8Z1+FCPQ4g`|ckrnKR(|KquMDgo8i!Gdsc-)-x8)=O*Obq&Aw!GppwF z-$~`4YawiFK~5i7Cuq70N(K-5x9#g=P0p zTsOr!WlWR1j>H%-#SM~yEdybzbdu?t{wBEZaGJ;q;ZV`x1Y zdF0$STj}@B!x`wI8#))*uh7>AbhS>mxQQhQyXop!Nb_@a_L+^JDgG_eKd^h)KDV8I z;jm)-fF!rHF=w9Ifxmm)d+1QE?wm+|4x!^jhd6WE+o5T37hVw!MgM8sQ?E@0Z}+er zJ5fc>R!VA5xzkqPSC6tCv_4ij({5s;N4~!u3wJ$?5C%sQ8n5B$o;C_cHH^?E_UuWC z&AYY=&}z)J89BYixQb3(tk$lBDeXZDO}JRmn8veic6yx`T}ln>@Xb6|)qT<$Fi;Dm zM({}d0jATEGS?AxwLQvKfI(lbFkZ~O~hE3QJ8Tz^RSZcNv=ImC)W6C5dlX=i~&4F6d@Gx z19z=nwTZ0z;vy9!{ct3IVrX8W;>f-RN8$<-Yzt7{pcG&z$VpLF=YmEecg?8#pg@po zXb`gp1eq0-WW7LbBXmb@>iez*%zFRCXJAZ$-A+y>u*8l)Jsr)eA*K9MEbim*3}!j3 z*KFG^HnVaN#h>W_W5oIhz?@O5R}DTHA=_X_SOxyK&lT&s_TqYM5Ox$zv27b7F-#aF zjKBd)2)M+6Nf=XbU+Pe4A#F;*ATS-@V-p_xW>@3Pt+>viYFHZhVf+kuc`_=e=Fs7j zkA?x6?ch+`hrW89#>;M#f*th>hplx_!yMdhhUVwN3CYU;V0wEzU%SWm|ARocb79?! zuh`sS>;c&n5xl>@@027EBpFOL&jQE_#;uE?9W)du0=DA%f>dq(nl=q2VD>O8RgdpB zao=TsMih(y)re9iq%He?+s?t7zS+;^CmiE(`tK;SgPBtdwVv>OXf6ds7|fvxoE@r} zm~fdQ-rwI5<^}KX@3>yCnCJPhR*!Vw)`Z*NS{VO*y0;A?*niKF?fm?`+7BL{&q1U2 z>Ny*~MmxitGlI$mYSGc@DFKwgNFYmKN(hu-oS+uLoM9zFX@fR(xcUZ4#jrw=?*&^j z-0vA88#JmaGk&D%Bwy0qL`_x@Q+8WwQ#(i78@YoVG zjXuTxo)@lk1NNef3?7fI#kuI&(Nfb5RyO2x1M&?>H&{-fQoyRnM=QlWYa3JBLp=VP>CMoD`I&h)6@vdw0jv9*7M0zb4j<~(H9XZ&8aFT`;xn3K8=hF)!1>kN_~GOkmES%wR51iddEj z@0aUdU|+6yf4ksvnXxSMA@ij9U{^~Vzx3SnHU9(q-vfB}I%nhW#EfHX`qvz8>MPzl%{sFoAWA~{P>*?^wH$FIL?2VGr6H!AGq>miIw%(X) zaK@;#!LdPjm`0p7P}(`mUo|R+#b{@dDpkXLdbo!LGWcST7J9xyxTDj%i-{LPc0{{t z5+bTcwAE0U{mBnBjjC?TQ* zMiGG5$2eey5MrTU|E(PxWH1IR`u(Zb2+5GHM+>?hdu6j zQXL^mDc$<40Ve(xdIa)VT=!V^nxOV9cb%}VJ0^WjPW?&+P7(uwWn@eRHOWmiq23ZlRCm)g1<63cD zV=G>IP6>?Qxzmq`~Q5>fY>n%hfnUUR2@x>2VjN=zO+^Ax$4H`y$3fh zqt3w{gQ^apU{sxLu+w11;-2u#lJ+b}$IEGROQig&D1RlYYvu?|XVZ%7?e6;_igU5s z2@qHy>;Y5M3iDFMuyMkw30ujql5482g2ij1Xjm z^^m^V=tJ(JBTp$8o&Oyf^Ad4cW=zvm8-+@LAi|mr+XjFOf-xc@LYVNjT>4({_V$Kv z?^j$ZMK}o8&n<_*rE{(IteAdCjvhUSpG@+B@};Nszw`a)$h8gm0Iz@E>zjP2XIk@8 zNYS-XRqknU@K35Ugv#bzU${0m6=m^yEhoEc3jNE4h7eN4wkjcBB@J#di}2oD1m# zm)n}3!Ll3qi>GG;u*j9ssKN?`_JB2M{tz>hSxp3 z22=m{{N#6!MSQL{Uu}1O9HH=|^UEM`>F5>Q^L6Baw+4cU9x>$>(OYAH3&zG~N0;pj zyFK5;<=~Ric=V&nyt}Q~v%sUuhi){C+W9thcddZM zFfR7n(ZW*sdQLARDT_r6x))%f&^L=@+)F zkYW%PWB}_5Y*R*tfI@WJIV;FnA*9axOBt33tb_{--s6N#33v74lnaA2KvTh*6x(FD zMygIBI|XTC!V&~;)kC)w0Tsm>XSW+H#jhEp3QHZezRp)%uWz_43+BrO%k_e35`-`z zn_@LXl!!nErs(n3X+z!&IVa4~54|7+wS=M>%8X43pSOZf2JQt|<%S#-AIkWZ1$RUg ziBQY+>2^ds<{l$*EgSepriqfg#3#w|T}g&G_+l#dV7KahdTp&zOQ>VPJ-OLBdWW3`7Xk zL8BFh-0U%1kW2#z=;ZoA4ASDX5T(w59(l;;G+R1T9iJ2wr~uCBKKEehH@+^*z=7wk zLpc|1rP4mACPmsXNu($5a}=37<+8k_`8?X_(c!$bGZMM8`VIj|uPC8sA)J7qHMupd zE_k)<&o(o48kHBa!(_PDB6EzG%`g-2c~jiigta7Wr2rw~+qWN8T*$uP)LnG9DMp{_ zloCz=8uw{_$DBtW@+W6|OVRdcLNQGdm&=07WyTz1-Ft1P!4xmT!Sey- z{p}6c>lK%I@_ZEG>RT>YrZCh~=xdhisPmc2%)j>^{@W?WD^&cMlgP2aCjkE*t*D7# zpEdC9D_Hynh@$Wcr3|BtLK~D4zzU_Cj}s*WrGQET(gq0|GsB)s7KCT1Vu?cBtZ%#seFvBE7KW zN3^;J-VB0B)>a4}`C=_}0Q`t}A8&*{h%j{!pXhn4IsSKC=*G{f5-%RA^TxHKtlSOz zsR;tihR~iT);`p>AsYU@e92Sey|sDaT0#fP$RmQUds<}Q==snf^lM1RgVd;vi>S{F z#_^7kJ!Pejx1yok+5}IHzR`Zh=&%v!Nb{&sscv1@ir`~{lqV?vSN$QMgMDa2NXl~EhYkS08bZ8 z^BZKjK(23y?^ncS#xyTZ15rgX!|&|P&o>0bk`eEMwB4{3ty=;^DWDjTm9U!OcPjWr zz^cF}5q^~wzl!3f0iX4AHGvw)n~)$L#uA0W5NzA#)`ULn_mwOR37!TStF@}zPx+zT zIQia%jMis31b#4EkCJ{iv1=5PBh6zJI+YVAwjzZC9pvnM@+c;6ItV_b<*oOv7uajs zaKCMpbDgo~R9~xp4q}ipM1WZYZ*jtp%LQ+j1>cq#*Er+bv{dxYo3RLXdPv>7g3&|R zOHu`kIQ>I)_poQ`JnfwxHze~>-9%c0`y#nc=}hl<9D_3-MKvvyrh_|;)>o1Bk)F9< z-+fx>NtfF9Tx}8UC*-o($!cjpSLxqpq6e+cnPxbQEB|ep!I^9ROcZwzS~hTED_GYJ zX)DmIFr^AcaHr9D0j%E87vEb$2%ut4v8c~%$}4WGyV58am&+SsEN)@PgrdhOSO@_n z2Z)rtt|1Sa>81qd;*qqq)Q_%Py~b&RJ;FTugervU&25BK+&PJgRSva>s|1O7zh3ai z&p+_~{vDUg+;wx@s1kKD+pdA{1vqf9TSK5P8UgzcI&)*w`mj5@!^;q|z z({eCO<^A~yDSSgI2?aBXWhBZdNJuD79pM=!28YG`i^2v98(1^a{pJTM-(kGMYE*I2 zt=iYDVB{*+%6>p3!1=AF}O<#-=Fhi)Qc9Z}XH)D_WVJpKpaa<%F z@#dql+((O}^4^T*sjeify+zKhXNKX4A^Lk&OK2&rHFc}fuqc699F^U<48MSylQ?AsGybi&5zmFQ(D~>Cr*F)6*G^VU&l@*pGmYZj-sQK~{oV^{O`O zV^TA%MX?8}Sc}}X>RDa(G)Oh-7HZlP$kHJ}%Lo-UY$3h?UA>t$mtH0nvRz} z(NIVc#e*`q+z}+=!h%T{g4`!Y0AY&-x7&u#&l~RdJBr<)<>tjQGr+NXhkJ1N<7QT> z&$6lu9&6nM3Dn1uB2E>EF+yT=ni(@P+(-3tnQ>b`k@JQk?tV~8!p(r+P{^jpSdpS4 zGdb;oOCM2(Vz?OG(I7;h|_?H@fr;M8=tjbsmkn`s6g&84C;1K(v2UV1my3OT;`)4q}iw*E4&1um32cSaDC{laF<&oX}PvKHD$HXXLnlpa0F#9V9S6jaPmp zRN51HQ}!JdPTR4aXg65rc7fwz@8&^#x4SbD$}lx7 z|6^S9skIyP126Dcyx9YtVc}j?BOnb&A=PZ*6)t@n&mVRAAIK9dJiEuMdUJLs_EOF zuxr?2M5vUpH3bw?#5m!{_n-LVk3aD3?fXvOs+v5)qbI(v-_}6e$sEA`rnt5T^MtPo z=&w^P?FG%F?$`9_&%aOY(Vbe3#Z|72+(-d%-eQfL= z+AeTPiNKt|u&zj*LV$4GBPpvevfDFN4{opx^pbj^tN2mtXtE1wXn*i}?C%q*$gA;0 zFHEUCcq@Lz3Hh>6>Y_Mj9;vOBce@&;)S(oEdCh z_?W8|_Rm}e58Zp((49RBhLNT^lhS$9>On693hhO-9(b)|U15rY{ZP9uIcH>3#IjWz zp#;hqtO>$~DD2jlT=2F8{PAPKw`)Wst+EAwz0c{6z<1{$ZZ3j$gt|R`jmz(DAJ!3f zZ%j#B1a|S_+7!f|7AC@oaj9$753)0Zn^TrWw2}uy{olMhP=woRFX(n-IzZy{*_jK9Q1QVL)g>Fu~{T zH*#KmPb&T#sfqL4iEvK|zYFkT!0%1*J0(wiWAW$K6jlt|_Ss!UcALt|jn?e6A7McF#?c+oqz8`n7(RBQezbl5tLEKmv*{dK z_qV>^+#w|AjN8rsT-VfTA#Hl+iH#9~1BK}{w^SJoMPBvYW&zFy)L|8HTFl} zczFOJzs~U(U$6LjqGPgk`?>IEnf;*_-%ygd7i)o{kOG(B_D`j_njM0o5y~^51&KFM zR*=jH(-mYH$Sb%cOs3f63Py&OJ2c->EJ4hZ*2FS4+Tgl)AH{5`+Sx>c$Q=?xO^9^r zh-4p?+_nUwJLFVcg9svy(s0U=*A#}kgokZ9r(l5me2M8Zqp&v zh^pw(@=zcjQvt`qS$V5M$x3&qAtjCek;)^FP7l5sG^9`FK``AYKK4X_@LXWrZ0VGS z;yIU2(QriiBoMW9_&i2OvExWfY30At9_O9g0jPOcwEO+s5IZkbZM1phlZeq{nfraN zVlh}53TPUTkmmZ3_W+5uIphqK4Xg^J0wKe;-C%Y{pn{o!t4z4YfXg-D=Z}d0_%Y%A zdI3~j#0W($39&3-txC)yNXhUkee|TN&ecjqTDAL&N|&6Mh=wGR>e+JUF5#%9^~00%5)^z{dwd1TNQz_3mLM#1YB?iU184 z(Ay8t+drVo1++}qrWrg(C<=lCTnaQK==6s5_5r!yF+*UNJ1AuY04p}!w*;+w7m80) zQU-3R;8!yIDyjPOJA!Gvi`8~?PWP}a5DFD6%Y+aXxNJ=;WyG!BG7PyU8j9Q?QpJh6 zz{+FMJQmC%$KrY9r}|jg27$31)-(sf5~r6gAR+ju{E(75P)c0PYrU{`e)S#qyHi0* zDfs=lfz1C+);d8faB(6c=C_C+*9HII+ZEs6F8J{_;caGI0^t&YB?Lq_u!R(JdqnK~ zaT-FR@~|_oYPH&PjRO<;e#~^(7vkif16fhjdI*z%z>1-nKXR?vdJI)BE{|?3+Bwv{ zz!++THd9ogPGP|z4n})I;^@k8E@;|XM=PFN;oAdlq=F!2CmA-Ni{zNH_~Z8aSw0|8J{!MY~*Z>HeSnNipMfL+^>b8`As2%Tf>-180V`iYc% zTH*z|z;bq`wHd73vEKedy3ClS9{{M+s>}=$7$irrX3||#)8g&90z~dHB7UkCMbUgn zuy)aKsCAPdMyX*(hH3U@(l7?j_{3@}ikuYFwBWi#OaXvym?Og!uucUbOoNVYns$+^ z7uMxOaZLwGs{=-lR>p*50Nlal#hzRLy>d}GzBWDVUFS*2xOa_zr>Y2Y>E8L{q^;37 z!|zRNYMOH+jUp@rkht<*^Wyw#mvXtWxotpkt|PFz)Ri+}lLuo+gk?vtIRwBGf?kmG z9aJ`uCaA6`xSA|nc83IVYe-A0T^j1UYQcIaLtyTY9r zw5|_+j9JP)Vv)UD3=O$vsY-jez;kpLF(6YOY-prYKzO8tv^ZX?!YAfFX7Jal+(Y4q z5zgod+xg{$FT1y05U4Nh=lTZQ=nJ%lE-}{wJTfDSA#m^mnhb@i6GZ?51eDuY zn?MQ(1a}3tb%SQbg*;^EulokOTyQUp(0KG96l0hW5ZqR8o@ZR?ij6nl{|pE<6|D$E zrU^37pk;=`L=CXlOxmXy5hdAxZhXYKKBAU)sP@lM-@>g7cowFUoQCm z{fZxNZ}`WXqt@@sgn0^Bf?y62Q+w{f5U%1yYTB41HRGHzOAq#-l^#-q%wXpCza8#v z4<1FG}A;CHb$aw8|CL++fUOJ!of;U^?O>H1rvA@R=d&2`*>iSA<{xeg4M3&x4QoNQvysijQ2!MOv3U8@M_Xs418N3I`WlS*~#;9tNSRplOEY z1mf(05>$Y)LB$JZLjr4dTduePIr;xCD@xu#`sv-QtN;=WRncD7&Ob|*z<2MCLcQtj z11)jto{%Eq9Bt8lu(S_9J_H-5VRTUilc7LEK#;vya1Ge@(gILKyqI}G_t?dexuXQn z9-^-TZg{Y{J8UTQnvi|85u}F#yP?BW7yo$Zo;kFgw$Vdy_-IjAg?$~Bwqc_(An;(q zZg^_dH9C`Yesc3;rW0aq{FGwy;4iH@pw9eI&^G4{rN>4BMu+jy!ARbYUe_c?mzFVP z=2d&u-y0}K;(7#5OLyGYwQ{)qXN1{XEfQDoR&QbwfW?1LQ9xOciu=;CF%*QY#eOG%l@MhD zrPRYAN(@+wfl9$Fif`=VwgB_gTM-!hWQ0<}bXo8%5;Ct~N+@QC%M1F9~&z&>zXNU)DR|25?t?sBi*D~ z8#}+-e@92kD}B^Nh z-SN*>$p2jQ;Bw7rz@~8BD6kMx7C)V9PMsK;;gz4Z*Cska&l;rd$sb|3LRCA&7Ku?e=H8 zsdEgqfR0B#U;E#c0us|PfvDY-82GUHpWR9TetNN=cASteZ_ZP@7ux>D5dYL&oeKFe z2xk92Ke&ACt{2DO)nZb1JIZ5$2o`9u12qF+WUWT_7&%WnfBO9U4ov}0t}0(B#K&m+ zGhL+HgB?&*I;g7;^b&fuaQQ?LIliA<>~vj@0v|9PbB1*1GE%c(g86f<>Qf?fG>wb< zNOR*~!|m_r%(X8AXN=KBG>ih(j(MjARwp8?pz#OnFevq{1w5WoV@bU2%{`%`*xZOYMVQs!S z3xkDm&jn(NV1}6mpTScbOHR12-V|8zu$urEV}54E=c-8RQ!(R!sagXjHP{@n)`RJT zqC1&X-3Ae0K~Zvbg)w&{S_0u+B4kR)N(j@8IL}TY3BDfIqR!Ko0G=k-nvlRsL`fSo z6H)@UQoxHkMWlv!NOCUvlrl;-q%Gl28H+I{6imes)WMCCau){|@<5$YK;3N68pWuC z59DD%Q}oesWa-mF2Qj?JZr^JW=OZPg-T(GIPb_5r;zlJqdSX9{(COf;BVTZD=_ICY zTxw5XOzzmQuDGpttoP);;almh9bE0?07Z;~WnS<$Pxx`Y;M?Vbf4p7reZJt^JYfmq zQ&e`ee1nY%HXzS5K<6?1-|2~X*h>!uv>mlW^n^qHcnFlk{`_~&5smZR zta)8vzo+%;R*<(1c`MLtmFmddf~4e~KkSoktH1ybG^K_}1L$d>j^sM6NerGQ3$CDr z+oHNaIK!;NERbHW1Spq7eR5uN`xiQ$LMvMA)Rh5fl-)XS%ou6ncIr7Gm3OYmi}Ycw z7R@zWtr^F-2pP0H3hfSS(nX;n4;#yvc=$Y07DGHdUUYTmLYg0h zD`(5SXTkx3oZ{E{r1~BB(bj@YMv>i-Yi;HAIInS_UWs&Gb)+MOgik)WqZ`R+nr}s) z+6)HTZSTFUUbyRnmcCqo?M@`OJ^#4Gjyrjew!K9zX?Bx!2TqYu#RN*n?^m zxuf8U{V$6L!n8>9oOk})7ZFSnkgNvAh+qm4%7iIY0$k2Wj4JMB{3dmjjSPuBWMnf# z4h}RJO&}`>V7$!}Vw$iP1xv&{&-nK92fn>K1t&(|OK#g*r*Ib+0kRkHmMX_GW=Qe1 zI91(+GCanTy27b9SV+ylgJWpOy2}eWY`Uh+ALM5qKn)>L#)m^}8d` zkor0rCZO#D-1h|E^SBqg54Dt5(*;l!O1>_LpZTJ{nuwq4mp*;5bK3N4i^pEyw4_yi zM6zE^*Y*Nj@7}F2L&1B3T(>XdYQ541LjmBS$f3Ji*wqv_Kj;;t0iXi5=$#8zryr=N zG6L$(eY^m=fi!p_P6f~e<5b%J z*PD8MstEU?z;15k!LK&AsJPQ|(r4sknV0Xo$nkFcX*4 zs2&k)dLlxxN-e2M{k$cx0P}P~&I#ML9)|&iGjG z_}8alGKHiSK^2QJ0!J)C@IEmvA|Mgu5TGF;MgT*z>r)~OAu1&0D%w#5-LM40_xCsa{Qiz9E--V!U<&Si8>+^HyHmN?=pPQ$T8JFNLt69J#Jq=R7RX7FQm)0d z7dRicPuy-dY^yhyTk&F{WM2pEy*eA)gv$lXJmDGwe$H2XUlzXMS@2W@e3Yw7d`F}a6`Ra z_cEaChJ)~Y-{1HEOzi735B~Qrs2R_w8Vxxf+%nq!N2lV4$HMs8OLvj|*I>*TL`3A` zP~zPhwt*8~TyMyALevmxFRlwx%E(*l-r?FNEk$9$pt>EApZkV}rD4Hf3rCt${75 z2r}6He35fa2GMToy}7l+_ClGY~RN zsy!F`Zsn1n;Cwq;--pC3ljT* zN);J2bxRiN+{}9LQ$@A|AxP*psUgTgP}>AxhuH8cbbYnvwQ*isWb&zCKT`(ElWF0& zHXG8tH+nm2y{?R6p>p!pio_YX5&It1^n15Oz(D6JufF~!o zp@+&0cEkOB9Wo6@t~a@@BZdBKJVO`z*!+ZEA11aZ(Iwj>CxqycBytW~d&Th%1AxRs zdUKj9yD3r7&H<1tCtd9N2s#Q~j{~%RQf?j==MZzx_DG)^i|m67OifuFM^jBjP5O+2vQs;>+TQhmn7qMMk?PO; zec9vScTpwv)W-8B>%S)>mkbD_s5y#f)v<)Uu+OGQB_m`8v!_!Mw^(;C#_#tHzkh$? z_wV0W*VP?v0AIg+vNIgh_;MLGIDHsvQs?WT7w^V|`~B9%l)l;fhC59Yc<@0^DIr*; zYq0oev!-u|MC3qzs0q7+1$o?cp(>UP6I2L11$Tp(7PJ`XbzL1P4*{7B5-0yX#X*1= zA|wD&1X3+KqZVZKrUXTi$v{@{`{Pf9DWbse$M+xZFoJ?oQB{IlT`>_51zIA=44X_< zaGJqd+-_2g5YYczeHKSr&X>7F_2A^Ar)qa~Q515gUCV7k7fF@6BJ+ zeXarSHlk>Fb1me2P4A$NA=k`-N||dM>cK+oP+<1`ckq>N$n7wdGuYE}1P@~MJ_{W* zBQ;S^cZ7Q{uI)5&d-9s54icz72Ykjt${s0#N>2cylRMN-OL;Eh|2qVdi4K6!VPeu8 zLn=b7rA=X_bBMP_H(FPeVu-B3gkC3@-RpVg&+*5);h+EKU-;|e17-#9@9!w=6RAQj za12HWs<@Ehb4xBxwjJ;aA)r*Zo|Mv%f#6ojsva7aQu6fPAtPa&Y@F@qLI?;`tinv^ z7q?>g;7o#@^E7I2Jc%;ns#o>R{Ui}@f znx6ub&yySBy{uKjGPfHL;Hm3Dv5HhpG>Fk|a;7OjU=&5(lH=*{a^U0M_Wz<|vR z=)FFyu0CxYc0quO7bt4ksnuK{EdIShC>#+exh0tfDAsB(W*`b66DY6FM`~iAtN;a& zctVqwtp{U(3$i8v;;ttO#HxO7mPicvreHqOA=#6)xNVx%;egr4(L@DAS~m%|CL}(o zx(A+jI|$AKkY^i1v%wh=SKni&ZUyfU~($R1sA7 zw#L_n?c;mN!^7wnZuU165PRwqe*PSzsNleZhy5+G|DbFiio75r_w#Y=)JL?#IBpzm zkMD8pYTK8zXW`IE51Yyu=wRdPoW&gD{oRfEY&Z<{bX^rb%8yd*^i+{kmRP!*CTgv$B_iy~~|NX!4-~aqC{Qm3DO3PAYkWZCrBXkUzI0jBI z6rqYE-5y1p_x0+*m;zkpkm0Fk)aVB9JK}OaU@6VkAU%pIwh>_TZmBrWTLs z3t%7_l5Vg`JW#3R9@X5CrqB_FK$0x?7d!D{kjLETSVF_)_?8FvwE8@J}1LF{Xu zzzzPynq0UD09#sd-&&A|+oa_#IwMdCU??If;>@^S7c9$+X__$4Gk(5*t0V6jF-lKd zBz5aP(yB8GP7TOg0;1c`TFD6J32;q|(whC!Y&1C>c%I#>$=ZG3GLZkbw!d0hoIb~h40bVr)`RQ!ix zU0D8bhP4>>dfy4p&mRw=dTryDOB!+l2wc3d*5uD=zIljDNu^ForB3Ty?3iyE_jPsA zH3>E?2ni5O0QsabmCcP9O2NnN4&5@AWdUNuw9HT#3IT-(sV1>b1#S_^cciR6PXnST zwpDvyg)jh1$oUQ{8*)y_d8_#c2CC>X>fU2k^8_mT<}^U-V3&}m4+j#kq2I4V;1iKI z;$UbgJp)8b0h?dTk`#H(NYVM$WlIR5>9s282m)1cBNKla()SF_{>m9-JnzrNvQLZf za0Wf&Nplq-H(*B(z?uhf$sn>YEhj4PzF)PbA8-$UB0>AkDfX%~QOsg;_`=;g&3Ib!>3zRx8 z2P-V68r7>kWP@2?M3BluR?WUID8N)jHpD}Rou7(WePJJqy#nl_4QsLDyNz2DlZ_9+ z_|QDtAX2iEs|OB_BW3g^9fU7urR?LwYY(=1&x%|d5OQKWBuCN-6@EqmIWLMc2W;$q zUyX3S>O%XtYPg<#yj-bAcp?6DmG}|eIWJJ=uN#OF?Qg}~kqb@_UHQmCZ4{elpYbei z-Tl&Ka9pr2(VBAdnLd9$GMBlu_j|kD@aLa@Vp?V_*9#OL)y>J%2cral2=}z%&)>iB zzy9mL@Xvq#6aV?2|A~M7>tDFv9m&yhibCd74D-Pb4&7(DA=#>-bGb8er;-(`k;FYn zq)uEYV44HwIDr{hrm5O|k#h-$rq--zE zE@mj#f_3#^tIxaJ1m15eFh$Ih7k#-DOfez|BZwSquK+-0xW5v7(w0_i>&?;hOY~i> z0s)$v%MPF<*x({6(}GkoR2b7dgD)4zdc$Q&xZm$sc*TVj?=s44$Yx!2MnpD?$+=O$<^;ws%C{kpFr(D50o;Ld+bGTDTc)3bgYRO z?cgEH%$Rc61;9~YRWQ~N#_k(zz~|>Dw(2q5toO!(jfilWBc`}uo+I8X*LrH#K-}VW znW7g$c>`C9Kq>z}Y46q@xy@t??g)Tnrlcy{-8~QU|Nq;0nLb~CcIlENfQWerTzN^= znekd)uCk<5CJ6!&JNCu2Kp_OILBNyo)pZlZC~!cHttRd!X%5vsPt(@Lf*;4t@k!i! zb75&y&1am{o)cYJ9obVFlu=}A_IpqmFJ6jvB{dPY=w)H^tVnYC_xA1!RPX@8VE?CG zy?&)}QN>f25Za-p_1TEisB9-<; zdAey|lf1V|Z94X6qGYEdDaV1rZp=!!C(_Ab^vr zU8blZ+$9oOMInyzc)B=3*w0bV8D_QQIyjIpR843o&X8=esH9wAE7TJt+UX?G0m*~J ze1Ro7sDw@&kp)E}CODBCd7dv|OnEbLhEA}SMc}|*YkYePcS*y=cWyEcZ1r%LI`X&8 zJRNReUl_`T4`{pj7X^6U?0oUTCK&=sj(l(Zc3id>2oCmgw11ytMEJEzeEf_=ldAA(D0aW7!&V{?Pmr0)%a;ImN@H-`#_*86|=;&E3o&QfD8#_vRfa;ci#T4 zxj5CXK&4Z4b3>^wnv}9hF&XzatHhNEkH-W5`q#g*U+@DzfBwYl%L~5N2mZI(!Sc^P z|KNZA=YQk#pTF_z*Dw6@&pT3#nAqjQB0FxUFsjdUQ&u+cl*a2*itKi1+0UyKN=+HP zW&6x&$p?WN#lU;BN}K08L2~t4Nkb5_nAuGp5Yr;e^NeMhF-;R*mK*N(I|z#9W^{o% z+RVJoloHmZxdi<4{(*H}kt9N70W&Zu*U#&T;HC+)YcwqKZlEO@_c1|bLkJ4z7YNOm zGu23$kOWZ4X_t;Ihc-ELJ#ij1DX`4o`yICs@p8Z8kIm>bt15ypbRsx*5U*fwg*Ea) zd7Br^v#q&M#E1DgZ4DtnB8Y_Qau9_;(Y)V{%^MH4lzky$O`{Cn)&6GerP@CX~WZNsnkPlTj3O|9%jlQU%LHcz1Xxo9M+0?y@DK)+Ern4)X2D*I`Rt3&4GFf%AXR(3y$Er?Uml!S z3eeGMXmr?*+~{ILM?Fg|awS<)RFL5UGpW|_n^K|>^JVn-VLv_DgIuMv6fw3A6qpKN zNU#GopBE2lI^IPvm_M>YEH#b^5o{_hGyx$>&2*p)B8CtU zB_XUErs75>9tvQZ7SKFldV2-G+_BE~|KTTyBLoqA1c7_3P!c2pXk~ELnk2RGtzPd^ zXi?HpqsqS(Kv1bg_Fe>gdaiXEqrRX_Fi@ry?AdD8J4`fJJ(Q)qVsIETotmvlSAwl} zwAr%>_~re@(T?|w!`-t5t{jXmg_GGn^BH0;x!xO{NlYM|ptXr$$MxK;6Y^QVZ2TfE zMp}ugUoX)Ft+qxCN%nmuwJ%C(O*z}6aUFFROD)@6@`ZBt{gY!Puh2N<3uJT!2t%TS zPLmb8(NG1EXbuX=BH2=kh{?fccLmA83szi9b+@3&RdFSWMNiuXklz=$q1N0i$f`?8 z@$n^XYcgA?arVIN(cdAIB&DYm5r%Pi&lcDoNd}t0XP|#b8OI*Q3LtZVxk6}14ixW@ zilXv9M^<`1@}4TvHyLuVQEO-8cEvF-VvQ>+qG!m)mDSG`RcGIL5F9{+tppA29_r?L z(1&60;N4wCiP`3mPCPzIY%ExWr>#)QhFm*!$f3*Mo5+-dq&6Ww7af9Wn!&k%`uO-l z2np|>|KP`uAGj?>wb&kC#$io)48LuNAz{uw@-{v-j2~=QbG(7@9_&ngdeXrfJ1F4Zq8x8-!T>2IoE}!IMfD&9KkUV z;|eW)w0^R+lLH-;7-{y9H9{TRJrX0VJLll;cj#lo{eFi86UROz;u8sL9_Nd*sO7{2 z^3*vf*}B+5YJ#xrAVZWVkxX#jSAn-NcnsZ@A`-*#;4f{TC$=eMZgxr&#F+Xyy5ZK@U^a{D=5XaXm&%n!876Q<%S<`Kk$0LVV*pe zWx_no#-C>gChj<{Ih5x81H2_HA8CWcAX_D0=BPcm$XbIL;ay_T!2HO@EKn})1VR=uwkEH>hsNd zUVjwI~r?=69zH%mCE?8ocgN7t6btn^&aBm4EDBO;N4ZHUYWVKd4V5!__&`}6%1vL(EG zD_{%aPDGgC5h-DstVrCp4ai6`a%c;6X#3tvo`^83W^ON!>mpOCR1^HfNC91OwloAF zzpv_B?_5KToU6P)W{g2nK3gZj?4*4D46~nbyDhlQmZW%F?!(x$aQwGz1M>q;+~J=8 z`sW>M*z)_0SmIKt3ALDBW=v*HR9}~UZx@9&bAZF($utUi2L%ZJ_W5gCs09dw+txEaOgvc?% zISa>WanWj4hRLWB#UnkXCdlH79;Ob#LUl?g_o^V~#O7pDYy*h^&kQ%)6vXA}#JaB7 z)=+u+AqB)}Bmbg#c)88+{sk|uH{6$-A=kHM2qUXDVJgskK-%94A73lBzu%!D!t;a| z@_5WI_-naghH2a)0}}y0wh$ltOyw+*LA2iXZ)qOY9kQo;+p+RJj;}33`((zG0=pLt zQl3^?I;zxSDOJ(=F>|3u%dhwB4xoDWeHd+8uS9C!oej_asgx9^(PczTn4CgF*fzv9 zLSt(CWCCJL&?wl})xwIl1j)s9D#1TFOfPN0`1g}LyhnGN;a^^%FL&_m2D~oj;^8Mm zC|pbsUa_W#DNOKQ5Mu%*MeIcGrC?4WAccS!N3kQ4WU6f#itDTE)Vl!n4W%{7&BC>c z8oNRj&iL5-oDc80CSx{mr6fRpe+KRg?B8+sXkcJFZ_5;?HGNuXPNYUv*@I+Hg|VfU zA+n#(xfMdGHWT~Lu%FbH{l)*d=K?!X7f)@8jaK+>HnPlPB*`OGvlPp;g{**;T9-CH z3{ev@sAe~fQk09p!D40_=h0r&_$HM1Xn|MkWu)mM?&HUL@I*v6#Da z;ld?AJXEKg0F@Ec=xb4GoKX08Sd~sY$U>QU_CUA+l{woqpL4*!i?|ILLGGhwM^^#&bmX+Z-nv6O z#;9FeV|9arz<0vEJ@us6_KnmQ9u6xRC`X;gcz$Ns^~Ltq{7N~y*IXd%&GsH4vP~mCm_rNmaOlJ|6~#RL>a^pJscV zDI@cJao$fVKGz3gjF@MSSH0EIZThe^QYHa~6KSpk8-BjN;C8#=e!F$|h3W{kO>j2b zXJOL@_F~T*&lT-v?~sy5!iq=&nmv4+kk$t<&ydMMoOxKkE;Awl5enG?SRKBEtWa=* z#}1iR{mo5DsP>Sv|e)qF8;dcw~ zx~5A=)@ILUTw`9dR%?`;28j`0pAS6pBuJpOi7V)D*n-&;mZ@>V5RxP?I+o5JGFjOh``h}$;E=Ep};Pdd`W^O z-j#5HOdqKhVfj!m1(kIPQmqLcamPot*V&8w+Vx8VhuRQ0e<-l8HjaM8-H#I6qBwSV zR*cARb!Ol3vipaqdU2=lRG@GbmHVt~y+WFg4<0aO!Q5B~9}DE)p@y7|q7J6>c{DE4 z$GW4wzh*Q~L*PdH-6o`M>!afoX7Ab(06}CN;mS?TD*nB5z?r34L#*SW0N=0AQYcr? z_YOf`rn!lnRWq_9aFfNQYiel5l!b*vE;k_x@7<0fvMZbr^M;sODl>9p$OPqV^I15W z*|W74AQ>bwaib+rPSXS>JKS!5s@It(KX}=D?{S;v{P(GT{(`=ccTEi03GK{3o&h&u zP8J9=PxhJbFN+mn06szZQbV{tzrL!AMwEn@67HKFg3~l*r;-w|lHhW_KyeSSdjhCF z5MlyzfRY2;Y`T#wpJ5S@L>tbN8bxQBFfAUkO}MKd5m~Sb34#*7k|4tP*|KWY0z?4w zP(bD6Q_A!SpVQ(<%|(gFR97>cve7X!)w6-?dd1=SASwb!O9rIQ^S*!{h1cwmql%er zUl&120qeTf#%KF_)F$%v<(BmfX7?I{KyHREg%k}Hj>YN1joK9-|_4H6aV${ivN0f!(VPjAcA8WRAJrwWhb=T|uq&^D%QP zmR)B@+D(YgvKI6dC2wC(gwvm`1x6M%=TYU3$IVC_FGZNtO)sm+i*PD3GbQCQ758@$ z>}SqU2NAnsNEwYWnUD3BkV3JwvvnL}c0^i3rp5_Gt$`|zI3j`+BT@(`hK-Kw0r0a2 zXAgg#Ch)ufvj@Bb&(0b|=iuA~MCn47Y)=p(gdlKhg2>iFWwr+%j}OGSVcX1lGKLk~ z_JG7#5$%5BR8t%EyeT>hT-4EmAjvdho=Wj*Hmd~?CDI|P-f96pfKk5#r1iAR zvp}}1nxdo$x9{tW5W2+V`u;%Q)<@rI4vHc~H61hry+th%!Os)&fj$-+nyrrJ%+-@r zcxC1^VhFRqxjAoODQ`@zb5#XWYzSaNpU#yzL1g)n_JgfcN;yo!C?6&yB1JB$3y0Gg zM<^GzA~rfHJZ!U}3pU!xe6Hptna81C23|E~1VVF4A*2O&aMzQcQ$Tv|a5{P~o($1g z_w@pe|X&bG0b##tWoP`sd6~ZZVHhVwL zy~y#I2(af(C7fIN^$P917^5Gd_eK6bSfk$@`uFNOg?1lWQ$?^{)aN1%qgJ6U{d(rc8?92i81B_W7nvWRIy?S z6zP5D3$?`MfGKvU#ct*KIR|$3I_~5HS_S4v<>m^}d-;HL@G%L^!M2x4J3GZ=SR zSc+K(My#TUVqq&v1bBxSW%Q*-PT zGi}LxhQ#(9uj`7BuNCX(ibvRx)jat3=R5xW?|WNGy$XL+X=lUAG|;emgq-;pW)?l2YGazHe+TSP4u0FY z99^!3|(fUh}{w|U-S?F0|Muw+U3;8 zr%BeV-!?{ly|DM)9&3hk^t(@mEE9iX24_$Dp?1hxp7ObZq+<<+^9ZM5a-(Y2(JBZ2 zc?r~0Rrr^Qs#??vxc-9zsjxacb$pZ99wONwUU73-_);ko_C3U|7D@I%Qng$PB4E+# zpIua$(xuxmX&tAlsyUBT-t?5w?raIz6~hWcvz3>ID92P0Kh8HMJiglIav};y5*in| zq0{^S*U(=ZZTHPdal@(aKgJVbhJBJyqB15BSDYzn?*(9;AJtS z5{!@RPGD%)ggDQborU@=50AGPEYRdO!-qn9xgil_o;{{)X$mr*(vVi9z#vREYIa8Z z(20PV&0m--7|aF1vUt$j3uY#~d~Nvn_yoIzyAZx4!leXJ#g{H-4m8pQ@^n#ui1 zD;;BdtdOLpC5VJ51WBgbA`(N4vw?yF*cLD)$yDmW!B}#Qs4{a1DQ^^Lgh`5bO9v- z>q!QEMw88y-A0R;JRIL^QG_J8`Iqi?_e?-*lXP|DFfEZJ1>fQ(39H(`nKl+)L*|CSaj_xFz5g6iX7!3ivz@Pa+1z0bsY(m~1D4-* zb=W8T*|oDGB&ArLU_uCxyyup6QKvZ_-@A>4X*hREtY9x3zJ89HS8|!e#TfDN@nzR) zn($ZyIEU4g^vc2UM(t~wB4S3cAD^Fy9}jHrU(gWn`1(TpvPtL`6#r}eZ-ig(c)a|? ze=G}L;qeNO$$B1;+8W8;A9bCT8o)T?sZpXz;pN}dByRGRl2UlueUa;&8@_*^U>n3Wr>jD7;odejRQg6e^J<^2;MrTjxkC@D z$g-QfiJZ_V3DBUBoTP{{84o6WH8&7}#0;{egc!5fZ!>B{OoBBggd~WCGLd7*D{#^y zo4ZD`Y6y^QKX+F27Z2$qgeVDXFsf27GA#Rh(QcT=V8yz9;qiDFZ#;(6GpMI$9=OWL zp4vMxZF5N*U#|#=opW&PD{W+|LQdBl)h@ukkp?z`Zb@apCeJ{-DX$~Ds?~V= zb(%TootC!;?#`Xw%*^9VA24d*juyiG>-Z9-eJCDELc*?iNUGW4Lo4U5N9zE}-(wuS zi5y}=x7kwW@=zA$ZdhuHlsT73Qg~+}Hs=T;)z`DJVjH*ZZ`_o}bPh``610n(ErqpN z-YHUb4JkHzg(9GNVUCDu(pc5nDO>1p=e(i3N3Pqr{F%>a{h1`E3%M^co)x%6=nlIh z2kXoxurFjC@pGOWKOg-ZQ0W~)*dMy58wl&=d%Hrk#}ShpqS{L%*o$uV2>3I5pgj%c zIl{fS9mGL=TDtVq71uF2aI%n-Ej+3x>i(c(966fYZxp2<^%K0C?QouE_>PlYg@dj| zkL)Odh^*IcoZ7`{J@kJj{XdS&1NJHPKauRuWAaLd>?+fexI*)&sffs*1 z71^(|wttM%sr-B=$-kGfdkQ)s>Z4Ikyx9wWe0>@+7VO~m4pjij%(%@9-jp%Vz?y)0 zwtdEX4|Rpk;yN>5D`3kgT7*o53WYFXQZmsa+5C@1;8k!73zh)*Enre(!m(IFpVb7^ zxVPC2Nr=Emplo+l&?V|P*af8)O_^H1b-u!Dbv!7Rd4g1FWTlxZ&;2w_nNP6i^~x}T zt6)#+sB%JCaGocvoUp}+kP^Ng=8x^YhnuI$$uI6Dt;lYZ5YiI8{=nn&3-Z_yz8=u^ zVIJXvjL1ho6z{~C=p7Uyf}f$h;FiU;l+kMzHP7to%Ht|3D@r+lMYF4iKvTBl%f)xf zNOwOiW9C|v1AzF34%%8YK^@hA5LXfF5)#xGTqzgrT*P{rx>dg4YF6sfes}v%$0=7n za>Az)#Kvy;y`|8J;W3_(``{VgC+m*j0niEk^K{+3(yf5rw%k06O>9z9gh$AQYeWoI zScgmvv9&Fb6ilC$9Yl1m;b9Yjrj)FqP&0H>m#1=BWSvq%5JD>MPEaIKY%z1bLrx)G zR}l*D`3%_=AqbO1$s5{1i_ha;)Q^Oe@D!iDU zr=w&A>W~JQoQWV$IuTWcMmO-6>gfGKIG3QHWT7k_T zJo(BIHU9E6_?a3irRF!?^Xt@&;Tn=4!gW*c5%j&Y$R33*;zZ}BuITR2G;+uFjcx;` zQKjCG5_=!}5!s=GY0uH0oJJ%gX)Uz9pF5GK-CN^RXYXy#_bT)gOosFhMzY$ z%|S1sa4`Zg7_yf%JC%4uZT_!}EEwVhCk{G!^M6*Kkv2mvMPhA!!`GMbH@6MjW(7ma z2zC+SmOU(HK5F@Fk^-RqFm2gCBPE8qFR}%iQWwB?|GFeG-e zNr@(;WL(>{K7h^qiqrOvn_CP`R^w}`^AL7eli*+J(*j92;Fjr4oE=dn5oi{`0j4qV z)iTUJ^TL@9Q-`iO9afueq+}Y9GD48SF$gY)ZREnd6uQMWutzyLbG(PofAci}iE;{M zZ8|b~-cw4bdw#WZKcOxt3B~<}85`^F{<`r#_erO{6GT^Nl_I_et$JO~z$*?icwJN0 za)}y>9Ye?=GC9me1VIvlNcK}Vw+@Q-+(=iH_Ob4ieO88PE>rX6uNs;SLCDe@qoLUA zYMPC&uLu7A^$&ji`i0NWPpn^`Sie5-_3@6!=La5-uiaU5oW>m!puZRVYgQji{_G~k zTQK`(D3FqZS*pgydvloT9YxCiU8yOZ@YdF&jE*%YE@D^a17|+(zcYnrt$C#Ny|jXx zAgr}sJGbf`i|d1?YX@qcrAH4zGrdi60d{+US4AylQM<}qbCi1KK)D^XZ^?|Ku#Diw zUryG2EYn=Orn&pjDf4PPy94oEq@$te80%@jvwi(`pF3|y%ZNwjjY;Q!T7zQzK873( z!G`PvcnZ!OPgU!7o5{UhL@7y8OeZMW1uX=l=knFp@Qr}6=jN(>@AUDkz`rVh&v@KJ zp{>Ubvv_NNhXhwd^y&NM-Rq=r1EQlP&rmEUIsN_h?@ZtDzWFI1oCY+GPe*)`1;a6~ z(=AF)8M9HPbB3Pw1$Loa%sh%coby9bDj8|01+I5+Jk_5sPB(odJav?;Y4**Iu!vhK z?a8VFKe+*Y?rr)?!9Nz)zT;H)>%W8<@F_3;e7#-Y7i(aS2==hCLyUHlpAidCNgYSN z1^TT$UcAGyEcp2Nz+>GIwiO|zyjKE`^?}D4aNh!6Uu`t}a$g{F z$1=Bw@M)UN&M*5zE7?9Pq!3IH1_TKk7C2@&3hJ^%i_j999R0@R~(o~0iLOLP71V~1&w{3%l4HP0+6g~$bm4cP1`3cMH zv8mz{0!kY~VlWx6djZ2iA+(LCVon~cjyUCPErDCy5)SJ#P27#5n^6FW;8HmQZ9Hy| ziGAkeZ5mY^zLW(-X{7eO_YYG(Ysy~Xtl%DKS>6qHn6&`U#Tl5)$)yx)E)CE7@T}*; zy)WW>XO-S^u<_7&Kj8VnHXbQ{mDBKPlcZ|txy z*!>xKyS=C)G3tTa2NFUx?m9Rx)5nX8OcH`uCv>*6Y(&@>)#~-)6q1^G3x$v&J(mApVn_Zikj)`6UO<+A8jnoBv^4>?1 zy_^atuf`wcHLuc=zAN6Zy2q<7v`}t_YmMiNw=Wp45aJ#+KfX>HI@0qFK8**~2{*hn zg3r^Wu8Zr!ciSWU`|F)jLW+6QR>dtPge@7e5>~{i#pagcv5eSB(|``Ej-tQ%nNCLI zfB?7mD)_?$O99v<)S@0ljys*Tka0`U2X=vo8f z%C#i{v%)z6@@U;LK+fCGI}Zs!3_zF&6EULNe#$D)C?GYuhg&zJ8ig=u6wJz$5Jd*s zOLe^v2bZSomXf*q;EE`V2sjx4Q!Gk3ua|;^sw$lJ&QYdgp^Tu} z2DB4tUQslz>bXWi5PlxHKe)1)ZTr=97(!2X?ka#h$pZBmpG)7B8N4#|#- zQAD=jtDRDPk8lH*w4@deJnWJv$8MmMG@oc5?3;Q~SsmjOHxUn6baihJcFujxouh?S0VMjZp$(FhD_26VWVJKy$LA z9`?i*(>+qC_V%Lv_cak4#$?nKk&v6vJi<4QGgl#__a02vFfKXRW6v!$FvQp5x{S3! z2^#}$wP($EvqsesF=`NTj`NlT5aZ@Oz=jOFBmhrVP;?221uk-eeBDj_$ka`QMRL+$ zS0JyE9Wwo-ZDIcRHgGZsHp(Jut}ikqGLF`Bqh z&7(e~Xg=2kiH;FS$z09yZc#*xCKG6Dm5H!SGv;|lat_IRkoQnOnQfD|&nC(E+~$uj z_HRgdY%4xKKJd>!@A&opKlu3g!ask%bhdpH;LDhJL<+k^pV9^8-dua}oGNtc9`1n$SvDHZc70kApeDXk zz?Tm#RrFLk9Z|_icc{LrBb7xVq;No&o|q-&MZCjPmpBJ3xnNA0BQ(wK0Qt8la_Wp| zP}TN>7(=;oquOh9@xV#y<_Hv@@D|wMnEyY=h@W+Kd)|9FkWRZ>qGsuHQ5Y8Q&Z`2M zYV_~9qIeXR>EZ9L3*y-~0)?XSE%*Cm0@F4C9Fcy}QQeGlU+$hB^E<`$>Ge6YXzWJv zNkSEz#2~rYZpQ!f;_{zIq{(sS>6($f#feYcA=CC+v!8dhYz@#nn+wdRXmzeoVMr2?_kd4;w?sMi(=l?}Y%aj;ZRFhva5W*j+fcngQo_2( zng4frHb_rHjzqPJZTHVb89Q4c%!B)Y<~a5m>~tbTF8q4{h)F?F;CUBS42xQ?qBw4o zQ*(c@=2J9BP*1+nOOzQgzaO_uR`96cHhHi!&}U=C%`M<;7f38-Nk&HRaI6*(q(%z0 zsirhfdQ~XQTON)w@fcNPS3Y71F(J(yU@(MH-B~szAj$5U_FQ2ZG(r9Oz|2U6uEL#r zOcqmmcJ-X&-E_I^-<1vtfT-iS7x#}9RU}*X4GVL&|GvxL+0CY;B6iI|F2Wmk+&JFs zJAFsynLB3OmlwF@4!9;34@lK=SQIAml~lC>l|GU^*89DxSk3l@PnkB&^Ng357d#|F zJwrSLlLKZCUKU$NNM`S+S`$bgj|UzPa|-#|R(ySZ;PH51eS8{SBx`MYoz$KpHxzMC zCi11AJfmOrx~_69OOajeBgvQ5lTmD~qSAg!*`v}Wec0B;(Nnt!X;DAd`PtNqAfEv! z2N#hi>5ONSe9d&^?~v;LoZmaEolWm+fnAEh9!jsF07GG=-2;URzw^#T;Amr(177kQ zagOU@?#RJ83@Lck60iL33~Ok|>uIZsy3s?qKs>mQh=>JfRF?s%e#|xQnP}j)_6Wy! zNrl#F``zO1Vxhgl1A~jlq3hvuipQ`(%Jn54o~mBZw}0eR738^c$qQoHH#vERRLA9g zp`y8QX~(JDmIL zH8_ftjnw06=9dz-nGL9 zOdz;ATD1lagWA8pX3UHfbr8oC3P_=@c-MTeYn1W@U%h#=3&43KUj!xfnv83=AngrJ z=xI@$59JPV+>uHgO#@x3H49~p`^)vxbNu&(cbPJ2a=WC#9usO#Cx9S12RBccf*qvv zcz}Q0;63Bx;{zTEj$ZKi+OQ=-h_*Kc383JHb>mqfoWRp-E(C0^WRybJs3OzikrWVC zAX;R1RA7Zbw+YdE=zT_7XXyGc5uO5(2`6wQt>bD0@HikmqO=0;}QHh4c(2M3{Y z=rcG!%SFto#!G>DegsVOj3os;qG@$fOo;0jND`tX2omNvf!QID!^8d1gmNh`_JU z4ewb9y#~ViNO-LFIp<|U;9OXe2X#^C)Ol(ba8J9!R=elypgV&3Zl_%TOpf6+!ZTYV z>?XM7R>ivz#pE#XlzZo3Rmo|*t~O?>MmI@G2h9z2zS$zZGaA+Np~NA!y}tR!xBaED zAIkSRlImDz=U@?ON^ZR7jF?kL6GQdh7Ufd_a-8zWDfm_k~Xdx>1tWj2aYKd7~?LXf$7mll>!Dl4=z94SJ z|8bnQ7ZF~*&f$0N16}kf>b-X^x$t20^!gny`5WF;v)4N!oWH{j zKk|B?|NL1rYwK41r4M+24SR~jzTvs*&Kr-^cjB*ln>D9oZsJ%!uHL`Gaj04<{hnw)93-R^GL1Y+dXwdT}K>_(DXvw z0;0&y3U$;55}LB!_?L3TdL zqxyj#nkOd-fOgGo-{eY6h$(<_$cQTkEw^i6j1EI))!D8|-CAa{h<6k>#LTHCbeP09 zoYLX?ouHPg*IvkFO0hoohy^>P2&Bf>lS{(ato}o$@}j zr2~(cy3fR!OAi4MH8*Ur-p`MZf8Z4GN%5)1&021!PN=yW90G{G;E1<6bvI^Xd6*I)SYpMSyK7fT)`U`>L@y5i%pLh__EN^uae zAfq0boaY&wpNC%1YtxA^q(i5a(DIvF$ckoHu2T55Gul2++3BKK0G694xM>2N6vL{` z@4w%#`{y#H1V2w!qbW`c(mi#t8577U)#Hj1dxb8Wqm^qxg{h$8cE2j^x+1XXEM$Rg zjZdeiXC@E(+UYcaCjaA$(CKOfaj>)#9tzJS!4OW2ZX{(RO|dK9ip`B;*Z{1EA}F5} zV->l5Ug*)KAi(&jd!EjBsOVKudgax4wOC3z(V63cArI5jg6~+!r`^xH=ig7y$M0q1 zZw=7*9+bmpa2f6TS_c_9MW7qqPt?5{!k*0p3m5_;Agp5E(|;&OaFxum!do!xuc zjlGXeT_67&vqv!HU==DhX_L<*vJnB?2W3p<`OPU^c1u!@_*HXP$m=eNMFkfRSJ9*T zS!i$GKL&i%ujTDJrtLIhwrzm)RHWN92s`z8Sy#^O?w=eyOS`AReqN8y?A3eF17Dj^ zT!s$C{K-0E9)Si!RV*Ddcn2nj5TYug_lV1c6lNsv5gcrUoo&}rp4ydQj)I`>pG_-%LndnrMBC`RU594d zr}@w|8#zEBxxhPVP>Xnn@om`D{(0|RrIIRQoDo7e2zZ%1+%%01iT7hNrCPxeqabW0 zC?^^9C_j6gsfbX{yj(_P0{~q12d1)Cdd&um;$kWCmXA=zhOWb#ue2k*&DfA;cd@6B zlg%=jqKaNqL9g@XML439y?1dDf!4ySCc69p03ZNKL_t(W6zWPHV0Sg92ombFFyo#g zIhn6dXQfV4<#n9g@UHClArn-GwNo@)=5Kx@fN92!XS~A0=>#UimT9Qw8ERQZ1oW3hKVd9swV> zJ8Rl~{qC9HgSZ0~?F4`w&)YOo0d+i2oYSYE(RYCJvpUeIn-}O>D^GWaa4x1zuy}1R zS05P4yv-inJG>b_6{-#B+fJ-jIHJV{?-|$TS-p5xxc#nk#@?s#yzoCGdCECO;kQtY zMw{q;8Lt*6b=P-~fe>2q5u=FD%J}m4oHKwc5gLDcy%}^O4otN`y}Bn?l#pl5*YEJ# zuO6spuXSDobf^sRdGqvSO%;D?TVG=_*9*6Z2oh69Hc}aIT6}kh3t0Ur(`|Y5Wx0?=>s>d@PeF2*GmvLOoBAxG_`(9yWbf0_3qlCS+!n#aKQPZTyk|_)2mbl{J=zjdQl8Eu3XV|NS||7!FAkv5MhGItnX4 z-KU#-kxg(MdX0^MAb2IhpHqMY0Z)X<0YS~9o{RQC6-f<|)@Tz7P09Sz^B!0oamu-b z><}|K+~x)M*B9_SA+SQH3Adkbc>C)=!OIO%Eyp8l36GetK`kEyj5P#&K304^9yN5y zJBOGXK4dKx$#IX_wyo~h<+|DPmr>-+C^`j|w_qEi-g)nF=LJ9h_yhO*9rJC$pFjV= zfBg9qKYzU7$J+~jy#0ZBo@>ArInF^bG!*nbxM)+jqCu7+7lAPXjXk~b3?=XBy(1`z zVIRLb>x&+*=vqoBSmAd!rUGTowGPv{vVZL}Mh>;+6X0`iq|pECHKShc!ta++6ovM; zn&y+c8P|=648_RbPmMlMP*P~Nyu$N{Z9Y+l4i}iZ;-00Bo@=2}_>*Ww{qIl}{!gd~ z&v?b7;rsLA^Z%sy>$laj)W`D?p{v)Y?*`Eg!w$u8F2G($QdAcv+!zc0|AHBjFb_}~59{_FdK)qA)59urlS4J1j*|1X%h zRuhsacyd`AkPx%yYvB#oiIsLXh#hT9`mh%O%&z;hhjxJnR5whwL+i`5ifZw3bv@d! z+V6^9J{??@rj-?gWmiGaS|R>j$|)VFB>UgzF2u#h0-a79rDZZJzq0XfA%Z7slGy>b zdBNZRyyN5JBaea^!UB1hoCx{AvMdN8;w?tp7ds3^t%#h3;HEq#b%3ge_yF+^$uVS_ zki3U@2l7+(D^?vTW|uBQ8Qh2+m7_n9s^du)H%~pft+CnSQM2bN4Sz3U+K-}Z(1?xz z%Xm-Cw_KW<8Qab$dq@!UZlF}n{+>l>R$!;F84W@cq=*zVKvA6!a`Bi>NEWUOkugPt zaj*FVVP-Vs_o}$=ixKVumihv_QL~QwigX#@<z}xE`ulGAEJZg--D2CKIbmjuQUsq%6^}qxybHClzox@ z9WD2GhRaiv2IRyC-MtR)tN9RTkbO@lc0$ZQklYDnb9el69 zD;PTg5eS3N^U>N)>Osi^NxegjIuTRj{n3z?a~b1})J0wX|0}qk@#wBXV!q`!pLq8c zRE`KI{@=&w~KhHyz8*;9JXkd8B>`LX$tbDBm| z#XgRsfFPTOpS+&8j4UN)Fg4+JSOUxg-|4?6*yWh_QYq85`F#H>NAU-7`JQcRCiu z(XOnY4j+D|3)>(%PS|>vDF+@9>hj;A$)NI{I|mrF2Hu@all(;W%$9VLYrudcYoG{( zpyT_LC=gNn{ps-UX~J86zuV*x9AR_jM3q2DdCKQOm@`K|M9E|w9rloNzvg*{UuLLd ztVp1F#_i`HnBU%z+?=US4x*Ahau2aySss3z!A_v|zu zXlfDbg`XYOs3s{Px((Ab0+)5L@u4P=)h0I*^qZ9a_fKZ zRq@Ifqx}9jJ|)qY&;jTL@=K@V`|mcn{ohB9_0bU{sazMNJA0u00n|s79v4U3H2aPH zS;M3)obO39utQT%k_?|Bzk7t2uf4i^F~V6|(w^6T_8vP0a~7Z4|GUjIKHeXop9Jq2zdk;JfBwP8SN6`` zA{enjk12~^W5WHOFwZk6$74^9>wYGVfXTs49yB>{7G-%q*Q7R)ErT5X!0{am4LINL>ISOWttPkCDmCGjNHbDy0dh7G@L7N;-ORN|@dZi| ziHyDz(uPNPAi*OjA&7OoSzJ(o+rHgc*FAZ zC*Wsx#m(_lms=x$qYE@5Qk@X=b|nm95F@ z7(PdNZ`+0x0=CazaE>rf#z}lURy@AGus%vb-BR&X$#|^82E?6ctVIA*v1=oDK;FtT zFCy^sRFP{#Vy%cPk;+Rhx~FN%++#loUJN;LEkvbE1yFq0)9(Iv&n95u9zCRXvWH!T zH1r6@8S?z>Id9j(4pm<`Fw1@|^NcsF5rJgWF^nkM*PANctAuyi%= z5GVou9DHG$I15F85*jF8duOMTWJphFI;56q@XR;;YF{W6vf`!AIe(!F z{0eol6qjtpbme$^2c%3Z$df-RzS3YgrQ86F5BC4blyjuT?I~5b+~a>aRKnxk}773Yk1JxvxIGv61upD)>l&m*b;?9E1%2|78z zc?(0*9J=Br+_N*(7DN3!1k`H|}}B`R|1aVLWTW>a!CNZFQ=ss#qr5Uw{03 z#p~-UUS3{snTLxJGT3%y$Oa?@rMZ|>%;%{3_NHqC>G(Q1NY zLsp9HvM=^U_Opib*)+SHL4A!=-bXpd0P|0WJ9)-Pz7;8+0a0f(wzC`!B7%=yI?vhY zYHvqUMr7rX9sut0a~-d*M42lci<85_r~6bysyC&KyLh-DEqb#*^m}SV`R^!3bPeU@ z<00IC|B(Jut_MlSF&?9Bd)E^yt{V(3Sp;P=0xOg((%?AeYuvj1!ND1|PZl%WjUJ;k zK4=L57=>GMLP>C)E#6Udqe5c?P?F$sF=XNp8SEEnxL%FY1H!Nw?+doG10xnCekY>i zu4`7htc-1e@A>XD3QSe#Tq%Uhx~*#t0BGp=!h1m%;Qe&sxRUWM$L47~aNk>;wj=>q ztH_NtVOzft*9TIx0(!aGc<}3M#pmZIK0iORFedwSgAPffqnJawwNF_fQZ_<{SE?=n zfE6<_HdHHoe4SdVm4BvXuEk?1Op4H~x3nw&zo(*@n5GmoQ!C7OQP*cSVSqrA)S?|# zbV)meLOQBdv-GTMR{Fw4c83NH+`?hK6!#RNy5>u2<~$p!bV~{E_y_a!f_d_o9b@v0 z**i>*@b|A@*d80acwn|>B8ebK$|K`fgfv44c)cxv3K&|8R_7e1yTg5(aetYyu3va8 zz>lAIC=&kp^(%iqwf*RT5wP8RHFufnN1grEoijVgI-&4;#|TAAS}i9nyrzwEixWb* zp3^j8_I=u@%ik*&)>4P*(v8w(IN;j>YrnUjaFs*1Oj24%23MZ3En%*)^{Qf16vyz> z1a?-WCG!YD^nj4hxHabh8Cy=a13M_27;qo@wLf>L(?%dWDk%~qi_gp1N74kAr5GhL zF=k7w$j%usXCkhzU6LDf4T zuX>*9Q(yKI&B@QXaL!k?p!G$#RuJ8sw+d#vzf^+ogfNN2jM)NF#LOZDT0N50G1O&? zMzO{~awwe;5R$olRPDt527h0WJORrD|Kkm}zy1r;{f;dpY#~A^;d51ZWl#_+v}+Qn z?F(BF{QC7bK0ZF6NSHk1=Z|}SMOUcbS%R9LXstc}?fQ?;@6MJ`8b5r$cT^5>pRjCy`~)$R+utww_BHrn2X|R$)A0~ufN}OLL1eYhD1k51>?^mF{idUIUb{I_uDe%OEVt{Le8RRVWNSiN=RB6h!aqvG zV{boYZt9j3=#G=wJvw$4o>cAR@^oSHj9D3zpTK!y09YeP2C3G`U{I}qO4A(eeg~lj zgcJaUxTBM)1FP1sn1fzJcMX64ob^_HM2LLce`Aa_j+}9ft}d=HsjPo$*084;4jqW# zbAw-}11A=N0v_B{3OGgR?n@qXUnT6F?%Oo#d}@qQ_M?uH5LNI98>CJpY$D~S32ruP zI+`aeuP?a&_<{L$1Kb47L100F6$zXY*i8^>llGLXf&BROiJ0AWrrEW9tM2m+v^$$1 z`8;7%%?+cAd3rK|ox`@pyw}_EHe+d!1VC^=1pNa>%i98i% zA8MM=<{VT(M6?Fm&|Q0-a)N+SB6NoPU;*VC`Z8#irKE&v4%AJz+z0Jq91 zP!%9WXp8^_e0>;YAchqaJNRWn*aF_)-|?^aU-R7tw_) zUZzjYjUta6No%pg4%J7sN3hRCIo0K0;@x4;Mw5;S%WWDC9nTKV+hOM?&LJISE+Zjg zlk9^{0e|a9brn!m=zYdA%@EH>AtDA7Bh8+1UlxSr4!K8A68NZ?Rq?lcVOPBBe3`FMN1*Lxj8z`CvmY~(3WWQFRMi)DAPRz2vGcY9T7Sj%UhCI^q)7!x7U z(G5vq$#Fz5?L^!SW1aRsfI8CqN+$~5!hxomsfiAcW-S}We%{WPz4-kGvbxbB3Q zu%D$r(>4$k)#FqkQ+j8299lKe|QCu*fj-` zQHaeqT?AVWTd^2W3!yQJ8^g~tXqte|4-A$mQK5nk1-4(|RtInxC)2sud%eHl_5NbT_3eh2 z+e@7c0xfy4I)Eru``2<0%<^?iEsQBvOU5EB=rvNs)k>HT2E8NQ0|Q0y+MNlf%z{(i z_6bkBw+tLavAd>lf8OkCy}gKWe}?TD4*U1-pINPG$Cv9xa96}|(lgsNs^Y8zM+HYt zZf|jCPw7s8br|!GM)cTqP`~4ud?u3VJDOt@=DEX43H-3b!wMXNK!T}>T{gz|%z$S& zn!pUC6p=z2Zff;=r7^{^Er2}c;Tgz@Wt|FS;QN)4x+>Wi5-pvHYSi3TL82jI{#bx2+>}S4A=Dy6Bw`EZ{PF+%_y0oNLjAclMy&r@@%8bE$K!#Ni#$iR zp-60qWM5oA+n}EDLD7ldicj|MD7w#7<7bWTnR`tC+98Cl@q1M2&Hi~Wn_?@3tmwMm zU+UjW;oVbKMggWDHd$sylGIsOIiy|(qFjS2MhBQS4U#9^e*joAg~$`bGqCvx?~Nll zWu$nSJ?6>b{qqB1ODMEH1tZEomJYXVh(F%&=TE{5FHQXR|8n-`O>*N%w(oH)Tp}Vf zC3V&GYu95`1J>g*l3xW(iv?-HydJwyA-RRY$P+mr@s8VPo%7y3)0V zo7(MMYf~kgo1ZuzV6x}^zoh$1-&B=PI)JxIyH)wB&%Yk{^!Yz&&y z5$)X_sO#Wk#OS1R9Z7)|;G7pZQkYT#s4w?65y4nFkhZpg*6ONhXetmvUXNnbi#;uW zFJ^{yEylsYj6+%1#&Jw?8bJyk4pLzEZHK<;7R5DTo`4e~RMS)vyO1POg>1igBKDu0Q*0@5DCLVEgd6?IF98_=ekYg_9vW0p?jPLf)U@ThdDfVdfN{yllf z-YIH70dCRHpPlRoDGAKYMRJ^^tKueTQZPm~QX+y$pI3GP&t1doQ&R5w=8dl`{>mY& zG}_CeC4Z)R-tbe92p5yta^w;*$B!zQ;xLc3b31A6v!k2hcA=#xN6l&&HIMHp;Te^o z65(B&H#y{@duGrs9ujF=Bvq!`z0SG{)v0A6^Js~`BN4gXtzC|_^ukRK)E%MfGg%a% zK_o>G?4I`?!*Isy%M0G$UlZduNsgR!t%qTd2RrSBiOniT>rj5w8fa23-A0ZkIjvq zB`HzK^r#f|fvW|1YZ2GwK(4kr{V^2%u{_(Uz}A2@LLRYNc)xAi;_dAX&o6Qh#7KZo z#?+X&xRJqpf-x#}e5JE&wL;%oDDKe_pu3wdg;8y z6jo$PH=9zI+z26Mai24$av-CW4ktzQG$l5>nlXPdFgP7J7l)jho}dYlwGbZK4pwV0 zM`>1Qpa}-vaXNGe@-Z4C@#G;C?Qk(%?a-oB6`oNfNLmhA&?yjz0izp1*s+#myG)RY zNxmVUNTqoe$wdSZatD^x(ny#MQlyrU0a91p+O-riR;+QEz|caLkqhg3Pl-yQfsuk_ zjS^HkX~!ilKIHViM2O%#35=o^pUEL8#dzEU2;{WH8}$IMxX_d|wTR!Jd{e~@kC6(! zHzX!E17OEsl8H=v=wYmdw+7TTu%`q1`;V~w0Z}OoqsMu2n0&y%0WLB;NOaw#p;QE? zJJk}|W*ZllE^SPF6tTB4uGyn3U z!AFY*Ei(i7ei-5{ctR~9*{UtqHS@ZTH0#as>I-PQTRBIY(o!a{(ry=B@J^9^{l=C* zyXe={Qtq*}C<+l_NgbHot++`F*=1#KNnxl$Lq!PIiCJ`4&Xq3qG);JUc@pBo(VDmL6iS#zh2SL;FfohCRg?3B}&rH)$ATggTKI2*=DX!)auT$L?69>N5NY}0O z8t;~WpHJIc9BpheE1+Kh03ZNKL_t)P%)3&ET6;^22)l*GTdg<5bk8|ACR#|qbx zF*53wMROPioZlpj#CtEPTgt$PfSU8YHC~JAHd$b+i~S?`qIDN~s{^rKG;bwdZINg) zTa|A_t*;&A*_@XRUB;+|!EOB-`K!M|2-aZ>$L*l1g5Lx9Z%b_dg>jWmtCt+nOQ ztPPd-QBOXzK`ur?Qo10;^`Hh!BT_g{MDVi-uilug(h?!>WIZ*S5Mu*tq`R$IiWMnB zA|{nr00St3t2*S1SmzsZsoX@F*T=a?;6M#Sj9V2Ygg;4J1k}#(U zy0|*Tu$at=6&#>Wy<<=n<}|as=jjkta*jC1Y^RB1=2Yv5nN<%;_n86*52Lk6B2a0q z^WM#p$%s-Y#fs6a;p3819w5FPsF}lENw1TP1ckT~v&ny@hbg1~5Q}^zzrL#pK&A7} z`wFLGFi(MzVF!qb7?P%;M6lMtb}gv2a7u%g-5p>XOdK(JhL41iA!&^q zQ{!qTW3Uf!eq1D-iotgoBR}swOXTr25|bCCqdfh|1e|rZHxo--@UR>}euA}a3M{i% zewAsOitKhVInOe#;LD_WVS-9p?OHpYr?(tKHn&_&EbHKzt%*{7Z*NI+ul63ENocA% zL>4S3;!O%zO-I>kGUW+Qy?4}ylD)6X-_zXMY~?hdHVYR5-AKWUMVDNUs@D3ptpa=P z6eZ;G1Fkw|_37wGxT*Uxm>Zh##h-=LUF9MH0nIn1a}Hq==J4Cw8=jw^@$~kZG}XQ^ zBSG`cydF)|CqH8hP>raCcbiRJiAJK9Bk~%7Bo8JRgAoydv|WJZt+gOE(;Q-DHmo_# z$|N0GE2&SdHPF;RnWeF5UHmk8ES5+GN*X|Om&=%&MmvHn(a|NYIK)L)dvW8(Wx>u^ zN^E8XQrt`lyrs3?E>7#3nr>>67xJGZ<%rQ^7)QLlz2N2L1?Tg*6xK#5{QAph_|%>B z9Az|_WKljc8f`WW$N7LZdbfLe-$P#R;fHQYNp2jT*HO83mm&uPY{^Zs4nKE0ws_22 zg}R_O71jx!TkAm%s^S0yAC?Sg0MAdaS4DFv#b9y1buXyuISkp{$TH$qgh6Sj zM8k3Lr5Rw=te0=KAkjwcai&-r6nR;(>2vcTb$dA(%c+4j3}D1G$@;rBQK>bQ%X{To zDpH%oQ^qkSW*8`3qWC>D5n2f8hLS;eF8t<6U*1oG4`9zS2}zkp99fbPBcQaA;x_Mj zB}qAXWJsk>a2n~yIQv>ai83Nh4W$({=~7&4QnTDdO9MtR!^Hr~#d^9Qa~DHLAZoqI z&&Q@LATACD3qx8xl}rXuE_+w@1gvz|SO%gYV)sygJ0VaC-o~_0jRlN_R|>%pn&Sce z!vng92WZKbGihSF>}bbVDH%m>XZW8tdc_1+_}EB_z46Ta(bzsH1Dx2C6!wK8$Qh7#F^uib}N=*ta%G z-)cOWTfE@)H`(fJsTt)AWFD}-e`Djmrz5d`e=>>N* z-{gVaq5~a5fSV=^!+`hqcl`F-Z}|NAGjtlqpad|4vbbc8oA+XB$fN1{HFdUusz$FD zph!&QL?0H#Mey^(;=PBDV<|lI=G?Y@F+LpoQ+Y_WGBeF2rWCOlp|nQR8uWb!rH?o? z28|`O#z5(KC1F_$|MMtFy4ZPZN(;ZyI}2huG5ZK_vK&L)`kq6<7ecMbC%k+BTwGHw z_Tx@(87lVg@g*O;Ce6eMD7{@=J12&i*SD{Dd3nL>>nlPCuvUzUFE1~6etrf)VM<+u z^=Uqb132ePQJv*4J~Gy={dFO}w?OO_+u!ppY!%jfGOOCfy|uwCzqgbN%W-0@xT}30 z%R@#jEvfbJ+s2eEOEDWi2L%`A*_E$oFW%-6$Bs12-S}JYW>GbH(Gx|Zspfi{nkdSHU!>81e1~s7dP03agT^^MrTTwr0z~i z_n6q^c)JzzT1<7JKA|N1S*%PEjAdF-2}VdoVDMwhu=2Y(qCI=1;?6`Ycb4AQ0?I^=pQ zd_d|s4U^50N5LJfeca2g+=bN*9n!98pnca@&O=*b0gkfp7Hebgm2GZqVjT4+6s^?rWAJfYKOPcDJQAePfaMUaa$ajo5p3 z=VFx>k_xR2#&IlWlDboHi~5tlPv+cGMWfl$LT^b*wt{Ht`=~a&*7qoCvW(scB?!Ra zC&W0G!mge&<;hWwG&Tzfib2yf=(-Np%5y87rhsW0;GBb|fK~%RF^+wYw-9h126#7$ zHo5OHd5`zYh(m92*B)j1fhehToM3;;`T50`yLgSCNC2DWK1_<*mEPZ-B>sn4&ln-V9$1>+XuY*Z$#Y^IZQ}018qgiOQeO_8zOXM zX|5!xMvWVU0w@H8=rM<4*i)noy7DC4~jbT4>z}d507fwCvf+K!IT?B1GBGBDfqV zCJ?k{MDJk}(ZYL|I?}T_J@2nn;?z@z9CPG-NhK23RC*r0Oihc_L;)&7MU{eI=J&FY z$D~uURuL*Pz-fQcR%js%Kr2~ut%XO#l)C&%TWByG5!68rLCzYqcXv2^{0YYoA7T3* zAO*)3=h5Np1118-DB5cs4JJQfn$BQ9fTu}hOS;Lhy0jPhS?&`6AAJdW0ip2PYc@Oc zye4r7&?&4&no1fb@zE706D&sr$M8Ywx63dAq(RC+sdqRx!k7ly8YnVzvZPX_IL-;N zv!Ph(hqmn(rp>(O8YPLCf!%xv%}CfdPvJ_DpAfRSmMIOE^zelo_(vp@oXkbzWpw;* zolpxb)K-H>KJeM=MI|I`-5}Z`jjSmn>wRK1>u_C#wZse)G0r3y8!DsmbzMYyaXifXlSrfwGd*+>z?qR<9_=<8xQEDBjE z+T_&t{Pv3H=VyF-dc^b7E1V0kN@I$vFbNnQfIdr?t?LB!MJg7JWn&er1|mBkYP7b+>CoeF?9jHh zXa(hjrD)OJtrG;dWGU;>+@7RukF$Qu)Vb$U-&^N?#2~s}fVDPDPChfd4+w$b zoX6YS+vem?Yx#Wcj)&QQp-c(g$)te0;Bg)wFbqPS2_e83gX6Ks{qck*Pp6CmtcB%> zpf!w=gPT(dQwX4O5^aA@nCmR=?(fBH*|zAq4t?Ljb}dwT{ulvT+iTr_&7AGd zZ20r}yg0mFO<=Mqu$p=_O@pqr3mQ#ftLMf>nwI#qzGwnM(*80Oyi#yE7$tjwv@Qnz zOht-rMD#%n$*Jf!3C*Zt$|%T$n^GvGwIu{ZWuToy^s{szPw_}ASZs%QX{Af|IS0;A zRM5s0$^_U$@f_Hd_dp^EA5ltU97iA-c*WN#0Wch~^h~L=Hb#}!OqMwA-1SBdf5Ac% zyzXAFalafBYh}j^qLf0&--8((98|i$j3)R9sK(-WcS3vjfWzHAn!X2VTR7RCB3Nm7 z=WrPvhH1ii9B>&YOye2g3Gg0@EEGa2LeuA_^nz>>WD!UWCN31Mx`?gS14;oXlY|Oa zEUrgTl|-F?MxI^~fXGuiv&|seaawnD^SuS2c(5`eS-Rv{G|%?X zcUo&8aG7T0{0OStyyJU} z-+kTkT8p)2qH1i>Jg(7Y$UN(`DKE(kD6`-gBgWuLC%0_4Nq8R$fnhc>E*@F}R5Ia& zx_ezEmT_2WdUGK=CiLFx>ni}@<>dumzI-X8ex)rqNP%`;sBFt=mWVJ;#l@^S-Ws82 zS9dP>7pJX6IfxPP`J!`jf~T9@H-ZteX;VHO`!aH|R^$HIpl@5WZG*0{IGtL2dN|?Z z!=XfCE7GD34!PKuE^uIlXrxQT(IaLUJt;&G0!J95uZpFG$)-quW)ETRt_1c{geT)w zU|NiGIRcth(TN2$-|HbwL*#Z#Q~(%oB)Gtse1P&SNTw8b98;oI9xN`T9|#r5L9IWArM^>`QntuRC-(s|>V z-V2wywQ${B2R89%%grzsgCff=aCiHjBgj=0Pw7F~X%T+2}l` z;4vlA(lAZ9jH7g>Q|HbE>55SljcKMCIF6Vmhp8Mw3D%??rs|Zvp5O89@fqjKIdy$i z@tiEfD|it?lBGO{zDL(JXpDt2D->7d^#DOS>?uGaC_*4cLmENJphN3c$W2Pak*vcq z-ILT!-AJLNJwro`qJbo89i*UD3uBtp#7Iqs=w)9C0f=4-cjtsglz*i?^x`Mj)QGA_ z?NF&PV6sVE#`?*>DW9pb=u`vZh$*MLY9K}nKpF>1*A1>92M=k+3&T3S4yvSwoQY&Q z79%KEvYS}d5V1xerYTI3oFp?X?QoTAPPmE^yrW4$Lz-VoD|kaVbUhCD_c(m`h~{*H zX**0DF*?S(8{s10JaBOV;}j6Q6tUxUh95={JQM;#P*B9_t*J$Kzb0tJVt6H()q$Zd z=;YZ#!Oi6UL;zxcWn;zT5F?o@K$Y{+zySIp#)o$we_06 z)-LBFn`tI|tpi~s-(#DC^}SHUy#jkZnGJzAKZhSRTNY)(MzIe7W-$`}fz5M0PAv{j z?BR~o&CPdyv9lk#?syZtWJp}6k7XWY z2m#J}jA>K&_U)S_Hod>&?d=UAL>SW`MqnJ>>is7)&5mAGsk$2|h9{AsB~06j)y>TC z91}SJ>1)hfTm$eNWH>@3(c2L1m$epc-=OJR9Qzi>Lx;OlkNcyTw%Vq_{rx?9Ym#Zp zpzAu^osM`o9mPTJCj=j%D1x*>j3jzB=fFWCRgotIDRQ}H4g-R@stalYA%vt!*9{nw zW+rWAQ5^pC>t`0UQ~!BlMk4@V8JdPMb9qR z&m*LzQ5HKEIY^2S&-Yy(nST5B73cFAPft%cpUBS!xF20E0kq>(Lm{7 z$5nBif3JVAuf3-&+j~801IU_rz3so4^_|io@tfGBd{7$4ad(=ww|MTYH(QIa`c9JP z_x{<^@a++qHa93<7X-_WN&URnhv@tq#aCYvZD)KS&?cj0Yit_Jnu4}#jK$&MBz)}2 z~2bw?jWg|)ub#Q^{}`6638pU-$7Mhv4A!RO0}_t!UE z#sML4p{TGD%E>$lkVE@0%J&%ER5rD)X<^fpAg{@p!lTGQskqx^;!1;UjI3{`;}Lx? z9s9;ukX{~=q=4ZWe`>8D_c&sLbQW0=LXyxR8PRQ$dMGfWo)fS%6EqZBrJw4C0rIQBC2Jx zmsBj%XsEQ{aHZoftWobLk*HKGX`%?5ifW|+t5GFc>D0kCaDm}Cp!H$|8GY`grH)yolB&s- z<{iZFZo#NpvOhF+TXnD39sOGj z{XL9hF2J`6&&9zyT@=Q4y4bp)&j!HUjVc?G58%{b7|vtDWXfncgaBm>nq;JI+ZLLD zySoQTkJJXo`@8a*+LNpSU4OvS(-Yp_USX|BQ;?=0Mr*inSQwuclSTk!6#Nu0gb8Oi z;%&I#G7fk>pYif`#`u0IT=%w-qFx&UD-9xsN*y{MB8FkY`+30mJfvWhh*Q_2>$*e| zk#!zQWHbsuNJYou{;o&fDOI;=8XS%tPNz8q&m{a`{eD6SaDfqgW&@|a!+U@Om02D?Rj&(?f zHL2;P4IKeAeGkO|@hn||($Lmato$_gj}^H=DJUic5)QM9B*kWM@G(Fs0$T!tbhBX; zbTm-)z6ya3NaKT&RAa^oE;_p#`>{;h;({2m2%<|nOI#yCYe@)F*H}peJ(L18z(ylB z8vVylXzm}Nk9W{bho~EbD6*+B2qSyqh`|T=mU!4CIjadA(&^Sv zMlU+rdvd(G=*?2jx?bW!NyDyWV=ep3&Qk)3?tUc;T6lT>2UFCzfplIg2IO^wD-&eB zpVb`fJrKwqXFCOmRh&w7-S*$xQ0JQ^-UM&2oBX_rq$aHCAv`lPqv*K^C<{^!=kVU8 zNK(dS954(6To5x*CVLP?jN|Nzt;d-qyd!C|mm2Ph>*=O)BV~uJ0x%_F2vbbVVlExX zY_gQk4Rb{DdQ;|^(M*(daOGm~%$nS|a3%SS!|Gb8m6nK0;b*PJ;n3lD>hR&=h=&g+ zd^&Xa^x*?OJREU<=y894Lf`kWRPZjYb<4rqV4E?sSZR4`PM4}hnGS#h%*u8?a4kfCkSyBBDI3#z(>F#M4YN^wL=pR)vcEM*LFS4$W|K-;#} zYn#J&=IHfI8juaebA+EJxI_*3<@0Z|x1nip=#Qf9zTBaCe!=tm8GrlhU*U!e{`Ft} z8NdJi&uH6L4BXZVt}l(-w_<~1nox+mK#I+>k*7(an-aU%V-EaLd894)KJPt-(P13L zXCmIcBK1|bt_fsyaGXM1g*i10VUc`$j`A#>W&zplSw%!111GlM)bbgK*PW>3KCLeZV@gJ zJc+E0qd}l_=uaJJlR`i8WJ46}GOf$lznF@Du*hp7bFRu#(JdYpMub-c2ST(Bx>Hjm zX`^=_rYmEdG`3I})V!9i#JoO>a5Vpasf@!S8^W&+$l*IAu=PHfwc9?jAod6dN+b3i z^r1)h@DcXz9=bn(O$%ni!~tjTaR~v=M@&BPvm;|1FF3!wU^t(_-Y1Pa3Rx%rOy@>~ z05qn(T082_ZbaOa7!=PyoDJfPxEXY|C2z>JSMF*{u^*E0v?eVn>2BxgOVtpJReiTM z_LZiTn&n?gqjagH>`rq}eAEw9P< zLJ378Qj*WEN3GY$wN(eYy0|6PF)lG?i<{Z+x9TqsK`NN}x%ZrO~(&C|{>oK=18oroI@`5r97r1FEhZ6aDp@PZls{*?o zdBjp2i7~TmzNH5Do1*@$!@w2-F?c7Ky{5s#{Q)07+~MJ&$4{S5`1J7uKAlc@I34lf z;V8z%u7_!{g&4 zo}XTl0d3aY=I-X!=<1g4_`0~O9`yAyT8(F8GMlOm*~hIyaSyMwWenURbL^QA_rhn2 z#HUWNi}8o!*7p|Rz2KY4wYuBI*5001BWNklGrm4P!|F#2?`Jp@p|wMF9>ZnA zdGK@ECQ|n|5rqKx$$ZKR7?6MX{16CngZMU5C3lz8HigRJ+;Kp6vL z53qfQ_RvEa4IhFuwWgF*d^sablXPH{Ohqvja#L=W39oxDwiQU4Xr=g;17engsxaUG zp_26Mk%rdj#hO~iTI4%uTbTPh^dBFf@9&}e4rCid(r`ZF;yo_TV+;&8NXU`*9&S2g z7|s}ncW`i$%&ZfVQ>WJ$vYbK^MvZBJY=p1&?mBEHGoKd?xtKflOHOk{T!0_82v8ZD zsSP0{N!~CF*>oodSgRIP50wo>RqaK4O@WgnN&x|z|P;h2BUYdxmx_>c7z*sp^BZ!$LIdo&- zMc@rU3$2p84wtsjxFn<0H*C4+Sfn$}uK|nVDNA1R#;dK~JXw_+Kq=8v-<|O3!ySJ2 z@q~wm7XS3S2mJKA2mJK#JDiR^9_|ikn;B;}hKOPEAl3_Q8^}PZ22fVg(#Ya6oB^e9 zJRZRWoL^rMqfkg(Wb|E&#&!u%PhuQY8n*3Wj3gBb16mlJVtA5{nrOX!xtX&rmpP*A zT969m|5Fti9z#IjkdogLqAUeeXd^N8TC2j*7VTg{Bto!J5rCz%-~-S>At-`oF)*M8IOlM=T=3g3p9|SVuD2@s^SBd|z#OXQ?skz|7F*1zr&rHb zhVie+9D5kPz3`^Ju5yh~x;38L!Xa&$AlGj5wG5>G9>vhJWdOY)@wjE${E^~%ZMxa& z(#V0^uf9iIn1EC=%gs%MxCr3Lhp<}zn00|d7NKIY^N~f2l^Z3*qJ_=Z$fIDXSj$9? zlqsl3Wegk#ygonS>$fL7K0ZP>J%0XQKjT0C_4hdT9o}DG1QDif!7JA5kr*;<3Cd9n zbcY`I_xJeepMH<-(LD5dWovxvIy@=`s?HIh~u$G+e)a8X&M~cLn*GkpHgE*CZhxoQoX#6 zX=Vs#6W;8ulYJHZGw@c`Yna9~`90nR&k zW(1O{ao|P{6+Q?V!jWjT3F%rfI7N1Ikcmp9lv_YEElfr65{auZmLRQ=3-p!$s>nuG zzvK{@);yKal14)r0(A|VyA!$(AE3GebR!2G4}}mNd)sl?r3GIU+I713cf5VINwc1GF4217>h-Vp zye+xr`up!qNR6sYg>hBfE;hzBmM@va#HG!sIQWISP*hTBgjLcUX<3*Tq+A-|anB~H0G9?zdd_S6*+%@H)E~uBUb&2CEjBb?~# zB@Z7fe2`u7J$fmwC&NgDG-7g%Jwj6 z0U#FLv$YKx+hQ06yVZ4FD!v`w2jTyAw!vi_;3f}aQ;*>EO#P;Pw8-AOwPf>;OsrVygcJi|Mf@w`s=S4Cy%ZZgXl0$czhJ?b#bv9 zeO+*7A_K3nbW|3@btih))EDOn`nup#n2}s-Jl)!4vZeoBOH?wGd(C&gh0@#V%GNZE z`p@%%yfC@!m>TP-+V4q3_RxR4Fw@=Ue(&L&wift$O0nHZnWLpkXDVaJsx=@~n8>wZ zN{qYn`knRc<-Nx!hfJeNSI~!~sR|O?-Rc~S)4>OY$LCl4?Qeg>G)?$$f5Jci^bvP= zchCg9zrPDlJ4Qq=g>ch!SJy2k#*O0$0wWF*cJcY!BhKd$zkdFL^Wbne9H5&PN>9+* z!rGWD7aHRvJO;9lrKCBe&Ax5|A9$oSn_nBHlnc}#}RIlb=CU` z{rE(V7mOwz4yj1P3u9 zTn^izh!|2>ND^@}C;Oq%;sr8V4jFxe_Td5Tp_c=kV|2zM`U%cxs6p;SYYoVa7~Tfy zPHP67N92G&qCSylfNI02d8}!vX!zzk~Vs6WI1JhZCR`JQOaDaq)~H5JpcJoyZuSb8wdt?sAc9 z7be&={j?@aYYD-HH@ds~ysI#j9N3+ltc+JjVkGU{tq zOHM)v5|zFji*hj;ZjE2BH!%MG=wQ9!#d&PAIMLNbWPMW2@t(}MTrL=f5nsN3!!N&l zhI3)1@s?9?>Ch?K9Z$>HlvizkDzUnp0(6M#h*4Jx4CkD5OBPtd`hCa$YdXO#W7hSk ze&!5kO_zeikZ0r0@z~-1)Zyd99X@@$!>5lAxIdlH*bc^6C?(yiahh-*Ck(>`9{_Dt z`K)4$u%-doPOwwSO|P|0X45H|1{gkd?xxA3KitC@gUdLH~i@@f5mu~uRR{`FnN!!kB>N?FYw;2PVII4 z^1KMdTZX$@Yqyhfx|R=Yb#b$SWpBz+KNqzrZ>vCDqvrOy*?ZCCaU)K7txvpuPH7kA z_&u^n?!0W_mFfa^kCL+2nb>EsSd30}WODg$V_}*G zJ_LOG?JGWi{(^D5;OC!z#=rgRKjYAeCOUWV>a2jQ#hgFSR3OtF-+Xs>hqmqU`uZ*b zT#v7qyo`XR$)oF!IP|@&H$H%pCO3ylX=P+BQ(1Z;T|;YCE)5GYW8N>~m6Wcg*wkix zYb~0tMca$9F;C5M2vYqF#TcQChH`Ug&Eaq;=C`~_vz8E-btp!CNX?&rZ&eDjB22*x zo=+KYjL_2emI8}3Y}+KNNh`F9zz8uwGr^KV0|m>3MmI2Nz1E}(>d+@?1~cHnU@$xg zUDLqoHr+!(reQ_{jYWHZhxXwl9c&JuQT9Cyj2JY+NC-N|a2te1BRC}Dh{#y-zRaoM zr=&^^K@J8nXwiiysh}7kY0;39$?a@dl!F35DflQ0LyS^@)?kwTmyN=}9wRl-rykA6 zkI?t`P=_A6>tPy;ke~@Z2t8^FGx^5*3FCCZ_cYGoz}x>U}1J zP@V%$lA|mqE3bo>ues>CSH^+%ihHxZWcl#4WvMy$x&>LyN!5 zggU(@Kj_9P^qs-s(BOEmI2~Ku-}U(2hkN|fr;qsfa6;cTKum@`=PYwrbq&1tcz=IS#j!5q z)f_-FC2e1G?9sMuL2tEf3#C*cb7-ApB5s7A2H9{GBeDm;&|1N0iKEpzb!{SN*eXJp zVgKWJDUuov!ZvS=V4B{}6CPjR@wZ>U;s5;CAMwlQZ{PqNk4HFn!MCSZc%MFdlNXDa zUV~nAYZv3bP(A#qtI1X8I>jh_2h~Tri||(B)S8#RF2rlB<(A}RYhBpVA^%7y%a#;n zk14v3_@wU!&fL;_Zyg|RY5vxefLjL2A1%apP2x&jx%;=IJbRz@d=Q#RP0UrYBw4(? zUhw$%h{wlgC6a;gej?s)@toZ0dpp=C+7ERmXc)XMFm?>Z!r-a-TK0axM)(RoSkQl0pRe8s;C>u z^~wNBXN<&?AT3h%AK@dpg;w3#lB z&AqGcNbfbJz9%PKJmcx>&GIku&2GpK|3m!a4t)-(;;4dVkm(lz%)S)YQ=&9HJw4&; z*GD+#VD#3;qpLA;9fes(HlvJgu13T44H$w5Zc%mC0fcnQRtZZ(RfjREh2pX-=yl9< zjTzd$`Lp*i+`OoH)XYihBlsMKwT%?lM~ma3!KpX+c;DmGeUD?`Kr0|P4dVr0^Dbl^!un;OJnr&^p8fhSXu>tL`q6 zE>$a=!adGKm;LSKf~U6&{_@K={NXSEz@Pu}E53evL2#lG|Lxm*c_@hpecPh%d&KBV z2e@t9Dp8FKy+o%N<5`9^W@mWRI}1M&oU1g}1(@J`B|Ft^OIgGrUC@+Dm%f zS^&StF5P3E?isN6j4|sN_N~;iwN`K)+rEVo-0HI5>N0;%hq&(C*Q4FNL&Gf&xU7FD z_)1y)jdcBp@OB>X%P+s+{q+^6(*ghfZ~uaS{`n^;0$yI8psgwh%eu={WMkHr^*ICw zLQDjX7BLe3_V-`#`O7yvJ-xu_7X9G_r3|cXaesebaCnEq0qW_gk_r*Dk~LdvQ)n1@ zDyho#Q)PnZqo6gp>d=*Icr~TSYqdzjwhXIfT}$2Ra_Hn);~o4|vHevwi_OR50D^+i zGmSoKK_xPKp(2q;GAL0?R3bV=1R#)ToI}9mCOAJ9BRw-CoC7*-q51&ZMHtgU8%f7y zuoRzK(r%;GLP+Wiy3-Nu>45v=Jt7l^%SF;<&u6$WiLtTkFd&L{xozd0IS+P9qRE5D z5C-_B1?z-vV<3zphJj_eoKk)n8k7y`3H?-ze|e%pHLjApq!1J^7y=GQG@m}ge*6GB+=JRyrm)&ds90c3E@BKJrTB(YG@s9Jn5F^I zJAgPb&6mZs$c9`A5Moa2h@KlLk>X+;FMbzNM3#fpIqXGR&SZ`h}A}_(+!Z9OU4X!m(#M|cra*j zXxZ8b*Lu{w2P~4ldC*aW)J4ysID*4!T7~1G#r@p@cc%sqrxu^?#ms257%L`ba8&TD z;Jip6JSQDlnq)-MAP}r>p-cm9JAe$d4zO0i*cRh(E)Rwq#jw~k4G@j!uBQt^h&UYN zVZ2;M#3{I3%6!FiSN!0Nw$Yam4vD;!nRk;Sc})XZ-Q+pYilE;@7WFczu0GYdhQ@ zEjYMJ_Q4p33*OFSid;5`al+^rO%tFK`JlBVqs$m)jayuXk1&2rvalyPs0+sR=qhjZ z3M6CW)!1+yF0d{x_mca*C)e2PF7L@G_7HV@gpRGRUvsFps2;aE?zjGI>-DUk^;?M3 z?|p__(Y|}34O=5j*)ZpLZvbf94yF-<;_J&he);?j!!Y3C{)GShkN=HNA5Mr6{j{+P zs%S&wRfs}uV#=nurjwAC^DyD_=il)8@dd*$funTGwUz^DM&V7#9JrPT4#R+kJAj8m zCdpk*T6Mc>u5Snlxth$PS@spLK7T3=mNYd^&74Wr3yz3Z0y>=5Y2BZy=O7<|@_wV! z=dTx7zrZPKIz4p~{vuff-YcO*Md|o@MCd4sx=i5!6$D?Wz{zkeskunPl5D=$Ai<%M zPerwu(Z(odZzdobh33$ry}QTh!#xgnC(-ea6TAY*Hqd>9cLY`u!4M9|Bf9$&y1o}w zVq^rbpqmyg5zzL)<$_^2LjllPLkrQ;`zZ(#kVOw4A*79%O^C!PZMa(7XqG^vZ1H3! z)TPh^DUooRATm&G5UmAU3$zWqiSQPf`UdTXdo&+Ef)4jU-=k@d&`pbIG~75zYGVj+ zL3HZVG~sf2mvr56fS)e1&PPBS18YrLBi-l`*p+%9MnT~PcHpSMtco$PUX$j7s;<(i zXFPERA8=A@Qw|f03Pi$NuRE=a^}TA4l*xcv^m@}EzR7#Na*3`_0~;}vMSty=1@<^PJU_qU>(@t&gNHtJU|)5GX94u) z$am{~2x=)8vwU5EFEl*qG!rEH$$1;UunX ztu>4_=(+}7-=J?b?hhRvjvYSU-QmzSWi;xUB{YE*CNJoxm}oHax=9?%O5$0yX~9v$ z4U=@QjTm-@VUVDOxM(dS6DIEw6R+ABgY$3^+>y0n zesY2YG`5BFjA3|Bonjyc*&q$lgRIl{r%K0G-6zZp8KCGS0g_I}^Si^J|MD4s_~W1O zhrhqz%eQa%_VS9C*9%_W&S*`8zR@@jBU&q&$Q27Szn zovZ z7Urq`cWq?Z(s%FSn|@@P@T2~VP3hNFCz==C;~(k#XM#d3BU$NO50?pFzI?^6U%oDAG&9terSCj)g zxa0!V=KCfUq9FvZ4~RCI@7O{6DCCRiO99WElSidX*fd5)`z(?=(jt|Sy&;O8ngt<< zBwf)~(i=%DIG5;0q!1_@m1WB6n9(R{aEL6S0ke@wU3!+80L2jvX*6W#>q8P|!z^jO z90Ai=GkIT zY=dA7CZpjyi_rJ*orTj8u{F>iKR|zcfWEs2+8(MsqUjF^iZD)7GBV09pKy@lIEpmn z@`jM$3UUtuO-e>(X86e^qLs*Zaxoe;K?iAKX^6fY8yNw00l8kQOR<@xGveu_WP*-z z|5V1ht;6}PCcu`&Efz?RF^nUA`|=I%mjTwc;5c`P7q7PxV#NCOm&0+=O;=-6p>n9Jlh4*T zpw{OIMWz1C;^z2aQ%96i3UO2G8EFbg)*TGYWTy7I()3`bN4Q z&N=ufoNFIEJS&7K1#eVTVDyyDCXvMO$O_{mI=#kN1RXGp4&FHg?*R6xxbD$3ElAl! z(jatQSB!{6B(e$H;&QnZlSXmg8Y6NI$C!pmM$XzGIN6Asrhy`Z_xE=M9-$C`;3QI= zq!?Ezv5dW|j182SvGc$Ua`AXly4au*U!(^Lb-Lg*ptHC zI!vrJ+Ut$tM^IC1xk|lBiBs^pdf;J+Ns1M4<7__DlvO|;z^iX_4i92mI^r1y_5}vgXnv!YL zSVZj+e1HcdkdP^+z_2_aI)cB1bgvnV!v$ZTU-9+%1&@!97{?2yVZeB~6vKb+SaOPV z;4BxA>|#l7B!)J6rhsu`U2_DP^f~1FEk6$|#<+s1B_MVU=)MQv9WdDrV`DIN8uoNR z`_u1Wk4Na^3DljS+YV7FOy1!<4Vb*bMK1T;Acv0n;?3m~x;ovzI0~ z>B^37DxGU)PC;mTo~l6P5lu2*ZlYFqntwu}$F}km*1cP1@r9fuYu^KJ z7XHF+zxJkGlY>@M!F0_efX^)UcR8qMDF`+*5Po#pxVP?Y1^cZDQnJR==GV<3MOYw6 z73lj)j@rYqrzG7Eao3_8!P2U)lv36ELl78eCdO8GLSWHBMEC9 z<}j7IGipr>M1_}^m&JWm$F=4-cIgs{(I}^;HOcr?3RA@?x_!c_Yf?BxDBSHDcNpq) zu^4fgJT8|JpMU#`Km748_^&_zf?vPA;`z6Gy2qR)(G^$6}v@m9VANhp8N7&e!0^K5VY)zet zIZbJRfGN0LO2r&}m8(YH30^|iR-?N;}JwKlE9gv({bnK{^x(<;GVbd001BW zNkl>p=Y^8@Dq&g#dH@27}KC*X^dn7hfYYckjN6bNuo;f zov3_sgF~kR+xvWfRvQOP=L{Sr^-w9HALJ3((W5ko@Msg#cz(+N%y22F^E4(8(n%>6y6>!7+0y6d5|fs4Qt7%sA;VkXJw=p>!_a=Bm{ zE^=^~B%q~hY`OO`K`j4UcrwXH1Ok*vl8Pn4$mlsptvt_4UCG#%>tZa3!z)93;#Air z=ruC#mI*p0N?JX6Ut?QyI8#o8HrgxHDgjAaB}-H4hDI64VWF$!I4&|0~X z+NQywYZGr)<2((CBdalb2W2dR(`odo#W(>4CMBDOF^JJXk%88&$U>Boj)0ZUFNYD+ zB#B<)Rwrm?w8mhV9ES5HVfPfq^BLazGEUC2jJCClFcxOUFbwJa&x=|F&~zuDG4O5# z$U&(QemVmfV6{T<5n5SjO9;_Jk%13UBHby%2L~5Cybl;%#IIk!;g5g*2mZf5{{w&f z{0*1U!H*N%Wx$!;@TLCi2__ya53VpN$gxObYp=uiq2sIq-U&PIh0oV?Ejy$ zH|vfhxy}SX+uS`iESZ&6WU)v}q}Y03v*` zwI8mTxw(f&AT@PPo~l9ufe3eVvwOe$Eh+GT%|iobO>F*u8R;;XBA`pi_k5x?>Evgq zcqvF(D)>%q^rtw+=R}MA#JKgPe@edc9MQ;#7^0Pv4+t*6acc0Fs5<5IyClN-8qW4P z(djucW1?%MD0J&RT!@Hr= zhHUEut;1kFxS|Q$aL}0w;&VgHP(_aA&8K_3ySan00nO@yyr((GZgYXl%S-Hb8*+i_ z4`|zcj&SCI#AcWp=WT`LP!ZIs~jw2wJFvkj{>b^gD2sI z1q&V_BvB!cyl6j}NLB)HLx+R6a7_bMuj6Dbf(ucrVB$Sj>7ED)?_7LsKrjL4DD{>o zAesWMf`?#a|LLuVgQQf+XbU%(0bSRjmI4(Q*sV6GWTcsd0LeI%kdWSwyxgcSF-D^` z!{{Fz=`x;?8lOXA$17B;2CLNyvZ??^qDsXjT+r~+zzYQ@$$i5`&UvRTn6c3oEfz?D z?DGT*@DSiUfXfP1ol>C#q!QrPAwXqx*ZDDsCqu+Iq8~AFCs#-xbTkxvF5CXJuFpj}H1#Juk9SsAz?tr%2 zqi+w;S`)=1fSMgfe?kZ_-a}ghZ4KZ7<7_OlBW=%kIA&2*3N~0UQ0NYibOpLkBF`c- zO_7c6PNVw|j|>xj3_i>#r%TPhICU;$$K>OQJ5fZVjclB>FmMD9*kCE!B5uK2_fQp0 zoH-}Dma!I+D{wx>$Cqb^i0RGLtlN>g>7(G4oldD7Lkp>k<`Mj3le25I`2(lv@hLI8 z_b3Ydg)=KQmPk50?`bUvaRlltH3ae{H1!-8Gm6ZIk?W;CJDkW%LF*V>|4*D%gPFiD{=&SAgb! zsw0Jf;2a_*U2zuq<`Eq>-lFd{?mvIQ?dM1Q>CZpmKYsdvr&hy3B6zYM{KXI7{b*Tzg{(N7K}Bo(ksc>uYQ_8#FP1WxwC!`T23;0}M7r zmgbW|Ca1vl>yl0ok?3{COpY~ru_)8D%#I+XOM4ba2=A1DI zrLyx;Ire5zOEOrKtvW;SaB*FmI1*PvM(`i?!QShE9EGa?Mdk-rtf)`XodJpH15x(q(Qdoy_jQfX2 zn9!_}yGPm=Hq8q4b_d_o(2SuG6{@RCR2Mt&^$J1N5OoEnBrK@7?goQiYjlIjfk=n0 zMc*9=EV4R+Mm^S*%=a1~K6^T=wAQei(0B@sqG^T|3{o(7FERz`cmg%kmB201bWfqU zr&4lXnut%ToHJte@ik|z95^m~kC0%DU*mx-PA=yRhRL63D6urjobR(f_{Dv8q^hu^ zy?pvRd7&$@$NQ}#(1j(RaUbA=&q=KA4812)M9xt?B;zNTEdUnI{B=Oj@O zCw@Dl#3#iWT;%g1OpWA8C@?CQnTYfb=OIOvH>RZ6S4!oAI?-7&8lO$*2{oj{j68A; z42>e;p>+>ydN2eiF5rUzXT+ftJW)8v)u1;+l)kj3hTN;-BejoJ*PL7HhFV;NSKC$ zW*f4j^s_V1_Nh4YQ(Wd#oA^u3YiaXWZf>bKPXC<{%~SM|ui-17+HX!py1%p^d4xj9 z7hZHi`5J1@+-&Sm4XkGj48fus;mwwS|y1q?A}y4K6MS zxdwo)@6oj_iJ@o7l$>K?qjhRhFuECE0x9yM^=|Ofa%#lhuSyD7b{+65m|zAf0Db6i|M?3(efosk&$npX0|Y0rymdfR(RoPcG$E@jrffpAZX}@12^QC!I7^Gme$25U31N8;S=y`4?ZflEdVYSCQ~6TZH~u}(KI6nG zXPK)^`$3pcE{Q@i-lH)}JtZgdlTKJm`*Qx?h-PQbbL2xzV&CbvL`?7mcRQUooK1eN z++%1Db{SNh7*~X(31rcmJd7!t-cx$$39Zqh$nig8skiiZr#TyqqgLm=& zIi-Fb`VKxME|!lXNA{wU|9tFmn7qa`?Q71@Dfv9nt1&5iF*P&EmQ11aazwF-Og*`i z5byX}`J)D4g2?%RkPgErSQebP!mGLhS9H)=FW@{yXePC~i(@|~s)=h!0J){Oz~H=t z5QN}ZAB8S4!D$-H%=5pU3sI<~CJ0696t&iH&Sl|aD$->f|7xwlm_XC4!MH^4+8ArB z0Kp-ghO=Y|<-H~QJ6Sl#(KTN)x{RO%^HI~j2y)?&mRxjS#Vj* zSfI%n(K>;Eo+?UXOW|B|3o4~lzW=4~b^2PFn7KqN5sJfG3&togqt^yiv&LWy-u?9_Jbr0$ zvD@J9|L{A!`Q{aZHE_WJT)+hKwY9?#T^c-`vqYItGP*1!FIxk-s&RdN32TA3??2+> z%`E`+KnlN}_6NwSLRGE6xP+=2yn6KwnoR@a9r{Cy{eF+W@1Z2mDQ>B`Al`LxFW51? zi8JD~ra~?`IncEVxiF@~l05$DXUPuJdjZECTrBFmAII*pxV{vPt{^#S6cTS+1d&6a zI3plqv)Q0&8tj@C0NNXAvga{G^m`ZvSWRfBNq~yyIe3b5jzQa8tPNUI?m~>Q1|O~I zOl+)0F&Tml;M~D`gV6W!GZSS&$Ek0viT$C&^HYaI z-{Y|FaOhe}*sW{ygG1;e70?2;jOngiAOxBkB8f8Ny(&>n>rJGsh&ZKFl-`)4s0&eG zX*ox{d6hLrsnK;#5iL+qpN$a-gp2tp5S%x(>q-a~gpABfce-gs2KR|<7gW4+m6x4VE)lEfsQ z{7@F!X&7&Mj7}8s2+o zJz8xAaQHx}S@48pGa;jb+(kzhLd}JwD0U{JQGFEXFr>7`R7?Wad3fuout&f!Slm56 z;M47A{QUL~Z*Ok#>Gm@ozC7W}Q;);G#eQh<>hc;P1T;;9?|$(uthM;`=_5F2Xw({& z)M(olpYQLn+BEp~%`b7i+d^;->jEAg9w0c!YO}@7mjk-4#g{K%@aO;d5y5#}US43m zUSqpkW4De6^L7m%Y)19wBA1sunU4?)pa>TjNA7b3-6T=LrAY%X-Q6FEn;8<;?EEPP<7_>iAnDLJ^Ppp-yhfU}xV zsA!v6RSnufgvDs31j4=j>!vVS@>pjLpj_h{Mkso|r zqpBnorGq)*_UCCw6hbPcDDkkMk|e6dSd?M%I*BGh)DOT;o{^E0=wd*YhXR+1C>Svi zCdGAg#<5zhaCv!&SC>~5lRgY+yB=n+uy!m2llQMPWG|b7%Bsj6r({`yK}V;LDB^V9 z!8wZ%Eo!6B1AXQ|DV!pLJ*8Vm93RGJn^6G_2CXdu8^EMM)g18n_(aYQab0&dz!-s2vqiJJ!e+g}YPAJd6}XV7>s54e3K+CSH`vI(_SrF{ z>pJv98=X)(=%ItR8mc0mzfvk^GZ1oZGNq5aoORLQdmuPC$tOWp$suaaEobLypfj|+ zQ*@D~;&Q3zoVsPWnWik{B08BU2#h%m^jdLGiYvGKJzn4Q*4SA0S2MZW@gNX;egbN;j{rN2z_t@{Bh|kyuAV>(I@aD}M{P4ps@Xf0$5+@A)w_8y7sK>*@!^r~ps7d7XY|c4wxd>s$ zDU9bfigWA!rBIodTs4-St+XaiO}y9%HTz4Exu*{hoV3wfIuuTQy|i&Ug_NJ8$dxvZ zOQ?3)5S7+fOB0Cl{^rl_4VqO0XMv}uJ-$31aQo>Fs#)P*{`k-M_BBmd{{7GYfiF*c z9J&tuV9@s()_aK9;8snI?RtaVZj0;74c40`QV&ECke`26q);{YKm2vwn0 z4Yu1YcH2u-O%1Iz4*O>u`UCN|3o4Muh*Z*^peBEJbY0^fA!S7ZM?PAlvJfbI#upTv zSTqx=#K^{t7u16o`<|Vn0!IiGGNO$|Wj%}xkdh8ip(Mqra|WdpcDo&}FD|jF8*mVf zt?l}(F`?*nmZ=-YBNyHw3^2xJDx44&Oi;KMH~|S-Tgn!Pv=K;DN=k zl98uwe01+(bS8KY^qod~=y6zeK;Tf4#OpRtz?gGH$26KyTJId{dIb}8F`O|tO9f=2 zjw&f&yo-}ZifErtdlf=qV^_sMG}8ER=ODZ|%8!sD#MDF{1%Sz5Va&zw08~|BwIUH? z-E6U1?;x56f-5LhqiWW)_m}~_cF>0SA8R>nNsD^pcknst-s^FIsHF6oX=O%s#p1vmu=Cg5agPcM(o z`I%atQ7JXndk+&r7C`2;OeXhdQ05bd=~w{xNxpkZzga3kzvi${JiBDD4ala_^T4fK&D{r|i#8Es*h`o{r!}rJ(8x z&3c9PZinr~1vcADsMQu~rA8I3XBiP;q5^}2kQJmLej#@b(YY`F4hB{USRZ1eA@e9~ zeAqaYqR<2e0i#_`a;##(oQjNO8AhX(k^edL@sO`r-uwh7q(?{J>`9jj3&oHrAXvoxBw|R6e_fbJq~q)r{@Fy z?N2{K366`4EAm?B4%JFw%O&dd3R+wI_2&<;))Nm?)Yxn!0{7S-p0V$G@>1>gSTz;C z{q|eDdi4scRgI=r2;QRYbsjODvr(EiWsI?jtNJ8-=!DP%cp-xK1rhM6#_!ykUqYDY zsKk;p#wkJOxodOI#%XDyHJ?D8o6ybevW^6JCw#}t_g7MXmMr>~Q0h}jjdN6o3M`4P z)iBoM-N#S3{dAA-zyBV8_q*SrsTBU7|MyS0y??-=Bjnmd>&&{^BJ>@=>G>X>H4b}& z=Y5O5zrc5IUgPTO0q`ecFA!;Qv~CijB#MKPF%K_745L7F{Sc6h!<0?|jL_?} zpAObR^g|YUYwIx>vJ_LQLS3yPxQaYe5Xitv7cEve%S69q3Mz!L9zGZ-7a)Ysg3GEV zz(Nm%i1xz(?*XlCM0Ew=eP*ME2(ZZLB|Vr@<50x8$D$>)E~D^$Z}I%x!P>DvVqD?S zbui8&FhTy%{Qz&{&jmUYI2eSAg@Z4214Z(n4IZ5FI8_}@0SFi(IuK*Do)AKGR}m9r zbWGkwv^{i1vTRIGbPhGAX~ORE8qIo(O0B>}g}@Y;sKHc)z$i?n8w>_*^OSpZAvguL0Z_(7=87MM_blx7)NmFY-AjZxEw}Pb#*Phw>Oi;$f`;7jm&XNW#Umz?L{kOFp>c_wb36Nc!FB zij)O!KzMO9eQx}*gn*Z}XXEc4`Iy!ccZeQfhN_a-?RL1ly23ZFU*XNGOT2!y!`1Z# zl%(;N(c}i;qJWSyg#ZbqD#)q=2jBv!!>tP#w1IXWSE~lWk3za>8Y6PiZ4+;>C>pfZ zNOz*~Gl?CM?{!tv>$bX&NVv=gu0Q~Hmi%c073E!fz}?*)etvs{+uM7z zS_24JZ+E!x96>f%YdXO6(7|Z~Z^=`&u2%pT_;h!V5UBuHy8~9u4x&zXonyUT(Fmcz8VE{il!Uh91BByWit?fBReX`)B<5Pe0=BDS)dL zWT>eyb^&G>V7!G092QBW#t8A162=B}gTY0d6yD$8B zgUx1x;5_#G!6MT0XemH7zPp@3I=0c1P^Km?T$Q%ee~&e zF6Ir;TreWE9(|-ej&bqR$*v1gTy6?c7U$63!yB?Kq(oXj+RcK&JDask0RVai=O3Ys z!Fs(#(=_DPY1C#(a(4}$=P?+U#fjFE zxW4auv@N-YSZ5HNg%36sYty1Q71)%s;Ihk1qKPEOoe(%6`4Jj=%BQ(ZL|yPZ`U>sX zd3Hc)h_L8#f$4-iA=aZ_Ca%F^J&pihoFs&RN-Y=I0V9$<*Vr*Xf(!{{gY)owdCxo- zewZ7xXxCRZ>2t~?V^g++kEyWbgmF%*(*C-;e;PB3ZLIeb0Eo`vxUHn*WF-oCoRlQF z%$x2!qrO~#)1UK2w^(vU!x*$1qr_7unUjxBq{WqCDpMO7HU59W8OlH7=^*p5)$xOY z;v7D3SZ{$%jm_(Cu)F>i*WbRu#lo}82X8&rszD`d)QWtlnUDz1LMVpA;}ce^4ZtK^uown|UDbdKfnn&#gB1as1AX6u zF>(Y6fqXC-V^GoSI$dWOJ#($4*l_Ow!97BZMAp^@VP{}X4+M+g zEqdFdZF}6_-r}!+{VP6wxPi46tJMmxFLzKvVlWoFszG-#WY5c?Cl6D`1o?S8hraLe zyl>IAEvyIj-7^M1pfOu0C9qzv32|cr0UmYDuvH2y?7cZQA5xj zT4?8JW68o6YT%XxDo2}WAoaAzD4Zz8KrSpJs^uuFq*=@@ujW5H8RyTQjirAl{%-pI zIi;hte_INcnZLhs6qzD*%Vu*fhA9z*CB$V!zmAS zXJN8WjPD=dg6LDk7bTjJa}L%8uwWyS>n0xJ<>x0io`IT6Hf>13$tmRKZjakfA0T+Z zKmWt;@lXHokFeI_-)=s@I0hks`_K321`X>SIWg%0O%<;#0@kZt78}31-eA4vc=P%i zOsT2T?%PslqZ`T_bZ7`S~z1hP!1IGfuI6OGm?A}hA!hqt? z^HDe*#g+gh1elL&i+hBiW6*8lkc)l8^L^^mjrCSfiswq0fb2dTxxd;9S6Kq60}Mp>4ona8Pwml)Ol3 zNQEOjojHPW2&Ld%fT}BSa0KgNf{E8n5{B#&IKq*JltHoS_|)a zOacvYE-&CMxne1$h)Tl4te{+`yiV*bi`wd(7qd_j!TBi-rvSZk&H^}Deex6(<7bX% zzCgC+#MY7ucFN93g*6kD*D*(w%fjDT3s%<=v^)kS=(?JTNIsj4L|RxCUCGE|j~xYy zaV}_|3H+#0_s#+QID{;P6O!hPY8G#Ow&z=Nfn$uOO({JU&LQv_2m9;(@h>XnPyO87 z(k^!rk#S9`;}~h}lfaNsU_dNT(!=Jx1LLC)b_$6p$B49X*a`3HYtX5=O1BKJ$-={# z3igx*+9`x`9;H71^{hZ(ZXh|XlrvOng{$jVc>U%Vc=h^Qyngi!t}eE?y1c@x z>kC|L*8my>>tYOX591xWZh-9uRI7D%?jRAPM}UU54pr4qS7<5WEI;H{gL4w37&AoA zO9mhS*gX0G>Vr^8@s-$J3X4 z{P^RKxVgE(HS0h)|i)2UtYTXQh0M zNMAw7vG}9+s)(;97&#bthxR~W8Zrtl$L9lQDG+m{vn)PKF4))5KVA}(%p2snom^Se zo}yKhh~&8u-#Kc=(mt}(tk1t*PE$@z#pdoT=X~eqhgmupGEHNW#zlUp2&EOL$ezoL zaWHTwE-ARfg*;8Ga%`}TbOe^yMkpI5AAms3CKoLKeE_gO4EXf%4!57b;PtC3{No>f zk2l|3q3c^HrSQWqzlYHd?{0p=-R&)&_bpZY(I=?47S?HK?{Ii}CX3HXqIz?IAHM$; zE-o(c_U&7I{P+ zA(}~h5nYntJVH!`1GnIw!$sGZ6dj$AIQRhP;&UYm3I%5qbdWIy#Ra&aiD2^HH^xBK zW1%V~g;hDf2fw|A5CY%1fc1Kvix=-Lsz$+!6+$;49B9f)6ITf##xrGK)+X*1Y~r$Gtpytfu&x6W(N2xaqWFoP&x`{C5Z=>u zwH88*`<2VQQwJ|1KnFANKhFCX^D%Xk+$02#Yr=9E&S2yFAiGkV8xUjY^LK8fy(CX; zAp}-6`Epb2JddcVjfMaL+USwmVH^f+Ftk1N(7{?we+==d0idZW)ODRFW+o!$+8F4F zSPz+tJ#w&lK;$pWqy4RH?9(5fTqS(Sc91;qlhm}b{y62(b`k)Ilh1O`9IXNAkD5H6 zvxHM%65_NpeM^mEro;#~(cO%;eK_KAmngBA=~U7hR|U|gBXZOI%;S!ltR=!vJe2zE^1q7BKb; zbW48X&1yr7iklb)01Udvrdh#*{I%Ow)5y_ViqCZxtd?l%I`gU1h_gf)m8$bWQ9dXo zdKx@Egd(cmQz}#P%T9#}yn}T;hVBWE54U*t_OG~k{}zvr&yZ5$^71-+R3G*&4t+PV z222)TN;$~rX&VVY5FA*q6xJ(+5H?vz>%7lVvSrFsDzKc>@jcrprU4vB=5|r)nP23c zz2sHB#N{uG-6<#kya)4=lSR47oqFz1(HqXupyo-C^9J;5?D$U6$4)=d4JcTN;%j3x_3RaBO<$k|PkGP4*)41Ul4eso4kZ_xR!0-{aNw4pvhd9qAbw{P6v^c-{}FB**Rj1A1*@a7;vHxkSBf z@cZBW0auro;KAeD?_Ps3h7TWaar5b(Ft^A%mQtcwk)T&f6`evlwC#R!{nInIUX#cy ziJJ343_`lfWH%xFWPA-z&4d>gJP^vsq7W}ImiP5?$|53d!^IeL&N(!r-^Vz}%a$=p z9*m8V2LS*Tqj>Kj7O{OhU|>CjqR%aq1UjJY2lTzh{?Os->H@n}LxE>ZAaL?ozW;oS zySqC)@An0&CTE~cM53*OP=tJHYXO)kg=y4!B1BYG6vfSCFD(j@1Z*VzQ0eAFXJK6X zyvo+AQc`L%7>~%Si<8;_AsnPE1gW0v4nyQ)vvBPD4gl5-J1;Htv=2%>x`gtC`t$_d; zt@<3S9ms1sk8F`UXqR@L$?qq|d}-5?x!|+nd!j5o;R15(VlX59N9UELF6kWid%Vfz z*A_%uf#tNb(b|hRL8`8Carp{YSKnf@y}+v3Vb!d$+g;+-^&6}!3F9;d-2vXAR|B*& z`0}(z-~yFeK~)XOW{QPN3i2jz2zA_8X(M$+?vH%AwCRKpAf(LW))XL79t2ZYlt>-m z6#{@kkI0MKEA`v+n@1pe-}qYHR_1AKR@lsD?QpDa!w>G z>qm+~LN#~{NU&j~Nyq|e&xch;V#XNO5@`@Z(Ta#2EHE~5jERZJBgMO(EAEy!bn{JV zDc$fTuJuxZU5*%+iqo&*S}&>BPlckK5>d{J{YewOAY?q3e7bb-oU*{1Q)%Yk>zs!O z0l~R=ANhD_rTwH(qmL+1;hqvaJR`qr5mCo9ZR4C`wdZ>W=L}qMNXFq{sc|$0Ry#Z& zdc1r04%U18-5-93-~aYk*sL2oJw3we9;>E;j^pgjW`}?N;~#M7en8vy=ry5l-h0%l zLeo@W6~{N%-{5k00W);?`0)e&^7C65FTi+(rmo`DX+?X?YDM;LU58;9(6)Ox=dfDW z;EnX>*ay{3E@xmT(^8G%5VRZeNo)Lc6NudzH#d-a@hNr=42?|*(i3&w$1+mrxasS!-U zT}%i_z%QAF6mN!4Xdz!)T#p5A$SGM)*fb$F{aQHx6X9NbN>MR&b zDP!e$dVCL_vh5?kX@1~_ql4d#p44*{zb!_L1&w1wx?;B&0MCw9!SiV3Q$-6sWC1L4 z;usIa>5J5wavUC_7@=9Ou-RQ=wcVkvYbZ&m@@})k)$Rgy1@u}*E|f!H9A4AC=1f3V zv2dPrZvxgiNJZ~$7zSMIu26Z0uIs?Tuv#^c64_3V3l)8B8+2WlM=Ik81(O)!^micy zSdXlZm+>LO|3t1Y`Jo z_X+Rby~C&bPiQ-XYIOmrsAt@4*0{QQMZVA0;`#X*UDq8oQiKFnnL08I1FEW;9Oe#g zwm#g1TN}IuTp7FVz++^2qLJhS6(gcVg8+|U42d7D11bj}4?iUZLOw{xHL2nmGH*l^ z9j4~vGby77cL2lCX=-?$4`9((mxPQ|bkwQ_mm*I%5+8X^KlJHb0>A@@6jj_$TwGto z>*VpkPm~*?O2mC8KO1aI6MVVuvg;#3n37!gUyY3 zKyUg9SR_vDLqZ7DszN}3H6ET>1W|#rn&ugvBIFS)7+loZcv#cNGtW~q>jgLhoE>0v zkG?&C1+otmvH=qnzyRkRbWe20{b7&i{WJRZKw&a{3u}9#^a%+e2*DPd&I;pfOySh% zwShLaK(2`%l6=ZTpy_N?Rj6x~pYa3)3QPwz zHEpM94Lj*{#`wHQc4t8n!TH3MWDa+~!Oa?=verw@@>g)MUv>~Ui(-d!X^uP- z+WBu22^WjJ$uBN0a%Z{Q?Q+7^YPHVji`yK^ihtMY<;9ZP^@s63UVNzDiLifDJX?U)Pyq` zg>MD2!va_=0u#l-S`E%5-haBq&4)X@dGiMU?Z5sJSJ!KNdAtR)M1xC0xPBNQV#Av> z6I6hvLq8-KmG&?z&})bH?{Dzw{xcvdtS>h3j+*W5c8jYk3RN-2;OXfJ&(F`Wmi&>0 zWZ-4oyAN5nF${Y2K=)y?*Oe|)$5TT~ws4##KmrUr-FGlbZ9|}fIyh=>10yGbK)^)s z7Ty^MS&>(^lL$fpVs@w+3tkl5<+C8AAbD|mzj2q4jDvFuqA>xP{t+UOl!{<$Y!q|* zj3Um9>~bO{xJpV|8tDrO!Q=G{oGj5KNI2?!6c&aok}MI}(k3p^Ge(C8H|5x}K&ApS z4F-~s*Nd2w5a2S6FN!P&J$t_VBxuIQBwr;Y!fJ(}6nF*jYK=y6uwcL=cp*8+Pn!Wc zin{r_0pMv8l+a+?!)giLA228h&PWXJy$6_q=MvU<7;DfS26Tr#+Wj-pLxv7U_u%jl zQpDoALLHMW$z_BlJ-w#p*bF*zuZ`AmJ&#DORCDg`bSjo9ut`WtkKe@3ak_sVPclnE zc6o+PfCo>mQ}c=BeBwTLi<{F=1lWS$FnksLFknj0o6{O67M$^OmFv_w2OlS0rSNd> z@R7Zz3l4VaHbVfLz%fJ6FIoyFT8I$iJxp~{DW)$08_EjtN9T10Y^)`lzH^20*G8Uy z4UhDQ65<&c7bI1QN@9ALDCgaWBz{4*a%-9f-Jzw|bh))T>uI~pC8tHk=btV58>T;g ziKFewh9+*gy zeTLyaZ*bmI>Xg<4oYvUXtI4=FS??HU<3>Pys){q*J$xn}spN2JLGlWcb687=^)L(+ zGc47JDlvxbb_cC>9OuY<_*9jQV_O5x9K6-&4tp3gz&VGHA3x&fpMS>B@86-@KSKzC z?PirnS6$cR(6xl_E3)V+-5=8ROv?SGIMl=eM~QBSQxuDk9SG8-ql|ec^kDQJ^^q@{ zM!Tn;mnCF+DPDUCL7sQ&rwaCS-qTBhVeUe5u5tKU z^gew}TOB#eH5dem+^okzAJBCj_H9>Kb2$uJXDXLRfD%H;JedDG6pBT+ots0vjD5=8M8{`BYn4_(*cpZ=Hsg1`OkuTd$6e!qvX3}8MBa?-w< zTq@`}kg&!8MT1w@Y7>K;0(RRicDu{Sx0cxN_jrDOMAvn> zNbuex*iaJv7c*4;4B+L&kuK^{ae>EJ89SiA14Y32|GU$GQ(F073pyz1}(Us6HFqBBn8<5`{QX$3ts71t08pdRxR|LSzW@eEpw;>J{1m(SB& zdp9qtOV_1S`|_zX<(!qVgU=S6bD-s%4kul+v2Ye=ZB)nC7TKDxq^QgrfVqfwUU>7= z!uWvT{Qn;pk@E-b*F<3+jRjnYT)U}AgElN=jRv%Xxlxyc8^V6!RZRt z3>f+Y9-jseodFXJ&fBa+r}RYfQmre6VK8`pJ`h@7?;r$^ z5yuK$yN6N=U%q_7dcDDJw?o%;&|0HuB8M9SeWxK6iJqFq<8U~DbBVfE;7-Fi1Hn9k zY4PFhPk8(GE#AL>kG5^0y~B39gN)-l#u)t$Yhp5F$VrcRV@f?z6gU}U;2EYI{&YX4 z{Zvje9VZwDf-A7VCnJ1-k#(RAMb<>*%kz>i?_T5wFBN{JQ$X46&kOEzLdPXUd?)<09j1&; zykj4q2Gq5{AOGne@SETM5>_8@c(#ySAvgvm$#p@d5Rf=QGtR*UhDyjN6sN?$q_#gC zIvn;b{`&T3^h1DW5`zO&wZdk#!dlg+RYe~2U5DrA=V-^tCYD3en^%ABOwHo5Ex?dAQ>l=adJ<|-Gb~}N3_j>LLTBADtbawY&bXp41rU+AsnaT zni)tg!G(o$lBP}x;Yuz;NPJHcNv5JVSPSC=c<_*35}HijG9=K9Clm3k4A-2-JCHPqakDk?tDH685`XfwC*591t|cnHKjC0nu4_!wQ90&GY^D}X9_n0 zn2n7WJATd-7hsi)#T?y-(ms~1z0AlZ^Pc$ZU+VxIoja;Q_Lt><0|mL0ccwN(bzpDIlin2)Pa+ zpjIMMI%>%1dXXqiX&R6`v#H3|u(9B#&^8Yo6`@lhx-kZD$KJ|GgOT?#;j(6I{+!HB z7|K05qo`73N0LQQk&{~p+3LIoV5wZc=4EGuc=9@npV4n9E|coIs{? zu0*Z1Gf;6lR3hB->A-Oz%nLdypU`1SJHU~`C>Gu0q?B0$P=1bi>To`foX_;#N{}0m zEYYEpB#{N~=qY!C`D=Mb#Ubr5E_zXU0HbdvI74s(+A$c<;XQ*7(O!>}>x1GO)N+IM zY713yz-o#j6||cL0E}~lc(Fnf3PrIe6X$6P(lHo zJU^eDM%(UTt%eXAwCw?3o}ZwU!lv3n+W|xSgn)o`a}8$$^x$B%g|7^RU^wUl9>09X zq3wJ#;r9 zZ~@0Wn5xi7D$=~SBoMO}0t|vHn235?Cc$L@>;Xcq0M5|116J!AK3aqw_D}HM;aA^% zgFpW9kGQiiaEM9~7uQ-ymBdaJ5G3tq8Md*DhxOd8 zB_VK3r z1v7vr_YNNb513>R$U*KdQem~)pxN$lb#;YrU%kfllBn zgF)N2X!m{A^%!SSDT$`3QAtG^6N-Qv?~m|g(*OV<07*naQ~+mz!5FkXi5azb7zT<{ zCt$@z`ciB#!HFuvMxchCMF-A3nDPi-BUr$3(qK@*D58Lm`0q+hHC9SdJ>r}P6GWR$ zyliq)Bfoba0=SjLqvr* zN1}Gf%%M&}1tC~8O#^s`Z(hB|kAL|qDybml3RP86npqrcuhw;5SX9&q7&8!3%@kIv zH6&;F{BR3v25dGp5C+_Q_=NZG-{aHGdwlx%0gs>WG3XvjRumvmub_25dzi%pyJ96i34ue|i$%FVCj>n(*7EC~?jRGOtV zU;gfLJX!|CDmaBzNI=03^u>smU{EO~Y>q3-2pN@-i;#!HrOiD!A(6KeH*=+Slt z0TRX;)Xf@i-h79^*W^AkSacns8Qr0W(LK6;k5{j*@O*fJ^A@$D1i4;2h^oSKdq4%i zcn78fgcL+60WkDER_k4!ury5rAfRpcKyY|{eU1PAzyCLERtlAjK~Ox=l6a;h%gvn=BY)+-2@@a&02Px<3ldSlU;;w^_WN_@7)#N~jeQYfhGSJTMXsCS;j>~&U z#P1csfk$10k^+Ns#y17X z#QeO9O>VmXXB&F}AxJRE^0iWmMCisCSmzLeh~YUB;A~NU7hSZ{W? zyu8N6#RazO4Vp@V1q$C`%#QS(xbIjU-L2r@V}ret4XT<1iApN)2%02>KUweP|2KV+ z0%;5M8kw#`w5IXAPWxS^QDL@c$#`$#G>Lmploh42*mSaIvLs%df`gn%fcph|;nQ@% zvJgIH(>kwH%Fj06gC~*Xi)SBlQ9rJb`FZ0{(o(Y1Q#1&e|9+}fPKULXjy-cADX-z= z+H^!SoBDLmCvI~pNe(tFMETa*ucL^Z3QSoFjF|r;SPDo8In6Qq3C}FPdEL$CrxhB_t;CbCZ&MD%u$f z{Le5WYtPhq|H>g$-m|ICzUeJ2(%l zn(<&)Y+P7Ma!A2wG``6CtJQ%0eh(o8 zHk%FH0N8#&>kazu5y2Zg+AsL@=>~uK@kiX>J>u!hBh1i&v4Gufho)XZJ3B$GPl*7R zrYRw~sqplO!Z5DM^q?-SpHm*u=jazlQReCWb9VB%nhRY|t+#oXKX>Uk#eJUJXC0?d zoqqkL&sToNBr;i|nUv`EQsa;gq$Nt(T$#P(Xk!zyCchb{h!6(eC#}s0d91>RMsFUZd}OR53A?*72x2NNH!Bb5wPMecR#BKmG+b zw|C&YAsvKJ@YbWQ8*H~*qF~J;!OMHOX;$b0{VwlZoRTFz@Q8-d)y(7@#mF=cYBG6|#8Ks|qFngQo&mN(rOm)RYlBQZNP^A|(MHojv5{ zgbrhYz&Pa_IKV(a$^hX5oDh)C!3hB$16k}~r<5&EZXBanlB_&aG&2y$5-%1`){l-H zC^)2?^GN3)o-Xs#b0s$}4B&!izkae3ljF7ZW5J!#&fviJrWhT!a*m7+Ao`LdP93tSrYOw#5@I+; zr6=0Rxk98YvJo)GV#m<~y$)Yo@P2`$UoIZODB!{u7E8(U&GZ9w1swK!Fjxp?AX&h= z64*8?kUt2GmrMY(_1R|5Ifr2wP&b?CV?8RIoz-Y+h0S`6t~=o4-F>v%3RxJK9#*Y2 zjCPS5&#|u8XrEhbnhiJy1~bIboPrPr??3z%KmGI*ZfSV}?iD$ur{C;($)Y$r1wkl0(NStGmqODw-+JmfbSS;&FapEfw=~3dz#v zE5mh4QO%rNeQuI+iY7L1FiT`(?kzq4{&`TqJidI1qx(|xP@)M-KtQ<(rtcpHgZ;k6 z^YZ~AG%(g;yM2Y#c85Vbbc2C54o~+F=q){G+gjltfB$Rz?ce+gtIZmLRrq-KjF0#C z;ELn7zxf_-zIg>}Ej~X!;qLAZN&y=58(8?Wfv$ba_XDl z*mMkLlGvsPWRn=A9jqZks#zc`IK@x;4iPBo6L`syrmY4nH2iwd4i2fnJ_ijhh7julk0(G@PE+rTQigJee$tl*=8rhfxU__P@LUj{r zEsh%54n&e7t^1=)@hh3eB9bkdV-WPc-bLrQOX-Y+_~QVlE(%gPAGF)4oa`4R-uDX^ z(k2^hs~X;0MSh!R6~3KmYU-JbC;Gn{|bzX`!{n z>CtgQBx)TJ$THb8h3xp```ycaF?Cx=5=PB%h0Idt?s|DcQ-O|2=xyxgF_}uj9Pzgk zH^#_2Lql_xRp#d>h~Yt?%H& z5ANgq?m6CEt?;u?U%*&kjT8L+fBG>#d-4MR+yDB%;IIDfukn+g`~-{Z*T^!D2d5Lv zvfskTU;jG(?Z5s*y!YOF_&@&7Kg0E6nKlROG~Rvi4u1a!zk{P`j`hs~vv~>KHdt>r zse?#`vjS68C=`ACB!0(J%5nWY;L#a{<+89`;J4JSk3C1mlq+NJLB=K0! z-~jlLRLkH)+8__!mQc(%hdiV~W{iP3AS(-$QlhmQx@o`z54$xQMshNIT1(PH04_}J zoFScg)Lf>nS1Oz(5iU3fkAV`*!*Gtw7^qG$*gfp-?p4yw@`S7asBelRrY85NfnpG9A{bASBjapu?d*=pciPr01eXvI zrYxpVOhE+=voRWVV^9!Gv(;}XtN z)Vs(sh)e@I+_QrTGV`6}=n%;sW7(B)Xp}+IG}QcQ8`w}>?VlZS`= zl>BG0H>q^a!deMr9#T>l-&h;gstgh|-GY_yoI!x7H&L20)^Lc$?QN#>vESdr5chm* zY)^_uMn<0w%3Z05hu_Nq*{_*m1Ct-zhq`-7uX)3E>7IuOSVIcca2nnHEHaU&_tC#b z`>5FN_vsed!)a@`7LbR=(Es0%djk>kUgvAjC3e(7@E{6@wUkb1oKMn_cpBDPW3}C2 zxwu3rbHF)R;{(;AfHP)q?EE&YVA5i2sHV0tY zphK7R-!{Shcf}M^$GaOz8w;Xgf}ge2>E~R7F<@J3lb8X!G97-LGgxm|@G%U;8GtdgO@*=$ z(5k^=afPc_Pw@KnODq=Gc=h@PmN#o?Z7`kAaqsS3IHRCc18aB5P+Uq_>!Gz8m1%Sr z_#N9CdtKBahqL=RbWfh?A?z-`9j(=E1fAhwOJEm1(=&SF9r#zYA4 z0IU)y%M4bvcy@IK=N#_dyN6nD;PeK+@$28j|MWlnOH8N0_2Laa|KcUqTVQrF$Jfg# zHotg|<@Fof90}aLdlx_d`KNgG>NS4&JHLUCzIGRPjtan8Jbv^A&M)rb;lqbGKRdy4 zwSeS+G7Y}-&2Qq@zw=F8+&RH^wS)+VQ)et@$4Bsn4!!b54&A$eiM3{t@tx~Sm6;KiUo5{(IGse1}e z<~KMGZ8a)YW7$;L7zH+&;G>VfjtB3(i>0DK9HSi?)uO5@thQS$S1Y=vmQrIQhS7Tu zZX{GFey6j73VgTgZjp3^_12P%_d8i>9TEbf`^-i{jJGra2+})*01fT~x{aB^`XCZ5 zrMH(cyT{;-&to)brO#ndm~bFbBo4{bvP|v_$6Ua{AH;v|eoul6I;dnkg9SroXfmM# zNu_QKJQ~bPDlS95SCSM60a#ebMx(V3jsuo)Xse(VsCfkr#|6B1&;gMvWsXc*a86i1 zlY-*HI>K3+#84rvQMY7lY?=mDRiUmcsHTQh^bA_7Zmioxibmu*Xvn-kGtoHEM_ePO*)1<|IQ*EJ|7FM@#-eG=xgza** zr(x|ELHj1gUa>_@=fsReXGAx~DIRKk=)ZO9GVnm|h}~*GNG{{t_uA_*>u3BS;qZ3X zk+AS2od{!1ZymH?;LL-=quy+>gvE4HfO!`dM0#yZIAoT?Ln05?R-2aoOgPAJK^IAf zuTQ5_GBj$9y5549Gc1hsK&Q&L&;c{X+E60y8Wutu|P;%d{wFS+-|n z7=q+)>xy&64>CT7$fHAS=U+8}aaaiN8)n&PaUP4{c=|pR^fLT=hqTmt&g#zh8g{RT z9f$7tZcHP7$hb8$hIWhW?q@IMF0NZh2EinxWZ)u$F%HTav~`WTZLqqz0pOvUC7QOv z(Ny9O{`tQ|mKAvN^h^BYlb_?&s~Sukqf#2mv^bkj@q_PtfWP>Q{~Q1N|NKAV@v~R> zC;#O4G06<-#Y-&R3E&(yn+I%#2CAQld*Vos$zFOdBy+K{IsB6-pZ|hBx4$%5g zq=RG(!!X7`cgD-2XXN6$b&RtlCvfm!mIYiO4@s3A*2_JQ5baGO?MqQ^7AKFlg+C>2 zd#6jsL(ow)(e-|o?e9f~^}E&Jkl?q z#ym~w>pVautR3AGZ#!UgUndpbd;|}>kD$G6pG;Be9T}E$4)Ryh>AbbT?tz2%itPOn zc`zO^q>d;RXD*l>srVxXA=`aj5l$`>0?XAVu@lFVf)0hd245 z6MfI{5ILbiXE=819+Pnl^^RF5aH!i|^}*RO#sNKqzZ-J254{(y^!y^(TDHjcfR+VxO;Je?RE>*Y(p2>K!}`J(o#aHz~xmMvYe3aHl(<=Eir~w(_*u( zF)3#_K0QNKHF)~fb1bfxxO4Fiw4vm^yqtoA!Z0Rfjxx`nlp=E_WAK)`dhsygox^Im zfYus$o?~&d!qL$Y=JPp@kB>2#Oz9b4udrI(V7*ylv)Q0+TkzmNu&(W|XApZ~TQbX% zW;=GZoU`Cs!8?PQ%t?Fg=`dYz4r46Zwt+7={_$`94!-+)zm3`5bBM`=7~|UFa=QWx z1$GSQ$g&LQ7pJ&$_Y4*uMM#*{$|fClT`An$+~8)l!Fs#Ga=FCipBg+afMun{j1h2Mjv0krnwYb5}a!qm|#*v9gDdNG9 z>*=0vYBX&_8f>MYjHX{PU`8nz-KK(izo@e5v+V{wrHMvB54Mf&QDS1DybI#tX+M`< zB8#2zAj?%=bx2|i27usMGS4595DujqW5&VTJae&5?(RPxj>tP5?YRqP;nchwAoJq+ zcFbf+a<**m9vhorj_qMQlhAFmHz^zL1EV1^(Ln4EB`5C}>cjn}J0%+1yEx~N2&9Ak z7toK^92S3v#@#V&CBox-ZyF5nlEw($0nUJjQLWMz4uJL=Z9uaTo3cS6Gt@js>sl~o zAtg{`1$0{i(!<%d2kY;R6YMUY)}{h_mwwbuXGGA9%aGn>tc4dm=$h#DF)kpugmIKO zDSLr1!6*|KA6PhRI>;~w=lX@vE;5zD>i+26b$P$mfyXG~PJw2X1LqFPTKLw2i78gA z70L`KPL9awPee>GXn1X5RSVrV$fbbH8R`%Q!G(Y|3c1XX&1unFH!Z*=xMy%+Xq-Xe zEwNyQKof`~k~_S3`3%pVeueFJgT>`F>beHcB+kxGFr7}}y~ldJ47%z_q3D|^qPYO@ zu+|0g%y{>-D--D%bp{8Ty#h7hyQGi@F>l>b&uwywZqaG{j-tSL;Ah4ME|{{$q!!)( z)>`kqzeEQZ@TdWV$oM90>aqJ0yJok=k$3TgV}{4>xU;*kM9rj3Aq7aq^)PIqyHG|x zXuM|K&frix+WmV&9AKAV0w68YS&@ehtfi5?M+hS_P)a9+U6E6~GQ7ohv%-3HjnmUp zOv>{_;b@u$n{|y}{^I92Jw3%{Lm?{{#}4<;3f#YU3?UdEfA$ITsl>-0e;r@{=12H% zfBR$1kIzsP1unN5S8GC5&Wj1Y_{FFA|5XT3_#Y zx87kkpI|o6aB=sD?yGAPDEPg?`tP-eX$+WTXw??$s>Ykk1b60>-Jotr8e&wPis0A)=;?yJPuDH3ixFj*=XsJh zAX1AWUpgdQGH{4Mwb6!V`pz}@)Rc(LR+4tay_}|jW2jpenA{L#+GVLZI@~j(1XYeUNv(GPLu$}kXHxykIp61C z4?A#ziGwZjVLN_oOx^kT$N=LRtRu~}wf$nz57HdHv1yE*=Q&g>;fx6nEZw}y>$FgJ z^*Vc`gn=-$-4IqwzeBl59AOJ~3K~#c4f_J;v)JF)2c_b6XK9`u0W8JxA zyxZ?W?-t2kXOB@QAO>$+r&F>Q72Ph~tUk(Y!U@`1z^E2YBhj`6v@Xd-?kwOeATl^_ zV61{REsV|JwgDaFJ({LTx=SHwVUCH6MKPgMmo)%$XjO}9v%!mJPqADsQB@mUUB1T6 z%?)Wh!SL?8?;z?`EHS6AM*1ETv=hC(H`(u|wDTQzI zCd97|DIG)o*Dy@wkep-e`*#gfLkDv-!1-yo07%fV8;@)mdQ+{NtZ2#+6sg-4H`;^gEEMLAEONm-USzqo_z z%PXvw3*=H@b~;BcI5zc`@O!f%)id&^=aWDN*;{{X6*Rqpv|Lix)3m;HN)* zjWVZAzAPqzT9V`by$ck%#KoO6aL&-SG>%`bc#jcl4H;k=0M#ng+lmVI6e8i^yg+Se zT|3GIR?7_@K70rN>fin=eEYlK!qsMltHmYSR)Y!Bu4hF-scM`9o~(hKNz&6gyT|#B zT}v7C>4}eTN*KHQOp2mFCM8aekHO!22+lda9nH4z*lueyO@o`OYc%T`+wB(5U%y6G zRah(*Xj|%#ZZ;bjL&dY>3}&lBY&Y@1Rq~Y#Fqw=2g24wOiuVpiYdF`!TNezG45o8n zrhUQoIlqiZxcy?&I5G9{OIoFUVWVPuOf#J`9w7g&f3_G*3 zW1Oa~o#~V{1}`-71*(173CzxS{TP+tq#vFr3!LEGAi4_6Xs&a9oM== z#sv&^2N%g01-Li^@T_O3+=BqTMTgzZjW{H!Ox4oJ9yavYz>iZx_9VA_p8z&YuRi3@ z8GbL`F$NC-0kJ?H?!h}#X4vNvJ%?bMFUye7mcdxn>&B6oeLU<1 zJxA{@<;W+{TfkDFKXT(eSvO0j%>5$8rUH0Op3v3$?1H+x#pJ$ua~K{FX&$tS(i%gH zMu>d%jyidah$0LW?Q880rk}+QSEr+?wT5X)8?8ZIowm`aHX8^A2w~u@#q+P8;PIDV zV7*>rxm;kqUL((QJb3T`lgT7R)V63_1!Ek9$RGsU>)PJNw3L$fjIz522#Ilg=mCtV zJb1j-RsH`*9(9N*JtlD(c0tA#tFbVZL+>m8FOKBnL3AivNg)`67~1aUF^sVt5hD4(ItI!JJY+*QloA+mP?jZr@Vmc_Cr_T>$&)9j>n-lyy-NqgJcrd9PoBNT&8ouJf9;#N|KK6Y z*%^xYJu2uJgEbr6tVlZGpzz)Y@55P+tE(&2+X}z<>5uTqPyQBJX7TU-^pEfx|M(ja z+@RWQ0P9e-E1CvypqNck@+I?u0>n9utc}5BGQng*2iECy0;>%sM|Z%uz<>TPe}mVr zu5fm77cwh?PSGRd8Nf*DvED2oH~?oM;czma!P=UNM+pd)p)7M89UZ}YkG5@*O9ok% zI66AU>({TbxO#Tv083WIRha%HkF1H49Xg8>J9$j4}OS0{nI~&kiZwOo&qk&q&S1{ zSvY7>VxTpo@vMhHpp{xK8@5Oo-3V69!$j8Q+ z3y2w)IZWanVJxfw7*nCkoPl#dI#AeBk|4TK8phBAGu$h8_W<6S`7l;Q4rLr&ga6pI z+chg$!a$CG{|*vvn9#TnwBS7s`R-YG``#W+mgsQb>9DaQr9|S|nD6Ip&1X5LWyB6` zIbMACiUQv$8uyvDR3wv2*f_v@u^VrB)+wZYS|~`Tg!J`pWV2utMJ#3Lh6xXz8H&TU zvRBXyQ@Mr(wsQ`(YSMx>96>uz8tC2WjqS{kfvwHCg!g*nr0Zyd^z7CyY5#iKaAMjQ z`5!8IM#IndvYn#sKa{;?`SfhbqlQ}oHHoPDLLB1h9|@5Nhw9eb=#oY ztZ{XDiAhnQt(JK7=yR-=3#hum_4PFvV|f4JyEr*Hf#)n~;;h~8#L|1{cYw#btYf&k zp|kgGK}UxSjt3VF_=5%Tn8|V<%jEXh&qE#DA?)6m-Yl7D1`CXHE+wROUDrbcVeAx- zEe3}o*>~?vz`6dIdT9KNp(eNSu7_bU-HA@uRNCbYcklCVhi#}4kNVB-HHz$JipOTX z=Q?V|BL`k7g%3Y?7w_D^i?(g?@Zm%J=tn=o<1e2Aj__P>E?;4Kbd0OT4Zi)I?_n}M z#+{2hsOtuA-YC3&y@7SqnflAW{7YuzK8$*-~BPp&yKNPTw}A@ z(7NFOnf3MQv74I64Z)09;(*iCqMZFRbz2+@4e8t0EA>PriE%W zAv0Bj_a8pMgLm%Z(dVC`+T7rHnqfXIFquq9E)hbcq+rn6pe!Y6rr&mlrww3Im*nsc)$CGra?Yhk2>ZtK9?B`t1|am*%1c<0_Z zk>%{tjhi6@d^`U8Mw6#k9t~gn3nhHv{ zuxe*oWJ68!f&Dv91%?GSgP_j2+{xdpqfT{15L1!AN$6t_-wVoe3@9=Q7P39832nH9 zg9W?*JVL&O*f*zhKk}Nx|KZU?=XHz6y}gp*pw@do=xv|sb|@@PFh1&U>$3APkcW&l z=*Dq_E(KE^@+mPMGz)&b6TOor`raOsGC2J3_4Ypl*_UW^-hl5$4YPwS@UAHQ?FDw| zl6g+>f4jr-Irx4zINTW4P#8>}=kU(JCqxR(B6HR z$vJFIa+$}mb@!CH`}eN1+rvA%*U^t@Pc9T}x1n@m_jp)n4GZkC0?9c?pOYctNNzKD z!NU78sGF8HlF-p%Ou-02(aB1n31clGTIv7BkR5E8T1aB>khFy$FPiJ|Mb=!c=-I@ zNj^;kfLnu34#^BDQ0$Qgt0Kg1NeQIjp}5CL}7 zk?vukyJ>beh2eV`cE^WlkKF}0{(CHbqDiv*I=jXDFv&9HbEV(soI^W1dLW9=c-uC( zxw*k)GQru|8NT}J3C_+=aDIM{)oO*0UcSaBKl>D`#S2_rukiDqegY4Pci;UQtnpZ^ z7C}Qv)SdOs5>7Rc8DLC{fBxV7Hh%Z_zK_$BIh<}`t;TFJhiWYt&%lLB*Ewnlqh6SE zj_r1v)`8R0(-bQ{o6hm-Ewj*sAhTYcQ$gLfEn2IP%Nc~o!7~P#aonAs;{47LI44Sn(+=CFhHEEksm z90cbOOr|L7x~`LKs(XLbb)B@$QOe}Ch1D7sz|qMGmdhpDwoQe0)6_d%Xz&`i@Eqj1 z4Ad*?&>OWQDRj+*E|?e{w`f%ZYkZJZ@h}mh22sWtrsV|3^Hbb8JAt+LfzGrkCTdny zgQ}@fH7!=_EiNxFaecGIdR1e!T4A%VGIMayJm!O7S@{n$-1}4VZ4y;PC8@fI8xRULNU;TcGnf@dGX%u5-bO1_u)M=G~$o#=jro{ zd!;{oorXVWI3>QVfhxyhqI(;<8%F@84psQN=R5szw@~rU!8-=)0qZPW&6e#loQVPh9px!v0 z^jAtLG;P~Sa589(4cf<@R?C{MMytEYI||n6DTrM7?yp zExL%y z>Z&n^uU=f?`uZAHX`G&(;_kf*IP0+r(e;c8n2x+927UCkUc9H_8#Ce^I`!U86dAdX zu|rdNcnE*H6lC~44r!>z5O!mzz(XhJp)PGqw$WYC#x|h%+J-U4-Fqk=I){4ip)3W=y^kzZMIlLS`xGD*m}V&tX;DlgA9Z zQZvXpjC_3Xb7Re_3l24>sGurP17KkIdm{eS5MQX8_8wgm)I4(;_xNhdc97QfbF)% z`S~g8x<*x1=`acaWjTe&GU&F2x0K)*gFaluS7H}@VvGue3u?;Limt(YGED}ocpchs z4;4j$TD9S`1*FJ2hFl|;!sctgVOZ=wc8~!I&ILl zHB{T8X)5TphSn-cuzYOr4fgQc|JQGbWLbu?C`k^PNeH(yz*`dzC0v9!wI1O6agWZ1k(snZ^#`*qrbW8k27qX9lUkCNDv_ui(#P6hUmY>>KN zQHktuYj8`_U)v6!v)kc@pj*ZV!-exf`r*Q+9bw%(nV%vTTWbTxBNtokPGcd$)?0)a zS8@(VO;#Ka7Da(Pb13ryv&j@?S)$Cd4%SUWyIq$$c0;-tJ7o>pRtMH=jas#68#?{Q zQCNJbc-TD7>ky2SPMHSXNGz=IDyMAInLRg-Xvo-;UW zdamFs>rhw*=Cv`s@vo`_J5<1qb$ol=>+ZK>0N-2q4{M~yUSs$98GAot2Z&)(;i2Ms zESO_>??f`kp`SBc5cb^EoheoPK0~%>>`3(&9DYzIKI}-x0)Rn z9d;(cAz*xqR%R`}X`50K{^+tm`2$pp*g8jN|Y*4to&;xOJqFxexs zbUWz2@HUbJ z1lH><0AM-8FSU8ns(DFp})U9GA6+M(feX$0|o^i8@lt+{!gV=|c#u_?#` zqM8dIgl4*+;;p`8hTp6`O1VhpzjSe9d}8q_ySEEY?=c=ZO$ko}P5 zB~DIGAh^THDHY)#efCECoy+22#py?a*xs?Iy)+RDME#$M%A94&iyb`-8A7$ljGw21C#k(}FhP`E-WaWP&2l51bE0 zap!&QQVOZqZkh%bwAnT7E_|VCYHYU^bxbNUnKg9_t2K<@Ii;QRV41&FcRf5S?}`VW z#y?$2z;NV43nPPe0Mk0)e-Oa>42$K8dgx5RN)H(hOfsj9aT4^_Qc6sxQ!qHRb%Qsr zpW~OG{v6I&yn6KtJma`?c7{85?m#jT7HxxVQzOfYfRM5%iXx0Qt3;ZJhmS-?2w?!9Cc?`)nCILBwp-UZK(mIh{!S^4qVd`3pyzPEQV-l%DAphY*JS;@Vc+iKs@m<2l zuwWnSu*V{2*!jM#a}oc1Ebb!Ws7pYJn`$hM#>TzFz?k?Ny88O=wd|TE#}@Fe1~k6@ zc=+ui9phLw8s?H|hWCs0U8e`(P|OpjHnNY;&Iqmd^5t_(r&CNOlcbeyH(LnNz*>VV z@tV5KCfv{YJcTLz`Jex1eE8vq`0jVVjqAlLw7SLpI~Qo1D&W#Wh?Ni8z0h=s=I>o- zkHBfZtkzp(QeaY+fM?ijHmOL`S_96asw&K8GcpZ240xY0#DXB+3)S^1-3yJUu0BN!w`2%h-N1W~lcOUjrLbPFQ4|Fg zE7l-)8JGlaZf+7EylEP6NivtZuG7zwQlil$F(e&+g`?@t(Am8gyZ4$>yF}SqkqIsu z|FW`x=PVq^7C1RM={;kaD4}?}L+%Nnt(%>!N+9i74uA==xuPf_GY;iEo;-bqCr`d2 z?5W5gWrjjd({xuzq9trLbS>}QyNC1BGu*qlgHM0?Ws;Dzp&i=wWyB^Cr3m-eMxJOF zK7gyD#+$mt+8UHaUxwD@^AnY-g*Ch4IqvmCb7g-W*y*~3$Y6a#pG8(+E~t41@3Gl# z!MN<)Q!Z(5$zV_V>R8P+vUU#fjapGd&hNzB{0eao&B3b&pgz`dW5yLLLDe^!E53hLG-Awg+J7 zzBb!2J$KW-Q-K{Hxyn%TZaJK*^ogR>mgF&HP%Dg!PgbP)Z+bHMDz zFQ#n(t6{W;)eeG@=FNvg02jn6ElNryi(0VbIhknYWsd1|in7QsEeqsDmTq>!dG!s1 z@%=^DemsrG4ZbxtnIn`^ST)3fuIn1B%5*Ko!Ja{?cYeC~DlxY%j8dk;cn9}g%h zsVlkDE;$Fl5b=X)4bK3kI1Ds6(~yNnWgE9q<~}wtHlxkaJ{&~ zlP6EmD23}cS2#O6!|Cx!DzJ>z@NnS5Lu4{V$>zC4th-W2O_2mi1btTGT85jM@lGcb zos_6>613RwT8@o{#`Ip!QKu<&Xr<^$6NC^j-b1_H0f2ixipd+w3x@ILhl=1~SVNzI zE=CU$!=D}R$G8}E+22Dw+R#YY?HKQ2zrww~lP2^>yJR{hgNKw1ckf<62tgfDt@c(EI5Ibf`T%q7mx&r+d4*OkVtMG>OCjfKo5 zM4l1CODQnZU8G6l*Zurs*Z2PY`>3i4#*pkQ6+}FT%osSM5j*2K1k0g#h4QF?auQD; zKgQ2K`6(XUy@!uJd=J%j3E>?klR2i7W58EQ!`w6$O}kA$yRi&;k)f`)6x?JLIG0#0 zm*hJE$KCr6@ch*^{^2J-L!%t--F*)yCuh)F<7T-;US{x+sOv4NdWDPgbEw9{Ifcbl zgS^a;QH71h+&QO5PcD=$Zbh+2-6{cm5>t>Cc z2HNJSGajijc@D4;oO5z=0x3DJuHNi6Yfgs0 zru8U`DTUSq$xx)-M0{gBAXJsw9UQF#a~@S&CF7}-65B1AI;Z6XT4`8LjfVAljnmW9 zgaedPhK7xSF%GjSHAZqFz(s+h*%3bf{1JZk=y5RSDo9bH$R|N^N6*)r%S%c!)D9wq z_}r8?m>o^=;Qa?UIyuIVfBX+5UF=MKx@f}g)JiD@IFCFNFvi1JmL?7+u(k!ypeia{ zWiC=dnPnLjbRr^HJ+vkhp4J9v+}`9WHerS#RB^q^^BhJ2#biqP43a~5hq|hec?a(- z+G^A3Tx+TgoI_LB;rg0zz-wW(N(rdm`;dm{M{Acc-FUawB*ZTr+@1Gi9Ak#iy52%^ zGARq}0KRXGh~*p^QmKE&Kty5JD_kR)gJK9AJd>l7`GmO( zK~T>5q(gVk_FxjjFgAKkyw^Y*(@b~0LsX#KK@*BJ?~&{~^vNX}owI?GCiduE;@|)2 zzxfYiM#uO|wUmlQk`DUi9d^I4kCKZ8wfBGngY)Eqr4SL)8WAeT!8pKKdH{{Gu-c^1 z3avG?sdwC5M?W-b$haV@bVV{&G>7nuhlSzrmq(qVDkeN){R4FAgDSDdi zsK3mzthZ>8?4(3q7NqAcDMEN!iz~c* z`4ZPRH?Y>?y{~-@Wl_L7hgK#$J5jmE{bc|EAOJ~3K~%9z*6nB>W`6FQAIDN0yVHc>{ePRryL$lG*RZis&G#@l zZR}ui$f-Ye-Ma_Bp?kb*OuT#d9)9qHAK=A{=g`_GM;v^&@xngmZh2S9TT@T$i{EWK>Pm)Izc>eqa z*6TH<(`hR9>2TJfXeETaR(Y&H$jIF+7rYaNbH@8I?8EBwuW{Sk`E z3>SCqhpsGLho~R5j^fT~ZLn~GvwSq4Lu-}Zj|tL`vYbF`6N&(luBo*S+iGX5)TW!X zt9ud8bzLLqI?{Ee=0gMLs8HQ()*%pSin7R&$t+D9RolXYq)Eb`(yQP(x#0Tp~iQ3?Tod$(;7p*dnobv&aD81)do0ej z+iiOPRaK>Xy$u>`tu>6YsY}cP-YXW6Wm%%CDy&wk)WJ8#fN>FM2OQd1NLfG`kH7hw zAK}Tf7tjV!iUNj?kB`9^uw35YW_gY4#T8WB!YB=;G%_KeREyPSh4p%k*DqgSQqFMi z?tLt7mO$`98SPNyB{G?Vg+iS{(ET6v-8Yz}Qg0h!74waBV(ng(@M z(XVXKwJkvgyeDHFXUXhp zw1(1}Qa6=`QVo;}6J`^6*QQ4c`Bi*9!!<;34k3wbQkDf~(>bQo3Cfa;z$6tZA#3eU`D_VzpR=3z5?)_uRfwv_^@Bf{*am06?!?6RJY+C*H z%z8#r5BPCCXdF-UF)A*3Bv}|Kx%khdw{~y_(8fSDEn20}HuR7*Z3W#bIM`iE90)&U zJw0p!B5{@DheWL9j5Lyr#%@Uiqjm4Wcud%p#gXwgNuYK?yvMj^m zdX+jhLI^OK!8@0V^oT^W=xd5&k(^;arEg46>^bX&`n(NkI97-bqrSTuwQgs27!^L` zTMi$@-g_Eg%R?P|uS28BP!l>#u^f)>;`{HO;>VI#hX#;gvf|UH zPqA1mQVLyM)OXU7u4%>gIvTMf9Sf6gSWF}gX>H)#Zj7JjIVOSr(=EQ8b7(v1ky;x} zCPfOR^3j~*{ODn;t0nJ#{#t7s9nDY_lTd^y0Hnj66cUrk6m{Fcz(NWMWh@FI@z;O# zSGZg~$DjPkALIS^-oefFB~3{faI;#$hM?7RCQ~AM03MTRfk{!o*alnxXXhu#AZZE)*Slwk zx{*U!0}G0ej!g1a8x&l?D&4uScbj39fwhW)RqS*M;~aS4vQuD>MO9rxaD?y{BBI11 zIC9EGM&0MOZBdpq&A7T*peQD^Muy-Nr8PyqGX^1SU&|bde-#=pW!(G({mgj4n@*>x z`C|+Pv&7;$%L=q@ox0#LFl4*kO&hw;hz))qTqPvlwpRG$r@z4U%^F|=QUXF`I66AU&CLpn#Z~HP3c(>*mQa^G&mcJ? zWG&;Ustq1L`Wz1*zK8FA=Ue#Ozx_MZHHXgxs-{ZUh1Q8^(u~i)#C(1X3kweF_B#NQ zi{y)P&QLOFw<$L$SXx*2*FXw--W6GK+z-2xKQjgw0z!0@fGP!%<=Af5IG#`8nL|@I z>7I4bxbJD*Q%!@-b`7UZPx?u^*T5!Z8+_kNxJTl#)!rNj?{o3wa>M?3)hv zi&5O_jT&~chtmKSrp9rf9m+bp4X<&Jp9_=vXejMoTYoEUth*0(>yP17V$4*z`(9%2 z{dM0%l1Di^iog|r^hf{tKN#x}e_7{yznn+PqYs^HN}Sq7 zSGtgk5`Ugn23i}mEg9yv+YRcL;O}i)!vvSQ(HhQLSZBh+Vtb-^nPuWrF_7x;&`1;pB!aMK01J$&+SuBW48UUOWDe7UYA)dD1 zolrTWv5$>6bPVXRZcq2zbFRmSoA1+9SSP&X&;l^_d)+@DJFP<;+_2j`lzogPQH@P_ zh9~*qYrTywGIr066~f)$j~m5MTYX5M-qkA))7FNa@ZmLa&SAA$;@PvWFrUwVCG%%@ z(Hs&;$gFI7(}i6Wy2Nx!WQ*ynL>`LxJQI+DjIv4_Xr+@e#h9IOHYT#hPHWUmc5#B; zg*FywU71W(ZQ;F3(wEcIQ+N%4IdI8POlN2tj_a!mfAtst1$Qrw@o)a*4{>}{Vtum! z=N5S;(6$XYvdW~lxpbU&49@?4~J}rqR7!I4WkW~%O#4k02j2Ld2lps3&B}J zmUZu?cmPVF88V{-yU{5NKq&WByIDMb@A)J+3rG<2(WGN@p@thZGP5{ZvUT(8?!_e|+omZNP| zD*os5Im$AJwFcMMS3S>LuQ3z4whlW(9}^tjx?ZQh`;1prl_sNfC_>Q6bI81aaSoq+ z`WY6hHAGgzIpEIu8H_P_^ym>@y?RB5QR|RpIhHpoY*t&mzP!ZC*RN4GEv%!$(K;Gm zGFZHN`5fLE+`Tx*YPH0+-U6Nqe+MokO|QfC5uEn6 zUiL&JMGe;0-dg1uJZw*Y-G$j`@!$U_akI9?Mf5{nO-N;DaxWiQIvtvzhi_;nSsZ;feY$>hnk=pQQjA! zxD;8Q*57UsXX*16ovC4Wjh8`6n}SnfT@$Bx1CLQJbckcLn}3^;a?j8>f^HuB?{0Hv zXlnPq>rWYP*xeS+b{qI$I1S$?UmXsfi=RtZH#97;B^`YHLA;m^REVLd-^Tz!>wDw{ zdegoO-wC%2+mS@#s3=}2YHgE&u&SVphBH)HE7R^ePS(IH60mb2;5-AYC43Yo-YWeH z7hOoOp3aqp1;{7ev-kW~BVA1O5rQ@y?g8fnoTHOrYk|x;6q6D~QDMDiC}oDDNr}tj zBfPx2PP)-u_mj+6Ldul5)y3uXFh!{_bd-W=3Bwc3B96JacS>cIxi_y>2IMtY9BryJ6QhE>vSgl5RJ>8&@3*@6qTG40lj-fSe`mE!GqpoYTZA)GHmj3+7$qBM7OZUQNvq4#w zSg+Tq!}aCkFTfbXdcDTU{D=Zrf&_*Ka#WP?m1T+5Y6Yha5t0N4513aAk1RcJ2=Wny zwk6|TlozoOWD+HS)>~lPS{v0n~UBWVnqxlIu-8E^=3zQ|g`1nt0nhRJ^=mKz z6w?V_UtZFh#5^v}&hg!EeH-`QIm34^zJaow;`rnQ-~IKEaeaM*)nq_yY3o-vN37I-UW?NG{Kw+Te}TkOTG6Uk^t z&0wM6jrURBIlx9g)lR2OhDpUdJUE;)6pbG7z0RR(8bDhZZ^0xFb&3cGNS!1l-R^N* z3q{xmhI*EF!O-J3By;Udvf?21WXw=G z3}A~833>_RL2zTN>@-E7b)n0!-c3X3MB9y|W+{P@{+#F(fT1%IWFTDueaxt*7eM5Y zq=91L0}WvfjcP+jh9M|@snBj)c)wc=QL9 zSFf+(jK;Jqae912PIk#5^9+-+=$Tw?V9_>p3m-ZkN-21)X_^tRe4=}@W5h(?$$3QT zXr^%wLxR;GLemW&f?*nIm%b6lpk1R~9C2G~dz-VHJuTObZ4M~$Z?vV$Q) z!xKC^&jT;pB!U-0ngXWgk&TJCyH4tX9+? z13;0Hm!ho=9DL_6LNbK&6Y67hk1nTo}D$mkv#;_p3t_z>6E*QlxrlL^r{ zyr&KD^74{Qn3iF6WAW9qXSlk4fq(HYeh=rTM_AmfaOdO{M@J{n9c)(9G+-c8ZCTDR zogbmD1-#YRZnvp;FR~okI&e;*6w~Pxmsd;t^?&_a6vY&$caFh%j;7Vr5z9)vxmrLn z4(B%Hp|BE0wADOtfjcjag|#eA%zTf=v!l@HKo=oNNGLYLJ+s{s=2UBq$z%fUES8%!j*e)ZdG+cQ zbcm>yB8S!%jO{+p_`R+1*sLqObMFE=FR<7)(0U6Q4tk8SU>2qORVfoTVcUB?={2h) z3F)SMMt{I`I!)&G?lToP^)A7NG`SfvS-=RFng&rL-?lC8+_^*Kl&VV4!)!Lgvlp*$ zv)o`)DNLqCTGPMy;tPEB>`6+hR5V>>Llo^AraP9drEBSKq`Q|80g;k!Nu|3xrCAyQ z>FyTk?i3Jdk*+iEhw}?|c6a8P`@Yf+`5fK&?kwc?VmmkD?#8P-DkjFQ^YO(86uk3V za-yDnB09-m$DGly*;J_ohXIGK%^mf9m9=DJE{F>D^C#f~L4k{T%VIB@B-L zdL!o*Yh7wFpS-+_;0mt<7sfjO<<_V9{S$3Q%HceRR!AfUepqEkPB!zEU;eGZK?56v zmK%(7Sw#H;+6%JvuHS)MQ;!mc2`^LAEA#HzK`C%AV`4DpJ>pgz!iVgDRKFNNV3yM@ z0Sq5~Uzz||MhGTStxllKFXb%w-HA?Fs(UGS?|_O-`#N?lp1^<=DvKA~u*6(G_Ma|0 z#w_o%s+bUEh2wxG8a!cB4fu=D=^pk_V{?$_U0$#e^1KpDiMm6o%XSH3DcVO>67(wM zH7-j6qL5#!$$>lsJ0F$~umqMC_{Y+m3dU|6l#>V7)I?oPN36-2`Uv3lzUu_`^Otm# zwgq76T`|e5BN!vVZ9zlNKTTr9TqI_ZX)`|l8w2&7uib^cHXnDcA;)jHZ)?N70~Q;R z(TE6@F-famYXLzTHtzH+il2?tw|+mQhtaa&tOAUh|BB4c!ZU=DGoz7htcL$StA*qPm!A)IaZ1e2KP{31;PwIgL2h_ zVF5dRZKS!0{rXpp&QU9)wC+)-;@Tjw*?6LfzHE$C=^3XrAGB;Twex$T%Rl1Z#@ktDYR2h7EQmhHl_na9D-wVML(i<)Ut`MI&en2WAGsjPwp!m`@ zaahSil~Csx=$!v%WXa^s5D;+3@^Ug25PZokUsqkgFrcrQz?0A6()BJYyr70Be}bDF z+o8%WwCe|{j}HNO{VRGDjw-_ya?Y36i&c%XCqR{yB^J)I`P=IJd>@-Isk zHywM?@r~i<_|v!`?}N)P;YetT>t8pciDWss0PT_u_o(8wVEtN~Y8#VXYJzWJ_lGLr z<}g+ZCje$A?qL^yiIMATa4PfY-zZm4GnPE@&%tGy`7(Bn6ox^^-`K$5lbwwb=e^&* zY0m&2vj`P6QQMqfDUp%q>=c`Oj87NV=gBAA#v=*?3=tZtFwkAGrnnH#5}kcE?> zQY6&%2ubM)n2Iat31m(kLYf(^Vz9ek9#}qfi4GkdFKxoBqF}oT$E|-ZJzMT@hQV-_ zT|{wCDRoHcZ`@2lu;DLVp~-1pd~Oq3%!S`I5r>>M=5A+joY}Y^^Pc@u#o0RrLcPAY zTF0*8Mulq@dJJPYVe54we4F5Jt5^?hK#5cyn}-E)#xYj^DO!vTMw``08fZ|*Q=;=R zO=>r*Zec@q)lX^s$*M2YViwxv=0IZns~P>TqwX|CR#P6$rwpMx$K6*6Q|3^(y+PqM zO}%vL=X;8LH>9ZHq&=7k-BVYA zFO2Q?(;<$uh!>86n>n?UVatO=!&!RIS~d1LwaWhE*dX1z@hk5=n({b?Qq{sRX^JJUO#!Z&FYn778#oW za(`2d+9iZ01GnkR3-t>kXN~o8j~l9igy19|G?rhzcMnM(dcO-%$8Ite%m(D>;;jKl zE2L$yT}3P?A@Bzc7D^nk>ZJ6M7H*nM;(cCQ-Mw2cr(1N&Zm}mHS&L6H`4!ya^x5bo z{)O4oyhnz-{g&3{gmrw1l07keceIw6`3giKG7r@0kprQ@h>(#_b;AoMq60C*Fno8>hfZVN@Ktkv!>Pree19CKbq|Tn#I9_CNs?6?9SUCZYyG(Wm+G@vbI`&WXsy+9KknXJ5bko^suGEUqd`( zv~(~*Kcu3Rr;6YHRz>)^pYt*AhA94Uqw6RC6`e_bqgvzbHcnsJnnboS-4BX?m@?R? z?>E?U2F&MApLfW}G~UU+fl}||*e23G^E&wVkKi27T(F}}-M-Dl0l|ECi!2C3zt4%M zpE003vYcjv*=4SUO$Xz<6S>n#P2EXQ7ihEx zN)<R+o2dq9ViGv2HiZ z%ie|hwdltMH$8E{4VL!1QXAMkze(F~ZEp$#dI2FT}gL|)pq}Ju9x@Iz(frIaG3WH3Z6_W@bPlRc@r4?UVP?nLct{!3q zk=+c^x`dQKKmFSrHwYDL_{O}9EDLjLk-uZ8YnM|WTS);qyn-R2-aL_%!C|ROd7~-< zR>x;aJv1DY7WjX*EM__0lA{IRZGXEgh1^~G6X1O@?TD+Uey03#l9lfT@nIX)QbDCN zbI;KgUl<`S(`Kc%KZ)kPBJFqD{&=`UC|caglKQv-k{6^aNS`Ev(&xcE)wX(17}p$k zSRAsnrs{xjsDg0~qgd5YyHM((jPlx+7F6g$xZN&>PlXoA@J4WuY1e!6*GbBG8B-n; zi|+O9`=2^kI>9~n&adDEsy9Hw#&Co6*3KG9nQ-SL$V=h&#G_(dPF*n2ArTwDRwXDA zj0BE#<{`(13J842H{L0ee1KbPF&|!Vr3%Ez}*f16E4%soqDnTcm8%;*C~m(ct{!8^>v z3il7;QX%k#MIq=6MmIRjP`VQ8*(S+K+1WOr@!Ks(sah-nF~@YneIi$z%XN;X=w{3F zj6hFuoJDl%-Sc@s!oYxR=a810^z2VHvOP7`7vte{xWXw3jrhFwS175jaW6yDbGelrq&i^$4z`FmhvvU7j--oSH4(x|L*c-9S%W{wi8`1$`@0IL9- zYW%h`c-yVP%!cSKrqMqM<&Va_H34g%3p+1cMaGb@n6s8iG8i32--Aa;p(G`2PvyLF zYwsV52wE*|4}_F-at2LPy@p3aUASX1Wo>ICgF!eL3xz3-VF+#VtJ^_~@qT*QNOEe> zZ-kA_@)Y`F7IlyGOw|IRP9w_w3a$EYlQz*}Y?daQYZc~{s;VXJp=sr;vNPpb!!e>T z2tpAUcyBO`DOU-q0{dlAk?hA6xHOyICJ|lx8L8FXbQdvmy1~a!tkv*l$#sp3khE)_ zORxEX-nx{(c!>b8|mWomuN6waIop&<}P`m`E}(Ids0C z*&tyGhZo*C58v?Wi8)W;Yg&Xy-edZEE=W3Zjhi2$?T+!>tu;$D<7DVU@#$Q!O`@yJ zwUK4Eq*ItpXbDLeBjidVU7IduO?iwvN=llxsji~Z&W$?=U+#0Tt3qFl5-9Gv|!ac5+e;G=1gvSdQT-`oF-+tQv=eJfC9W-x}hU&iio{>4F-m434p?b)1 z8-#|pPy_V+A9oPFnDhA@lg$OS!%3t zXppZ;OybpzQ~nV%D~Q`WsLe(gCOr=%s0kke#uNY#0wA2@YP^{@;$H&Ayl^k?5A$i2 zlLhA^vE7R5CV}Xg>CI zs(}A(#}?4aJhn=lg+4Yj<0qE`g9t8XZz6^beiR@4B=VnR)Z}R;e{W}i{+B`Y$`eA& zQ2&=eePA!#}2?*HIP@!O7vL8RhEV6)s_xcD6hIcQnkB}P|KeUpM zgriE5egwp=*FF7Pug_b1cfW`hzj36-m6fFyuw%%%uGgK;iD|sGO*-ffK`aoJ?6Oxu z&1BGlk*DOurXwhbAnIViTqCU!qZY~audCEIj*m&Pqf>{o!FPVCu?R}iD!vBb`;8cZ8IXzG0p9f z=POEgDC||F~rPRYV(F?iU%)gc3zN4%>ujuvc}UNl2*U1y0)7V~Bz6&kSxrVFGm543csk$N+6 z>A8^w_$cbQmQA6MCO*?`K|QyguUJA~jj`t)pN{=i{y28_N~GPrT_cT|Vo-)tSw(Yns+szhvNX*weECfW*!%ZP1E_l*7Pvrs@RMjDw~NT# z&F7BREN7R`O@mh%-?ggZY@h>SC*17Bm?k!i%E9}8@tH?7F9&Y7hI|sXhBw`#174ob zFMs{WP^#w%58<(!33LrsfP6H-LEZ)k1Ck6?H70_SQ*|gI1-C+?HF_iO(55MOAP52I z;~IWuaI&RRPF~mQj5uyOkA#~Lm4SxXe5JwOb2leo3BzOUe!k$y$74aDt|bZYa@*BjT1Dkg-`AewK?oszz1l+Kw>sw9#Ohge zP2CG9&u_J*1&A8uTVuHdu7^V0NOp2IFXC|(XEZJhRN*UkVgfYCQf&nItBEW(n3&R$ zQw24c?Y`lSu+-GlBpu2Q+M-mGqM6~fvVh%rg#g@3BDpN`auQEPC%XnV1eHBIrjs}T%4@%ot&QTEPTrV@~5u5cLN?`@?|5* zM|KIz(W3j`(eqALKT~~fppR(iJ8sn;HKi^Vg5x~IK`@8ttUlOuR75DKrZIe7Q4EzQ zeM33fj+3T-#QIE=Q^LrCLED~+u3p&q`NP=PmSD;_1yU@Om#0-^1yQ!RYz?gopAtnA z5%_(iSOL?jCiTO?<|{<& zyCyzT_UOkYH)=^jHVN?(4 zM#uF{ES>*1#-yX&;@h}0%=yN}0)sC_E|?rag6cC-{$9S;B%NB0Y)XZ_EWmE!vlBsM`(8{6bi+?_%!o! zK9C+ZxvS)=S48UKs?JorrUq?Et`pwCH_G@C@5dP>nN@C>W ziIj#C3utIg*1nq@zipMh)Mn4XB*3te56u~YL?ZwK{r}3tfCp}WzeMpF&Kqf+=(Yy_ zTO~%(%;@)&{ZB^}?)l+L@68kwEx&Sg?+K$c#Tj}9$V?GzO&@{JMgJ)|lOLVhs4FRV z+%9@-)KT*-fpVFWq-bGy(e-lRvP_N|9#V~@64|QeFm%SODOXSbBk1nFd3c{`AOJ!n z3-`NZ?mc^L^#MGLuNB5#zTZE3-+wa^1^j}9CGCCYA_MpLB6*SlXI*VV+1SH-Ji|pS zfd0;gzt2UuvHRS}A;W5R8WNW|A}ry*Z*1C#l2za5+w?Cz*a}y#{1{&aU3Z8);AQIx z;fPuDB7&=D7&ve2ns|2wRZC8a27d{{n{g{UN%sh{cIt?=l7}|c=nRh~t@)KY(lNR# ziqTh7mDkwI(OoX7j19YmZMbq7=Y{xjJ+n-^^Y(9UQYjQc%M$1QG6@+G_}Pz{jx2q( z17!uf;uN&vT|45}nPp?@5TMh+F&37?5o%$=TV@*~>?v=0U_-T{Y3l=FrAS$L&PMB~ zmJg2|vKNn~@G30%K|7GQLhtZgRt058Jlfl*YXp9I-C`bgFL{mB2*4Her*0=6pH4d5 z`aZiKyk!^@#XIU?S~0XqiLY$$bSViXxJ+5IXh(-Hxx5AU+gblfXh^dNEtt_zQce^O zZA+pVBwQ9K+0JRUAt|!a4JoYxG2@}-)C<-b+pRJd+lOWHIPa7+VgIO8HaqZ{cdMdI zSVAf*r*y)t4y}_c;3nRp9a9pe%G-35+j26QYx~itEWS>(j>lPAJ1S^$V5N~<{_X9e zW8JA>lDYxSPaX05znJ3(m@Z=Eu@>=q&L2<8MaTYflR1jKyVxTtJ1ZkKU&b43Ls)t& zS`AYm35Z2o?sHAGh3fi zq++7(dDx}@gdCfa*$1~l`hf`{Fnot}b9oKI3X7;ag~sp184|VDWAfGAF!5upZSU-Y znZnLOP~BE;g!#-13J60AjJtNkDwFVNe0f>jTYODOEaTyDCi7w{8Q%T+G|4&RdMxYH znkcJ?29KNk^F7}FbZDmQ`70+!E)Ah@I7JN}KCewhq8u0%74@yEG_8Hm#9Lsoj=usV z<6k_YCGSZjM-n8T;8WS_42+NfZI@DbJja1J5bU(}qNofwN0L(nq9g;|XtRCd$e}M)V zJ7Fvr55E`%k3||QdB{ooj({4(Xa4BrsVY{A$ITT^#--{H4eE1u4hXlmKnbNJ3A30ZV?YcBVN9|lyFpP{?=q~W3HvWY^{@B{bG|Qvh8ji{fm_ET5Qym0R{=t~ zH)bdPFr9fQGFJaDRcg<0{>x8&Jxg3gz7-|*Rd7uq_lCf{jWC=b9D z0|(7+fR1`1tn*_x+K7e`mmuLeVk!;OC2SskjxT!j;`tiOJ^JaQoa3P19EvKj^IY3R zp}{t9GYBbRI+nH38LiwX{Aj4ky;?wr{IRHz5pjPwOc^Z*qtsPzbv-3Y(n#2R^0_g$ zF-mQ^%BTC^lz4_Kpd8OJb9~^h^QD-bp%F2RZ1$WCY%i2vwQP2!$m;r5`X@v!cgax_ zS2759{jCgxk-d3t#Hu@VN&IwdgnMc9Pl)f1bL+Wybo&mqyJF*2HXi2#%1bk!o)=C)^_Fh=1hAG2gFHSxj{3*Gn5?bkL$du7tA(5pl^b!dyfD+`V%p{4ts5 zpaOhm*t*+EEkW>yx!;wogizf;`W@lS8)n3#_Y__eB8Q2IT1{}N05#d48zMV?sQTWR z!^J~jP z2MzQhJ0V?ZBdB)3Bmq)pL|KVyogn1_3@dxx~; zcZ)F2gmZSj)i)4p2&NE={AH}{uI)_Ik=^r~}9uyP92ZT}wY%f{vmqAomU4|X^ z$|sbT<@z74cZ5&;5v(f6oH#m4`FE1kuLwYbeQDa!<{hVmZiOD3$5(C?IYTtGNjRT; zZ+>A`#c-Gp)22yf9gbd&`;_3KgiIE8Y-GK=1VSBruNU+o7z9&i5Wo-!4C;k7>a^$O zp_aCx={sGde`_~ZZSC*~g^a1n9>4pj9myFr8|cbpB@#S-*=Xlm#YASI7)(N!(}^yC zFrKZyL9j%xtnWK+z!ZPH5!n?UT3JB`n&>WHe9q~jNfmI<=;DMMnSk+3_>EuK)spqy zx1JYOV3J6XZtMrphNB}O_hA^wwaI(qb5Pa;B{UNTn~Rgt?V_JiZlIchr;+Y$Vqs2N zy7DK@FTskXer7Sq$1mO)SBGkQx<`fc6a~}MK(oTj2t_07~T70 z*1oWyv}O)(b`JTU*?(~i7S^PuHPVT0QnvOurU8FAHk^bALDZmVkscJ1d6YidEBV24bHc%sy#rtN#_=GSgDK-W(H^5#q`ne>4YqQX&)oUqiCe(01>QO$eOFU8h8m$ zOjZnGp6AqyMt7#f7}RpM3pB@Q--N=CjiCCZE>=$G%EurD)%Ft-dskytOrz<@)#zgq z5IACrQjtA!=$m%9e##^N$EM7|$aD~yOz7h&cPieQ>j#sq0FU%IN1ktvST(d2`r}}J z7+Jzf+PF|q^ZrOnIXk?3BRtcx5pq`d08i@2HT%Lu^zw#1_OUtWz{73|{v=ugOR^dw zNC~xk$9>!8TR6%9j=LFf>}R4Y-Vwe8qK~_!|4z+;E*Nf}jOU7(58iOc6`|rLmWX`l z_6^(r5>uJpn)Uti=+I>Q5J*0KImrkJ{?rwiXoZavVNoSW7^l0r^v*u+=TAPuA(T`t z-@6wJ5DNDLJl&)p#Xl4kzy zP>cn?%uZj3;`GN5)P&7`Z$LOuRcAP^K7aj$p;vNoy<}n`x^necZ2!@m>a(k($;V>^ zk;djllbeDg@J%R!u1Eh@aQ{*Xj-67rf=xMDMS#ZP<+#Ymr?z12-o258Lc;$H7r+y? zo$EzKk%4=xM~P9p{`|Xj1Bi4G&87RP_SXVR2()uw^fatEVA;@xc9lkz`NaM$?8zV# zn6T4Z^f!JBv&~jOmczRypn#k1qh(Jm>?X5=)!!l@l;L&QBU@W68!4ef(%CEzX5 zH=p}Zf$A6{|7UjL}y>dL#@fPAhVc^t|g9UbyVt_y26} zkVEgoTrcj?@l+ZZR$MZmpZITCGhycjtE+t~kyo0UoaD*XNIDd$7Y9rQ68+8W-1!_^ zqdjLi0dgK2?UAb2Ok#W=3@6~O%Rgn6j$Y9wGr$+&k=ip89elJ%bkP-atWa8iEGl!w zq6L$FgeR~EnuOQT4ASq9q`)Jie~V=WA}uV8$3$+irSc=X<}?H#HL`j9XwqQspM1l; zS*v-^3N|0~@G|G{pmFV1AP?kfd%kLYL6hQ&plS}mhUW4T{AtlugOOHH#iaex@9yFA zCNbSSVi*~^@O2C7;=cw1PpF*}+ljNnSFez}e)~4IR~U8rqI0-R2JhARu={|HY*nNl z8!`s=W=mw@n`9q~`g&Cc-ZWozh`g75`xL5PIa z0;)CbkrDz|FoS_-`PN9v$;G$rmuYGNA=W+j6{>k=9%;j}XeR0Vpt@0FkvPrv)a1=f z{8n?ef8?cutgY40L^1d#!enxt-?}Fh!8~rhBdiy?O}Z(wt8)e+{;S+rWe*YLhxs#Qtr8|4r52cVjtq`95*wG$dVoUzIvfy$0J?K$K zkLa)P@W*qIZ4OWsW2!?82^%~#@e3QW3kkUAdc~lAeWHKg>5nstp*%>-(C4Wmr4;=G zf@*;U2&wiiL0;z@@YXzlE0mNk-O*B{MZSh*@SAzuzyP8gmiOQLLvKINsOM){xl6b; z81I}2tPY@URam<356C7tIkAJMEZ!R%@BH4O2i}iBhWhUAwW^B-FbUV@m`K_0DF+DT z(>5J1(NC(!DP2w;9xjm-$2nu3i{w0yS;C$mCSb z#h+iK)B#U;XVe=**ZcnwyR|D0m&Ycr1f)FQ19-E5Ovx`vdmnlGpC4~8i}IgHGcqz- z+q0y7Z^4$fNN2Zal<zj@OjFtS9$ zWX8#W=m1wBt=?s_wneD#Bfp$6x`W`F5T8V#hF_hSWzu><6lrS4edH&hLV%|-Fo)0$ zYj8D#Kij#ZB7Ml$O=pDEdD_+2@zc#Uvi)!>Xm?EoF3((?3RPDne#R!0U%;jb(fxf8 z

Y|2IKfKB2T+TKZtIbe07yTM+*g_gx2>Yf|Hs!dlE8_G1H>ro$oNT`q)~oqMF1% zpI3@EI`>;4X>FB=t(*z;Oxvh-a^U!ng)lFqnw(ok8gls~eJA5;tp~ezmC+aLxCr!w zCbHzG1J^PoLauK!yVH%U<+6D_>j}P;C@EIG#?z|Jm*i`%=G=}|%sB&U5NxuARy}FE zID=>#8~MtWdPoxxL-nLWc=rOz%TdY#88C8ewP3w0^2CZDy80V_I6Q^O0|;GBW+Z7u zGB!DFqGd=rL~^vSLb^eO0Uw`CBMwE_3~mpu1f^OJBbrfRNVV8tT98Z|&l15`SJHjN zBlll=xgHTtuekA0tYzBm)xXo&;xp(F*F_V0vBR`}CU;?(Yx^wNNLHKvHF@{a9pSpM1& zd1_Wado(`%O`UEC0}n(gM-C;bR${Z@0A->cOD=mRAr(KZHoJZ!5WHoqg02)ZjDkZ_ z9c}RCtRWR4N!}pWx_lO+-pR1%_i`*u+9<~ z_G+dY+JSB-vh2rVmFD=5hgoan^cI9AdoEJ(Nlub2MVL~eM1Gm;ILHwD{9g+I0=}Ib ze?N(dZ}^b8*{tHBz81y@I29P0T?c#}&m5Bg)Mrf!nLxeEqhAtE&w`0HEj6;Ouoq(6 zuR7LlJcR`QIf3sgK5WW62DCAO5Q9#`OajtPMXhEzSG$a3}O!x-;1nJm=u}i7qaf!E`UZa6L zct-ywRz_|hTh0XOrTpGr!naZUkyo?LeoFIz0`+V#(lMfzO*s678`SgF#->#8V*~_5 z)#a&PAzQO6Crc3jUK=YM-;%MtpTZ!EJFxfXv>0n|d1O$30ap$(j8|t=NIMW6Lz+l9 zEpZmKJP}a+K#UZcRRGnIqe#jn;|N1f+d-4_`Czy8&8=nY`=7zS=8Zdw5O+18i03UT5)DCjV7kOc(oEX8Qe2wkTK z$$mM9RA3OA4?v(9mCZvPBt}cvvMg9R=R2h5}{5^ZmneQL>dJ{mYA>{c^B&RzVep76wpZR&0w?jr8^y z!MW?1n0#m2J1!-KAf=MDY}w&0DUOfaP8N}PNjm4X*@sH)yPeHUixgcse7}O6C*fx&vc!mkgHzYjlVH6iA-|w2 zEZ!Ni|HCJa45FWN67Bt+`5`dG%OT^@%Z?N^2Ui_vW5$)7bm?vhqTwlGQ3Ay zvt%DwH~GO$=lwTNOe&u(xXuoPtbv(Of!7YyKh)78YLbrzKU9YgLM`G;dx zoeZ%sEJ0PDn`eB;6CLH?s9gpPB38%yHpR@LqfX?l4f{swdZvGPWPO6nR?jdS)oX%;7*`%pI-~!C4X-(rr5gd`^$C3qqUFc&9>WF_xzW&RF^(!?Hj5c z3%@;2k=idfRSWLq;h}%fX@}N|Q8QX-bQSn6!@0b!b zAe*xBTD;LmvDU`L=GQ~#42yGGvLO zwrqaq+1>cXg2BUPXGt{Hv~1~;lO*YU&oLWU8~H6FiLX8X1-+f&l0W+1`iMojPcsp& zB?H_820UbnghPR|tqlRFG=kjy$nw*p7ZWG6R6ofLZ6Wg9U^Q%Pc@_{%iUrY}z;1pX ze;Vg=#xikw1Zv8zfReh!- zq?OPs1kiX0C_>h=OtDe;X6Zvs6LF>?d%vY%f)h!f!i5E*K9#5+Vqz}&gCb<39(@JM zq6M)*2=d+cc0=Z?>-vjSGlbIBj3!F2Xo{D51|HLa)6l^-sn#u5o(=zEAcM5URY5#t z5y_)Yfv^cd|InMq=q;oYAJ93(0IK->mlL2_I%Fi#Bkb~HB=D;Nq^e{}V#f)D`HWjs zT%3QiPsS8Ti{0La!<&Psn&mnwct4zw0j<@jTKH!CBHUqByx{5O@Ot(oBk}t`ssy$< z6cid`WPeodw$m5vqS`rKYkLw>QY?TajGZ|0Z2f4Re$rZk@Z!2H)K8*^tC<2FU1+kY z!lNF(mnM7I<)W`W@65^f)W$CuR@Lk|%Xbl%wD*%5P`dz4JOF^|58GRpYHV_Lq~LG3 z1s0Nk>9(l>s0_GlRY0~7ht~ZNPd%=kH*EHYy*KU)|Bs|nmKz)#myZEkpU=6L?5Te> ztvJ-a8-Mf18lqnsMTryP83)l4J1u-`{|j`t;t*sb+!qpYzWXDk>~338a`?ZQ=lI*# zh6|azAtmkbd!YO3jc??=FU|s5ppE$B0gL}bL;m(&LO}Sp7`MpwJ^;%F6u=IGvh)m@ zxl%%Uz*g$l<6qCtr%PH0UFsJi2GsiA_kW1S+J~P}aeYrZ8woImE$Cmqsm{v;HZ0Ey zvYjvPCdZU4E^lp(_;v`S3|C6wyNP!Og!(9Yxz@ca2<;{#mLc^08-8XO^AEGB``u%B zN~pS{dl(>_Q_|)mi-M7|@6xdU^)aMJBJV(95%@RQ&O-Z#Tqa8wRUzn|mXfXT?^rQc z+N&HJuPIvP1g_`)6i3kQ`?82ca%qn6f`qz{v}lmKKh2)fb9U0MAJ7ItX%eYL(C?cEdQW2zFu#@CjiT?jzVaLM>+HR?N>hV5Z>lYFe}pthF} zb;BCLXGxLzT4m zR=)UafUXAbs))l5*G1Yfqbelf-VsXoxj)vkLer7UdGl7Y9Q-bK92#K|1qZw?h56>u zCgpT;Q~q!(@LK)wBGX#alEK=%1PTVt&-Ymwu0oLxkQg_`$T=*YJsa(xUlo4B^O>ij zsMFH`LS{z1%1S9@n&$po$EIt7(8*=JuY_tX(pXjMS!}>?u==bK2@Ze%Wu(m=x!xxh z26-ZPL9UU-ZD2>VFgEH=EIJG}D^A_~287@J`ihq|- z*8%tVhW(gVV;wtP4GqK(>w1nVvDO6$Q|WiHuTKfD$krJoq`&9^3`g6pSQ(=lZFmoT zmtlaq`vqgm|B(a6AUJ^}pg!a+DxHPp>f(axVJsbuuaYM0Cor-IWG&wrp^P-a>=;ed<@!}`?Ja)oIQa8kX`_bOu$Q6 zRtle9si3zQnSuqYNcxDl-ge8GN1eZOHiPKS^=gb`wnDICg~*zB zEcMg2p9A|R$y|-oiMYJZ2AHwaV? zzjG7a2P+_IPo| zBvot$?+zO0X ztm;tVL6zIf^rptb2YqLOs(+JHEzZivdn-j~a#1)#)5lY2N6QSi6a>iF93Pn%T1^H* zk==zhI@AquY{heUY2u%6OR#%kocM3ha*wJ^ZXW|Rcha?Qf~~~cKKMlDxkuZ33_P~I zsYR4^Re!|e5W|3;KAV%Fk-{fO(jCB|cQ$Qgf5K!SOmX)^bL35tKNA+p6{3|Y4pgw! zs+iG2&>$i=Q+i@r7#-|jt&|qvfp|_spLrlxr$SRT`6L1SZ+<<#tlzk8rUf-FMY+Xa zdZV#S#eVhMmXY=n7Cj-aSg$p2fR@DvoD;wOjm)YyS0p9(;R3}nWpx)E3v!6AJ`~5K zb@}XS$3msR?e6(9cK4a-U`vFL*e_(Jc0bM@L+dK5!8ewH5(W+D%lk!d;%k!?2vf%{ zf*}w=nS)do1XAaxn`Aaf_XV$D+9^`ZS>)PeF>NI!zH)dYKlQCglOZnY+&d!oG}p+7 zrinlV^VvFS>K~+oR-Sg%iDZ|kkLn{!ORg0IETIiun7B+{udO3q{AeRT>{IZr<3JVD z`+aeRZTp>KPVKUK1Kf$zyMQ#w#?E^nmWP7NX|tnr5Cdw#WoO@|?18!hsN3nVve2{? zY6HAYHziAGA}=0Jz?L)HC%YK2+E1FV13mpT33WNf<_(6XqMNdMsgd=B%IQIhc*Vvf zHLeAz%B{&vC(=k$r-q zD6Pb}QEWJ|uJhlFQzOwV7G*D)5}!i;4J{P&)(aWa1_M)Z!R|W^--o~ZssQ}(2vm08 z%6E3Wu0Oiicq)<5RmqpP(K1-n}A>k7e+}yAaaj2VgD4%I&2h{C; zW6kV!@3Zdi?|s8By=TcpsHv!S^?M$O095tz--=gxB?=Zfp0&~}Slf=hg$U>n4> z<#(>dL!}9vo`KR5gEpc7{|`^g6gtAs&>ORtarYP3L>dBMR=cMo&hV*bb%wwu1bCg` z$J&F-i2!?XTkG(*xuxl7xKvY#d>|s_*XL+QTYl2L9XLSC?=#1vPz0pDug;Supe%pC zse3Jnbj}MAO3oW?~^BOI#nDW{z$mG#}=z+_TzjKx0 z4#ANYS}5EIXv#Fze#Tj)fx4iyLXbKWdcDJzCVKH=?g@H8H{Pmf(g~Vy`vj$hKHM^= zT^#O5+7lGC119Ov%u@Wuruvk5Z3l{s=&IGJeya%YEIrL}(hqCK%~c(|;=-06NMrs*DVn(QFjQ-0q%2 zK}t$!1AX0O;sqg?tE*LT&t{5}xs!28&$r!Wqc>o77#y8+6pA&HE7*V*0hx}kogtK_ z?n$g#fT4Y}4Fx;Zrm`LNb#11MAyH0NYoHCL>xEy4g-;%D6j>J8_`NIJ;l321rAyj< ziqGg(pJ>sU_19~rqzcR77gP{}vjczxd;<_0wMPtM&gqXqIx)`6+E;v18 z0T&J~kb&=iG<{W6TV31ji#x@kxVsmE7MB9W-HSU#gS!@&0L9(i9g16VD+DVp#of>T z&KUn~E;5pl?6saL&zxqw1w`Qk*iBk&+!=#`Nnfbr9NL@fdtEtOuF6)$V!qB5@e~j) zmwy_rS45N%TOyK$0MvRz4SL7V4_MCX|I)WvWl}BwgS65sTq7%*nbr0AMus++@Yp0} zG_%9=(2iFOy4m8rmX_AmH8|2oFSdLl*cl9Guqc_C!d2JVhr{j6+!sKGIc@+2BMf=Jz> zY_N=L4VKGL5-z=#g+6KfY(VOVm+&*t;LIoCwO^7D31pZ_9{R#H6`TrGHEer@pi|3` zi4z2o=Nq(_?KIJmT;G?p(K(_a%O8=dr0bpMHu9B=<49RQZ&P(@%Ja!EA|wqAjU|wS z0ALvLfnxilbkkIDecrR+%TuzcxVUA- zP2tpdA$_A|uYCId4afTkf@T+Oh=Dx9&5_H?dhFa1n-MyOwL%GnA;YF-|Fv3$PBTbG zB42)F$ZxGcUwm`UDyW&7CG*?(@5bT`$ZEzOy9%&UxQ5^BtJ4% z#*72ib=lE@f&9Gd8WWhBL<6o+DoTc(cmfH2l|V+3kchsX7nI}kz#9n%M7eYhZoW(! z?_4X34gjhzC;5S=yKfAS600T$*BJq1yObgzM)t#*X`|7%b_3$34n~z_SUn0TSMM)# z9?*~Ac`n2d>^b29-6m6A-yEw3c8_7Fr%K|6+Wh23xTDjx!~ekF5#|RNfv={I4HbVTj9p)U>%iSmBh! z>XXBWqU~?CN2FH#jm{>`zaN1BXo>RD9~*e;wi+qQ!kxglE#&hi~1vri?4&WAEZkSiX-Vd`X=qo1h%6$Ik^i?V}%{t3IHyVdE( zjDFyX;Iw%nBDEr<g3lb_ieb_U}7B<;LrT0_2)@J+CnGE;Wxm1>+j*NGLM&53oF?Be0)i#`!4)a3ddv8A(1VQE+Q3H{tGgylQ`AS zM_n0w;)?FNWHk(Gl*j~`xl#VI5`v*kKQmwB{AYTRMRxN0%%~#~GIKrzgx0H0UgRbM zN}20Gp$H`LdIhS`f2<7&W_aMh)@}+DGA>&Mn?nxndd=op1fwAWOhgDaF>|A@cj(`P{+}s_{(OnG{2RxZ^QdF_ zrdaW3fmOedPrV??sHB~n&hyq)?C=K1Uxj#zboIIpfGs8WfBiSL@14Da5uz{eOg@d2 zV-43m=N?n-b~P!Qi;E}!bP&#!96o|DB9mA%kXa@QNXe4?J3kty0fq`cu5PZ@c1PKFcC#SEERvqH=5Vtt(Q=uu!%0%EzgvpqIo z@}PFhv=~%yad9!tqE zOoqa~MZwubv$sJNdI8F+{O~1oQjeI;yfsD!NFkJ4H#ZQVr0OEps5VD0cEn7k5PP}C ze@?!hI5~*Nfp0076y>G){izlwoT~TUr*{M(P6JWlnmQwV<%{^1yfNKBVfFI}K59`H z+X+OZ^dVQss|%!OoYxUb%V`ot$#=>nuHRP$*t3aWCZ}5l1w7w5h`jyK{)mnUN#`Ak zE5VII#e7D}(_@ce04QYt%pudMOQie5d!L$2qlK*33BV8rlu0D9xz1!Lq_J}mq4RgR zeJP!%@<48%wH^dw42XmlKl^yg=UA=vz9*<@rv~GPhW;>&t}$pIXE63lY2EbC*@M7y82H88OzmDkaqOO>rewD_Thpt)D)t$}9| z#?C@ZOa~(2ntX|NIIRcjtW666kAG)Egwx-;I=|{x)Juo=$o4vae8NL&MN!rHh&f0& zPa}ED?bhV2i&vn(Mc3Vwt+Rx1qWcYKG|jGd|7-ulO{_B+uFQvD_KZlgl~W@ z2D?lRR~9DQG1?+Oon0GZF-5JP$Z_r6q+@K&1R6Y**ZJ86-k0kvKqqFX>n`|dz$PqfIs_Tm`Yz-%u&8t;qgpr1clQ)SaD`$b?gCq^vGi~CWXx{OnB=d$pB|82P> z9c}lmg5t0Om+Y0nbb?IuuT1#Pc!`6sA6MNzGtr5U#Q9cMNTewwahHdPBsEDEqcsSZ zuAiwKyA;~laQSPp{bg(}TA*AXEM-P(s4{1@f>*nc%3W2`&&Y$&A_GiVk_^|Wl01$y zvK6XbDchz?*l#qxH%BoRtPa}l+$v6X)v;AjJ?VN~ex9D*Bze>G zJeH_kUpcJu#;9cogBKUe3yvKKG8QX_5G)=gBB1XgC|p>Eo^6yy8T%u)oOkk#GeyX4%N}G_yKE&)o?OBtH|GKb z>E2TGjCl$dub*KfGMNz3kk*`DY(=t8e2kUpx<2c~lkO{G{kTE8L|-gCeM+SEn47|n+-z?bon!D|8coC1 za;SQ9>VQn6V8({YpHEg*LYsG-6(>J}?#Vr4JC`!%=c(2m(`0vkWUmrgd))olCTF%T zoWO70=$0#^U9s)!_MyOnhY5KV@j_YG%A`bY^EfA$cKiT@np{7T)Xtu_92SuQA0iQL ze3j(p2z;u+KJ8keEzi)+TpqK3){T@U{8>^#S{35E-$$mhXVlTGicWaQn_gszSnKi01+IYtcWENo-}LH0B#gp3>Fhb!rWq#+M=+cH^fC1M z`jdAhen*q#4E-0AOf`!Z)PEn)INC>({acvS^bZ^SL~qaaCw6UlGL?@pVEesmrvw*}6yrk|5?^NnHBBzTSrXcE`9LOlS&5*!Q9fE+|LS$ju}cInLoAl1 zp@HMo)^fl`6%EMO2r6COd8~&;Y^i5OO?qs$la~3-WZX6$#7quItmta?|FycK+OaXY zzy*B^qi_$krr}fzQ318824dltG{A7?qaNp_2zJNZ9@MjZ{GJx>ryA+Dxi{5xM#Z<)LA>2n9bH%E&iO zuJ}3_AP<@I>L0s|Htn2P93~@yUW7CA@fl*bA~hl=9el9C^G)}sXgJqH)?z%(#AKN< zL>`f-Z9(uyCf(lzw5nq1wT#?$2?qR<=EbKa?e;{nT|skdtb$A5QfO)AH=y#5<6ZQNeiF0@bQK?AT4=`kkhrmkqg|6?hJj3{`6qG@Oc1H}ZL9 zBdAPjYE|xCY$SW+6howPUM-Nic({q#*)iL{4oil@Ylurjq%=yJ=+$WTkldbSoAluT zs)gUnB|;NC1?4L4puO1mw1o8j$+TaokxPuu=m5=V9W31GTeD^HEOBrfDS;YSI z>S5p3uEdXcg)x3teq&`Q{qR88`)=5C8TaEat8`}H)J+hEI`tfIcz<%S)V(;7X z!^rys#r5h3W7*DTIYv23>Sw*m;74Eafba1fevcErf6y_HfiRq~bJqvXs1>T!Kww zY3*8}&3!-)LOi458kK9`if6El8a~}AKfJor`vc~BoV0L_7RzuUcDGSHtv~@Ix7JDn zsK)F4#|$EFSl88ytAS|8pq&!pysbz2SNbf>>7$z`DHF5-)X;sW84IpcPLkO4DT3eQ zbaJFggH)A^tA9FF&HbfJ)>#J^!zn6Ue7c6@SCuLX<879kmzL@nZ@i~d`oSqFI8v&= zY%Pwh=se_RQ_2G8G6=%xUZvCuv_D!D|9Ih9!6Q;__Yu;WpwbkhGsF&eOQ$BhT|y*< z`ozNDNf(ydSkITS86dUV(tbX+HB=cFm(9hc~AZ!D{65@X(;fh&cb7-hg*GW@d{Z$MdT z**&Z*h*(d%8PQkhc#Y4rX=d7og$Aa;;Qr(t3)lp)hknRQ zYatJ+-hNV#x{4e1^h7;~sJ_XuX86e{~l9L;uOP z=O~{F6)3LT9D%I&I&>A`QXomQ)*7N&a!Hf}zvw7&J_Dv#WVcz;2(?w5ApJ$a6AV3K*Ese zK4$x${`&DB{Y2Gbb_1sMragK~5u~|@Wz;_FE_@~TC|;8YON3r;uG7(UYVhW|j>QOi z33~$TMo2X9(e_h757Yl9NaNR44wuI{s#eE!a}b&H>#$~NaZ5H2$EVBe{6*%%dHIvD zSy8KeoERB1Ohmu0-^D5ysiRCCH@b!{Un72}31r`qb0ae~4F$`TQ%B)I)ViLh*un>> z4oa;CtJ^ld`N?ix+2h7w|1%b>n7>z=CU5BNop#~ce|gFBuWc1axD*{BfBV;*F>OV1 zlmoS~eVaK@^n1&>?Re-&Ui`ujReHMF*M`pOE>5R${G8*F4&wsO)?07DDVT7gU6aJ2 z-TZeJiHoTo)JAOfu=xFrc{#VUPxMK4bAR)-Ge7}L`en8D72#}M=r59}XUK+8ZtdGx ztut6;_c9sRCs3*Skrz{E6X!ASxyxI-gxr{u>?d@x}( zsWG!3j~X-I#)&&<`LzHHdbl$4DAig>q0}++PaWM?m&z{J`)pUjrO;-)JaDI>!p2Lt zbu!E8hOW2zh!)`An?v0R(R7ifLQmT3>)z2M{ z^RGm`uc1{?=FP!$Xjqe}2}}p^wUMMrF;a`Cve~^HcPRZ>7cBT?^2wuGlAJal@@G`y zQX{vEiqL+E8HzDzSZ3PWDIYf>Vq*&jy7WvFNXmx;>`tS&ar?%jKb`B-tOhWRk5|AWhj8hMJ+`fvB(= zMA)I&$Z}Z2O?rj}MF`ZCkvIjM%{cTX(M^;$v#0q(6o_--ll;n|eH+iKL|S3uXyQh; zm8JMFDFm$A0u!2j_8s4Pbesf*t$al+gwwAsE>Q+%BWFFw-9U|qocIZYSiVg$q5%&7JwoedGdG(b?CVMqj4@0T&Dg6* zv5dul;QQ|s14{-7HTg$nAy~YwWS4W{CTLj~@I_baWj8zXVz0{bA;YM1(Fk_vHlQe{2z1NYLF!`Hzyok>cUAKi4iD`73 z5Bq$N>C=93wSKpi2HoJ;_frr52&l)|%o+GN#7I-~?7(WR%{jaGw)Kr(UhZw|`#bL2 z#fP^909;)qXNvw63b-N5@i`L^d4HV#l*<9^vc`Qb;?F*-x%4F~`rEWjkZ(nEJkek~ zBTxH*f=nInqfO_?1jj4-z-%z1qL=sGPoLKBEAHYbF)d-I-)gmu3nStw8gy7az3=d- zFnmJD8&`gc>2eR>o-EIHY+vos#WIPsJR3iTY$HM{gzHDxqd6p? zM8v{|E3#TEdXanJKWQT_{ojc=hv{Jl0=t^#`Ivm4a$Up~ z?SqJPd2ywLKNsCoG-tW4AI+zoi={d$;5N zYklQ~y8i|#+N6!$=vpqE*1p=<_Ix8us!s2>{==SkgQ!=^M1eJ|aCM9Mxk238cEj}3 z6O>?pI19u)rxd-el+Nm+r7NylqiP|8cm~hG80%cPlQ3iB6w3wK;ML1b#gM2HN^f5X zl~IvnEG{ej8|Gy2rFeEqnz`teHMGuPm%eA3;o~WN5z+JQ^f!&~t{fg?qB$w%x2za< zEhUqxt%0#>Q8@3LGwVfPCPCip2| zm!+)BYDq+6znwD>>$Pr86kbMI(TSSF!3rmxC(+MY!tBzoW$iv{5)8J97ypKaW3dz| zN#j8L?fQ}VW<2f-9E{BJx?>O;;e};3YiWf`Lqh?pYe74m2jkzS`5-4tb*P11s~-E; zk#S6R;~s;E2uLxT2HQumnlU&FaWSz~`8-Y_k%gu25NsHwCr-NzBWyy1g8(=MlK*=> zI4ebkz^D<&%(--6UEdUAMzNMW=zHx6QTO>FBD?UyE71yV zLy^$E4{F=|u(d&ErlB$>)~+P!g@3UYr0m|lh$Jkf_fJ9zOybM8{;%Fg@C!8_sR zW8wML5Ql%FMe60@EX~h3s7?HA2C%=rUDh|pCJ)Sm(R(rc=}S@8^R-iE;0L+7~OA)V3G_a{W6ck=*X_A8kA+-8AbFCen3 zQLm;}wQ{jwT~3Z>f-iTv)S%rr{n373jmZpX6|^gP=<9>wRw?3cHnH5Ha$Rn|W1NW} z_wdwe`wix6d_3?swL#l+|L<#K8I=7h<2gg^E&VrX`Vg^EvmIpW^Fj`|^bnk>#4szw0fr!}VvHpz92;KIR8;^l{h}1t43$@r7a~@M zm8-QF3DWxld_}L+px!!}f|NfAVGnWbHiIzBqXLDL2a@<+XFtX9in;>^oQPi#{h?MJ>t0q z2gmCn4>H7z*`hc1CDj9c-&HH_uZB03$}$Vy)$RI(FPe(J*v%j{`?ZChYg65${&0MU zVnUFtbjfUcBv~?ar~akC?(9y3$Z8wefREOx0d0jde6JFrgqaadC~jGL%2QBMo-wv& zWxWl)o)Q_kz_YL{z96y!^m?2DcZ!AzoOGq|uWg2eQejYJcLZlhfks$4v*rB9G|YQL zLf1Ie;lBesbT|-8t{j}Uu+aeeyT*C9&UL-x+4FnVICb(7CK>CyyE|JW58YH`8)Q@c z-6Li?H)+ird{)BBr)!;REo4atO5A?aYv07S)>iG(!_(7KD7ymo#o?RZ)D%P4%@wcz zk@AZ$FlG=Mb@lc21^#s!b!jgerM8M{LP{Z7t^wi>SP3^(ZRi_6mMl=l2$AYSOtD7( zQ5c!>5MPFz2jn(3y0RO0izhV^#U8k=ehyVDo7u3sKU)Wu0errey7tec^JeGUrq?2e zxI2lHj<8>hJKa8^0hlx=N0=TJKAwW?dhOP(%F@iT@ka`^2EMe(dC;TpSx4eYV$pfH zHn_x46c@VVkt@<>unN23ah;Jl%1(i-rpAk9XvDpn$trGsp3?VCg(B+dRb*#2K`Tq_ z8yXQEUE8lH02)G1FIwO40;17r1J2K10Y@vXfR>UtXDaN2pYINJmU7c-2_%Aq9I38o2b3rodat5V4;;aY~T zGR*spbj2X}L`4hV$CUW%hf6b{rK#3`TOHVc8)vSCgUA$0`zf=g>AoK5*_9-Fb)S)u zk~%s4som4OeuMxiT&UDaN=irICm@_YCNBl2TyPKE-bBSOm$VQuV~9It#hVRwZ^+a@ z3$VVm^IA9fV>|N)qS!p!ZIDT(Svb#hV!6i5F;hZ~O#AqVMF$L0^R~?=AtmV4S5;N_ z@JBc_#diMzro;Z1vs4$yi~MEx)|35;eeIefYTmc0`r53LcJ^M2Kvc>|Jt=w`GzUpB zX)fk?6xiqrx+;}0G#OP?RTO52vaEjtriV$@!zMJk+F>W8A#CVnwf7lU##F*t{fJY4 zeWl+6UM!$k2o&%;0ze(nUd!%|uDd$!SzR{43hU_W`Pw4c=55EKu?tS3yJ^9D@e_@4 z3>V_cuMT_JitnJMctRXc`)~`Mf3PpG`DWRB z9vVg7Kd_y3FJn8XZ!k}EvsWfPx(rp{JF4T^WtSwJ;EDF;8!ogN@_e*!q-#xw^jP!z+2|8Us$V3jVaNJ}|&Z1h{tteuUAYsU)R73_({Y=$%pOFtIz*NWaZg}=VO zuG$|8)%Qr+@ZpK;f}%c}5TV~OMn|#gt3p0@Fpp^|5L`1ox=0tJMfnby3!AqasO}0# z=cw-L`e6`6BLJ5rk3;(fzTKLAvEf{kVp5asddqUN4V;&1FacvkK&SI7qADqnULZgb z7r7nE?@$;#Gb|iYujs>qp_)XA1)61JVPy8Qhs) zUoBnt8$S};y(EZ>WwadLJ{46H$o%1QOVX1vO44~fVs5OzeS3X63KRV=)j|%-t_Xch zD_Hi!aM$Y+Ab<@o_uQfR?$2{@W-0;S1Qq~RGQyt)VAu}te1JFFnT_oGCYFa61OdR1 z)|7qwICm0l4MzJZI9jQ6C%+^ujA@mW ziQ$Z(oN6t{zEroCu<|%V>dpmcQiTk#!?2afMd=mQd#+MyFE08dMcUp2Pxu@!Zr^WC zURHCTU474eHg`7Pp97||g*-?yi^ZLsquSc*QEQAk`^S=TOY?tdw54?aoPPojCVxE=v1bsU!5U+Gsn4 zSnokde_`4|S8KPJS36BpI$a;sRkM_Dsh8%yZp9osJ1nPM#j2{eUUfRXEX_lL3!}Wm z>HbR1m&3H4;23JM<$vJ#u7~^B8C|qZVs%Trf1Fby?%e6R{?GFJ`)`M@&W1Gq7<)V( z_jWN0zSKoux3cK$t_%w{<}3Sa_33sduOBI+NZMo&_K`s$evuN@<)L}_AERh3Q}hVH zHNNoWw6$)AyC7#p=rD{KdPmO>9zA{a;5{DgQB--4C${Et-J61@5BL&!#qNtN&_M%nsdbZpa@<$afc*UFpE_lB6@|B5Cl7Ke4ZGwW4< z;~XcZo(J-{cl6X<$hr9ct62{rq(hO`q*|kruv=cqnB*4_sE;}FJpu)3IiTv->_bx6 zxPbyu`S3$pXBvK%X))xvrpZFtc$I!~3G=+;GnH7gWSH`KZChDM0b#*{s;G|4d7Jw` zLS4U|tUEaY&ARLU?HQ2MOO4*}fH}mhJ!Ag(COu9TKBx!^^%%-eDFig@{-OcyX%x*s zu3!ny7Hk;ApK%^-|B^{1jUDZT;m;vs8-{tOQ2t zNVO?h$&zFgfQ|+{093}$$J&h1O!4HtVx`@(y-*WSCcvYp{#-Ep%2cfI8y8sEjG2dm zp=99)2ZJ`pUwOl60kj1=1xJX!O?_zdIx(Cp8tUrKB_t1!OukIjNTG$U>00A{ zZuH*^(qh)iRU*mKc@tq_yTSYkjP|G+AO*+yXpYXv?^ZJ=P^eY(8&5`?SW?uGuXK(L z@bpQi&O1VjzA(Wz9zoXJ$GdH8LHc>oSwgMnS7Eu&)V*)jn_G6hFIJIrp-3YX7x(XP zn^yd!OE0F=v+UzZ{HW|-+cE|L!HvTABFGL8+47psd6mkMuBsub^Ijxxy?cB%CEoeH zk7?a8(`TermyKaio-1<_$UR3#d=-2E&eZUM{2eR>#0VsF=_wx%$4`guHXc6BYYGqK~?3?)dez|%GH+5x-^mzP{}Ni(*$jD{7} zAUXi;0f{AvC3e~OH5yxnNh2SU#T?~DgNFl<$~uy(z}tK5!__RXz;84PvQJlI7hA+kI2i!xRgD1Il$V25~or1 zQ{;!q1VV`|B0Qq}lLKvSOG9w{y| z5xEFI#2`LJTf6OS7;?in~Bij74`uH!QE zB=M#0QLLlC!aC6Eg_eB-(yBd%;@j)I>}jr#MbqZSbfhp0jUN>a#ERh?D$3v?urmdi zKB%OmWeK3Wg>N9ovqTe5a_`#wW0=TDs@im?WZY*1N2 zGu%DTEhSB59e>)zqMes#>=3$J7CZ)DCwu*pm&-FTV&Y2C4-sp5qD%>*$DjUN`_Zw= zE&LSQgURW96l7GPCNNOK(dLJJYAl(mJCMo;cARk1t0uT^Crigf^dTyg(?EI`Pllw>>0RkRxygYb+lQkUT;d(M2u(-l6>EO`J(Xe1Ewyk)>5VFN4@NyjB-Dx*xJoO=`)V4p6{>s zOcP0twXtHVTA+^_9b9R|HSJU*4r||Z83d>1IIe4fo>i9rp+7%dpr(f5mFSXysjmzg@E9Wje-lpCGrf63^ z_X+5g%i7tI{cVM|&0iH_`O>KQ%u{5}Wqj2>{f6FqH~F5$qFr<0<|$LTzOSD9ieB6O zCi%Afz87G{mAm|O#E)s0?6@Tnl<~5C%4AX;EohBEgQDK&n|RsZtnBi#1#r(UM~B2F ze~Qac8@PAgE*%>7evjj6A{SK9{4It6-MMu-tVHppH%LBG&f}hfbU$c6kc(DCWU1oK zpF^K{F$XdPjOUFjV6j7`LVpvY)fjflkd9=1h=`*sB2r{H`!92e%$&(#DsXW~-#mLc zHLdvbi-#Z?!NjM#r)P9o$*6*@?}3-b%%rpYB;$s3az?vU~Ah%%aH!&I^DcjW4D3)vo;kHPcbh~=;q_Y z+L+=K4hun7b=+3_1PNR7a?&AO6l!2^V?6O)3hmOJX(xm}7~-%k!T7aYQ}CAj2a|$| zq7jP8JWdU5BPe#J$7l^GSfB1co(>y5Uf4P9La%0t0T`V{Mmes5fj5zT5rYs>wGastJtL_%aL5Q1&dqT83F#!pV%7J+SU*H(c>W%fSX0{&CN?l48}w^v{`p2?Xu}LY zVSkh$wTej07$&7VOt-2yvO9c!iPl_G6*_3`^Pid#c|){W`)uqoyGbI3J!IL0Z#FVp z38|V5LtGAFm>PD+X%c+bI{|jqXwJ5L%>VCAL}z>b=gbIqnRd#f*o5&jK0U) zH=8ya)GeRW6mK2P;~M$?mA-rOb1QxvEENG#xr-QiLPBVw2hmMKQQO}yxRO_3@%4Vl z;mP>kx#pS)8qbiR1Ai(aD&%Cyn0*{JOj#hKQkenjH@uSFcFT6wpHpe*vaU+gBf?~H zUM}8KEAuE;1FrPRt_}7U7&<1uS60wJx_Nqo_M4ZDXi#C_e&@a=XMOhTXV%ZFB*lNQ zvzH^APiM1DViYI#@g&R6p`s~gB_LFj1za5ki0S%7sKGMZI>?- z1|4ny@BV-3<7(vGHH1#l+L(K-@nBX`?wu{nSfyZYoTgX!;bGVNbb8H!|CK zPSWUDF@);LVd5(Hy)Poq)fzAJilC;sg-c93i2doj+z9#u0jcOI>*N& z2tS6YsdgU`TF4YDU~-UM@xASDZZYr$^ou@3ya%55+(`m%uYlCt$F=E;6yt{v4|8cf zgW3T{X@GD0S0~@5Wg=T*+$Nb!VmEzIflKC|F(5?$YJIER+?vXUzBIl+=3ee+e!o~3 zeWQso9ZL&%LmTA&d*{$3`wOnY8Dg#I;G&Ab6>AUL`n zNGtb(3mA`Xz0JMEDZ65R)l{qQ!oVzM{4V6JTx{ss*VIg+M^Ph^$E&RR#xFQx&Cf5~ zZ!MWZ2#DO_g(lsYEci~q6nkZFQH(4toyvA}=Y8XCs6?LoE#XjJ$0l%w1ZUiE^@I|Y zX&jab$+fHAhoN-A>5T&rNs+{|1`(a@48s#-u~Dr>4C`Qc9;Ckc0Ms}}^8 z#|o12RueDu)Tbb2E+s2#%AX@>x2@`&Lld&KN%$;fb=XkEC|`PBYtP*BX_>^ZpmOfG zQ1M5fh@JH@W+yfxP2K{&YMp+6ekfhSANr8R2oi@{k35K-R>SoxAFkd2)RXUwtNPW72ulT{c@yp})x1}dUK9Y_j zdgjwYMgmcc0!KoU)&BWr_l*qqAcs2XreBVEDIg6QHCuJFBv!G}?Y^jnChPR@-zyUc z_J&oUrq7CmygG2%jjtVHQ+BoDsI}HELv?tJCZxqGRlLwijgozoCa=Rk{o_2}d8WxW z*>gP7B}B%9x<&pn3+t+;A;y%HxsZ#Jx%i&Tu^Ep>H<0fviYgc^(1VnxCNq}_7bj<9 zAW8k1kxeyZbBfeojLhAH3}e`t8e&HATP=>7OH2zBdYvTfzYS+#uX>-jUX&*&(&*?C zkmNm{suq{hJq(SN$kLPiP?~)lHKd;6=bs5dYeVgMd3%Jg?zL zr%`iZI!v<$&EZ&*X%qA{(Vl5nzMP%*gB&EdY0-PwfMex%?o*{S1_tGJ*ZZIT9`S_= z%brJjgzaulKO9R(OhpdDNT#{|kf`kATa^FU85~yC?jVOA%R?nTjJc$LGG-sUN-DLI zOs$Oa*yx-z)dgw-GWot2K(@5s8*4ua`$R3#$z>&^A(-HqxoOh;SB=R7=2y1C@T_sl z;{U4C3N2=Iv20}eMx<=n_4cISbvLlATkX>E3bXDQPw6(6qJ$>Q&%gC|U}TAwk6c$W z5lbUhCCG4>jE2@Cao(m`#{yq&b^G|1WLJ0Cw%uG%pm4O2c%)TNH)I9qNbvCi+ioB6 z$|Is@zw}$HdsH{o93yOalPnCMScB^_*Y$ipXp$zXovT^R zsVNy@@0)}J(L0+QpG(}VTxHc?let}e48~qTnwA)iR#ptaMEirWfhXpNfrAddrmYNY%rkwhB z`Zxsy-BcpN z2t(rjnN(@Pkt=r9S^@D|mFof;E>j+if#*UNsb(T+h}C?zx-iK7Js3}8&zsvmnMEP0 zq3%{qQ zM+cjOY0{h&Rl%b%r=rsC*h%GK=<5@r3IBy!jB$DKE_aCDWSAW9#&JzW{pzv`?srYF z*K)5YT0qkzklC+hmwE$eWsIn{Z%v}j#Wu(Md5goht6-$(=|AzR8HNq}qcV1e6vDR5 zs3|9SHmlB|3#ni#sU5*FCo_Ws*XQ1yu}9+tG9$RJ#Tv>_1ccfv$aTf zhpt||@a+w=dGw_h<7-}C<#rL|5hT%vdxyeOh5c)*Hny?i(h*u^rY_7!-VKl`qy^< z9cd%~J!x_g&p~To3{5%kde~x;rYnyz7tYFWwiGdTxjlBx%FX5`kM}xzJR!of(9H`* z#^0icTW|^O;>44dCSs;eOd!OMR~{a$#_aCHe&2t8^B_I@@X$}#J9;YQaR^o`*>TmX zMCk6>qms?1$sGjstl-G~gJFoJkytF8@AHe@`xs%;pF*P$=y~D!`*mkTL(j?cG2u7a zQtXL{dxzh6!}e+G=KkBIq`n3s*a5ZhKlKLZFVIv`1l34XSS7bk6qgKu1B6nUK11Eb99)&g;*{ACoutMZ7aI zXRatGPW16}X#KayoA2F_B%|8zA;C!rtj11{<8(4s1A=;MxIr(UGAsZFhbw!^x_Q-i zhh%ftjN+L;7jQ1LgZCoG%=<6?F#*nOz^;F}YFB#+AV-{5Tf?5^b1U89jl7Yx-WLmk zYhd@qE8hP+u%ZbMoryZBXvig92x6f*(Fc$Z(kAy9y-QwCKLR#h#n<09@TIYVBxv0h zTBWL$n^OwEG|I1Df6a0&8g%~Wf8BVT%@h{wnOGS}(wdOxetKmuoQtQT#|8|C4!>uRHoGzP;hpVK z#^;Na=HYcdTflh26%T6KntwFyW&j0i(i?M;KW#ofytR>Ulm|S>XP&YAl5z&q;!#rmJ2Hroy@*NUbeb zCqQ2QnMktguyZjc^Jl9*9BN1N-hcj`5F=zxdf#D*hCq>V?YVybxujJoGpgan{Xh2+ z=ofJt9yub1uOa%?1SU8_DhMi$;Jk^s5(~$|>x^f|#xEPi`QMi${a@|EryeZDU27dT zj3@Il93+c+ky=h_J|rJIF1H5B78xuk)shuVbN}%pGCGjxnENESGFQf{HWe=$+QbhE zA`@p3$45^3l9U!DO}DiUyk7PzubJ%gBl0A3o&89Eth_mqeGDNhl1_f{>t_(v z2YH(@KZ!qBAD}j1V;ZO5@{)Ao4%RtKnk~FM85n*Y`vo;sRpYS*zL_`;(VK0LDu>y` zMZ}I%9ze^MZvmL98SKY@qh8OMCrIw--SBWNpJzpuRVm90A^3slk z!6p~>n;DZf+ccXUm<#?A%T@zqRgb{TFTjFZ@?Inciu!do(B7@Z`&EB3`MY}j8HJ8$ z)H*quS9c}FM+EU-YxVY-NXZVaQrEoCqTdOmHv(4{@_8=?X7XgUk7wz_T$;}k7c2oxz4FVNt@-QC??ixzhR6xZUerMMS&cbDSsu0`&7 z?-<_?AQ{PFudKb+obwr?17P3#^DP4>7|Z`0H!(Rr!cV@8OwZ z1@K<1eWQ-SJ&i(E(|Do?U z=>Smd3fb@C4R|QHA*d$w1k|QHIcpaO81+C%q{^=rUtlT(jS-V2a2Cxu_>M$OCSX{d za`{6;Ku*5bn=90~cSd3$@iB5-KV83aAfHA-k)==Z4<+B2@mYb1kYL;{ulG$DWpt{n z_$_7G!toray>zlp+m2@!6&KjsIIvNDC1oXzK~e1<`RWI--3em`TzKw$9$jnrZ3#ux zHNW|Ha)=krSm|9z(-GcyvD;5UqI`ZQ#qQfB;{0v%N(NSz&6)V+Y}8Vp<00Z2A5v~N z8An*UKYjYXcQI#OA9r$mpEx`iV>?NAn1(7IPffQfpAC^-op87Te`d}zm$RFr%M;%< zqFmNA$;lN4rQ76AMF;39S#P87BW;?7=ii@L*an((a)(V3Qr((E z*2M$Dl495bKYr}1QNXKyV@jJ0Br34w5dLdzWqBR@t?pLQkO?neErD#c3BL%NzUk0P zN1^WO@05T`Y}r_#Z;)LNWNi|k*#EOdNBBixe3kBYndd=TtRd_>Zk-`x~j zdR5aW;)n)BsH=y3$Ek{hS5NIiz{yNDRSTebJt#F!N^*6?6GJJN_p(#BszU$3EKP)J zq!2E4YM-d6PMaT_TQIF?{e#x-Djo+Z7m=b)Ar!2>XS|Y+k;&fhV%PF_%UAZe^{ZZad)MvS|=~wXgFGjp$ibj$L;`#gy-Yp;3*oYsxYnRk+`!@SN zP6Cg}#)P#VWiwoBFuWBz*&ahZ7u`)JB8NlS-YxpK6A9a_CSELfIF_P_}O zi!uAx&}xX!!t%#tZ`kAdQo}#La6<>C?U^r>eFZOdI*D%Zn#OL%L%iy9hFrNSc;E9^NyhSKbWR~aeynE^*6Oki(ZZGxVO7CK_)nd zp^lZ6@4M3Qmyg(F2=59+O66!v!+(8Ir4Py{Eg;r!vmFBbV&WH4*RPY!f?@IBe~(yl zf0kPbHW~zA5#Ks)#Yu{oQ@^@D-Jt6wsgKYin3yfP@Fa@Am?j;iL+5I~9bAXN1CT*-C%0-&`So+q=#bUC+Ja9{p4mKmoi*9<61) z_I#pd*}Fjh+8Mx6cPUn3(9s3>Fmfi!)JH5S%1cSYAe;e%D7`)KCowZJoJ$I3TQ)M|Qoqb8{>a}lc&uDVndrqm0 z#D1zs*=S-2|4=3eNMW!^(}!g7AJTyQN77cmgq6l`I1&LflSE7g{1liNBeqJRR}A=H zhFdp==R~F#sY=Ft+p8jMvTMvyw&Q?Glni-${;?B|_<$DQAmSFiuh6B;}Vq^94o zv+x3AIlg4^rPBt+>m@nt`u;Qz*C8h>uE~)?J%WVUVOrTw;KI`o3g2crcTjMFRm7kf zvZWmdb=t=gc5-H6(O1Rvy0rG~#6_p1-?!LjrRnd%g?);1WAV;( zPUc@HpQbMM*Lktus-K3bV|3u=OJ^kf26a4FS zEBoKv`ZCk>_Yb{elL>DzHJo1Y41dO-`3=tSfzXe77meFBO_abfBmzPyfA?5RI5XmW z$st)2ZL$a2kNlSUw=sjZC4ID?$;^?&KRSrYC9r}5!8nwHID(v$I;U!XEc%_c*N)Rk zqgz5HOikfEX={{Z%uRb;@3;58*UxoOP9NwBDbi6zw(M(@LdW|O`C-Nbvy`NNML@|Q zbyEi}p%vHMnuU|4_|mSupgEGrBN#M1HK=~a`541y?%g&rb(?&uN2i2Sk}2GV?HuvG z!~k!r_Jp@Cci@uehW8chB)Sbdm+iGB`B5N5=hc{8Y0WdLS#Qgiqc@-^A}t_5i{3i& zI4818;+|~t-~mTXODQGTgf@c0x^gBI(#FgL&vf#^e)q{v;Xz}NOG;QhK8DyzHHrCR zK61Bn)bGt-ROkIFN=N^;V{2hQ6SQ72B>c@Vqkc0Fck`74zh<+65KE2C$t`=(k}6+r zHv;R!(%1;CjrQy^*#^U=Uy#q@WQ;XI(5X(!u_o3)rc z&plp#@RZ0`I!RRQ8qC4_aC5zc9tf}NP&WoQZasTVS9i8ihLj;xo04xsFsX-Zap;Fe z=FmeZGI!p$kDFm+;fCB6KPuVZY{?4;y2`sTmkcdBuBxy9Ffe^;9J0Or+52d0q1tO3 zMx1c;h$xlPZr7XtK9l6E#Suwb3(_-5k64J2i1{lSeHm7+c#0kkIUqm5nb*TJvW7^= zoOsR<0sJGg4L)%WOKoZ3@e#;@_6#hZAf+LIi()B0`v6Tch1u4)a6e9wu^_I=3vIdA z7gkR+U5p2e@@LyOH}9^O*wWfZYC3H>23)v%&d&4`qeT^hw4acKHlPoB+xk^ zkG6~NSU`3xRyOL2H}n!WpAEhq=9kp}v;dz*D7i(RpYuu-Cy2aV-muSFpONg_9;n$M zDQ6d_9na1gB>ciZyDE2)0HMD4%q;CNz;yvx6z^NEV2Z_U?gP63FtPfDk>)M1StjJH;z=o$MDhCycCLTwMxEEcii&?pf`xi*x{zq$^2hpfsfx3L=0l zWIGdZ_b)946Jr|TdC2WKrzuOO3ek~S2~_4{99HjN69VaI;k-fhg|9@M?rs;}^#GPmB<&Y2}un;+g$m_(CoQOHCC#NZzEI zl|YBPbO~Z={DFgy`eJyRXYhT_7CG4^IGOlK749c~7+q8Zr5N77iu%C$;hEofsw={- zBz5*EwH9n;g$^Y6*OVJ3e}~W-rTkpyAzFvcaWq_uaC**ytK_9utkOD0@5Q+8lj-gu3Q%r%RT|8_5i|kQnCWh=KmZk~c zn+COb_{B*mw(kK0Qn@jh7I90m^b(^_h)pSsICXS0MP%W7uvG%ZVUdjI_%@Pwa=79F zOTUj|G^aKN?>TzCgsoMfVN`C)PV^{vW{4_H3}XmpwI0I7*JaC+TcBp+=;0e(q}9od zbjtJKp(H4Yf*jKNi8XH&ZO06e8WAZU$hjv6XrE-lU!X5-A1(1nSah}-8LU}80YOXa zKhU{Fo_Nb^6~i%i46%;t046yiD0CWWKY=iDZ}2yB9Tj|nD{;^ihj>1tu6$97{8vX$ zmtc#Dtj-ktRJ^LJvPoBxw4%#B!^U{5$=+7Aa%Nvv$O59RSlr@(QzFuQSm=r z@VS(VbsUk8AS{0mC@pQ>WWKk-sCJO5uU>XTAE^cjgm98$Hom;H8ue zZUR|PK$diLqB8ccMq<60j?-q$>*nZx?aHW??N2N$LSDkulxcl%{b^04JqvsS0(}7Y z@$xmsFS53l)%%V$yJzKFN7UE$Tm1fQMu2$crO7}9tjol547@yqtu}S@Xu}TwHYA!q z8(&SjzE-InM5uo z9MyGI=woR1OEE&@)Kf7Yk)TaaN02N03;N7^q44984&RgvY_O%Mb=xcAiem$2e1uW#=>4< zjxzL}_2vTH@z9+6PcCIvTM|uu3?qt(h~a@3+1&=QpoziBK^E@HRDUyuti};y)IbK> zj>;l2HLY9l!M!3L6~Mh#y8Bcc8160wG*<{b*qxHfN4vl^S?sM(yR$;E?7*+G8$(u^ zS4V;}T2TaiY{+*+o^e0lm;fg+Do&PoUDS^${cb_K1}m|-}v54^~}>b5LM_7 zpAa^R$+yaX^UPD#9d^WJ&j!2}Fs;#uDO9inn9f`JhL|4h?8Si@vUsQ;$~a<15u6+< zJys$fZGm9w{=q%0$*)gZqkH}v2Os$G5D(un%oOEhtgJm?saXZm?!+(&Vp))b@5rM4 z_lQR!Fi7f>n&w7j7aho!XNDLX2>Aspn5LxA-UVFn(otZ|ymIx&eEsXBm6hRBXSt5_ zXu+Q~=x%+JF0M|of1dxadbsDQ$8lwQd^1FlxXBKZQv_l5UedY$v-Qpt7F)+(`4SFdnSiW2rZp#e* zP`FwKY*w>@A0bBRAKUNDW&a-fP3xypHi>&Lfb?TYEo+Js!5;7S%D?>(X$1O%v{zI= z{~5?EfP@IVkLyuW^H^hO>sQBptvcogtQ_yi9ejP|XAuhx>-!DCVbh79?C8Sbgx@8K zy{Dz6&k_=p{Fdd?nX@2~|7&9lra}BOQQ;Q~LrJ4SM0q9&sQ<;RD^Gwp?*Nsp z^s^89gw#+WJ1Ak2r2H7j+dOoU_I48bhwd6p_34X)x*=paL>)gNqS)Q&oa3sdw{~9w zxF|Bco_%{mig?6ZW{9UlRU)s};3i;Kvnx(bLB``5_E7XX{>Nu-H}VHdj+~KVNmb z%q1K01*Yene)sFI?-yGf{RJL^1b}8vhdBq?K;+ZI_@yUz(y*BRch0S?({cwn6g_HZLv+ zF){6h@Ze{cKUs8cOWZ3>P#b12&9oW4FSXw=tO8JR5;0^07R(dQH=b1HwJ1zqwQnMD z5=K~AATc3>W&x2OKzAk8RX!%61;TwWa=$MxHcd*RN258tcbey2mSAcxjq#Z92rclW zcc@fdmbQGy9BiXP*OEU2FHJxv2JmmXi8oSyc%3*vMD-S2u$4IQ^{yW&^e4@0f#&Ho zypmE^J3LRY_Mn1oy&{ONY=&@N`Xr`USg~a!%+1p6uhic1i_RM#VJ&-tU*fZ2o^! zow+5J>)B)GiltQIEq?r|W9pO%hm^c884DP(o9hKLMXJS_{H#J}AIA4SSxBRu*MZ;r z2_)(2Y3LUF3GCWQfO}|^guCIrGew+c;Ql=ABmH`?e1su%$qd|~*wUnZ5G%vG3&dUu zLKEac8ek}>r*%fw;T~m;3W4|dnY&Kr#Tpo_bhFGO5n2)K&w(oM=5K=KJNr8lei>hu zJ&`&&W}|b82!4o?Wgv(6u$(w-X)IF+9u@-@7XHg1*C_fYuG|;HWTJ}=|uDZ>t zA~7b2cDdr&YVTcU@zC;iyNJP5cBy<@t5l zGkT;C5n;mNsH|8$(UJg{z5r+M>N@lukY9JYhXm=kO}da=IQK?v^#{!rcM97 z8>YQ+F01PHO3KHLlLtELeFf$d6i}bT{y3WZ{i+)?X*4+d>m-|~D;FPM-`N>QWbPKv z#PuTAx3qp_F<9+-X0f`3V}N;!d~pA7ZB~L{=+Yhic>ADGL36YQeXO&D^T zKlL-cSEIIIHbKn)`j#%okcxbi>AKX%g#{1R-=Z_K?x*z&U{Iukw>OZ7BCJdUQ|lQ( zAbmv|JaYUYGaqk5{)reqwArfjdEyFK3mR!Ax!>%dusEQL>sYEGTQJ~<>*L}QM>GiO zPeYXt4VxHp5(5&so;-ed=nVu;YDb8>ZiM8oPdIQVEFQ&NWS&1G>+0)oS@6GbaLeNg zX@tGq88N~DpTvOM%5r(4$}^e8dq^0TG4%$(29^%?fJKb@ z6i?3$4l}~HBX43m^< za*oz%{MK_YZov)y=5o>r2~AXul%kWWsi%WN7z;@5>oAVu%}G_Un4*@Io8DczP{E*> z_~5XzD$aLWu=b0SDhVPmfQavnJcN~F74&)t(+8`bUwaR=v=mL%jf@;p4p!VX!Emf_=J|0&zb%aA&S??Ju6fE*-B zEdxTNrF!P4fYs?r{q(0GB;_jE(IgpKKTo9h`;(ZsO`jvkVhV(|GL@wo5U}73lJGjb zq5y~1Q@+gt^Ahxo>}6)^oZI-2-bM33ZK9e4YU$A1bot3?G#Tp@`!w^VD#?rP+yH#) z6(eO5^lhVW=oS~v1*~>WgU2|qoJNZLLkJ#vu6}y3*~8QoGycwgmW%^n8FV>n1SfK4 zBGm$BCmq@mqzG||YQF_`@GC|xXFC;c$f!pDpMH=q!c%v|wHYk&-}S2a`LD<+X8z|6 zJfxPN3*NcDdy}(l`r!84z>;{R!X@j2W3{*#U zoeFHG$ooA1#P$_?@4Uo?G_B+=$h3H}Ry51R6euJTt*X~wqVg*tW#7W&AYrVN znluhUKp}$g+*JQx!l2hXjK4mQGw# zIIU`gG1eGrlfPnD?;xGTn<<^Py2P80TJFd#H`Rv)Ia3-XG_WXzx73Mwdd##)BC495 zo856{gr%k0Q(n-EEEl69b48XQ2IEl|y#>;QWI!SAf{2!~7RhPlJA+U?xw?~)FO%_4 zC|Z~;G$+>SA}BoQdys!kP2!AwGwSUKjSPDCB9%s9w}lx9o!HS%^BO= zQ)4R7K)5ZBt=G8;kc(88|3F=&6o|`&;OQk}2iC=GNBUyE~4lm<*A<1>L4m zKA$Hxd5ExMx-+j9&p=aHq(Xa5JnVJ^W2nCHpY8d=;AQ-LV=Cz1Lyy3-2*|{N zPz4R`n;@xZhGyD0{=Do#9#kZ*2!=7(aFHlF){GG7X2GNiEM#^wKFDQB=FS6EA=|Mp^IkbQZRvVD7ez#es@CH&?sJwra7Tug*ksD zxxT1MQ#Om{3rBdzs-x)u>qn!_$reFH!*dni<>MS+V5X#lwh2k0 zVkOVGw&ckwAo`jR`{y%WwS0Q)8IAkA<^$o0xpexf>GO5xyKy77HjZ(a{z6X3PprT$ z5Xvgo&Yxg*E+3}xPAlAx`MDS9eXa+urSc*U+Q-7!i8(VQkxG-x#+!0`a18RTA~;rH z6O~Kt3PJc_8Z1V5qZ8>tlK8}ax&6&%zl&yWj#KaAojBE}R!p~d|4bJ1^CE3~oIfZ{ zEv%9*kPT;3-n8pyT?{?jq*r}3$)l8se}{|JzT>}(t~|MjW`_9%L_7@Y_@#<`ES#)l zGBwquy5l0KLRo)~-xDYkQ^n#xO{BN-#3qPh!RAiBNsR2~&yvM%MVP}_hUhdzp+3os zYyqMy?(Tg=q~KLae>8^7*&>nP1S3p1ZP}sjS*=j5){uNySat!253EqiZdmd-jK>?V z_1l|L6TUD+gNTSRGu3IY;Z}4$qkB>a#3E#?<_6bH zJ&ntuvVr!~m#XhVQ4qgt#v0+G>gBS9S@^*A(>nQqp%qe-lOciLDnx2IZ3VU`U`(_= zzlYb&TGY^tM4X6*K2r{n&0?C|5}94`zaQNfI4jwDDU-g6k$BfAl}E2}Q=CI2epmo! z?|7>aVU%LzSF9JnlXtk@gQa#2%FoZ2q#wM-;qmeUG3OAe9@GhG-5D}CI3xse;zw|~ zvm<15rDuD=S`^dFt_m0knj?O9b8~e19$v}-CQ^U6XmcLj!-ceT0@Y2s(D3;m(5+GY zfER3yy!rQ%bZL@8JhkiR;o*1pjFA2MmtZraXX%j{h$8@#VuG{f4D0%*E(d^#cL}}p zBaqhp!uxuqvrg$LTWtCMD%wt249*|>gw%geUbUSEUI+)ICmT7STJ*L87Q`St}+clt$*jL6)0wiPmr2?*rM;9<^1M4)Lpc%S|^ zqklcB6qf!`o@uB0LJFt{3i3_0LOycZZvhI=!Em^FdI#zf^37dbp_D37Flw*D2HgMjKw74 zzY>KX$&#(Ys13UrmvZgYc4YCzqH9V@YRkDD!1S|=)_CrdG|(uS2So9o+VXL$S;L$0 zc=X7yALA2=b3NZhNpRC+l5Q&mc@bhxVk)Ie5P>_bwG+EzdV*uISgzkP17waU6gi`m z3x(tLh!9Cf->Xt<8AmvuNys2&z`oDoAE>1n7_7yyli(bAwLDq(BKZOH+dR4upytIf z4AE*vcXxg&44P*&;19}v`(w~K?+`pb>7L>UYvS+aX3%{(7&uno& z>BU{LFDwP_BGG&BQSw1Dj^FF~E8eO%>Np{JF@$+3h=c1CRP3d;(jba@u}2J8|26ep zGOKArc-(L6IhiXh-0yanS?s6k*h{p4 zc&S$^52s81NO3+t(~JMIE7K8lguYx9lt@@d*2N+|abPM8X}VwYdjEFue!U0C$%Oh{ zM+tOEkgZB6;l=$;$g5O-^^P@pnR(mG-Xie5ByeQ@6C4Ytm9-gq-WJib{n>%s+mj{& zIq&K?4)lzkig!sdYRH_v@TEOIkG4uPR+VPLS(XTze74qg4@}?4Be41J?=--t2uNlj z`|sBW-nRq$Vp(K5E~nJ|Q|%IYA!%4@|Hm@el;lOpAFHc+rW6Q8ss|b$N=x_0JZ6W! zj-XOZY=Azo!h%sCDC9EWex+Ob){AZuUHuH|?Ng?Te>#o!Mt*)11gpoUbb@qI*AZyI zcPLgVHMx(Y6{Z{)k=F}sS2Jo4ZU;p{IPVD}h@@?9hEZ7(EOnYMIOX6A@y`CXLjiEn zlILQeuysYiD&z9)!R?j6aRY<>yc-(CxXu;t5#J_qk0q>O zV213$;*)Qu_6G;Y-b8rZao*Qs??<8+W?j!7FzH)|4aj4mjdK~2BsP4(Rf=PCogXr# z`~EG{t}TwWUERTehIMJjZN)T2_P$u|D9TlwQ!2qPT=H5$8lW!u_#2#1i>z!VRuXGSrA+CFJ`k~(G{T`fQN6_o0s~85x2=sfpBED_ZW_zJ=p8pLlrO6`T z6J226Ij8{nUN`y@L{#)kkhMpA+}3j#$z8^uUbl~8-oTdV=fe(SbIWjsyb*?A2>84l zLTCrStLv`4I^p0pKkVhPnAsHdxi-UyR1ZbUqW>zJupIhKKu}~j@EtS z&jriNxo+l24j34*HEJ?UdO8VD<|1w{3=N?irR^Y)$1z$O!#{nSDfp7)4!vhjN-U7< z%JEpxhJW>`>o=Y}&ey{tYts0+VFo07+tfWY1OW830p%8u zDFakI{m%DmK4dQxp_oP>2gOwuBjj-x>;Gv1Vjt@P{K|zFK!IuU`G=@0ORYp^kc4=) z))w*a{v7zv^ju?D$Zu zJlSMs4#MvpCab8QgNJTb30D@RM5JsAED1-=Nn2<@4Ffv=wQ>c?@{&VJrc~kd5_^S# zs-y3~hdx*#+gnZ{OS%C+h>0l+t<$(!#*Uk#ZEEav0OPv}cc%LxVV)n5xsYE2VQ6-83gq&>q;n3Vi zBB@Z0T34vEu)|&3^s=+{y9U={q!73^4X1W3L-u2=h9NE~XHy``cN>hc-FAeSqupru z!C!<%ED(m4rjbOGMwXYl`Mfz)ijg=v#KK5{p5_A-V+?3J-C62El|#R<7IKMMkgy>a z^WL&JwVN6?1%b`XL|s!m(+4jVpXRkzIhB&0iDYA^1;-vM8ZVVAli|s=o0lkN4Jrz& z+csZ+ea`O3f;{g`vatczoH12Q@*R?AaY2FC)!eNYD<>auJUBZ?fEYcCl>Ag$>(ih zo&fP21D9<}S6C9s%D+6*=XqY>QSW(*?2XL*?oz}yW*~Nr7lgsif_#0l{^8^^457Gi zhJ^9E!`|ItsGz{R7f{tOjRMT)qPe)sEYOJmHcOS1%;4(ETG|>6!zC?*YfHq3_(N@0@YO1N zyQ27rvokua5%WooLKJOjCbGA-WB5DE(>c4yKbb}&leK;9xZj-;@pgDKNfbkZr*Aka z3TO~jQ}i6F#oUxI3c?UWgNNT{BGRp&--vW?6;s;W>mt##VNN&LnC~Jb^}aDVisx{~ z)3+dLZtU5_0%V>8-u%Uw?N-Kda@j2rpg%69IP>Pi;_s6qZ;rFGvW&gFJ^}_3VgF~U zue#lEVguR{z^ZRuh3-N&kCvX8luYc@l|D#Y{P*=>$bN>2pC4Jr%SuNSAd7U-3+?F< z0Z!uf?SesHUmv0GbN>4+D68vjakDR4juykk?~W%kfYpTMcdOwCt@OS9P5T=sR6?T3 z`QOaq>T2QbLTbrBHEHr|0>w=~-|lK@NMrByoa^ar52E(EE6|CQcRZY_!UJH=_c?VU ze#c0|P6({&TT`Lun?3g(WIS$$_!J4W1^$P4%k#n>cUt44Bw5tconiNHu&t$#FUW{P6nchdJ^N~L z@_7Um^2VU0*# z-?-vLAEWNc317>J-R?2n(Qicu3=|BwkHiLJ!V%D-Bd(@r^l<&C*j^;M@1zu&A)0lS z%M_e^Xw*<=+ronDw{|&&8#kYF5yHU{(?g-lUBTo{P<4;7613DuM(Wu@i9w4{3Kroe`j* z@cs2XRB=Czn%GjQY(xD`)Cq@=BdoZHB8AKX5!n<*Zq)Dfd-~V`^?Mn3BPdG7jr9B= zWzq!GZ8U|0@)_^8ZZP>=qu(QuNVZsoHvbtKTxpy5D@*eMo`5c|_&Ur|sxEFlSyZ)mi{?*54E7fzUf}| z(`k)?VK_-few@?<;p+kp7$E)m_3@zCddwI$n(7N5-rXP0qL3&75MIwdX=Kf>pIoix zn{r7rhivk=5CY$LiDrpraP8vh_h|AFRA7fB?hL@GdUmcdB(bC*I0Wdo#^MC%cZSQ{3$9p?mQ02<{S*Cpg^*rmb{u?ItgC({8}aamt}*s{AXM8A(s(U+eG??q{9$R?)|O z2`QGkFCsI}d1-_UnrP*SMDq;WgFZ7eR4M_bPFNld%p80^AW3zAmEv(KT457yS){9WNH^-`+ z8m9RDN6f;Bcn7hDVj$llw0HGJyUssV*_^9gUTexKMPz0AVa^;!OUvB{8`(JnEcK}@ z^%@qlUq#fmiGc)oRH9^(h$QR~sE$l(#x)}{X}lPV8=~1!4KbM# z6ZAefinmt{n-mLKaJ=70LBiEH{_N~pkrek{<81X`P!z|wV`TjQD;^=!^*FMZz2*6vgXQ&%Si*R8Em<2m`hQi_`ctlNj z-=R&OA^;|aH%y|i}Cyg=;IXkm#Xb(Ac!ce$M+MhZ9g4vSP=tXs`bm87!Rbf+X<>?g6 z{y6+ax(WZgP*1(Dd1Xb%+@{c&&@B0|kuQkA%oOxKq#8^dMaNcPrR_qZ*Ia;=GG?u+ z79fiU9^SZlMjr^Ba6F!eT`qzpAS|2L9JNSv;riQMR?(InkZZ%^@TEd@yC|jmBDFVA zXYU|UXzEyE?f6kFw9go`Ek!sTb7lx3|CEt|X=3VHDwOl?e!CXeA!4)UBb=FJwvI8& zAI(3y&@-dhJB06UpP~W$_ci4aH_~^>AHy=}(^JK=H~T_sY^k!H(9Slm`z`Hv**@-T zP95sY_5m+#dbZ!bZQnfO0MYyX0LrC3naXuaG?l=~W0D&E@xu4J-aeI%Dw{qN(cc!g z_gX(UdDb6oh{^Z{8WqMnQ#6_Lm1!|zSV|LF$#%ZZ9L|QiEgsA$iU*-!+F9wHo~{Y< zmB(4|{q;F?bwPFbnfn_M9(#%t_?X4*BbEwxJF=Ml)QT3ygDkMl-V#T0MT&pzLy}r> zb(pVIvgtw)Nll8?Ws3TtE3RJe%XDbPaz%Iy`LEm zO;lz+{BGg(zF7sJ43h)nWF@tv1qusCqECg9x{rA!>izpuH}kHJPH~=kAQMu;2v7s= zUHg~#>3Rw-UCf@>%b6l^13GoF>BLTD>29vjhVk?Y++Pwzi9Zd)`TkAtbgQSw$l%P? zh>W$~TjQF)j|-u$JW0oE-Nzx$ZowI7oBfquUuhE;qI6yGrBNy&gChm&$}yqx{eT7$ zo!-2Vjkbbau~H(%yk@SrbsEyL@;%Wj&iW$~v|)#iWj^ne8z}hkkJ{l$NOHUMIWSjc zy2F?8wU9!s@{iXu_mIq#3W83nb}>zwfu}YK8LDe{|`BC5zmYqQu8D06F z;IDOr48;^HU9j`r%*e1(pFt7=?^9wJ8~kVR`{{1XFfAA~!72~2Na0fKy*TU~N59Gn zb-q~e3;(s!gtt7Nw33q~weT6ll=zwO$~q_wA;995uwm?EY(VC$>ZpyG*+woIhSi=4 zM1jwOmFwx^lknE_V+~^4aFN(|=%F^S)MjI63~7m;Avp zJ)}ZrRJgk=cp+HRqMYZ(%LHh>IR*Yv0rB>Xe}8{@b2#&GK26ysC^vXbe9<4HNc(ZW%2LO{zz_<}J~GTFXPx-< zdq0Rb!+DU8n^aCc!kf{>R{_0aUIaSSB!vkq!BWDu7>YWC zllqDApl=7qBWwGvOAhE&W@m_kN(ox(fvXrWVqw0@oQDkY)zzkCk4+vEYFa2gPHX{7 zaS#1Yq0RX&SpL_hkZDsXRAT3HSf;+=5=Wn5iQ_EpJbB!fHHh?Z`h+zQGcqBlg=m6@ z3hc#QBE7z@_05CapKnmCj0k(Y`C|~x+y(0AtCkJD+|U3Q15hVInEO>oo&aSDudq$c6OIg3$`6Rths%%x3*Cf&ef~>u+0yZ^rKzbE5aqc$yzxgzM=L5=xZfOL zlL~kp-G6NyF8hG@wY>a?Ub(zml{oC*4S=jf%PuFB^vS0x zv;k>VI3P&uhup(+cdhv0cR_U)P=2fhP9&PF1v^n6c5DVC1^5`d41$9Q_XtrL#$a{i@V=#e7Vv%tB`b2S-r5v zCJ49wqpZs_P?2Ds-zdqNrW6r_r``2$hc{PMxcyCvu&rn(QCV!4D{T!^2z9Z9dnW{KNyPax;iXyp zqd?H#wY(myS9qc+hus7trFII&x*X9BUEM~&;{(k7BuoQ(xJPIBbe*7Wju0#XX+!pEK}Qe_>PnHI0wAs>BZC1P0?DN$YRXqV_b(F(WKIoM$q{X1MCYyLmi= zrlcjMYBgb2E}&^^kR{FNkuVP7N@%VUYNW;D()z%c%GQ7&0)yU<-&#XTHFB(uEo=4p z34RyBJn=cz%Ajb@ZOVLmV`=t`{`Nf7A#5b&)Jc+y6{WnkBPotg4yvIDsue8Ofz-3< z6Xxe8x`qDRx8_Ly_pxLE!KxEfS=~r1ClPtntsqcVZ`o$_`TCddamAhsYgpzbyG9Lj ze|om))zfHrJ|E)YH`D;9c1>WeAhy!b1c+K3AUE5_mFw!L!^hKwSpJ2Myyz(9C~FMF6SuXbQ@b``;haKlbmC2pf2Hw1#CKi9327D zHn5%sGWcVb6<|P^p|Q%qIKafl=F2c$AneI_CQtRsw{igdBvH8#0k!AGk@q-^!;Bwv zXi6LmhABV@l%-EtTw4>HI~MwldFvgnq3?s@wF3YA&_))w_vZ*Z;Bx`^X~G70J^hg3 zn#k2{!$C}HQ93GsX_=2s*M@-11#s3v=4 zfD8V?l!^RaNn%^L@cn-v))&@o3P8?=YEeC-Gp0G3e50|NuVB0G?|$v+tW*7022|w!^1YnYk-sVRRV%#P{$Sdp*8^~|(EZD>K$=vM!_V+#hGN?s= z(SM(CIGbR>21=$y7SWY0%90fpS0BPI)Wn3#@4{-~;Tr!s5v#$6F0lgP`_ntb#dn|S z1c5AuDpP6@-H0FHuZC}G*^t0T2O^lX1tmLq!|QWQIG>!JZg%wyC@CNQ#Zum*b&6;F zRgp`KRLFdA8#jV(A#BLq)*DLZ3o0huR6Bn#QWb={T zNGsi(;Q!Hd7G6=cZ5J1m?rxCo?i!@KySt=YS_J6^>5vwrySp2PM!Ffgo9{f|TJL{w z*360f+SlH{Ey&TqqnLAre{o~V^Ngb|-xoLUSy&^{~y_3%7 zboM1L!3VMFQ~gs01rG8B#_3`kcMb(2Bujt{!aH~R zc|d{$EQsl#bt=^;H(XD#x0U?{&irJ<52MNG8;VoF6BxS(Vhbzk)XvrUhw<_cBOwjH z*y{L2k?|W&R!+{Q6F?5b|B(m48NR|B6LT2?UX~C0+&CtETk(7a1`kv$5LQauNnJY0 z(E5uL&O!3Jy>P!8o$rrGX)dTj+-AB+*%HH2vJ#u#PsWy*Czu{H5j_<1#wC)N=E#DA zg1{E&22>Fv6RhsfhTk7ZR^NO{ao9Ft>PPn0R#t{jf$5%L>TaZo1CaGA(Z4K6J7vbp zY^k99%v>Ox9kZ?M^Qy!v&!giFNH*lvVEaV8WzQ3(hC9g*bY;K>izcThQ~w;$(3C6~ z^T81O95n#lWZb;tJu)gSG-WPI#Iya|7R{=r+C{oP|6EIDXxUgO3r6uHKZmY~wG$rT zIv$dqV#`&!C`cM|4mI*>?hcPmn*+29fL|WefSZ~+S5t*YwVW~U2B<^H9f%%=1t*$g zQPcUcvdx)PxZXK{+wO63N)^|et147h=}V##O_Gh=*tL+69&9iuMlqfAM9)<$l^BxhRLTLM|?ea|yV?Z=rgvo@EB4oc(Ly zhpa*SOAfjLzB3rhyC%r5J@6l@ZDdP&v6SKT zpgLTnhHjgs5_E2n2ALvXQ#1q!j~~cX8O8kW^C|qpxKUNuC9a{7va<5bxwfhnt)JGH za2d36j|xHe>`*r@v-A5<)j+bzcq7)R#O!2F5+v%$@9((;gnwabVoJrbZw;(E}?Q#q)40|3#GvhNGP=WhJD>oLbiL!Mz%bVBgMhDdwsqb`07j)BQWiMPc zw})b#$u!nZg;Hc9;G#6y znzDi`$BT&+^d3~$V;Ff06`zjX>x1kR;DaulB?BF>@XA@Q{v=ym-nU$cQ4U31Go_H& zFnA)HxXDyP>3`RS8=?BJ(!B{pvcC`0=luJ|8Did3EeHJKkBqyw$bao90MGJWF zKXHgNX~Rut+A93c37dkzma{WB;m-#P$hl0oZthVTY#~2z^=NFiILS?fH&StPi@v~h zgP>c3r2#8>;rBwUc{!1YS((68)#th^@ykoLukz~=uou)5Suu)Qjp9hji=9rOW&seH{hKq>@YQ#BBQTTw!w_$?_`;Cq;KAx zuGY8!h>hP3gK&U=Yb8oDK4S4>%O*qt-pR2)GMa%Kd*E{U=;2aJs@irz9O#P^SMOS?ai17J zvX8&t#R-O0Y8ah-(6T`RBqvW>%VnE0TLDO9kPwq(e}NCGs7NrbLbYt5Y703x*8B*R zA_$3qM04c-wR&K2OkKWQU~BSAET8w`M;Yk?!MMIZgaxWWJ`0bzoax2Ru}q9?ne(8$ zh8PHI{O4I~Dxp3})!#-;&d>YILIE#Jv;hlC>!g%p{i6_+sWo?jqU+xGbTvdEK{De` zAP}*&O)?AW>*xQK!R)Wyx$}sCRi)T98}XGc|Kqi;k1o71qe)eOzt|Cbr(RWfNPhhf z$~~y|?n-xG^&12fIV{csea4(e%-w2PoOsXbz{DnIg}`8gy(DORv$~xU4JLyU6_bEm znTgzbv{_%KU<43sD;wQ%o}FGs7RPs@FeQTVWeU*PmM^v>Q~{UX`zynKcVRe6M?5ZZ zj^+14f2b0hiCMB=N;Jc6M4yo(o?8^8)n#?Cm5XBo%{~q0v%I z6sd68Y;`6`$oRk`^dS>DVGJ(G7$wIg6Hl{@0MXEV5WhUXlImWjaopv1JbH#vY6uJ& zc4t9}j5ICL?Bt&0Ts`a@2_9ze#`K}Kh$q3vcdRU^tR4Ya{8M(t@u3u7oRB(fwoTDv zg>ElZS*(hRAa&TX%nBK3zJs@ED_IG~IDsmif1XeowtgZO5S&z zTvqZNP*xVqc)-JvpjwJBTYdPAt?xD3Joz4+p>C+S$oxspD&OPr&;RvK2v%(_WNQO8 zGF4(nZuJgL9HB-DSQZrgDlH-^sl2Kc+>!ZkMSP(JhA#_F?~4z8%kQCm)@aq7grc?o z+-lt5b6EK4eUS7IzH7n9!0jKA@N;?^AK*D7P zNL{LPPm`!XlNm5_xVX4rSW@IQ8XY zo=-@q|8%v<<^Ig@zt$mf)jPAN-{|tu20pqnv_c++I{;D|a4*qxK2A89fsDVnMg&wz z8#;D%5I{^4??pe6iS{C*rG{My5m?vg%xS>0i~chixtMVB$C4fj`?j^mn}8?Igj}7b z?Ba9tsi3UCJw0D!rS~_j>FvApawbSOCF{VyYg`Co__yqDYI=@8Y%r8nIC=lXZw3Bd zQwNP{PZ>l(;x}n*z=0Qgffp*mP+m=fDXHFQBZqCXoFan=jTiqJ>PNRpW6n`UYina$ zHZxw}@VMJlMdfi2Y*5jm1{AsKVA{7QqkB^mI`_isuENo{Nv#Z9)H>NWCG(ZY>5+9@<5sVqDgZyw-*e(}M}L zrpm|#p6Aq;&sJphI1A%OsP2-Y{=bB_uL2>0bE4u|@K3NIPI@CGusq~8mL+z~yG8k2 zn6-_Nwm1Q6qH>DHqRZPaVSo3SwJ{begGCLL4caQ%TUTYf$`Dr0nazk616u0H5_%S2 zg?@y95->|S$nenUmSLSj3lYMY;iw#bsF6Yr6uxXhSInf1np9K`aa8DP=hSpI@m@Cs zuVuXL=p{4!Y&@aDMk0T?rpvyst5H;lhJF@vqWQu+g3M7u$fZq)j zWCwQbAUU6H>72dYQs@Jbtj6mVk+`^gGT#B9vk*JUo;R`GuKwIiCx(Y5x)etWDPvNt zA&5$pjT!+MXf)-uc{NC|_d*TPq35?}(Y zzbFM1;)ucQK5a9rHpgSt3!7QzT4?8CdFdQVe%JQnTU!oq>w&Ku7hP|x@9|N41e7H% zv-0-EN&Ku`cerq2tn7l{f))qW*A<v6a;F_;Fb(!9@RTrMF1RCSVHid<#ym$uR61L)KBV|y;*zh>|79{y9k_&Gx}b$tqv1(Srtl>A!+Bj{x3L|Lud@3;vpBbY$k+TlEiZWB*@!t^@Ww z2QxF```7*(+)jk$Zd6-dPOB+^n>9~yHIod?Whq2@KhVS;DsiTU8;W{Q2NiCvYR8Nx z9ha^&)R9cL{?Y#)G#r)XMy}T;O5d}!MSfenlCC6$FmtDekWsv+4VYZK53;@f%Yk|y z{59T64FE{^A|eO+8&9|!Z+A^I4tU{owt<0YXxcN*MVJxJCIS`R2Ho; z(T)0-CuwBH=HG;FfRi{esi(YL}45dMHrv+252ozkd%if&M63gsVXj?qM@Th|Fzg6LniLX#P#0$#CGCPT+h9^UDK@Iz;iy8<6t-*lIcna%6n z+Kp8AXGBE4qYxR+0o5k%e0n^Ss?m*vyjTGN0^PGHQTrrX51$DjS2TPE(JXLx$n@fU z=s7w<2;^x~`yIvYLrkHQuBzBT)4h_iGW}TXySED!Ntcz)N|dB`Vj zv#abRDT7S8(tj6>7xC^y7+JURrq>y;`pJ*WMa}?#?uLbxFJ?zR?He{+X6nxyE%0yK<0T_I{T=Nu-tSb@k}+a~hp` z2bza2rO8}8U5^7r%=tz5snHBBzAYuFQ6yFr=0UjRQTzXoI;> zfD*c13SakpwMdurdwc+4W8*HJh?t=mCHDzz7AeOi%Og3GJjq3@gj%gsr^`x@B%85U zoV7~hD}HYv95^`^E`?&D&gb@E(pAA zZJqc9@fgjT#+dTt!jU|+vJU?(JH<$Hz!RGkXajQ*tpDv3*lv|t(=0dlGcws&N*o1C zXwb!nBo0q^Xw}G{a;N9%cnV71dZ?k`Ko@;Bd8za^o=TgUXp{<1j)y?Ed5Wvua3=La z5N{xrt19CDmY3}~k;cj-EmV2Uk&42|gjkZ_Du1x%zZ>ka7_yN1&5Dv&It-Pq{Pr08 zbHg36WPhJHVn`Iy*clz}9M?xmD^KhRWgQ(>u z)4{IwzSWyE4MqfLl*IH1kXW#6!E%sG@hYmQB~U@rzt|8k$uX3J@re}FpfyqwWkt(S zGKkA zBj}ib2%SZ>lKF7TUknGkk-BLh2Pxn?;k4yZ$#=G7XsQDO=@&pI(1yM zY2a5WWS`)KT8Anc=+c3<1DiF{oen@6c}j(nUtG|*jU0G{0ZI|FviwHx-(P(Hz2D@N ztia0>A;wY3%KY@(pT;O*H!^SH&K@|^J6Rd91KJvfYoiCuX2L>{(@*@v_`Y7jj!(5# zJ}X&n6d?`jkbg2<1?tbHjaOwgp z=jQ}Y=+L2JL;?d&2ag~Jc*m~ak!Le%+pPcS5n;eaA_Z^!;JMIt)T*wRfP`xj!Nahw zt7|HZEU-Uy{fQ$kReJ6=!;kB%VFGZec)dm!m9}eXqn(l1F$1%tO+~s=$*XTf=IS&Z zAuW||Mp#7H@3N1q{I~nkzwD2&REg|^qyKQWiZpjT^dj}N|MBG?^8=j=KBguK6(!sA z5Y2M!-MmCQ0b!0uxcAMjodG=K-C(qUlXD~o`fF8VclQY`{T!-@IDRkG5|pZc{t*Bo z^?LRFDs#R1@5|yuvARUO_2DEQxDVBHtwHeKq<sJlB@y1=-24u7j?5B><2<}& z&%6rbVw4!_lV=yvag;Uoq{WU{Ai7HYHRU4Y%$(3M6hgqt$?&NoS41LH&Hbif=g0Hn ze}WO~)P4yo@-_n}m{_rOfJ3bVu)vEi2WzP=KP9(bx@Nov^Dp#TB&wts$>EeT<+vx^ zB;{Uy8~@s{A`AMZ=Gtm7-Dns`!8J&U&pNhQSzuwn4HYb^%Qk*_sPAwy(*A=vz|oG! zU7rg=-3!)~5~KF}T7VSO5uoS>h1pXF+qbk#%27ml_0W3L^UY?dvSE7#`bl7U_`;(g zL{aGA%V(CO8ZWk>V*nuGymnM#oz7ah_ocuPK=3H}rpG4VRN291+%&Eh>FL@fBw^4L zPI?-KWh(f(aek~bFP|{e(aV6%9X9D8%_rOOjl=5vRy8`esKsK_l)bc87dlaUh!=Uz zJX@C^v;;R1eoFVnbv}#+?kYN-h0ef z;}>5y)4AW6x!d8ldJY(~go^M^w%i)o;_i8MYZ?~1K^g?G(hf|D);0~I1wGWl)Kc3G z$_u(>Wu`4g)p{&T<#zQr^(*Ws-*CO6)HsYFGy(p zc)KSP#p5(h-lv*DDqX{E=l;X*4#w+JTWJCCU#khgd6?eP03drqOS) z111~7?bSB}Le0D;OzlVBK`9xN$B{5&SK zD3F0@4mSIP7nl9q>HwRoJWE6+SWt7xT||zu`ksr; zEA=G0pDAw#xjDI)j9piZ|Mg@5eL`VEeh=|Oabzxjo}(KtkU(MkuQ!ys0i-ED%*C@IEFZ4?CA>(O{NbA`MR%#UG`DN7BibK8pTD>#;6MUNR zb!J6~0-3+dyETbsiOb{RGrutC@G>*h;M*apX=B#8BUhyoY;rKCy7{@9Mw5#rgPIXE4;4)?}Mv53`C5o6uGAcU=%a39|mP zs%idRDX5`VyRPFn<&+n5@DxkSIcnh2E+85iOC>8?40l*59**ijH6}T)9#S?+`x{rX z=f48blI~tQyASlw(vGcPh;>g9X-u|I<^Y;0)#Fc;lU@K@gdH z2fI@^>D|Dcqo?1WORvPFo!p%ablUxGB!N@U&o0iUa=aR7$bx0s>B?b{Sa5MJvW2c# z218ldr6@=&KIFCY+($ns0mi4}v*PPBP~G~LjB9S-)XK~EPs+ZgO!5e=Wz0<@F#(5K zH_cBELVJ{bN_RDL=amXgz#(WKe>2eQXGc-x!gA{GCWt%&wQ0&15d*&e#@rafrHI); zVcg#x%U&QCPU4@4OgVJ;dG9L53YyU2kL~eJ|7BPI5O z($z}dU|R>@klzZ}a(tKw3xoo;!*$7x^Y{+3SfUAh8abxKo#yG+u zh_P>O$^AQF*Yo?!2H!_Ot86#(Tax6@orOi-w4_%zCSD=@RT$n~LwwcTaEUbO&SA~7 zVcnOJ>vLZ6DA;v%Kb^nxa03OA?7P}do&vq670{ybgFsd;0fRerCF4<7>5`LP`X6am zy1#a8ZtcK*RJ0FurRcvP%(}8-J}N}(X2-RL$)3Ts4Rx~$lf#T!TcVEATLCdy|E4u! z!c~y6)VWy7%bxQ%joJa#Tdn>gb?vO;6dv@Y32+2tLC~QAr_ahB!ISbS>!X;ml zxFK10U{}5UdF|6dGj&b6?B(OLVrMwC!~XpI>>qY|aS;!2AX+PTZkyIOcaLm0f|f=V zRzNm1o)SCIgo5rf7L-{OQ?A83{-}3ODw;To>g?Gu-hMCNQ;k}q++wFd&*f#!$+t0VN31;#S@KN6sj-u>O#+WW05N$~pU?WV?)hjZYWub#SeGWL4%@>VUmqwM@s`MK%mdn`Ti^l2uLmZsiqVe7#LiHZM=O1y}#52Y)>Df zQYSJh)~+hqi?fqnYOlW&qKUkvO&mifh&tHaW$k3QRb6s6_SlN6JLw#TaGLWkgqAcE z^FTwavSfQ?*QVWJRSWCs^!}prh-Z%C-8c4m{$OH!IP6m%siOyvWJNVn(sRbfk(yTQ zn}AB}UO6qZouq&(GO0&%)@5O(lja9TL^1k^4vp^v8%{i#U=I@DSlVpT{`zwLY|=sA zg&=wUwjS;Ad7@A@UWZEey_{RK1DqE-HNU)^PRm5q7J%SY+P7Ti*LVMvcAK^L6iq<} zGm`S|wblrnPBV)0>Dm|bDm(fQPfnr*o1DUa{OL{0&y98vhHf*2V8jStw^K@uSkN@P@XWOEXzE zlz~Gd<@2vEf_q7R(aJJ&#VEApD_*m+_7`7>LY#Ny608xtGvfK|sZ0|} zui6Sg1m$azg1Ie9KaZ)OhvLrCiXcvFnU?2qqS_H>dr--Jj%Ib&KL!7Zhf<(Qe1mP+ znj>0H<&YIBo_zY7jYFxC;pXYmW5KZ%j0W1gyu^y@X;XW~MU=uoq@$HdHqNtOtrif3 z{p%u?Nc)Cfki31$8i-IXPSr`opb3yt*1PsH-;dvS_fn0_Tllujxb~*Ho`nOB|DJO& zNX z#{e5N6UxP!rgUJR!fXpF2BXsA`1*RKDN$9mKT&tSoIQgE)S8%Zl^+kf-nuS>&)?~j zEb6a0!+JPS71;^Q8$=O%_@W2fDzB4Z?a1#(EJ|-AWz(%bV`ZUc;yQK*ZLq-B^zlQAKV!4b$rCzi6J$zA<@WcEmY2gGCZ zz>CbET!1hJ5RA{M5eM;eK>njZBgPY|m(YiLhcTZHDx{9A$+U zO5dbo%d(>SEzJ8EYu7lC0t5PVfaBFPB;-1T>Q`2l4}<(-z3`}WxEYq%#i`S~Z@~L~ zU|cPeH;^@NPZ6HdVM+b>ysO?iiKSr1RfFEyXA>>zwPh0CDUHisi}`_`sFWB#_Q z+$p{`KTMUU;1;QOaVqkpo^ux0%ue9K$B>o^fO z&CSY+r{M=50c%moly970HLGMT#1iQu$K@-uqHxsUk4^f# z7Vv3XJRrEa{#U85!b^?JV*1XZjSe=1WU;0$9nmU~l&GjW5{?-Um|tr25D!UJ3sJ~9 z8lvUe)0Yydf@CMU^o45O$`3-!mJMf%_&D(ez&Df6PW&Pj?VT`#t!bbUY7P&#JN1Yt z6=|BWOQaZ0V8;|Fy{%SX4apEUVED3@^6rPD|Kwdf03k%tzAozeK6y#ZwSL`s-n#u1 z6?t8;yZ6|&2q&kG<0Ensh9PsG-C zl?2jUmNJarL4-SAP;Bc+>1$SgIxC}XwRlxr*+^q(!47h4Z1M^eZzXX^7D0))uz7gj zC!0Idr}^xyAx7)aU$@tBnN>)BkcDdHWH!yi;tB(Bae5Mkwr z`B-$vTT03%T4P&{1CQO&F?D6BGv?c2+*^1#-SR40; z!%|kx)v#VI6?Up^uOAPvfzHI&4+g&s+;{eMJxmzG8M@qDV5$8|DCSqAIyoo1IJRR= zEP-)Y^d?ZJpufsLr~vsrqy@fKbs`L!Hsm>cU1>yc^zn9JSW0OjMb0PjrQgsYCx>v2+66-#1bm6nL6;qb$cyVlxmbLKZ1b}ZRZISjpVffk*;~!PlU>` z@@aPr-)fc%v`b0RN0TI56{IfrpP}IHz}H_#8Eijv&;eQF2fbYMtv6do1Ifu;@HN(Z zj@aBY+b3F0aksoeTP|CW8P8e?os@w=7P-s#0q4~h+YdhD>B+0Aj$Ar=cE0=W(RFtu z&&=j4_~M$HL@-5q-9qVPnE90?)O{u01X>~@fBrd ztjPtaoerx3i0D<dA8ODr*;#nSEXp2WI<53TrR?fhSJ^lF^4@g_nlEh z8QkFK^AbLY=t^a!nY6Jqq)6)rxm4dBz$~4@*B?8j*qgTL(UA#7s^xc zL<9cB&%)i{le~VYU7YcGoZwL@phNtpa^Po)XeXtqx!Z!KLPS_@E=r6(R9R zZ^FVmB2;@%1jv`%F*%URAYUc;Ddl{j=1RBMBvR))#-RYOGG0B4cxd;fQ7- z*}K|ks_I((n-2#zO!bOCQF4k*tqt40k3qOl1DmnF=xgJHZ%x12W~jid1sdG%_=Znp zH7_6sr-pWaryB7@uTM2U32T^9VK~a7EEV)P>K!H7`Hp<{knK!RbNbnsC^a^Y9qsmp zy7UL+Z$K43#;|<1WYBdhEta%?1TT~TYqO`sUHO2nq#bsQiw@;cxtY4)Ld;&zPpg`m ztSZwr8G)T7A{gAC;=AS=DM=|X6ce`P{am3E@~mKIgazA-6%{AFjN*0j%zB50ooMD- zF85R6Gz0ke&Odq!zZSKSj%36RHcSp%|ES8L_nL+D!vEw%HSgR0(fxUP@SP~Hn!JTW zz~mWP4>?~ydqsD6J8Z+_t(f5|VKIa@1uoaWA2|OgDRsnpiP)G`<%{2hl@DiWf_g!r zPK6PypI2@PhT_iin5k@IC4R4Rdl@Yq%;H3mMfCpH|#^CpJD;P|p+4a@rMA_rt%v~!i+9S8LIC2qL8 zb46bVBRhSj#Qdyj_t3g1tXZL+4A^q>EF5e}skO%DN=jKAnYMxmG8QrMk6Ud0gPBB4 z-`dG_doq>&@nCk^#(&(eP-71T&XFI)L)P}}I)VoYJvDthTa>5Wg2jE9M#sz)*6bVi zv07sCW0Wqo@;*aLgk8+hjNyfyZJ^#HxzsArUkMkI3(%*-QAPU2Zej`n0{=6u%BWGXLmOG&z>77^gL zETlT$AiQ+dV{1%QoWF8ju699?1c~y5E@K$T`?HGG$@1A7Qh4oluF+U}F^4k;JY;a}uN`r~HC`d0@yR7kblaCom1FR=Od+Jy4zP`~%;KI(B~oG0a_m zNWxqXm}Sd=tnaAw)}9`YIW+&SUgRwc9n{z=wWOGH)cTS^A2RI4bzf71J(D;Czf!L$ zQ|hS$epEoS_6@dADfBn`QpO!Mz;Cz+cu*PJjYdu;*b*jjDtZrV_DsSc%VcXH;f$~Wp3Cq7KlRRe z`q$>x!}jKL5-Fxl(I^b^+hVrH*vkDS@c_?ypzzq>n|pyKUc&ep+%)q2Y)U@SQcg&8MQPE%(1BQt2KI0-CdWa{+q}5=-ac%z5;^bF!|aU(LH4F`fo(;1 zsKWfYKvK6%N+DabKwji)HAg48jbRR-s8FNBOfZG|p!^2znn>Mvr3byen4gKX4?T`x zt@)R6xDM}Ebu4DPH$ zSgp~CHXzH{4EvNYCIlIa&=ptAY+xDgX}^?}o535e>0^s-RZO(d*5>V|9QfH(R<>?R znmZ3*KY{l2L9-eYuJnh>*6S|wIohg4h*4aJ4inu+7CCxWoTx5sgYY`0g1W?dx|ZiF zd8Sl6Az{$=&29+MHA2#IG$2mjpHs?W0>}$2F$X`_}dd;c4{p1 zzByDiPJ5ob(~>5dIIj7vB{#$E;2!?d`BMicfOQ7mVYaI&0Enml?grf)nb&E((BWl& zTb30jYL9>CvRNel5uE|?iJXrE zZ%zi2iQr3uYe3`f*_t3ccGT^Us?JO9!6adUqGA29qolCUKOXBmYz&i%ztW1T^TjbT zU;hwN79VOd7h*XSSX55fhJpb8C#wcM_S|UQ3LXuIp;J8Lp)%q%K7ft=ZR?Kt%>P2T zR>DMqN>db!-&!m#)nX+Q(D(`>6eit9`XRRcbRewtHcj}r?2-u7WOqUtVEYnx-e0uTzcW51sn@aOX{4BtN(wMoSS!vZim(n{NYTsb>@=exb zcZ$;APjzV=uVZl9?=^`EWaRbdA^)Q|Q$Q6%ZB>Tj^L}0xg(dO_M59axK9$;}s+Q-5?$2Ea_Gw>mwd)CAvAJw#7l(|h_) zTHMGp=fHpK^j;IVv0mQ}FI&jBR{N8$`@`@{KQS`N($WT%efC8Nk3ax*;L6?^?}R9y zLuxqfsmXL&z%hia240Q~rWbp8z3DxQxOo@BN?sXMplxogt%sQ)l;0=^ziU)3TD?3Oui$JBFG@Hv`RxqKOCy#`DYP zrQBBOr+||nv8PWGLQo%0*>qxaNmXO-TqZBC##r5)&Er@D_Z;4?o;OU_>Z8HPrpW2_ zX3yhIKtK(4y)N=)E;YtifPE zJTm^mJbd$q>+?W3u&q(6Z|bAPq`LsMyz6ND2YOpbEQK~P>G~Dn=zL^jg>NN|Of40) z{Hu*NP0mQC*UtBRVsJ>ZM97s)K6-q})!`5Y>k=1Hbo|Li`$QCL*8pQxS6|O5-s8^` zyd#EOt!BLnp!tjw^svbaxNo+>XaONEzk9=t>F0-L23gz*BhM(X9oO*>vKKHudhtha zv#`|saX4lBCYk3Up7N-OPdmclnfMU8=xNg#8Kw8~Y}zf$rKLaGfq=RKtLmE%{{C^ZuDb|)VLrcD= zZagzglN9?J8~I&f)w@0)7lBSMZCMXY0^*7;~*FRyU8;8{3(PM8o16 zN+?FO7W`^z%P61mE4hGP3s2kk$M_=m7j)l!Ygh0MWk(JRXp zy>e0&Szw|$ihaqsvuVu7|EZKlBZ~=y@#!LexN2NHJS4kw9qdO{IeQv`H5n1pRVuWz zvO%JJr~ZVq@`^88#umg%YsQs70UXIKHtB z*C}oRKCSU(fFf3l`8UUmLC82HW2E_C`oo#0@R}RJl%U};<8H*v6vf_MXJjqx!4Dn- ze^t0e!;z|WrSEHQme}ukKQDi!ZRfnW{0b2VNjpurQO6r6m-+8)?WeEkx$^tGdaqp{ zxOEPEp87&A5$w{6Cf@4DDx;ex_WhR&?pjdKY(r=y?AoKRb0E+CM2g9N?s##b?Ygp7 z{w|B0rrFNGSpJ++45x(dV64}_uF4E#xuP6?HiA0EXNBk~!4nVDgcS0S3xw~Jc0L`B zRHM=o(?;^~BPJnr164Op_+d4$rcEPqo$c3F7!73~Vz3rhcHGZX%Djpq2SFz) z_0Y1@KRh^!hPML}fOn7fC+}-CZ8DfZjh?4s@%mTk=PAtk^;S2-_E7R{C29o86bc-j zo#{z(jtJ!Ba2vB#Lh+FEaGD@U^dVaED!e!M@2YU?9|1n7^(uw*<+ygv0jlMH`4D-M zy=U+^7YR%Ya7XooBCF9vU5u<*sPKoclSg_K&)P4bjbD$oy&)64)v{x(FWbD%^)GdS zFLrcrJ6zN_Z)ZzPQ+xq*&aMiHd%$5@2%Hdw)fuSo_JrmS39n|$lUAh z9&_H#go`v9;S;(=LYCa<@K`7EE)Ht*iqj8kN{hJz3bQQl?wy>Sza=f($Jz439iWkU zcNYkIUnNgi^)(aE*orUe&T2UD;uVcV{qWPM6%v*n-5r&j)Eg@+Wz#9go>Lq$Yss^N z8DwyGkeLf_AEu{$ChmN|e4k-`>oEsaFzr7)qya{v zFk3Mq_cpVG4;-X%&oTcAN16>s>bT}QvB=r2fS*g&%K}G^es<=MvR`y4xY%w4OdM5U z+a8!#>aWcs7f2EIPmhm}4;~@y&2D=tcJcGq*i<}5;?NQI6wfsQeIM z;EV@9Pnryyz-F@W;BkzcAn3JF;bxsMv{G zGLQ-fe4i(IuA?s{G_4=%ElTHo8?5o*S~@#Dg-TIe-OeIc9hp4jALCeAz{9Cq9=DUp zHg8!r$)cbi)KH%Ee(zwd(aWh_E~i5x$e^-?N2ue2usKNUm64!4qx17njUrPM_L;F` zdT(cJ(IP`})4U3M?+l`7K|Gv3MO7tHAyi)aKx(l&MmR|En?O;JLQIi#f^&xSVYY!r z*4ms0qnIH*{9<8SHHCC))*n)Fi5LfPjCwX|lk(+8 z(%%pwxM%DFcE!c%Mv?^|qsnU3U+^Jn;R@b_U*@a%x-Ja)9pY!l$T3UPQYimfhyhga zon{?_kPjj342=Hcr57vq6&@=7LWMD?8#KL^K+H;as^_%Gv?GW)n@EZwk2>}Oj)NM zaCZj6w>CRtX=^v8nW5Nf)~arqV9*l-o4a|%sN z8rnBcUJx3LU??I)y-;lTqs&4IkGU*Cdy`SD7uJCb`NVu20sB>N%x`sFw_e{~cEhF7 zL;&`MGyv?1tCNlc%qv12I!O!>iG=0?wGtc*i1r6q(3bf=iX97`Y_kiW+5E$XLsa6H zRO6r+E^{&!XoUQq=C12jVa>T@Yf-u*e7<6|>c5%Lsn|v)*X)o`eVp8=Q;lRJjQRHR zz+Nyj%$k^&M(nvxiCb0)d2^oeAQ_@nUKVNJiYjZ}|0(E&k3+4wnm^j>#q%{Tz1{Z! zW~Fg&cQ?e$U|IvGAm7AL6CKPY>;&v4butriV7&j2rn7L0@_YaON2EczQ@XorQMwzY z8v*I=kdCF1?(XiCE?JtT8;KR^uIK*#W}d%bXLjbC`&`#MUa2$Mw#5}fLf%qIawAPl z+%tIp)AwL?eQ{X9fF}x=a{vHhK4W)*dxMUPm)8;If2#?WLMnCwwO*&yEydn(^QLw- zA2l-$rx2s^v``2SC%4zrw5AA-3F*|7=kw=6ORIFhW@^z<1z9U6-52@^=QQfEt8)## zi@yUSH1UP6Y&Jv74#Uy{tH1V=<}yl?Ht)TzT>UB1NvWjm?|zd~ zv0tM2{f4;NhL@(ZN`$?BYHP7Jf~HMJU-|u26MmrgtV`;lfdzS64B(6K6jJ_x%Or0p zV_2til6g@+M28_YU;zl#^cEe+t{$vGR-SCbD@I_u&O|nclq?1lflKZUwjn-!2rjpIvH;6b+18VP6lHVsbc}`Hi-GtjSXS$4a!%epcJs6aiRkzRqj}}afT#YDmwS!Qj%v$tJ ze$sKsfC7t?O<3JG!gqBZIE7)qn8?^5HT}XsMhJpk>}Z>Pg*3r>rv|QVG3lw6l8+iT zTTjK%fM!vYW69GReczQVnDBE$P^aaO5XRZVsZMxNpF&VhiweXTX8)R94BxMV8*Kq= zt)9x62XDAgJh?$ANbmkCuf~k{i%)Ke@@HdU73gPe*Au~xs)vO+ihzfneb2W}d*RTV z4Ra>C=%(}YwMSzKcn%NrbJ35XaeK zdAYw@N44gfHcMHVT^!RLzIO;Cxc3KrFUIFteHXBO&4|{`^RG}o6_hzv(uo(UWP7E(qu;$P-)umZx#D%& z?|H&EF62HDfhhMb(g7n>^HTTyZjAqqKbNLv}pqF*4%r?EU!w8b|$#-Tm_>!@f5Ji1$7vn$xla zgH%8dkO00ysoc4Xl4;@{U)Hj9*y^1+KCTc?;j`azC+=KZYdvKkW(S+ERbm)wZW$^y zf#tpYYxv|($nO_@_V#84j2y0S*BpJvtZ z1%CKirTwO>N{<_Q-LNiEK0|lO)CP>CmZ4bB514(^rSr50$W)3;UoIH#rUfS;-cSGR zHv?|y&th@^BxkCE_h`(Ir6!U)WuikzTmQ&wn&Qf*#@4S=SJTUD&S@k~COugEE|SH3 zcR#0ZOs9@uLv?>$bmr{yn4%(JU|@HDVEk%Hu`a&5*)#2w^YKIS5~E@!codY=U<>D? zH23Azl_1J2Mfq`hcXxNd7vThvjt}yH5=9XFu$lhQynl2=r3~fHn&Q%{H{uBP?lN!j z0BAv1H+c_;s`1l8VlO;#akCGnyp(HeU_@v1nwkj9JIFi>=gk;|Tr)v{h@Sl^ruZJyH788O|p?>qbC8hN)h z{U*$$%5n9_nz@>5u2anNTdFSi5gH}zSyIK3elrlejYG5js*m&DwO39B*V0e&>W$Nh z#SZHixU`}?i*E$4T+qfg6SPP5x-P>n!qmSs;0KarTv6RK{KVjU83`*}X$T^KC~EA| zvMIn78Jh|YgP*2n&c#`qlP4@c!%;uoYn*L^GdR11nPR+TkQU0gsX{Jh!f@3V-Z@(0 zq^ZWajF!MAJ#3}(r1rgw)VXmo+vFS@-QrX{b*hfC&&)hm)!V{b7ro{KBYvsl(fK~{ z08rgki4CpvTJsJA;9=ggGA(qu;25MKxC9IL>FIC&v33IQts7q4o&j~>H#`Ejyeuzy zMn2Q0mvBG74lu}Ks6;iWotvAr_2fMk(+h0FpXCZ#*2R1Jo1SK0MRst?@Q$d3{nIFW z`7lSqaXo5xOnGb_T91-(t+MXpzL{sX)=EeDbB)~;c>~4XLpTr!tbue+ag(Z*h|V^) zV+A(%rrNglra1Z}K@&Fow(&el8XQs1Ohqn`t$Y2z2HiVrbgeJ?^`%&5i!o8Cf-jo-9=<8o7Lz8pD?VpkR91O zhSx|!)=Ly`{t=YP&1ZV!fTx~c*ZSL!ZCw;l}@GBgpxJB~?~su0{axHAZ> z4R7`o9%;4Sh^G!+t6j0%_e2sxEZB*aOma@2f6QA0B?M2w9@ax(gd7GqEcp*h-KdtarZ5b%k8_kJ$Ct(p*JJCMHJ5;HVH$MB(d~ zszsHt3C>)RfEU2#1hoFsPWxYwZK*L8r>mB$;wSDKU)iN!cD-ZCpyf34?< zveRM7_)aNX0Mjiw(Em!+v;uDHyQc5du&zE0sxIW;q%4s2X89K zM(w^(*;XW7RaT9YPI^_%OWLb>K6o>%OP(B+7t;bp#>u3Zm>4$fk~{bn4WFjG{&7BuQ>*$UeRp1 zz)VRL{9yv~MAEbA*~Z=G-u`v=%>{PydIW0?`q*sfpAm{Jaqr)h&quP)iwv5*7k~7h ze_M=ft{|+;BjnjmMTHLQDrX%O)0)uPFpQD&=BP5V&cWH@F=P7$ywONyIzK@s7f6-q z5hw$%X#ncD+Jq((;9AvX6RY@hdn%b)#gl!bWLv{`)#b?~OJjjstfw5aNDdpJtd_A{ zIl~16Rulfo<*vkwquKWpv!FL|E5{`Z-PBx5knQq(#&f&xZ%LJ(e2h%mKjCpCK19mU z)2d4ZVJ#8*uMj?etgdm)M9c3a<#WrRrN#Z8K>U%4N-I?iv>o0^Fp{Zw5Z7zdy|(;2d_IzWx)F zPC<$rIas@-LEV~iCUAIKwbK&)_ z^vdKSH^#+;#NELHwh^_zItNpbu?mSd{)lQmqTTrh#_h~n%Hx`i!gFD+Uhl`zcWQb! z%^8#JkcDB$6-k9OI6bYoWtfb`Nj&&!&=^(sS`3|HJeS>JxICti!)-vNDvf+Ns z=l&Ao2m!f$*V}Pf2hxKKi&e;JDSX)SmA%xFQ}ZsnSpM9aV(?Rfv13mxc{9=7_kv?# zVHg)ZxMOgNP+;&Pa(olL*rG{Ky>5x<%)>1o_(Ub46>0xcJpSP?3ru`O)H{c zm;Y_REDQyDE@<2>Tk#O^aRB-(3(KSCAO2I>8_e#gND=DrI@ziPb`z)qJ`}_M_h=m_^sld=hdILp#c`seC{%><|S134UC9(E8JNWCqd4 zAlyCL3>@UTNA=7bHE`*A=N+Qwzkp2WzrLxRe)rT#p62UqR$cXNVc7y%x7u&5o;i6h zUE#;Ua-@?q4>9(yzLg~KUvhz!*)J7d5^~&t_`~9HR8{>^wMF7 zcF;tWdS#Pa{tG9nA%2NYXyH2r`xalL&3QC`qJUynycpCsEP_xO_nC$9rU~1ALbr#eifKex-!#Z3sH%G zIPdX%03reJdmm!oAS<1vY8XiV1$ZOBa+R#ylu0FG5IaxVriN~zua;yh;+-ay1Q=!t@asH zhg>}_8$7?0H@jFBSH~VfVq!(CF-C*yOUjN~%J+j7O3L(02QE=b#9m`f;0p^WPmd)< z>pAz@XzV4QTruB~|C=_U9Ugo102h-zdAwQ{zf^Jxh|AQelXQenSNT$X9Q6)KNQ|O@ z=C}!>;I_IaU_UhH3SwYjc6grg_1@GtUR@t!GZJIWmL5FsqVq71FGjiqq`jSA(0~m5 zvhw_%+(Chd1bM>UBYWCYl%PO}?}XELGJBv1=v};)g)}2>%91r|=2Uo0jAreI&xfC? z7cBDT1lhSD8RnP>-}y=5QBo0r%5ngqaBt9PC%u<$ zX6mp@Y_!3{f!Wk3WuOu$!^!KE9_rZJ--x|GoZ{>G?>tug)i4D)qOi6_)b|#>1W)|D zqwV;2CP%=r>u-AetjA#Lh?f^80Y^g^?g=|P`(vSpaL&j`aI|d!WoU3{AB`oiyCw0G zhZz0E{tEU;vj}(fHF#3#j<>RIPosm|IsmkZP> z7tKay3DjM!_B{D>SK*NqpP)54mH*x2XXk77=&C-U>paUr+%5^%VWt%)&N+Mw%z*3L z`jnx?(_JkXpndqjk%Yli`wPhk|F+38ZeHMhVu7=ZZa^bXKkw(lax;^ygJM-CzO2~4 zq!IFE_BG~(y!OiRRvU95gTAlUIrFW2kg)tZUUK>Q-S0pOKEu;6Cd%IuMb#|BK(%fBtg2W-Eo5o+ebaRY_?X4a#c#@n5oYYiNj-eXlro5xx^wPq14xFR z^nRb(vEa{-i&K?yH`k0Hg+r||d7X#IKQu!wk}w&`Xa#L;YEZ&rTZnKw7a=12S(&Xh z*c6u%Jj@E;l5LLEh(g@SPe-JlSG;61lcJ+coihU{mFQ5rk?ovG<#4@oc{0eHoKER2 zzvLH>@KUX=x$)^$a0*{D52g4kHLBoW-_mb<~{w(RF z)W}AWNh_Ot0sqckXe=0j8{(M+dUtqV`yR$+FZtC`$1ydLvYJEP-b_%fJJ4{USTg_T zNA7G`d%!7%0)Ze4r%@0B9Rh?jbrP++uYm_b_KMEL4frJGzu-~Ds#)l?#>mE3xvasC zor&h>T9rlDCjxMa_m=a<}!mAA}zeZaBpd+Wp25EClh<>tZ9a zC5&-Ib=dTa1up90__x@;sjjUjjJ`XOw=nVNp0}~%-QbW1^c^zywNPXS^MP>kn6gRa zS~h7Z11_0sk)1C~tD7u=D{f6Ib{+(W#bJs&3^v`>Eq?&~tUs~>bGz@K*H4q#&80aX z!X{6%+B`H!{4Ej@kHIiYq6#Nfnt{$*;!}LBBDHe>w4@7Z;CJ+x&SL>KwtAVqkX=gor~iLYm;O7gyWNuD z=hR~_w%-_wvg7DhAB3mN(?~Z1p6r2IP0H>!Di-~GK5);@Yq8YN=qsPWN_VXyVo&iW z8^|ht-)+s=%<*Ic`k8I5VV`_0&(b6hH~zUNBsghiK`|~@Y~S&DiqbsL zQNrpAqgY9$iwik;Q_r?E8Rd{rkswAo5NI*1nRKZ+1;L!u3AcEa)46%ww>omC50MK5 zWc1f=c^nICaJml_im=a0Fh%n^|aEpgX`==yz=%vZ4mBpR{X+tR<&hut?z zr0X5-B7VkaP7(>Dd{kqSt?w8ls;bb|1?fFFn25xW@9IzuJF*d+wBZgMoKHa5C3h0* zo##EZPc98_+~DoIWEpR5*)_#kf%$U|oUiPAzPORQ+&wT$sGHymb7;`qnOhew;=&^v z;zGs`@E0B7!v=dsm#?rJ3{ns|=X|k)qhlR|j?m%qLKRkL+E1|wj-FE9Fy#-a*X~UB zRji73*(&rI={&8|{MKs(JvMERI1FC>&VIy7fgK@i7NQNS8$-pfJ1#C(cGTupB5un^ zs`U;mmvKb}?FFR+5DbtPLt%kN_?Q!{VvQZ|XU-{~5l%!)?uA$0g`0vEddy;F89i`E zrJ8p0<|qw>t2@rm@@FCLuu7{Z9?(4@A>kcFHeFp&_@)N1HIlLMWDBHdLpC>!)SA)a zlS~at8m#GNkeiXiYp-|0Lco!(l?kgvym~l?l8;2785!ynOa{6U5(D&Do7I_?e|BVO zzRPw5{$EYFQ8QbdwSlI*3_P8K3y4&XFK6;N>&JE}_>sF+8tmVx8biDaXV?&UO>15! zFUsHbNoq61Yv=nHG}&$Iz5cibqMIbbwig5D`Y}tydSMd#uRU$|UB<88y*IIEmk`2N z?!1TJYZn%)iTK{}CQUi}tNn%nx0B+dz^toE0W#4@al63lTCppK@fkwZQ|V^xWYej` zNlRvMpz2@DtKF-=vNS3cX{l(dFimhx9OCJjlS-~FrF#Hx1@zBSBKItP=1CdTm=Y!v zF47gzSj9;=HHE)NsAt3&MAUeeVD9(53Nn`;dJ0CQlYV=NS~|W3Jzl)8X4ZB5(mX{^ zPqi9wktA(WvG<<60TZsCpH|o-b;XV#ifbp~d(FX(KwuDb>-k;peHi7wK)}n_`^UT& z6zHARzBhJz6n`~lk$Ow4Q(Tt4iy?#9?WE>_UrMOZUpfJwIny z%K>1M&tuJS^8#Q^M**<~6Coh)7K3moh$8Wj4v6mUj2Ff49dVHR_}8V8(`%G&DdrS~ z?vBLj3nF>fKG|d^eVlo*m0z{~_{b9sUt9^eoV2GgRf(WyoWwgvAA5g8=)SJt zf5oxYFyY?wFpgRGRLsr5yy|Of5(m^tV+z#{dKW;X?fwuk3t7k(PVc#;rxf!aI(xkh z+&$}lA%6Yy(l)C*{@a>DfCXX@kp{<*f2?PX9tnmF7RknASMD$M2w3M7;iNY0$+8lb zQNiiTXA@fE&D*Thky>&AwQ0y_Y)D8*{@4yh=&IkP{d?(d0pb5kjHPM}3PRM*R2xvk zS@R_N&{GGbBgjt{lWtDn*g{m?T6A`mLQ+$w18$WsmFjhkKjKsAQ)yTkw228SkKn_m z!WX{}dx=s!i#j79z;#0GXU)0EzEJvIQ)yHY5!QHM=vTD!ht$WJO48pWU9&UjeitSM zz2TuI1p}$E=yYD#6SXh*#@=R5mr^MW@M2sOa13K=K#OQz4L#HvT6TYD{S)&$aa-~c z%M)Vro0Q+?!S!&Odr2L8Vc%PQdKH|p5e4!dqQ+2~;-}iVaASH!e#6K`6CRT`}?Barw`IR?`=q8c9H15S=SQoEQk>vR6YzE^5weO0=&JDFnp;=At zJw>NI0H$v2G>z`=uSfP@w0h5YZ&N8U)TSE#Q7;dJ)_`-d?CA2$cS{V`-Sa4NBN!gY zf}Hf*1@#zAc*4^}%HO;SbnH^A`Kcf+MvGXw8OgJu51a2GVGS-&;?5;A;RpyGGfVpE zH1YH|w;aHY3iS+&ol~_Mxx#b=*vXcO23}$d=gqW};Hu_BF)^_O z8^Bfp3(TKLanO zb*kBktmv|QVvkAep2;FM!tjLtN+-}+7mQ7cewWuzK}9LD*XJRQUCC0_5jCc6WX%uG z`~bU2Qtmlf+0!TV(Bt%T>m*eArb%!}_~Kfq9Zon~L3ZW}3khGJG+`GtHn{E_eoA~m583c)kLny^kMoQ`maWm^RYC1eShy)YOU;ao0Ct*C zzPuMj@!xBC{t(Jh(bV8WFO=yCH;*1{&=xVLmUYI{o=!n z(KduSQ!m`0ty}Y+hzvxz16s(_M?5A=;~9*iiR1=))zrlsyZfr`t zO?^Nqx`B8*1x8a=swm5opgpJGKi9Jvep1lmQIUP8$@==^c_m|Pl3s%zTL$FL>*=)3 z`}`G2G|&TF-0!Yf*|?ip>!mDDE9Ane7JHB$F1@y+4SCdbyzGgh#Z4Oi7L^p9gkmHp zTsOn$RuBRYr^=UU5_)+3H`w=X%d9alfw7R{ys^aBM^pi-X$%_U$|_>l_g*M#ak# zFn;2FLVD+)ZpqB6n7#7I?y@n@Y@pPzz+4Q9pwC@HKtP_A9W!9R2ch(NT9RKS4T$;& zQlc1NayNw9&+l6z_bdc?wHOS2xZeBm>y}w`t4es~t91Soa`C-Xaxqb+tbLuC+`DgS z>S2<&$G85dq3B8D8v7p$Rarse$G+C&l9oCmSmI>tOlT^%SX0UE@e-Nww<-2d%W@#{IHPDNpaanvav1=orVv2H$Tf7X7p!5~aaJ}2q7fdv@Cu%#Jny4Rt z2>P8&4bN@CEsKZGJWpoS6{1F`L6i#nV9D37uV|(3LT)x*;*M;1{zu>O>gw&B5IFm< zwgiM|-}dtH4QmJ!VO=5wKe;J(oftEUTHsB`8}EhO*tRnuBkS${zvd%U$9|SoUUIhD z>8BFL^hS~*GNA{uMF-DX;}DQm1g8pFq$|L-OAS1A*82^Ok5l&frkQ2iQW7Ac8;;D?tQ|*3&IXT@dFm)2Za=` zFq`fAg5(45zKnPOGvNS$&R5vk>pO^^4A^Ee`ff=v;AV}|sY*+WMvw^KVA{pO65kOr zy6;@{x&z$|A8BxaB!=a?=U$Z#6A1mRwO+;FW^97vc)wKp554WIH!eZk5t`6@#A?H}Rz|kqY*vCoU0t&rQ~s>&p2O?rQ`zUwFdJ;@ zbWk3d7=R%@yEGTSrSUt2y=5qkhA`wdH6cLj$j^rRaEp=UmGAqnlikNpG@e2X^~}(=+I3$VyIfZ}#M5*O=QZiKa|EoL59;AO zktL^JG>e?J7U{WY&2}+Ml=g3G)@$N)&9fuG374wCh;6(o*g2)Y_>k|ot_R&DeCM&S zg@i~LSZh^ZO32=6BmO$gGiD#!Kts4}U7_|!(l(~&!cGIvb8z>)K&HExUtI2dyK*p_cm-n!#+JG-T^-%gS~SO zmA?79Q7qliho)37d6^TX;dj&u3UVFpSOOUK3j4SupJ(2w$Y6xV7}!c0wjuZZyoaxp zC-1s62UOXN3F27hW=KE6I68L0K@WV*aO$JX}!UY5F38kW=OrD_~C6%mYfu_ zXmnc#4vrOBN3&?)Blv%1EYN?ORtCxvoGKlvd(1|CPsF`9EuJAuWMSvwwfZw2q)Mmb z3~RigpXt+Bdw&%Hf5k{M)q^s;q2G~w*poyBoE>88`|sIfy17O(eBp&DMDG>C@)Mk{ z(U%#q1q!~%b01&S?p$14)e|90GN2oUzyG{FP})#+m=<`jb$$_o1Uyml_G+M8JDaw5 zLfL0cHY8srm8Il_tL+o4LuabLk8eHrzVVQjJ+#!lvS4tBMGOC}&&cdW%M@NYNelT% z{QtcG(L^oH7Y@)LPWdRL_A_dwb@M>vb0volOuzT(F4FM0`TT>dm(7M;Gj@qq-6BP- z#Ok(wUI3{%D<&n#LPJ?l%m=dJ+x8UJP+7Sg`+;13kF4fOkm{n8W**_tip628L-k86 zSE;4JH&H`FwJ+XY{Q83}E8w-{rvm*AU5r}8Js<&rcfqH<=j>J=Vb(?#=4<2l#%TxV z9)r`*DL@e~BqUVC$Q*huHlaGq<)6Rw`zfv?C25JMvhuHZnkiJoy}sw}9bqKhBs^?U zXt6w!aU_^pL7>`Zyjkiv>8c5#uICCvkNLLF_%QH)4Xl8-<>V&3Of~Ov)AtPF)X$OZ z1hI~Z%nZ!u^=?Vt4x`Y)8cMqPye{IVakW1ff86;&LeZ^k%wqUXh7EI-;HAAJwTz58 zEFl~^oGwzt1jQUNV1d7@!pT$B-F^tiW&J+7Y4N+$@MEZ~Hl0;WxB$kPb9ehMx$)<1 zp5>OZxj0OUz@dxdQ9NrcsR8`35x3ls7cmtTRcutSjnk3~5S%S-^5!h_iO?i2<*ANO z11t2Dz)UV6+~nlj2H`Adw~m2`x(60h=^@94pvQl0x;dg46sUB%HL4x1_CShw29x^8 zI=f5@e^WsXhb?~$?qq&7Znk~<`5C=pl(A;K@gpU$yX<)iRj=`P)^~MIaRF26bj~8o)Pv3F#tjEX{2qK)XzY?D5 z51yRYHvo&+uIRLd*?)b;*GCUtF2|BzG;kp?U&Hsjb`WFhHuCCHP~my#2F1v-=p>Y| zB}@&+_&*~nywhOG6lSCzmQjP+va=6_8Wmvme%p~W3SqqJZ6%MD2wC)z)vrrbcg$h> zK^+r>tjaI9rF_;@S!t9+mSi};i65I#OWDVb)7wKoe=-TW_$5P6Z?)C9pJ!sRNYPqN~cv6r!%WloA%aGk! zs1i$0-P8Ur{2Itz<>2!^C^KAT`Fo3mRNOzG9vQ1lZVq4(3YMkwZ9;)~2;w$}4UlFl z{uv%avEpoWo)Jdl#~aOwYFLJ4DqAIJXdWQ!sS^`-lY1AmInOYHKlG_GFx9vl8>q_c z5gm|n@dn{gRPbWJ;qs@+CGOaT+)(**SqrpbDxOFg@ckj4LuQYkD^6*K;m32i zu#Gp&r05k4iD4W*Eqwc2%10k(9E`SpvpT2s@zgCUA|||cMuW2d6t4{&)lhZ}$v9r<_ z#-*Ugm8Z*?ZbMQyJZ~3tM!{U}@Bd5*DWo>o61En>l}G}A9(6Fc7q(NPtj^;53Gp#x zSC>f=?rI!s_c$f7)J6~*{XYD?1-Tff;6KS)Uc;`aelG05eR9}vaNXMq<<)kNxRur` zzoXv?Tfn|-Aeizok&;G)F{Ccv25T*d_IPvsF)Rh0u!W)3@^X%AIp~belZ+dv{Z2W>9P1Rqy{%H*7M4 zz6*snshkX>G8rK$WlaS9wiJw0d3A)#$)oEFLY}v`N1;~7tY~#(w|`h;`-_-Rhrbyn zkAn>e{SLGGrtSF6J=#@;h+P{5cUFobe$X}x6ydgV5Omd|*&Q9htk+V3l;UfDEYToq zTaHPIPEDH91UP0mx|B~4Q(L{k!2XlYErtVU&c6m5;nh-rgm&H{e(w*cy)wF$po?oB z$G)jeKZ(;X{%}T|UKbM1DbxkY2IVljtzi}ObGN)R`sIforh?WAF=kmhz{0_kvrMx1 z&-a$XN@jpm0Mz!rT&+&lr)PX5Zwkp85zL}B^>?VfCs-t6a_wZdC>*=D zE4IyEn&lNzz$ss_m^0is&A%AvO8#nX(JEN`Nxc4j=R1xbDnGwH7t;TtDDf-@=#>G)DA>a;0`29rD55_-=k8aziG}dDI1`}%~dfg+?HyN6b09AhC*qASI`}? zAv}xC+9M`t*J#%Zh+z_k3?hg|c@IqozV56I`-lr>e#*sZvb zjn?^O14&=RZ3oCF_*3|)H3?*L=TYpQSD$K+lbM%JPtx-kr0-(U(UijK3r!okO?r$pWA8jwe(Q}kIEvn=-rd?{muP&} z@9jp;>Pyg1lGXkr_cP2UB6!7ZV5gsKt2ToSY@Nx|d$ARmcc?1CB7JcRxRO}>YF>Pl@&&q8=I}k5yNerzjV+ENX1eG5JZW5Nn;gfM`M#Jaj+O8tVo`8z6KhnOUT9BuW$( zPjHytdI0R1R>o&l@>9;Qhev^p(;La7ylQvd{Eb3;uiII?3=M!m1PH2NnIbHe#uZKy zWuo|yeqMb3iYAUw6GP|=ViMU!k25d9r{j+QWyy|O_lYB*j_@B^k)idhvM(}?2CeD$ znV`3a=_VuS^U2pYN^WwuBfz9Vaku4_0~kPD-)^Aoo@W&Cd7>~T^+6OFpBx4G;uhW< zl*VNJHt#o)GiNt9sfsI$Pke*zyB8jXkUt&;LI1NF(RwcOPv@XM4Kp6#vS}8M%9nTgd%ckQNdg3;h$H zl;0vX4phZRB)KS1q)Oav|JSA$_9FMVNn4vT05eJDuQg{bOML442@|BKNO*pJ18T)YLSyV zA0ya(ehHPN$c7FL4UoXv)PG^2Q*27IW4Xr+-DGB&xQ&fPi#mBJAK|Rk4mW?$z*ap% zsAROM?icoXasO`tO{?`D{;c4O<>=wA>TIGwwok^%jLx6`UkGY z&=fbgY87H;7y97)8QN-+??7&75p87|_C;vP(;vy3h?{ePrz~+y5&P4oI^+0v=YcDR zP7Y2`KnhLqpPIIRg`u>XB({>({>*Z*Ff1bsm4kqUT|(?{HB`8%Xa0v-&&F?;d3#DR zbNKE(Bk6JO3ua7op0fHc-!PMBQw#}1NaZ@NAvu^qspk2-X<}=U8WMIji~y}A=OjK@sN#VqE`fNxUP}hR1OjuY z>+TyU-%u|9*8`KU&G_tOD&g+Zxji!F`#iMuC?Bx5^@=K;VHlO=L*;TGEvcjTE26aA zltEc$Ri+TVB$nU(yXK)?wYoH(d+RC zqx?-dY~gKfqhUBhsun5V_&DfA-s}9^Pr%E2_3F7LYdPywif8=x2pxQUdLq6v3XEl- z6b0j?qcTYzc2}$g<<7%p=Z^u>FJE2Y3EQ70e~{mK&=Sdr_DD5Bx8{MLGwpcsFr1Ps zYs&t^v5+!<=><6iWoaHehIP+tqoE=AXOJe;qfYwyK8aEngur%BAE zB*lbnE^n5T9`VAK%U4xmaZD|if2WVv~gFL_bx#+ey`)q-VU<}bMZjT_$NA>eJLP|24$F&|SFd-uS3ha*3T zcZwtE5X;XD575~xMdbYFL;OCJPb#D zI`V4-BpYc;kBSaJhuigrR{JAv&7>P#JrJXX40Dzllz!H9*AR!86xo_A`w zitiM7YNLCvn#qe~N7~Dbt1Bx{J}8L@f33rsz?8Y7F#j9$-ySyg$CPe0xkU9ZG+IX6 zC;TLE{$L4}leV(|GflVDW%E?mQlcr&kIx`ek#gQmLj)GE>z7$y!TKuJ=4I*t~vJEh2Zu zH>zpN7!AABKF8U*C5M3a)}2@+@A##}VV_@P^#%u4B3D$-n0KfK?i5*pufGwPL6%9s`T z5xY5+er`WX6?G5Bu@JZqO85MrF2kk61Rr4jCHc;H6@1_$$&M$ixd2g%Q>5sAdnY`d zG3~gWZK_2e>USG?vkTAkq1P3B9SO)V*Z;gn=8FzfEEC88%;fDM?xn#zd)l_h>d3BP z?6Gh$t&&$x!3OK#m@Z2-8p2;AU2YN4Z9om_2z&!I$wTHxDR;XvD<{e;gNu@B*a@a} zYQ81-hSr`FaA!1dE4qknMY*VaR9BX$hhFs4472~xsmZ_wpH5RA4#HncwlbX}P z^d6S~=I-Oui7QCgBEdo~Asc!EZFJiv_knBWPCOSnkd|3n(ppTPZ7*h(v5-ayfH53Z zf56>IDcO;Vf9^3bG1mTV2=Tlxu02`&!I4LXb;bSRx+?gak<4cMx_962t=AY5GGoT| zmlCr+hVF-VT>Fa%Pue5XlVq1WR?RP-SowQVQwD_cLO-aJ!AJfkGY9oFty;|c$f1Sb zLXJrYs+9ZU-PFUd6B4_o<;`^8r$HEwwo?6#Me;M^U(0Xa0A)uUH;iZlO+5TP-I-6hd3oWV$gO~8Ty{$f zx`+?fpu8Rbh&DC_U|gn$;#dtRuaw?P`C6^wg}?6A&}jb9NH`Qy5u9K? z;yotu}s-{&FdXC_#k81bFa)D!racPdJ-znR70(5sXF7 z)&ozvTmuMbTPf_G7;}6~6WEqQX6`;pwLGD1v)4p2axXhL(j}-Qb=D_9WgPVp3IdnU z(tDq(8`oSHUKvXSSgoWL!qm6n;oa;(Qs^!ZRsARJSY0Sp!?j7Ef_Ch2x0Kt?CoyJ4 zizTOk0LaQNH7K5BZIOs@w|=d*KyB|=BVQ`1fTQ!(En9B)Th8lHp!er9k=ge)D?e2( zKY!1PwFov10(ScXU?$aom;%C&9c{@Y*Z>{}BrttvNU!X0}}!u05VVioYm>b^_-$?~#rzv}H|%gHC8|0WB1zrqoi zQ5SfX^}`J)Od9)xaWsfePjD$R!c3)82el|ldUEWBB*#;_Jpc8+{~c?oD(C=a0rNi3 z7ST{-+b?Gk`0XsYV>EIRhp(bI#ND;CiD#UPslRbN*`(zFfcHjAkIEMB#itJU;$K~#n?fG*ZelHb?Q&-nQ&7ksLVEUB zQwz}w)_%y8P|$@0H?KF>v81P{8|Tw($!zi7vTDQob?zmjb9AtI7=+K|K#TI0{wnGm zs;QnwFLNA3w6x9~+EdYe#*c&%nDP<1xo#vJ1wr?!|>UA90C9##wJDxX`8KCR@QaNx_>2Prnd0BN^ zTGe@z76V%t-o$1?zLPNU3EU`rw}4_afs*$Aa@+FQq*8#R%*sJroRXF*gz?7hO|Mqa z#4GAVf+$yNhS$`wMu1JCx)o{2qLXbh2S$><-uU%B;O%2QPo@GfkioGz6V@^))(%G#Vc2IY1u3pvQwB7PVuIBz>>Kt;MS+OpMJ2pXz)v zun5`Ck@iw7RcI9LA3h$PFoYIpjIyw(bsiOE#G;6+#?17LPXu=(oA*!o5I1iaB0&mM z@_+NBoGZ~6mGiBI>X>v*-g{g)pjy@6_wl-`W;@9(u?@a@0vjAN{e@FCb!`>!v`aZJwHjlNK(0%izML>G^S!B`k%J z%_i#uq3pCzQH;Cke5!`)%j)N6idoi$Oq0J?81gg65qRxRQy{N%D&v>FH@dQEN}kH# z{;3Q#bU|}#^BE=1_NmtA122hI2vy4`#;N`(7;??vA$FJN{{x3Xc)l_@rj^1tFeXx7 zY|EypSw}RQj#|Lsp)o!|OlJoi9A4x6`P0w^mlBVo>zcvh>w}C(1gX?&wP3MW^vqz> zZjp>VJKh{)LsBwY7;|Yi^A5n7q2iN)0zxKEI=GXrOV>%u^ zKS$*``#0|Lr62kcq|WKAp>Db`&W@wBwzJ^FHJr`&xcl0D9=`jnej0Vzi9cKbUv|Hw z!np513Ayv%hY4C~{9M;{A4rgZ|J%6w;1W+`?$gs#mdjEOeb?xmgBv}cA==>pU+q>*R0odFE@MRtv5M4JEOA(EbPtp zIXXUOI-SO@sOnAKQpzxCbD}?BBy(rNk`+b4ojZ4WSx6eu5A~u+YnuwCi;Ii??~KP| zOiXTEE|;;;2`Iq5gMFO!%%e^?Nmni|F39sRNf1Kt>%ac%{Mmp1Iv;%afHH>V{Nzvl z6utF#$W~pOBW4zpZdZ(+`4m*KmL!uOTF4e z25ra9LNNE9Mkt=^K zaGjy)EO|BJ==lk!$7j6xmwt%({xv!ru3q!td*8;>V2mWogRv1Qa9zi084kWu1@81@ zRxv-k)9d2vx`t8C@@#>U8LPTuZ#>1g4us=kdCqdRV!U^a`)_`l!yETGIo~jyPN`RG zzVn^0BSecQG*nir6>YoW#`SxYm1i9%sY)x(&zGoTYw`_#8rvr%=XuV>#ga1W{}V|k z>8f8er?VsT7#3tnXFc2lh9sbbdrcmIG(qWg_IgkZDM_G(ddf^9mAKShcRiKCIm6z3 z#$-I{P3zxh|{ z!aqqPebtoks$jrR+NZ@!`P_V8Nsv3mbuzO1lx_A2U&D6Vu>Eig7G=Ol8E1Q$Qjp$M{KJ3zKk?IF{y9$1 z&v^Fi8Hb05+`e^>gZ*1LY)6_d001BWNkl_sMtcwA z(T5%D;Rtpo9{y62SHFmAg+%r`&m<8s#*mjq&u&hg+N!Gh@0D25sqjoAzHKK$_jI5z z$=EKe>9uJcs6a|8jOqGAYm#8tm|j_w!N1Wq9nEGP0-Q!8&d<*&ih}+9{hlWA^y$;S zpe>8=cT(zN;B$8v=df)&Kt-aHv$i*N@9piyYqEZU#4?>uIXOA$-(!-M+`fIAqoX4> zn@!IKx7I?I(QE>j_~77xCyyR8pU*?bT4kJ^pCBO=eRbU*PR`HIkut;%A0M6Y^vSd6 zsMqL1^V|RBcQ{|1^X_-QOIhalxK0(S=;P<}_*sTf6y2{U-h1x7{svMjKK}3{noW(! z!+Lj6X5>opyxH(!D|l9x+?(cPlMF2zYPrYbk>k5h9&%2{UwPvY;Vlm@PB}+lg=9A0 z=VHA;IZ0lPkh)-bag1p?uHCsumQ}cB#e)YQa`gNuo)9WSM30Wg6RPoqle1I2pg-u` zxN(D9ci)PMrX!AypR>0&WqEPNVsXx9y<)lE;IQoP&oQ>)^yGrEkleg=535SL?t)u4 z@AL4{$2@)XkfI2Nt;bKEaK5-;e}6_%YK&de){d&^7|jkiIyz#cik^W!Bt513|KcK~ z*3IX0nx=`~gAOQOFe0ZtGdv5XkBm+*;lgoesHMt!cW@sTWeef+u~cP{w^?TH)nG#c<7fu^WAL65+5w{Qf%BSIa%V zUuN~IwAech(gFSJWijeIn(J5az>_rORUP(EmW;4t7QNiPep$r(aDPpN5S1%(pTD%J zvnAGS?^~rp&|1A(2B{u_`V^!lDl+-E-^&<>_kyyF3JhzhFL?>l1Sb){f+;eO4K;7C z*2?rq>;S0t-n=+s0DSH6q6G{pOQs8raa-wwBqkb(VA^m#5HqZIXy;I55IcZY_}F0$ z#=N$v`xk8^qajxrCTfwrlr-x#&U9cJl(k43NW;c9(Ap5OEF5_h!Yh?gWCbdY#V{7p zb$Dk0A3L}cw9IJiGF-gnI_PTg_)Me671eCSXm3m#$M4C#YMliqLNvACcC4j~(GGmZ{GXGmPn1{R*!<}Bp(h$NeAy8bg2OEPuAN+$YJcfQi8Ty z_7eq*ry7qy?=mvA%=(2`2ynvUy$;iJsdrvq~=}>UfusD0lZ~eQk@{K?GU2aZiUsp+!bfyWTOhh0SSjpe{*?+)a{qdjR+0!RHdh{_TM^899I^yW~d5A(6 z2H`t$CBbwQg=TU39Ag}1CF%U|vyPf=6XK^2M^pX`7-bpGY&btZrtKWLEMhWcMwaFM zNL8RH$_dn(n>P-*ed{%T;4?mUN?V#{6D3(u$|XVh&W(SvKZ;(T4k32Csz} zEZ(VbPLZ=Onj42`DbXJeh4ADlV%b_cYiPO_74_hW2$BxKRaNzydO8g5?d|pdExn$k zNw%HoLuj%h7)YC@AuDo5lW{nVXvJ(k55yqfMJ9AOoT)5F<|V~=f>a^;`}p{XF3L1i z3=tWRr&#N$>or-ijbKlP%Fu1o=sa{Qr}L`sKBndX9?CN74~Tnv`)uma!E;j4Scj=M zD%71wDm`&Vdgw}YWaa|Yv z6&=oc%A&&9j>cGwu~fOHRgO2`dJA*9;pF2-WQC&0CD+>pcT~kjz@M9zqb_5$+OVRb z+P}+%bUZpe<-)FPy-d&6(;U;XY|5lT z%LG4YfhbCbWzc{rf*%CK{=k2PpY0De48b-9(6CGxGE7lpa3IN?Avw)$IK$yIhtoa1 z)S6Y9dGl^(j|hK=IOm?5nN{6X0fky}yURHdZ@lmG{GQgZG7-=877;qMVpY^cp(ART zrsect%H`8D;)6NICvQ?4OOnl4uAb5Af=H$y8m9`2M;HNhQ;|e5+k8V+6-W$9SuS2Y zbJqrjI7(P=3c_^4K{jU8wggt9jU4dYRW zHHxQa7i>2T@4Pui%95&S(3QZ{4N?d$FRw5pJh9G-RKP?h-DQ+9Ae-X!?nc?961{esv82SJyQM2M7J(y1Qqz*3PUhHKr@dtn8;! zQU*>kXk3#k2vvWtbdRGfORQ92B|=7f)H3Vg1iK#Az8pe#YYyf{TJ?2Q-*unZ^(osh zaE3v{;)Wqn+P%p;x0K!1c8qG-LnJ;eRqhHd=~{z1O=0P3tl=85~>`VsNmziFv&qrQUzsH-^(NaB10CC*AZ1)Lua# z3<)XV=rt~G-GvTSRYh5EL3YKvMw6k@&RDB6qBKJn?%(6_m>>vgnwrYANK%AI`a^0} zReRXJFjNH6N15;9jjp8tbwM!K-{h_Umt8>3&duzQd)kfCWDCY({06U->rxrxiUi?r zG-GxDB3oh6PJBxeMy^OTICC48#tM>AN)&`NdE?$Nt1)ehsas6!#$`eq+NMOe6_^@J z%4B&TnYNZt9$?BI3tsUkl9ND{pD7L(bCvM$|o zQj#Em^=d&?t@y(~c$as7|67c+k&BlfM6`C;N7J@!*K5w7eSoPKJbgSOP!Vx9B27k& zrxRwgIcb`5Fp4QRHGzuUbR!4|N4p?~z;7Db!{nuO-M6yJscM5Zf>ygU%s>Sg<8hKk zFv<={lL;p$clq)c-$t8;rm0!4mt0+4@#5@^M~^hSmCtwyFA&ZreJ;#t^sIF```oY|zF~H@Yt(%d+mfo-SBO(Kf9! zECnIfxX$g9M<08gsizFs{qgE;>2A9&guH?G>mFZclIoCWU83Pouif37-Ouhi(OH(U zUaxy{NY}yETDycy>!xNsN7_He&cN5UEvKiaj(cC^UM@oaGlEF^h1M~pI~j?4y)2{2 zgy+xCu~v{}W2DTS!ONqhqA2pC^vE5e{hjYL*$H)7_0PML3C(6Rj*gBvKR@Sc>4IRg zB%&+}1oUHhYc1>bx;HCsw_B#usgFK)&-=pty7$(a-P&-q zT66Et9X|iYTReSw#$vlB%o50Rj)D|us5PHd1*Wbs zdV~xUHbu*_YG}PAL0ExBQr8usRA>VqKYYyL(FwEp9NlX2eB%zh)=iVF5vXvdNjBPY zb#>KC8lpI&sA^(+g=qq|+XZc7iPOYMw*tk%!9gE!A1Q-W5vO8>RisJ;W&;p*D9 z?J=93M5G&ycT=KneedpvZi?9Lg+tBu^}lx=Y%xeB?TS5P2F0LHy>$Bi2wgY3^jDne zj0W1!NddRpElDyai6v46fa(w4*5fj-ch`rH|9Xe{W!mZ6wa@kj(|Q-QV)q&ZuQL3- zig&%=rM;bW@~W=&r**!&VW5n-wHtn&2ktP=79;F1^!e83 zZw7mS+c)*iFq%(6y@p}fONC@EDP*(5=GoR0(`*mK*q;cuw2fh{H+}-UOVu&PFb~6i zs=QrqT!SvzO=}`{X8g{8-ueB4ARwS^`Uh~kHfR5Z+odwP2U-hP`PVr1d8cV@!_~bkWQOZClecl^@F+ zgo+8mm>^0C(-Bq#?o_SZs6tr*G|t%BX^{ZYpMqVgo*BI9dv0KVMQY(Lbu}<81}NvM z6+5oD9&`?GTP$t_z}(_G?o*UhfH4lo6h>~Nu(~9QLh9P-;*<{tFbI!r-06sK)10Yc zr$g+Y>V>sz*XKR^+G=A^_%~K@hC-^oq5g< zZu&qftT2>$!N(tbhi8vs!Z;&}6T);%oQ{}G513A8%+f_&&?aC5dOZCQSI~>~QB%N}6@)~b{`QLNeecSTQ zZ~SZi`LF*oT9fxN?=X6$ndR{4q<>EUmW!*t;H#|*D;kd1+Ipq18R__(-S(f$V^*D}+F&T~d_P4)7U6iOu?%_Ol z9ZnF+9iC55Pnl0px0=8R09ES)MaJ5`>`r2Dg^3l{Z<(7*V&--qp)|yZ_ z*6k=8d(TG8YPISmlS(PZ1m`9$h>q%tDM7p3&=!$&Cq#vk^rD zlhGI@4CgN%V@!*cif1pLyIAoGmU)Xd5!+(P{i7q|DCFbEX9%1Dw`~kX;kwgR>GrU? zZAiV*u_#-zEMvRf?iDCqf!vW3x@&ybOlb%Bv7HBJS2&ygcc)414p3cZyiXXeHEm-U zjbncp^cY$z{7ByM_N%I)kqy>MN#Zz1$t9zyAx$Jm>l#5)VueB=_T(im3s3nh#Ebo} z8Q|`uxMBRW0xYIask|wnxSjm*Y0a+B@>u^WpX(;bFFyp_#;5KN6<*3~to5Dj+n-OD z>TCpD@1G0fOw0_@FZGQ&;W}Z;?5z{GY0iaojo-ds=?%I4<5P9tfHI~fkP0Ov%4b=0 z-@EqT--R$0Y|M7={Rd#NU^E($M6vV7_&TQZ`&3osjm1g-7&`xo)|!BhUu$=nn0*ms z1%YzW+MSzt7o_1vMy9R&gKAOQU`XVXL=;M-GNei1oym%#)NIxz=bM7M zscD;ap0mW_zggou=UyJoYxKuJsJHSY!xQeXy&fmKzx2=h3lHVWOAY_?YjX^0|4 zSvGW_%MKMJWxQ8(8ly4VanPkyv_=z#8G*9A@#g1gv|;Mq_lv~^ckdnUIi`1=VYf*h zo*egPKWS>#R||?F=P*5@u4J!09ufk=FvPTOQCM%ceSz!r*%4u&dYx&2@(V~zYc!Kl z#(Hti|NhVZSDNjTgTwhAUwlaXcvVMc*o7Zzx4Ujx=Zg?_7Z}qO1AX`2ho*F0t4{i{ zUaxx+Mn^R0W1FQU%d(yY-D&hy7`P6lbaI?L&-?d%7xWVlL@Cqh6l*P;&4#9_`O=rZ zM4oT@IO<(N?uwo&+8J7lqGCRq_2@vy`xQGAwwJ@L*K0350Bu`Vt1HT~bTPliZ3@;C zh=wEkJ9qB%oysn~uj{sFSw`4%>+uJS5tD;CK@hn>st&;xC`8**HZ7rw$cqgpckeMj zIz|N{fBSF!9RelE%YuuG3(n4-vRSQ(qqIi@c16~ZrZSvxNGZ`+UjN)%1R~(s<7cj@ zR}oQ?@no~+y+}}M!zxW^saX{pwugtTrW2mlE7qkUjsxzeDQQy^jVCOYE6(c%o2IBh zQMC=_Hb+TkV1M-J3EE0d?mYk*5UQ5T?DD?7-A?0i5eNs0LzfRA+J0uT14c$5;WI$az`BoGrPHHEV zPneXRZepn$P2FfuODesQKOr5pWPNCfZzvi1?)7a4^INfa*q563uA2`#nS^U5ioLDv z##$y!UzB|s((h$m= zipePBt*5rmX=Ox2FrZYuJkrq+te!ZNQ}Y-;kN zqQw=iMupfQLdBkEY@PGo*b-wKgfxV4;Kc7r(&~z$sS%Aq*R@YFbdfJs8*Jm~8MbYl zaZa}mKVw{XT-OavRZ!O@ZQWq4b_=u&QBh0~CWtVmZk$MgAaxPkrooEZApE3VcZ2=uGXAAedGdBf{=KTpu&K= zcjknF=HZ7wIh;-@w*^TS_5n#k2!c*mXj_C7NStOb2%?^z;x?0-W>r#L zwiv0rEC>Q`itJJV1!~U$-w5RyJ0C{THZ4*L0%@p}|Aa!0}G{%}kt|>e*#aL(XEQ*3i1v~b2ulipa?(HC4OlIW=; zZQHmJXOeMrbVQW6@7>Wxs4#K;a@q36>z`vXnedlCe4ju2&Ublm|CGC@_qcoa zE^oj64q@nsHV;4kuvfs2;v!Id{qZ^D zgJUjbNGu~FHRF#yS@6RT&xuE4N-J3{m;Bi2G3m*ir>hmun}%gm69;2-YtgoH@#ta5 z!F0xxr)R{Y5tI25P17Q!<@u9`RK*e@AdDkq;KsdS93zBeJkD5LUG{{Q*I$1VtZ=l9 zI3+JM##BfZ(wdg5)zYm4eoqnBc_!-CaR2xYTD#47Hl6Y0;Roc~CG%;qdR zgP4oU4UeCM+&@T}Opkc-XazC^YpAM{i}MBR)wUl=H_dKZ-~!infh}cSF`hb3`e-!b z$G-9oPo6#PO{BuUicA+PIYhkk?Z>pRI;*iDkUrcrBYYFAuq zr=Fy$TaP{i6g7~(450x?iAFKQPMw81g);g zH*4}D$9VU>5{}9tghGnIMVed3BX*cM>(C}PM(7q{v`feo`R?X1EmpT~%NEAtWn96A zFpimR4azrUoncfDy4h~KH)0^uu><6uw0?AAuc7ifjE+OW2`PG7f!jb`40~e@LMVdB zAqt~7#SV(HegVT`jN@i^BOUQ6#r4Zh-j4rm!8U9c7d-by#BrAJ$-@F&9imOn|MBbp z8|8M%Bu%lcVKN%~&g?FDbvWKsO1X>IxX0gW3$}IzhLVIqKrDdR#rir8y3+`n)U2k~t?2Nzo^Y0UeG07-nI&pEzQIaysB3ixOLtWkAz-xoXB2~b2 zI_24n-e*hfJJugR{FryY^-bzx#rkT&M<2gWQ|27c4k+>s2$$e@8*g=& zz-ew-z{OsQ<1i+DxS`j+6HwQ+lN~p=qQ{<=KKi_q{20>`setKx#&)~yQyDwyOqT%J zZ9LXmoX0sWmuRUOKzF@Ifx-qM< zY^suMo)S&o;YGg2Xh@|XRx#QAV;b9VvA&`WG~sB*UtTVl+M3hX-=HWYYE!w9E|MsW zIXH;129GH;%x5P=$(ZGG$w-ErJ$Z!i24-gn1F3}9=5GiiKMiUc1d=2jb1f^ESwxA2@O|QtKJJ>eYS!S79}7_oJ{Keg9m)_$tMWm1H;0I zuYUEb=*CU9cFDi(4N26HHsYi`?po~#K5bj<71b}}EqCMd{#p=jBBi~TqQm7n?!V8i zsB4NcC&?3{C?OGwK)FM1_q`f_kn7f%+h}H=)>Ynhpl{XW&u-a zNKDJ&bVQbfNTyhw(6lo)#fH^-&2qV}L>z2TY3twP9J0j0ZM<6hejK+ka>Kh-s z_0p~NhX*s>fB29)uf2f?66&JnG#e8}g5~N3Q7Bkkt=VigCUQHM?)a-)Y`Xd&chEb948hQ?QQ z<8Oq%nOAqvZ;e~OPAeHmN{4$+7nsw9zVuyTyMIn_QT6_F_v(#T91N}NZOj_Ddp$Zq4R97u4vGREGMp;Z8TEf7O{ZvGpxPsv1_%3<5WwBb&lnqT$)A-n!pKohy5vct5w`WZZv#SOMd0Nl2BDo9 z#&x+B%ClJUlocaDxO~R`Vt$#!*1h4)o|&MdkyyXDSmPK;N;vaL+qP6~<2H>r1uHNT z0x5fzxC*2Gg4Mg{pRVF>7{XzhN?2kCRevF)&8=36Aa*Dv?1*h${w~+5nP31z5Br3kCs38*FQ7 zOp7qqecZM#mGa_@=a1V#z+}qw8hw#v@8JDmH2grIF2ilU(Q39VhBJ#}gUTNoWUs!AOALzcYt z^&dXYVGzQwgFSq&uIuBjAJjVHfkf=gvc3x%hCAX*m&z!FV6j;A4)0-_X;+AL3*>Az zqb@6?lpGu!@Z#c}gM)*6hSnCSgvMl$0Ue{H$(oIlg7y*LSYC{}5ZFU$%grVwVyX(5{ zdDk7j(8Xq7^~taKX2aFhRo~$skH;>xb+aN#A_6HW>k3_mJNb&O8I4B#y`TGsTrO8U z{#TFP=anTY5{%Ns%S#f1U}v^;TysZzFvcRp&XC=igx>n%7YJ3rC-48rbGienvStz` zWI@P}3(a^u=gv68s+s_cG9e#ta-Ipz3*beriP9M&9`SoW_>e3;qR1;m9Q6n0u26jT z>={K-aC-Uxgd&X-7MGW7*Gq&oBx!C+8}+i0YC9F#_SAhUb{aTx#`UL`8iP>4did3 zHy!Sbi=BCRI1THlBwfRyqvLdw80GTrIH=UUWMr8s9Lx-ofpsZWf1_6Fbed6gw=PHRe{f^{WyS z_y5ifdCIGb?pGG$=BD3in23G5RK`)@#K5BXvX1hO5@oNEN3OrFPIhWtkV+3%xQ+RJ z-K%r`H83}{<_;z3paEttU~8wV-n}GU;MN}EZ}9#$zU|jEH5L~lIP?@0bp^TH3s>s? zuC*qKBZ|Uxx6^clRI(4GalwVA*llP7vytc$khJX6)!fG*l$I=t$VMTFtQo10n3kZ; zNrYh(N{;3!(@8|A9A2-{+8ethDsn>b(P+YCG^45t$0V$B@;rAVxw7zq8!eI0*wAng zK^aN(K}_97Tx|r)1314bxLB;%Gz~@Vx(01igRYRRn@T$Dou+LXl0YHL2xT;NTVM!K zDj*0$XH2R!O=~b(qU*}XuS07ZBAL({9G|ytP*&1n(ZU7DG}@qqV@nHf6mq8?CoMr4 zUy>MS;4)i8n7FQkb+i;~4A{ooat)T&EuO+6gf~bUobJaTDufDrD7zg5(6mTD0ugd& z){?$UVXQ?OH{dbdsnuB0D526N(P%`Hr4*|inFc5ky08uFa5jMm`jL;5>zJFJ18)=z zf`HH$>8+O{$UqTl?O4;+G0kHcLEEreoOzRgViJa6K!r}LYNaL3;yx{Gzi```BW@V# zuC0Uui#ClP3wOLyJ?M`5!cbd((>fd;QV^mDQBI=Mg1%a@GA=G#D9L%}%1<13J5Exv z@r?0!N)%^I59S;l9dS51VlqD_$x^0cMI4Pug9L3FR^=7CtX%aiVzq$@lr!U;mdx;fODO`Nz20F5LB| zz_cx)h*05_|NOuBWsFw*_Sb%syGJvmb=@Z`UDvD88Yvw?#ri{Gs6xLL?rW>NF1b6b zN?(APy(F@JbHFdPWku19el^OvYm_FE25pmihb$Z5j@bPKctI@p!^w zv0!n2>2$JH#d5LW-o1Oi71#;K}okNis{UXK1QTMBv`UXd z9E8@nW!@V;&7fg7B&*mCkkQRe{p)+n!REG5!rOke><&oAm|hC%yl2Y2{=PfiAvmls z19@Ugnz||UdcF1@lnA9luLh8WDj<-GqHtzztt}#P`-Lqn<)*^a7Kubkg*L6*`*4R( zsocR@%784(Jmt+$Zq@|TXop52^kF5|431WM51g(7K^%sR#xc`z%F%4h!DK|1hD=k% zWSo+XT!ykN>2?jxTSRU=%1 zYXoT;GTmD4OlRaL374ya7ne&e7i+GnoTe=>gcxHnju4Homb%#zR1$>2GzKXR!Wy)x zd##OW46P4FvDzECd}h6{?)0MDmfC<73acE;Qdnp`$68p6(%PYZ{K-$@*w#w8F@;cx z8!P%Z1?i+D!noH+o7Q!?t@a6w+UdxJ!YUUHZ>`gvYv0=zK6+UQiB%5yXRYanT*jI{ z@i7px$M8r5A_y^BVUeiNU6{spAs#JlD~Q>JW#FHy75Y{N_fT8gbuorUzw0QT;rKC* z<9^(!tsxM>9+UODo@^L?@LAp5pJvp2*+^@*2=0hF;Xt}za4h(8bw%lkB33*ijAEiN zBOQ;JPG`h%%w%@Ncs!-pT=1Pg{X^GrZyV~epr|Y2EG6=Zrrn{X>r@IUNk>zHIH56` z>S{?<<_M!{YmKoIDcxeS8-pt1NO5}dfbajwyFB{veSYs7UuQZUb9Co~qIBUg!n*4X z1%ZnAFMr{`#qYb~c-Fb#+Ca=iI$} zmn_RztyZLI+9Mx3`9+c>u80W&M;*CbB9&sCI=RPPUohu+P83BfmrKGh;^5$b!^1=J zJm2A){K#JGmZB&~)0DHbr;NvA(saaXwPHGT(vVJH-3899mP-z%Q&y`LdFdoCNs{y= zlFq^IHb6&=Fkbf3b@R8|EvK(N=;aIt;he{hACrxoL9!?c=JP|!e9PqEfDb?Zh+qBH zUnTc?@6jlwZ8S~UfEqB&EhIizMuj0(NgD0RJ7v*p+ih!5VaS6Auk-xu1 z7}s0g&O&~CGUYX;saj1L1~fu4O{SQ=P-zM(Kv_j#{ej$5 znzC$6RW{6KGw$9$#g0<)&4$a%3r9)vSj#vFiDD;Bn#~S*^5|iYHY_W5=rC=|a+?zd zlBUQ>!ie=|&A|aYdh(FXs%dvmx~TV@C`$H>+MU_C`<||A?GApOzhKv;WltL75{E;os^}Tkw;}%a zr*axCMW345dopn5wP7*cNz*+e&#*FHLvU*n(wxNlpE$gzupbyZl7vu z9Q2F#_|ROFxm=fJ*q0eA?MwH}>n1{L&EDGFX|AoGsZ-Zoo=&GuZY%d?Phl8R2c@T0?QpG~Pf1M1eS@fNTaFHo{krc$ z3A^;tAP5NVOgqQr{tYU+n+1dL9ZwWQK}ZxkSM_w15yc^sQNVZZ-jKZsO-MW8KC z2QDL$Y|P@~vR6>M)Jf$c@2xjW`r`U!1?hE4#BJlV>+*-a?KlnZ7^Es2rgfts78jYDuCP)>MW@Er`@7`-vbwdz_grVZ{{25i@Fmq*h z!0j+eN_q~wWilNR3fL^4^TA*I3E!Gz{O!O0k4WQ`V!I^_pzy%rMhK)0`A7fNKj!)K z=luEizD?@QByD2|0)_Uv+aQQAh8~qTd>?L@9(_WkxCQIj9iqBIpevZWE|$h(nzmm@ zhSLmdEoqwe(tzQ0(zfnvI`iplHtWA`JRWoZ{(X<^a~Lsam~jRAbUO9=;gY=AVw!qj zvQ#WLE{q^dTmcfNDS25kpU+WELsOOU8OkK6%K|(H!B6rXDS&4QY~*S2dfW zbQuF#N)Wlg9TkQw*K3poi{Qoc3j_ggzWxUDqhl^!JSR%shE>-!8q0Jt!!|8tnbTA? zRtO@cFxpdyu+%;(y{I;voZjQ~-UI&PkH1HmR}e$fuDLH-{)1%1U88x?HvH)FoJ*rI z!kG;3&t`o2=!C;CAuQJ@rTAPL^Q*E3s4h}e+AA7ly>Sanro+EV2>hcBeeEExf z@Wb~h%aW>IQRW5lXvVrUJeZwg3>?podHVPn4}bI*oZLO(`T56aUGc{KL$WmD;l%}2 zEornx8#upOvf8Xk;{>$f-o1OS0IggBs{MU2Y&>A_2fa1#yz>r05b^H2?~)`5d7keT zDNZsKAZ5@W}g;X$Qr&_6@$FY{2?8 z!eM2*PVM#dNP0@vzIpDt$^T{kqi)UqtHzS={aap_WtbZs+E>XvZscIxQjES#GBT7< zAh?mz?EYK!q_N$9caJN0DP3h41wWK|_6;Plqlt9V)uCX-3OAyQQc~HhIZ|p9OG+aU91(>QZML9dumat*wA#C|kw_UK zwLhv1ng7x3=|hvZj|s7=!0ON+%PM?gZS} z#%-tr9b1x(+-OL+v6+*YxGwp1z4dJ)xSizanzrp4j_vw_)SvKua%4y07v&zucPP;8sfKnA;XxiGP(QATaMA~%}G`5BG;|8#8JvG|C9fYfBHZF54`vN z@ABH=5pBE0;&j7JZBat`YkwbaIFx`~*W(Q-FhlKjUDv&#r0bwvU0pfWsL@pQP8u?q zOnUwA&gAL--fQA+Nfzw7lUJ7uj4{0Z_S<~xTiAUsWc;snBE^s8vGM+qnLTe0hoHC!!y`geV%cW^5Vq>+JcgTxM}%(6md^U&bM3s(878&rBNZH zbiz8{@~qtQ(I*f2@yP*S9>>h2;6W%kjAB+rg^?1YLR1*i>IQ8LVUn_1T(MXzIeqPO zTrHPuYlGRYSS&7R>YDH%BaTuwdC9?i<`d}#0V_&zeD5_5PVO)rP090;tE)@G6zZx# zMFHFOnrCMhgmL1+)1>6!U``N^ncw{aDo!v6?%%(UZYp%S;^}(D(`V1fMlnaT5v!{O zi{+MDyLAsKxLU2byjpVaICcS9vl&mGojKFBirxCCHCpfV?OlqbwU%eko)O2XOO=eG zJ)GUn)?I|JKP2pr!z9{L|(@yW)t+kzT+8tt5f4@fFBQP|Y4{20gcY4=7gdmV8 zwL=63L4Z_Ye+|j&Q!eR>EagAGOX~1`Ec2@3&Gwqz>p?UBZmEnnyVWmi@(lO6PfJ4H zPlnzng~(e>o3|b$ZtY-uuDHEjcl|2D$Iky{_RXQf^hVj?G~hO>*sD?{hl!B;hXV16 zu%4R|Rg3Wk+nqddJRbYCwIE6}H}UfN{-HFcn=tg#_C}(0({u5s(yon5Y{*B7uyZaWtJ}P+V=-tRE5}xCM825ALoR+}+*XNpSZ7L4yqh zcM@C&cbCCkgFBr4o~rLZRa4AtS@-Jhs|WC{I}gVSa2AV1S@iI|u|6xY&LFk8$T|AG zwqf9!!q%mTZSIjw5HNKFtrpfvu@2AJ6?5wpakRSrHd!zO#e#cQ{;Pz63baORCLEd? zdUq?FQN^`|mH$UUZJHK>@)WAI%D32(Vw!K|*`dQ3DlLJER7z3W$kbjP>>$^Ah=mwA zpwc4eUGz^`UreORJTO=9Qn#3*&seX8cZkL?DoKz$>=k~$@!0QTqaX?p;j{=FU5CD! z6BV*kZy43Ce(ujIQDSVRIS(iN& zT`$US`fsK0mt6-%7hQw7I|LGZBp&z>F3`!&8Jv~Pyn0$ijj=`?Ic?VC3@bFTS6Ji@2vaR7PoKL9V93T7Y+df+gAnpqVJ zc$ku&)F0j2q8KSwg*o$fQogVjk8EILTh~wQ;OI2Oa$+LwMsNQdc zKA*&!S)8%H{UH#)#9)E9zZf<|ZhoH5O?iI-$DnUsXI+hO19xqv1RXu$_RRACya2=a z6VxN|h5u%Qf5Lbvzx|l<%f}h;E;2bM?dsUGugOI>f?S@*>QB?CuO~eC<6Qld0Z0j8 zq8goKf5gdPZU;*L)N$dCW+4X;x$UdSci^~o`fqo8FPP$5uK&IQDW&vWa$J+ZvDFjQ;YUC*DpiRNHU z>4zz$=~=*4zeiD1{&{FY%`cegF!UKH#XdoJUMlcnz|mNp7=K z#xMh+;oS$)3OmJ4-3DkSeY4`#czXR1;E_Xsk1i>Lb0=|q=i5=NA*&y;H)3|1$k5O0 z{A1R%1{@ZDkEZiPVRClIAUJ$WLY2|iz$mDMQ#Z{Z*sE}@5vy%B>+Zl$*pDA7J;4J~{LWJLO|zD~goe(#1bqWPsi$BxJ7`9+Mq0rO zEERjmov(CVlh0&t-yR>5jyy&JyoM~?#BdWkn$=vmx+Zr`lvFF_XVbupItC&;iSLKm z#JR+mesUZ1JSXM95kJbW_6B&30pOS5zM6No_q0S&-~3S5(^uq$EsW=nQJn<` zZKO&Zr{G&+tM@0Hvt9#MVO5$0^Fu^jQ_(C^)?dOi&QpjN7PKUiZA|SatyY{rPgOBi zS}CHu>Q2r@G%b!YsfTUYSUIYs@j-x42_$L!smZJMO$1J2@xLuQKxRvoe=1oA0QERq zr>A2_x>b7*4?qwxUwv_2437!G@4voIX`Q>`29Yc|wKU3yFd(ImHW^Pbk+EXk$|o5v zipG4<3l?>VjR6#<;po|%3cb7U!Vvs~#Kga?t!8b|lmmXz$NU#;;N~QHf8l+|4Ss&V z48339!3#dhc=%!bh?5pxZu{^v|B+xKKmW36<4JpNJ`^r>pC$F1A4H$`Q4LV(NkItIe{8pRyfCoNsMfr7DGz>Gu6lTQJ@4Y#^ zX083~&xvFB<>-D?WO7gz^`)h$qt@D~iFeL^H4_vs!9O}q z&~7M*aW5$OjGnyusnfBmeOmRr(`s`=a!7lGO_YVx=;pAmpx-j-lj&Xs9kP~5W8W#_ zmP$RC3burmSY?yeQPrk4`rl%X{i&R}KedbI*ZU;TF|LRF-9wjWXEaQ~0CQ3`WTCEy%>vSh|S@3o% zxIwv+2nucK$Ox$#ZoXa;j>^Dnufy!V-kE(pKaa}m%>rchyGW=ZFzLoXdpQ6qUW!jHInEHHzC^z zPafWf6bUc|W~Jnp%AX`5rrprh#TPzfilQi0AqtReTz{Z+iw>~ER zKn;rfSjxcD5^y=7{9ycMJ+SfE@k9UB9nuV{iUL|@uoX5aU_ zcHi!pl)&Z=j>()-3W|o>RU@mIu#zwf3v_rrJs)jEYpsmMEaJp5@8rXQP1=C1Y~o>F z?l}QbfJUTNOF$2s9}^KRs=}m(!J`4 zqVz4WNV&SX&8&(ul<*1X-V!f!fowenUSEY(Gcg8Wbg?d^>OYB#>CRD`8)te;3=0|G zzpR#*1CizoHshH&?)<OXy=6OfFzG11SMlMnC&1meTB+)N)wyOwef+nZ)6Ed% z=RH{!_QSoMiAe-e(hiCN*ZF`{4~sKMe?(snA1xM+xuVOHoijYl&l#rzNvh#pYxiIM zRQodG9Ta}Kn^UuH@Fi=aw&^{t_y*3nPWQ^?IlWz{enhFv9wapJ;z1RMA=k@pb-C$? zxp=}Id^g**InUcU9H1GZGABc2-}8DVNb0n%#zV7UYh+|#wm_tCrn8^GK2o+wBtdPO zRXhCJzhJA(+xGV_?W8*(YF1VRyJti@tP>mS&n5T#;bVheS@`(As^0H4Lp<6C_ ztiq{xf2{3o1%El0pfkk3w{{D)7lbc}aQ z`@RzBKCf{B#m|$%a8DFenGh-%<-|Q~a_(vKWUSR7t*=i!Zdd46JL5WJVI<)b_#nX{ zsgyBN{Fj4@2@0PO_~{kvSWE z@OKwQ$dO5B=GncSgYNf6t^32x6Zlp;sks`P47}BQLnrlx<@Px<)V4C}S}fL6MVbn7 zIWWH|E3Z#zl(4G}$@J3(igp#?@)Vs>W^8f2ojLf<)7XT1$tj~C7Dts$Ltp>??J(oc z|1u7#;#=G*-rBlj%F%q8P7DUH@Tpv${Z=M13P@)}1=>0#vz@dNyw_~2xN#R_Pg2+^6NEoCDQ=9^ zSH3q$S~cB$u3{ctSL`QlB|QDLHNkro&k?uUoeelPc@?1zS=5LX^D)Lx5MJRLwiquJ zk3@2RATU$@Fu)cB4E)>k71~u_B&4$-{qp^8f2m`HXcQUHIoHQKL13o8s?0lFl|_N@$!<%0yE>;Uzve&`+-tfV6nyl`QI}SD6idk_Ysmo z5YMaer|!g4YyQriA8>`(TK)*#cr~O=MXcHA*m{4Oeh1+{pP+^Ox~J!zK&}vs9RT#y z8ZBzuUT9xP>Zmm^Y5gk=exVy9BSnyqC4`M*hn<k{f5CU?LDmDjE;vZj~+GQ@O<*`_#-2IzVf@P0>YvUjVpr+e*f=?beW@38|gPErw z*I@f1#9Ybd4~x|D?AMVb$u3#o*Q~>Ua^tR`ap1c`HezetfK++=8)#Sh6op_gWOYti zvDXpKyhJdRLt1%kzvhy>OQs`z)P#>9hxeQSs$-gjH(=j0^F{^*V( zT61WIb^TP*chBm|u4yrDhn^7!_jR;enL`&-#kVR2{&N?8KDkgXFS1R(Ff;Urb;%WF z?`Ejes2-GQcC(7p>k9#TD=QsZCoP5sNi18&YeBwyN{u#lv=)zBu$!G*} zcDkpq%bqo7Fr2{Nc=mo-e!rfS8)SHgIKQJ6aa|X!Pw@_Es;dir)Vq#% z4orOC6n*;ia{mq$-QRl4(oIQ{;%N4gvR$IG589rQS!@|kJbuhywGOi0;U*>Fg7_43 z#!Pw6;=Y26JR;h7LBleNIZE(DWbl$+E^S`6;bK@pS3+xb@<^=6 zE!gVmG-dViBd&Peh^n5epWAmi;VNq&zDZgKY24nYwoj$~^0u4!mPz*ZFY@KN>)wBT z)fhn}@D*p{c^&#E92$%*|ICl;DXFRvb~e=2oZzYX51PRi z9hy|pvM8dq&V^9=cL=+6f$t}0GZ8I(5Zs`pt1M{*bFQR*bTy*`vD-djp$&vczg{DV zkWdy8Db^k~zTsDS`!0e*xw7io|L%A-SanXg!k;fHdLU~c zo`erbJh_m?OJ~5LkHXDtG1$0@;X@p;%0Cr-HLshv2nU_nW<{}hiz4BGP;GNm9Imts z%~vVgXa6IZVLlH}G=w2-R2MKec;5g!Apl&Lv^l^C zg;Z!C|DfSaMXG&42ZbdTtP~2nN06(_ZX}IdWI#y8X7uS-`DMums&kJ`%6-NPN<_UQ z;df!cXTP8qY=SaAQx5pIGA(Cez^YMxK5{JP=+IHaGP4se z{NOCTG7}`YSwxSm_v}(r&huvv$)3c|;rUxBd0dFB+bN4FzVBN?n&Vt?2L$I8-BJjjzYC4?E^YQ5w$$< zy7Hnt&K<~Y0Y3RJyXYHy*E==T@-9{(+^DUL3~q@xYfz{vFOHG|p|-nw@L)EtcaC8| zH(+P($%b2|mMqI`U(i|I^ne+M$3!S5G|xh9R^U(z`Aol4g__(e%Z#j|WEL*26Ke~H zGvVuDnTayTi!?E#BT4^@qw2B49pUJrpw5UqrU?PhB*&p>m87XDQ|98=C;E$M`&AoH zJzh-XHCPc-tk@iRM$y@3m<<7{s#gfh6o=8-;RrDD2pD@p~&ZvmPX;{ zD)+skLN4P%w-2>XHX&hw)D?k%lE1G8l_eg{aFjzk#hm`>oouvBvZg^4N%)YzI>hK^ zCjdPPONAHbzJ>SYDDhqS_*Qt?2Qtub5C{HJKON?g=IZ9Py{Kn+l^y(QEQ>fS3b-cV zR(LX7DHUa+U^FEWwmNzRbAz*W_&l%=s~f!aU7HVZ(O&~SokjmRw)e7Ag968V7ArmN zfV!$)3(l?c^J;JW-zS98hl6u^_BsDj!KtaAWs2e^Mc>mjBHEue|H_K4TJfMr#(;(! ztn)-!zFY(cdikB-(#ZoE1Uj_9Us^_f2Z@U{#@APSimVe8k2kZ*!ZT#Pid|*W-+rh` z$*ubtmruk?_ z)s)3gXvNPo%8Cj+((P=qulL7^-Zs(Sz6D=<2SrlLKTanG^&7wK8DBkjy+6NnblrQq z%3LqAiR{UWKB=BmrWATY^@BfXu*B5FZ(MghjywB#$DXw4FzZ%k+6+WT;V;5X!o7@V zd&;%rC?hxV5w5JMwv5-A-uP##`que!l>&phEM)+9X+V;d8C4W=Mv7di6SOYveb-? zeZEzOF&>HeI?`JQFUf)~;33|*@uojc4yin#&+Sr7_vu+fgWFekD<_!Ll0HekyXI|# zt-+7}XB=egBxcXbu($uVRsgFPSdrwwcl7tV zK$OS0ONPaY>)YUttEkgO(hZvQ1ueg8&bL&JR=ba;u%^h{1JmhPdx2-6_a0^wXZ(uo z)~#;T?r3FuAqzmoj>dXr0&4cO=z0!Y+I_d>wlCK2sGjhsx!Q1 zC*xRECqdgSm`sfgQq+F}m=K)efFo

Wp+Ky-FhSM0tEdny|Hx95RLk23<7SUKoX^ zVZF|Ta48!iklpCG>g0`c{yPu-zKo;tUjY(dZmtPkvnX|-M{5C=(b7kmDX$o#iv)GXnFnEnQ(0E5dyQHF%?4I$n0W#{2%3}^zmve$ZEwRrf4Qf>sc z`W}8eL-TlPO#jx1ADt&&j#(B|w#EO5Qc*Y-N~yh~HK2U!i247~_$xMHP)H;Se1f-z z<(w~`MMe;s`Q7@Vvbs(|sI@y{;J}<{m?CEIt%1USRqojc<~a>;1xi=we&TDe;{`w>)Y)sZ|=97|%gw zKhnw&)zoZ!{Vb}liDPYT9f%<|xOjnf<8)S|Rgo9WSYlD9;~-ne5)Wp|X=4v5zf#?i zn{Qj*Jpm#)aAN5RQ+ocGN00nKMllku&&+dhZ;xi;;o$t{C9bVaFmXW(CqM8GIj14u zd39rd|G1USr6i4cu|mY@wJ1^K^vg${Y*avMY!iHMYjX)5wg^iL0-?p4+gIK1uo8{5 zTFkkPH@J?RT1eo-twGlS`Az~qf;nTf)8zQv&@jWs`f)h_9WFok&DZ`wOH~{7{gCW! z@ueyFjQ3A_`z~AX(`S*_Q#|2~*5|PfXSZ$N#2KndH3gA}&5tpKCP9Ich8bn)ln2{s zI#N=t5t2Fq3cWWOKtM@#B?lDjPg?Z z>bCmi^bX(K*q8i9FIGRG#h#J!9Wqc=D}NTE4%m>bO)N!>d5a6G5m06I(M;=$R8QThPC&N4jyvMXuimbdfQf zeroP7&?uun7uSEsZlwLJpo*Q{%=cMtkIvwG61}FA^mS{G6Z}5PbMDp@U&qet`4AtR zpiN;jm^U*YC^{ZAzY?>hEgl@s|qiF ziTrLzU{gw8r{b69Cx34w8jBOrVUOb)u948gdt8SWpQ9+&0P4uEAc*JKoXzLi>B3u-7g@A?&>E z1rk{~(p4QpQNq=?xKrNeSCC(q?xjdsXHTlyt+^Njwe2Z`j8;bFKFx~2!l*wN5>6O- zX!Cbc*C4MR;G!k#^qa5>R3>Hw>g;-TvleWv_$1Ex{Up>*zy}VbSrSVN$Q^?1f)pF< z8deR73Z@ekkR8rxiUdt;XXXKv>7$XT1iDBekUa*t@RDZnxQjaz!5cK{+*JfEiQIS{WFd)TSRg-DjWQ(IilH7(M)EZM<1CK!BM->YGF&!Dysll67Y<@mzR*E4Ec2E2 zOD}sbe*C)4+crSk2ircZdk2YWrmd|zW=>3Ca&AJ;NYo}WbMrW|6ZnN6lh`q^AG5}- z;96RKQECVkmZ4f|x_kNc`UMSIHHje%`sIF>Wr%Oqp_^Jsa$Z0%ba}d@fgudH%qr#s_W5Ecb}!z0krP6PrO2TF>nkRFuD-6=(g&-? zb5?PT8{A*3@&D%qFy$6(UlWI6DE2YPSqE7RJU>59pmfC_1eMF()Yx}r+tGVy|Ltmwh6d%+He6tEGFL}Z4i3^*N+z8!OzpB?v64Ds$K zA6*uK=w2M_Uj#zGTZM2TC9{ezvB>S*8k6=*$yI(VYX1`5)tpk!nbvw7Z2hhFBX{ug zzgy~@o<6!yw!DHxe#>o%9;OVhreIXx9nBM<5aAV{RX*iSg`@e1<+W9EN%kl!U2<2C zZK9GbK_E+hmMbvsAMmczA%kmMb_npse9$N__z%^-b|u!PoYT6~K;hJK6A9bM4DiqNJXqP-XVm@CK^g*1rBkPtY1d)`?n_;s-~ zbgJ_i5W%{Pbz-aVPW=(;)*k=9UZ5K)<)pH3kKLkikTCA?&tPil^wvTHzQ%J!fO&TJ zLP~1ai~|)gs9$uklWWrDOz}&GdAhsLuAZA0dncBjrep+ixVS!6)SlZHAeAY06%5$c zv+%$tk9Zp1UvwbL9 zfjkdoObQRn^wrZS8=|D>@b$|AZl=r4v+jLP{)Cldqur8eQ)dEe@z=TBvWHr>VAgP7q>2T$46Rkm1rwtvRaM;4p~6*WYSk>tq7Bk zg+uEq)oeTid0dBxcH+uT$dZSIqIjP!)_=wpB1=aX29kGo8<|{peE7+;MydNV%YcXy zi;`&yztCe%4c~sob_%l2M0%CuZQNnilog7d6Q7@4V&3T4uU4oLmL~G|4?Pmk3IFJT zaMXY5vU7Zeauf!=et*HNL`suZawSPJm&e;Ucx=JZtqeopFH)H%mY{U$_BP+{rE)k1 zW?cb57%E>WZ0b46(y*hI7c1N}6EMr70iqQ1HW$p6(t@gKCWaSfQ&p*3Zw!0SpLva= zmhNMC?AOpjNCxW?8Sr4xI#M$kOQ;iO@(5>a848Dp$UOXgQ!MCdo}!zb?IbG;*p%8! zYn=}zxN8s9>v5u(@)>5M@6fS5U6zs$r{*fZVEvHosE8E6W77+6l}hjEI9K;b8ng+C zY!n`>yzFGN1n^#%F?y{U${GzYqi1c=Rz6{z+zOT5p;vfo97 z&g8>!OqyM)`OY8dm=!0T@UVhzM#UMd-t2C77$)dcWmaCFaGpgK`^1cCXp^DLxJ9;6=RfBxT%g-0ZQt&D$AM2O@uJ?lP&o zREdmx&AlSv@tYxjv)(J<-!{R?+P^!e@c>=bW7PQHwXMC!@C8B{v${#9yVDjtd3h8# zQ5Z}(N|7R$NN~-N-v~6Y;>7+9f!5JKXjI7KuH(Tl6{r(-Vb{Y6y$I-1_@OQd7;p=` zik$xtb2d6~cUgo2Y2a{hSGLzFNR1)3zs8%~auMqvn8+pG2^e z7U}P9{r+&jL`guI`rH^1xPDcDdYIIEe?s5T7HTDD=r<<5TNnO{e;jaX-IXA`xpm@_ z$U61PVV&Q|E%rMiGX~-rg6(F~gpXyO(Z7k(?Lq1NZ%>ux zegfv2yMa4g4l+6JTw3>woY;(LRp@OY6bU;bz5ECtvPRrRK(Xy!xE{W`H<3OE>!xw0 ze+`T++JhoW!Ahdq^b>s*bnsAW9D#@WF=Ig>PG-&)z=DZmQ!`ChxBP8`Gje1mW z7E@bWyV$n3&HKV8D`Iw*z_=r@FBXpt-obRsqP~_awH9){UAMQjnX79A?A)Z){~q4%*N6OU#i4wR&chM$ zu;vkzZj^W}zrxNK=nE8uOY0$uv&C2D%rguSQ^$7DilBZ=B2UO<%fS9oiuprYe23B~ z$VUQ$G0t%+o{VAgz5R!WEKm7(xE+VC%y~7QqsmDeD>1`&Gd#$L{&je& zO>S#I+i=$%>Qmsq*vN?U)Emss(92I9ql7GMkPRiB;X+l-ycuxUO^2;|GcAjaE{w{~ zCUW-OmkJi)1$~K9ZV^gbh% zi77i7Q*Z+5y!_^q!prhp8C#%qctW|9xV%Ur;Cv_k>wZGJPO)prm!uypzOXcjv_OVb zD(Rl@SVY~N&oZc0<>I^rQn2PKepCQolo)d{E4a5P;*Sn(pcq$|mroDx_|uYhJ7EDF zl5QwR*PH7Dn>%b}cL3CgS9Wt~`$BcL-H!s&TNhX$JT10P`mNm1=X)CUZ)M#gPvn2d zEfU(?o`&x34M+T`s@UH#VbyNe&LB1#_!wBt+ps{G zjX4P2zs9^q@b65v^S^B!G;DymA1MCWwh-D{UPie+jnmUFU#ZR9xUOaXYv>@C)|*po zkV8GTm=)Q+|K=3lOlYosD05S8ZvA2MQ_74pmN*K_AOS&0oRD;JGi zmV9wV0Cr(Rp8i4%6^O~I5kJRPRbwmHuyU53Tmy?C(4_UpTLY(7p<{dl79BNibaRk~ zb=*OeAhnWzqNT?y?rl)Jw$~1((BzaZ)H!UB=bO3FPsy-0rrLX1)5yGm(wHSl;^wV= zKl-3M426GlA!`RpWNs7$ln;ZI1$PY8kx3^|f78UPh5V~?k=@1_M}$Eeq1L*N(mFLH zTgyZN!B61w=pD=jffUs_x*#v?@YjcHb2OGg!XGSH9VJO7E%*9O*}C5Of);=1V?_9@ z@Qu_pH7|02CKLs^ta4fei4VW!AUo?15eEy>mC&CdHI62O%?#;9up8!150$ z3^y?B+Sy4IwGtw2Fk(Xti4tO4MeUHj+WF({$QTnsjfSa~T(bZx-hX52BFX@tZ zK2xx$zyO}LHMYs{902wqEiElkCQN$9HH!djL0X;->kR4DNqDhoaXbolx$eW2(7}8p z8AgQ2kgPLLQhbzSANow%C`RWHch^+9y*fszwLyT#uw8={HycLp-7KGmov?PhPa7JnIiy;~?#66g`+`_vbt`)Hl%N3&LZU<#+# zU;F68Q6$0;F*zY47!>WdNl7q_QK}y#DB5eO(xenp!q8UbP?}_`N@$WkNJlN0>Er7{ zueWpEGh1c&lEgPr=M3X9Mk*dlO4qm`)0y!0B&tai|5*|SP`BNHBn(ZDk<@=ofsZ`V zi`nv+7YGykFA$$2cHXw4_NU|=M3?RJy1CFmSpBuaZpeHikP}Gbnj_+enf1<;jVdOuC$s(0NEh;g66CX!_QRlKyzf|tbO*-8GhY%yY2=WwAIhJjWhL?#SUAA4mf+*8Q# z4Yw^dlU8NV9{*!J<}c;**T8MXk5O9_m?Qp|@sUPsY4J7?@&BHhr!|dJ3edGZfFXhU z`}Xz=$^mhWao2v^#v`dbp}V*DppVf0@o~(!+m7nxC4N<)E7>4Nd^NtZOl3Mzibbzq zU9m07vQ7VJ2AisB_v>p;>hd2v*3N*(lyR%si`=(+pI60npqgnp@iBFbOrVLO%(3I( zcw4e33oH@+-|{(8_1;Yokk0}bNkD{h@aupBZ2!oWeE9>7<)5#TtSKDtZVmg2hSx5E z%3Hs%V6=FJx?a8w@f)BiHb_PPM}q_UYsQm}#RJoeq@*{%w+-)M{*^Shqt>twPRH4`SDpILH5hLQ-V0NbUjG+@NE=;SP8C zREldTlEUgUw9#4=D+G~UKffq!(Fu$r^cgd{<6t{`b-$e2ZF<*J?x}6N3+ub5IYq;J zHkMxUIjr=o+PVo!d*%2TvLIK3*Ca|4x7PIg?7vOczHpL@Go>OA8-dfwpD>y8D-g8F zyacl!)WhjkI=<+SsYf0r_a{U`j>kMNmANTiQL}ZDtz>Zgb>`1tjsMilVAQ>dDmRKf zO!U!5v3EQ~tC^7yJ{pU`8~Q{~OGT4O&O3Tsg2$HAf>fy{-X-y0xfVj3Q|3WsF=>h@?xpb5Y4G%^pc`t`_ z*yptI;a(1LYJ}fEX%THtCAk{i<)~v2O268d96Z&vaKLMXVdI)}EeNEcbg-m0m=H6@ z!RIBzN7HB|&>wbc`K*4~VF&l(%T@)>IhitHn%-FH-?m$0BspX5&K3EJ{Ae{+#dJ||gO*}RPe8W&Xv zVvr;49qC7iNC_h!7V{= zeGz9u2qK?Xa-R!t@OX}DN}o52wl{Vb$i2J2J3pVmo2~Qibm1gVz^dnhw|8BkloHGH z9~Io$Je_OHO!Jh)DizKxDQ7(90~PI_|UhOi|XdJl{q{uEHc>~%Vi}w#D%RKOE0hE&s3`+mCTCU z^hI_kj9Y)#s1GswKwOOU3q8MMlsP&mVPXTz}QYF3Y_(*Qpg){H|j+ z*z6+;s(m;7&tMpd&KDxY9w9RK7Gqe=Ih$qq!(%^QU6fex@G^l%2l)VPbZ?< z`#!?}=#(1&UQp^Uf4oyk!h(C96PEnPDUAn=S4*EVxZwL%+x8{kMSZIbo03f#9n0mzUGW6iPQ! z)l;AG8@1j#LhpfgSY~KXWk^)r1be)d>Oq_g73+jDVz@acL6ayQJV{=@H>`MeNVu|G z93`2Kt80*iYS7Rb=K*w8u-ZwRc>xE#BFB@JzR5%=dT8_;_|B9EepZc}I0lP}Du-B= z8&w{lo+t@pnRw>o&IS6+`0d$EUL3z4_^V5QOM9E@V-&bN4(e94HgDXCWe(U{FL?d# z5vG7Klmwn5{}Pw^FNu0-p{40_Sc$5eMtdC_JHOQX5;_c@Ry(Og^1Wv7Gx81ot;wKt z5$Z*2aP zI6C@yUng=M?5Eh3X1AFz{nyhYxW>OTWAy)rB1hS}s6pzD3++Cay~xzDh4~mZRew7= zEQLs^N_NMyd8JgBHoDlOhbyqA)l6hkIZkdPxIh5CCE)Gx064DX<>say@RJ4JU;_JU z$1;sRfSAMilbtXT0M+I#R=>PyV#CD_gaD3OinLt|9?K4c0?(yq{6rZlKyLvS6LFWl zW8J=t-F+{4M;-uz!prkh6nghhKcy$T`59@hau9k|OuI941rOvEfN}&}E+6DYe3oN# zlK8ht9DH-f1R)FPFXLz*l6mpMxJv#JkZvEOhBHP-wcrUN4l}}2JAhS{&`k%b>a-qL zLWPyEz#ItTn)Uzzds=-}BfGvLS7yX;eb<81yus+I$~iDL|GmgbM)xq6oG^-uYA1xgq>J~>#lPA9Eh&3$N<~b-;py%U z_kcJfqvqkP>v8pEI{%Gfq$ld+*p4t{fiZf65mN~hn#u#HlCW+9YmL6D1O^WevYB{qI22u%;9L zfoVt@{c=wDE@{gD{A=8tOI&$zsR;Hg*H|(TWoR98!Onff-n3iiccnt&g3>SG;Y8B< z4p1HVRKhM6KRxIBequ-6=n_hzU(03r{tt{T$Q{WgD8Coju%w!khvjtUrp7FRU%VP2 z`K_OUjLb>jvcY}jS@5GOv5B6A9z%2rg)X5uhWSMx(AKM&3{%^#m$i6#y0MV9^3KWi!uwoN-7y0|(R!%hU zm<*{q>#pMwB!I}Z5x}v}{3F1H-_p>|X`jgH9B+-qEgiVozZ8_CXztm>mCT_+fEFgo zakVHj4gBN;&iczGs#(jOS;8M{3Gc;MH$RjfS#Ypo`^YLyBXD zl2!Y*jJxXSw^WN7yS?)veuwzbH1#r5eW>7D4jR9R)Y+0zs4%0#GS1Ia=d@Fo{RnxT zRa9Bis^x12;Zu3PuW4>J?!u5%GO#}qg*Ux$c}cz})gfz`wEdYn)u#muh;A58$By{D z07>wY{_x|GxURNT^!-B1!>-N_Gp_9X9IWb^I?B}=GLPVT<3d)V$Wtb-^SVj~jc&>f zS5#!1;FVBmweaos-Ca6xPb<;Um*`Zb+W;*lY-%#Ih=5nW>O?{!>xs{Sz)vZUKzM(;~0b?f;okd7ht=6vDh^Uf-~{LhNC>I5V3|W1WK6g%fYnM zS=4bu^(fHHg>blIy%yIalct?mHqnFQW0Jynkk>*{yqeFn@xePwN$~=^ps=KZG`XEe z?)ARs1hCCW1KF5;Vl?sd>T&CkVCXp-jvIdDkA41hzK`7NBBAP6cYM-fp9S6rzN*fT#gy`&u-|XcaU@xxZhYG?{gg8qvN7U{EnoYD?dn_wVt@-#Zu-;t+*+7 zx%g54oZY7WwbOUbOF3qzu&>m?E|EWXDtyx8K$eaWx@B{nCwH^y{JBT`n~lwL0E*a( zBbLErQSb<+&F{L8vHrzvh!SvJ}$`tQs}CJGnM zyDGBg3j(!*e6N@owz?L712egzS^0_^59ndjZRC~H`mJ^!`kM9FYEkD@hCtLSd;FfR8&MNC$=rs+JTo#g&$fRW1BSV< z6{sWgc($ljZK^MC>|!+ZgY6|a8XAbD-Ar|qpqfXw<61QgX1Q!T!A_ zP}KC`omuocpoRcoK9=?WvlTy_G~cwA+I}(*GzSiMv)@2DO9L8>65f=J! z7S?73`Ukp25ia{q>SEvbNC&xvvPb(gr;MeHFMrdmxQdy+_{sKr;`I7mKBZV0YBY`P ze*qq!tj_HfaeU4o5y)oB_3`z6&Sa>Trajq06)orl7q&_<#hEkEX~D7)gd0;m{@h(C zudxwss9M}_3|gI0>c6%{(;Q2kmsU{vdL-O4bH{GSx|M0@V zeB|&knI^Kf&8)u7s+B1GbFHr9M4M^QTaEwM0??uh%fs|`81lbzDZM^;s{M8na0Amp z5`8|40|GiD@jv#V(ff5K#xnhewQn-b|87lpgLar`Y=zU%#DBl?83aY8O5y)Gi;24% zG=8M0Yc1onVPrMl6fV;B3>D1lUJqF^=8@&b zH#FT}>q<~JQ1dDCCtI8%pY*P#)5p@9Hy`zuEgc6;CLZ*SO@#NSTvqZN=UclPeZz%G zzC05w30Hjk6T5J-aD%Lp>A9gs+flny^7$kc)tT5}|5fO>^kiRZza{j6CvLgBEBpIc z})F*+Te1{^9u_O-QNk2 z`uk~X4vG(6U`dkKhB-ERBFeA&{uK~QM6!RD53x=vbbbfVn=+JHj!_o;5*8BNmW|1T)HXK*mB=C{kdjL)5`?>c-iliH*vf5Wl&kwTbf4Jv5rC|J zsm)tpDIMa5KyuO(Ro~lM;gYF*?cd0-opg}Mp+gli-DH&6cb&@0U$1>Mi z9;x3h)kZi)3SgVf>KblDOGS}^#YLewbNE*wUExJ=KjA!wW#@vkt>oFqJ`J^s;$5L1 z0??7%4b@y9*-H+V8mjspLCv0H8JiPdv4@R{)!a~P1nS%TJc&2S{UDZp>91jtm*yKo z5@G$dF8U~!?x2Z>$-l<{X4k&k=jGw}s}c?1@O@r8nkdm@SBcR3jHRA(s_-qxFQ`{oGQ21*E=8dnm4*~C<}?DCPgpc zjYv%YEd6`!dCcn#)*EPnEM@VU7Gn-&nF_6Pqo0$LDgq5gU@5$}D{JuEC)JQAe@uy9 z;5kZ)z^(wO0OyylNa-`!A|tmg_1XFRZ5x+x|Km{#QKywlyqXK3^zS2)APD7(5kqB5 z?)d$?pzQte3F5ikR&=|4}1XcZZ%jRFR?FEF0h zM4!yl`b1H7(`Fyj>aN8^Zk$9J(edl{qR$#)49BGz#1xZ(<&=@?PptIq@33^=tiVfu ztzj&eiUhC;Ip90x*G)00u;A#Bu~Q;Ner$Al!jkS%@v$?>`swE*Xr)2$`*By|c#a={ zcu19FEInkgQ;m87W%_bDEDLX26eX$_XcE1=yi7RJ9*U~$)Wa^vj$c%m@Q zu`GGH-{~tT6uybBMS9ut0G_|fT1+%L@E^Qy>Yo-NDDIs5{q{@7pZ!uSuu zBF}So)#M{E-bkkB=A4Sjjzz-BHlMl%L>!o>(NHtk+A?vn^!`z9J5T+q(V4z?ozqYI zj&30sd#y~}ZIS?rl&$9pQIjK}g%&<2i6Q5mPzWFr_6F_AHFW1I=Dbe=$wO%etrbDD zU$q$~V!HECHG}DC#?%wf(4@7u?h^ejKL628MA+^71%1kj%*|l)`tNN<>71aRtQ;8# zFS_{&Fa9mZrsnyh{Ro@?W#aFqk)LS?t=m5MoKE6fTNyNC);QK5aOH3JzSg1=<~kh3 zJmcz=3aOCQHfmBVpj?6S<0m2{>>t{-zWxiGb8>!d*y-q>mVI9G2R&~tw9m}>F)*WD zx58oAXYH!IY;w$_vJqB4E`qrAXxc0f=2K%I2nL`gIB2=yIqv8xLKBiic-VjOu}`}c z&QnnGf~Aq@al<4Bg#PjU)T6oq`U+J3OQ#y~wuG78w^|2F`D!DA(*0NX+$gWN6Pzkmhzu?&NRs(m?s z;Yi^o4c?kmkn$mxk5U|T*#pipwq4=5a_c&^uDIvod}?cs&E_K6=Ki#lX$gOQiN#y? z%+lN=+J@rN_02OFO?GZ4h!8p!<|vXRuU*nkAA^Xk?OKf2U~A2>VRnV$jTAzEdwv~zXe&O+W$z)V^6e|L zN;YnP_T*B^pnW7B-m*?px>ECa>jN#_ct5}o&@k25lbMpYeyJ;)XHFSZf$7MmDD zqeP?%LwOt9(+aL+jwu+9T6QA-Zryz?>@`k)2QsZ|_8?&tK~`ij^>39fgrYX}@mlg94{D{UIMm6b6meaa?i8?Pu?etS^N z;_H%OA(SQHqeP)L&-yc;ztT}Q>G3Zf*Tf&aY5l0!C~+4uT495WH?O?1vTjqyzBr46 z`95WGQ8~M>v%r142(F=JUdMrf;Z;+_wb`zReB9i^(*OQ*^*{DBh?fT)^1}kNY%MV3 z5JJD>sIOYb5fnPm$6Tzl7HlS@_WNyu-rW|h-2i2n^z2cuS}~<&g4?LNJU`Nd&YsU$ z(5b1KdHhip+n2(>I>g}{$(v0YH|V)JS5A^rS>t4AL~H!O|%1LuTnC=a=`?bx7{V^d8s zYqT|$P&vN!548V7)65q+_#9V}ba)Yr_RKH}f*v9zogyip2a-4l&9lL6WQt)V&L>sL zj{fCFDVm_^PD?M`ofw2dgsbXtTKk768rRjpymV3}T+2~HfTWPEbfj4hxsSTPp zF9bYZFLn^Kx$NbdNJLrWcvIvNG}ZI$_j86--%y&}b1@VWD3!x(vV zx|=dbL{9|Z9^Ecd#e7^cBsL@bZY!=q2*QWKiNtyUEdT^^c7Nr>PR3urql}*=;y(mz z-=&tDGI=Dyy?|V)jSB_@y;XjBO7#RYdU|?V==OOX*1ZW1%xo$vb?>y`H02_LhMR-Z zf*N&GcVnzHj;k`QKROq~q4w=o<>Dm6_CB3}&`Cf9knaMNBlq8XIJfo7M>Qk?|HC>u z1sst-Zm>Pm0gegauP<`clSt>PER*1DG?)*vY+N)^l*lLoW{i<}ry6gq)>C3!MILYI zQ-%va^j!pFN||Ex)#L8?DA|8tGG{LG^K9REVFldrvkIE`883*i>`%}4{eGNEssB+A zC0hg6!70rQKJ$`-k4f>vrvlu65-};>}(c78a^?=9?RUN54si)1e)TYv!K6e^TuRr&=dtw70f-Uq3 zNK6_R<9%MUX{rCf(iJ#&q#09Y`)WaZ=GF|YR&y$^n#6Rkr1==NMQi5sZpBwL_N+V4 zx#2OEP(#uual9 z7L4h$)&C%xvdcjMy(ZrR532|p_z*Zd8V&KA7Z? z1$Y8sOYG@b6`*MrXumk{@lHsfmsbF)W)L>#NzA|R9IX&M-Dh$r(yoLalF(QB;Ib)Q zo`GFegHCz-NnEuV%je+sn+qBL+AI#TJ@)M5=jKvA$#LYjicCPRbjG$%RB|HRM?vi; z$$y;ks&($PJVuI;!mEISw8AZ2Wd>;m8|7)Onc3K)C3XAe!$?A?;S`yY{ZcHVKq(0K zO)iqGR8;;*fwy$BzM@0v2c<%8Z!(TXux*l>7I!6ba2|K%&EsWB1}btrTqbjf{VlO< zzQ9uWDOi5Nh@izc5ohjha>G~AW~D^-_L41kE8q-Z?jP+opyT##<r=oH+Bd^X1l z9lmb03oL8&?wZSX$h%*87VL0{)_hV?y=3x>vhUD{$XJirNo=s=t2C78kiENNivJOzj=}P9$zK;`8U4 z|MH+L?2}7E)?bs=Q>o$vT5xSDBj|b8-E|`l;BJs{f)dNQYKVDANnt)t?Jh(#r+YE74cdo1DXTe`N-h` zfGe!MJl`0;-|9s!e_(Vn?%@AiP|spstLGv6MOOe_A<;?}1K?Rq4xE{1&NoYJ8{(pE z+ACJz_1%SAh~%>gXe2VYbh%ESCyCxA`Q2_XioRTkuBqvFUHs@nt49!5oM>0f zlP9YKfDp&BR0cU2Lb?2f2%Mzp%&jCh@;~aYnGDv`D@p>dJ!fXuw832LvK#GzUyN75U88QX zBGpK7VHQhgG|ulyKQ=GfVz+JU9S~@!?d?#d6~BzFOBkNLvH(>s)+iUp$%}0FZoUXF-wVYbQg0%@^SAm2htk6&{F!LISJxeqO)&#o708w)8j0nJVaQ zyG(V+gQu)KzBn!2Hd4|MrSSuAo`M8~`_O|?cVp%%pM`OlV%}NX0TkKgvTpYC?XRNR zwOy=whE7>2+#fw>$wTiIXVulr8aJl_Eo;;2eT;-!3a(9otXW7rns*AvkX3`jsD;s_ zCU-hK6z&*g0_8S%T^S*Qj z?Q5_7HN}vHy!b_PG*B%b=GQ!ldkyH{>ySi2{{{~y#tV4M}dj<{U%dE?qW~E{g$Sr~M5}b7kOrrgA{`fj9^y&Pw`_^i=$nM7N z#ooq>Fr<@_gD4p)X4nj$@3tZbf%WW?-7j%SOW)BRv)nf*Fk#8XzE6aA{AbKXP?Df1 z0RN6LYzr$|B{}G}_z2sQ$@#z)|g>ZedJe8&DxC&(eB5yZs_l z&R_8e0Ez0roQ!F9qVs;}==gIr4&E)`&gylPDzLO4X06T=>6XT$=R1An=ss+{(=uR_ zT(`AW5n_38v{KRroW zpUL`7Scp}s41gk3N&lzy>)E0m8;$c^mb=fqk6Vxbxh9xt_EJCHhaK80CHEARngw@i z@v|mIhRccMIebW)b3Z`@H161XbOIcb@`Gju-4P(Sw?|JR(PGA-yUIu~*Dya`EixK^ zN~l{$$xth`Eq4K;SmXwXGDoelry2-nH_{-9@fKh?G9Y9mMA6O2??Qj<;x`Mre`1MA8PP|ETJv7Mep)CvhMFpn3Tkk(~Psji%w)(hFgFmAT&+mqGe)s?)AU z9!f$Fl_bBCi@m?O|CU(|B_eqD*jFPe;}o%N`nldo#-oPQQ1<3f_VV!Sv zxdof1HTr^U9DPCQSJq{_9kDOX9@H6^*fP7J*S*2~|772PYgUZ-6=U^k^%Lw({hEEE zP`>TTZj0>)o@I245s>F&ug<{7F>N$C%KjO7b&wnjp$p)+p^0RW-)2yg#v`peeB(c< zen{ka26rfxw;C=4yx|ePg&v^a3e#rx=xT@JHf2+-A*iutI;^XmCFB>LytP=XNmYVB zpYjx~8_tGP8u>i!0^uQhn(bpvlfn!xTYQqa)-u7j*n9MKgs35e=oXR`#Q_Yv$Abar za1I}#Etc~f91;0#f#+p5zwyOc;nNur@uavo@-fzkJb(NPDuZSX9#y!n=z526a9ei0 zu@6lj|2Jg{wv|i?Igqk%)|&r*FE{}1QcI<}#x6od)}H0&wP(ko9ODxvSyC)n;6Eck z(3WeB8s2b5e|mbq?zz;~x!e9p?jJ_j_XZmvnDKvz;{P49*GJ?Po~Wgb`QJ)F8y+tG z7F-?!8(p+f@76uW#dD&NVg>Q-}N4Lyhwv>JyeWuOt5v2LJfGx?&=Yb zBY~&X=i5KCFM5fMPoJp$;+maSYZo0#W7dIm*fHAPi#CAEbOcv2JCUv}ru2I}>t~Sb z0+>QTHL_@-Xx8jk+3@(STp=rlKG-oLy~|Law$&ObWR9S6XO*l;X;_@xF)frA5)(uB zaYv=qfh;-E(O|8KMN6T=#bEOvC&d24>Tho#ctg@fGR1-bGT0MYh2|EX+o{v+0X()n zzYK?`na90+{rj&rLKy~i95B0>zbRX4NN-Y1H;hz&l$!=a;bsmJ5J5X_L+u4Eb8d^X z)H`>1JEZNMti{>Xd0t-B>G-j}-7itSx(}6FADlYh``zm8Ol_<4_5zSr!!$GJ(LLTu z2n0IAR4h34?CU;8my3#dAm@B%+sGJ6;9y4*!(_yjk=OWTi}G(CC=V1_B?lcd4L$Rk z(rxQIpFpo!M#TC>QWGr~hfEoocCV_H*8e;hpw2MxJ^C7WZqEIVBL7*&U9uLt&xMxd zoP{iK>cetY5zTewKg@fYC11ABD=IYD*CK+LOWD_xDdB%0IX{A+YtFJ`<{A+J7YuKU zt0gYCavQcZ0{(R?GZy8`y(bJJd{@#im5q<0)cY)SzoFbA>gy?N6S5YR@lS0jT&GX6 zxWD6s2 z(z?fkJCQelDy9ImC6(`_dWjAFpV$Z`o%qi`1Ea6D;lSxTq3B-hl$0#;e zB+)v}Ko?7&>`twixWnKQ**h_2H)Jbecmx^-vVasIgj{54bL}T{=w#-l4PR>Qbd!(y zObMoSd%$fCgY3TiEpipRRm@_9(bUVb&97)OHzOu1VGd6x))aBegsWfGGeP;}HyD5; zk8#dASTO_0#)!B;>l6K(@U@R^?6n-_hNvhJkE`t@|90A0>It;PSbP#r9db1}9h7%r zoq(2{->2`J>Gr}$!i+Tm3Vnk$)*fbl_OI1$&e&v37ktIPzOM55>qDm^CAah-6`B9; zESz^nG)pz(g7S#k?&a4274ze*ReSNDj*hOoP~1yZGs{~z%}5kvhVZ8Y+fg0MaL~ma zVBh(rTx^(7vwYMxuO4wRp;8}x0&fL?EAl*1vLU}=}iB5JjB8}9$34a(1pTt zjPmv1JCC9!&ou!VRI4)&PtUN%*r-aJ)y{lcJV(EiInf2jdH4e$dvO8D6Xd3cVv9cF zfEfX~u}2l7KEkGb)zRzbm~#0lRDsP^QB$0#nB~~eWVAW(;pE@V(> zARh1Ur>=W=e%(W!p4{SQ(!;#KKM=Lnvc%h0{@R$6?K^uLkDAw={IzDFs<6++wB-LT zvcvfDNiVxBbA6zZFzF$Tpqu`S=e0}nuVJIHeP(`&um&R#nH0k>$&yrS_P6!*&jOXV zLWG#-pOFtHwU^1kEht@wc2ah@T70IzCQvuM(xoFE^LvKgmDUBgvmfyc;6)JgIFq%;G#BBQ#zGc_lx5c0wwzLKYl%jDmdMZph}0lbu314N zNo|}5;n*pX@s0<6f`pxXn7saGf@MSg>g}xti#5X>{q$7+)Eo9Ln#xnHuXV#gntuj( z#9!fx>ou_J%zh6~cuzaZOhO7fiwJJIQAO%p=I=fImO1(Na+4$%wO?q5w`08JDAkd( zVCY?l(Uy!vZiztb1f^ywH7(t~nRq?ED{_B`o9Zdkn@Aoi|yg1!T>1`?#u z*TRPy7WeaP&Uz074>{*_?%dc^Qx8LzC?!P;`F4E>($MWh%tn5IeVCzG2r zL0@c!zH_d!ceJ>E<5e5Eg0Xe-NOo1#W$FIE7GNSRjDr})aag&jI))zw<-oTNTPS!b22L7A%0dNP46)RW^exC?KHTD!a=DVq@1IYalDVq zVcSOPA$;#|@5iTxP9+0_T*Eo6q`?tyh%c*HT9Is_bz|QxLPSa9I7P5;Gqr4TYm*~p z4z$SrLD!unq$d<9V=H^EU)9JfRb?TCF=qD=Md=x6E|M9p4 zlvQI(ZXW}-ys=#WvIk)((Gj6cgbCc+T(H3aeR5W?T^FKC)bjJ$nlEG)H}1|!9Or(22SL>0$Xx@^a(qaQ(aF8#O)c-j^+E>nwMAsluy zJ(3A@=dyZay`V`v8A$P|X9k@V-l*&bc)Ior*9VXl<93q;BzY#UuZc7yA=N9G>l^Q^ zgtYJE^pIQD{RZm%4|1mjlB)JDGYYmrzO8Y_IsR#fUbKBq6iqh|55&hDtWsN1`Be(l?+*Y`3V@#Nymap@VGpf!!&Qyh4KaWHm>bVj|C zJHe*|$jKDrnfK4Q0Er2NSr|fexb7XHa^lwCc6x%j*MpABDHzlVRQ<8TK5lNC8&k{| z$9jZPVmwr}1|QYJ$8PvlMa4}?tMt9#I1s8>+{c=rTf15v_n0n`&rHW@sZ9=oWw98; zxJEd(py9HIXJEw6ldeXD>}1pdbnM^D%XRx%4{G6p{Rf_5!u;a#6=7q$NOB&nmW_y%w0WAe z#xakHUO~-B5q_Pfv;R}9OIqIYcNmP^@*<;dO0!TpBKgSw8zp(2WYLnuw-6*0txZ#a=@bea@USxihi;b#Js)Lo|ZuuH1mT*(MQX zjhF&`ID~&e`=+#t*y=lWd4qqXUTd-jNYry_q?HSOfT&F@veCgPN9*ZNs^ zW{d>3eDJ)^rBQnl2LC=AJS3Sew?-U|ON7qtICtS3j~=(%Wgp-El`7~sYtPQQ)_iX? zuOyUc>#1s@6UB{Q>BpQC^5NBwt{UnC8MUp-C#3h#2-7wjY!EsGQm3<$>plvMf&$vb zd9l1%TH#fThw^1`B2sWz&lbO2TGAI%o3x~!KmTI;dw#ibsMSVwE1F4=BXj#7@SgO< zeW6RVs7|Abla9t$;I@hIM7FK4(Fke(lWWhV8)v?3NDo60?43@K_~wYGth$aH;w{H~ z%|I#Z!}G?c*+dask`l`|a5=(o{iYvJ;b1Wyd-oWgCsTg%I5sGuHu@3xh!R ziU{_@M40X$ZDt?aZ+n3H`%zrwEPVS{h+Fti<{(BhM2Xp$=dLqN7vF5Mh-zX-|HipU zcssvKz;(|Rzw~v!EG4Qy9HpAFcQ92xyq~^3*Q_-z@sLtgnHPWkNvhV*1Wpjy>^$}@ z1!tmF*}A*{|1URprOU>FYW&+Vx3r?nMg-ug1IEk1o(x#7xd^z1dl0yIa~D_WFO@M3 zaRS=e>Al|)rT?7>s%jpeoWN4APFE#5De+K50hgOrIYdSUBV*}b3r>bavU-Kq&8p`D z0F}4h8e=7xfEwl(Fhmft842avkd>7IDIFdLCtOOpPDBk#QWXq<#(vNmv#)0H2uJ?> z1Q@2J8{e-zV?R$B-w(4mu9-D5ja~ED9n2;kcskv!Iz7K_gW5TXqE=9ESw!bLy8q0B z{qaQm4b{cl1~)hL=ndApbV(}dXoo6UOuosp>|cK1em`nmDaIShmk`ZXoXWRdq?2>- z7EDk-IKVBLkNehBRIy(pOUQR0<4@uP3>jv&DbI&Jg@n-q@*pZz(ubZ*quzG@%>MLi zJT=xK11zY3qG|FLm_vw~@U)xglf1OrR#mT=#O&-3 zMqlk@F+i*}RJF)ABx&=)dpD@^kr%>8Ev4WDfM^&zUiFa!I%?TUCoiq@x;YA261U@t zSvvNH&0xq`=3D(~`^n2&U_Aju&`oebZWQe{nS@INmA@;Qr|qo%=c}m8+vC#Z0iz#w z-EYgSA{Rv_&DETl9z>PS2UJ#RK#m*m76J@ZsUA`1qZ_&SzucN|N|HWO&T;D4XMgAl zor}x0*)iww^TitJcH=WRQ4R~DM37**B&)OcDW{V z*@smhJP>qCq-FV2MI0GuDO2_PkZ*m;IQtWKWzroiJ|K~GEe3y2sorse+Dz%tGb?nt zkJ{Lre=OCBotaMHSms0HDip>kGWQy5v69khS6x0#r(D=Y#D^xuH3445M@(WmQOS4s zuCmM8FI)*86J8nT()`uYHm%I89^MjC#$r=x3Dd3BTg}6=uaq_idw}Ke5{gN^P*mZqhYxUMvFDa+IoHBt9=?w2Nw(DS*{l;F0FEGTwOsZ6(_25gdV}jKinZ2QbjkX<1R&zl|LRIUGM@jrJ zlQ)rTPsMskNFe~&OK;t&i7Sh5P2&prvktFSXr@nmF@40|`WNHfP_%vh8TMTBV10Bt zPe>b9MJFNkR7z)XE$$o2J9P2*n@dTIBwG>mlnma>dQ!EZUbFHSaa#+V*I~Y%ox|zH z1@xn!$bo+Ij~_qQ%+&#b#fnTUM4ls7+6;0VA(kmFSyMA@QKHocO&_KNhJ~nI32$d# z>tc8Hou;W|37OXGdQ%nW+LVpaeF#5V@eL_k3L7SXQN}nKJ!l1qp{^AVTIhP-_Gg@#)(0%?tfYAN9kg-{!&E2I6_?@Y96qVbpJKInFUn=9i@wo!FZhjZ&0tE7)7ChkoSpK5%;^MZ9fl#1aMo}^h%h>;l zP$fIC=Ww5NxvmI=;V!s6dcZa?mAW|mldI4zxmGrj%Pni4Ei1oqr=IPPIIXqt+H-*S zXnpY~tN(t1$_!&PIVv3%w7Ay-?%!0v<~}}R)Euvt?5E6H4g+u0>Alq1{Z($!gq)8{ zu>plK5<(%WaN%?WfB6BqCWQt!mWuxyE9(TEDJ>H8D5<}UgMewlbb@=dpEV&*9sePxb3 zZ-T|egc1|(S`FSlb)SCW79p^r=4!xRKVTQnZCl$jP~KW^H~)T(jy%QuNnQ*Ofzrkj zTWQfwzUqQ*2|CW7-jhaPB;DY?qVV%tKru+)eDg%|gqgLhoSNgSWy-3B){q?AZK1am zF#jdP7T&-L8t9|f#H)o@+CY`Etbm5%iyACg`U|d>`BGw26KZ~`zvrJVB0?#Pe2&e% zXqN26K2lvCvyANtz5;cq~d({U&Z$jqiJ< zoA$A;5f?$|4X71`RfvVhIX0#*l_=VMHKXt0OS;jwoxqz;1ofDNv@9+zvu^*-12;*P zNi3=ZSL#i*?DO9uP(O1_9)jdJnhAfdi&wQ*L;(`+KW|*7No_g9;t$QqhDEW|ov+*8 zOCjHQU8Rd0eTgr@K?1S&xo12@Y#xTi0V7b{R#7M zoukHXSY?H$KG|j^{nG=cly_Q@P~daM!NEbSZze;8gr5In3rEohRe)>mj%=C2Jfjq$ zZiBd?z}e?g5{&gC>5c2(R2CvF5~j5;8vle%@PmB}`xT7r?p8;4b{1av>7&|J1%ZssEqxt83V6XUPzx;#vd`) zp0Aw{R)N>mfD~Z_LF!O0w~^e$Jp&nZ7w9GFo}DEuawzp5a^x9W^yb(BCO-og8P$L8 z%hGuoq?4M_khvQb)ojqUa^HXB!28hy`ZDNB?7gZ<*u}(<&+$esKSn`zCg23;;~Y6S z9MWak3UHMB)Ce?3o?O?fR2opM0F@r~pU2=y>mD=M{yCv#Jw{cQaLClzw!U4w!|2bo z2Pkoi2F%j>dW%t9enE@ljp2Gq@+ZC znK;K}+Hk97X*f0~FNH8W%zw}-=YXo2h2+`jY4sA(B2oLD(gJIM-6Hrj^Jc0+Z}RNW zTKdE7z3fr8gOx5~KjCkuQT03x0jI|cRSf5T+wt$^X)Y**&q*8JgXZj{b@1HWw2j9M zq(;xfY4^|nr;$Yr(3JIb*dF| z{>#Z2<(zvk!H$R(CluLI@U5f4yyo7Jy?QVHv7LYK`-IHcJN~LJ{UJ)G2a^nEY*T?T z_BpyXbH1Cnh7cVoRbE-vmNX+*?hbJ~CEa<$@3~P@MG^xm3$0T5wGI-kZN-a@36rdH zDI8=fi?PxStLZRhw}NO@PM3gIxzJ=H2VM&oaYLR3YspIWfTJ)^7CYnwXF6$GVJmy5 z1M^C@ib`P;6uIhMt>?4`hXV~NB%zHF9HCdsJoyH~9xSGhOt(OWm(t!-BL^9bgfwY7=X4ByP$kmB?kR0InSUez_# z+ED-pUvB*_3{BV0dfC4ouYdBjl({v-LWrWA6vgnz1v;+p%I=H;m!<<@D;x1^f6L#A z_t2PO5;^Cpp`+^CVTq#`<-7a@+4(BXdI@=4#t1PDsz;j1q%p0mu>m9CXC3^+NfJUv zf-eySxVi#nJejpd)r*dv1|#ML!A$@KBdcD|!628CS!Xg&f7tP0thVZXgCj|dbn^BX z?EuU$jN+~Q08qbsKU}khAVQ+pi!Nj2ApA#RlVo6|FKRSD0BXf#1ECrPE+dD7uG-Q2 z9hI!}!ysZ1BRe!^a*mgu1J*{Xa4Ir{(U%`RpY5OBaZ3D*@w^?ljeQ>WJVCufzIM;_ za%Fs1?e%m=3}OMTpI1k3KRZtPQ&rJ=Vm&!F(y4>X%Qm+AtHXl}T8!&i(GyvKG@K$i z#mFh#Wgmrn?#)}UkKF_Z>cK8@0(MnId!cDLrM$7e1O&K zIl{L}FetqtdA^h+XY4N{1I}Okh~&QADiYP9T%G)4?SlGW**PF4;-4U-WhJz^x;F1H zj?mdF{Z&iwPi+-k;uMyc1%eMhLtB7Nc5_hZDSz0! z+w;c6^>r7GSBx_BRUGuK??Iwbe5iN$F%~}uCe)`mGHLVs!#XH4iR(WwBNox-?6mhW z-<+6>pyTqG>~DpXBsFcXSv4g)%DhSIpxnYr{r#c>5D!a!uuyvZ&M(pHa1d!i4_KXP zY?5ByCNX19HnMWvL;GyUQU2Hs7k1YYQI$L0xjeq9_T@E-Qh25B!|&-+7_K~P^MMDy67 zX_?g~ZK{D)F3n@tCdakK3?_s+>iu-zh+)g0cSxZ^AnqpkE81W{S)ZOIlU~+%gy>ib z-l8<8TLeDm663`pBl$vl<9P#!z#~2S$DdZl&(b^Y(jOy4&x&v3o|9fuJD%qQVmqFi zUxm1}x5x z)B1(qIa!DPwZ9^lPwY|hzo_egGM$?<^mfI(pK*3x0*Q2a?fIO8nw?HLLv_Os+>yqJl_mV;UsSV7sn4zt9ST=(_z`2p-r8U3AaFZu;U5^$-d1NaWbH(fc`+XR1hAIcM93ZJa zLVD@{^~Mxla)1Y>-){r7)&!7lzW}LazRV!I9y;Pqqm+VD1w!b}q433Gw5PHE;6;vW-He>g|%)W_hMOsbXBTo%anCO_A5;)k^G@x^OQa(0+Bczy%G@p`^ae@uz zyNEfZ^B+2O=Eo`(LGoa;}4Ej#LR4%_?TMTe&pBsteM%LE z<8V65cM3H)@Bd+3izhLqp=$5oyTmwkBS_FNn#eT~khUB@8y=4!k0YMRMVme=I@Pb$ z7C?M=y%q2s^SO0e+nCn#-}-1yg<6c=|8?VU)I;(Yt$zWbbhHGs@J~@RkvB?pr_;#+ z-Lp=5M(sW!$%(VJ(D-YTRVT=CcruL=-4uhkiFJCUbw-lniVlUHjZow&mtzGra{6DO zc;tW>-jmoWsS%Bt7C?D|mNWbEBJhn-!C@n%vcUDd9|||0MT;EfyfwnuZ!;Ad1G?;$ zm6cOqF9?Xy<#mrK4EqEtw!DwWs>^DZXhL!v$*Vpxq0%mJV;yXlO*8)X^#r22%!IPf zh5^>To4@~P$944!$MbFWbJF9k$|K*)#o8me-wkYS+YDISXxOS$#>=z+QVb8ibjP^C z6!zWO*#0^ErFj)ZYojlb!hg^^gHnvN6d6Ck<1io3_pO-!RI>REkc_59?g7J#*Mv+f zsqEK@;{sFm8&6M=Q@^e@mKG?H!8|$6=6x6)2Ca2^=w#2G70^1Q*fINLDl#eKq|T1n z`SF-?l6le$$WZ(Dq8@hCLwqz{P}C&~B}rs8@waITS$JIP<OX#${nSiR!)>Js)Ld1gx6>(VhQomG(H>+xxZp)#?JkAZ;+ieTp^O5H{Mkzql=N

q_q$AdR6k@ zCDckfz53=9o0#JkpBNyh5WG+MrO_0oi`NTQXUrt}1X8!FU2^Az5qJe2{Mn8^T%CU|a@|nt%t|q7+@nxTMj-gB;%>%c z@#*;KPPIC!JSdz)_RO!~>;du(t_H5p-$iUi^yMP zKN3%)Sr>|FYu{5{WP)}Uh3t&xc{=y(5bAGsm9?X*TI@9IpH%o$m5W~i2GH1M%AWXK z5PFD3J}^!w5P4f5%$Hkn@>8=nWpqEQJc<;emXn-!TH=et^!DTwNKcwm_uBeX`u<#P zY`NL#?tZ>wOy&7_Z4_WUR@eP*|00liHcM=L{_|zXc;n{jIWR&LD1q5uo|#3v*B)D6 zA_7luo-qkO;q^V0mEK35HZN73T5-*O8KyBQ+c z9h4v`TbsDXFH5}abKLSb!-BvWD+O_dwa^u~?Ez^5RXf5O0T8xHs; z?Cyr`QZvrao*|BCbKDLd?hdHu6^@-I93jjPE0vAQux zvM)QqrF`cA9jy9jLq7k+r4(EXjv-MSQjjN98%~keYIx&muof~ep67$yAa1g}Vr)}Gg`)iEpbO~DP{Rq#~Ho}-Z z6yiG2WfYXVf-Ff%($xEH%kK5^JnQHwLA2Nx4K_XsJV{fOx2;6)ry@#3UI3=MK#%aA zHk%ET$)t1M2;x7jHAPVz6zb?pgg^6d{aL>Ao$v79{Kfy0a=k?*G0m>zZ~l$H&JVx;1ODuv_*49W z-}n3ZhyURJWVu*iaQxrRX5)(GIPsrh+quEq->;~4l?(qtP*w%T;F}#NOBXMn`g3;; zPIWMO2)^I}X;(s0Y6@E5>1d9yf~qY2 zGv}^JnmOy&H}Bpu9?iM9oDs!OdHVDUr4-wuWW8R~)UFv?t(~pn^C{QY9GMOO+byE5xHj*xRlEW*Q{r<5R&vnFMP+I5i%Ov3+FpX4Y&I`RLG7h z)9wEDkYe1o9dSUTap8Z)U{$a_R32}%wAvncYg-H$(U}AQc)8NPz|)R@V~9I@Y81km;$i>L%Lm@O{l&V^@!X$_LWn&zK=caR4i&eW$QRfFO)+VV z_K~G^YpIo`Z4Im1pqq-KHB?0CYz%RQmL*2G=$C^rm6VmwW6oO-l%7dcPJ~VxjXIycP7wf(S+;7Dl<@CsF|K0-? z;hZq%SnxT7kPIQ%kJ4BO_klcW08Vds4gol9FtkVI0s*K0jP1vo$M4JbthNp}hvV1m z3!~lV(RO0G{(BFFt6)DBP*Fsq+wQznFU~tO*>N1R+c|qS=RhGl?`kO}+KK}aWpD!- zkH;PV+4%~~Zu05wYmd-rLz*YNxqU;LrX*R)YPI5n4?bYC*>s-UbzL7MKnAyu{^uP~ z%HWe9(CjqLdH(zZUcY@yk|bPTUn7L@2s@oaiCdfHp2pHE-m_8exwDG#bjJ1Vg0Fw` zNBQZ0@%QqJ|LZT1ONnhQd6ZC>JAU@R`>U9`L0E@ES557n73G|Jnx-L%VrpuV)H$Pk z`swGcNs*GKaRq1VsWXvsaqhZlSnhVr=X0{r2;Ue);JSSuPhSA$jxW4VO;^>EsHf+;uE=YwqtB#BqcW5JxGW{_sm${R4lUS}x}o zeDL8*uCA__PiJnjYeXl2TyD0s+K{CqKL7knK6>>DLf359OR92*u+H|=SWVm7&dFm) z+#N>o%0EZ74(=v1=h|W|Z{EJe1ge&BDVjnEwq-$Gw=7pTyn6Mj`)r(`(LC69jR_W= z`(msp3i6Tr?{qe1x7lJ$%VM$MqmMtK*i}ds(YEgXOT4>CJ{kMM(WR(nS>_V-)ZU3< z2xT5}iU`GZe_c3EH0;y8hQN$d>)`(T_VnIy#;M|*=H--A$xvp9ilc|L$^nk_emzwK zuf>CXYfsUP4zG!KaOqQ1_L4l~+B+L!!i6u24cG`{+pbh~z+}+j`E%&_+k$>5PuMq{ zp63|YGhHz*kUf-nk1!7bv!Re~gYy-_r!F3%+xtf3P~aHoBPN`S?K_Zx4Rr^hChVd5 z3amM_pEX#5&v9S|7-RMY_PNx!KCC}fP@fZ4Jr)yv?gl=Eem}-9?f<*a(KNIj*)%k|rELsK2@>U0+HsPz+qK9NL@n4hH9|E+5*pp0t$B!& zwk^hU7^4%TwS%9Rj_kkxx}$kWDQH?ZMwY@A+3py+f4zrzw47P|hKkG~k)u52jX5wTWPqQqPc4@8qGW?e4 zQVa!ZIHy44=zP?Tr*Zfq-gsJ95Vi%^5~~eu-SFZEAFqZE*OnQeDL8bnzCSadBu2?bo%_Jo z5JG%BMLc$1>bn;WS;D@rR;3T>^v|AL;TRI`-1E3A-{O9Fi zj*IR&=tV=_*Tb7#K8W!iETGO59jA(v$GnY?3x)3d&UhyuAaJ^$H!t_yUdM!SJT#YP zxF2^}yfuxo`%%LNVgeFiTH-DKSc*BMWUtqy*z}#@$X(uMI_0gVaty;MyT~ z{|VVEG8!5oF=8)#Iz|Aj6huOLrM`e3x@{1k4HDy#HF2Q8?yjRf6p9FA{j=*ACgr;_ zt1!Aj5hF!JIvNvYDHH`VmV-R_Q?v#K3dW(u?Ul9-*nNTH0kZB9lfwwaR z;{@x_Ffj|EHmz~K-$haI^yyPjl1L@q60q%rXyfsCkA!O*#wp(HqF`G;= zt>%}0>6iF}|LPy*-~3a5lE3)p|GX>Sbi=QH_t*HnKm9N8?Qj1!{?0G`?<863i)KlZ zq%>9C@vLtbH_YcQ?Q*x-y27rhQHh{6jZ5GaVA>Wf1iIF!cuzGc%d!jDITqE1`@XJg zkgD@Qzqz>~iX@+W@(D@_?(Ximy}d;u&_*-Lrd`u@adG7le@mLCthP%&y!wdAWQvV) zCOV@kcFbo}F6R?}{5y8Lf;1m<{pL%W*6^F(`wb@33#61x^9k0p=(c9NuBgirblXwr zQZEp6jnhL^^}u}s-JyZw@ff8PW$A1k17{s1%KJ=rl&bFYNZdZ9!N@*cZ@=zVRmFIm zQj{g5@r?Xyj`;KSYQ%!5i!y0N;?W%ola*4*}z4x4b_O4pB*6;WIz5&a#6wU5{$B!SPX&Nk- z>!Y;QBxTX0@i_H$n4xg&!lXvQhR{GtISSB?O*V%>g`YG{`9lx+;A4g1Sbfq%-0z{j z#uL9OTFIDC^id-cQGSjANYb(P3>+fq~?bsTKpm@`We2|z3DTtfmlLqoU7R5jBX6=gkiMnMtVO)yQoP=kkX!>BI&a+Kwz30VT1(z}nobips#fb^qW0Y)3eTomd;&#c>3syD`!t3XBE5cMv$jfHG>iO$ydWn=(+X z0h55G2Bq8pX@)d^gfv@0mvv;tW&>Ub2pF?*yasGk&@!gr9&>VuIoNS1O6)8#B_c7w zX=U6$yT{2M7PJn&jf>-+Kl6y!slP8ViWEDE_#$siIXy(CV+16=7Q=!veqW=TvE#F8 zBO`=`1S>{LO(+gy=acSznUi)_!^14LRHD>|Vt6Ec?BMZVueAvi5O2%oQDcuxDT$XFLh+6TJx*0hG~bnkJxiQd`QGr#Km}l8xn^Q$|22L)*568OZeCtt zQRFBSiv50r&D}NX8Yt#V6ZJnW#P!uHiGWGn|w zQk-3!Lo0!@+(M$Y^clsVGy~_%0ygSccM_6`jRkNhV@T2tNbq}}Qg(VMWCK>DU@1o{ zG@3S$1d;Lthr`|#x*AE6p=m0o9f%O^B*WqM25-Lg1p9pnMmY9c+eEffL0G;ZDCHoA zqS{x;-ksxm^D{ho_gy=!rPe-kykIzKNU_ZrotS#+hjXwLkN8*XNy4T7NqF}kd#6Z;(hs} zrotC!B;s(X(3yoM#1JdOfJ@VK5yOV37Ri_`u)lsD9$pRWMxvvx^pxM}a9T2kA`Cak zA-X%YM#9%4wkR4D^ARpPMROYCiH{)=!!e+L0R8vJ-1N9$jy-C})aWr~;>g-*U}rg2 zyn?6@^fcy_Lg{IK;h0bpCtQN=OMjh0s^ZTZ^WI}BjMg1u<(rQ{A)%d8+-U3dEVQ)jy|c|yN}+YGA8DFmzu$-Z=21jnR09a;bgcdGv=onq`)g2^ zB{Zl@=o7);+c(gj>+RDVWA48Hn#19M*=&Y9&#~KWpcDzn?*6a^VV25LRtJckea)t- z?PSW)VWenn@y;zZElsUI^cT-Q$N&AW{{;WRZ~qRGEXOCGe1b21_+_-x;7~T2CjkHxuVoz3~_~w;OAvSlj7D+qMn~Bgh%Ej!!g)qFuop%Z_xEI;yos+bTfmkWw0&RaoTR zPj>c)+WMe7x<`K$-aTi2{WgtoP6+nrrFo9>Zfl#4n;V>;zY&~EvMdV??tE@tR5+o? z(iFS9Tf1iNZt>{y0&TnR6_0Tt+tCK7i?X&z=ul@fbo`2W%JwxnYud3X-k8(K5QG>H z1?viB?V1`rkn&3t$j8jwIZh!UD_VKf{7vdM{92%~r=TP_1Wsfk^ z*oIFXQBdPG*m?U?7;g6)64omPCG^;N4rKBywRMpmWlIDQ7QRR(qs~)3x@WY98v_>> z)iqFYS2RV}jL(~6GXpv}hdUixtXVSJiv1DX?VL79J0A*Lwy7TH+7?+lO3OL6^y;gj zNe?OqI(`oZ?joNdMez`!UaJjXY@5V}D{6-rG(Oah}RAeC)Mi2-5M`fy7f#8w^J7o{c{7RG^b=m=$`$A|S6J@zoP zov1JdjJg8PF_42Rj?vww%&1!(1cY%AmVmMh#cYY4yT^oe=rUtT7{7sFvX~kRi-~!< zWI_;mACG@5O>0UoFy%!ZbHK-5bISc=IPx2gC1Y_;hoF#A7m=xEb1GhUD&n{QZ)V^W zbUHRTMuA>OTQL+Xc8$e!z{6NLkN*{OpS9M(W==S6vFDhM37x#C&;N{`c+t60c*I!f zHrVhbNn-s`9kfum0>&4!F^^lhf;UFb+qUhk0e=|9-0d_?t@T`z0j>a#1)F}odp8kZ z6vgPa5CTP-Az9jkj~Zac@OOMLm-rid3 zl~y>EyI_IG(gbZOAf*6|bxuiW25M|L5v9~RQ90UCOpUThs+}WF59Li$fD&i}91ax# z>#Xwd@gr!hqUXPF>q#jOG4qzrl_1Y&5aJrSb5dC@m!au1#$df(hsM&sKgJlg+bu3H zFD-Q|PtmrHKMxhA;T-}QJlIAp`g)UXtvk~M#Qb4%vZ0?6&yRUw55qwa=#zHu^KKPW zMSO3Pc#kkWb~LkkC)RVnvPkmuG@nEWt+#}WJ)vVex}%zj*k_dXib#q$xFzOoQ%WI~ z3s{LzTV<@En-SwI0Vz7xF6~+1X=9OXV`YHB2m*wFf(C2BuBb-Ojbo_6Iy&Dd^JG?g zzlH_9A*1F6of92($bURxjWu9o0CEkdEDoj%38nqBln=Y6{s(a?PX}w$fCuV(_?Vj6-G{DCy$4Spv5kejW;A+W33bjYU|`Hxz8p7z z)VM7rY9*mHfg!20fKgy61LY(nY8ld5Y^jKU94r$Jf%a&Uv0*e?>)<#LbFg~F9HRj_ zA=H3}&tU?3!d!x+(He%>@Ek=LvU~xXSKH^&+lD|NJ_gNV4?ky~X#`7u4Pg z&A%p`^F~n=!O_ECD=!GM$fO9Apdm*zrZ~l1{E#B(UdMYphbEbFDA__P0|L{t1@uB1 z?`*SGc*e9?_SVmsl>}#h6H1tnHMG5Nz5OKe&B`Dxr8>%fBs~NqRQ5hH`7aYixoyU`A`Y;Y56_Mme73_Rl9B1@swURHMbG2>zo8oqHi4 zr%9r!eX5Y@zbW@RaUzlFID$kgoDyA*FYsxRg1>R6im=!90G<+@^$P(OQ2x*%Q4VSV z%B-9<_0JIllvKE^32wFxcC~_`1t`m`DpyKK=_n4ATFSn$35|jJ?;>^ybz|`um1Tgn z12#uK;QfLw@+j5B&NNIHk*zh*!hmQi7&V517z&UCNxlS6GDzK8eR1SLO+a32GBGAj z9Q(Q{;os0k@6^2-dk;ej#L)(IA_Z{_36CiVF<-L(Gc2Fj-=DGIrGB^yIVsG1ozLBK zCz_c4Oba;8$>(yc5jsZJ^~v`>cKzdm+ur}qdBvwDp0fEGqUwHBA3L~ozNHrBU9DD- zS~>oBH{SQujM;1!3T7V(oh2PV(%RGUVC$rnhLrZbq-hG4rfAz5ZEeT>-c!{-qxP_< zVH|xZb(}>_G?W(3g#$<#g{(%5Wn?XzlC?+cnd%H&L^nq1Jm}>{k}xPQt&K8%Q>DdGKgD=KY#H8Yc28d<4e4MwgQpL zCC+lpS2JWrpr|S+RRPHYpK61bb&CoboTo^W3@J~LFpj&Xfl&fgU8AZ>6!W=_K;Lbk zv_M%3tc!)61W*H^T4F#!GJcj#|aO+bue9^gS~Zd7E%(5MQz43Y$M*)hK5-2V9jR$LUc3*K$rv! zQT~`d*UkCLY{#kZ7d1vzm(lg5+`=x@z_f+vrj*9G9aCKiJFxq9_gK)l{`@;SIHsp-@ zh)!h;CRFbrY+t%E5PiX7svnrAOJ~3K~#i*YHCzc!l=e}t<2fzC`%~` z4GC2+#HMk>R_#8z&y?Nc6iPd0)_<(*ooy)i_2>gU8`QZjh( z;teGBT?IOeu~^YPCK~Loe~n?#%kVu7)$^S&uXP zK1I0 z-od1;8z|`D@DV$b`0w?F{E$Wz8at!FX}4bd^J5DWg+o~dYKy0{_`*I(67Zz&*5YHv zJ@W3aO_JEDNs(oNo}#rzQRLPM1% zS;uLo(s|x0DA{7ZSmL7(zkUM|uYK^+Ft}|EHcb&DQF__I}D2f8y zfibh$4ExWY;qk)D#0$IYrBX<+xCZXiSc^X@B4htT?QTV+u=EDy6 z?k-G@PU^S3%akn&X>V`s(KtrH77Jq0i04cu>WSgRbx7t5{t)ZN}$ zMu*b;ler2ppPUc^qtzr6A!askZc}URTC@T~gyKIAuu-E)o!$9EgL8{gIw15T(s=*| zt<=HI>ez8k2V)J-Lzhzb3XeM!iJ@$*= z$BFhAFeYw~aYTD&3=y}A8jn~LXIwt$@JttQ5{mW-RBDWqI%Toe>(GWpRgAuwX`b#F z?{};?8~%H|Ay8vu$vJf*Kw==24U924@W32E)>cUPYQM*>0;FM}ECHp7Rs1TqSuhH% ztT(1{_GTbfIBBo1D^`?&cA`ZC1!WX8m|e1Q*9|}r1*PbKpX9mQ281zaSbIKgG-Ru+ zPq&6ev9lazzYTVN_8?F_*OsYkHpcfI8|9o5LylQEzOLiNP)Ia2rW~WR#P4&6GEc>n zj|CeX^P@7oPc9iNQWh155NM-fo){oW zIi%Y&{`imo7@}$*+8RPDG>1L1CPAL(?z#baM7{A%L*|P2SU8#%1t{e>++LwM98k7< zq{xv_hPrO>nYxB<6Qp&6vn)YT6cD1tkFM|VX-)C@{u(VIxOkGHpbY!A#$8*X;R!fR zkWdQdgqpr_sOuV!9z8+ony;#=+&yfOWjSOvkbrb)qe}i#SHsh3C0+{``zzi zyWNEAW7miG!=~VrLRn=Cw9*iwfz%3wCB1zo=JFe3d9VKOIJ3pBXziM%JVmuT;L#h8 z?Ud!PM_t!WgV0*8d}#FI=hdR%o9zvZA!wQgPoBJOwF<&cYudKO`Po^psswDf&F$Sa z=6QjtI$*tC+Gk}xw+>VTYf>^{gE!4N?iXNAc5D%FN&}EJO8Hguzq_KBVCpCuBGn$0^Be(RbSsTuJ~2keqlWeh_TcS}*k!|o)%D6i zJ)$uinJ$}-iaQM4Bf-#Mind5$2!V-gUJW4t<<6RQ)rKQFBBY9)=J0>XQLL6GZpDYY=5NjEz>jO$oQq<CAt8_UD)C+c-$Ortf7YLRkVthY*nDL^}~$|T7wX^1+Jr1N?u^t5}( zl)!Pgo~(~+KYU~=W_PSe*TW6n-(LVKQh|@X=6%zOq2hmxHsK$@PEGgadu##_PXWA(O*~@s z!6d^Xe8}*5;+6K$@3j6II zX`15s^XGW*;DL2tSuO*GBr9^%&ud(so#SqIXY~NPI}~XGTiwuJkk?T$J<^Exp5KTz z!GhL@xbqD?YhiMaL&wk=s+1J0mzyH7Vb;PHa%YSNRc}U zRQT%?xk#Cz2)*yTVhBbip5qQrozqsAcC8V!6+B0pMtd%Ld~QHlFtB%iSshv|JnyEz zx);1Rtgrf_-)WYGKa-SFkxe1#ou}~`75nP@eSVbYIH0WB34rrqCoE8Ed()*O^ckHG zw$=)qB_Yn+Ba`&2=ez9NL)UFE6ZlXzX^?f6JQK*_7*aOI-L)6GZ>&Ey zF7Z^7UO_-Ri@&~8$}!qEmBJVJW*$+42B#DZ%$oRf0w@=L!E4M{8jo{{O(n1|YgCQF zp=r>x8nPxJNe)F52*sgE3d#x)ZByU~O8{okC8H&n<6cQ_#gi1gYH5g;i3NYw@P4_(M zAdIn`|Ng{?F^bgrGY_XqQY#pOP|Q(kJyva6VwWhYghikEd^Q^PlTa1~xFn#ILF?A? z2^~t3BsO_ZYa4Oh5bF%&J4AjMm=gT?jx&r46S~d_(4H$z~2+)M0-PHK-gZE*Y z7HwHVHZ9iYYkd9dUx%RvKm6fmc=7Z(u3z0iHMf8hHXgRSfLtr3pdFfRjKMt1k>@$C zt35=)Aw`XpYM7K_#}w8L15Fb&X@-hvuH6NV=r{1Wy%i&B5_#TU4_-C@06W1gkR7{NB> zIEVvSLeU6?ge4AQQP41;5#>p06`CbujLnd+Gf2Q$FQzHCBWJF79yQ|xzJ@U+0q?GAZ1bN8+RPZ<(Mk>@$CUfkMXqo%ZL ztr3_l*SNmBMed4dn}Di8kU%SiBIihp6bc3`qM>z#6YY5sTerDk5R8d(3Or9(AL(_d z6B)+T$D#e2=S%mv%YHgdZN7x^wGU`;moNrUBreD-1qzY%s@7fVZ|CFeqPqzNNM!jp zn8;B|0KTr&D*RtXCG`AKmV(k3&u1rc2N&SS)H|0QWhR>{Bg00OZBeS^#+E zI_?p!jUD=7F&%k1T7+D>hkz3rP){2j+9|A0S%{sYaP&GMIz8S$-C>&7;(Slh7kbnL z4Qqo(tss&Rjf4Yr2)#S#r_~swhC3#;2;5^I1ExCPp$Y+ zGEl~$j1y{b=Yy#T3KTYP>-hS_+~`xD)MGY>Q_prxR~Y+V%6zl#DGBB%0@^ok!_b`je)VktqrE0V zF+4Ko(O*BRj|Gy1kU&lF2%Zq47t8INFHgbnf0w4&pgHYZZh6{*7ox?*xaHe+8}rbT zD&}STCejNpy=#Q$gDa)5*=(YOK+`!(v~6hqx^zet8qKC@AhdPAS*^}+sA~ND^Ut9` zpuzC&`yXJjUf@^$>Q_;h4fdNY{>4B4XZYkhe+rhRy=jAXE;@cvP%Ibrz}fGBR$`VV zNC|gIxGmbWMblnmmL)jI2Dd`sNs;5ZUD4Q9vqVj zc^IZLW!a!83K(OXH^vysvIGDe4hQfgM_HDb6${jdGCUJ0x7Rn}9E>GLqD(R{J(!|) zOj&}CyNu9|;X7hg>NO+BZV@!_dWV$Q*geTa{?cRl1SeCZ2WQTZVxg4f2pmmugY(<{ zu4-eHx;W^%?2o@u`kvQAnnf{GZct@%kw^L>pmnIT~S`KNVfLsGIA&`lJ)&$$8f=nsof}>RwmC)E%0{cp%ZW`RR6{ytE zgoEhJ(mSXtx&bgZ#?Z_P9YF|)Hf|%QNLlWv9imI1@*9GCSd>yxLXnFQbumLpl3Cwt z)q?qgscn(+Y_xzrGO`k7}jZIUtV&hJX>Wj>n#xkU|bQ2U?;2sW^65)$vUu@TP-D}$VBU2IzEI;M& zHje)K#D#v$;r5>29V+hiFUtLAPhsyS($+P~vb0=eM}P2zMNt$;T|Bqev29rA!oxWS zVH_`BzQUKk@-ZGhejESKw?Dy~?|uN57WnkDzr^>x_dWcZzw%Xl<;x%8t#{tWzy6c| z3$rxqy=N1Udx5sCv0Se}j6z!;V59)@4B8NIFeHpawiRZ)fRZilq{L6_7U%Oh9wi!o z{m}{~nd2g35Jch@5?4(Hk>to`b5vTQEcc+)M$WHRD^L);eEtIOK6xAS`5g7W3EXs_ z`soFpX_{J#xw?W90$K?WM)CBEpCV0jWIRE!Tq4hNBuR$#>JkqhUP39m?^tR|4n_z* z{q$3O@THHiKAVHNre(9)g!OxrGHg1#+u)xcX8;%kaEC?dj{d&+KqST(w!6KxRLmEs zni?NHcmM-spA9!b@m}SD7Un{mvcd{@&(6-UJ(MuUV81VMc6Ns9U~M0T5XiF`=JPqW z+r1N1)_Cj9cW^iyknsd&^oTAcM}b^@(4#|~`?jn&ayFur zjB?fOB#gS8h`x`%@`a*jJDYn#vEW2`KvcZid+z}Lm?-gBEG~N@P5YmU=@dpE(KAg$IUA0or_w1;alXb< zDs5rvQm7b3Mhy~1pd^8!$}I?O(IX9T=1Kp=if}YREmAZs(6kDhmSA7DsA_?#6?TLQ z4ni_$1JHB^Whj&;Fr3@Jqtu2QfS_r1wkT&5G<1`ZuN!3`A->cX%r1qCaWFmu;~8|b z5BE0khRyxgC{}@xi2`&=xHt5g9!sPecFkiHiH;(`13KuVtf%NuL&SXSzQ3*>;CLaL7r!*>n6ND=d8zf_4|QGgkv;5F4XA_FKZ6pE4?g$++wC^k!TB*O!rD~O+7?f<+02bh zOGqO@Ns7iuBv5E&3$8MNC6=;aDtvcW;`00gzdX-zK^0n&K@o~O7(6ouFWVM(63A97 zJUTnW-Sr)mQrO;Ykh^KZgNGMbEEd@Bw}7H(+6sWROH9)oG_f=bttAfo9h7o3A5Cy^ z{s2N7l!po%u?4xlaqA*Snm)sFxddYg=JPocs-ca-TW`FDrm3NnMXq<-J1k~tpaKoW zx``7mE2Tm}mo3)l(SBps8w=~qVk9IK*+MGpb_b+sin^|mrYV-oC93)m?uXVgG#7rY zl}!^g20rAbEXz>PtXJm{t-^9O$JNypmdj;teYb6k*=&ZF&+o8auW@^OiwDISWZPh| zc!-3u5L@kO4J6P5W2yr=LWrmIIHxAnakb)$K}v`%;2e!ZMeY=a*y*&2Y;|GiV17uT zi7R?RJ!>_fZc`gA^J< zD`ZAvo)XBMKq`uJLD8-=NR^`&z^>NV9t3uEjk*;$R0n910xSU|Ibdv@uQ41j6r4GP zUQsB>z>f{AVpYr8&V`oem!JQi{O&ABq@<#d~}R z#OR6;){?GmTUQ`a6os8iy?prs(goSrYsdo4L~C26|INUd9mJi~IKPwuzxxL2nZ0(#n6ja+nG;Kurqk%HiR23RogK%Q)z6is6AAE>bGu+6=FCb+L z*+^7}Yn1z~T>>+2aSgatWbXbSU?=D`&o4LU=VTsmOR3}Yj1Bb!)`-~1N*z4&lNJr@!W(+D%i+{i_JAF!ME9Dydrj#C$Eub+{b6{0 z9SPMr>+${rxMeiBEr99B!Wb`fdtXNllr%k#(a=)LU|6*3h;K^*ABZ@igCWOm0%J6e zse^ue>@>abXY14VF@5#L9jZ z43s30%3uwGR@zXRMgV68LA^}Ssti&ayxcT6)C&8u#i2PsD8P^mESZ6^3`9$4O<@QH z2)Ap2IA<41ZTAm=u*8m~V{s?3Hdkq0pxrQlXfQ?qH>xLw9*YnrB5Y3~yi*AFP=Gqc z(;KxPatEF-uHz0r_9C9*=uZ{@r@XcArxTIU$;azlD=!-K8|n~U9(!N^e;R?|Yu?Wj z^vH$@oJd=cc8(-N#}GfZi;M0dlJ5)bfOymXz3|0FM{}V)G~XlJ{_AJ68QP`|#e+qf zd5BN<#rb?b5B|V064E)6^xYm(ZW{!TF8Vd+olS<0F|k-{WvNSYEe7z>_3F-H2Y~u@C}zTA->bM?zYz{V#a>^mBaWEB^-0 z&d%`a)eC(8lkXr)2+r0^a7NHnl|_0)1Epop=_P(1(pdqiZ7L==6ltq*sR@2{zC^(d zzGxfBVvgIY#LGrQYechE+_=njaXaOWejs23v)9`uXTNQX@pbwOhB zp61tYRaG{UT5Igf1D?G1UdPkt3{op7qmfb$AsSbJS%hvr&(YlOaQW6_)S~U2Y+S=y zmL(R;+!=tsU9d^u{+bYvt&IVrj?nC1!iCp#lS|{K83;+Sz4L?)^gYHp zz8K$BGcu{!au{0Ar7663XCG&X=}|T?I9G;I?j04xL0$cUYmiSEYSs(o<^uCh_ zF$OZCg=nn2H480pGNX9&fr$RTzniR(UCTqoD&>Dtx-Bea^ zXx+u08)CqXfd+v|EE>g$hG7JGLNQAX8VN|HAhf}G!BDppb(^A;1ZAyoduXt)4rnS3 zr8x{`AUp$0auAkvqcUYvB(1vF0EAhG5M%9=w6QAaG@ZGJ-*U;daSPfU=Q+m3pGVW~ znk>c&y9KRwmGj${Jm@2It0%E2x}sy=upR_XN*A$iRaH>;_Sg2D2fc5%?`80 z8jG__JR$~431}%$RTa)3SV5_hwWH=CPMZ}G*;IA zU<|*;JkaFNGVZhko(kl}v-_&HNc3(Oc<5T|uEA7(eS0tN1VTt?ZO^4zv?%5a?DuZXCHAS>Y@(kK2tkw(Aq?@`B#;p)O_*rX! z(Ezo11e*HrG>2k)SCL`;(VwvO=@4erC2Rn)=y+eIy<*S@X<;DC9HY8*NIW~C%Q7&G z3_y3%10JoGf()pECj8lYS@-D~Lr^IOEsu-Rj%wmBgNi_yIK8na0`%8ErlX9wogn)B zAS3xG+8l}NJEs&J1&3)h(72T0c-{$&0}8UP>46inI5Cw+$Tt# zn&|jv(oP1BIr78gFYkhprs)xlWUP@Ogn%bJxMmC~KV4jNC;Ey7%!H8O3_@X1K~FDA z7!S{aN49snU3eXzsyO_4F&dKRIYi`@?LWI0+r{tCdm#I3;K%je4a66R9%;8lQQ5mE z-izD&cl(eKd!1SD9{U1cN{N&wsLKO*nm|bdFowD*(MpLl&+xTh|26#i4}XOJ`oH=w zkuc_jnF7bpdQ5q}8763ke;{i%daMK8U zp(PZb;bybLjS$!=hHIlxDg~V|(0L9Hd!G~+XsQ}gG*~>mL|N_wMbSTkv1nIo>%3vK z02GiVDMTZ1_38y)y?Bl!%R#7tCKQcSFh)VP0v8t-V5z{vH{L_r3ds5jL>oMP`W*B1 zS-3YUqcBh*c`+0QMEAtJ#+Xoq#D2R&@WAuvrL=1x%Q9@Y)}>^%Jj1K&8!Q$JWLbu~ zEWs#xI+Ff`S9I$;$*^25admZvv$HeY++5+EciwV7*#eu*=7_7>Gz}Jug5-^w&y^jUb{{9%PKTkz z<9|vi80GyYcOcg8fiQZ=6{q3%F@Pj|Z4@syDzF=X#2ud zML}c4jQo5pLvh`IpKdY?cBFgi6|?Y`sw@)w(olRGDUM79;(b&OXrHkNad^GrtO3Sd zif`Q<2uQ@COaljn7>ic- z<32GGVcFdPX|#J&k-s$|?sa?;p`H{i#v+8Vfqo{9 zT2GEC#w~%4k*r}+JyvYmZcaIG9zQy=Xcsjpto>&HAz_I}0Ue*z+4C{(EXfSTBBLL3xp(t_k)fusulJ)ir9VP)Ulqanul&!mtd4D*N`dfN2^~ z0Wc_#qyWn}OuYwF9AI;3<9tKi1L!xO*b~?<_V_xCIlGLB6nw&z(*0=GVc|6_uBW)j z{&&w;o#HviuVps_?lu=4QK0C(oc}4_^C|J}7Gax5J6ZXJyAP6*-^)=s21r0I+`Q1L-xi%15oWhh{^)=)y)1K4!7oWwOv zZEMHoKK9&mv8{UsbyP6se3dN^m6&58r*IZ*zCiJS0JJS^6UG4pP(tn6bVY&>o5@m( zHhNSW+CVySoKgynvWHC5G*~W|!A->9ix`3Tw2=>icT3g6DDSl6 z6EZWvO(wOpG4Ass$DwNR8^8JQ;_v?_|0({-AAAEp`oZ_WiMFgV1BkYDp-liI3Q{!4 z5&|{TFcr}5T4*DXrx|Jx{PUmv3~$d@c(7>j%lSDL2|-eDtU*vnjTr;p;VEDQ%8LZo z$sFIlsj+W0_Cx?uBWVG%nu9YA4Gzr+Kn;?Vf*6B@rPyqCwpnmg1R(?thXa@*-WVhuyx!+wZ&!Ev4I!Z1Lt%Zy{_$ri>1aSJO0@XDetap=E`t zV%ToCSS&xrtE+1y8OLt3#rgUSMr+K93_`SE6vz{f&1Qq;YK6_+9WKuvqTnem&o5A< z7QG`dAR19(q!l@9M+YU8!?++e0&)a+#gu|>-=&TQ=iNL=2*C1tnNnRHLkw}069muy z*bT&(&iO}0++QzbR1%#K6BeJ_4xq&LZJ(u{)SnJdfzJ{-ReokQ$}P%d=g zSVcNk1oaMNr9iZScH;vI$00(Tj)ap|X7?dvU9C@@Lq}8?xoAvsgu;^}kL#&`kW(Y{ z`@ZHBPx};dJLa2tQUDsbd>owXV5g(ChTSvov8!qvN{Lq05Q0Io6pSYw5<&^6PQhq~gwG&oX|JoYvAjxCB$Q95T#_lfA#<-2 z2Vu6Un(-`n|Hd|H!>PfPcr^~PnX&>J6ZLi?J&8UMhE8(GPiXg{2J&})995no)qbIwMejgBKnkJ7p9^|C3V-q9fbtbUvgO00#L zTN^?MILcnQ<}r^uMxKf3BR(NkJVG9|*5GLpP|E)3xa0Z8(c#(^H@?Bp(xNJUWa-fp zkCywUZ-}P#!)kaB-SM`3P1A%VNhzhJbRkLzfXWM%JCyP0LQrGxtP4UzG7F1N2r5qoe zJ;K8z$AU7Prx~C$R=UN4FYpT~A$B)t&r>weSS=T5s|pMRY`zND(Lb9_(^!g#XuE^c ziAs|sL7t@8>`Tn%OKdhZm;&-5hY$+e@&;LwqTJtg_Ks6<1Ut$7bjSwDFe8o$|mj?HF+rfIM` zTL#Ycdc6+MSdydw2pZ8wKm&6eT!Qs_jaM(P@#u{QVPbPQ9I#w2k!2Yciv<{8;_l`a zi^U?W*~)1N{G^4sXF1CO3YF{FvKvWY$m?bW%K3hemTgMGz28Ue@r=U%O#)hNZpQ)ALJ55+X4 z6pRxjDFn{e??~X7)>!P~A`$P5~G=r1H=-7ul6+km~n2-8Zk602;nc$x) ztjE4@3Xz|pp`7{^79#D6YUWJ*vN2BTUiX&+Q68CE&LqvVFL}V1&mBU^K=w}9u~t>8|zUl zc@Upk+b56I#m*3~YtTOyZV*$9?pxda_m0@(C z_*$K6j$>YRoU9gefUQLrdXqDc0{Q7Mr7ZG-Hi1VM|NPi0j}QW(B&bj3ii^<5!N8{t zb{1$f*r+LY+LdJ)idjSmPJDn55A)c+)jKVO1Hyg8n0p<@p~N1jj1urPv9yxtAdX+( zQyp68L;?a(&O*_zVbBQMWCY(?_^UD>8OK+^2 z61AwIq(PC-k!3Rou?Gc#6fN3vk1Wfe8N*?FhqhecaC-xmBw#c_u~>pLXE&=QUR^yy zmcG?B@9w;l&IVD)ei7%_fuD-R>B0Uvp;5D!xQWHh<__>yeL~>;e2pScgSRgs#&P2N zdyN$K@A7O0pzjFK@1uJjTTM?eTaO`qD2J0Ip_N4LHXLLKQeMC=lxWAKVZ!gzgjFG9g<+P=00 z{iIAK;)yRks>_4}CxUSRr@aZMYDIKzN3=*kmGgh+LWR5wiw7cXac%dZgwfy+Z*^nV zbfKetM6@63_H=C~>kzw-+v$-p37|R={#3&_JbQWfLjkS(t_S_X+LP(YC=Yt<00-<1 zL2L`-j06lZJ;#nyUF@mC==h>^#SU?i?5Dy$rb05NikLAT@2U4czNw6(*{>6_(zo;h z7$U^h#7MEV1EbVMvAeOA(F%qbB;LV=awuw$C_qz#Oc5wUvB(J8)S%HCmvfFsXB=e% z>??`Qp~ik+LkNMkEkS65lmn&KFx(ZXYWiCDxLzlmI)>DPSc2kIOgAv=A)ASvp4pg)#v|!tis|f{6xy`uq+c8ZTR*%5z*U*Vb7D z1k%{TOB>mvoOyag(^PgpRIZ_;1Z`DAYoM6TkQW?>t!;o7s}(-_^2ca}!fv-iRqi3G z68rrgWp%LkM(wQYOp&3kYs}^=yn68ko;-Pi_4y@QD5M$3mmYtB?|t_UQp=ur(eHQK z80eT2$`}k(SmWW`&>am+X^o;Nu-PBb3W1`q9@X3J79W22A!=uxm@s;@e==qZ`1VkN zQikop2K0bY94Z?VU)MDrJ$l1&(>3a{?K$6gUjIAqShp0fL72^EXxkQ-=PNf_hb!&@ z!pKCCd;hfh)StV(PfvOzdyP!z;(-w8GITZbjm=nHGo0uRi|jtPy8kPld&|gZA^@rPJ}z6Y6RXiKR$qIoY+KyjnOIO zZx}f~79`SNA)Qi}oG4_b(7CaP>=Z@gzJHsti@T4TJ86SP$x*>K)r7>hPgYc*ow=ub z&n&h4Z)zW4!VI`JpxTa8a;i`>jht&NQi8MG;9a+iRq0*8&=@EB({ z*hZO?6Nfl9`gH`0W+2q?9J7%6G(tH!MbC*j#P?BqrtaG*u>5%akWqJ<`%v~%h_)A) z`7fCY#u>BL8+y^+ht`ixb*2#Su`z1Qt@N9JOwqZ|Z#zcAV3wM|b|l{mk=M3yCZ`t)_I`?#c7f2XK6wWcb)?r%gu<(r? zHI6Q8zM2Ipv&N=Nf077bcSC*ucVDD>4RT^P=b2=COO7aBmn5AP99y*gg%HF$T(}^-_co@Zsj@4Rkt%>j^6^ZPN(*+3+e@^Nkfa z;jjp;gqaAa>7!TujfcKgrwh|{xTpBir%>km#`UKP<9pv9Fj`zr(Omokcj`5V%}DHf zXya-L4C{od5&{YeI{XiyoPrzsKxnN|q#7wTSY!m+P_zX_T>^D2kY^dTc>!)#c>au{ zss*%5di0UPLpP5puJxEL;{Qw8do@dwoatdtnsRMUANLu|%r_nYL2h7oNnKD8+6zVS zg1=JI-`F5!$Qvm_A!@}XumA=a05gO6+%fITrO`#2%F52_^DQDKFmqgYS7l|s@AE$9 z#1Y0_8$DK&o6UfLQ<@f$+M;O6yLyUeJcYJ|hhP{?Fh;fG`!r5n{19D1s(2j>H%X9; zM$Yo4pW^*b70OfYIaAMI3iS^+y715ndB-W*PFM(=gIl3(8$VVL`OSn;a5`|9UC|wL z6T``gbJ7SSi{0mQR%jt|$2zy=EU>W!P)voJ2S33NxVTh6| znqvXAOY#e^w|h-D!i<{~#u$iF=zB4Guf8c8iFGk@I^mSy?Yr0bU;gL+34ix@e`kE2 zM&7ga|iUEDyfp>rcfgl>M`yPMVJ>u)-C4RvR^fQk3u*IAG9&(wZ(F(jF;H-k^ zHdruyYIl1fRxIgP|m`RQlM`;2r<}gy0pvrY-Poz3Pc+* zrtAeM(db2s!*P$B`2~1hnZL<6%8LTLoZ)$qgA;|rZiC}-2Pp*hJ5#_5C2%+#FrP00 zsqpUITTq9dF=N|xC+@(Rp)JvXqifc&JvtpS#)x0XZoQTB8Sd`x&@>HJt1IjehR=U< zbA!X)P&gQ4kSgTO%D~^>Sy<-idWqZTFK{>QwX)*bs;ba;@S@x?_(l`^OlX@ocw9@zvex5(m2g6LPREkcvxtbpJp{uj zFCq*z7h{JgntZMB`)+TDT|2xVze7MHJ33du`U0IKnhQNHy#4nTfp(4@!PJNn?KN|z zw9@FJ^Vf*C)##eWK{-C8NlFmHN9S1>xDuYJlu~f3i=s3erZ(E@O(^vOd&UU3rEECQ zZN^-^q3vGJk`8p{^@n6r7MN@hP;YSIfmjU?&PIR+aT7pDE6g6(9kGK}XsM|+L7oR$ z2UMLeut#HE;>Hu?EG@&KJw`JZ9nj$epfw2PqX)}9@Trk^&*Z(~F})#SvRV@eeAAw_B$Z5@)e#yoIs5fXCteorC4DfIUo zmFX$kNt`?y$H+fryElcdpZopPa~?k5aeCotQ{x(wVeyB>oTG^-jQvYpVH}Pa-RE_D zS9d@vApwhyxS}^4le(yESHSjt@40@dW-&~vbB%+0KUt9vNOC{8hq%uY7V&XPXnYM_ zN}r=dm;;?!fW%Tl0&0y*kTjpWH+ECjf(j%p#L9{SZG8mi8Cb@!KOFI&|M&k58K=k? z8$H8rGGGvI(|9nQLAL}F1U%EImBych!jck*Lyy0`TH$XO45}6Qzjs?a2#HomBx@r$b~T+L_rKFjd_!H5oXP>5Ed6Gw1v8ll~8hy8x@5TMl;Z?!o}4bj4@n4lgM+5&GrFp zeSi=GtK}T^L80vq9-VY+E?l?T?!7K>C|ui~N9ruV$^u>2VZGTQ%M2B0x7`8&s+n=7 zVT>Tp7u+o5e+A6!HT!+yWV z?XwqNRO!+nrR-4@Ml|Xu0-yv^XlQz>y&>_iSxti-#&tzUMP5)yKan&|JOVp#xJOgV zAW4xZjMDg0+}zXe4~`c}7d6qHrD1TwA)!YajggR$jA<8fGNjTLT!8XoJOulJ2yFI@ zyM`KE;bNC95?mi5L74{8fq;+^E0i5kYicaWn9UDL!4m5?PWN^=-&dQd6&;ZmyFlh+E76dE+Z{<7G8P4=!>fGev zp++^H5G)Rz6#@igD2f9IkGR-|=h@q0HO-BkDz;PO>2od-;RAe9#DxcV0*#yIxavuf z;WUpL$!4hqvW~qxrCmM{Hz#2*^ zigMtcN;rQ@g+fxy^AdV_fq6N{1KopAD;|;RgbEU0v*Dm&lZ{jg@pqhZXVd445v_eZ zdu-zvkN@KW??XhE@x7uHleCXPyf>)PpW^;ct%2|}#-q7dxtxkQ4~yxMHPl3-`=MHh zR1+MF9H+Q`Vd83hZ&Ea=frFjdai=g8GXm?$Oh$shfhVoJU76do9a2p6fP^29$B~m%`RlsZp@GvvQ4}5(c14#v+F+4YorzhkKWxiY-dRGf^ppUda=>XFSPuZW-a;FC>8!-M|f3MtkMz&^~a4 zqk4!69|}w5Mdi>ilM_n7cs`rlNnMlcMDVY)``nc$cksXdGbBJbSp*Jgd#X}F@% z`8lM50{|yl`Z0~35SY0e5+f>c47wZbj1PD8RGXOSIFTzFG&`0dlzq=bgC zOmQwFAulsVl2Q+M7zOIZmP(#1aB6qNFsvs0pVZ2WDP2|N4|+W$N3kH_K?m0eL5F@? zR7QoDGD1e*EfQ*z-h4YVT5SG$P@ITYeH5*Iz|3zeXsV&LFrSqIJn+NhnYLpnZ4YOl z{J)Nw4iiYtrkw-tbzrG-Fl@Xz#NHD2osoJ%T~}dLeK;nlwFk zUFyRTg^ibPng&hNV7Xj+T0_RnRH-NmL&>uob0;hdKUavF`w=uVg?raDP@+SgWl*xW zYg$7P0WIu4#R!g~#=M+EG%dKK$TT+|;u!~^kW&H;0jV`;#-N27-RsfX1q019sP%hr zq0!|Tazda*hu4xo77KL8J&x)}{F}>L{EzuHK3inaONy7X3RfKgt0l;MhGTogwmCv_ z<3n7q9K7qH3XQ6op_4tpV8d7xl&0n%HTcsjB~aG~%&G;d*$hq7U@@<-*|gBSKrbn@ zCZM8&7AXmkMnsFk7tf`iCF!<<~#Q;c!4n0nv5ftir{`HNN}P?~!L5_wVoU(I>Ca zi58jwZPy_$W+?I*wp)|>`2PKSeD?X5&`M&toLfzdf)*y3kx+*Wo)^`PCW?`$kd21X z`h@P_gKU&3F2gCEIH3qygjkW2DXK~Jquzl_^#Yn|w4y&bGu&i|QVLE(Y5^Pkw1YiM z273y%`$ONGL|ARlKmWXjfnyrzM1L}Ub+j9$6gUH@dp#}3%?yByy1!-j4;crvs=p7o`a-f;h*kF8a zhX^*JX*H$P3)-jBouv~{hP4zkZH1J^A&*9O$Z=p;Oc@E^lM1w98iNCkbHn2wVzqV7 zT_Z+t&-py33Yk!4I~3F*Iwu2qN$|n#1rxnIiv*e|Q#tv4xACQ@3Mp~oxp93G1=VRf z%aHVhv(6*uoJF1rGV$M6CV=57*OzmS5nhSQ2`E*5%n2w6*`q3rcj^!%Lq-#f6lxy| zFjJo~RF-@OM>Wpb8(ndXpJVsAnu*mbk_cI5md!`+?*)@2M zw%`vZ&V3{^05r7`d4;KpbzK`|TXr6`j`zK^_?v=KHg5hkg;3VQ(iIRHhforS!@(E+ z4&l!89Kr_VgcG~IH*wwOK4Qd!jQ5%_H0X2>(cs|l-L#aLs}k&}Km~`E3dc%73khn} z=zu237&A?}7!x?-wZb?7RT3>EIwiq7po2gQ0jhc&+aB+Pz^YdGa(;!|qQFnDFFqEaiC=H-u-`x8zQ}Q3H>ipkT0(I+9BOOA%ypM zcI(T~J`O0V$^suY%D&V1>gT^ek~)C&+}d?himvPYndiih4s7rUp?#l(0Jpa{keZB&@W`4g|tyX>tGRXOdX{KBAS(agcIHK!1R9b^lj@4>~AAa}|nKpEgvMfz@fi!_< zeQ%yS7l&Sp78e&w8(L(Z6V5q`GDF`P9<~8}_~`i_ILdky>wRv&8Z6-kVWI+(dp#j^ z$hru09V(%5a)CFFGU+H)&XZY70U^dtAK`17Lb&r^V~qLtHD$-!hkLe?Cvn_h!803* z8I_@J2`MLm2Upa?(ilSbkpUqe8gNFb-`iZlDT(wE-=6wQ6c`5WNNS4e1(VDKbUEiT zPY<#7c+v`P38mna1c5&m=(9Bd3yNlnv>-oqeZyim^|SsTJy3!SazD^ar|hQP6!Dxk zNuRu@=>1J0cjwgnDO$sntAJZT$>N0!oMtlWR)<6+7gag>n?#?CzEhNop%BPM^py|c zKgUIsnixf$qY)T!5IgIU9eX$H3FG)FE42?1WO~6To~FFSUo$q2E^X4F_>^+H0a0jV z=!F@ZuPzqm5K#&l9hyh%?v$xJ=yDIfS$@W)7x><*}jwdv?B<2C7usdUV5N-%PsVnY+6Q0?heBd&Bn z^-xNB9;ho!0pq%mWf_Xh@Nz@nX(0s4vK$qw6vQL1j=n+W3tzZ+?sO2tUK9l=V>lk0 z;T}0eMFLVu6Ol}*8DT4Pf2+y}8kO*g66i;Wvk@pN+56_77M6;l6c{IlUrYJGwFa4d zrpAYZI+^q-B~cJ=o-voCr!_jEkmWffkszuAAsQUoa2zQGqs-eODmmuyyT9%2=O{rd zd$d}jWE>^QFy{oN(6~4@_!sjV{PN>xD0B}cTFePSw{LK-HGcJYhwrIGOF0gWLW2y@ z3_>ZeGRNcNJua7*)-JBYes6r7UBT3LwZC_LFVXh`MKK(%Rb>j|uItb?EiNu^@$suK z(MuD~Q`a>%cR!$RjyUf2*lpKnnxl26kl1auXk?2lHyRck1)BDVo5i)E=O_YcCmB^$ zAbgePw)p(BSKja2Q8bM`o&aE;8K)-z z47z_j9`xwNEa27EA;aE?hdSYq;lP z50g!difcj$SZFD0gHi??JszEX##8+?X_<|t(BXvC71x9iAR7*iFi|tJzat|`C#BTK zv}lkB(fY*?1r#bIcIBoPBW&p22T}m@!=j93n@NK{JXwjpk&g< z=EMWn-uy7hNFyEnY(^kz(k6!_IpX?*ANUmAWJat`M(b1B z7+2!PdS@EIDZ$-8H@-aeyRq0TT%WOkaB7WBA>%1d>y%*doTJBSC=x~rb|bDk?fTET zs+{f-gWx3&pgCQiI(Z$ZL_pyNc=CDG=@>7zz%q^rY=j7V?zDYA9WPSbXzkOM2 z7u0@}4)!3W%rS2qJ7~Z^ixmk%?V+Z?IsRh zYvVoa((_!C;gHxVYRr4D0n8QcA2=SLnKaL@qS&gcu-R-ZI05f5-F2Ofu%{mBcBzQ_V~zX! zM}ROCd4c-4#pB~6E>}xjUtXE_?w`33an)X{(n*E7Zc)t_c=PT(KK|%4tk-KWOX2If z4%gS$czk?BQ51N5e87A@H~VcbAPL9uc*J6{z<$3+p656m4#uKU3Cw0C7_-F|6+RN( zfn!riuc>p`rAB)iVSwPCuHk_e5+@7A*e2VfgX%ja=AD9yVDQ!`l0G(F; zzl~R>Q4#x98i?@%gWpuQpsD{%Q`UIVyYgM~B;+4$1aSdBg@%qs@xhPAf{Bnz78cjB zfPc4K?LD?b*>!lvxW$w5CTvdoDSSa_qUs- z@fKt*w8bOlde8_oO=E%w7`HA5wy1|XnHadnCghSUrTk&!0%nXTGWT>g$0OI8j2ely zZT;cY_x-4uiT5mDkVtjnjY}<7)=O)T)pekZL-zzs0$gb*0jPrca1N!F(Sg7eqy{^hUK^3Pfu!;6?|*~#SfeOrxW0XkJm+Anz;d}nRn5)4r34pO&(TYT z!{GoXj?hw}X=*gJz-&&vRa)2e;5;)^3#Bld&HOsZbJHaCowSsY$`@K;u*>n-plMrN zTwdXDI2g(c6u$WUQ)D?q-y6pm)98hiE$V&PyWWa*7fTQ@TwY${-MjZj%xI&}i>k!& zb&Vo34d_Qdxk1+n-=Mho^zXm_0hd=dxWB*0t5>hkG&NqnxG~~7|6FU!Dc945aYDqW zO$yYAj-aJTiX0tfOsUf>1IK|DO8WE4zLAmFxcQ~wT04*OP$LvR-_CJJTmNfl?WYHX z!sxY_Hr!(Eyx_;N+nNxcX6Q)fVZliw@XYK7B;Yk`t6L!;R2e4>P5s2r1gZ?bUsy}f z_?&klY`0g2LQEq*WMILB*oYJfGRjALdsby9XIfbN_R^vK)^D1m(ct8ylbj;XQ*^?q zsj*VVz`<$gQXub?slsGE>6N+gbl9m{nLp*)F+xDkgse;Y-Gnn zX?z$HU!2FNq51nrdK!j{+>Nec_5Tzbg&H z$0s@U4jq z#jQSTiH&(Tg&&L!iosX(l( zJpz+L+fQj+^vP#pZg?L2Te)cfj#ragbqP1^3f1o(KG55PAE77*C_a=79iDg+r z$PP`@L>6nz7ZF}WtLX?O4)>?S;efWQtv{;`ap`*0QU!cJ3TO!_HJYaL?nO! zV)5*`iImXN2;!hYY*EZ~fl5kH*+Hu#>RzK~IaW8Y_?BIG^nYv{pWW@ zjcEo99Z6{z6uT2Z4ivKjH;W5!5WHJI;+>|rYxeklw?lPv38n?|$M5mCKY4+lesYEO zU4j4e{cHT;c)%V6dCO3;46^MoyS>6sUw($w%Ty%dpxWk(Dwzt`tmaz>n*gVBXGgF$}q+-o6QC%2J4J76o2r=&t|(tRT)dbwyUw< zZ}5|sFK~6Wg6JB{e`O;;CUmc2EJL%~&?z1>2-a?_4N%7yB)5suF$rvNxdWn z<)2@ez?nQRv0iVnT&_Hw%+aUHvczHcVEo|Q7G+s_4!0s|WWkqmXc)w&%F`^u0@xt5 zaxAQl>^LPs`AGK2>J$8wr%-PM+WL*(D+jv)vz^#MYXP(kQ-$7`? zt~qjnI+@~ABV1+9e_Yei?}h;6l)GAr{x&rUPr6l^QM<1jSqL;l_2E+!Ye%&Wi|ccM zG*1;}ar#hPWX9v~b18gbutur_2?aV{sjCMln1Xojl;{6j!*AEE4j;}H-NQxVk*FdZ zMV+HwoD)07h25AFl`ahY4NcGhVw8L;Y$oRIPL12oSsRXihUgFGEl;8Rp~X(dI4&+0 zLE)ShzomqWlc6hsGcg^FbyD{v#n*l6vrTouQ%FmyDF4uFmU<9lvE0-(Nli*p&uy4A zm=d0)`0zu@BpKbeR0MpAuQo+}IrqFwUB3{~CV}OWJMi2g;KYxVoA`0UEI$|nZ`w6~ zp>U9bi~?#Lk6UYv*Ji5 zg`lo$|Gu)kJmsZE_cu;y9dqr2Q7utXBdWb!Rjwpnl4xa*UUuLe$EI)bTd{^LDjXs3ekX9?1@_Ae zbWID&88XUI-@Qe5Gs73FYv}9~u+0wN$_6!&K*q6H%<=8-{|Jy0vx^m)-2t6YSj`IT zwg=1>!=$EZ8W5s!d3lLEn?VR^x!DYDt009zT&to)+tyIRG;NF%^itsA{x1M!D5@EX zyuxC2iK49V?AZ%cMTy7lBZ@M^HNV7iImhMo6@GmEgO6%=wvJ8&o@JQ{XX$%TOQ$e} z_fWWT&heMOyavxQu#9^VEYBD|{^Tc+Qdq}^%s&t2-V(pA9QVHKI$U1e;?Ljzh>t#g zh0SJT_h5ylY4FMCpJTV%SqBz@#bOD@7@D>RXC}$=+4Gm!@At@Z(}XS-3kW?}P4<0n z^hVa9LsJ56b2Y}zc?>?;y~^uYPW3D?^-f9&;REFKNebi$%?|cU>HZEG_C4nuVrWnj z)CQhtt&wq~JJQzrgInhvq6f|~;~{^Tz_?1CY9SaSqhvvMEnHDe1CI2FXRYIUfJMzT z4Zw|YflY{U9MS}%eRPCk6HA#RCSZXRjSPL7Lwv3)JtshY>gS&3ual$?bn5-2p23v;T?z%BLby$nk)K@iRO6B2JU?}x zQqP=OD>OhTL=s_*8|*0*A&d=oB1K9mWFRmdZD?5r-tkc(?on!t!)ao)zpiT^v+W8* z$Jr)Sd&@qivfeywb|+NV-mr99)DDfJMVrs}=fQ1mfAuP*xaxI-^T{^bRPI zg<&|M81Wz@gpH_So%Psa#b@|8t0gWQ21yv+^}t$bY?~wQh{CSv@V2RO=sFx>iZ_xM zAe@8J;jj(C7`G-e%5an|Iw>%t1v*Lb&0&vq*FuyOq%3g{fqmbj(tzkPWW@~gtiV5f z{|?oyz-Jd9<6+n0&3=RJfVd*^eSMAPa_J{5oO39leUf9AnPTSC zPd~-K{kQ);Hk%#(!+-pb*zOP5?RGfq_jvW`Cs?gk5Y5pb^OV~HT?gxedQhs~8Mm3u zW&==y7cXAm#~l>kc-iJ1M2mTiS@R=aYfxke%#hEVO+k z+PYq3!y45JSw^i$(FK+ac7FnTROC`Zys*#+`o=(jc?OBM$ukLuY{&^w`jn>}?tOGz zKg5)b7>ra3BaXNK8DbD;nj>&u8|%`HO{)gLJgv)25Ztw7fTMrG(NBhiMX4mX3-Y1q z^HMs_wFe*#qMbSu{rPU|R;83lo=&(^h0V)3r!J{aoizq4OZw!5dGwlkn8*%a)03d= ziHnHKkPmODL=bOI?ATK)>n1@V6#jtoLJs4?Ae95Y0x#g`)?=-1R9Jj;W0+ZYW)`6^na? z5ZiNj%!oM(_ip=$*)UYPZu6f~7Vy4Y~-%(`I%06+|a z?t(j-rUAE>ZGg!Fc=P6sr?nU>H*4{xlsO2r9?}s5FZqz-l4>3uawnnvv**@~QVJO< z@%_UZ|BvkOby?twFg(vIyvP7HtI+id>#GWHw>h?l9$PT%HNiV2@fTS`ND8gHKijLX%0;ZGC=@hf`Jw~!=fZ;bqldAu%$IfM!^+9trS?MQ8y2GqbnTQ3hGhdZ&-^w zXHd{!EdzwYvYcUk+(Y&)YOV41^$x%M*Z&$fw^#VXH~(awr>+CfsOJ(ZrO>o{+})di z3QjW|`yF~AP!ttD{o-o~p|IT@uwHNR*%x0ziv#}gAO8_~M!-2m-*q6W2SW~}T6DF9 zYOXM=mdJ7&Bi^)t?xA!WSdtRVW+guR>=l0ZyWjbQNtzoBEXxW23e|iDMS;KjcmE!L z{_YKa{mmO3e)}uzHb3I}YKgDE_zZn#grM3YlzCZzS>#vs#@jdNIT|fdcY7@6E9?(7 zE?2jZ5)ewG={xM}BW|8OL)SED>jtaU3j6I2H_x8oa5zAU2F-DY)zt;Es>GYS_xQ=P zXV^a8V^MvEx)GSq8HDUWdId%`h=K{wQ4D?GooJroyb9r`(&8kdTqy<84M?>+tupJz zK|mlNP?ouQ&g@jj*<)%-z@ScCkQ`!62(>ny?!4!I;^m#Hlr7XrkakTtxUGMbwy#N8 zl2XSkB5eL9@q%E#=V=X4jQ2oICa2YLL2iHo_j7D?$eZiNPnvAThP|2*LvwMB4`Z3Z z!pVTL`w(bC?Hw>*GeI+_0X}1GmNi8%SK1^^Pk@2`ni1yQ6b!H5;lx$|iST;pA&K$y zoX3#)VShhNZInuZXDsR9<^Ns5Ok)P(vhkaTZDLMpmqB-ABjRI~CL2YED?QBtR!YGF zpp!^p+*PK8d@(H`EUMhtD=es8G5C~l%@vdGGbSBJ$TZJ6iHHY0_c%yL*>3kk#^nxu zJr@gpj$4#M1><7Wi7%i@lI~zSQ$0zI2#cUpXXkmNOe4=tob-G?$82UC4&t9prFNz| z$SL|us>_VmSBn4qA+9M?Lc?k5lP%tqG|z}WMZaSQniL&kM3(?gyZbZLmH4`ZJUZ8D zJ1^*`go{&lf>UF-xEY!fb-ECwDVxbDXO!{ppIRz;Dn*ugZ)&B~;98OJsUE^UBsev; zXg%$Rw8uR2Tv+ccl4VA`1YkCs;qmctgb;^eJMo$g?IfK~uzP(Mzut9jLmw&t03ZNK zL_t)-C*oyUhV6EXs;aPDE^&8vhb&`=2|MBXa9*|XwHy2YN{^U3HxdSdu4$pG0-KiM zH`^Y6+6l~QhLl!=G zAPE808olh$OW?o$fB%4g^)LSl-~QnnTr6hjyCY_^%8OBlXM>Ie(Lx9)X$lOjgm-WFD{=@iaD+peq=IS2nyyFNb>Kyh*YDoq%ddWprl}#i4zsd=77~}2muTA- zFP=Ta(P|9l^EnB|c`heMdZaM#^$jb8qoHDfa4th4XL0=Lr6d1JyG$jzCJ4utB zvNZLMRMe#XftbR^O|ebQ7w*xfAkC@a5i`rTr_O~UI=`pV0G+K}7^WBQ`4q|`x75Bq z1B3SbWvT4Iwd@`4?a{RqFm?*{Ru^4YFt3ONYGIcjA>76zi?c^kr?@>_|>VOnX)uX7EeA7 zHPJ+z5g4SrB2(c)VM=12XPC`qkZKL7`cXuzD*#gl@+q1IePV*y(fkPPLb(ONvn<}8ssjY{mj-6c3 z&@m_!5Ty#}QxS3`67h)A*n%(QSBGB{LXMLK?dv*vh|s3c$x7}I)3PjmK#glk=JT-# z*SUQNA-un`(t30t$Ll#DL+m`j1HB14gtD2|V~W(uopGb@c*u-J%D@+os0*uE$%^4Zi)|?*P@~Km8y7E57*R73NiGrxxr492k$+HTu3mk>%*S z4!`~FZ}IBW9<(Ts_Rcv_}BS`ePsP=Iv|4J7xk(nzgpxJmA^0Ta-nH z-EKGH8@uUIRaJQQ?3uC2v;6<6oEzV9taW?nX-mMF82g&{W!g?|m3ls6R4p8^a#K zBM}~FV{U6$?Adx~ERfV9@J=4Y^KNg5=^H1Yk;O3lAPPpDt1Uv#vka73G*)Bad|RG# zMoas9H0h#2SwbrWdb$S&0zyX_AcPs3%}H_162+r|${0dQrYZa>4Q-Ccdj-Pxr-R^h z4@$7J!a^AY1;+0)PG(M_@bTH`1gc6aZ)!1sG-F+t5ir_>ZAz?=G2Dy8b22!e?CR2# zpjQ?w2`eOmAS92%r8ADtIO5TK_xIg(4nH3cIo1PT&Ad4YeOBOfPRx{24yX9QQ=P$6 zAt)yugdR}9f$~3gQApYav6v$~el4lf$y3bvM$*XQjFOR%F)pkX#$DjK^u!b;B>wDA z6^s7oi5)$~E+A*Fce0R+L>Ep#<$f;Db6i|pfb(}J2zJbw3OjH$(XdU~5XRkf>>~2d z4U?JTI8PNf9=)`2lKSI``fvhUitpF;pjoevDdAr76Y*eAuwWG30Tvd(MSs zd>!bd>&SQ=k|$FwQ;kOWPpHMvfrDqbhbc>KB8)Ky>SE&Wx>Lqa?KMA>|RR6kt1oXVn53Wq4I)*mVM%PNTVGSRZzH0|F&G z{JGwt>3V2zNJ=4~Kzd=Ps4eQ<7VYtX&Eq3(ufIfdto`*4dA;U+4Mj%A3o9;V*lpJM z_7A@WVH{;KgQf(}uYZE&<;o+w<*dTh%{8uWZc$YgP&fGYkAJ|sckeKp7x?baf5a!B zd}N~SqkX{9Lh?MvVzEHibttQRm^O7i2w}*x65o9D4Q_9qW3#=-XPTcv^u^)41$rrPtZP(@B{sVqZf?$d+Q5rLlYsG&llM3-($79!fvz1a(RKStx;wajGMxj6C2OYH8R4{5mP%=VB|DpEGWi9x|e^BT(}z{pvPtRy`e%5@=1K z3H97$ZfP zfgYU*FC6MZ4XwopC`^HkCz`JC+&Y8GTahCR?7CF4s5$4@a4vu)H4d4&S?3%aQoKC9h!5*v%y*ocl%)9ou>dC} zUWu)(ruc%V@BPEvYP{W+6(c%S%Dq>&8RpjK)vYfl2poKL)yRQ_5CU#Uh=xAH&3f#* z&i`IG31E!+e|I*0F@hXVRZ{=$&}&z`w{7d+Q>amJE*vqXZS-u6)Dx#*!>E8^Y_vx+ z#;mx`yhe*2d#R9dhM%n#_@$Vm?ls=mHQqEer0TKGIrc3>BM9C}f!F;8f>Jy%V|it4 z%m_eD@gmS!uWyso1^}Y%kQE$#-+{3Lig2u{#<%a@qpE6LRXIMHbIhQ@c>z}B_$-^@ zOPQl4JqVF_*c~9V46P8*RD)3tC<&sC=W^dSn3W}(`T#uw*=&Zk zZ7tnsY-i>uTUS?CxVyW9mcVQ=N7pxKng&V%&322|uixSi-~1jw{o+$x+*~4O44;1X zIqu%QHw{?Rm?n)5`=El+7*K7R#a8qnZHMo_{~o{m<=>!b8nkVT^?HqmhX;J|#TO=i zy{xd`A55^$a*6eNi?S^7mmhz`<>d{OQrK^IsH!=RO^Z)H`2>A?#MR{j870UVL7o{8 zZx`kyRAyaH_>)t&FyWBK^@B8p5}_e26FwTA6Vo)ZJPW+5si#IT=wNDL5ME8kZWSTu z6F+kqJw=N(($k`p6G&K$Q^FEdmBDO5kzwzrR@|sOJti(t-GrZj5Cx@#KX(*y!B7tE zX2Itg=W=KoaGLcXKpl!zb#mtDs0IWfHY6}{PTAsmbcTfbGM)vthSX}m$Y6gOq;G1= ze;zRoh@PBYpQ~So@39d`GpLVslq4bI-ZS9 zpD2EwO3(Wc{-%rn3?W*g!-rBQ-)D>v>j^iD7`Yz4PNs_{f+V4TihGaON&vSdQccYQ)6c0S)letauTxd|L(F&Wr zr)(F`6+|f^iAwmI`sM<*2zJw+Gbn9p#1{Lwk0?KOCzeQ{Ck;RGZ`E2Wgk7#~eJ7&8G1Zc`kq>ZwO~ z+qyxPWl+R~CAjZDJUk2zDUp|ZilZN1S657jjcG`C@m}x2{W~}9P&Uyt#Z7nr-gTW1 zg6ew#*$e--g%Bt;aMv9054uI$^mxV!T=5*A7IS=66zDS}Y&;$n+P24?6nLW*eiRz7 zyABy)X2?Pqh$ddhEtL73LiHewfGLSwGY|n3nu95Z$HNhSL5A&ak54hfWmRFRfqPM7 zyWik8XP9LRR2joXMggKAh(y=7U^GKn6%a7O){Es58PD*zzQ^iv2`OaK)g*2nrBYy= zgK>`eeC{LCo4Q7x2W+BA(Wxf9S)~x0fJVsCI?~Q;0EQN^+wE|BdyBFx@!faEI`D8X#Wc?|yuW{hPzvkq78e&6 zmdavu0e#ot`uZAmU7P*fz7}H)o$4?vGZZC9ky8^F&#AY-82Q*Ghmw`=AZk4{@}!;j$^MWvBm|kT<$b4I@~vT6wKtNy`eYs$=OVYLfK0J2|EE& zobWI{--i8_KpDGS*g$;+psAUqvXkPHo(THjuMe3X4H|8(K z*MaJxt488sb-bIn@H%G|rwFXT(R7;e*diQhxD>vrgLXvIbfOA>4JDM0lN`0Zmc*;K zwI&~IRYSvOgE3?@gXqloyX!jac6-!y4XsRcbnKq-6z4qV;m0U#{C-m2+EWE=YHd$_ z)~Sg{%wwiOryhzDKjih|!gI=E@SN~6RL)Sg3~gYKrzSzOSKsh@P}K z44YCn`8hW=7`vE=)A1vvUZfMRgH8(L7(xlOJUuKOl3cfqFKT_`Z0QqaS)%D0a5@Bm zD5X%ArFCrRpPWji8ofUFJ!eDck{R7+4(Sb36qHjh^HUH05G3)|fWdv4YX(uw@ERJT z0cPk>${l`Iar|m8)+}7W3Av^1m>gaPC zk{a=&U>P3kBi;y&_ic|n?*V-Q4TA6MJ^t|ch>vCk{?)S*OAU~w1$qgUoBJlZ9=m1_ zl5xxPCAhh{fzrLbM-`;hXF1r;DXD8)RMi|`e)UuAkF^Q;X?xt?-=psjkW!-VIl2i)FV zK}g{C_7+n0D2og^Q>e-uWto8z>5FSAH5g~6h*lc0lt8P2tIr6$f3!~#41#0Ai4mh? zkjKS^GiI<;CyMj>jf4O$-cM8eLYz+2@v|>b67x(5J0QRz^-$~6Js&?V3U}jh@4t;#ofR; zXMvcv5~JR6;?KFim%OpjVILO}j8KGYEPj9CL6r(b2*)~O1*uLJef~2@6B|r9OEw@W z3IqVtv7T|9h>JnzBOLNaM^l7|!s5gdZtR4(aR|{*O-$mJC-Y-cXcv#CeUYOnL@#kT z9I;-n@&5gLJUpyz3LYQ*ja16wHL+dT1>Oom%15?7o&miPX6Ns)yD>~$$Aeq8WHIP{W zS#bQYdBBD-Ty_mw31lGn{@CHqLgUy8eAG3#C{~ywM@f6AULmh?6B(_|0Vx%*UO%E~ z8eFXANi9K`xaRjD09timjNouMpb-j-%V)@o64mSi>)js5hqqviVY7a~dVPnksnNBD zn@lOicE7=Vw#3!d6_(2-ilP{_0@ixdHBgR!uaxp$-GpTL#V>w=H}76!K40Sc>t|TZ zD^vx;alb=P2Pr&F6FMb_ZmX;q~j+ zSg+Uk<=^}b9@c9}MNqd54hQ1_Z`QnVvO4` zBdg}-Qo7faGgA5$Pwy&IAv$e0C?y_obsU@e0AB0aB3XQ zsz-%ah|r|Gu0vsrduTw+$emDg0Eg}rsRGp8P$WBxbM%r?hzqkk!3ormoT0yHNGO#K z0!eZwwe}CBAIUHt6@|+4fMU<%5$ec@cX2qmM#>b-#(pMvU$(;?-7}SWewP_7ju#TA z%;V}b6SHyXq#hxBmO@vI*iJ3Qr9YYG z*k_PN^p-GmB%~Fknvr;N!x$e42*dl}JelJ)=w8e5qo=4{=5NV}?=4SkI@9}u`z+b$ zeTN|(S(X9HY?4Yyl(Wj9m)5(Tz{GTC%piNNP2%%H!U1xYve7dDx7& zTmz%A5S}s;j;eDipc)t_4b`LRD7dW9)IA#6V9rbY2#WvKNz6Abep%*NUP>sjMlOMj zW{^sQa1(k#LD9DgjBxZypdl@gQIsr)?mL65u^C#;p}0bs&2W$kozggP39UQq`#l~+ zjk;r~`A?vT0(gc_Qetf{ARaI3!$+1R)How-h92+^*0LcRa+n0sxJ=)&@fwFadcMVUe9)5h8u1~AXDwtmB>hLV zWdzikL$iQGt^zs+yvMxusBB0jI7fL6`Oq4f=Ng;8Gw{rnl7@OkLYgIlus0Gl5aXml zS5KTqq-Q}*B1gXcD)bAd6n!u41d5KPJ`S0ec8~FAD}YW94jznB6QM{9<>18OMEUR>^5JYCfwRZ(|6v4u5*$nzbcA}B6m4~ih2Zpi=d^={DwRNn(+8!R zO^szkl=>-7jw0u++!)9N=UKs-vZd%SVF5Mm zwM<7%M5@b9dUra1YbVn57Bmsd#2WNz3?sR7*DTf58zH1wN{*hz>_*x49p2vED>qaJ%+$JfpYUc#}QD>9}K zjuge>oZHLPm~n~^p5oZW1$SyJ6}y0>rVXbPq*LdbA#}h7Xi6(t%~qGx+R0Yp$xNii=L$gqLv8i+iD(jA1-=+HvY4kF7zxP%lv zs1#_m!iyI#uw9#}nY;eZ8q}Nt=9;+X!l7b|#R4y0Ji~Y2eFrHe4u?G`=Xm$-4f3+U ze6~cHFR;42L^)rW*ywzQ)fd;G)|FLgv8uR%aO?x!%I<4VcUtL{cv)-X7jA!;@UV#&UmpN9e6|zjBEbLmKu>j0I zzatK-vsxR3w~j{W*JzX!OwUZXor}X1DxI7>Cyfg92}Lvh-Y{^ZlP*_Nli$>{IHk`? z3&U}ivUvV~%oqH_dyVTfGHMFOfk1R}0z5cV1tn*cbSQ-eFt|TCzwK1vnx5dMsmD`} zbgniVK$$Ut_(RMl&S~P#o#iQ@j-R6_#5~sUAUNmnkQ!G`6~&BF>rE{u7AZc6s~NvW zh~}MhiC}?p)OAAVgmFW0eJV0ciO;702Az0tNOBxLwZSOIsSb(^jRd`eM)U-$7Iww5 zPBku+fVu}p1Kdsw`c7bX*yHZ;0q^hDxPRQ>-TMc;d;f@shb@$XNBqLqbhI3Ia7Za3 zeCN)fiA`s;Nuh>_Xwh81Zv5rq;+LO(mtVNI#2%MbdcvPZ!+r*IlU8FwP{CeDaWU z=#X~DUG`0rMYls58zBTNU`h-yBY~{QP}fIuUDR;!GRB~^2*g{| zHzkY_be*}+RW%1=nZ1q*vTxA0HJWyZ`nUm?4D0(jE>>6QOkxgJs}*Lm1?KZPw2)w& z_-3ytbH5G^B0XO3Zp{qOrvf2*;8ACMp!eD4N^5Q?7-6z3v1p$*^aVyJj`b0b4;x%v z-QeNj0fZ1#RfY9>ZKrwW`poB*p$v%*qV3E?r{LIb4O+cB?oCk*;CMXZ;&O$}c8A;B z=ctc+yu7`{Vm3q0dT_>!E05JlX-ZD`?k-B5MRvBPInB=MR2V&Pa=@S`!G?21Y^-0I zqJ;XulSFYH*B9r`{S;_s&T2AggB%LhW8iB5t@QZ@BrGly!E20V!Ni;fjyuuk zI5kVTTBXjW)AN=lMTD*%i_4$XwD1(zAwjsEa|uaLGh&uR%$As<`c7H!#($rus14_e z<#S!ylncYu;T-=>PUy&#gHi%1(|*F|;zOr6qEGQ!KctBFk*#No=U{}uQruzsL5?ct zialtYppqZbVfkMt00=gClpZi`zALHzdE001BWNkl2xX=`t(tuEqxoHsQ#S9sxpb+TW4#=pn z#|scL!=bd#I8l(YMCK!57@SYO zD6wv@aGVzam*8>(MJ2Qrpx~gCqiz~>U5A%1U;62TOHDNQRQdxq=GO1`drvRpl%kr= zyuZ2X1$wDKGlK1Ik7NC4#@QfPKV+z?3ag7tKq+e#smJ_%B~fsW-Ue(9(@Z+DPGo^k zvXC9JyfS5@9+Ed5&=fw0y=^3&g`mJ^eMWo^XaHk2vlW`rrzV~@)ZaG&hvma%0P$;3T&4V!Jvr- zfifA)K7!iND>YbhZ}bHzf5Jt}^2MJ*8`XrCOJZy%7Z<})Nl(epTAct0@dWf-{g6U9 z-6VXfi8z-~YzqEq7c9r^KCRdE$YPIZ4W&hLuTSaA#uP_q?FX*~n4&xS&m0BikOVhA zm2Z(cOQy~lGey$?MDVxOq^4!+zQws65xR47{o}vI&mHoqvHMh^oN`1+a++guy7Leu z)83Nj5U@%2kq-WqAOB; za$AIekEm{Ra3nb%kA9-jbsc0swk`}e{E&taqd7DX9=hKZLV#M{xbxed&1N=Sq?>gA zaQ8H(I58*ewbY)I{n(<&P=kQUSqeHN-J|&$Q0Vcpn&aooC5ooUUpj$C*7#&mK~RNG zNi@wKH6z&P936m+5M<7eoTb;SQVK+A^qmA@6q*T$uEoczIi4?bw3`NXE3oNn?3Kh0 z3gURc|4-SQ_DGVX>0yr@endoOtVD>EKvLpTE9sL2=;!Ru z(Kme&AbyYttN>CZKQl^M6+W~L8zxS6?oRBr=?t|K!t!rk2LeV_L^ z4s{Do5}af+{In?1rWA)-p(ZJy8lctogo;uml%s81cfZ%GE#~t%@;t|CwF)g(y(Y~H z`qtZ(Zs0h_^KX0uP2E8ViOpt%!=Xgg>_HhtQI#%cUN$8v(Lh!O9zFdCS(ahH-=S$M z;2^PFo@n|--3;^vy$JodKzJ|-Qa$BSMXpIg2$W@wLs4L{IK{)m0~lktzP`f!{k`+v zUavQJ{`@)Gsz$j#AkTB$@AmlCx1Q>zNh%YGE^&2rh5ey+1@}Ck>42M@#xVyR2 zL)a!>21$Fq2+g>u*aTxt+uR1x<`dwHLm)lP5Q*s;0H~uB_7Pr{TYXOjhRmj9kpnrbHU^UhL54tQ(-a3(6nQP z`qcP7Jl5raKXZ&4@O3-JW4xyKJs{!F>p9m`g=MG$&e2F~9Qb{5RI@ z1e=B;Jz{MKdwx-4-XB$Zq(mu$>LiLoiOp`W=^zhlyn20$-+%QAtJMZd5pX9))3MA_ zjR%}qUj4DS^srfC!MH3gl46=gJc_bKjUCIzO=9REgTQ8Nik9#`>pH(Ev*@cuAbpXf z|K7(M(*dI3@e;=r)MJNreE;LG?-3aFUjE;hfH*{k*uc|tc+k)YN%v7D?~tL^yq^Ud zY5a37!WZmeoCWLJ(P5z6m=pjK%3M&5T`O(d>Im#C3n)f5fzKB9nrgrX8j2w0%xkbH zrA~!!lO25#xh>dzgnle|h8PsRN45Kgg%GM|J4OhlzeoRDRaHi87mk@5A<(J@l}d0> z3U`&jFPaLQVvo;=!hexJ#z$#_H*||vq5!%SEm1mAFag?K3q}$U%dzyXdE0eBr%_e~ zppgOzBX~v={1d)FcDBG))L2y=)?JI8kXSc0R3p)Ffs$nSO|iwM+d+y18^xhm3Z;23 zKuVn`^ySN!E-6t8Kv3aq?1*PuDooH;p6jM10Ylpg?Du=TyI)~GUm#6$JpJHIUo)a< zjBnrG;;`GGtu!b>1+YI9NM|ctoSmboY8Pzd?G$CX5S*19NPzC$A`JwtJQpZ=`ZyRhN;6MVM5cy@bP zR3BJQ@%tv+V*ub(zCn*HhkWI+b9tC%?ALX@KY0j_d3!SuxRC@V22s1EJSV6z=a6G5 z*jlTlK$#jvoqgKs6r;kvw~%7U9BMswZQ|?1$2y!b7lSdC{Ake0*DOeUk%E3XdX%d@ zUD&8#>=6nT5C|owoJfvwZ2K_|o#Y?|?@L8A5ker8at8Qu@J&2|uzs5FOA_?mL8gLS z0#s4<=(S$}_$Zw#VoW5h5CWo=I2;bRUp?S{v&Gx{72e#w!|ONiaQpTi5DF(JC&r7` z1QBE$LXhC0o(eHJHjOye)Ws^`sr5FBGJ1ka2@!ZHtBEdpYMn@rJZ3fVzMrS^e2&Ku z;i)Ois2k1*hj8k1PX!wFzwGsq?zuT80E#!C-Uk-W2UaI=VSrE%eBcAOl_C1=zduHd zM#F5*#7u?kWQZcVpB}&2PyV8WK}j`;7PrNZFBr7cnWkx60q@%w`i0w6Lt&pW+t@jJ zltHb^syb@R7=)pC(+?O#+@Ds&_LT9VsSF3(KkV(ZA<&{x6fX}Q{$3qWwk^I?0)T39qXXdk$?#A9BJDY+j4{1;sl8z5Um1D8S=KpMO9;- z=eW*iz=ETd1P7_`&{Vi@Yuwf)HeCnFGc>ZmUQkHFA)!Es1S1-~tcn6po;*QaYCrRf ziwksJhs}0}EK8zsGmvE(ZEf2cLMU{dans=(o6X9Euy7;dOVG7II-lc%4?cisZqT)@ zZjkB*hryJ+c% zZ5xR`ihO$@$1&Qd6~sCKg&`0%tC4Jn;QWw8yLxG{m)Re^+JPM}jD?v5_xmOp6z^l# z=oor_EP0y*Ygq)LH?c;nFRE1^b05``mPRx=foE)VIvZ;MM=7{b9okd%`ZHsaLrr^z zL40lEMmF{=4;y4MsUc8GfyaKX{up!$GLMz~!;$`YM=*L21<{nl+T&eA&JA+pBAP{dq}A- zf>F-by5}M%qckh~97qhQV*Yz<+ZLkj+(gFTpF*xH8#J_jKu2BID2l=rH@nRir>Cb* ztY_Dey??$HVw@!A9~PaVK`GHA?v4|k=cB@LzX0|rBh0gfwEu2j4}cR-274IQD3}Z6 zAaKG=Ej$DA>=fHp;#Zpk1Qpmb0-DUQsayQtyI1(EJHw6Y@HkJAvr}9uf(KbTab7^9 zkzUYD*Wsbu;nB$)i6Q{y5Qgd?6W~R=#%5jPg5@}2DNbi|+$?f1mSbC`Cu{bYq6MtQtc8009lfw zs%tl#6rx4hl-QR$%w{trG{JWL7R%)c7-OhwJw2G6&TxKpiNk)Q9cShl2%Q=Kf0(bW zBky-zS=xz6S(a#;Mz1eU+}fMZ=Q`D~D4>+k;#&|TDR+|=&N|P?7@#&r5%Ce)u{?TrzAh?Ab;~&i*lWg`X7=o}b>?H6fBD(8;jsJ+55-)Z8XDhPCjp zi3yTI#{yvV!Z+}^n*Ol<*AZf4BfTQf{MigYoK2(kcvMn>c?-z*XVg>?;ySi5BvEgi zX7uKQRs0Dw1*OdS!TLUleSy@!f0uLb^PW1*AGF0oJl=B$tC|)91UF8_7G%mfCP>)@ zBOs|nPwDXPQQft@OU8&9z5PruUY0@#5J_CVmK|@h#JSL2Nma{B#Ji{!@AVsKrCY&Mht|_q_4UwZwW)RVBMv?(i zXdzvtEfa0QYpDm;1?5<(DDgOIcEc6+vq6oF@~q&bi(XHe=hH{{yP#2wgHFa8(J<0p z8QU!ZAv$ekW_a(6YF}R~IMMOZ!W{ToQ0TwMu_BtM2>hFEabT~%ElRfAExM*fp65YK zxSp&i)O8)$rCDAxq=F<8^Z6XR-41101`as>eYV%f#gBU-M`N@e?SrbPN5m_NDWxu0 z#&3ugiv=o!Y`bU1JG?p}Kt0sl{++aPd%N#Y;wCXvXqw7yx5MGE8$`8ttpZPK&^*Dm zV~~=75e5N)P0AqmEw-XWCOVw0OI-5`=ZjN_BmuTtkR*jNQZZ+VN3`#)Y+BUo0{kik z%GV5cW|#|YYV2EHrt`?A9q*n@*$xi4@w&%q&ZJ3OQd;@j3lSBc=UC)3Jlx;n;^GqP%{`W97wFL9d^yAU za)CT!XhjFQn1iVK=!@py_bMVnOaUW7E4A@iY6fm9e` z*3uL7+Js9LtQluX3>h@|Fq9Q3g@)(aJ_Uc2 z0}#=BImVyUH$Wdm!j2^2>2Mvt$e}^7M$km4A+4g7B2?HCIysI50LlnNr;#N}ec`GV z2{J%PZT?R*r*mJFSZy|%7P2ky?%g}w-Mz!xyL%mj%TlM-w*^ehksaG~7$J~BO4E=( z9a<2H009}}8wZ}_gn*IQNrZ#aKK0MKMO4Opz`lnV;kDyhSA3J>jiy`EBV0WHHGScP zEo_fDal|wY8BJJ7bSS*fQRKbOHxcb*%!VpNZZ+yMHgV}h6U2hIZR0{fV$orI|6>nm z+lW|Bvb8_72Z_Cgt>{cMNdn%xk7WA=4^cpxa3_4TX!dM2L)Uef&1QjUG9D+!$i*1P zF`#Qj-|Gr}kFRarO#F1dvFVw0C$T4}yLVEdQ_^#H=+}#HTj)@Hq0plLdDKe*-De37 zvO%H*4vb@m7HPdj+bC>Mqw9KZs^&OLhqe(yusf8Xj3b@RKl?v+V0yy2z_nuS`&mw(S!_U^dJ3o@Ds@P19h%FR23>jm%yu8HWaB%Bjzu)8Wd)WTn=#7(K+nORDs~xB zM~l^C)+xtq$;P7CkI^=!zCTdWD`JE`9%ouAkjNkUm>2I@P{vfajzyaXMFPUC`o1_) zBM+P$iPeVZs-PE%l+qlUJ+EAvqB*`ygoFi<^@CKFf2uQr^}n~Z=+!xaG zTdhrJI364mtI8nn5FXomWY><5WFHe9#Rax+6KJ0U z`=0&hV9cQ<_Q-W~JF8wN)Jzcj(SO^vNRrH14O%-n4Ny?$nqc2onx<rSATQ9v+> z0|43zRI)?M;9N1{m}ZSG5mX25QBBjtM4KyALZFZWr#wfE7I*Cyd#XdmuF^TA6j(I^ zsca#6jkEeKz*3Z=1J%BrXoN%oq1{**b&UfPbkM+B;cB4n=RDAFB&num=(I;*S7>U4 zY)x2=5l2xPwiW1<#KUTZ)6-L|*J~t{;lmF;!0Xqqoj|TGH3vIM60Fy2 zEEWqV2EDwzL|vA_RA{+eVzbuNlCms7sM!x0!R6&S7y&5ZPKO-$p^u!IE-1=?VXz@P z=Grhm^hf?Wv;#m4_{i>TizozR)QK^w;aKrDmXi=R**u`U4Qm=X0Z#ajZ5KqO2ee4l zy2c_dV8{5!7Id`xKkbhS_&!F|P}nYb&W zM7@XmJnr&wjH5H=a53gkGL-^3DvXoFJMfK|PbxhDu!;Bn!A!>ERHusQq4^^+T+r3|!}9x<=4lz^4dN_j813oqK~lWMg#Mtuf9(rJ*kg>0D99XiEO?eQE(? z34{oJS|#bzEhUT%A|ca-a5Mp!3MCk`V4AY7j75ksD(W9DW8o(;&pf7;_`kP>XB-GL zDdhClx>Cv|G5Sca?`0Y`BO&tRQ$qZv#=Z|-L=(tPfTu|yLTlUBai0C6(>9LQN#xj6 zfQBS(hMC@V1(g7JG=uRXo6N0XjOxbq>vQY zHwBdFP$(c}6p|*`)E(w2gWw$K^n^kxjc%1?jWnHsvcxr2b*=5?D8e=7+w@s9nR6Wn zE!qxcb#O%i13{AJn4P9L91f`KvTqR0Xxa(`FD@>y-|vy z61&|F=gTFCp-wTzuv_i0Se!yBh23t4v&$>&cLmPQ&QTV7JifU?&KY>3Jo`v$8f-Oa zblv}nrdh^(YDI}l_4C(q;09t}L-sz#V`6JROfB|Q_N_dp+%VoJG9KGg$3%p&#b{U$ z#UgLb-=*I4$1k#b69`Q+A(VOr@(>m8i*|2M9qdEB4r)r|I5j<;GOo~KK|}Nyv0Sx2 z^!^z$)T>yLBz3e*-MEoZL*{+<-q0c}ngOcK1*|nMh^EZazC6%VJri;7T`SECmw~p* z+M8Mjr?GVu=v|b5J!u#;GiK&Jw$R3Iz?4(SfI~H5Z8C*|$JR!JVx0iWq1O6B2?Yo# z`cBA?Wmh4wMPE0&TSr)cswKJCMZr3O(>}Gc-9fPBS<)vq4%_BRc6OvWAqA} z+SG4U`sX%~=HU$8A^aj!T7L^WvZMOFDn&pU$97*}x7*`kwZq%h8V{=t-aV|a-R}Z^ zE~Ok@Q$fhipbrc}gd1yFmVqlnEE*w%Kna1?91^zpu?Iz5++o6Z{1|OSS)a<7LL%Wf zuJ#b~J#_7Q^@V|M@-VVt#f6j*0>U&=lv-Lr7|JpzYDQ4pfUBmCJDkKk-RW^5CY#;& z*>A?8&p^Zp20)Cywv^p~N~K*pgj*Mu8|gPXK4Pn5(DglVZX#AF31y16q)%t`?%%P| zpS@n1H_lum=8I@6oe-g9GtQoQ!Zkh9U)bsM_WGy$L7 zBKkIX#U{HEqMW#sFa`wz$*q<{f>Vml?3Gku#JQ&b%kAm`N(kh$1r#V6DX#J=cIoA{pAyE{SZU7sBq9|~A z^9aBH{qOPQ$rGHMoZ$X`<<|Cgy9MVImzS4#`}QpWV7J?$X&QX^;fKya$J&@KPtQ>l zg`4bERfQ)XJVmwN;OWh$VARlfJhHC=+TFS>-_(LxY%(I(}A6S(1Eaugu3CGy|pNy3RzzLxI_pidbfgcN3d0#~N7!P&Iu4W3Q9_yfb5J+GxMJ}D@m2!sS4wmaOvd%$XQz;;*Sezn5=YK7gQfKot~ zq^Lw?VulG?w<#%PS!#qrT`=z6?RLnr42#7gD6)N2r4bs@$<8u&$j4&8V-$?B4cIj( zW};zzt$o)7fPyg^pbkF2*7**bNrx4GSPv>XQs{)y?8#ANdCUo8Y((j7emubqj&#sd z)1s+xocOik;{2H3Xy9EsqR#KRmjX$`y#}mv#dSzSIqtO`yMhGGk5Yhl$oZecBFuqk z(jehJqRtpY*XTy8scMJtS~SvElKY3FZ%`Vu001BWNkl^KTW@tb0Yysf}^ijL(FZH=5|;EX{f40TtdlE4B40t#IxfP{jl2`JGi zmM610KK<<5=sJo0X77qaAa|cVNfL)1``4mxLON&1mL(}Vq0n^=2w{e^EL}m^G>vV`r^mF5!Jd8 zLMhr#;@!hNve_K_{T_8);|JgWW0d6qRZ$udF~xqr$7i2?3uSr0cDr@%Mf3R#3F9bg z?Tx+PSIF}mH#ax9eft)tr>8nLJ>yWa!z@p*$P*--fKx3b)97_)8Zt7fGw};2OHqn- zE<%a{hkESUpRy$tdQ?4{lM&NB-sjXb)&R%F^;qigSVKLAaE^)?X}mwHz*;z{F{IKC zCd#K&M(2r_$gH2~aYqnqQ)hDqrrb1!4Fg6fgC0K{%uMMJXkhGTn`$^T-DKzv7CYKa zfj?URAqIPB-&}}35!Js>Y?}W*whjkBA2gu-X_2N0l2fuTu!kZYHA(fDDyGLgwWoY0 z$HF|qB3U?ecWU$+Q#gEMaJ^mxbW|qmA84rezJIrPl++!vbCh6xm*gSD;lqSr@%PGD z`{1Z3hy+2=v#SQr+g1%wdrBtw?Z!3>JlGz~f-T!J5? z{isY4OmcRorY^RC=#wRNj`*DuBOH^ma~q$XR`}?w-+;vL(NDYd zX$`&wVLWym6Ds)yr~miN8|_wA1<~r_Ix*7?|8rX|tIy%~dEfE0ZA|2-qCL>^b>r)2 zi(mU0{SmZZ5WAmgU&AYs{R7Sxh;jIdG@WHoTurxyad&rjcXxN^4Q>+>2p-(sT|x-% z7F>fnB)9|y7@Xi9oI&o%S9PoSH$SME(|x-4-p^WVM*7}f(9fr|uoDRbqlLc!OoQl$ z$2b@IL&Z_9l(@G9aa7S%RKY+sRsoJrz44skus3vvQej-i7pnn5j!j^G4IU9??(oA` z-O>zLG&?d*nC|XZn9a9z>aBLmXRNN<=|s;n&ug&u>FwqMx(7`pBI;?Y+5!R4kXuN2 z38JnMq(uO7?@?V=XtpUHHS}Ho3M`DcgEz6+tEZbL33Hu4TU82aF8mO*FNg;msavx< z)5}@oY_Lc1a`W?d+WVlCQm+r7cV#~12;NHblEzl9!<2x zWU~zA9g_#^A{!j@ z@H3`a;!n3&4nah8jloM|QHqX%d-8K*m47lEzIm-;fNjB{La|NMt?rfw93{3rGapL; zqaWbqVDKD^fEwX)Uijtpc2FVw&*1kkJ#Do>nOb3SpbA@)bZl5Za}_Z#s&A__nS!dT z9%D^UQ{egL(`$-r>v9jM{1k7dcQI{vC~5P3*$oqZ+WWu%dt5jr=?~KUOCooyrY8EtBF`9bfT@{!sBFjk*<*5IHTZ=j^iH=|3O9UE{$~(uLp~h4Iclq9+(p^6Db|$h28D&t!S;}#N>>U3wF^DKM0i{2UV0i%eiyG{ z42%BsFh{O*CX6gMsJFo+`zt{K5WtRgc7oD?y~_6a-C~EnWl0_N5{a+i{!k3qM_lriKk}bL_GiGN76zB6vM(O&`kPp;!E@@ z4Qa#~f@R4TBeGuzg&(Bt^;_9SsXA8nbEC=onx8iXsUlsV$%zf`)XSXbDukWJg4zPq zW5Q(ymWI}jklf0u(&nxb1MU3UE^=N2Tz;sJh&PxBD2a(%xzEd%_RZef({E8)oaNp*HPJKQ_if%yY7N9U`pYAlXiLeaHxZNf z$a%2H(2V#&E{u$klfPT$s5lifTkDIi`#t?Hi#;`(NQJ>xIdiqxYR60Go}rfy@zJ+H zu>l8wEWiv|q6o?Q+iemYjg?tna6UuNPc=0a)!8_*ybK&UQ4bN#TlghGOfr2}^f}TS zD!XhV2}YHVqD>6S`bY30>Yqy|FnpziN9@pb-%Y1y@|ZKQbX`?hys!36{#}$*=jwK{ z8gVC)2V+EyuH1biIH=;XPz$TDRc-j z@CBSsSQmcvs}3_puAW3$Tpkg>^_C=Yx}G{Ps^SU6-T8AAJ8!;AP!LC#Dx39Pic&O; zBC686;8)EI(R-P^xM#FW3v-K>>W#Y5m^xN#RrRs=xTn50Qw`^=r7lF21we zCYF9=Eo4cHun(%z>y$l4$gW1c`wTGx`dGQS9B#qE)P)a1@5=;dE&y%WaVLD4Sk0cR zh)AQiIk-->su~TbUjX_45a5*txA`)C0F#=cM_Sa(qfdo^kMvGMr_dP#hXxZr)u-4D z=jVSgwSWl+wup3}g7GJ|p9QZ+(z51+EE8m&wcwc?VQ&%B{H7%A(Gj}J}u#+JGV)U0q)KK7#k~%Eeh$MG&$C6*5C@N2LtR))>3aH zx@oskX$LZuV?hfdLP13C0|K?f1F)`Kk;Yu*(f49p+(R0;lm8~J@)1-b1!DLq%i4@I z6%Xs?-oU8tGgJ5Kd-PVcKXJ72P7$b6{Mhhxcj%t*8zjK5Ie z2H^>^%KfeXNU^eB(saX8kh^@Jkdle#mB{8QsS~xjWjUnfA#$qjC?wu(>f+kB@vnU9 zYByCrn$7v>B0Ea5fIeTS2tV@?MrVzpTi5%*bNmS!X`fMv>uKNB-N`D52ma(@=wIK& z0SgjMi|4QKs6ScN)yZP=jZ};zEB@|!ub!y&5vk2*?uUN7g50!sNSl`HDCN$XdAoIL zb$xoEd3^U1=y&-7wp4|HjA-D;1lG7r%3mvqZW@wWCE(j0hYEwgW2b^IGau}+gleaY z$9pN){)HdB-00_;n*l0G$-&<4VIbZfgOzck+c&(cOT63X3XWjXI008KMd80dlix#O zRZ)A}aIVgLnem^L@BV|gLO%x#v%?JlihE#$$5z9UQ}H0dF4;f?u7_%PHj3qS@7R&}xIqY9w3zT}VMN zazXGxmx!qaK%Nmm;VqtD+kIY+8GE0O5wW5vr>C{%+62W`A?PMjR{>JWkT$?Ebn6iV zGDIY?r=kZ(OO8VuniPJ$mgoekDCHH7UbYR>iz|4&sSuIw0*t9Wf1DeK)g6UJ4fWPJ zTj6s*Osx1m6c5J*{8-jtbm3~q;%)S@VRW@F?pOww( zH+Qi{)K=u-Xa7~i;}u`-jG#ZyQNQ43b!>L6PuIQx5hMpQeJA<+)1v1W7qk)mdwYO> zRL1;2XGzYlA1kZJ1u=jEZRZ)y9K3ycie~JLc%u6$FS~7>vUx?EXpa)eCN=VQ3==H# zC5bnnhK$)@syad|E+TUYIN(0xX=2v!Yo->FuP$%1wltt)5MapsfjT*qAoaoG$X1te z>Op7Nm?ZlHA@i)d&&wOq)1moo{#3=#Kw60Q!)6Zt zr?1yEMP8bx>ouc(PwI&CxT2FzxL=k33i*7rY{qhQ3aKo{4K{G;E@9Ji2qWeUI>x^# zL-T3A0)L8#Mi{9fd|CmIW&E5f{>i4XO_m^>_;FI?GY4VkG;THE!BAkb#~ z8RD&hME?|u_+b_ke>Ow@r;uxHL%{%1basVM0$jV9FLgYrs!0|mo6~k+>VZuRc_ByFyoJg&urv^ z26V*=?M(vij=V3q-xh>SVN<--*y&`vFuL7j4h2jzs%S~;lX0OG4gJ4<3Jzn-uNT(09sFnsgrCiuXGwO|Jn zS^>)rry>Gb!}chDi146PJEWId+ULV*O~W~#p8x=3n?E>^}X-yPN4*&tEC=tO>s^SfV)3-=sk2^T&dUz>p9( zfHvzl(q%oST0=mnCTMc(8J?X-z;1yk4Vvu1<^DXX9^JW*B@ zdIf*S;a#$c>#tOZpwAk+gv+2EZn;X)A zu)M%tI41+vp2$sAorC6=Mxg-XxN@f{Nvb&HU4c1Xzu{#Tw@H4JD&AKUmO%>0EdGJ_ znx*A1!MVv2D}Zzwi%{}p2{|Ehrlb(1)g?DuN%!T(@>akcos zi(agu$4>J0bcVSl=Zo_TAZN*pquL44^G;g4wkc+YL(}!Mn6hz3VZ<)>>m}4E-*S69 zD82y5`(8c=+f@@yr0WBe^!BxOU*y|k@T29Gckr9&>v|uwZ`L!iOG*yql0g=%+TGzF z|8{5jCaU#zy;=B)p{{;<)&mcEM)mF;v5F5IT3n}tvY>>1F+^ufcHM(RQ~&)D2DOBL zLNv5}*$G>xnpe^6LU}V@+Eiub0=}^%qKwK*PWYXssdf8ip+lJ|dxl;v2a$-VeZTvqYO%t4s@{^s9732Yz^= zm9`8)g2)H6B*>nc^n9hiBj=A{fZQ+D6M&$-NAD+C*28!d?L9=wHwRH9+WW4t6{6rg zpnB_7&ux+LUaBI*99$hD4`XOfZ%gRQPvpKHsP7^kqtnWNm-J5ztd2{(%0N0xHL*Hk zM(t26lz}4`K`Vk;R1+|d2mEOlKZQf16M=ftrE%kQw(UvhFLB?V|I;-0Z*=$=RxBby z0ws|V5#&^pWv0jw99QJ{H=O028hbLG12152`on_9YO|v zOdBFC(XEg^*_$T`x~px0Uty2T?R&V0AD(y+ot67zn?!p%d}86)-ep@yu|NJw754i@ zV_tl)0OdLP!Ts7L`yIE!!TE__&*(q2xedtY8HTjG$f69SGi$s0`Nb8yJs+4PEDBDm zCE}Rh@PIJw=GZq?nUq{?vLp9gOkdqEU^l5-3WF3L8)Po~gq)WK6SGCfLtccZt~KGv z!h%s4RKun($6unrbsuw-en8GBoQ9;rgF>B3w!VK(7ASzt2w|&!oN$V+?|nk+ds?iY z&A8u^7#T8+swWvE?gJj+b>77mcHbLwR)OWt+r#FYaI@Rd$(K^r2%Y~~c(??f@IOEH zy`lqojiql#(okX_k3iT(p@-nt<9Zz`v_vdDu}^`d+G#s9%#v6aImYY;wZ}wwX!fhu z=P#Z|7q;@coTzbTtb*W8Eh3V#N{xBC1B&LAe|Nm89AP6TVX>{z5C96o=xS3mZx222 zNn-$Tr|_3y7mAvam=`E;kZq5|69eVp!}Ik_qe(5C$ryl$148c0U(5w08GaxpQG%Q) zBA_E5j29?I>@mx^_Ua*2N z&41m>r8y7xH(-0`r!1FOuv-qAee`aoR|#fxNoRKLy!^hkLJsT}EA)il#0q~txDSlu zIv%2+{lpRjuWs|SPeMl}d^SK3p*ahhY)PtOfKeav!?k+bwS3O$qhMz+BL>-^z7(gj z95#lWIu+sAHjZT^vWiO^H9xTY9%;WNBgek66wm7>fv%6D?2-ukg@oy&*&?6_T@G59 z*_fe}v(R*g>R87?Lj0AGGx>u0n7+6vev|oWecD7(HRieyUp?s6HM98_GcuAFTA zW6e()G;6e}OX~mm9(F9;vk2uTdrVQ5qq6yoTCrV8e-e*uX|I=ac*=p>) z??g~I>9tv4#ztTenK6yx$?$>D7$zny0su)e{U{mQ*2(%Uw0AlS+;?J!WJ`Yg=6_@Q zt_bn+d452Zde|cEeg2EMTK;(i{lK8POo9MniG0_yEDdQ*wf$BivW%qVF<5rJ0=83( zp8k;`;JJrGl9Me~#+Quk7c55;fuTckq%dG|ztzW0X*@+?B9Sw7d3Xh4UIHa_C@m2E z4sx@t=P7%nomw_R1=hY^QQWWF)UNmYgqzXOoN zV*J--XR3aDAu${3Yw5fD!W5>(?foa*G=_n*GxB%2pBih4R3NG#6e=C3U#ODD(@hxm z*^0d{!?k(kM{qaU?n%?R)Cq0|wy_cuu3mm&!Y&&$>Y@=T4}T}P0jJW;iRON)-`InV zGlef*`CLVLR9MmQ0L^|07!?>8mdU%V5<$+WnpY^WvF}s#c7Q+%MRTx^k5P$}cn0vT z?JuWXf&iZ|vDJC6lE6mpdJh|rl&Oe=Nxsf|<1oM|k%amBTZsejs4S_ls?Ylt8d758 zWO2TP$P~>-Rc-CrG0EoS4lNB`qbL+UILNw)@9HL~9Brv8_`226YcpxH-RVZD9=DN3 zSsIrf1+*L(r$9}_H*t}N7oHyFi5%wBUpu(QAPfK5_BW2F64!W{d*Mj2q~SNpH z8oRGxzJqVDOk;HAkST-SdLOOe4;7{NEpT44GnuulsXYQIkIUtaGgqTrx&Ue%@X4cs z%EwmEBRXY&I*!?6eXNYXu(MjndiHn5#V7Zc%9+aL?ez%iF7BIF@LOAaef2EnZyYUa z=4d)Bdms3Y1!Z=eh*Wz`rJXm|nT?f3b&D~_R_w?A^XVjIh@qi%Fwg6TCV3&+D+%j9 zzFHOiJV*g@pn^Yx$y81lxL&$o5ik%gxD7GGWa9pSQH*lJ%su@@DV`sdmTc-wp)Zx( zB;sQ4oY*^vB;>8*=ER1eR_d;RQwtTf7Qrdi^qbY!X?8DC`mIXMh&%mJ*`-FSpwR7wjHvgR)b1|VT}TJ-uv7Cb*l(`yQB6>>hah44K0yR!$7xvpJahQqV7vFt0BzStdy`b> zjkHqY#m=fwy?@^2dNv&r1CE)r+XR~HMI3iO|KfxH9KHy8N>2zCEfuU`uN~)n+5*l% zVA4Pjcx40QmDQ`pb_nNwGd{rxEH<{o^8j@KvZ3MjYY>p*7h>Go50HT0zq60s9^``h zHcL3vr{1}UgAJV9O(*x=1vG&{M?kf_yNDYU=~lrlv+kxhrK8GzOT=7{a%zbL{j_Oj zxpDZ&$A2jE7Quy*VQnG(`-9 zuSE#kofpD@N8urG!+G<}6pngHVzeKuwaGd*uN^*PEwS4%^A=|g6QE97;NkKo*Dn;m zPVo?7ly1f!R5*I@RiR2cGesNTQYo1Jl$zk!ji^kRl35uW%1V9yaQTrY{3^GP2O0YV zfuWzq@OCmu?v7u`(pDwj%F3Lvwrk8*J_>DrqTdfE)6;uoM=#SFDxu}mHXoylhV}C~ zRLV3pSwTY?HU{6~NSmn5Q%ItqX81gcrQ_T&bN|Xq>Gp(0xhp2G2rb~t zkzRAIOo)b2q~v=bQ`Z4JVr_%?mR1V_iRdVz z1pWZcU~c}6PKjjtm;y%8yj6q(E#M6*-9PbFdJOQP_TaO~4r>m|%d|au7$9oYTp$3Z zc{m&8oLPAD7$zcFLQLli3kNLIcSXk}EU8TE zI>G@61UXRehoj9GPM}b7e?BUBMUjU7+LVjMiqLQI3};ZK6^q;qx>A1*4t^ncdoFlm z?+&~Vv3waK&hDind(ZEjw$GEL@#OH$SC04X$pifOKnLgZkDo5*}m zmEvjmcQ%z*jn2SRIfOHZlVj6~>i?VS9(ViUfQi!U;&JN;;=s6yZWv8 zKbR>1HenZ-YXZ+Wa~o*2d|zD6EAz6M_Y%yP@C_Srbj~(EE>C~;qb>;;rr0EjAje;$ zoLG*jAa2xI!%iZTrvbUrl{-FiDS!+J$|6eWaMTjpn*!+(QfL9%JJS3;EHUv9iO-T` ze`pjm;o(sgqE;PN^f2Wy^Ojl!!tH0Xt{059Yd4!cJeOz9wJ=#qdR;wbs59Qn$lfUK zw)JBzr5`JK3i56#k}hO(u|K^V)I0{I@cemTpBdFo>|AO0jjFiL2lkd7hS{UQ@|3XZxE32df7(a zdPO%?dbCs;U%~;Xq0e~1)eDD z`OzP(RkEq-h2W?R)t2%6rek4Y?N7L<<6JE(ijz_GaDsUYHraNjxOD$c1#o?9MPew5qWoL{Q4? zRH(T&8bTh742ekN+_g!={%|}!>Q}L>u}N`(FYoGA+gBXUJ8&pTcC8ZVH2GmxElp4) z|BhdG$VOI)U!H}Y(tGHs{W0E8(di0iv`4B!LD{2;(yqyqBuQfsH19?@_+^D~;__c( zfeXc~RStjr>#7p1roONjR}R`EN3_7y98gyVHOqRk2ud=kx&aj>gL-2z(j)N&z-Mb%U=LU$~O0>pxsJ5%g@wI!{zM@wUn zHKx+Intr-+Y$3k+24|z!{YRK>wN|l1P=-Qy6aU_LHAfU7%eQ>B)2mR?9LRPi%D`h$ z`S|ux*9+?CAf|u@7h7Ie6w#JhokQkiYVFVB7UT<@Ony-l6Y9CST)OROCr+q3NOa;Y zdq^4OBI4pBFJ0miHUFtJQyA*gtD>+F)5LA9L&O;pwi?WLze>OHF6DT`EY5HhJ*9vo z7H2XWyeds3#!0YQl-sh}qTL7iS~SBSZIVWw5rU!K!Ju;D(JwM88HU?fUgEbNQx)I_ z4lOO7f&!~n3wc(!QM|KSC#EQ`L;)S+ z!5%DNIZleD7`o`^l+T-V>lZmO;hxK>4Mft+wPBJ}0N3X2r+p;jeCsaA_Rag)b?XW+ zPU??dks;xH$$?)I3(xN3{VeFiZ6GWv`R&}V=O5!G%4UWm^mJhI?j1)F%cyB=E8gWY zQynTzO8vqNO!}c}D$$c9e{JLDfKj?UiC{aJ7t`2ls29pwR?*k+#J0y_2Vz&1pNrY-5CWTQJ(!NI;6VknQc%s;Wtgv~{bv)cc%#V2!ey#{PfnHuC`f9p`brmS%_A~9E~w{aq5yn*<`!#$F$J>(({t20ylk* z0+(z-sdXT`!czpYs{R@jI=TOZyExk*l3q}_d+d83BNrVoXLUIe?3iQbjivTrYKo%z znSTS^U}s(H17h3Jyew}k4o;~jOMaj1P35N()_7DgoIoApcq#6P{v<`t`rpCQtK!BX zB-pk#VxyV&cj9>|DdUA3!}7&t5lwV*%}KQ*-!@~pW@fGuuhrMq*0z8i#lvlVFr`QR z$ScmJ=d6 z4`}eqnXx4LBr8&l9>mI&+H*fnwG+YKR-K4(>@x!%D5J^2&!AH;@q@pqu6c*brB}|= z?l^E6i?9lK9NN>D$9I@gj}N5IRFZ>`_IkJoCT;$P2=N0P|F=Nk{RFydZP&*LipjCzp1sZ%kzC$(c#Vv*Yb2(*YclDq}4X?#U?RrNT8^lQI^g&B*y(-nG)?Mzwf#ZwIV#jTGSCZ z%Z^J-9Sz*)9@o@p^8u+Wv*j`%lSWFJtf`Kxi&b}v<~Q3QZSPfY*xoCQTD8rIbPZ3!MM@!%0XQ^+Qi4KM)f}%SP_(0w=#d@bqfd5p?E(fL~KoFD`NQanlnu}W|1Ms*-)Y8^A*WWeG z>q(xUD==kK8IO;Q8f4fRy$R!eQcAE$(#3iDDBF?xMi3{}@R!n_z|kr%F3!XB=dC|I z=9(bNb~tLewxnwTtKWIW!>rqtQ>ugXmDt_-UHvA{vBXA6fI=7cDk;3Cje+@_MPl*p zcvv`{7(QX7Tpzgl7g8blLJGEYIQ!&w`Kc6I?VEP4k7ymT?|aZ;7@j7ZfGykSNpx`L zVdvInAiA;~$}-SOl75>2VaI*$`#l`SgukPxPJ=B_TBmT2D;O^!Zm{x972$W-h(;D- zWF|0zNbMi;>~@sl=GS-m+y5+N^ydR;FpRb7jUaL)?X?!U$+SP}Q*mG=c?~!lt7-id zur*;}m!xBY5mEP-s!od-8$F66pqteS@`M%BQIs~P z~D+SLRNykVK{W%%Z z-oAX%KKeIBPR(`{YLZI*7OFsJ85EhoaQuO_nvcw0|3m=jaVR}jbO zpa+jwnn-l4Yfe#necAer*$tJhA${Zli`d(dL#dGt`cVExQg5P!vcC1@R zZ+9ymwpQE&uG6)zu7vwgVSKI@(QB5lSEuArDdOP%gG%#h4TmM;Z z3IEVjdmnYp6&WOS&uW_4)60zv*WxzH_ftU zdM3ulvjae>O*cdEH}U-O1Ni{*{K_+j!#b=vC~3Ia~it8F6_ zU%9VVJ{DLv8Ua7CSQoHj|519$(yt`(BNX2k#|aO=-;%w12ma}vck06@9hySfSvPX@ z3l0_Za0dXNB_|FHv0kwAh(gqu6=dIG9glbHmgBLpWDhtsj0KXA=TcOOaZj8*PJOf3 z1fmbSghTJnB|#Xm%q$h7Hv@h~`m=MzbM>M&Nw)@xJm>UOT@Azj+@AiV{49RLd zOpsOnRD-nate8x=9zK%VH_;(`S4~b3earUQ3cl)m$;#DMLf@DZw+mSg_b`bd1n)NRp#g>SYn!BdGcaI_d*#{Ew}Em`8tJBpSpX6z0^H+h~uIFcpNe!cMAY2HL_`AyJ zW)x;17vVnX@UF@5$J-v9^qzS2S#ey27xj9-D3}!pPr%1 zlvUhG0zIAfWbaZ|-m0rZ82SMLkBGW15oXYHbHUEtE&FVQjjwNH^NI4qqVzLX4%Gj7 zA@~j$O|(mm{R{48KHsQK`7AlQan|;*oh&s-{kElCIW7rU6Aey$wcI&B$6Ug`w>w^% zRbWJ5<>N=v<8pqgEp!Sjf2ZJ|Rn2oZbIyI+9y_}3 zi7nw%>=HrGB*5rnnYt}WuNiXI-?4ANURH}zJCfIW0v#3Zg|!uc&(H&6Hl7car3a6# z!?o=4TNTqGnKUy8NhSx^u^?G9T>_vl2kduPxyzkB^?$|i-@kY+o4o+i3VZw8^?Acx=l=N{U2O|@EJ?x{dnkD~B8GC-^b#4-m56I1i`K`-mGxKpy`?lx) zV!^63BU?-k|0RI>3W<94H?NLZZc@~V(rvdJt0ebv5pBc<_Rsg2yV~2MHK&zM-7%=! zM}Zl67wznIh)DOz8YpyAHTQ>9qNN*iRy$=GaIqQ~aF=l~zlXu!`jit-*v1=}v)5eMULH*&wM+ce4SI)VTSOllU)(>i%ySeW3p<+L z&n-N`H&xN3$nykW-rfec|2X+@=9OYEybQ#UR-lV)iECxAT1!s#l=k%4|lQAJF+)|`1*<++z*&53|3})klb2FyYxN+@jTH`ZU2+KJ=;Rm zFSbXNs%Gvs9?9HN(BE^@Kl02V`kFfp*vX)g>%!XQ&dl6~a*o%XU+y&vZc~BeG8to`(`EVM1}vaQFNnReFPIVXP5R=7$M zqK&d%y0mc1M?Za3A+{Z8<*fKKyrrf=oe=-Z8pjnMagm9eg8KDRBhnFvR?-Z6gjQ5P z(uWF7rRB@-b^9y~Z9zQvIIibF{d5gXIKS(_9FaAB!NLcZ*I$oT6-qm9I)fop4#h70 zk04X`no5dFS|(N--+6Q`_b}I%pTRLmd=LDqmNA?&l7_n@oJmrJV;d(ww(`%L%54^@ z)%wW@UpFq?+9BIRQ_2Akm$2>k-aonkpHfH>s$7L^3|*va^p{qg$bLtm`)A&>$1FHS zTG}#{K{i&AIK41*=4sXmywPKt9h&zBD6m*b8;7o0xVLg@xSUebOW%S(&Vxfe5;^p zR-Ru;QDUSIA8gEusH?KMB~lRw?ecFiPi|gte~x~;v;+wilw1&KX=^oP&6tO~V62u8 z0iht}8~(h!(HV*?h5i@f0gjztgtui$s$#oN1Acs8k)ZGyCHV~{WBLs9Eos%(dN;2) zn4)BF@802I#Y^EU2p^W1o`A75vV1`VBmgYzxMGEcmJR;AA}Na579bT-%BrVhG^kGr za^AR6Gj~sU{DS3T(Kq;VhTLKv-3PtH77>>m3V!+;3=3L?*ugmHAB` zpmTgxcb(P+3r^2)Th-z-Y_8W{&Ag3C@5ayc_5b>X>g?jeU;p@9X%00Rv8D0QFS7R? zAXT`2g!?{%=Cb*kP@MAca?v*cy$9Q63oYMqzGLrxyTp2zOuhT(55ueyP#rtB1IfY# zK~JoAQ1}|p^suQ9yYo_-$=}DmKIFJq*z~&kH;@-y|9o}V5GIM^biY~4F@a+H795;p zh2*TYCEdNUig$JMh<*4<8ZJ~7J{-ZrSDvgxG@9YAD!`fqf4)^~1p01a9HaV4R>HFg zDVz-EiNE7B>GS|C)t@&`@0V??Z+M41+>$hX2(Z2J|a zTl;VB6IPrKcoCvKMB(;`>UN?aVPY}$T@JLTz}z2xlYtt~yVAgotp%4&35)1P(15p#;NzpoE z?+Cf_)<-+QkjG}H6}W*xq1E|CNAvzw0DEIHSA3|j?V_j~Iwk{Vktje-N=JgXC8*){ zJ1ROfz#i~H$zY8G8vLq!bo;3^pMRW(V>8m4E!o^iE|IlpCiXhy#ptoll(eOoi5bia z<7w(Er&D-yueQm9?{!vX$kCk~(=?8h0?+$7ONU1uMW?m2*IRF&&DfUU)po`VJbG{i zDTko7zs}xM>~6* zZT_|k?c^a%?{?8k$5v_j3(J8)oXkZVkEciU&nP!v(jRM@G`llOj}pzos>`@b#I9_h zL&i|_H2~sGPwT?rTC&sY1VLD@uSOe1rg4>Ri{%UWuU7DQi1zZeLXHmUWxk#*W#O_iwBD)hda|bHEVD+VbJ)q<*fA5+=Uf>(C3h&axw$>4YCi zg~xI@AVbt^IXml+t^QGbuA`TCXQlx!x9b1n`Jnd~Zp&vyeu?Wr$v{;4=Gm-};J>I< zz)E5$DE>dzez^Pl`+;hYo(-#xOH5g?O{2C-M1LcArE+dYqH5GL6yw9IIWW#Pee)Z1En1+k(Se z3sffktwi$LC3Z-v@l}6mo%mi2Q(jw<5fCi&#Te( z*!OyH5^;~^jnguuqG>Qd>*s)|c*RC6nW&ZSVWe|YGO1)f=($n*3zrjz zzkNEt`#qFR9D+@I_;^t<`IL^F59@g%;q2n<>N z192eu_J3A!L0!J*va>;fw{CbJJhHCx&7Yi#wTw7n3JC6*UE=Hva<$S4awJP0NaUTi z{7PT+*~9!`FrY^9;Khp4e88r8CBop>;wM6-tH902KR=~pOIY61Yo8gY$qp6Y)YAtJ zXusv_O}#fp`VwrMS$VR0olE@M$@&qy%ELyqEJJqFp|WlO5JZ@Rfes(QlNr_i_k%;- zXvnp%7hqaoZEXf4`)8pzgZ0-ee^*G2NMY!<6Zo7%WM*b9hBN>E#(*K8^ZdJf?jxxO zi(lVSTuC#0>3OC+*?0hC@b89X<*g4$aYZpijl_)1)4q;2n z+>-sXh5y_EB>zc8Hejfhc$$OSApNoA0O!e-7M?C4CC;X*$2Z^_5 z^=IO@z2JZI3Kb!W>4E=e0d%c9B*G&@{v(3iVnq*Oo!s`g4_5l${7GX#zlnw)C#8-( zeE#7|V53KX*ao3IcLs~}iA3r-7i4j>-Q-~zV3&19F!2|9hy|FlMxJ?{*z5Dh zG|gdCV{U=o{9z}SyL4z*Z?6|v2?davNdyHP-4pdGvANxJljo;9H+AIVy-NT29(*dD zhamZF&Ua$iN~t}PxiGukS7+&eE1wmjFqm5{VilQ`DY2i^wWP3|9^l$9C1KV-|y6%9qfjxMx{?M)zL*AlWbTq;fX!Y(lFr zyK+nO6oaDH6wTLh*k4IvCxqvgX=!^!I+|gN#;d^e>OP`XF>(xbDEb|@9a(fl!N%W* zioHsdzESwuZ=VS>@~>fF;w$E1A0^Pnb)Pq`Y=|c>bcqK%Kj1<;WjEQlH{kD}fq3<& zSjeAJ%(ihMzm13bGuX@h&k&+plZBa*cX}@d&{02};{4o3k8AVd?OB6s!kHZ{8q9J!P=ZrcR&gJ_GQM1I z2c?+NnDJ8T>~Q>z!G#VLjJdmOWG~!tkGQLP^1PRlEGYwTyPn#OM&X8tf5%-=_*qc$ zq75uapt^YYbBBkGE_YZlF7?Vm)ij~s?4>5mwfXgBA@VtSbAuA1mQbP>v@^O;#3i{7 z(>|R^?wPT4m_?O~=mj_V3$He{NzEV>Ga%@!fITMlXZ?k^CO? z3Bi|WtU3GRpExOSL&~^6-C}f|NtNz%Q@#zNg}}OO`p&KGDu-e*MuenbEMfU`B*^x- zD}LF7i-dLF=o^)OyLdBg2xwN46Gp2r3@sK@)HSdw9)<|J{Cn$cy`B^0!ke3h6Nen< z+7=x9wbZ&L!jQDgryx?J&hM1UgTz`edA>6|)s0$@>7oEYpBWBOI}XmkAXo1>??D^K z#8!TbNiEEeVaQTFE-k`w=O`eo{%?ZO>fh9*p~JGPpp3&2^~PlTcE;uE=7?}92eaBZ z6!16$LM(-9dQMJGE?3RaLeNp7QcyZJFP`6T6TlH^*Hi88oD%3|`n)X6Y~UAI2Uo(L z4}JiGXX62h!ar=vPqU5|qijpZDV)3a0nSzwxE@ho9nR4keV7$M?)Ldhn(dd&-TMUh z{fj>)tGW?=|8_kuQp*g}0(|O&LA1knObi2tlxs_2iQ;KDW$gF%ogc8IzQtAoiL>kp zA#}{u^Yz&4Lu824umj)wu@5Hw-X*HEj73*@Jx~atHCszPF5PTDy1hc^wwWr-{%mXP z%JsADjl`;aqD4f%C_jrRAlfLN4}&^jzhUXQ2&{yJ%Ah?+!KD=~cRC%3i&OePVI zkxj?WM&+ZT?5Wp^}&l(hJu!}PkAN1~gEENRtv{zTKi zJvdP+ppV8-6*H+@bdc3ZB`O`%Xd&|!(1d=Q#S|r~Z1QB*AW2H)uC^x>%ZJ_tf z82iyEzw_o;U_D8-KuNK5il>u{8V@9Wa%h>ZALgyG8jz`=Ea!3mi{#w+emO_spuk2c6Rt&24P{&M zkN|-rH&7dWXXC*opz2IcF$H8{|83Rn#}o?k>c%rEkKN6Ku?8$T7a^TXEAwLbp?%pm z0u<-XMWhW&yrbOgZeoIh?mRI-IJ3p$LR|KMR(e;7$J`-jN%bR~^m41d>qVn5`lpt8Rbfw2G9bHAdc$Zd-z=AnC zIsz29*Dp(wDZgvqNAa+6o<^UdYD(M~2!&*3Gqg|uFxn))WAJt)1X)!b2;SbaMTd0e z?E|a>55+i&2FfRsT64Ez-nzgKO-Mhn|C#}hf^WZZ5;y@o$j0WTG%>m*uw5r_@gaM< zzubm}3c2qFJRTS;m-ptgj}N=OH+OG9{bg$lLKF$`tCs6Wf-YcO-VRT{2#AaOYEv5c zKXYyeVN{^bcX6ACmi5NNx#;92Z1|g{DYi&|u4EXwpjfqH6qAK0G3Y$r49)w#1x=F} z2bk8i?IZ#|qj`*hk&|7e{UnleM}NtUvn{GZ+)RVopHVSD zU--`CFvEi$|KTgwFhE8))cz)nia>F)=0||VZI{Ra!{-^N0_E3abGmZCF3_U^$Ta(3&Pw`cM#)`)!Sf8P;`n@1=RjjGGj@6FX?q-D7fb zoITL$#8#e9PP;VoA%#kEmBWWbWvx{Yvx{9%|u)JUUX7Q=FSJlc~N?DVJs_NCQ*&%CTQb;phMoDz!MLY zpz_q(PEYH4`m+FBPx@-wN^yN#WAhZ#@|aQXl^f%YJ;D>-uvO0_mx*ATMzMy9Z`#@&{0lVRnO zS9tP&sDlo{DBpfVEzMIBrlrOU$^gJVv>m`r_S4@ zo!vtr-E#ZEo6l`G?hu$7Adu-Y&(B)M(o0>)u*dIb?slJ5ZTS~@V(apkNQ|#y92OBFlxFV1!HFhy*H2?O zM_-ZwE(1@yNWP=4Y|B-a8Y}xr!sD|}(jjVrr&wySzUL&|-%k{Ptv6b@6 zKz`>q6wZY_yv%(M+~1Kh88YQhZa17A7PyNj^4g@f=E^2f=cxQJV}S7I^a-{sB+=tF^g-eDmq_Hh63^-w#h!$3$*x@oDap$fUcA8nirvEWhW_)~!B zZ}#h=3YC?8c<%oY6spWq7=)=4kO!xm56yFhW_rHUrgfM#eQKQdbBJ3e3T@*wT!oJ> zWJ;AW9yogU!P*9G5HkKkI0%you$nkvqz$lg#I0S};JlE(VlMir$Ey*HKEtDy<$15+ zD?M+PL4o4rI>JLn0OE!a4h``lf$`e9dC{b)_lob;$Z3MbS0~`gS(OaP z+h1y7Ex++nTr^f5KkUub&0<_QUrm%m^)`P&M3}7LePt==W-3al+`nD%hJ& zN)aHm-G*f>gmAUfRd(f2+TL=#Mv`1%%d_7P-ziDyV z52J4{9B-(%ZT?#7=b)A=u z=PU_XW24mz@xg0|B%)8LpzQ6P6nzb-&yKGRV3wkDo`w<0W#M~`j@ekB|P0= zzhs4bm~^~~#!`ceqHE>ANgb`yz=Gi_7sZX0DFMlKxC7&dr*XKz)ebS*wKIV_j}8|t z0w#S<6kaZQ2oe>FX`zadT6e2Cw^#=;^pv1J&T^JohpXHr4c>|%nb>c|SFG@0%4$s6 z=H~^TFZAq9o)^0rNGT{tM@U~P{J*kjP*oZo5Yk_2#NIn5U&T}@{Fu0+n(1DiKu`@Q z$n#{_S_mH8C7v^bOO0tIFosGK1XUZAj1vA9?cmj)Va@;oQFzQJXO~^|VwUeBtAL<~^)5XrMK*s&VD<)Ua;%1UZz zD6AyAm<2w;y+@(4>$?=>n2!p6=E3S`uaPp}NtPvBLp%mw@s%*y27R+(oyZsW%2MjMDn=PwcQ(T6FWJ|>w?#vMcCm+ib!00O&-hj&waBCRL`%N%ZG;++OAerF8Tr85 zkmZSM@jrUV4v?pU+bVURv0u}H=cv}A(FT7bsnvFh+ zrwHuLp3J&*mh`2Lo~=|(e(h5yg8_;wNC+jTjQ|D+$n1_Kf3UoS)!0M$!K)cE8zs37 zxL{e)_VroSi&|y3bv0h0+m}CFT^tn_>7;K&=G|xK2|}Zf*r}K7&4Xk!CE@bbzr&2f zl6n!y8Q7IlB}B(mMaWbxj9w2-c&=%JX>))jO|P5*Z%0=^)T;~F_i{_p4>1RT$SrXS z#?|V5{ONtpB)6bVGPVn7-q7ICNB;pwM~Olnb`gWFACIbPV4h#uWQt8cf8M*h0}h^D zpcI`uSG4f+a&x^9c=c(Y@c}{90GyBlE3&B$d(~xcjE8ZQvuqEd0i4r{RLxB^$VeGu z+Dq>4V}I$fGheMeX^LlV4BVJdBV*YZMgW^_d#vIC-=T)M&Y606{AdG~)SkfN*YR1x zbWA~2vP#h7wk?#Y;YN;M-p(?*GRmKh#vmm0S?FlZX&+h{x)*Ww1_NfI-)3e9*rJlD zmc-VMI`LdG6bB^PZrZWALN&n(wRRkBxKZS_bg~dmr|&i`M`_x64vK>38vL1|l%dGI z1tj0fK@Lvtdm4^W9L0!JvqK1#4Be?Oj_w`s?iU-dWyu6fUh{upJ|3El>1k-E{%OPs zWfo9e|Vnu6xykZpZJ0wVSrXsRlM?A=qu8 zzu@M@;8CNK@nEFXq6q0ZlsANOG*457AoHSy^)YPGQ+=}TI1JvdOkyW#$O13Z6jK#n zH?KPRVQx_s+hf|T!3v~@mlD{KY{>DHh77wiWcY{`BL0y-d%_+KGAz{=MWK>^QBeAV zYA0fA*5`NFH~uGMa03j|FtpO`)Hiy7b)vUXbVDqb$@8qL2e-jqc3$$9c~xcB(t2%M z_8FI)3h{uY_f!kxNjzshzX)10(m#r2Z&d)CTj_+w8*#$cVjxP8$P_uG`vqNdw!3RghC^ZMTHfyf!YSE$`zuHR<7 zys?S>U*?V;8pyF+@wF_=y-E}u^OJVYhC3-)UrEXf6;&@CS|jM^iY}#V9Jz4r?<3)| zZEbB=oZ9`~-$eVKFNE{*>#z2c#f1!~d`M-sfM?e~pPQzR-~9!7Hat+QbPM#{zs37p zb^rIbvc6sI;ZaJH+Xb$VU7v!Zd5J`a0DT@shdU8g5`m304LWi)7HS*reRs5^kZW+h?TSb~lb5xMccRyaaj#lkNg|v}O)Q4R zuaItSS(-EVICBuPHqkI{V$b<`oB=5h1U{6n7FxFyUGI1N`@tO*?h zt9T$OZih5pIB9w!WJsl6>_iEZHLUUug>oV%@#O+^d)tIo&Ba z1*ItnpMo|y@;SQZf{+gmrz91bi^Q%7I1xS}PTqK?pdnlLt8=k5G2LQHQ21v@B+a7b zty}{mJAoe`^~qB-m=UZDXj=%CrcR#-R5-nYWU z?RAkZM+6gGC)iHiICfwd%lA>V{$#82p%7!xlYIPQ&ACUXjXU4w+;SqcMFVIwFDbXr zN*G1tdr(3~>J>7JnM$bzVyFH)4MF;~3(;lpTHW#_9DFPgngriCSERBBl~e?V$fS$SUtNKxSJ(j}B>wVD!+Ri-2%5cDB$=ULP ztjF^Y(~>(?)pPp$0Cbj5mB0oBfUpBU0Gn!e3t`?Zs>|N8C?Y#6vQdb~2(Lq`Z+6Oq zZdsNM+>iI9GA+cTcjRxPZH`}-Ou1n+1UV*k5xbM>4-90=vmsH>J-)ZB-$Ho8w z)PsQM>gDd+wpsrs&`U1dzy3uBr@vE^Tvb$@XMvpaHF-|n*o1HTOY*!bb4+!|OlO0R z#zICA%0tnK47FYRQ1GExYNl;$Ogdjg!FMOivb4%4Wb(p$d5K~BNti;GC_%13bv|dy zpoGDIgg=sM8vPl(epsJkf&;ijR0_dBfM4iPc>Q1Lzx##kdKq%ew=E) zx21?%VbZ)rh2NIWS(kgAVvjHGtcK~78r5v%rH456;26qIhxAOhVIA+2UZNZX**E>` z!IkH<#D~NOl@`cz1FGvapN#H((!C>Vws}E6OAor~fq_%LNw%~|UO&KRce!04K^iqj z4SU?HJ4C8+|2tVBD?36T%vyjqTqrwE?Nu!2IM#dUg2zCI2q(=%8i@nN=FN^<>r`15KC3;AULd9V^6OGLs{ftkuf6bVgBGOgq-HR!< zPj#-1Ce`TQigZdnCphjYfW<3fzOv&@j>Vl;TlhQV<$XN6iG0|OFZoiSEDq%9^jWT+{yTLGoiOB5 z>mW-mLNw=}SBxNPPfM{#0)}*z>f*>g9%pRiH%b zC9OY`U7*|mw_2=bwNp=|ogGC#xG&W19aPiO1_Ca;)IyXXD&l^5q11+tPz3R^5+&%63!$F^;UK8#bfiG|We7(J4X%Fy} z3J4nP0UI^Q37Aa%sc#IZg#qr;oW6VNTfiRjZ^QHDh%jW63Am@h*su_Mvt9^7AXjsN z!lDTxpoyQs+kGw{WL1i@L1?Jn5hW1TqLI(3+!zS!0}l}4@N~t3bLWs7=5>VbkCMDe ziZ7U6RtxcMw1aH84MLAKQ%q_=STs?q22*O9TvMjS=R2{mvl;Q@(gi!PM+ONMUOKd6 zJV|-7SRpnt_wxodZr{ZWY^O!v>e3S4PMr>WUD98r{C(ryUxril)mspaF&U)0U zbCc$s<(YOQjY~5k8kr?)=x7r{$5psU+(tCMt4Iu)J0Z18x``^vpKd(M8ggfMq0*am z-gps2gimncp~2r5PA~EgGR}KCBsyriVbI53iN~}(^Rpq43KmmBhm zYY`fA^$>c0F~T7dqC5|gKyl=QCF6shIVC7QS>G)f}hx<4zAK zK&8OKXQH!dx(!{9Mo&*6@%1aeC1J>3WGu&}rs#_7cYXV8i&^y>t(Vv$Hn&1Cij|pU zyCAPtYUr2u)>Hkb9a(6i_zG7NQQi2t8<|n-ihoC72y&d|W`Kf&e>cVy_y6BUUraVhs^N?+s5X z6Hc9FUcP&yFL$>2)09M!^JIC7M5tAtLCA2t!9V=~J({4WIr$XozVY?BO!Cj{ggoKB zXhprbB~=C5{kguAj|XJH>t84#gNyRN*yhL!gaiH4VO#?y+ycNIi`vfT3xYGk>x2q%m*+>iZ}d^FxGqz)Q%n(A*pE99#5gW)2I~u^|Y<$cfJvXy12q zbV!(70+YPxo8Mncg&v>x8R=B9$}|O3mRrP%Vv`pHPUcvCQ0x1hpThEWvt}`TtljQ` zG#Od+r4+!5N^iT$?}~F)aed6Em-vRE)u1s4pRYPK4L7hu@~M;;?r3ffORHoNp}Pz6 z=K#)H7ibT&8883d5Pa5mcJuIwTTD-vxTO5@ZPf{Zilp%NIL?`hsPAD9FaTWvv6P18 zy5&#I%Ikfz>j^+&FCzz#<{?g`M{h>THdHrmwu6s*)7w6)c7;Miy z-5W>*KOrkZC7V z!x&gTR8$ri4h6ps3V>yD?6rQ^d-&{iJvq9Fw(?a3bexLn-_Q4AemCC;#E(Gih8UxL zFd9EBS%WxaHL!B05~tgAc7!^b1ury_MbNFp#H&#ESiWR4ZU0hiwISHe_4t-MQ7DYB zO1#Jty^J@bzcm_?5eeRtRCgbkrriVuUYjTQxQ!1V#;4^;@h~c%8*fCAFJRJnVHpu0 z&dm<>A@BcaNWJ*f zPGli4LivPp*R4f?_%vlRf8#*|xhuA!1vPU>YLhrBSTGxK2N_%3mT0{W<``@ITHJ0I zOB;`?bWvV;{!Ip+h($i);L6!+EQ3pnO2<(0=s^w8L~J12VQex#)jBW+Yt)B=!azJ) z{ZXp=?VOB`(FN`1XbS(B1!a1^v{5WhTub-)%&w*V-WaK}| z@W_a)8@hSI?hp2Uw6?+oWSxTO_)rdGs4-1qk6OCz5zfD?RGO|d62NMgejr($b1 znJAxaJWBIK#xz@Zn50P|)9{7PY91kq$0sHZwQ5J|P=w|6nG{C1_SZPEPV6fgT$vSg zu&CTQiEw#CS#jbCRrSF2xEG6yA=fTl{(m~|-?mhq#TRvWOBxdGDfV}A@*+jg@oc3M z_m>ipvI_Z1qDc69zF0n`PE5${F;m=FUoZ6vK|?l zR54{eWLKjNE}cxptx9gF#e2{42a)tQp(-nMcUR2Hi0P%D<{3t7BbZ){O;OVS2{voU zfp05|CD-pN_fT8dqm^s8bwjI{I1G4eVa`4d4Y) z+H{CmN{YOY*`F@C%kLjImAh;?#j^&Lpm3T75oaSCz8;5-0B6QP_ad0 z{J}`zfQ;QWWo!etxNwF~nVu~s=r)_8>~S!pAA$y(hC)~1I7?E7?ZMZg33cTgH@uY9 z&N>pqcz7tjsy7a4~cBHTkPapIc=9Ot;tNCxL$b={eA&NH*@<9Jcw4`il&kOEBIY}O`jp+ zTl`>w%3$DUWhgY z-#A)0*PS_G3RaLsWE}rzg_|0MvstYf?4EPufN%lodR#4|f40+Y0qhhdf-vc? zQY;BN_<(r^RaheFU;(p6B9`U70YW7r8n5J(OyECU9*07&a$lp@_t+l_BXUlWmL&&; zmM;nK;bZA9c?gBcIF7E#R zvGu3_#&IQ%MpumFSy+lqfjXEm85X$`%;Qy9Gn(=_7@B2%x>-OL6qtladabrNV+}?h zERBnCRXhV<0NfX{F7b?tuJx~21cRy30-BM)HTh2){1{ttfA;a5cPHA=k?S)8!#D1r z=ks>p-ubZq;oViFGXSqb954n|)u4nvEf!v#w{J(kmNTLN`UoHqWmTuOqLT14oe$I( z0u29wL#y3&``;4|xU~MWJHqAz;W;2ou?MJ5H7I^Qo;4FP{+2+cafp~0uGJQM;zP-g zeZASYkZUsLwjSMBvSSv=3?cD*ml7~H?|Bo1<)If%*^h|rtXgqW6)NJW(2x-)TGHp> z>tSCEEF)dC)e))tx}X)N9p`<~;BLGPI7qIvKXWrn_-|BMDX#eE?`efkYrda8ydJ5> z8(q@dM=ZRKhjD(rs9qXu;%Pa_e&@^oG#0hJWa#yFll~|jFiXxL>|J4r$wRuTLz`Qx z4vP5QN%#0PRY$S7+>iof1yqv($t2Z%oP9;}w3z3)nPo^3F1+8t?;@HEWd>OR{PSIC zSQyoakm*V0lL8akCZrczlIv0Uwnk>BEZXe7JozlneWG0mGo$c^S*b-{qMwM|N$kZa znx*ck)3-l|VVhg!#UqGb8bC8r3I z_KZT!oS|%UG4fKeP$USR%l3!K69<)mKZikLYBsB`FE#`^`oU^VW{X7wCY?@PgkAQik_$ zIa9^|3B>XoZsN$!)G2d!#*T_zwS<5^RpZ7fw-C*Awj1AwxGyI6RHjeA5W@6%9o)PZ z#(y3IGtP%imW2HY1Ym;Y?X6Y>0^*{PA#X6>P5Y7kVd-y{Dr{-)!HJlAE8(CxyMUy< z2w|5wMq|6)&z8NbQ3!Toh5LJZ)JR0W-Q+0!$!YXq$LipKqtCNOp&o3-=p3fC4eOWW z$@*>sl(CAHfl7sm1;rb{#JoWPO$ay^e}74$d40VXH|t#o{AWBo9KqZB>FQ#T5AP51 z#-^tGfBrbMurH8Qp9UP1sxP}YuSzS$0>{`-@5Fzu$bWbafFF8&IGx*2F*`E@1JI}T zKfYWYT>@Qnb~k??3Ojc}5DgQS-=Vt`!sjzAW((X84peXn90eifIB`(HGk(F^;h|1b z7!ZiX)iijqyt?~Pp*RDDeeo!nqIaBYrm9Tf!%WcZkqs`Nla`uX5_onTOUuchPqA>X z?1(4P(kB4+8zmv~Ulx%O1m?I_m$>l|(1YNdCabXF3x*+nmQ|#HFBW<2^Jt;6dPKE$ z!9oT$&aF$h7?YeKiiP=bu|h1JSyqvt>_~jIu=Z`C--l^fr2URtEGwPmz)*8CDf?GD z`H!cV@>zJlyxe2lwmzm)){=cq?RE!q+z0(NKiKhe1)QDOgbR_$)LNc?;Zci3p(}no zlCrh`orF;T$OCW@-;#yk4@w(1_~JPcXjYC}L5zbIj+jZx3UO{o6r&0D@>zemB9EQ) z;67oM+zjJFIfBDrpa}-mj{`I2Ipi=E_{3=fCyZ%fZPr+Das@bvB}itZh%02@8baGC8Se zrrU@Lk*F(tS?rz!Vp2OQ9hT}UPU_q~5flN6Z)3YGd4YtOKZ@+)c9!{gaT=vHoIr#( zr9;7C(RzGtJ$2T{f#f6xb2p+Z>Z}rA3p~I1#};Oe7#RqLx)Zh)YI4}CzOsHT1aVA5f5b^xBg>$l#%a8 z?UGtwXPG#wbM4KtVI7w&66QeN>`6)(&DoLV`6ZJW<}VT)kpp%hPkj*MA5P+dG+|Yc z)hSYFBI>|O=7@}}PtW$@^Y#F=ZF=BhmD`9P7lfs7$JJ5>73Ij}&}%TxFMpVdd$9%o zVbV1nj`zbZt2DzL^Pgzwchhmm)%i&!r2Fqb2gpwN8hrpEaf)6fzTc zCe64V;HVPZQ&~{Onh0s)bT!dl_OeY0O9vwe>#)4#?1x5qqzO5}=v z6jyJ)xaq{VBYX1mI*Q-=DDf+n`d7vc^GTAk?~=`x{$DoMWhff*zH7|bn7QdCNj1@y z9W~F2MP}f9|J+NWsat{Z_VB9ND27yEAcZ&~dl_YyhX1)XIOh8_q*8tqT~(l=w1nzT zJn8-%$g&FNCpD8FQ6kMq(WnL;`!$Vmua9jlzGm-0@IfTlO{@w2e}F*5iT0TL`w!E% zh`Uwpe_j|ZB{B@~fTlPZhIx)n0%T%BaV7cW9A-AZQuSIw=XsFGZ z7Hl}C`{$^;-&WtLT;?j;@e76)$hU=A?lKkL2F+HwO?3~d(w!{KlCH~CYAX@b*fhCe zMm0vQO`6$DlO|+PU$-6Z7GZDc((EfO6eEg0xk({O^?MM|FG3@-AQbIj=vIgyVf zo1=U#a_BvFNa6+T@C40t_4V~vzrL83Frolg56fOrs3|G0i>viZho948R~D^nl3Bo? z!P~!?(((tf2vmN0mnRGp+c}=Zdla9gU|K_JHV1<&=+x4m3PJ}T*+mjG+4tg!&!x;P z9J_U}Xw95OqA$%7rp^+=fY-A{r}5rw=v#BHkbj06&~(9-gD-FYh~kChvP(wwlo#hE zHJ`v~7F}#OMYGkfFr3EuJL)ZdB#jE1oh0xs`0}ijdgf!D_1+z#%&er{2sxu# zM@1&+FPX8DCCd*kWh1h9OOxSXWVYi5m3hZ@+w6lkEF9p@m7kbLxQoLsND%4aW~W~` z;~=jlH-zATuz-C?Q)mI_dGy0XoreBenMo%^(?smN!Fh4 zrNh-^djocd_N7M}Exx5pgUf49xr-5YUx4?u_oVGe5WD~p()pSYrg-j?{`%hkMgm|O zdI{5)AgXjeQ-B~1K$ZZhiyZ9HM` zk!hU`xT9Te?P;@_<~E=nLsN#!6~(Ivt_fn5Ls@F$5uYc*ah!M%8ZnI4 zQ|HA;1+cKs+L%ix%u}WQ-ok{TC;63q)i9cCnWRHhK7dAAY*OFNV@3>SlJ7)@|8cH& z97zzgcNM!=uWV4(#+oKgf*qyj!I_(YOO64uD5EHk+c1nz>rT|h6B8+`Zd?~UcnS$l z4mNpS{+sJU1zifM_0G-n7N0Ff+(5Ji7{7a?Aa{79pv?q|JZ=;!Sgws*^4f)}ns8HF zG!5jW&Aw>70f$xzllJ3G77v?93g$MK}38mMN-Mmrq^4q}V#btSZ{b)`s(YHjq{K4nic>o1yb zw=vq{LqTs6v)ESp1^kCMTOb1QaF6KI_Ith{x!f`>y@_GD9y>iG0}nww`Qe$Njc3%a zkFRm_Ot%KI-=j)y8TB+IVS~5*L(jq)CW&B`!t61$KSXS<_TAMZf#B}xvKZrOVFKEP z1&T}OIeOK3Zwszu0I-soPsd?>gC_v1xgcTHQ+8@6CBsQiEQ=_|eXO=(H@ zVdC`Sai?s#YXJwJxbTp9KVriA_k@KVv1twhC9Uw!ej3tDuy*A1P)mj!Ly!Rt0(=3o zziQB*(z>I@ZsJh~V5#etOaI|v065^o!!?bIi)-Vm%Rd~-!9;oyO-&67At50J+^*mC zgs0Oo>AzvhYI^0vpKss)g@gYKIL`^0`M0R6u>be__S;>1M|VFM{t5_X>HIJB3Ib5hry4cA|sRk#>gN}`x^shjR1 zTEB?6=J@6HUsHIa(*jBM5)FQkRd@EH_z7_?ia(cJ;;qD%y%0=J?Y1&}RJO#HZ8LS=&AdOrfY)>2&l>SV2kWy^D0^%45>&ih28MvW{9>%%AAJ6kvJ=mVm3ldA zs06-Z%|aOF3N7wLbNScxbVsY?r~^NgRuN(0$OM57ul?#24U-SolBFP$E=sXKgL@+^ zoqkyP=6hdI&pJ-gkHPX1&Q@YG0&)@3P1sZ2BTOUbct=8aM&)1z|LhDH0aTjh^=DzH z_CVlXGptLUkPhX>gj?wPm!f7#TkvJu9b>@j-az=w?_jY;<&38^P8r zWXLPe6&GW5)hSw*S6Z;Jvmvcs+MvU`GyD4-Gx|qVmLp|ju@JZ)L~rL{@o;4Zt{$W9 zXM6eNHgC|~=4O5_hdz+T7wHu7)ZF(y-C-vk71j!98H^58+&5LyFC9#dGH9$*UvKN^ z34&vT%BvSp&vS(M>{5lB zRJ29i6q8*UJ_xNd2kmLm4vd3 zGSyUz@GR=6$$A)Rr$1@8HrQy)1^`ml+6wS4qFy7LW%M6YjK+U=+Ev8fumoIHq7{)vzi=+7 zz+3I}GVq9&9)-a@_s%Qk8j(QVF++n13sLCvcIrdR&4 zfLa$Qn}O&Tp%MOJ!nJ`ZfO$7ieAos%@|dzU7_(h3nuZKF+s;BkodTq_yLQvviFAf4 ztJIZ(RLU6>ErN)8oJ1@qn@{%Kq?;-&jw~$gii7ql=Sb=1(E2}um*RY{@8RFP$-=6IyaeQQju8*Y*;i zloak%mWrsET@$hoUD%I@E;JFrY(P{`BZvs^KwPFjA$n5@%DWc~lo z0u-AkaJn%K@ZgxPNfDSkQOFY)Z8RFU{*l&R@y9X7D?H1tB=|W-RHuE}2c?qsIS&7qXsPM&Am32|LBS zY^IKahfCM^CZZx`!8} zk`KmHcQJ3QB9KmnjR!_BQb^H2qkz}MMMr(fQbsj4AKxMo>ai&wrH(2?5aPdk94)39LM7BX5 zeeiD=#zZz;3vfn)8gl&3Utd4Gg#m-mN7^3*pbY(~qq(lJ*YkW#N3InYU$dz_{{F`W z!Y%%Xt6f;M4cc!t%t3!|i9?=F7=R_n&fgap00%fSa)R9Va^^YJOGV=G*R9htaCKn@FgM# zOM#s?ny)5;yG+Y`P2xvJwjUzmh zy6UM=KTSDWYv{s5eVW4RpTg%)+CN0WR^r98Got8pI;ONp;%ES6WfbXacDMSSNdX*Z?SGAYt@NA-CNrJ=5iO|5yM3(eEE~Y4>bgBuM!jBOC^g zq)p`O+FFR=zpi^)L9XPBEF~HjPyw4l-pI%kxgD^`!#G(y?*Vd2C!3N?J}^mJ>xzHa zVt$w)wVeCO%krU~82{HnlQb^%ml7kex4!@xfUXy92S}ZOMCtYUKGjAdiV5$C3|JdM zEE*-Y?;n6ys+#~AWt5u^A(Uz8D=z>;Ky_pldw=l^dT~Q{4tTln?H?OlXHQEscgt%a zSUQ$ibwfwJS#lMFV`A2~;5^3jo|q>`Jdc3#M5-iz0a>prLv&1cN0=`JOk@)_xcqX5rvd^bFAmKhe+fu?}&{sb`^&A>}!~S zx1OX$~+Mn;;y=g=$8vNkgCSiIAC2A3hJrUvFqnrAc)i+dl^o$s)J z+8(58(K6rk%_cb(juGX*>_MLIY5SZ#&DdvSU{vA11tm4Y8+h>$OdcGud8B-t7NqJJ znlJXW1lu?_;Zhd_PjH3@pZEtMJq%OEs!$TyAf@zN2^Y<*oA4B!(8Y z71|%D-JhwnRxyuPYDalMFqb!nHfeA~jk6(PQoUc;xd(?{w>*>Q0!SE8BrTa{dOkV! zP|dY!L}FM>RcD(sW-H{xl2zY8IAsW_t+2Adg(iHw3I76$1HRiqk(XON!@ov|FI-8z z#$cn$hW2-Np}}{@a&_c2H4?rnLrAew9vqBl!Kj)FjCGWy&#u73c)ET50dT6aW46iamJ_Qc#}?-Y1jvJNiD$zukjTMJ$_vYrTI~JG{Co z_|%7rMB3S^L9$h~acWeck@?cBY%I$F1&eq@p!aQH9mB$SgvwYVH8D!)_9b~9`uD3| zC3@2(uMEUI03UDbS|*Y+dh8XJSI{!t{A?rVaBdK*f6)-{qLXv}e>9y1SCwtocIoc! zknZm8P)b6&OF-%Fu1zB?-Q6JF-5?;%-jp=b{ayDnzV{zE9Ak5>bFJf;Q-6H4a;qkS zE2guzx3gegv`NV;nR3_H(dzw`*NSKmdOxoTh)qKp+(Yc7dq7f7vH2r0J+r=}&(UZ# zWmDX&>!j)GCmR90YEfeQte2Ehb=NBxsuWNi=TU%e7hd09)b|c89G0Wpsrakb-x(wh zePg~uEkUP<=_fP}lb*0;nmb=GiiBt~#jx6K7foy)#^db~16_gOoVCYJw)MU75&`$qko zaT)iLwlJk;&KdkSj_K3DUoTpymUNr_8gpPezfW5r{)yl9*Q7!%p}{|~nY{5FYrDAX zjyw1LY789cB%^;%;$lKJ41bZYwzb{(hvT9Gp|m7qYiXG##4)$Io2((JZ4cWqt+SyW zM1x?P1c{omwyB@Zt4fK~0e5LQeW7UwLr>ADd#h6PgntgE2{eihp1pyiM|YNBBWH?U zy8_t{RPJa(?J0ZnklBughdx1k&0j>}6h=$!DV!tpk2le#QkheP0wUFYHY59Qwfd`6 zQKG{_3(Jy{Qx4Dxqcjwhl!LmwtswKAalUJK)eW{$^U{iw!h1YND2n;0npx4czZ$Lm zaT4LFwv~4Jt0RTAA8pz4jaH-Jg-D~63z_+Y?_7@bIT^L!6^v?kA!@(N`-_p>NM_$} zFQzFmiV8yp>c`6rSz>e1gP)Hv)xIeWRn#~$B2#b3X(R>Ka~+NLUrh&p;V^-$NW26A zzr20{j@&{K@txso23zIeXR$a{N(zsoXQqIy?O1K2!V0*`-v}YV_CQQ>f~3ki)LkXg zWWDv$5T#!N#qeyT#GDd;O(9l1%n5o)4;Pbq z2pLP)WRRozSav7o5gwlmd@*Z7@0Lu}Ut(J0OCqnOl$zr3R4pRkHZ)4*ol%pN^+;K5 z=pCyC5bGb($CW=9_dKKcjx0wj72BZoG{H$o{(NiAdgOYw7 z$;2a3k`>tfll5?os!FjK=2kfV$ixrf|HSOlo#!5&Vj3?jr|vQE3mzBM`M82~#xR}g z1s6YH9f|9Htc5FWpgY-oDdO)2PEdLg-@Y}2RL$ox%%ANxQ3z)vSO$r(*3__=Qv-6uJhl!0q9A9tyz z<*llwha&@qoBV*t3XQ*{?QLiTJ&nmqtU+RL?5&wQ>*g#^F z-Y_K%P1y@s`c!v%nCO+F*e|d6?NRty`H&DH#0TNu8g(vFhLw-o)2N0G^W6% zslB%sv+IjQd@(tNl5WI1+L{LZ%K_O)(wi$OxP^4(YyA29`jqdFk-J6kzhPCTpWE&5 z?duL*+*=vYAU(Wc-U)ioID*biXdg0lJTh(Vb|k0KOmg1lTT+$iR)*97Ed--&3o<_W zn$l2?Cc_(~IFm8wf7&}=A`0cgl8P~kj!^$2HTFK<)-`-3;Vf$K?TRE3Hp~%taC=7j zCV%sag+*^dTer+tyUdd69t`~0{N&+77YGJT0bWK3vv@1ypBwZ~kdK8iA?i`d;b)eT zIbN02DBVxZR5PJG;Vu}oRx*1H>}ge7cVOz@{eT)+coIH8=6=eg3F9R}J5P zh^qB7QxH0Q^=BFo^h9F>7s_mIH{e9$xcdKG138WGmMJ3Zd&YR#1c}af5~hkBQy1l6 zP%UA4Z{EjGMXs<({XXZ; zy@;++djMNR1CRICsrEy|Dvn2EPbxgVuQAq_H1~{~VKn%_g23dbW_NCX5-=I+^+rxBzZu^Iutn`?@TWN-;`&iq?$TD`e+ z+3(fRFMP)xz#>HL5~Fv3Q{8szbr80;*AIETAi(jugS1c5onDUfUpf*JBB2W+3QvuepJum|qfOQN>^H(vE$`3zcEd$7|F zVdXxN@un4RiM4ICs)NW|uPY=f7s;urQ;*=2(de==97Kx_(1gSDz!PeCrfNBH1LBKI zj;B0gEL@S0LQW&?r^dFuzQ}0CI{MZDBk(+ft-D=h`i02VY$oCRq?GtahtQnCT%TkM z9m&HLE)#*bXV~`WeTO*FakmB3_Uo-^}0^)e;uvT7$VQ)e{K3kphQ40Fpi zAb|nPiObp$hkWSy%IshzWW@9>baUxy?$=;xkQL&ohlOM)2qLJgVa_YO>oR=R+~C#s zERRZU+9H)eZRi{LfJ9v{Br%vR;OGQYUOKA#YWmNwDExilEJ)s8dS7W|Z)x5D469@n zbhXC-4U@)7Ni6b8Js_KJv+cy-BpH>7-Ryz2!I5JcbN!-R9(8e!S{~HV8MhR9;B;OC z5u9j5*`;6plZ`J&Ox~z9qzUIw?f?sX&r#CR6vqVSMUbeAEk}S&M)U0r`*C4Kq(JE<2-yLMn@4H+78XuK5J|5e6{}u{5vs9o~WQulTPP($P(KUnGfND zNNR&l2RbHV1sz=pBru~5lC(M3)K_DRn9v4;q;d4SjOzL`(BXC0TN!^2hTW4yHqqaF z=&EFoGQfZxVa!~(UgY@666#4Bo!!-w06zSIUjD(gpSG>-J{a~wMl}t^QsNJl$OsJ@ ztga5{`cdXXLVH9`VZzJ%u4&-ec6SO4UyBx+H^sY|XBa=tf2n3*|5#A@r53x;d;tYk z4-e}*n9ef1vARG(Is{GuFGH5V0_7Nic0CV2kOfCPA` zR(juvM~GfFx8E`9jC;@)c}wsFWs=>P$i-O2Ei8)t$4Oj}sbW#J#0^rc3mJ4VCd>ZD zS@G7~N@iMd#ii4a5_rgqjJd+3q14?-Wx?8Witkna3Lfuzxvg@a;;JQn>Z{3%oX-A!3$_ljHZ z5a{`I`0hY&`lb`tGo+jgTJe+9%$ zh`)29CL$r4KDJMw!?@4ITW(hkrKhj(C%GK0{g}WiSQXhp&987;B4N`)y1CGE80h#t zCzNEA6V4mvv4WJHo$F_ckK5JBCpydQb8=r9>X&w4`q`%!^#9A0t{!>U_R3Aw=w?>owh zX)Km)D6I$yUtXMK>GHlq5AeE0Usi#wi5CRH9+%2$)=)hPfr!%5cR1idfn{w9#Q; zmsXKay1Aeg*fSDm{YDYyB_jFeJLJ(>QW)>7TT2Z$Xs0a`1p^d!;Wmgu0WSdp5K<6s zPxbneJb}m>N0X{8*z1P^t8B`0f{$EpnBwB?4G$mTZd7zuAp{yUACqsA)zCFG5|i6* zI~T9H+Mh(v;Oj?lB@#wb60cq+*DvC(&yl)^W!CDq3P!;^-29GYjF%(xHz~wug4-)4 z%?iCwGETF7s$9`v9%B#TGar7dHawHi-6$*($NcT+T)E2(@C3{L4Y&!wgVTH+5NLq$ z8p$Q8F_%@Dh0mXba#u^PPQW+DIi6n~EzQ~dYH6mcXqcM^d3q8C$0r~UmwmMZ_mc)j zao@aRe_r4Xu8P*-B?kqdln`p<8BSBG!9vWr8Vd9!lhVM2{h#gYHJDOM;4B7&)~Mjz z&L}ZCm!Y)$q}#?|9(2+I#LuEsSZcF)3-HMCg~Eqt}zEN?7@ojsm3LH#;Hq^J=TJTeXELFyZ}bG%y?w zVY6Y>r$w40lK9`zuVZ}{U6HU3Nt^FHX8y5PSs11 zK;lC3c6na*QVUA!1d52&XWNAoTKKGfe}0#MOcbsZb+Xb5Skx${d8&l|-!vR+NCmXS z^r12bYY?B$V_Vul#zajarxApS-z9!Tl_3jZcJ82JFk-vR zW_n0(EAbpYQKxSPA9XA6a8C}V_Akm1r4%Hgl3i#zmzO0b(82jsv`<$()8&5t1U=qO z`znJcar0*0IEDDM#26CuIp8xDR^b3w2|brQMs05P8S295rVJKOJOl}Yl6WR%n46F3 zyR*V{G^Ok41_MV=A+|pMfEB?YC;f}nMO6OnQJDLAusgh@BsD8c;HK*w_-0g>Oy0a@ z?0r>lLW!w>yf;zu#7^sMxfn)b-uE_oBgG( zL4wTLvu*Hvu8cPnk(hPQ)>#ZBh0 zeH2~3$hk+%m9dldoCCtRK_Vt0F&azA;RJN{{!1!uZWgek{&!EGl53NoxWkY#n)mWq zvYq5t*AivmDYZh9Qe;IQAZl)9=l}U3X}dQt!I>=7D9@UtY8qimpOHb4o87YHtIlPx z(6@E-rZv+RYEKw70U?S6paGGrSupRZuoVC1B1+a5Ga%MBP~-TIybN2ors(x;zD5nM zwysS6G4v+}@ekg!UludKVr7mO{q3eq0$cxlz-Fx#y~{PBuPu^hq+t~D>TkOzTC?vY z7*>ZG)kV=Ko7DbcZ`>8CUN6tg>FqR(lVJA`aRe6(DSad{1rFT!JwL_xNJyb3&1IeM zMdR@69Ue+9!KwoR2RR{qZlKz|Ss1_D(dO3H4zQF3@L(w43B;F0W-%2puB8!Dxe0s@ z52I3X!mHIq%<`7EO^Fah&lRb>0VGAXJ#+gvStghwv8~ty|AzgPC`6vCEM!xqVWUA# z!O0mu-H&4jyOK(EjjT|Sw4^0m800935fAxf7JO0Ms;wRqQ`x1h->x37836tg5Kky% zMFlArEXYaz5KBILT;|%|Mtt^rf4xsk{;(jF4wxYV)jUcl#q;eAy1cJ}3`_SQ@b^6? zq*_b`E_MH~SqWven(BJk0FO7NgM}Jfg`-AJ`29htbBm6o-%@3iKog_FRP8LJmp?N; zw($=!d8}Pc-07Y!`0DK4>u zxumox&nQ*-xJ zG0>)mD;jb*S%S>8e=x!;=p~=PoJMu%hR?@wFP>m3?}GhEM=n8=JMRJPH5)XH1D;nIcC1IUisHLf&zXtxl5s)v%hyK}YVv5P`N3 zWqz7Mqk-&IaK{#!i_t*;Wupd7J%5gAX2ffUK9U>8NyZ&3Kdd%d`@Jj6B$u8kRQm0H?BS+|(R&xH2z%0mKUE)9i{9sam6gaV(IP&U#< zv#hexw54D0E?8%=l{|xSKuS<3j?-4G-Q5h=`KLm}>q_gW_&>W9DRpKzPwX29Z0di{ z%badauzZ99hehL=R(dzv4GjKo@2XcCxHXf~`RN?YevqP6m*u3edM3UdFW!fjM;@S6 z2hb%1;%dp0HCK+_#(OJP4z!2<;J0-M zfXqm29Qv;SxqIb|NEACAVXOZPq5eb%G$B1YjoND)p#J?AGGK;b{O(xSu=&4IS!5)6 z{HPd4BzdkxU_9^){!jTW|Ms*Ty|~jXHS-j&kUN;RuE#Fr;H|j0K?fX{vl=w*RgjWo zHv^|JJf-yyPyX0o@AXq&gArp5H*&0#32V!aBYI2B6mjG%UNNq32;TivU>>`oAm9@+ z$J|RFw!f2xSB^FCxT2RgVm~b^?xM@^kVC1~*1>Rk+f!b%|GIwZ+Ce4zp0s#l=}iZ# z=Xu4uvYO`H;hlY!aF?vV2Cu16{i_HkG*}3PmK7f>u2vb*fHB$Y*CtSRcDNc|H}fb z!YJV+s*W&j{R$b889F5Hpm^SdejXGjer4nvHsIJyB`S##;WFt$5)u>LfJyr^E$4RnxC5bIA^+4XR(_VM`;X+}osC4_r8=K2-(1%v#` zV^brK)-5=S<6X&fX5ci)UgMSkaCGyLEYL;=p|y=HoX#n8k8!F&hD&}ce`TSRjsI$g zJOK&M|E0^BcA~C=qh7nWH>G1dYG$^Xww+3BV)JqVkz!{?}B6oIof2)mFr2dTS zxD@_ThxQVs*k~I6nH>#tXfg2dzJPIS?b1GFAZH~*L~t0g-mY#U%$gPynG-L7tXBrh z(uMHJ3Bzuk28i>51RS?^z%Mab(n*CbN>^A%7})n(#dk)Z$NsFqI-QdeNE5`DG1u!S zk*b$DkTQnX+F8O#Y`L8u4Q}~F+;tNcylT(=$6r61FK!K=h^~m z`zb^~Tq}-?2=UB~31=AwIGs?V-(FoopWJ4Z`=7W=$^rGa8Xcgp`oDruIKu2Z=;Xv6 z1c@qBV^V%SI6#0XdPD)y{()P zg5>&(9QRHON1vJ#RGV`j4-2NEG6>k-)5fgF1Nr2F7T;$qw67ZyIjU>m@$Io)CO^Hn ze$oetv{ZA{4>D5e-B66Tq^MI%x%xRF<+*cxWDb;&KJAFdSZj@Bq(fo&XEp;7I0xa zN4(XK&vSpg)`&tO0f>AzK|r$cSxlHvRwIqhqw}XLD^uufhe^t3y*T>2H5vtNX469q)JO#!j&cfgH zNRg4jM^Y+!xC)|;#@C|K#L@wuPo{*725L0LyBSEz;-mcwC>cn3qV>h(hA;`V3Fw=` z%=4soaZZ?=IL|Q+aq%$^EDJZ1eHD$hhVr3Y4{OUT80DTr%A#NHE=Z6xB(nn|zVD~G zd(YR^1Us+98c5A3C5^FuZ^f#(`H_{A?zd=|#-R?BmaWNScFc%4ZzhnfzZ68}Vkn=T zGW{wFb2syU0Ixh33gF{2o>=#BdZcuMQp=T*zrllY;S%8}=2i{kM$R;!X|aw^Ptn4e z8~#+!wZT4pAG(?|YchgQComE9f<6a^(c)Af!-R^Q0nn;}Lg)}s82e96h$IzHTlJgX zDGi>miRq&q4}pcjR0*1blsLxCSa;6g691KOE|zp25z`-0xDi@j5(vqnINpjdN^o?N zcE6xyKdxC;9wSG=ytk`RQOAy(qVbDQK;HOCeu*#xyQ*dvPl-D5VTi>NXVK!w46*3P ziB|J}hzfW)KlmvY?;qSR?kiV~o$cJj{8bc!%F(u)ZZcmv@}Lt*j6V4qp&4E}_>2&R zM%~4=OXmL0LdDBoEn#D?cdZq@|1kQAHv8hX=P`QQMz!L~nuM$6n~TtHlRd2~#UfdB z?zL~4;Nql{53?ojNT1jFptOKujBnG}ere>XWA;EG+p+7@rO!cChM)gZlEEjV*L-}P zYB*e+st7|g)=%aac&;UB=3lzKcv___^vVvu(lywW9OBSz#hWEn?I?*u*12#AUiaV% ztS#bJ9k%oj$FK-`6{3H9Jfv~c<;K|JrKXZ~LS}(3fCq7Mu0KGe(_@`Yjj_xiH81LTWuZ{mKGa>8w#2&)eKw(B%E zg2LzC@a#eVbu)gm#F#JZ1NvVWN^w7=zwR8yU46i>_&-NbGfHmfQTBjfIG02FjLmjA zwgtyP>5KzB25iYVtVxG7kR(M=fM-rr5fprhSiA3zEl4-z*XhVs&v72zh9^nGwWgWe+zR^3^xQnh!|P*UYrMD6~B; zN$oBX^I4E7&fVO@fymC)HmF0QoKG9p#lUJ3Z}8c-@BkLHvlw|?bJzTNWC&3r_uCI`4gONR!NsB}w1(wl6Qlut8-6&~yzR-2IE6lAMrXy@9 zDHMJ6CD96*a;IH3%CvpIUrWs35e?6g{mwiO*WX#TfA4&*I)Ib+TsPc5>W#GgZ^vmb z@NxVYha>y#llPi2Ds|y4mc;Wf7DVp0_8bHpl-+Q!aGgMUA5wtyBKIcG3EAh2XEDqy zy{BJ7l|7d3M>)L@Ad&Ql53Hmh#67ue;^H1z9L()OuaSFhjVRFT(=5tH-9Dy!WtFHE z4dhkgbpbtgX%&tx?K4b>%-7fe^_j#xsUSpIR>~io#l!UyZenb-lwV5VTQNjGP@|y9 zL^>~xOW|uuJ&irhIz|;IB2qaJ@$DbUooivuQU9gM6OtDL1~^$a0cPPu2aWt)GWQk~ zi+8EGqi1ZpB`ATR+214!?QoLphSV~#1_ryyh|o1(L*vBkf8noI+xfkp-3zYkJp8Q- z92ix*m`|_+d+j@*y^JXO5bIm zk8)fzhR&d(?(pi~wcQTeoMGbfHdfHS+)LM-)3n&3S)nJ;>;OLC$cKmNg1xplWpNKX z>7PF@vcTzv&)^`D>-7-}WTg?9W~j3n^ihLx8~A&D^+ zutp8~aN%FCC4m9hE{a;HCp5ZBD}jAL$}`SpBuvhUBv)#3QLO+YOZ4cdg6PIYUw+>& zIHK^Q)BA*(6$3LOVFB#aVDR2-h%?#W*UlDwZ5ZGx1%*!3^$Y)LtRgCOJ09p?8KtLp#*A}!+Ov9q&(*s()! z83vTJYMPg33fI+8rkK%lQoJhrf{FS23mt*{98`xtP^Om-7Q^kgg#Z32SoiqgAJVC& z{8djoSm;r_7ptco-6Hm(0GkJ6F?sE_D&l11Q{6Nau^}A&WRH?u-Oue-^djLBw2tpo zx!G8ZECd+6lJIlFy8PiGCA6}z)ry6SkZ_8TbbfK9NI74s1Zh0!;b-7ziv>>+&No5(GStJohNiYW{Wf z3<6^ij9k%$FJ3qjq9er6=&47+leW$h?Di~^id8Uww1Z}Y!h$I}Fe4(93(764J(=TW zy=q9%d`ZiJcQ~-fqX6?WUaG}a+rYQF@-*bUtcUNIZR;+~T^hEhkW&fuieSFY%Zo5% z!`KxcN?u}^^!W7yeaw2X=YV;JWq~Z=(h(t+g$&pU){q|+W%ple%!D=>E~<}FjZ1i& zwF`7F$e~B|3AA2$fAvk3Ob94c{bv4D;DLxk+x9IsGBT1XEIt^8`Fw(wRo33c1t+IS z?~B*#6aLogW*v3OP$Xs^fLdhmdwPIh5$N2hhlEd2kY99Q$dfS0A1LKdyQSUqD}`}I z9M0xJIxhnHFeP5FpzyOk@XZ)Egu#Dxd}@$ks)COhaWmc{TkO)9`Wn9bBriVxMmFic z`IjO#MS6(LePjV|EjF;KT6YBV1F2q{e4g+{9i!?5M!p z7kw=Ts0sD zXhH@ztH#ItWwq9yXAUVgU|8F|oDj;5rQ%5Bw85*G(CACn359s&q`{@tNVisLmIx7M zyfjbW-Fn99cv($LPyTMI)AQBE%6dXe6gnN9h9vb!2kB3C=3DxjLv?31SeKIZ3(Bal4jCQdz7c6Qxx_ZcP;^^+qImAgmJP!)Um$BYV z-8so}IQEGhRCHd+Rdopni1uGGTj$-83sv(}xH*Q+(hgqPekDk_&vW(+j5Us9L_tRQ z=oj!n^u_(@AT(I^4H+cSn|UybD&)N$i1PKxg&^U{?Jpw=d4n+6?&W9;24Rdm(Z<767Q>vm z@y{eBKt!X^kn#|^Tt}jnb+#D}4xj^dwfD&5*V7Yj%Fp|K{S1g*0ca{?_@zwoSR{#$ z_Neq##fkrpz3lXDVV6ftn<@(s8q3LiL+|oKOq{f}p%n1=IMk6y9v@Gpi;#S+*_st( ze=2k*EdI{q32t)^Ar-jyCp9$Islvw)iOFfzmr<67F&&BKz=$_S$G{hel_CaBj(O^a z^NLuoRe$_ZY?Dpz_qjMnpM|I$8dTuS(gf93+#@g&;!K=FX4{)nYO`irh;#{0j)BWq zg)$M>SYsAU(QrYbeo7ngc4>pB5)I(23XS=K3M}V#M9n@)k`W)eZSvf3Q)G{>g^foz zF0893;u^u41Szvql}PF-gCYjeF!bPyu-MPV%TkH>N-lw{U)dKmCueV<1oHjK4H)ss zfv11S`nmy`2>4-z>Z7_^I?)o*Ory{5om&Bp%cp&oF28?daoKzR&o69C5{Z&`gSQI* zL60f70{;W50>M)$)iSzf64Mj(_PzReJ9SRzZ*20vaq;C6Y_m}6O#T-Ny95t^%rP-6 zV6DQ!oykBNJ}Z9;>)lT8tcz;uj`MYqsJ zs}pW0RAj{RzDlNwCz;94m`<{q3H=B^8-&!D&tm#1>$+fCF=fG2GT)|kz&UvD9+m*V ze7xDGzh63lPB39PDJa#$r89<`$z`iiOe$_n=umThtf?+G){~r7zw9KHpxBsD&iG%m z0IjA%Tf~xW{*Sz;Vks8tkHa=0VG#@~*}6#I$K%;hZ;^wjM98%S5xF+><4!S3P=kwJ z{p~zJE?=iJA9$AAA4kMJ{3rVNGQcUJXi!vY1q>e8$pW#m-`_pqQNI@<4qy3vt_-yE zF#nKE37?Hb?h0S|^N~LJ+w{r{-$YTtb9OBIQGi@aF8?YadPY+@B6pxS<@Kxk>D?=@$aQ&&x}%c1yeL5M$k z6*^87p5paZjs*jT!`v*27VjI;=Td;7(}#XCoZBC1vgl5g^QL{=n@%}lGaz=lLAL%yO+HY1(=BO zCMN+#!~N2~ey%n5-}Ph5wl7KN@&27ZZLH1-s>U=qB&`6F?BUD1O(DMF%xj#wh_xKMUSQ4*ZP|mkR z=3CXDzv72W8h!M;ziaclJ0-5IWe-96seZzIH6i|0;1EkzM9x7_Llj?)=||s5d}-jl z-=!B=NmM(#-QKH@@irxwA({PenG3V@3!l4D+2VEe*e?6V@W70%^40aM|K(f=;(hYA zt7v}$>M8A~@DQO8RAq`VoX8H=d0NqZ=HC*3WCM3E&XT)#KHawjg^d=P^|61r^>+RS zDtMC7lxc)B9?9RArGvz}#g^!Es~w4J5AI(Gz2oP7Gr|2>YE8VTuS4IWH?tCyN58)| zAcv~O?})S4h>!dc&a)vsSFV_#g{ctd%Z#(A?M(Q;W8KQ(2M36nuJjR;ck3DV?2q(7HOYGnCYkTcBK;f|DTO>k^ei8kU~t3lv6Oo}AfiGrp_x^!rQ74+0$9ek$zpbn7Qsk~rXUP3MJy{EYBJ2b5MFtT8WK^aa<1o`c zq0U5e2{b+o9VZB(o8SAaHwSHld*5FJNA~ye{g>0o7)G4oGWwtIdv^}iBzEfqhrWAC z4#L+O`$Y;kzEh+VI?j3W85{p5iYNc>cs_qe64^TX3X~~cu4W%D-v0#x?3_2yYpx*_ z$!xd#hyQMqT9E-n^%A1yWRX!-N7K*FA?p(aurUPP>YJt50=|pyZB5b}>$s2RyzL?GzdNWqo->?Aw}irNS*~n`FQ%1fbn+5l&q|wr)*#kTCJgKd|{8BK$8X4 z#-!~uZ72h(ooX+NS(}-@MMj2z-`d2G10Vm9y0}?oBY8mhYPR#e4J2SMrIVT_l=kx- zv=#<~LhOStLgnSGKXvly)F2WYv&|FA?&SfJuzKME3^R`Z;R;+DI4cIFsyU)ii#0vM zuk@OWvHx9^VBwVJOB>tARWfqAkuM2`49b1)Bs*8PCB~Uze0bd2wTW zsJmy643#E{sJBX7YcGpR_X>iIo3Enbxf(EC9sKt?9cSgHG*e#$hp$0#e5Um1Lt~g< zuxThGMtFO!YmRX?%jXi1ASBjosa&hxbq9^X`~;NZMk$9i{5#>pK3L@^2m~~#1X|^k z02gNyGRJ%)27AbISqQyKV#G0bi+0=Bui@{ zldQCvT)wVTUIK0!l*fh&8oBTIU$lRJSmPB@uS{QG z*VtF8tJ$b+nfA0d9;?N5x{rM~YWTd?H)^a`hNYC#rf6zjogd|L+olXEZCtP%(j)&b z3*hATRX@*UosM+RDdCa!`<+`i+3rv2;%1hO$1gRgklPf6UmWux;QLhjFD{%h*N<9x zTXoZ=;SSc!&dMAa0zM7Et%50@zVuOVA`{)MAO*?bJgx#aJ0q$HZ`4!Y(3TEeZf*-l_$;# zJrdoZ7|mWHyUx^14jICpvQQF&-p!QGaw=RSq!673_}++J(RJ%`{ej9^DSPkMlKlvkcFp-C+K9=; zCW1_fmV$mGH4Mc>P4iK|>}SFsa0D}D{{gAz%HN>xZDMjND^}6#>+4jeAc5A7+WA&C zfYX66LiAsA?<8GLE-I8%j1c-ZW%awgsJM8TIjusY=owXO)Fcy0Zr-uL-6|Wy0laFV zefGwnZadLX*;8 zrlz^zSJl!hi47pRb!S}=q%=BRVW9kd_|C~Q?zaalXWZzh2pL8Kr+h)}*U!`+%7VMh zri9`?B4w0S?0skGF@=CaT_evi7D^;)aRe~H&5PYh@tyV{DUlmS=2$azENMF9ZfV<8 zE0z4jjAbdk>YR0z;KpiG_(-Sw$=!sRwE;c`!@_D5EtNBIM?+g-X3V+}zG9;cFiK!x zO^6QrJCrPkX^28c3a|5$e(V4q@<2A>ryelmb6AB-j?*djLQ1o`m|n~Qe4^(soRHF; zf+IpvMSR!8C^}jpj@l%r5E@KtdngtCh!SbLwb4&bSl7=ss{Ui7LLP-!2CB~Sg^e`X zgC!;(MDnh+^wvy7d-bMbH1Mg9KKfm(UeWpYbX5_@q9K0v#G+i{@fK~8tLoO|Ixfq7 z*1So|F?X%pF@h;N*wL&sGH84=u!HI0|NTJXFWiDa+fRSB%Hw8PA*rJEW2}>|NAUYq znufW~(aewDk3AtyatbqIFlg;^3vxfDD^oC@WK(@&(6~top0d&4G!%>!9r#&z-J@Hz zO(SHu@||=(ieoQ?Ad=>mR?Ioe+BWpR3F5?{Xtmh^vHBhH5Sn5!(y4hB zdOII{h3XNE(eB-9p#GxqY0XCgd4R)0q>Mi)}(vSQ9gz0jtzHOTeh?A)5PatsuMR#~tP!Yk*Fm*9?0Qf*guLHDCM~!RfS#Efu^Gj zh3a>x!2~ocKz5QV6M_yk(wy%N9&9(V5|&r{-fd4g|0287GE@>0670t>Dua z2f&Q?>T^QEX`TUB179vc7S$0AB+suH5^r8n?EwUz7qSwP)GqeVE|39L2dX*@>+(7u z0NZp1behy-1M}~vKvHSiI%Uq}xC3LXk%PC3bCw3}$|oL^b{D3|Jif-MyhcLT3l58s zudp&o#5j$vntz7Qwoh;&&yvyx3Bf7lcg0sWSRY)8wz6+>3?}wDSgOOR^=4%Kg)-Xq zD*4c-=GIWGeeikF9xldq+-dizABsYvoR98^B53;Hbxuf(RyyVdG@!a6DglBAa%R;Z zb%kXiN^t@fI?KI|#COGoj3K6-7n_#Y^wadFFl&h_)mHRq{c#5CJzO_igKvMzC+MMM zbD}R@g$M!R-zYd|xE7iIa!<$;!)PMEa!9t%t&sg2Yc+yw|G-lMxhPEdSF)66d{+-K z=5tgBPKazf?yIw~2yuo?u+03l5NJe}Mo*UX>NkwG?6ZE)%5c!iUNaZv{Nan`Bz>Zy zJby0swCGn|&B>l6p`q=zl6wk)IZ@Pr$-J_S0=OA;rud&GYq1v3GwoO)hM2`S&JXbw zv)F6qUw}A}TNV1|ia=6-^EOd3E%xZx&-DFw#S$v6J8}J-DXQFMj#|o_2xc&M z&Q<0IS0>wj*TiV~h8((gzPDQ@HxY77p88K{cn^#5GKS+Y3CGy*b=1F*vc=hWzvSz~ z!p0hZb+XS#=VT5YoEL&8T6@SU?YG6V)F_~2i)aWXM$~dgrbcV#V)TZebU;cn1BD4f z1f{?7@nqZh;n1)-xB5AQlO$GuIeLS#CPEluSrs%8Z-RbPmqShU>3=EyN;0oqBCEYT zPvnE+4NcNmo?k6TedHP+8nMqCkevLX;yE|be`Blg48d@FYxnpCrmMQ%ZmjBVl_LKp zNCOk9?daz#Spg|pXkj_zd6P!Sz&5T`V&^(N;o)XiY;6<6qAe5;nD6OYZAeA8#1h$z zGy%?KpFa9n!e7BxEio4TYSH50k#WL0p^z-k2WQApD07!By?A06&w5@+O5(#b zi2zJ&;AkoVF24BH2zX_sT;A=cbXnYW-ZHhrXrRY7-1gR1^0a|gUz>~wZa+e=yMm(+ z;KBeHqM4sjfQTID$WC40tG#3!L|R|2R=B@shRAlrv<7sZKFpahq_!!q6|HMU5pPw* zdB>(tNF>KgP3cp_pd5}_g+ejt=Rx#{-ROA0_Mx`9tzn{>sbSlbv0X4P?piJW+=7Ca zRq&c1(5YwY@76Kym)8z;NJhmA9jF!ftlG6G6~F{U3yreZ$duDXd7 z(Xy%Vqwy3-s>TG^2hnQiGvLK(-u5SB^ljU};bYB;)PF*b)vySvD=H0X(i<@Q-b9=& zt;=KfUYqPPO`(MbXoP*>1{x%%j+}KWI zv$1X4Xw1g8ZKGk6#ibg3d6wA3MPQ;X@K z12Tcw(S-wtL}XWe+(w4fv_MA@PB0v`HmkvUFk4(j4z|w{-)(__6B=|gavP|K=N%pa z)vUx}TF>=nB%@h>W~WqC@`JX-&JTXWat3qgqJ%{%cRCa1LH1GZZnjF@zeo05IQ#j< z{d>k)h%skC{@%QULB6Yze| zRoubte+N!H#!h7XK82QJdJr#Pfejz%8mtyrhTY+FOf`o*^3(-YirYSLg^5Uk_G?VOzGu8%upN)1XHm!}8 zvWa6g&eG6+BYtzuz1m^r~TJlgdwMM)$uVH3|oud}z!oYw^ ztNI&}^jQ0NcZ1BBg`Gkuzl=YQm zV$Z<04dBr7JN6=&=&>#ZXURZD92xiie)R8vJ=`zBoMR~;nh`Zr)LuB!|L{(xE}p_* zbtRV*7;HKd-!{$_P04sDdlPh;A>49QL?3_b+caSc5SD{jU87vBG{z=;V4+5IGP7EC z-=0)whrGZ^07KNLpW)3!12t!5Wizk+J<`wJ>?dt4j+VOo*rOmem`W%vrJ0psU#5gt z1LB&+@_eo4xg&TrPT=ghvYzWhJhDuzY#7%vbd5T-zyak?wYUl!ZHaQ~56ZD3up9g$ zq`omKf202(%7B{tr^1H<64c_jl9qdl9}qY4Amoa~&vi&Q^#_L6)v^J`~a*6(Sct(6vGIt29m* zbp`YvbSHSTEP^#Pp15D;XIu;4ar{pFTd>f6_BEcX{Kk$SMS1Lmm8Sbo=~qnaByg#s zf$W2;Fx5V!g3MDx@OHa6ySv;Z7~Lo`n}h!B`a z|KK}plo0qxL;n6X#6wsFUbD>k5CLnei-16AlG#>NR0KCYJa)}-GS z(nX7agwl@W7HSfR?~75F9fkW>xXI;X_BZW6ks9m@-4_-z@wg7=Q?uqxib`=MRvW_+_k1gJ>gFA*F^fR3RMAm?tnsiXO3g6%`gHII;b9LSo3< zjG;`dIr23AcXPeRoKbOkj5Q^G3QKag}_B_MSqb0tb}#25$qhr!Oa5vh8zuD8ol(Fket zs18|>&|*u_pedP^qhV0vTWIqB9nQ6y8(GsEgXSK?TnDT}67}Ks_Lsj**kZzej`a@) zUxBo#Jan00ELO0tLz!bR5z8V+*3yu#84CmvSt&476!Mp2Qz4)e_^xMK|lWmoT} zieF{1BNFpEYKxuJv=Wz&$cD=#qYcY{rdgQ{r3_}FIU;NaI{yn<;Xzv^Rl1FiDRwfo zZaJMhMxPZpS_ts?teHjkhlW`pY=qmIsSN#I9>8*UXpI9;^(%{t|D?cXdy2G(zC1lb z+ig@9!9kIes+CcuDxM&+t4f#6ZA_TiY?JpVp0`>$mJHm)CZW31rXNYn?4Cil6AxDKgPF3xW%mhlscjh6ibW*{Yu0}`&H%oQB zG*+I6h#Pg3^{)SxK9b4w-63CA3YHkBtuy7bUUkvr0-bh-GLsytlb%Y_q7Z42#lw0d z{;kX+3dn9MyOKfut|a3n`@C>YD6VmKcMlg^Ik+2@+T7VGPKMT02)mTFURoRG6*4j^ zsisd&Mmw)NS0;Wu^^#JWM?-Y(ks!0)Q!|<$2 z){P~gf4f2#a0pZb&8>8C_k(OO-YP-Vw6iksGZ?+@FS#1QiO0|$vGybSmI0r9D{zcd z^+yDM?vd;W6JB?5&uhWT4(reoypP}@2m%bwJ0y1=SM6I&^bOO?n!dRmxN`ry{@D62 zaayz$7UJ5pHg`Ds%wc!(O)%^(bJs+1wnw__7&C`&mPj+NvyR+bvNUxFcLirTHZe_p zQ;XUYEJ{H|C26Z>>vy8ckViMdtojPkVE64+XEnZn&^By7fY`h5x$en|e=N-X%uRT^ zYhFFOi@!8PLQ9^L|6!B&TOkCO*-*Kk3`&-ca5U5E+$29L@#;?QG?Uds77B|nSwZ@= zl9MuJS6&ncJFY9OkU9k%_eiaV%Szey>kcvS`^@4d82gI{MKBulB_Vp{$@||Gdu!mN zgu^o^n;OPccKpCYq`@L2tWXMT5q|PE)axf*i8#jb!p==JdBy|=cBTOb+qEyr;Lo-=e4jXfP&r56n4sB9 zoP=jymq!+@=04?)ca#;;1|d__=cMS=OtKfVL9yQ#6|*~dO(c(@fswAHKci&V^{%== zkUcZQI`M|MS9~z;tXw9KwhfckHzVh$A)U&c*I&qV#^(}nQc)rOqM&d{8WTFfh}hz; z;pGfvO}ryK2@>TI})zX0LMF;2m^x|{3O zcI&Hj$JE3`3*^Z_LxKTBQ7dzb2uLE7p(j5Zg%}r5)F6#ENs$$jf<~bYJqwF9GL{82 z2y&7q-XKN=9l!infCKV~>YcmM+cwQOvZOM_<@pegm6OVf?Az_k& z!I{2vri2A07_%*k9`Rva$v`VTl`&`dL*&DC8d=44?8&5v zXGF|@GD#W0awYiI;XD_~>INExom*I4G5U6end{oTa_(MCaLq(5p#flgOV;egz!he( z+r`k1EhjAe>A6pcVU~`ZBs*pi`dniaWNgFKw`ndmG%m@i9*Ixq zj^!2_JnE=R$S8OG$F4c)&Bw50>)}^JJfgjVFDl|V zt4s+4jW~?_5?QpA;Sx6$Mslrm2D#6nWYM+$>FpkJs+gZ_aya=}GDrj- zxEuo4;Y_QQU>8n8qG&fI)ni_*TO2%j{9U<#rOQuZ0~s`m67CFlxw)ORh;>cNj5#MM zISnH@2xgH*VUZZ$kY|ZZ3Og4szKv!Ib%0}syQ-=c3xSeJ5H*3Xs%cH{Ba*bdMrkmK z;U*+ZHbOMB06xXcND^@o^XNUK^dj7#gJF(@=U>CM+h9$9RvgTkT1tw?nH)c#U`Ge7 zX6)+;h6z!z2wx!l8C+f6u;WNerEFJ|gYf$9PrQ_nJrJp12#+26^@O}xLM^N=g4^B+ zbZRqTtx$B%O;vGMxWink&opADLym8T)VXDuz7)u3$QmB)+_T!H9Xc0{iDczhtJ~Im zfV@FcXWHX>+9s9l7cl#yI@n_?puP!Z)_qw=J63jY;l(TM`*H6u@xPs>D_=l1dGD7n zxR>ab5XMkGIJqK`J^LFK8V=_W*IZxdo%K zIbGMXXE|!x0iKT$5D;o%Im=9%!P)u?nmiS@l7C}~73m0>^cd{%e#aKBmGYMYBP(==??efG8Oq5k6kRyaYSYLIlwf z8L{K)dqUogD=m8&1^mHV=e=kPnrEa&=wGbR&A=!D?lM2#H^S7I0Sxkg_$BCoc#72AYyhoH*elncL%-^l(d%J?#WzZ9O$ zhB`QD*Q39UY1F&WDQ+pkY3PB2qPF&nlaVvs7W3xl-<#sy%7Bu984viy`*x_oSZBgC z%(L(#3B(kxV$B#G66%)}mLV7y=7UO>*6+)<*ot#l64CXplT(ziTIYMO{|g5C;!i)kM=l-(A3O(-p5W#x;_9#Gclf0smFSW|)!bNe z$qE;L#WroX-5E|N#K%x|l@IUl>kAZP2~kNpH{y9)no|N2CxkHWUraPPk>FS>kdtYZ z6Hv)7j$`9*p+yCXqbuOcP!tGVFjCY_{~$VWAthHpAv>IeA%H1R6=i(|)@(S+;2gMS zvg1}(*35}3-|}w&gvKp`W2|qo<8B}-x90G`Q;<*xA{XRp!covDs;2a*c>J|2+G!e1 zoC_{HjW3z}5u2r=2<>F{2NH{X{Bxnf>CH5{<3KumU{GA%gR?B*Zc^4tJ zeLl-vP=&9_3=n4B!{2hks{8}1B} z{g`>%77XD&3lgZDm3_$tjun^dSIO&~$$ZB`ozXwwhTVR zCguH4g0bzWyu{D|u|#f(%209gPzrOfY)bp~J!A+%;O+_R>$&y`&?XunV6O^sj2)1y z(+@HzG9}zt;wwE=CFAM%*EE6Pr6=F?k7#n?sa>7r1u{ETPTgwLxVRfvBz`2;x7S6J zQ9z6)Y4$!NQz9>*r{P<~S=iO`M40`T9;3!6wo4yafF=;^$f+npw3N!Bcj~!j3VER$ zGzRMCPZkVjm*%qbGsC><>hVh40+k?0aCu6UdBEp>r*;>w{JnX~kR?2JZaT^xdZ5#k z=$l%8buTosB*@Ye(SGmY&wO4+Pr5!RNXZ&Jar(M~I}+r$>%VJ{4?Ix0HF)gq!pB&d0b^|J*(1em?o+b*zrzO0)4oN?jV! z`qz-pNeFK%BtX8=|esru8abmJz&yW;J0kI;|fTr~CuY z?4U!&8K@tK&@RM7ED=pp_?w0InhwYRp9PTO2uC2XfvouxM1lQOBcW?^}e3st{n+HH85S#AWKhUI0Ah>nyAl+@8`SKfg9GwF` zsj=1?V{L!whS^>HTce9cDB67xhnP|G{|5BiJq~4fdirogjnxtScFdZ{yi>SwcL1Wz zl`o-@(H46pWWRaST3h^g)Y>Sg1rFqy3uxfMC0nIzJ^CBtGuFkhq|QQnvE4(6*huRq z1TMMTFQ|HBp2j_r?Jhte74i#*`&BR2cEGY}_Gb@7~O(mG^otSFBK7V zX?UtB#r*p@Z|^90^DNIVh!g}ZA+liKryDb_*nl(BJchyKBJVwpcv9~j>*D88_fKJT z`wVNUS4!ZLla#$5_wBT+kJ&lw?vlur$QLCYYn69{huKBYbzSKZ!;vcnm6-1tspl@E z{zo#>t}YXFAgKvlrEp>7B!hdTT#-v-=roy8ol9Ex+0qI`k@T-SO5-HBv0EmFO(Ss`P81Hcj|%JFN~BKnhY z&)8af?D_P;hS;40#uai3T3ln-R{Vu!VH7MyUlK|B%c_K0=0pz2UN)Ve_Y@CP*n#By z`L4-Ze}BIPv*ocrSL^cMKwHF&Q;@9xbFu!RyXK9>SHn1HChxNsF1AE4vJ zgy81(Y_fXeU6lfSQq{T>JakY>r%k3dt@$#b2==_bdXxCJ+ z;Vi*xDlE%XiMBTgpAk_f^+nblI1c3|y+u=GGfV$VNI$fgxs{Ac?l0nFBOTjytFl>k zGKc$Tv#}XBnOt%6iSUb->|k~Pmup_w#QRz^ExswEdG3U^2Dau84ce9pn}O%=Cktbp(i2J-xQ)7= zPlwk3Zp4ED>oo8lUN`h&{YX&aWEFtfJRoy=1Mc-9zX4=804YQ9_FYKK zPGQ{|m<&7cAk77>dTLpyK$39GVk;!`aLYLT-e~>i?CXlVY+%3*Du;g^BwFqi!~)f{ zped?@h9cIs^Zo!H>R_udhqsyC@lcCPmayCLtQNdfO|TR2^HI^ql#*&NYJr5D2wYEt zl_C*R2IBl*UB;6+U)#S^`Ss_Nu1>ob*>Ed{R>{}xbW6I^5=kH1jp7E(UL7&w-`F|e zY{#xe)?+;O)x{Q#!>H?dWOpLwXg>=Oz}*PdzF#xjEytZonbm$kn!3^x)@V)YVyO#y z^W`&?yWxDS+-?TT{p@l18nWLnWjBf@^}BzjbDZ&shVZT6qqWFNwF;imN7I!~(d%Rw z{lIy?UxyW(?aiOaXmM@!q)L%G`DDaW_V{Crd&RO>{E2PN=VNE^Gmopxmh5}U$I_Zv`Jy^mDR)IkqT#B z8bTcZ6qBG%gcxaAa=779J2)q8>b_7(jcLcz>S|>N%FAz_UZ2yDilc~z3Ah5i#Ph!( z;fDIu45}C95gvo*g{l~QR!=Z45m-# z>~JV#{!W}De?$DTqIHCr>)$HN*CjM9|1^_vZaq31=kx^h!$|F<^!At{X>>PJRIIre zSVl3nuO5|U_W<55Pk~-!^+>f2uNiq(#+%suqoAZz7bqP3eQvn3q1~8OXpve=TVWap4!~KO;=}PDx{~^}4TV9&?lLuQwrzieIH9AY=b?7; zIGW;MDk~!-*=30m^%?KvbLb@q3g>_#`*^?n^gV+~@;e^0`)q#$A5aphY|A_tV$P6D zgcIxvh&Z?b7BWUO@v+wmplSqQp1{zZtm=2fZ0@X;c0~@Qj8?)r_MdgXihtP{_<(D7 z`J597@87?3j2$KdQP?I|gMSK7Iv3BeOSW;<$vngfMNb;G;u`QsgVJFyK16(Lsk&~wz`(R!fj$4*i}`#;+jZZ77@2GOsZ)RB^qF326RTX+Gq+~Xm8c;GPO9TssXnBS z7!e|yl^7`s5q~J!sLgYCc5;N0+6whoBvcz%LU`t)8P5av&lTx}zu09LpDpeJ1 zh4WcozjBD;e3bzm!En-~NQ|{R7SRe(R&?h6-`LNmrY~jwDk9;TE~b53y+)>5qp(ay zt4Uo+R8fh0EXUgx&PC|BbN;tnSB+exymHBnfof*73yg2zG)78|@<|vH-fTsA@Qk7J z)2I+PBH^7xec_>+#Y$5)mFVBP0?#qm1e>x@X@rfxSkO$8_PXsX%aCc`Hhn>5rq23( z^t14uJ#wH(EaJ>FH~I{fDJp_VAJjk2s){Q16vWJOhh{;SWxcovXYp5{YX(a=OC!)t=qzM({p1#&?ba9POlM=Z6sQTK4>sUF7t4y} zQmhUah(|t%CrHadk1bkg2Tr!az)#q?N!O&?Fl_(bjW-m}Jim zrzQfH2AR+n2(kn#yLw>qEY<|%1W@<@i|*U)Gke&PJmjSZ0muQ^OHfmWkAGdZ1FaNM zRLuh+O#a0Sn85zKJNC8```mTJ7n>p5&L9nZhabjBgFMRm&!w|-_4U^H5%Yvn>Kb8M zG~j2i!~i0}z3Y*So<{(tIp`N*eZAH1fB3TV9Oae}vFw|FALdeIuN^6o4|ob_YCQFT zSKW5x25{@6i;KA08N{b*NC)J;4{{)B8lB8=bR;B_o@bO1ZMZ#ih1@RU1)}nDn?C;l zC!#hBO6Q*i3`D97cn2b?2UN1GjTTHG)n@Y-p{UMZ9Q~A4VGOvGAs7fgl(q>+7@H6& ziv_NBEH|ucS5lnCEyd&F?{SJ%N)KP8+~eCPB0EAoQ{(fu<;d+ zt1yE98#THbG;#Es_l<^yr-_M{g@LDTI$UMkg%ddEquCAQWf=!yFGUJKJ%i*(HpPFI ztlnV{at-k9U*-)|w^JA-?t;J^+$&};DdsUi z=YDbOcEWME&_@ejMI+6m9EG1_8Mb8^GWdZ52%q0yaYhf|fo~;G9@A+jajpy;cX&K1 z84WqTJ<)r2;w8>7q=8mVx+#|ac{OFOzlhzT7 z!~CNWGBGaLQHN;b^gd_Oy;jnhJII$?j$U6+-(^g#RqF0{#St&7p&dzlrVXZR>AXRr6Dnb=YDxLaUm6r90I zdja@=1+85SR8&+TuI1(vmWmbc%9nTQA9O#Up?2`_fud`dt4PCv?EZacTR7AX7A%5$3}C1Vye24ZU~*FK=>zx> zEL+7kTD(3#1OY}UXyD)ml(_|bB6Hd0Vplr>nAU=<#S=z9S{wi;I#ns(XP{EPeKt&q zY9)iuWqyACK(BCz=nl!ko9;vQvxv&Pl|jYlC`o|02Dc&%MMzc)iIld2IHg%^%Jy~Y z4I$pyfbN{-&Flf^^RL1ffn16ey%BJue9lSi2rji!PY)N&*>(>+gmr8gY+O12o8Wsi zL8-ZMUxswgv@RjnQ3EOp2TPsGqy6{s^A)*>v|NsTDy0_6gP(^s(a$^2R+ys3(H{c& z>BAVAx%TLG&3KdiB}Y?nn@t#3dhO3H=<-l4yOF+!*>Q=XQ|}4dFef`{cUXc#U}W<6 zazmND!~KS6l9Z^oy}Lw7`vH6dTV}kj>ss(kDxynAuZ>DbUsTOEXCH;I)(bLJ4%I8~ zO!3X7@qdj)zpb{CmV|^#FF2+65^^dYcuHBX;<){tVrQ#=+nHKjxgOtd92%{^;)!#y z32%lsp~{FIw@W&vQt_+HA(L0ejx}=52Mb{g9*|?2Cl6_K%AWKt{2-e^g_Z0a-j@_# zL4y1^N`+jElhpQNRjn20k>*edyOGy`2aOknel?hfsb0Z(y$H4G=r`tb+xntd;Y+B5 z+eOGMPR5H03g_y3(fYwznwt8Zhxem|9csql&ino>YZJ-*iTo@Kd91esgGF=qz=&i} z+U&>IWLP=AL-!^av-L7wMV9bndYLO^ZCa$1VCXX-Ol&gF5tj$xu!Cg+oqr=^R|U%K z=U1pe>W7MwFXPG4k=e>pG%xSF@tP7+gSfHrM$v=iv~g?1E~m4O{#wBL?UX!5a#5R@ z3{?4?Z5tAE9EkU?LjB<$*Y+_8(dlCb^hfN9qD^sAUIGTb^Eb-XMkiUP6mV8V$d(#D|Ezj*Bz=y(;)5 zoVFwqS^=Eg04KY;T5_xA>}s9m{Hwvrs^bGkRWdeJk0e&fX6HdnPFr9$p#;S-C_`TS zgV@`^Nnig&SKG|e&k2Mm1+8{u!)sjBS6zoC|9h!5DBrAhVq4BqL}voMA}W2kVHa;= zT&(QI-XJx~S0YN7F*I-@`VZA`jFfMwJc`WCSl9h!FEzXZ0@ey+ zTe!?2b;_SrHZBe?b@AxMl=!2ovN$26NOnXN+mF=D-!XGJ5HTI4XAeb8uCQ2IDrL@o z=(wvZ_`+jwx?pr|fiTCmgG#5BCwD7|CZ(NxeIDH-?|V2U_TNCr>v%N4v3}KO3!7v9>pi6!{v=r&}KI3sm*XHRs`9)6p zgLY`7+=oAq%K#f&+Bq`mllTTv;Hr3ZwbScx>(P&8G43GKe*cbLp=7Sy=K6S=;O*nF zcNCbgNZc(hV(wk0Lbyh-mSF)c&<5RFrvTqR%cWgFiiDo+?56UkREKyJ{hw{fw51p` z0(i|I_qq5N+&&hx+pC*9yo^cch(YjW-Tx_3cpjbt0zR*-@#)nQDzv2OZeCvSQP2lj zj0vTH1q{%iySlnUjeoRshh|Iy+ti0wKjWm=^QMi9xktffPQdQqpv~{T73dnz4Nw)% zVE`yJ>eF4pClcbWQ(Ks-S|-A?>Cz5n?{bAr;4&s~Bhd4FOb{L0B2KM3QRprrudC;@ zcO8V(Alsjbu32_Yv21mG{Aic^u6pvNVB`=pgHZ4!W&-c?gqp%R$;6WBHrMS(@;;l) zdeelroGI!Y#+?R&;)K=lp11p1s>o;_7M$F^xc<}d%5n|{?ub-HdnBq_8CK_0qL%`{ zl0u+~h}rc$TmqM#OSD5$NM4F~-I0}eWI}UDyt-D7Ip%exKiyp3X@qhI%R8~&U)>X| zB0G0!nH9nTC($GY!%B=Na0%V$%+4F=1YLjWi8GBdM}EPGre^!K8_r=Qq|YlZg_Nz5 zXP~|+3wPI-Wj>IKJzZ84_l9@t+roY4N?pP^EXMl1_MyaT8|zN1YerukgOEH2BhiGv zj-s(r;8(r4P#A20}GK{Jw0O$|$nzX|30td{Qa?OmZT6|LLtS zagli+Lg0h(!z50=ZZAMD;$8*;n@-x-f+};#IJ}=8(WZ=lFLBayK%AL!ym9MyB?C;Y z78++Uj$Y6f;*4|H-E{x{-U+moaM?3pE!MvC^(YY>~IiWZV6n|z)q zcP?pWI2OdYyBNIJ^|}oTBARcyt9+dvzNhc6<;10$iyES%K~EmPiZ#1f-VE(;`0^6?n~P$0*eWbSx#l(2K@RL^kj5Yh-^D1)!v9dGZIc&35yKHjTV0=DkKMNvYjzDa zg+NlVf13p_qL(AO5IC(mERvp5i7z6;rSvx0TM>EddLd6kYVu17S@7e5;EuvISHb_DpY~iE#xp<8@l(!{f9;_XY~=VE zzr{=irj^w0AI{lLCoinupYt1jD;x05md-y(VSU?q+!C8nRb+MD#vuzmcU-ej8J3Sc zJ01xCy}_bE54tv+wtoA54C1ek{}oSdAtr)Q(XUXTWM}yk_HMZQ6?_>cS7k^=nmEueMP;IR}3L}4V!1Do_=?eR1QR~|wBlap) zy|T?0U$*FMYA_)Owz~JO@ivr2kKPRL4{oqAFDR8i%Ra^)b#eKfs2`9sqIaQYI^z~o zHbrXw({Qe72cQlV=~0upsKLkV2TPM`4#v&YC(q+-3a0d_oi}jId6zlTT)bLf)@ue) zIrg<$3WW@*tp-BDtafDg&8YU#>+^wlr^`1a;{g8T4sUk0p2vs}R9h5FaPEpD=@w%y z3$hmD5w@{l3B8VvxJ+|e2pUJ10}Hf+ETd5$7!ZZ9|0=Awn;Y$f|3gr9?n zTSTe*{PE4mbf#Wnu$bP$7`+*bJf>~Gvu{%b*x;EP8K^sjU!JMUObGcLPvslqOAj(p z$;ddn%OOErtWBz8P0_$gX@uMiDAd=uy0R~RMbRs>SP>nM`3rCwc}$2Mgo#y1DtCg} z9Tg|o;r!QiIkeNa@C&2{-t3`rbXj(xKqp&;wlz`mHQIZCvJYK?021wc)aM-;Z`n-N z=q~bLpiI>v-co~GCDJU1k-)6CS46-}^D>qp`5)SHL-0)G-u#eDNX?gr;K`%hYZX6q z_IR;5C%OLXj09n`t(xnHJ)E3rn3FqJ`(<~9*nb%rxB|jGyGPH^=hG-SFz>VK(m>T_ zACQga%6xx5!W^kW_08iJeGT@w;@EW9C{E^_7mMvba)CeIn6|`3^UIi|a>@1zm%-zg#L+gQh(QmOVA#JwF*s3w>$vBJ4FQ&5|{PP}P2N8Qrg%6K&> zAHjyU=A8-0KldNdc35tBcv%=-Nb9ia8nM{Q?NT}FpW!~U|27Ue{rBl^W?#j zfb2v|7}E<<5fqOfhCw2@zRn+?oBSSBsD;17;=_;X{MnK$^Qgl4%o3$JZeN|gL>~R& z5PsvgVNdS7*Ul;8kdqC0?#(G}%dgLoRuy!;aDVgtr5W>&quv>O29Kw8kCgBLV?2^a zPCQW`x6M=|fqv0|(-+8(i!#7bb5kBhA<#ARL=Q3K1fMrE7 zISk~aEMxoXlX#<_B7=E0hH}&s;>I)krTtHYl+j;b>+}A?F=Vi{nU%=aMNGPH#z13~ ziD||U6ZJrH&*{(dKDtj4*KQ)3g#ive1x(HCx_%!j=YZBx9vi|0DFNZ$eXky%;)UB$ zwM>MjjjyFAA!C45I2f$xg-@-nKoo7K%Yu_KU$m$jgN(#}O4HX2`H~;qR9!4uSH}}R zF3J+)-Xz+j+pl}h5=zlLU$mN64*p{a0TuPiNvPoFd66Pht~6EE6eJ0fV}9;PMkCy7 zdYVc4)eH|uSGk(KPaZuYv2n4Cjm;r)qifo0LS>Vp&Bl9xqC-rablTcQJw@^a3c-(R zB+_nNGZ`hosdC+cg_pGFLeOQxO&5(nt-;)V(#X}-+cPGGv`h-43(AOqqA0*d7uE<> zX=C$AI+Y|CpTchm?@zEft$!LCm}fNr9}yvfhIGO-AhEXM-|sKGtiWU4@Xe-9Hqy{I zZ9CD|H~MN*d*kz+tZK+7q?Y01UR*V88y{G|}x?ejApu!lV0+5h(syJB&C zTq-gfFsHGg0PwpD4}gCMn;Z?WNiq<#Es636Pfn~hiBLe{#JWHF&=TCQ{4f5u^?ZL9 zEH`m^looZ0cmC7pNPpiQ-ooc(6-G&?<*?hax>yXEZtHje5d@un(M3}A<91l!{inLV zz2-R{`Y6afBCkDK8vSmvU>n-CWK0{;0y$N01*6N_nBDo-Tyu`{?e(w09=eTl5*Ihc z6gf{VWg0D)`fXuSrA}IJK>tv%75lIM&jQpydSKy<=$xjH+7+iZWH;rw)_OB#jiKr~ zI~(~Z*$G;V&!}kQ$+Kj=`VwAwiVjJ<{%wp>@YYod+n@Zdfs^CgAWO8Z+Inv{E%eF_ z@mlx%yT=2pEuH%(m`tXZYIeE8@~^I7g=H`(daK+SR7YJUtj&Law zA-i2)HJn3FjK$pk=fpq)~at5mH{11}aiPvUbWetP2SyA4zaWzsO zqis&`AYq@FG$h@29YRI3f+(Qu=uF%F`xP#-_JZ*}a*N@GRsj>py4!KGvNz4Xf< zU)zmN@4DoNOQKR$Pe;L3Go5$}(K8UU+JXB7eWs>Zvz2SGA%GomYuUcaS+f z6E2~EYZ)nT;?NiF++XkEVP=-DT77Cqj}0}{E15i?6CE)V^OVf^gR&$x#=yZT?f1SQ zZ5dL`+A3pmRo`1vWvBJjt>MU+gpsg5h4awOS}tp*HS!P}L2m{6@gft#hkAK&(`7w8 zxHvmFm0;H}=lBW=PZ>UaV+LE3G$kW;pwT~ni{aOm*zYl(_zRJD)`5R)xxhyh8uf%z zzNz<}52sYTH5_((@6Eb+BSO}+3_m))`J2b8FhyRkA3twH$NN~m-3P4Tx9t96?#an` z!pF&~S77O8DqYNu_BK)BMg_r~7BKaeBWlT$#1+Q$CTzffi%xYgYZ8bOcSTns0(c4boz^mttJ zs_Z=2v<<1E_|oh=guY{;5-XCxw+><)sw6EPsou9{6yru>@quW9$pPGcIWV&o>@RhL zb2?qQbWmnZj`}OL!5RpJ5ZwIq^oEAFg?Cg1xrv;lNFJM7uOXg@XEH48nWwc zmV?=>0cL5f)_8->xR-pGcsF{^=c%1L@zGnK&Y`OAq zSir6U9-BuobaKO1+)~Bz&=acyJS@;tdj8JKoMjj!PI?UteQ|srA z6rA1lbmwCrbbf&m3thU{ro4q*ZV2lJ31Tifw-&?R}k<5xqJ>3 z{x6H2B6zt$I_X&TLIzHfpzOeK#1|`}{*IY8e95-D ze#Wv}iKZ4Abnz6?`Y$a(>S>-ft|anwd5H+n`PRxOZdw-)NW`?1<0p>=QUuyTWzI z2OoNi{u2Wt0?dI25G>37qh7<$??NlcHyr#zh0g_e2)zv2<5}~BDa_@iBFf2VM?K9? zC!_jL%GY+GOg}P?4^zT3~H(v!U__(Q)aDZ#ftWXwXnk#QMob3N|G+ANo{1rK(4_<#D6uNY zf6zj@Vzj7eG=e^YQw1IbJ?xIssIV>_h!eUii@6!EKuQh*DckkFq`y=Ojs@;=L{l&X_sOXa-yzEe58*5{3$>u>Io2^eO?&Esoa^Nc$ic*gpgD@>?C8)${8_piHPth0)?Kh*aMD%q2 z2%X4;QiW`PKb1$^#8}+$Y`SwBrmP&zG7^h~5pUe+ePR~|$NA|+d;NJ5CFIH@_ZB;2 zUWBp0^4YbQXsWud9o2$v3q}_cn$o3bR6O||IUwUxCl?O1Q<12cD}!hn=PVPR?Sp6! z*Tv9%Ua#O}TH;y9Ur_JhcF|^3vNF!E{U(%yo>vW(_QBx00DT`D20 zSBU+?Hs3>hhC?_zsS&aKvWs7C^XTd&9Lx2{SxjQROYabqm_cBV+N4?A5GW59M}7{W7{?xH@0mxwr!gmyN&HMY?3xM z8>5Z6aT?q2`Tb|!53n;k=j^l3eP6^(WVZl|F@v(vdFq#UNetVap?SCSRf{~`e*b}d zIV0NO+t#_*+P(AaUs&KYPPVyqLLZ?yvELW4%#az$4z*IxNy`iQ#RlZ)F2DhgCHxxH@~`_4N&a@9*v`EG6gu z;ss6V;A#cIN+CY3qCXc@Rr4t!v`tYa0ec~^QuisdW`XfVy7cS7TsG2+nOti(8K+HE zThgdWQ=XZ-zFx?OMu>!8#%X7F0Y++W`RgHoD;8TEpu@<_RH&x8KPIIsp(MHaQ2xoB z+WQ9JlyJCO4Do2`Nh8NMGuMzXJK0S-P^dpt6eMg@g^s`NfAlOx)#vqOaYkz|m>v@R zrzcBC&LfP5lvKP;{!@YVUjj}#WE=Qa zqHnj@%8V6=K&bi={u>#WGWK}Zy8hOgx7jllfv^rxjJI=Uu)YbD3MUS}^OTL(Ejb*y z{jCiKDk-aUa$}IRV6&0DBvz$!eRHl3#7rn*(#oO?NoDQ*eh2)g7{lm+A_zk#78lUk{jyAWn%w(ao+`f0N( z!xWb9ck~H^HiQm0)jd4q;E%!oMimklpWfm`4UD+QgC@E)H@ES9Ml$D46??Vor9X)7 zXk2=R3TcuGM% z01@2(m_*lE()+Zd(L%;Y!H4{L`f+mzl>68*8-R)Yk(kst_I~I#%@`z9lN&QncknW# ztI?oenGt&t5-c`JiGLL^Zk_(?aaPVOki>lviFsFk%;cQ(y14S_7?xX&3)r;>tx#pKk;4=%3+gA=2U_O_+98_>l>F#Kc+210Km6&D$m9J8roL&0}-Pd~9R0CrSC|VfbaxRL7Q#5s$OB zX1ZeNODmPeHODRgD38?X)sjBfR`}{pqPH-@%1CKiMpmpiQhl;1%IHFAe_*YZSACgF zmD$>YwvsfeKEqJDi)o;?L4I{a);&o7 z{^9|?UA(G@)oZ@zrYX#faV5iVZSFbOr^3V!riRbbjXoGcmwTUa&(I+7TOMmC<4xB!+IQ|6L!w{ah1^#l5gKRX`(z9^S}8B<0m-XGgoh=OvYCk&6=e!>NCdo$KYS7$ z&MQ;S@xNSR$^(x51N{QMqjL~{r`&uEJMZKO#kGS6+0ciK%xl*F3BO(4M5#f|uvYU& zaEK@KS4a!Id55;_9(kG{%!!SYmE^)Mj}7S7w=;Ex)#M7lSmn&%9*^iJk(ZP`5;RBo zUW9q$4ss*u|1mAMnH{5Uy4kk;APm@>f!b3#ovNW9)q$jwL@LBexDt&B$U5-t@??5v zi6k1o*$;XRSqV1!O~b=~!mUFXIv_Ao(nQSvJ}wW^r{OP=#V5UZ8trHt*`1?K9xxx^ zb_)$YrD4=!s2-j`JFY=2)leYZHyfaUa$lfPUkp}$(i+jduu13#%DUQ^KEJ}0+7TH} z+jwrk0++&=;OmwsnaS1uF=he>kkBBm?8GkdqEbR6dt?@AnBH=H^$7JHzANAbf)d8q z*rXq#WdrsBMC|y>AaCZ7;`r%$AKBT(MIOC-L!f#L4(vNLF@fyeNgVjT&&JAJfd+fI z<0`iHv#dC3nEd?`)X4Ka&Ua;IW+p|$ytfyi9m2hI#{e=9Ajp9MV10d^IR|EO#bl>( z3uLLtCQEfOh@8;$IOXy#l0~=nbGQSN4niLpwEulp8GCbmlRp^}k3eNYN=&=X-mmpB zwvziwQF{pdo>J@3FHKaoi@fcNo=p0t?+~L9>18F%LU|I0xManPxjJowzem0GloOti z=Qthf%JbbaeE5l(@pj=$ug}ZJVj74pfn4^c))dL#pd4RLq_+Xs=rYQ8t;9{PHq08$ zf046OvSiccGp8F==-WQOk_dH`{@9(NofxrgZr@~36x$8R4f&PERjy@W$P|Ofe!h8T zI_~oj;CAe@KlCk)e@<2KMqd_z@M%Enc1E{}j`6DSraE9fgNu&tVoZ%jbBJf+2kN9y z_AkZ3`Uldl0!K}+Jl!Kbb5!Z!-qT8r$cazk7w00tV6Km|PT7r%$9-^GCOrHJ%?o=^ z6k9?qu37SVpHlg_WA^-QG(8}{3ygf)yV&yeufBiVZfa(Lu9+hY-6$@6GvaV7Oa2j( zRy3A>g%l$ru5i32YD2t!1#GVX^!s7u6NP3f%KGnN#82n?1{tB}Ryc{WLVoxxOG&-Q z92@E|ytqmka=yw-_&mfZOcwhK3mM^NNR#fajCl)xOtVHXf~m^kEQTgXFYdD{5Vrzf z@QehvkB}OGp7)Gpenl>+cF>h&F+-lz%E_SHTZgRN&7h~`xjN9% z#--C)^bOqLN+K{^nrmSENV_XcrC}|r+pPC78zdg(I7+vmwyZu1t4N$}V^uE-YMUWV zh)wk@1~f$kCRyGw)Sm_x>CZQZa-TlOroBHMOC9F}>f&-KDI5E>TH?j8Vy8%c4lF-A zNxz(OzrSsLka`&bZ9!dKLOX*XbU;%)d;>OdZO@ZCyby?#I&a^$79EZ3W$z$=aM>&- z78S3?{BE7EwB7a1g`~3YnC$BSP_T2k)ElfIpzgHRkr@vJF%LBa-!Unb!r5SLqs+{( z6+;7wWd&}+s@z1t?D*@yjAaN1CyGEhN;&HD3d(t9NP9*jUG1)4M24(1bx%7W^2^I} zV*SkZ@uv0Ql?Nx&cpoFspi3~cUPIq{%r}ncIZVn=j5dVgUvT#OrQfZxUDNVaK8v;x zIdQBo>ivQQ**V4dJoH-RRA3CHmF(2OjDOL_tzpRL4Yt|KT2|Y$g|2_nt{EgzI9TFf znt*K4lcU!l43iJKG6 zalUH8A@uQSW?!rwX3rmr%D}hLeA?%SNUF)G9@*gsc5g#>wUG1m5UKgcxm+ySDj}ra z?VDa&bBRXoogGA|; z7{V}I(KxHy@hoqRV}<1lZQ_YeHgoOD^>SA;pyTH18j;uw|$vy=q$I;UYXr+qSG z|2YFxt#Dfyt;o~M&;}*g1uor&CDR9#3$k+{)QhYz$lelkvmfc-jaaR@nlrqdq)63T zWd|cOFFut|E~ebWkYcK2dPJ{e@0!nfAoB+ohQ9KGPd&5sj1ENs1XWr?w8#xB+trol z=6xI_G+_D^Mef6&88fmtTU1hi%6${RMe|hyKpvMb9&Ep89~C+ALe)F+FS>C&?N@1Tg^pkIPCAh9OE664noVdYnsq6!?;eZlgK=#}5_8$`e zUk_wKPf?9ra`)Pqg!*wIzA8RpCE4f#GJwqUoWf<^V6IIe1b33Ksi7!OI)ZT z!LKnJ(Jc>$KT&&NLM1Xs3N-Lou-jG^4(X2(03jJP-ywix>_mN>ZwOM&wm4~2`JMgB z_*|x`@sL|Zh4WBfyciksi2i{be3QEcB-jc*h^j5&-tx@_^l9|_w|g#ct#2Q=%9c@% z6ft}8ABrW^HXlAnyCcExX0Rn$ocmMZ{=jR^)wd-d;z~4|dOVi@K`uSkv(4n1KG?__ zMbA#~NP|Sy(j|~p;?8BXn+U0>_o!z^$?n>Ihd?u6i@d%5h( zXCv>kl%8ZxM1|nT*sYtZP2~mk5Q^;fwFN2t19$oj8no6&u^aBs$`U(sM6m6FO{YrH zgOda&Q|=>l2-<1tlsG9%;hy!R5C_nvV6?eCbOyIoMKdu!_*{-$u7-oMf7X9BEztJo zzKA3MYN%*>eR@(HMAU-h(En(R0Rz9s`SBo{Oo5|DPl|K3?M8pwIdoZl=;19`alIO46 z)Q86EWJ86!b5n^Z-rhvrjaHUVCG*`T8Q6Gssx4XAQK>8JLJM$c8q~&#FzP!$aTVA8 zi@EFQ?>s^M`NGYbi8s1{m^?#TJ0Gh=u}Pub=1rB*)54*aj^>WQNSlR@(Bx4mmWb`E z*{=^*N=WC!KC3S|MzltZXdATj7c$Y0SDW>2zxY8j{4sKU2LPr>v$Sr8w^>Yl2O{{7wxdsR)UCT>&jHz2 z&|0(?7hs-%?Qjc?rcYM_LMlXNBpIV}-~J=y&pTX-??MN6*d2Y>d_IzZdkw_yMhpR#N>N0fOz2_6H9>1G2 z*1*I!ZC8&&@}Uyj7p3-WYh#d#Y2FJZ&Am7ZD#xF1o{tfBife*#Iux~GPg1t0?7!SB z(b6eUz_}S5=GNM2WzTpO&Lbn4gyPKPrFeY@KO8;wj^2JJ`M}#;WA2W=+(hTawaS)a z9YG(VyKvA9)-Pq=hP>%Y41DIj`LTj~Trfp<$@BQ*`Z)L;_8P=lx^nG-WB+MHX{R7# z<+gk0maqTu7-rv~5 z&_I+FCwqX^$o>-&ysZybbAbf$1vVR5bn%OI2gQ4c?%w&1fRWYZSe?k*Rx-4P`mD}o z6IvLN&=A@%@Oq+&aJg>iy|GFDZIc9Qsi}-ku{1d+4#E?T&H;D;<*g~fb142P2y&fv z_6hBJ@n^~p8KWh>&N<%1E4iGKbnL^)c0)MYWlPSw8YC}pxHpQ|5&<*8($OjLQC=tRCweVirq`4P1E!i6bU;FjcN6cwQCo=xN$=;su}!>MW4E-A8#!StQ9!0k4R z8$xsF{wwb2lY4eNwND{B2)dxLW`XN*zoBprHNW&KrM3hMD*Y#5 zXa$;1AAu7omYs&EC9aB{GX3g^X&HMwP~)z8dSe zFvFx%c2TpXbdP@);V$p@ zmXL_?o07w)Cnr|i*{sx1Ba<>zjQp79Pxbk%ppx{I=z(}09b%|Cyp$-Ua85WzcNh${ z-4I(Tv9Da5)sco1`rbVZF^#Z=9Fo=C+^^N<>mI+{=0dHS=+f8L1t%Our?VTsjc527 zVP+8DPE4)2=3ro{u31-=l~(zRz7!%c<(;_7s1(VV4DH;$8UX`>^eJ{P?{$hW!LlkV zQ=PxrMHqjvz>8EhQ-hJl0EY44E<#C0hKOBBGL!{@temU*b&v4$Spxr?2`|DVdY)cF z!@;+1eToF;`C)%2F1$j0kEUlKtfg_(czg$rFTyXvJ&lZ%j(9{s1l?&T_MY65fPhnR zLI)#%i6S)(8+q|a=UPib;$)P%&#V`nzwlJ=pi>WyrKI6XE6?)TPrmi@7zuYFaGy6tn&)=*y0(suBBpS-XUFJ#NwrIO%niDMBL6&GRU9*OhaX zGc^?QjFSmE$ow^$Rn}Kc$1qBe@{iYHzPHMpreW1F`TF7I8=e>rUyXHcu)3zxgIsPl zRJPu(V4vAh#DHA)ywZAIF-refNT|{lBvL9D4JDcHjXMv~=ej>3Q}?VyD7cg({?4(N z;iQzvG}{@bzLEgSI&IR+e z85)#EKTcU~4d!)4g@pJ7e&f%ZC?=Vy@%?*P?mTbK#8vlkLDI-rIL7ULzXQ?}oq?1* z3ado7e;g=A4BHj*(BFbTj@|n^eYOC`u$_Vd(SmOD8!KlN5G5T4o1RWSrT?9hAon2* zN;NA7TA8XTE*86;aD~^=e8`?82aG5%r2>?lby`;3ZA@EyNx%J8$s z=chwY=8r>gRT}i4SI(ml)!#Ib=mBrpIF$+L>s>bl0kkT3ktRJH_Kwk5o?aBtD{^moWjeQnrA6J zAK=bk+w#=(z#}<+x`Tnvno=>!5-i+gFRnyp=E}*D{7vfYd_T=Do0cdV@){150^d;= z;bc{HgJ5x&{UzHf!W5O(38gd-tm0zv{BqSbxYUjpE7CrO#hZT zd2S=;Z=1cyQmyx=_7fTe+H^*Cs-)Co5j^?8#vu08XZ?N%c2&zr(95PngBigr7ix}u zbjkM7i)O|_xvB5(St4lyHnRF$(~ zPUSzNa`cNBqwwev23^eFP2+sgD3zLitvEKW{A)C1IjiB~@Mbc-E`8kf?grmjzLuX7o?rauV`y6I0hYwwx0eS#qiL4R z-k6b*^^&JE>j=PxC#I0tp=T~q2tK~ToS8{xm{<*IIIKkd{bPuCD==4xjU ze!Z(>*n44jfB1DWH<#G9?&|tBw8HN7W)08_t>HMeQHt9YRc;f3~+rzW6ek;l_ zV7ur?q8uF=E#5&};pWQm)z`qm#f$&yB-iRy8eRUr7|P`=;$;M0_F2ypRL9)bw$R4-?Xa0{q@4!z;7??_9VJ@H6$qe)5t)q0>&84{>U8HmJPUXIoURX zp9ZK3a{gjvWax#++1(szBL9rVO$$iHhU!{tl(3JRwFgWGYm5CXk{Lj{mKp42O%Wtu@o(1j|bsY~DTO-Y#a8&Cx~R&%h{#sOE}< zb#OiK)HCoL>Q0PLqKj$=TaqZ4=y8QGOjE7%-C$NjVSQs`=X*m>cm@{WH^?KZNn1go zWeEMjp!NlppjqB&fMTPb!Oh$He3)Kdfu?veX_>iZqRr1niSax>1RL&0vQXXNgE(fh zo`L~aV$9C=lEv8JR6EX|fc-D51P>+1>Fg%s$zq%SL+vk@Cv*_b5w0~p+1n>4NO_z9CbYi3`Aj#SD4EFC;&<hmG2U=3SgFXrQ@ zt`?<}>G1me{a0H^;E?rAAy`VV4V7^H`UNn*{Lfj7tqou5w!=j8`S3UyN0dLU5 zMMxM9l*`4rt49DdWqESmH;pj0r2P{pg-^XpuY;nm&;%B~{{92rzofPQ_^uG$KAo-o zk}>rakeL~DK>F8#CY=Ah1~6$wY5^gjB615fY6>NG_9zjEX!@*~BH9@mac@@$GSzJL z8=`>G>G=qR&Fx`WQ0+H_gmT6&(*4t-Dw4M; zR0D~0#%me*5{rJWMOqU60Mbw=B1tpL$uJt@s;~1sB_5Hs7pbK6`zeRH_Fh7`(OIEr zr8dZ%lob$*hvCYWeYCB2PJbu(R$mbBq8e{X(4Xda3bQ|CuirX% z2Bly@$+V+WdIV_c3Ne+}vDEx1IEyG`h&G?*YO{~~eIg%9Y%`?FE_v>#&=C7zP}<9Z zLw#cLXOQ9Y_8-r~SCw_;bt}w=#x!oy`f&^#q0F6B54GH~5c?rW#(SGX`WxcDAMXqx6cg@aT3Uul+ljRd4H45BE(B?czvBSq!zg( zU1I5R%`q?{5F<}PWR>SJ^{3r+el=N!;*mZpx4tw{M{f)y;*1%PkvFUYyW2 zkx68KBE=T^8nOwdEmXvCot37M{k!A>58!sYT#9bYPz1Efhb@a;1Ew<6Y)_8xh=5iK z)8J(M=>#&0tW710l`=ZwSw6Zsa2t(Qhkm6MZ_mfNs70!f^J<<_o&7xPCnkY$wJ)Ax z=p48hi2h{xsA%ppE^6PfBGsCvWYOBXKdkiDGUr^&l+#UxV!q#zoN7nZ6VH+*EuY^n zI~$Oou`qlWPAuBSMF98HO;fa7#;-@&%9+F1G81f6jOX+n5h~j`_O@hAU7Z~8=%*Vk zg{@wUA)VKC{GO-P&ynm?XULl(#4_&ryE>^-dnAD{xMum+uFR)|`2`9zTs572yoRX3 z7WIpy=5%!d-H>9k-3xOJ%_$X zNAwUbYz9W33PeXer-X*hLN>`+sw%@F;3sZgfl@rp+Nr`#`V7o@fQc{18m+DzQCJ*Oh1B^WXV>titF3I26|)Z}spOf9n6yY1FI2(fKUruGeX z75{i{r-UI8L3M%4_wEF@=jBdE*JR7I)eyXMObEn4RORyLRD`9_ZKP<#ot_c{QM2VZ ztZZ!mwXyuqyiNgoVlQR&pPf&R5x7MA_(#1vrMDgck85S%9k$ zS`UaY@ApE}65$5W&sn;dxM%HLA0VadvoXm6KZ;l@Y*nMsl{udWahLK0#?~ zM_kXJTFDf+9_?=53xncRQgw6ckGJ2@kd5~l!~I*{k*AY>)RvTFz{p3~O^aDx*P|e$ zN=_}52-u^@ypDnB83TC4%m$W(@ryWk%H-Xu-OVWECI7{BnHG{)>Oc_03LR1Bt}*On zh1%PT%WHBS!?;yAXoFB=n>CRmOkcZIs`BjQboG78 zSS`&sQ=mm;h-&T;EA-HhP}E#mVV^y?7H)&fcUZKPQK?AKMPGyY1sv=974@K;XJThP zN4hfG?>Eo-UnFY_fAX9z@n@GEH8h1zb7Id|s{|I_R^`rf}fe{RzC zfqD;jvn7LS*ThfZ+qT&=6+HRg08JD4NP!-{5b2~_EB$F^C}5;Y5)Cq@U7Kc=B%fH0 zVOy^5UdDjrpna5RL3)ScF_jm4?S&t$dgYbNGJ5*+rVwm-g~e6IPpFa-nsx+kZz#N} z5==c-l|K}D%*(gg$tmQx_1^Yk98FOQxjDDPT*Mf6n()=oz3RLQ<}?bNif4&6rm3Ln z^inDVX*SobTnR0ER0$f^)2}}549L;(e^7iHT!1Y6s~;P?RvvxMzj$xa0zjNhf%7n3F%uv_{r6e!MVT3o)R|FHo)TcS;&_EBYOI1_95I7(x^5-ZuZ}^u-dln6`G<)#}IdjOZ(3$Sas! zJribWi5Eixz-?EQTow@<8t@)-d!Jd}Zx;Zs$;$5g4q`-xZ*cHP$^Q)S8L$r`Gm+|I z*pt?rlQv&*_0brrM`}Oy`$0-5P98AHIh9nA1c80F-u^D%-N7^CAv>;-uKwg6kS4b4 zF>Y{Mzo5!QeGs$+dU;>H z6s|5WLrZGJ7??Xmmc3}Ma@n?uYd!&g)qdPJ??WcBu)jpwH!8%FJ;QrsO`(e6Eg* z1hWW%D6lE*mLnJxuGn9>2nD+7sRx`LjY?%`F(5spn*+oVzC|N=^~mJvM;2i3L4o(^ zDsOHwro|3NV|l<*b&i(5sM4>T9wFPu)Jn#N@HsZR+=p$>xAVIgv<%4Q57hf+%L-SV zKRsOMz>2zCcToviSfso6Ny1nrI7_n!Yt13-ktFA>&BB)04wX|`m(ysWD?K)~pYwM4 zu#U+bbGfBHMu=lRs$6<}L>~qFE;CxOFo-YOvolx5C$C4VBBNvGyMQ~f5 zxYA)AHGL!>tNJbc9L18O)WKD)z9dHC>`mmJxvsjiQQq<@w?{}%mqzZxMxGQa=Ya%p z2#R)$aZr;bbMxh`R=%OfkS0sfE>rxYJFb`FpY;_lBF^}H0k7TV-k;EY$HX4dol5eM zKJNz@MtJ6>CAE}gQb9HQJOqD1TwlNUNUOoi{f!1UzI8JnzLHN480B+|Us1O?!nkjq zuqt~7dxS%=;oMeB89r&jj=Il@l|;h9Thaa=DC0gaFmd&38Zr5}GXdz3r^2~Oo5$-3 zwyWMZ@(;n9A7LagEnpc@p_0>NzI+vc$OZ1!LXjW|y>Gxly%$+(UYP`e0b$Gs2~p=4 zK+?J6+UK(s1X^k^0fR@AMGz`}C2@?N!|-6JIkn(wATVb#G2=5~$jsr;#+7`o_P6gl zUJSTx7bKfg4D0Ot)fV*j8|N+~z>SRh6Zinf0V__k%GsGXIT_mV00|(k4=OW z$?Df6@2Q+ZykImxrE095LQp`$PRj4S%U_7Uo?o-^-alfjzsocG+v^BAZ^CdPlJG0m zd75HixFsfDY8j|!qE%eX3wR_S|5kU+S}>JAtD~d8g$)QYrjf7OFDR@uD=3X9Xbw?i ztl@sx$G4g&?UGw-M^D#)i4y}7I^X)wvibRB>jxsy?%hfXF-ieeq zPjFsLtQ<||s&CS#w2RBB>vEKSs< z%Y1^YhJm=j!W`g`gG6k`;AbjkknUHAPtjMTbr^@OXfj-EJ6<{}AJ|#8=(M}K{m~CB z_KRK=kzqHFodE^q%KFG}RkE@$kTQv#@Wn)uOOlq7Dl%lZ?(HyEblx3yXngqzl|LI# z1AeU$p2%rubBm(P9kK3ZF_!oJ9vGrq^P$~044HoUiV+?T!w9-3ybrp7X6OLh?G;TU zC+~IKoweDGY&OL6_{s(#w5KJgi$=L_jl(YQ<$10Pk}uRaMo`j57sazVWhMGJH-b0v z7$)D=yhz{gT|V$!HUq;x4nN-M0oZZTEAiz8-5SbG;HfcV#SxAY1`xn~`TmtLukc)* zmxT9MrY^G$-@n2lOZ1Aw%cPrZFA;*issX!Rae2b}L);;X;wq_-lfGCO@Tx8}S%Qzd z-lv%N$T$uh+EMTg+MuAsAkVeU^wEkE*?rQ1aCR`oRPANVY5G3Dv5 zWpTy4M0)b}YD*}rSA#K!4wFifRm}5L8{x)Q4GjA-#OPobw7`-KRZr!N>)K7~d?_^o zvhzc=eGj)qei8TA7fscVRGawN1sx>MDCyIfl+P36WXDz2JVSyy7zRQ=s(Bzn-9n0S zFzl~`BtIOZ2uR{{vvrxtDsrA3e5gDmEKcMqD5kg*>>vw(81HJ@;!q7H>-jpCc~K1p zCASk>TYXKJ6bzN5Di7SN2Rb}VLHtzlI9pMU1@x0Gy@oJ^ilqbN&$d;Fw4;b-ty;l3 zg*-!cKfs4MStN@6%3n6_;%N3Y9Z<Ai#o;enk&MqUCaV6^=j{LEI77@$YFK%ZL z5HX~pQ7l)a27hP9x)Yz`9fgUm+FqRhmh@RG%R|k1wkXBrOc;m15J>^jR!0jvwAxqm zi-NdHhuB#veBW@3!&Yo`RRuEO9->7Vj!bW2@+z3j^EkCLfCE*vUvU4Tmi2-vgQLf3 zUCg?{%2ZD5oZ#-L9|XWQ6k4!vDAtgFUhbl-1S8kn5uCvuCiu+|kEG;64F``yJNknm zgX;##p5OdS;~^|Xf}|YmO6S-O?a2zsSukkfecP|b4W8U3YiBHBx$C8)9&*BlDGo~F z{)kx`%3tbF%zV0}S!3zhkIyCQy{WEn2w;KIvLqNV+VWhzWU^*YQDQ`O%zF5k{PDiEv$H@yW)`~GH#mr$LDZEr zbcWizg5ovay;0Ph=_%)Bv~;9Odh!D*W28t4X?1uQ7Dz!;!-@V?$C7UwI#9n+x^YGc z+oxVsJ=uJ+4E|Qt1Ut4Qjp2I5ZY|vQRU z&kT~_KSA|3=7us_)v{+ZWr)@JG%{607A6sSuBy{ac35Xf7n>wtBo{@e&n=el;7JUB zagksu1sCCHKx7O{*J9)47Rr`-a7hVl=V|Lz8e~0 z@AceGQ&Ab9a;a@Fx71bG-;j`?tO@YWTk|x|Iy{0IDX!bs4PAX$Pyse$v8?aZbt|SKuxG4NC$nC6(t|LXY zg0b-$!o1e*q!l5>PGBr&teYp2cZast71b+eaKk)u4ibn^k{N9oVuOE~j|6!ai@my%fGt+8C-n9!-}Z z+}B|?enNCraTW5ch+QDbu$NP&C~n&5G2PUv%7xpY;5eez{Zpi8Y#!u?T+a2rBl-^i zI%N_B+_V#-VfImP&LGLo(Wxoi;P)qb^1Gf5XK}w{0HjZJ$$in1N;8Re+=^kENd|9B@8y-W8!l7$FZ{Me<&3nzwg_ ze(4)_N2R49V3H6=V}MlwQOErC4Z2xf&{{9fE3wh2LCGqi%MfUG`NXN=17btyOA!_w z5FVRd$mqovX|yGvI~21w`zAxyd2!N}sweS->_N2D!p&4+8kOlHsk|9{AM@b2yFU5y zTYdoZuU=-XVGNSRq^6XH)N;J4mx%dV9W^M&KQv}G)DHDfND3jtH_ zWPcj}0xdPNzx@ey9qe(7p}JF?I@;lFjlv#EMX4zX z((<(}h=oNhwGq5qQn~2oOJxt$e6DRRxGvPpIc)0z%2nBAP283Su}J&nk}1?9vhmaG zFUaJDKDcLl?O+u$*gOXh4|4IM9GwXNlE2^lTOnTEmlrST%?$@-{eB#gQ@-Yr)Brg|HYN4Ob0i>hCMQH3TAi*)m}j_>Mx z))vV$f?#Vlp!DsA(7B%V^7$SqH&L&F5C;ye8rGA=bBF8-!&U1<=jlf~< zb>7hZZQO7J&lBqp&Bu$mP935pjsS+6_sYMx9y|;T2#8;Cw0<1?hR#xU>mWz$>;cnAD86Ah|^ zG{z%<3)KuaM)|T%KY61~+TjeLUa`zqaDNo3$CO4?;6V@P36*7HT)L*XIE8f@@9+x9 za&UXzc8MOyMT;1jNWAO3DDCD@fp}a%cM%!J+pziQ;G?{zV-gg#;S8FxwjhR+B)7|f zLs$Jz%8lGhoT(8V5;WFZ7U_%8$JS6WSMeyy<*?r0>J=b&X!sZj?JA8e{PLRHf zwGUZG$X!)k?7c0EQn5K?341}X27{gr3pg65V5x$@Dq$4%(@0*V+7Rw}0Or<;+nl`6 z6)|?9v>^=aw=%O0i~@yX*`9XhUFlykOXM(*ZH(SHSm{1{2$=TOGGSfK6iUNk78rkV z7Cqi)rV~F&8xKm%x_#siswm0-j_;GC;nyF`zT-xHCv*sRg*wJ~GZfDF%Vzv&Pt4>K zoIGPJeJYx0>(hI~!O^<+Cg2{ozK?yXrSjlJ$@IYpyHC}}#BP+PPy@ioz zk2P$KD#Q_x=+jsncDi<^_8NdT>BIY~%JJ_^21tA9*WIy0qk|~tL?hmqD;>_z(9+&F zk|ohN<{O|+c8)QmFi$PJ@v#y)8Yxydmg5#$C++UTUBWc~+9f#sb1I&Tad>~4_Q-xh9YXnMQ7vw3>DIrg&+jx1Qx4mO~-0ys>-nz7P`M z(BlhQn?M!{d=5SL?duWV1;0W6JVOIeAn*+~fPU6DG!$nH0C25&Q{Rs1y0l18;KkX! zw;-5dw~80gZvo#qShko_)6dTEaf2=NyCq$RsFq@M_fP}t7 zNb!MxHvDa-_UfT96a94`=72xGg#csTd-VuOEDb#-EGLFdGhfoN70;xwIVaCO8#?58 z%*V&GrUZqZs4LV*5vRzOhk0+kJug=`i9&*eQ)N8sGK+_a5`QCBTi8n40Ve?((ulr` z9K1&%vp)#+88%Ww#o3n!1gX7nV=Rr(gvLN@JXkv7aDC{fK~wNubJBm@uC(fn7opX| z+h2V)8KIAZrUE4f>STRohcR%odUPITg393V)xeo{bLCU^SR^V2DVy6lxafc2CYDsfdhdS4$?YOQc~454-M;}`3+9ie_GsLA6L`NMg3%S z;TQiLIqc{{~I3nX-f~Pt4Cet^}J&3+=(z=Nd-Ig zAx*m5=Iwo_xelHZyCA^%J#~ZEyh0-V$2XD&hqIzenkeW~`F$As!AwBI7w^2eMv8`- z-*^j500!vDGc%&tR#W8oILc07i4&UKJgpeVZzKG z7u7`kj~ab3Pdck}w4PWrUxk5X^%YR4{&Xtsi)oC72~*uvF!EX#*TspF<&%BkNsI9} z-90|GmDTx1%f*prB!jA|;sBsF0XUN+pMcRV2g8xYYiPsa*Eo-|1*{{|nl~`8h23*) zf4mHuxVou>&pKT$$vS(PQ|_;Y?mPAr+d>X}yIaz2Xz0_6 z4Iibp>VqP@d3-E2V6!&ljzknTIUXc44pf;^G^e zU4$?~5c5q>HjEwR#N)!`oV;07eQ?Lhf1bo)-!>N~qlO?uyl=c5!PdvW#7g1eHSepb z?^|jRF>QLuYN4ve)6qF!pfXXnoLqe4SfR#mKvHT&od0i*@A)TrDt6w z9MArbrn3r*Ym1UF?(XjH?(VLE;O-XOEqHK(1_9u#Qs=s`HhDXccIivTs%dTd_U$J)l2b#i}lBwUa`&ijsS z3PndSsmBbzYtLIW?ZusRv61yGfC_ zLwuljEi02yhsjV3vs*Ed5*>oR66&9Cgx$XCb7uq^RgfA2#I)IX&DbJQ{@c0L7Z7J!{A+Wgz# z{H;CDb+cZ_8E$GTtu#v?ksWXnd4piH@7pu4SYZ3e8hbD3*XO#cw}-88{B*YlH~4<1 zujXyn6Tm3DQUta)#5GS2xgF4aQ|u75SraH`Fws^%ef#HoY+JXC$Ww!8gpAI1Uo|bkb|L2v}EpwPijP03Ni%# zi9pemwZ5DSv3W7hEUdfssayAKOe;U6GmA}9MP)|YK(4*Ayp~1~xwD>Q?7C|X z)i+*oir^)n?(>0ZJwvT+z2WBzc( zgqV%e8yi#Q^BR;UCVYoa?ukHC5MT`(AIxZPZ|@sXe*gk{zFr=uTN6)#iF3zhNN0ZG zrcr3;YL-DWh8-x?8s7^=5nf;42^-0;?w3rZj^Q#-X$zEDdh)_GxBuJRUGGJU7Yg5- zMS`js`s0X@NFw--;1l=e@c74RYuWMJtC<2n+d z>6OL@#mSQF9t?5TeZ8@zI1E{Ww3$lpX6~%@3o4j#ydr%rHw$ZtQMw}<5!-3mMcxz@ zvjiMhinDorZ~r0ZTa4yMo^&4JS+N(&vXTQq{Xi@zTm1v8GbdNvC4c4l5CnTK5^DsGXa5OvE$oq84R zSP6twxCWm30Tx6kOk{oWXe4SlbF%x97m;l~^dSh)Ycy!B_6729Pm}t&F(D)2exPk3 z2cU=LA1+N0R>{RY%1tpqM!l{oPO4Kkq9ord!0%{%O8>GQ5xe0%J0RAbZ>iGRy6%G? z#nUmdkHtFj{6)!)3!4r3@OXg#B;x2>w2#m?wU8*xapjQUA3|{|Dg*;lsPuo#8(2#t z>eV<*82khty|`BIxZ>R|8gg=rbDux0)5Tx<|p|--HWt}FRx^gD(NfB9oQ^{0*|$EG^B}onqJ}~ES*gzE6c6Xjz<$dPx2xh zmw_>@t>tjpNGF#2mQCpu9)DZ-Hx|NOaMY8w%~Ctl?0*46xe^p^QtstWJ%NYhx`>cD zqP;agq&OHDHCz)rs$I|ESZt&4W*(!=Af=KV=dYw?9!{@^5vt$L z{lRIm)?Yz0`08=U|ANttEma_{WC+0x*gV$PvuOIG)$@Vs`UHC4t(W91bB+wR=Iz6d z7PnCXD7GKc>C!227z4S-I z<$)&BB0* z1b~cXLlpGfR%Cc!1Ahq&u}HEyd-KSDtB5{-=3gck!eO|+RY%uQ0^rq<(mpcAc)s_~ za5~l4MuF&KnlXh)N~J6eLOro z0H;Yf2;ieM!dE~u*}LBUSnFVH*t(o}F2s>uf{ZUZRV%K^XcC`8^6~L$@9N^3L$2x? zRNX?vNoQ>Q#&`K=Z;t-IOa(pA{l{TaRP8uunl3GqG+HQ8DJ@O(;miQfBPA&MY)49% z_QqXKk0^RJAwygC{sTJ6|DvO5>drGlWmNv?b-%*PhBO_od)F*iFF+5qvIJg0OJcx{ zXKq(5hOz^1mq+Yt?KiFybUXREZ{_LzUnlGqyO~-1rDOF^j(@7TNi$jUS@ySnVk%&Z z>RXoaBzmNd{#P4;F*mB1GLhvfKF2TLO6ZfSyd)BF_h+7Hvh+t8Pv6y#_9@rg0C{Vz z_f8ealJ?}(Me{#D1NLs+H7_hl`z0##>g9%v}(ND5+4RH3Liq^mgUfOMO<=i z=q-0gw=l}4@!1IuJ|NNZ=iXXLF=O;}1k=1{S~BythoU;zj`sMnG+)qw$R1%u`X86O z2ZFpNW*Y}#%KqL;`4Ow7Q&??2_7lb-k{WePGjv^3SKl3>zARlXa7}y3E6s{9UoWl7coJ1ujer(S zhRaCd1z!VOfVHwC_TWlGX zHcMeV%k<1U-3kxUH+%xfdd$tyqH5*XdHLkPV>fbbBVJG-yU%!8{Vy<*QCSZE^dDK}GP9&dGH?L)dgYX~T{3hNxq$p#12DtQ<=6~7&+jl$d$*nTKE56g zXmuvt(9DikjZ%eb7`riztuMa;x3YGmx_XlD+ac;=W*Y&^tGCe4z!{0OSRSg{0tHqQ z?fGw@(xO1Z@W0&eXqQ=kvGG3X5?*Q7g!*i$&f8X5s> zL<7a{^13K#hI7I11yA-FvNHV8gdt=oG22qgB=8&2>9EZLmgRO%5QB)i*(UN~Me=Zj zP-$8SRK-Q&vPT<3f3?$dv2p3mB65UegnND^BIPA-{>YnX7;TO_^O&RJx-0gklE>51 znU9$t0k^{KQDfEaL)6Gb3`7@Adfdxb5qeCmhvtUXQ@ZZw5(wCFD8$5cQiy>HDy``l zoQJ!(>>`f!-8d*=VCz8nwjU#eNpxzOHMY8h+utR|sRS-Jj=5GZ1s&zpSCE2g?t$vd zxc<%J?(=;qV%8lI+uUHSSlQi(~51}#WXm7bcx3eo~M%m=QQ|r1A@dr4=MHUmmc^+ z92Q@7Q7!q(9lbT5Rky?SAkrFKzkTUokvs{4+k}5hrXc_{_Z2Z$TN?N25m8oi```sCP;C!<)kibev$`{)Pn~IsOT{Hyv4NZxEpeQk# z^advYZz^Jh9gqYu2Sl3dIeEu9#V**bLSerdhqYFKdQTl?-nX!T3&=F+hmZIy=VK)mHp}8Y}{@0A_gMT@dE_z2r;+1Vu|i8rp%#T zup|xYSfTsJ?%1b0k>VnqxrT3Zb z#}SlXcAQJFNgDeXNf}65Lq!q#8{4UYUkhZ-$V;g3iRu*4eY49(v5z`t$r)7jA=4#> zjsM>ZfUpj67n9b0-2}Ep{5n^8dlaIdA)wEXe(1XiiDXN)Sy~>L97?qVBsqfdzx|L} zg4WKR0z{d_5$Y2MI6lj~FNa8b_1{p4A+gB@uEd(xB&PS_<+FrN#`q| zEB^Y$%;OdL-#A)YYOARF@1*DJ>l-@V=WY91lCH%-`0yuLbuQG6Io`=<`TW78zjv#R zy0l;$)c=)?!!V1^3gT-CY~C7L5jilI0Au!!`s49l00OPss!PA1ym6)gnX1_&U}4D^ z7X%b1vWxr%z)gLI2Go4DJsx&$5t!HE;`636`fqrKr$?6Kb&H5f-_hgfz$#6c+sc7a zkgx{IvV@YzAA*5Z|Mv3@5(SD3w3JsvhRvRyP!&pG`q9i`zNJ z_)GZ@;<)tw9L}93CSd?hjs@;w^KaBuasHGe8{9bn!cZb7LJcnr<_n3du_MJY?eN6ijUEG)ptWwS5$I!AN@z2E$I6PvmOy))l(j*)VZ|L(Nu~R+kuPmK0etIFq z>C?43yZE{zMmBhTvH)I+2#961@or?X%Hb%G4RmvlIe`P4Jf^ z>$|@st^h_npr(r}O>^2lVZRI|Z_>P+Qi>pMF|GK#Y5f=^$`uCiYcr& z?Q837y|mj}5>pUWN75&-pMhYLAHH%;;n)4($h?HTLzym3f0|}NZ8Kt;+)$h8m*kI3 z7b6$!WL*|ae=9X#TaA>gp<&geoFB1LtRPci{2!S8(^^u9kWy&dc!>DMUyz2vR#9V~ zq!(!I57Yi8%Bwh=AIG8=_wifGX?rG8yM2zyKAp{*q?Ab-+}YlO{hSp+$p(ZL29=h> zbdF<1srSb#4mza6Bg1$L z4Xi=87_|B1Uk*LRUNeYj5KEtojEo9Sh3&wG6hc+lGPZhFlP8888H};W5kSAlKgTRJ9AMkRa&L-T}x2I`DW;RtD71ZJK`A=bjJ&x(c~iU>~4lx(bk>eE+yjnx5sQp<@_YH(krZhDB-% zA&d@PTU%QEo+Np^d_7ngB&+`ncXFTOqgTg1gN$gR_3O*gTMxq!qug#agCL8Z_M1}0 zU!RyCjlr$yrOv;lzG0FIge#y(lXuT?A%?k%{T9omX<+m6jK5k(FotX|t&U_9$@9kG zDbJllyg3RRgh($XJA_)&>iD^}cGiL|D`K0cK}v&M{wK}P)aHS7_D?Z9fxvAP6cvWq zGn9V}Hk)>VqGhaF{vJ~Fd_Bg5s;qe1k-a%#JFqPJe)b4wvl42{O$m^Q7?IU2$kRO>{u+J^3l&Mp>{1kk@&`GpV&W3&Gy zyFu8LZ9~4XSTU5;3Jh{Q{t4Vj+m2sdhd>)RqA}u_6{C?%5ZPZiIKqzj&eE8LHw>0Z ztQ;vPw65pmjHM)oCBA9%2=Sg2VoaD)iDbi;ei&kRiAhQBKid@%(@ESPr4FwtWRv?ZO-MIlk34C>jHpR;6CF;r zI@ToLhx-~EqO_nA>HsATd)mZYH?uWVLw6;9yC*Ty^6{_g4uk0B5~+&Iok>he6eiqk zu3A+18R*nS+I4i}kGsO4%htD$_2rde){zXoLn&ZU>s+*tB6Wu+%7=Lv&-vjf6@y6B zU>`rJ6OoBxY)ztqzyw@XFr?~NoL+g$;of!(+;Y$AW6a~F?7t572bxwIIpoI5n9hW- z>qH0ufi)$@MSOff*a!ap6_QBg99!m&BO0rLPR>N*=!2U9x!$DRX~3bC>L!o{vTNy( z*m@B2YGP4Fml0d@s*Jpk?Yz$oIv9&Nkbv>m7)l5TE;D?`|SB=8c zw!26olZcKY8FO1WVxEBG>ss68H1gN7ABJqbiXNUg85sRx)|Am<4WA6LK=#5_(SH1( zKWLDF{j4&VaU8bYnXv(u(F~!mx;EyJwp_SJC0942x>D&Jd<|n^lQc|!r*LK9Y92c0 z^sU}K*4OT)jCa(IJfVnI;|`~Hjd*;HEVi82=HZh- z+tXRo*z$^W(|z}QFIM2h(g-8OrqTH$)+Yugx0fLoaQvO&U3RRTag$~&NtB3B zAWqJ3`#UtdK0rkq#RDhV)BNyJ#{LYf7mBrosxIfd6IWgdzB&|IpAWfT$Dtri^7n^{ zL5DzKWU$ZHnx9w!Dw?icCa&@3PF;<*NsMVlMQ{k=-6`P(NG=(R3QIMA345NBl#WpT zi@>lGsx9rP*1$vQOog$0ji=QarTjdT^?9vXk~)^B%PyKpNa<@pp|MCy0HX1gitl45 zXC}q~#lC`ck`oar`&pFD_cD^%5y6o_F?dR3jH2$?OVE4ES+CO9_xJ zfuZx5Z@R<_L#!#sPYTe6ay|C2sAw~kwa+-ETwg9o4{rsZdq#jo)x$;%2YA_q|G%5a z;%PeTzpvxt#7=yM2$Ze@%|N^ipqgEZ6V%@2@YewkeDL#AIQoEl-t#bp#x>+1g$m>r zAy2sR>UMD{qe*5Q?S*(ypUV;mQvTm2QAAJ@P%rf44q1xxAHee}`qC}ng(z2hx__FF z0O8`|qU-Pg_;%@~9gE*X069%ZN6yHJeADbsEEvl@AmH?;=cj^2{Kh1K(aDaBjZPmx z%Pg4hDz4s^OIE^kQw03h7vvx@ZcjNy?MIR5xz&1`ps*ICJA?szoZ>zoq-hNTWu3tn zb*J0OGxb_4H&}B$j0UqRf=)LI$IGe#4_R%y3dRb|S>z2u*<@Mcx8Te0p7jzp&n}7W z`ef+OMNkxlZlitfDvqdQyKWzXMArY#)HKG8piKOABc|BFPLw`LkxlM3D^I^f2Jt$F7Byd2{{=KJnBd6$AUhQ605kI-AA5%1?9qWZXe@q|jcP1d-0ST8*YVS1J}a^S8O za0v1bP43|C;ac^mPq-9&1?g5q(V zl*d;XfNexqLc6JEHJ-EqJ%#uyb)n!3puVI1nMIo&6g$W`*mcv^RQwd-;Lu%6=!AZ- z&|N<(Y_#r_Uo4T*=q728!;G)X`ZcG5BKWd7+Uo^R3^-on@C)i0IqX zN^wdzbLdZoS$(lc7Z&a~EM-PbcQl*dL%_(C5_~h6j0?bFrn)-GFtIuep7I>;a|;3B z$e{E>Fq~{TQ7$Ks#~gx)XrNT*T4Al@oiV(NJ*$D6;WG6yOXXJmU*0qgrQ*{>0ezu< z!N{J@5Ri|-(}b>`$-h9c5x~PID%F?u?cZYTBUM9%(jLUDS9^t{6JL_=?ICLHz*RD_ zp|4sk3XaI3|ObsI3E1OaS6c@EtId?*}w!0q(wlou@;%ek|Ol8sbtM63ux zQ`Z1Ycp@A3Vrlyz?bv3QaxaOxeD*JRV1@^kz|j0CakI_{F|x|O-oSX<%vca&d)h@4 zkC$!9@%3pcBr*Hw-anztzTg~^H-{IPD>pbLMGVx>UvHUA>z3$(Qt;tgnrm^S{rw@>20CdQrp4<;ndvVw@$r;u`^0Td;{C|3;uGW1BZ=1# zt$6fvzI1@Lq`6DbfkX6Nu7(mJJxgY7);LbqJo2R2OfIE#6?gsS^rSOr2F`Ncm|kL9 z&oFW#&M){0r09rR*__ncwr9q^Nb^S+qJjY|W3Ma?lT$)kHYMI=N;W-yvbt+C!u!5r z06SzzfsGmy>PWr{*KvO=L0tY~u3~jMu1VtzGu_1k0$XV3S{lS;Uk#vo^uLl$Dyc8I zrTv;_k#J09#z1=5_{|m(gM2oX&>(=2##$vk(7soihs_m5B}*9r&iWmViDW(?LpgOY z$K?MAew@&cpt)j36`mLsQaB2g>MO!$k==V6*rOatqWu%|_epLMOVMxXNs2k@kH4C#pp>eA#o&6u!uj@;YF)U>jV_TN$>>64?rJzk zMNN#Qc|Oc%KHLbDx5a{!${|6uqi&AuB!3Q@aa^3y2hHX$Bxk@R-0MW%`OGX_rZ}(# zJa}=ii>FXP^I~RZ=KFi?XJ*fhKl~7b9NRZHvqEu!Lx6)1NN0L>{<*JNG{QsrIZ5KS0p)cEP{wgfiA+KxmtB;Tw?wA1HD`Sz=Fead`=7 z0`26{E@B~w-Mm-em-g16ohOVYB`9I+M z>w2D%to4f+iBYt6c6SH(#c~PngLH5yBA)KI(b{A9iiRRO2~{_s+}1}4)mlhoKP|fv z#m^4z$|PWdgVD>^@#O^hnTa$O)?dhq&Rw*4VqJf#^Ce*Iy?(9R?KT({Q>MRuF-0(% z)+4~{mXDy5z-kHDwEKBHMS-W{c&`vg6uC|vRD21)ruV~k>M?DNOzlByUP#sS)yPJg z=qPo(909pJ`B%Pl`UpkJEt@g;B*XPNhYzXnVoWsxaTx~IM-W{Dl*lH^Oh@92m#;(1 zUIa6S>57D;LmT!SCOaU9MpRbYPmp|B*ka3;cOd|lLfD!6;HGtO+wA#uy3y5ZEr(hJ4 zB->Ck_(JQVODvhU*lDa>TQJlj@=KQDRNV6~%)mJ<7U&|yU&C1YoJvb7?Vz)R*ZT>e zANWE@NKnR~X31Tpmy+1X8s)Whl5@k|4+jliebr-@P4%E*_ogG@EzitFNU~H_BS3*( zU&GuOSb;lCULL>QgYYeBiT)fddqN+mqaLWoO3N+0oB$ge8D%Am+#F<;`rau)#Y@>m zhHc=S&_^{AsIWvv)0GFP38EUK z=ajHZa5I1wg;dG7UbRn;>e4A)U7+VhJP~#}2L(FhU%MHVX zlPGS)E|^ZCSRi`394PxFPgpRuLw1-)*hHcQi#Pyblfu6%P?C{34XPIg9v3uU%PC0`Z%g+8}uMSTWviO@!{{c0DLFr6o_e_ix8i=+eDFcGQh` z;9)O&V?2~pymmCYiV__`PY;rY)4|mJ3~`t6KhB_tild-pZ`FPw3QUy=8maol++Va6 zhSL65yyXqutlwF1wdENIwRBj!7v|>SP`>uf08up_dAR&Wq1q-laW~sL4wR!|4qkBm zeO->4+oYt^7-#7`#WGk(#bRMo!B;|S?79fyts2!-ucGSD@<4T!hprzZJOll#QpnG! zG8H)|#U;ZuK1!t_1$U+sS7M{rm-*u0_uhqTIm(n(tiwu@-;->j3hqbU+@k8eZQ@x4 zQ~s{e?Cu>6;3K}@DVsC~yv1BoKaRok_d5oPn1NCR&+kWZ(NBRF!Uwq$T(*N*#_&Jx zF{w{dO2_p*hvb;Jj%J>|%m5b1Rh%a?Xc0IoSe_^L@i9Z;!h zqb6OG)>4}2On1a5rW?OQv~&p=@dUi9Fm#~6PODh?ztv$Myl&j)uxfk;bieHB+4 zHgOCVDAm;1*u2}Mn1x9FGcl<|grrY15v&~G=!VJPn zt)vfm?&-APd)Y<|)f&5LH8ep9Oi7rhHgRR6l(hC4tVu^6HgmD27;<&T-)tWjO6s2+ zPFFM~U!eTK#iu0sSpyuNgl#ZrQ2gCknE5=gzq0Oq(SMiOmKIqL=-_2 zYLa*ih+H}w?~{rKLTlGQ>Q^rJu!(H#?MkV-Luz&Qt^3^yzG+5qNQYyIL4sz5LN&1T z%ZDMd!;-0(8%gRI>jIFTS_C0Rd6Ce}(HS`_ORwf-mDN=!ZbWQtFm)~HiTt%xl3;l! z7Fl zW7Jc{(mHk|uAmZX3w#xQD3#Q2(ke2zm~QW_Y*(g2DMB0!;d+>9pcY zRyhI5rL|bVc>weJIjdIG^Dy!!>=K6>{VxU0 z3AN0O-X^O|-;emo7^<#*@D`26!V=>VhZy|w!ayW7+9xQ$fcT@$D|v(orF+`C9ca_* zEA=-=s-$*~CejF{qCKOT{@Z91NC5(8(SQe6AhnYE+tv?nEmkz`AlX-A8P@3P+vI4z zbJP7V?2$vIr`m{rJ(+`arq%Is=Zy?4Z6fzMjK*&H&G-^(yPFipG3yR;$*BE?mMVyq zWxrheNJ3Y6nixO@gG%}-GEo@`YM>V#P87T+^}L%5kZSdnl-Y;}v|jbW$gc)y3Vyo7 zVFr%E%+t4i5Qlim!FO7u8sa&PnuYfbo;K1#EwuDxgu^|Xo{@q>)o2K0J4!Txte#yq z2U$zn+d=w{*fokPBdcs-^(v?}Vumcs^eAsbIH|H4ZFAf|Vbv|VSC#-v<4<+NhG&Fe}I64Oh_e1b=+X-B|CcV3b>cb%xG1nwh&br z3Tg#+(S^p#Unh_uHQH)77}nVR_OxL`i;1dGeN&wz5JNOZn1ro749s4)fi-fu`oVgA z83S^6wnU<=_aeDgvfM$e?ogGnZb`!Prc{&YLJ#bdLsBuKPxylvJt=s%r_oM!<>f9I z*5+(TX@aCz!*|v|>i3&@eckE$zYS5QX|Or6M5Y}RhyX_XKYzi_4x|zxu$!$0TG0^h z1q4vEWw`9um5;v}FG>D_Nc9EJ8&&K6`m1=GvLxJrI2{`@NiZ0AjRDmoGF-&<%tQa> z+CEgBVfff{Kt1F`7})kMo_f8Dl=TCjzLI`9YC(@Cpz!!0aK?D)8QBtl#i>DO$6g%m znFcb-zJh1}A>Btt>S#`6_4YjqKMs8{U2l=U7Q&`4km4e=&sTev23iG*hKx z3e4x?6fTDN2TU;Xd5k@m(h7m$kSTuN%);h&sw+p-W_r(wvXrFIU3M8G$yWwdjSK!+ z{7!qJ2L71td?ZayNYA?;OjTB+V_b(?$~euN+}1OaL;#DcYkxVBKZ1~;M^7-K@Y zbVzp*bD6wXCf8(n$1xHJ+K^Dj9+@3Px5l`iW!)HoRu8PEnAmb|m5HAmB`*^!k!iod z6D&MxTDm7@>8p#Mg3&I$G(YB_8%_7(mh!+$la~V{9S$}Q`c?4_|L+BW3#CHdK>C?4 z+N3whUP-^o%hdw|QvB4JNo5OAgQYlI7@eM*S=T=u`IS;-(|7O2mm@;gOodqxL4E2l z8RWPMCMQ0iTW~x8OM2B=orzvDTMSIHIW7cQ!K~?xSCpaP6#|H5HRVL2GhxD~J|-5Q zLf-ivoc=uQWRj(lGf7wV0HU-g4S?hmpR~Mp!AhaNvFV6Uw171t@>@BK}^hE(?l2I&j2%I#(dU`H7|3QCI zavv&dkrTK1I-ER98*MI8{lH5`X3}qv00w7yj}mXwmJB?P%6|Ok8|q1lIq~)wybS5c zed6{q#{byp8UUBGYm60~E}kihCQx_igrEP*6Ky~gO=AoN5d^-!5@r_Ku10&KCA3^w zmS9uh7LV+ugnR@h<`46bZZ)Z5!TDbT)4_u0jX*juYCHzeAiit`PfWSKR$q$(&58{x zL-Q(^qOEJrMY&y8!|hrE`2oRiYij{Ks`-n>%x6rd-`n^p(TDURLF z%N|QIuHS0O@Ew{B)1rB7D~wW(|FsFPoul%6+NX6$XVDnHSDt$5{dno!Tln?a&I#Tc zWq?Q0F|O87ZPmCDeIn)X>ymlGBJK_e^1tG-zkA)%2wCee)=j@)afifIsCcLi0slS% zYyt1}riM@r3s!|-`U^K@QKWL1#G3U?Cg${!;6;$!#SbKe8HjSNFMMwIKOQ>LBIuEk z3>>}02C!hGi~2Ip95W?SIv%S?+uLJgA;Q9LV&Mau;k7MsP>{z-XQAX8`_EUHyXAm;6j zNM?sj;G;>=Zk>cr>b-$Q4f~uSWAW`nIMVw5QtP3`>f0xG|G!@3+ASnrPmY#lrJlp3 zQf`~yicpdnk?OL}M)y!zjl@I}h_ofk93lj~R}7pes#?2lnKW@`D-g}E1Kw5@E>@=& zazUkbxB7)-cXhLlG+{k=?^+Q|#frzbxoltyXb&m}5&H52%*$(ED^JgE6Z}Y<^IHiX5KD>g{**Y{^Tfyg*yDe0M4?`Ae8odfuVX zToO>L*m{ckU#X|iPb4zNfCTFDX-!S}r4%fhZYXb`hxVZMBogbjZC8P9Pmx_;5xMvB zxT8*=K9_(vAX2dd&JU4W@=AHwv?>V#YOOzBwS1$rQ>0$E%f4}fnRo?N=Q!RdBSOnF zZAsMR*?OogIO_vs=k((D`iS>;>PL3!qaRYfy9;$)If{vi6*(LJyL^AVw)}Vck8Os9 z?wwF-j*&4{Dx|`dhDO-sPBidF1W0D46ra)Ez5Q=dHVIlvfG7$<6fyv~$ue;NZR8pd zKrFaFxuYKPj1Azau1r5(La3V?{QN%NMS(%_{=C$?1I)(B7^t!W83f+` zGX#nh`%89bVaY2MzWMVZoD7Z!Cjnx~-bUM&+%@mHq3Y)&zFH4EW6qk!gadG1g@{*^ zDRSkXC^h?u;!l+=$qY@+2eGYsu^X5r&@q&0ip&g-(|v!-LK>4ZUZ`xRsd zGMHe8K9?!L>WJ{(X+Wi*`(ag1Q04pnVPfwk!wVVtU77VstHGdL-u>K_HkvYwA*ww5 z$~?tEW9@f3tZNo*4Z+-BnQCj%9oyH-qEI7+>}n4drEbF(wTMzD)xv$JMCR5}AY_tO|R05w>FBw}JlncJ)N=yst&qhd7j_rd} zVsG#MF8OotC&YO%^HP7Z)F7RE2r4<#DY7!I;a(Inx-HyiKknN>q)edk++~qJDA6zB zs$lNQp&h)V?d*0OHdm#s7@<<`rS5zz-4*}->g-pjv%-jvu9P)&`prfA3iZ?_9@#mf ztCF#AcZnss(NN*(fy@2D|JCVy&Y)Ouh?gC61<72)yw#qm;zvRA`}>^_jS9s>8W$nk zDjo=a9yglVxi&`!{?fRSFFUjV+rP}s16y$Fdl5G>1_rCr1bH|*OY(0%SOh52{M(B| z2j6Fwp(TR z4Qw&!PgtQHDNPB+sq-^p3piU8uGS@HqYHVu;+_O^d&B`}rB0vAtEXG=;|g|2yR#us zI=%BWj?IsVqt~=j-F^f#GhqWNw)X4}Y(MP!)@Hv!Tz>E~qU6`D0D`Ej`Yfk8r3Zv) z``EDj_!HCm4HtkR+z=8RwLtXt6u);JLrgg&e2#9{Ea}MdAJaEpJBiV`+8K%Hq$4Zr z3Fxc8wNYD2jcp!0j%Vi@syA#gu?ia>xq-gg>wJRs zQWh}Jw%-4>DPoi`;*}zBR-UhniLT>Gs`T5GV>swKq#24~*ErjZX3F$s&E>|L;X#*8 z4QY#W-fUGbsj%JzGtno+*a?vL74LrgjLCpqB#cYjGSmJO#x!=L!o3(XB(oakes`rH z*3)1(Q3eYorL_Tu!N@}^w$=Z)L^VFuWq3WD5KGtSarIf|QlHQHmB5rSXZ5fi9I_iXNN{g^Qo( zDTS7fgyY`F(q+G}@u?Qpbnw;GZAD|5X673YODeU*BwboG&S;yz_so8!Hx(aao*8&q z^;rHpyZ@41$~D8vrB}H!F+%rZX#qXth4CGM%dvTN(OoS<4Ydoq$l?8hQ6V9Zw=AZ8 z);B!X&4yYXD8|95nUL0X{`n;h3bRb$V}8*@ZTGom*qZKK`W!}_ege?bk8 zIbVc^L3d9_}9Phg$9l&(x{EGZxX16)_45{N6I9KADm_ zg+6d*@M;_3$l-ISUJL(w>kIz#0@N5S2;mw1c~?h*p^WwVK~dR~h(?Tfj4Y-FsIeLndm01EKi zxdf&Ja!v(#!XJh$!1e}MlCJJv303FJT4EJE*IH+u_Ov~XDV6DJxX;1w?|I07Cv2j> z^gO|t=H*{K-#dzg_$f`u@0*1H$34JYRDO%OmzG_yKX3!Ax4K>qMaAB42uGyj-M7S? zT*dM&*PoB$*Ioktd*?lW%Ov_C90^74y@z&28~$e}VjOl4-^N|FfrT;NhmHS6ERab3 zo-h8k1%!;fa3ELUjOQp|hIi-fiSVBK{KVs;#~oT?JJLAC_gY{LMHl%&W<+pmy5pOR zDOhDXDEGU*FY^=%7uC0dvfrm2k%(dwd<`DhhMSX=GomHNi6Lf=K6bKbMtYdCn=72UMTC zX=gTh1YL$0_L zJjQlI&k{deiDo?pAM|~X=bqMSvx{emROcp6RFw-UxW;rgWrY3`W|R*w2Q>&$>9XzG zXPc>x8(Rl5^bcE}r*@~g2#`zurb6YCn5wb;?v;Yfxllz`h?^6yF|_m*MpMMwhT5NM zW!$r`G^|%moGQ(hWF!XGj$0kUV@8?p*Pgv+mS`CwEZwl@CIih@9Z%EJ;uWMcI+>Sy zqn`m2!LiUNls_US#Ts2-vAs%1BAxysESWVtcyC$rW?1S3p(Si4#oG$2#fC_Z=bUH^ zB(1OB*Ks;c04)yD$K8DG7W8yfYqnD4q#!BFSM=%``UjI2DxjB*67xnQz4#931tfb8 zgQ8wSjlMwWkP#ygC6Ah$AIyRa3hBQNgwbk{bfM9_lcQusBfI|k<@1cXKLMPcWl?|( zb_!_0JAC{a1`HKt9@e5?U;U{IKF0-C0NoKq%Ab!t6Pf-^5bXLvK&oIO-ZK!~tB!CE zo9ZL*hJ|_IMzRMYq51$O+tdo^iX_f?O)v2MhGdw*z}y`Y@C07-ss}XJTFy(kn|-rA zHSXHn42Yl0l3^wLr4zkSHJq7Af4BqEbNNY(dFj@+QRK{nL8r0@n?utVc>m1X^Krrd zxN|9P5h6n4Fw!>#2aDX|4B!@Rz4tWwch~_~s-@fMfjj8mS# zm%^5Ws6%yHL>wRP06bX!c7b!S~D8?<@q@Ekk z9R8RMCZmff(gFW^pQ1mg+A&{V1>+%mX@}l~!M)`o^ps*6BrP?@!R-^S7IPmE<$GiQ zw?^S~L9=%W@m5`0a!NPj%;`NTd$PK>(}8`aL?YI0-TJ%X3sVhqfoX(dDY3%m3b}hr zRsl09CpW*(;HtQ*o8tPuZ*`^3=TuR&;i0Z@$?!>ZUZTCc-?A-hgkmkbaPHkHmC0~k z#+i@&M(%lanpxpUpiCztgrP~ZE;WjiFiA53qZ-1N=F?%EbW4~>!w>yGjOHr@C>REh zM+J}-5KARm$7M2xJmOVr+tEKKT*uoXaCSrGSUzjHuPWGl{%LD156hI>-Rt*0m&~g$ zB!1_1?*dFPIK#IDr_{@(og>(2PnPjzfsz~=Qjz)`p{0`$L)(<;r$NsrS?hU;_Y+R& z7vtiVzk69_jh~GW1MAf$ykG~#V0_H+lF04k-NTe=k1Y0mX4*a=SC%i#_xHYL3PanROHgsEHOz*`oJ z7MDmvzNYFnn4T4Uq~sem1C}uQbq^G!;!U=Kt89W|NgRvx@}pLbj43~9m~?zsmUk81 zWm6tzd;$G9jfW7~s`NBr=ncotpVxwmfB*cBp1k>o`){sx0TB{>V5EY$HDJJh!&3!` zK3~E|n3_Z)+Zxhg!{Tsy7)EwHGU>ZtA6Z5G9|ysSF99=%qF2?ZO8#D6y*^z>qJY_+k?AEvX5*Gr z)bAll)gyLfB=X?}Jz7u3{Tu$YQWjDqPzwT;f`@8y{8jrI#~nP8<3qFPMd79M8|dxq z{w)NmZ{36faEELP{qoej#@M6tA_AgNSi_;00marP@1mnCWv{kwD(`d9?GGSK$~`p| zreEB-=0mc5l(DK8SNeO36Zr<8-klFuqdF`0gPdH@}lW&uaL&!2|m52SP?tAms&L4sO; z6*8i1&XH1N-k9v8;H;=5M827T+AH1I1k8gR;du&2Ft%g_DZ{$zp5I|(^Y!HTQ+N;Y z$g>f{fEac65?79Q)DuS37jzY^B|j2@e&H*PRuB&V_*hlGBAAacW*hW_tliN-wInvAku2c)ecZ)a_>cC9vR&x8~QO&&T zJZQmO(**e680U%XIc@WHQ0pN@txm8O{U)(`2?d&^tnj0qTTLO-aG2MGw38?JJpGf@ zyulu`aEp58Ut_YoU~#UgRe$R->XZLgcwLet$j+U&Cp)&Ro5SKm!rlIMWVF(cObTg= z#-4DC36>l6KSEu;s#poj;2~w+l#?G4PK!iuUp5U{bdjUo(I^6;ct_SuDL^ z49x{m;y+U2pO>oluOlEL)AP^Q1u3) zmZ$z;NEgoDn>RHO3*R}Lfm=3y(AC6XA> zAev1po#fzW?uPvNzGtSKvnF#uY}4NIvG!oSS~#$LJbxKC{`9a=ZjP2Gm5+~)Fe12u ztLNX;=l`b8$D(fn%5l|F)-2-A{Q3JR=ld0fa~}2yH^AJ1y4#x|UtYxjd2~qX5?iYx zWPom?Y*n_Ig=@`$m&A|zU1pR)@$TY}SHC{z)7{Om-T6j}Ti0lOUrL1M^AU2O*!$0$ zB$yBExj>nq$7A4D1dxpXWldZGH>8butKKe)^|+P zT1J(-_03)nn(;AM^xG2AiC`Y43`Q#O#eP4#3TGjtofBscBr->aZ>K7O{Z2n5ei%_R z^h(fHV6&58k@S~=!eq%NUA|lF?8fe;VSFz~*d!X7Tx=ywCqekgeQa*MC_n7^gtg~W zk1trGQqBWyl9n~$DIG!V)zSFfCpDhu2E4%f^8MrC5iFkNnvt1QZX2k zIN812UI~A|lktScqoKF4NkZq+qz+mqRMc1;^1|tfzUx(XR@_y6C(VFBXxV0Z&xG$F zX3NkXNHpex+#k#?nwZf8(@#aZpR=$v`xj`0 zKA>3dUDP=A7tze$!f39>iyw!3p?nT8kAK~`J>P>>pHlEkWWwKH%N6?ONqh12(=!)k zr9w2m@Y`aO-Wv@aC2 z7&2ULQEOk7*}R&T$1FQZPzY~ALS5qXhyA~(`kV|~wB^ANpDsIRH_wS7ddHKn+l2kW zs#q=x$;X)aCk=Rp9`nlKqhUh8asJwP=QD-K;h#BiIQS_*BSyaB{`o(sJg^M{WD)op zIQIq#83+5#N(+PNB zE-4c5Jjwv{J7yRU0CRo;(rPfRQwK-@c^|G16=Env|J$jm%I^XJyK$+VOQ4JGo{|5k zFj@rImvh#9aV{jK0Uyt9*F0Ohx`sR&`}yx?kqC#e{V^SW*ozo!clk!<=H`YOYye*M zXA<(iPf=x<@UJW6uR-U3=>!{QZ|8gwYP&kSz;m3gx}Gm-igDA&}bMLzgFCBH2 zbop&3R_n(MW#Uf|!sZXrWr8Uyo@=v+B7v%?*Ug_;ikRuMQbG=_Ye`egyCF(dws{I) z##2bmu6l;L98!cE{JNm_rfCI~o!;@0x;bXSVO(#58*dqYw)C~htm5YkRp84pZ#mAN zp%v3m#@11s=NMg(Qt{pRaiC=COhxx(Fh{w+i+(=qm)68ZtwkxXcah1>`NuHS>o<(e zymj$7t%?|1ZjG@;K|3z|2~}Q3vWtt z&vYq=UC+@r`dYH!OfJb=7iMfQw}NJ-U|J-jAlik>%Df#%Pv97xnp0Bq7j+L->`!9r zv={D$d9-wS%9)yZx=k&8K3!rc1q=5FCvhw-Ubv6+F5N%`9WW3GRf|iggo%FDfngDU zrxVZeV0}j^yP`Q^K}DV0UN3eI3Q# zI1nZB28oke*hxJnH*DO$8l5}9{*sN=9|Oc$gOqh^egH}AfG5u+2T6_R?~{MBk&MAS z5dA*o5etZyfXQGqE>5KBPT8Qnsn~b582bb8{<4Y;o5vX3=MF=9ABE=*z|2aL_@ud5 z14K4lZoj=40|#eQ63ER3RP2CQ>Fu%Zt^fR-b-IFVf5)VSG!5=kyk*@vaEiA!-5r5R zWN}mfcECe0yw8czEO?LaqGy01$0XbUWt_(*t`G3bcfY;*0`xyVKup`(;VM@7c)3kJqRpH zjvZ+FKO4rl2KBC4?Q1aL_`KWdk+lF;3P~v=! z<0Z^TWNrTy7v7)6{?&fdhv1c~<66cF_nNX$WKJB5Q02N}P2Ey{m0E+-Y%R25+yH?| z4n1wqhdGGAPLp!Ei5M=-P;Z0yB1^p#1^Msb=B-WEl_;zD`JsW~f$~rxAO6T8?6$9} z!qhk3op4?!uNplKBLS5G z2`2kh``6#QN_kV~9up!*07HbY1N{%Kr#?QjtERu3+dzgKU`97Ez&1pN+2pvkrdkaB zw=6OU50|{+&41p;f3tO|0W8h8+Cx%$Xo-{C z?R$^$pD~xyJ5FPqo|JH4w!&(R`#4ub!CfFa+`ox~=0gW`Pj&cqeWT)!`!3tMm6A$J$e@3uqf`3z;&aTgE#dzALuq6NVx^8rAA+D2_qLqWx7V%Z9`0 ztmP@y;BKt%ox*YvvYno#SMX4ITaw|=Lk+J1Y(Yr&H$ z9gbC%BB%YmSDP=+UAe%(^a#;xN=3h9>GBv$iJ&S0l@_BIY&j|s(I21Dz7-N$E^cw? zo#^5|G*i1`kI$4OH4TZ&g7%Ig`)_+JaXxy96l!p;nad8v#Cs6;qw)l-{QQf*&jEEY zz%A{F7h4&&=pzgyYa3{u9sEE*o!@+PU+ZtTAsMgwQIWmu4%UPOX;qU(rh|Qb5fXxw zSGWTWbEfhAK5^LZp6rqS(t^rkOQa7`ybRW$i60m5aUp>v=V&#>7ZFD!Q~UUQP=vLB zdFsn^>Qmc}At4@T+m&dZSaCc`Pyl7rJENsB{$E^Hr zzaH<~j+Vo;@-g@8jp!RUof=boi#{a-soFl4ckh;^g+rM{-&fr}*_kK)1V(sDaMV?b zj=rmmeOf(>!;wbGx&Q@Vzeb-oR9bHx-i|YTFBIqNN1a222(+`?$~vZhySPTB4PQdPTgX$KB1z50FjooU1ZPa) zAUHd-ZUobhib*hz$TmCFM;zqP&{rTlCw&&6tSsyKIE$issoa;tJ4eH!4}YXe)Jtf5 z`r~&Abw;(V8B^W9bwPkNW12MRZ@Fr-bS`&Ri{gj;C!+Y2X`5&<@BLZ1Y zIQJoYXTtDtMh`wSso%f2qPYI1EkFzc$;*kA=kc3z_Esh6)rqpVm4WZdRmPeH;iL3U zA9`wrPmqpui1#HgDNSnncfn#Hd)9V$HXbG7x+<<`76CrarT8p@=JK++sW>XGM^2@k zFK`JdvnvZeb8Vke#q`7mkb5)2HL|k9?dMpRVq@|?(3lo_=`={|SxRy&Ey?Jd=Y;}V=gmr!7QHjDD4elQK)#pK&Xrjryw=-v z`a$vtgnNrVSfh|OF1rSeLA)V0F%dBs-9T-W$3F6YrtT6O@7Yf8Lb8E^duk9xL*2MQXx?eQsKv;6Z< z`4DCM`(2mAhgj371nezeuhhR7<~#ZO2nwK7z(=TbU{^RpSbl0>I6E4q25$4QH=yklSDY?ifm0ZgxkTPqMl zFtnTWU*kKc{+~ZdnYZ)NI5`{7F0YOYvqSy)NglfAo9TCH$_2Xv{LvYh;>1exm`k9&S9egYk+78973H{ zQ+S)n2Iolo5z0b9wd3idSagWtI$Bllr@YZB0c{xh5W8-i?Py^#pXJK2JE~ksyX7+K zM1;@R_fZh6ntibN3IyT!D0;M8@tNj|_{Fn~vAHCz^NgP?L#|fhUrbDqmey6TkHw$Fy*;(GlqRldrhrhHf-nn|P3K1o+A| zH%WZLi#QSW?8#CwpV#6Nd}n3P5{Vsq!yTH6ZOJu!j&`8@28_;GijtM+;zN9yvLbWJ zA)o4VFeEVf$u4Y;g4%XWz*tZUUJv#ZOwyZCFEM(ATwX=n3vKGMS*FiisKU$ZA8FN4 zePce6ZSb`Bebcq9Q;9YkpOV#syf-Isyt9y*Nd7@ZIc_shkkUA%#r%mx0gr>!Ox=6Z z?>Yop&JMErK48CQI6B-j9^l?M4)l^cUdl#QD0=1O9SW!`|bFJp`DihmrWmv5m z6@{rAgAzjwcHeu?eV|r<_wKBYBZ1ne>k;Hnt~Lzx^(2YD4$A-%;SVbS;OiuIA)C>u z`*CU7|8=8?9NED`KX1nRqb}jMxqE_-?>hrtkhXj~g@k1wDvZBd^z)SITWKCjc^Zvs zI0PbF&Mv1qJPo{lZf=~ZEL?CzaxvB+a%F-$hqer$z#0ghDCMmSd})6g1G1xh zN@qvMfR$%#_r-#5VZ)ZR!iR;Eli=UxYF$n&Zo@zM%NzCwMT#{Cbv7n{XAPUm?svqc zK$Ob#sy+1MGRZ0yqF2Z$M>1V{*~vu*+72`=U{+LA{aKPeR{8cLYgd@*Fd}Xc*$}=P z$RhHf#*waQ;{Af%ZbCd2-=>b__|3UZ@R?TD*ueA=fUN6${!vdSph$>z4C|OPh!)o`h8{X_^*;9w<3A1g3Anm} zgRvZIYoJ*2x(GIrF`~2V4B8YS9Rw;+rIi^T1Xg=xTZ!4GE}`E`zS6N zuf|dfiTiX3nyZPjK@;If%$GSSsYKle+ixBen5r`|Y1oD^4`1WtyHEF>0Vc$k(IHbN zp;Y~(rZ1@pxNPxp#2QH1&JFLFoR40|+Z%)gYRvMKpIjbm`4VF^cwoGTdmO&xX3CU^T$FRwuhr-S*z zQjVU6nVtUTBQHz2+P{?nK@nQo!Tf!4qMuu6&+A2=`U5He*&e5k!2ug7UgJonfca8)&`h1}#7D zs9yR5W+*+p%#KTk^h;i<;zwsqRwXzA%Pb0fytWEtxA-tEN-92 zTOZ^eW+o!K{w8OJ6Cz?uxqN48O@H5)6XVjUHD{$|kNyqP$yC!}GcWcuX4et#8z-yB zoW~Y+ZYeyaDZdM$3;02fhEUj=!DG3Tqm#_)9Im1ITuVEvu7AD+Bk3Pel@w!_kIPO= zp|0_C;F*-S>a+g!OCDH3`CA#8^BA)0+!$Czio+x#jMz3-G|(05}~ z@Z&QGrNg|4>a1r8g7o4AU008ixyJ9!B&J#a9V=>GYS~6e{c?K`9hhd>tF95_)9UPD z8uXkNSZ%@fGoG@~pHV%w7Ho5^u^J(DR8Rf(dos489v&V_6P1RpYsju^Zjy_{wRp!0h8KD6#sHQ9e7dI^We^@V-42tr*c>i! z7skI7-(c{}>SI+QF~wj=#ca!+!ba&bd19Tb8~>5O>OvzcI_Vd*NI5+XSyJ&fhS6C~ zsv41C6QS@49ggh{M=C&50{DCx}?s9X0nXQ5}qy z->Waq^HJq=5h+~ooLK?#z~2LGL$Z6E_6aCr89cD*0^g}gI_3p6mxokE;a8UcR! zb3aohOETNU>#@DQ3v6FS{2s6_WIBt0%M>v2{io$dbIJE?=2&69WcSZuXf@L$$ILl# zA^KO}VxtN)?Q>lZfq)#FUq~|M%xrgc@9@wYzZ<5V4=t+>Ee>B+AxJ-dd>~0oZgCGJ7On+!9r`f5N?+F{8)&`24Qb zY^jd+7dA|-l?{{%Qfm|%@JsH@Z1tAK%E-R<4vOZ~`YMJxgQd2*5P-UVrOwsQbwzV+@$&N5L*_p55 z|MJlu-B9kD8wYh94+s~^R;j(4O;!W`85Hk~Gg@e0 zmie));&u_He!*Z@O~oGIt5{l}&uf;}FKgj5DQ)aD^46DW%V2cm!|jYj<1T_aay2z& z54;)cr9?h{!T(@VtM@P@QJ<}Q3l`!Im%43EpfXhFQ=oQXs;B8`!w}SQ4Xo6F68`kW z7?x4S#d$3Ef6q%%Gh#=+O2p{_cbFcfr^iw8HstLDi|&qK-P+#jLfH-v;9NbNc!&OO$ll+1}LXR%~=mS2m9!$up0hjeykPvvn(ANUCbCS;L? zNFjiqh;M_n6CRKa`gEC2)3teVR5&d)Bm^^dxG>YKRvDbyLVj`D= z0ostWTWH#MFDp>|X2n6PUk+7`w9l;mH|%&Nh6Bl&m^Axh%4@O|zQ6nlCr{lB-`O%P z$i5T&=D204CW|O|+w=uMk+KW_9?yPwwFYWQV&QU;d+#$JWs8c6n*Z3? z1x!u#8$ZE&OxMBmdgCdoZEQOBh3==l^$rykF=xs{Ig7@l!hP%yn-es;(HPVGHR+Ca z*iGW5`XS<@QY62qrmsf}t5wn+O}daw1oEi(DC{_I#g$P`^%S*|l-Pz@BOR7BH1tZj z)b*6L_sH;b@e}jR7=zhz0+PzJp5I+NlvXW5EbF`;V18!lwzK7@4-;0Z(mlw_5ExP0 zP4^w%Oe6D>Fu>FXx*oC5$sJp-ZH9ky8m`nE=k+YURGZnF`&uF%CayWQlA6k|CFwYj z_SamrkpscaOAEGsiE3xELja<#cNe8o_lp#&~HYdHQ{h2}0 zn-!H8taM8(@Lt&-E)@Gu8~xg&@rCL?$r#OL9g zA;i4%>{qgL_Q>GfBLSPklH?r-L$vE#YqF!Ym~8p!d(AHyLmLtnmzmKiF(y^iql{eC z7l~23_@K$S+W)@ZMl27FyHK{}q*$ao=E%NjrbP+?EO1OxA z176wmR;aOT?Gf3&XdX57%X^7|&(wfP;qv);5>cs1>PFlPwfYllbvZ;aw7Wtrlikel z^p1FA7hpjGu>Jd(3ikg}W^$l?r|xFPHW$<@aiFw2pM3sy{Nb={DXcGJ3N!k`yA-z} z1#7K;aMNkpJXKx%_(`zx24+WmyMNXIN;i3Ihb$`bs$iP+-^<@fVDq0<%;)!15n^P? z=-1%w%8M$ozsT*B5j*_g^NadXW7(887!-E2EV8!%G5xVYE3b^P^gaSMLG?06UiDn# z*7|#EQHg*wC^Hhht;6fWMUZ6gg&ax9|G(HOV-%Q*9Tzg6TM5iV`2SWz4COA39s9lM zP&wYn_#s+UzR*uLpGb`okgHpWJD>jee^+)tNfFMyZy3|BTj@-&Y*g(a!s^M6L1*Os zdOtf9Htb%f{Y}d>bVOV{U83!m_)kJyQX2@Kot;%WW3H2&p*cZ8%VB7XGoKl4M#QqE ziSFxfNn=WaV4QI1!1tp9tK9l3EX?tjbjhK$_8C06B!QDsyrBz-ej*JH4J@VPDkj1G zLYOU+|3f)U)}O{@(DJaY?E=JE>D{^-+6+APY*o;Te4jT#RWeh|tFX9y*d+EG4^B<| z_$NQTuoTuHi!e>*%ApcHkw}BjQ4tolW~7DMc0P)*2I);xId)%h_%&8F5j!hAq=XisxQ2jBM(INNNP z%@$e{RN;Is?YB~!&f7Cm%D(Wn)%|0g$d7?r?{xJO zb;zxHNqL#z0UUATY>43ZW(RzzE>*_CHa-R%2e*6wddn@;k%c1de7b|d3$=hX??mJlt5Uejg$flRvWt;!6w3M*r4`P{ zlnj#J-m~IUH)R79wPMIM`oWLo=bKgiQ>M*&yMToB^psKWIG%Vl%weP`GXdT#2fBMV zu$KyDeembfP5D!CV9#6*)XYR*-z}jA@LI+^A9(!)Odm}x{Dp~XtAi()F)PSHwfcY# z7r2!k*3^5%_B|ejjUnb+z8JyL_alt~RLb}e^J;0Zj8OC!JioE{C*`wNO)`@5!|{wOLPdR+%6{*VG~GDOO5N5r3+tl9(nH zkse-7co8^Fb}=dSJE=;OG>8n!G?vGS!G|- z3$=$g_|&W==Y-n((46AqTo451cza$>e*mE2q-QpiT`Yx)7525LFl^Y#4!A4*NB0*u3Iu}1fI9z zO<_e7GfrTP%MN#5M5!my@AaL|KR`RFtDql`3~~(0vew9+JX%o#nQCS9jgSSW9rp zs3U_a;(_5@iMw?m0r_{bf8I5chNUcB0p%p{Ls8vw=|x(j$KfeE6LfcqqvF0}jAb22 zqsnn}Ep2)$tx{TmJRIeIzC4`Bw6G+I9i@l~Uv6@cLS{D{;@5Eyc3Z2O8mJGpODE-BIL2blMqSG2LhtOmvbaZqx%Pe-6{mBJuxh2 zJlTg+1T4F7=(=0!o*yHj9y@`~6_6>>B3iV@c8QL3fmJ%sJVGW ze@oy*Z=cG^CB4`eK5b8^V9lIBe7hol3kEg;kaLjIwVT$MenHH;`PtEz3h3V@GyZ>_ z3xX;A?d>kbV+E4EwDECi4`GVSTdVWe%&t3klfNdk7=K*5;gT|{!@7gM$Vm;0GdT(m zr#q2ZmT`Z$=cwOCNkxU{Ch{7`&T{RKb1R> zm)a(5dfZ>+tQ?#-A+kC&sG5lz`p^|lo#qtw@L3@48;rp(u(hb@%@-}rG1L)*xU9bH zYZ4dKY~v}YCry1iN`S6JD_j-ZoV%8Dh%G2tj8R{R9q}*?r$(bxY@4}s>FSLqzc|FY zJMEfy<}0lH;iafN`eXumd2@b~2whiv*(Yy$dlK{tOCmS~stvJi+($>hh*C8@YX6a0bbN^nn%*YVLxKV%io}!oq@?aa zq1>QscrWrhYAT4GEsKNr0~#z!_F0x9E@do~r0avq?-Wx=*m{@uO~in@*@{1tmsSr65UFG03M zv-j4owbp>de$H1g-)uBtnG;F4cq1&&?!d+Ky;_}av&v#j?$d|3OcA$^P-lt;q+!P0 zFs>NuXb8c||7!t6=d~hU^G=wtwaz19JANiem`8Lg(m{qz8rL}d%`7^ECVZtO4-I#5 z+2%gx#K|s+_`llb0GtwyhM#?HB-Ui+slor5oGyBv{`18~X5#YZGMoVV)75hiell|n zH$hUfrpHr+n*A?tk7soP^?d@!rLNe;*ttkP_(~h~_pUW{l?w}H3%KXHx0qc<(Ecnq z*g96ta>p#&j*{6VbbKXHjI}-l@X33DUe)nNmTj60(L|L|7@vy+jxwJg&ahHs|BXxC z9QZe}rP(@&YckV+$JSL&U@m3u9Ly|fy=i>EI*-%d`F9>YGKIFI)*OTPyz1^iRbBhQ zlWc^N52c%hitr;hV|em(%f~8rqEyT*b&yFXlI2%!TG$EhIkbXCP@8v3z)oB5ypVq# zaktKnVz_Y=!l2E|k`G5)fQ3W`_OHzy0RpRaOb|)*3ImwZlV?;$ZuWara|vA~V%ir@ zQex^MbYojvYeJH1k;1NNCAeU=0V9h>*)v?G5l`RpwpOPcBzc%D^&kwrGs=(;s=te- zKZU@;4*v>Ke%C7g%#T^fc%R2Oh~Q-RF=-N5+zDm$Ygnxdp3sd_4a;c zbWQ=Siem}cK}5eP$*Ip%6JrNe-`6}E{%)sXLPc>|)eT9;aub4KXr~wAJo`_YCSDF( z>c3QN3o76Y?Bt6b5`#do6(WeVx$E3LUnLR>ykhANUA=FpIwc4ci490N6FY4x%NFkm zM{wKk1fjeC9(<=0QQDmv&oXDm$MFGO|fy_yE*}rsXVS?<8jhCITVYh10#8H=S7u6G=|6Hvjh(Tq^6uT=BSj%m>{6uOI37B`@4AX(x{r*f__ z4BllATtIEJPEkf#r`krXk4x}^8KIJll70t?H5MAI zA>}5QJOM+p5&_6#| zs2pxj~d@<>V6C|mlm1+Nxsf8{>^cl$29$eJN_G%@ZHM0~Abbz%laCjQg3zmrj zUp5LkZ?R3=JKBZ-tC7>^{T={M(ZWXzVJyiNsx$`J4M$VCnrSj=&*T7!$b*m1Koigp zc|6-N#N>w(Ks4~%Yxidp^%xih9(W#gQGU`z?vPAd$HWH=2lR}1bPT;Z_kLA?<1ZDE z$L}|9<(wm$Y*XZ<;H0Lk4QH-+&92S( zOdqg)&Zf+YF=C$M0Re&%tJcObBx5jA-GhA8I3#=ag0wo!=o3YLZUdnjD?rZhMZkRr zgmVpUl#1c{2mOSIT@ira0|q|zMvhmx+t2uCcmF->gb<~Xvu`bg>4?|!gsHW7;Vesi z+VhQ>wdG}2^%G*^_1r34;P}6?;ccI|t?90*KJ|+zXb*`}r%fJzl1g*In%k6opDeYI z(qhF3_u|?HD1^7rM$}3#WWuy!p|M793E_!sPdL=dF1cYoyfsB5(J=82)SvX~bnUG+ zf2Sb5UrlH1MGey)G*qZaRjm*{YBE-p3|OA!yHAN5x>y3Lp<4Wu({IEMmI zvVUdY*ZJsC+mc>!^9q?#z=ZrJxk+;u3nKlF>=956aUa*Ttx+;SFK5J0=pJoGeQ*B#fPoA zdI}t_?Z&5Y5b5dDAG2X{0@>g2_)yF4qK}PpMoZnTsK2HeUMGA)+iz))+7DM}Ra9?K zqf|oLwzzim8u*MOEIH#~Uny~k_n5T3L3682e-&y~MqMUJ$~F$=Kr2l~ti#UxT-8L2 zoH~}s{mLymiNX<&cXU~h?42*ox!5ba<(8m1CH?ee{*Ye~$~%jskvNc1U2VtxCN!VN z1d6e8(GxZ+u{Ws+mn*fwp-mbSmg+pi+9`erD#tc=E-=rcC2z&g9d%JVmmUzO`bEfU z)gu~?n(Guk$CEwJsX0qfF$LsfS343lAKJ_Oe-zU!Yzo6cIKf&Ff8=rCO z)=J2y0TSJ|-;Gk|Hd59!26K%I5J(N^R`+*r!$oecPRCrfQ9T1@cj9c01t!2w<|PUQr?_X zXUdXN@$5%K3HG(AfG%`!#=xfv7nDWlE|@isE7eN&mVd5kW>r2WV?*3k0g->`N+>S1s zrqzX#7h|uS0OYc)m`^bLG%_haK5x@)`NGqX>*64&F>R~EXxErlUHl*!QTP>BmLP{r zCKp*%g&N-wPKuA$rD;MyebS^dYD7 zC7(q^T?KZ0K@(ne4P3>6%|PkXIIaP$zF?hS`a)50I_vWs?L(%aqWX&&x&ul*qZ~v- zNImU|ux@6DR6Gkr)^!8R1~Z+ilU_hMRif{T@D0%$>KJoOd-SDhQm|;$y{xglmMBJBRD3L_v45q*E8of zV_N8{@BS>0r6{z_e<>x^jBBmy1I5%?Bhps3lu~?am6#YG$U-$u)oUwA^@8-NvBh{j&FCaD6pvh*J zt=Zyz{*nX9({EK#JRmff;~Vd}%qAzBGDIxe7Pa08$yp1MKa&}?;=c}$H0U`kb0%VB zdcD=OsuH5^6JtHe5!kn8`fZP*rL!pC?)r`G{$yaC$2lM?+CsiH4}U$MU!5(DVo)WU z{&4#e^#qi4Kex=Xs4Oj-btUX^&#&?#&-H|agootOw#Gsd}2?u`{U zBih)Vmyvh|{`{Bh;5*iOE4>~P$3)P#_A_5(Hn%pp{mlUwAFxPPVK?6C54(Adi;P76 zZEW-(KEmt5yvbW0rp(t@DDU#&;lD67pqd4Oez}$?w@Ob+#I_~cVP%Q1c&cd*7;{b# zUny!1hjnxuInd4BgXCo2aT#yb@kxxA-)w?GyzKx0}OzS4cEl1Zi57SS##rY3Jn zvgi5!QAiIep(Iks=5=HSET;(K@r$1}&N284(Ka$s<*n0G#k zZDU+-@`F4I3E**K301YcvRiF{9`zl+6+ErWB=e7#iA4We_Hc^bdI*SkShm&?>MwPK zqVNPsWD|>pxG?Q0S*j;t2nuWzlS6%)U^0A9F%-I5i51zOhGDz?;At&;DRQG zSf}@FddKJsI=>^^F_sjhxL0A}1>mKk%M@yM5bTWgq>gCh>vv`ckTJhCYB`@XAW7YB zmPvrdY6j5G)9O*!Za#tudbsCUk9?ZS4=z~NaY=p);qF3YxXu|Gg_EF>bCH`GCmQJ| zwr61y(W(kdw<%wyQ{u6&GH4(BY+^WrnCA?LBA5S48br1K6J!5RVkDXW4~Hq05lyG* zRM&MTiL7n~f$Ix`OFp4)>4bvF&KFRrb3hxfmy9PST+Z&PBgQX|vY{e!Bfi zu$Xm!s2@#N<-6j^omOH!o zW+K>=wh!+BHrdvWj>MCrqlojXO6Lmr*xzpqX8C3vHMYB?&O*|QzO8Z2r6Zmf+ofmi zQ5GLYq9YtPTz`ABz!<2J%=x57mL4#&c`wh4YF?5jAp70l-2;NV|J8DqRIK6~__O%= zJkG<#JqDMqBE`)F?uKZop!ensF>QG%*l_apv0)wuW?XRuVS|~+)-xIQ1tES6vXSoC z(*p1IgNlOgJVLk614jCf09Fz}j=l6L>UYec`yKw{)}v7jX0{^Y!Q)Hfe_$G5EB%A- z9^fK%xYq^e<^oC!nK+5tMB21&jLYw+0)S(_wd?2ZpDVmPH=Vlwqv@<-^6a)CjJvy2 z+}$be?oiy_io3hJI}~?!ch>^N-3k==piun0|HVnTX-G(VvERM+nwe+Xw*^qd1-uA; z#Qv1Efu|*m*|cnt;-RXhxp2}*lK;cp*WYSvUc*P4&jHd2+5pFeWLF#N{W6RsR!S81 zZW_=}Q(!JPL4TpxhgDLxVwIr?H#R>rNFF1XC|mqYz@@c78z}Ci4N;Y)-XIR*(~@L2 zsmt8w7~^xs;mew5w;hnUqo4=Ft(1+*QV+!-3yww1Hso9!C}HR$^vA7_XLB?-oC5Q`V>a5dBA zijk5_=TP6$!#jpXjidB8m*qi(pg2t~5F;X*l#CIEsfM^#JugnFd}&+?%@u3ThH8*S zV4j|u&$+P3=B_z7ILv8@2u4Ktvw}cvfJn-@qFUZplW3dcki;t0WgLC-A2TJ=5qz=$MMx0V#TuJ$_|&G-QEa!-U?C zxHP>9y|OnKT)`Yk)EINA+?uqlZAXa-iY{4E*mWrDZtLf#(XU*d4QKO>{E5t{j*|i~ zxDZ-3%^Z@AN~)C#(w6L-FR4|EOxX(59_i(yWw9dl-(%s7P7^QJ-@BzLb1lDsLrnUy z7>2$6bzOKT)@YiYxX;>RT+^*o(e11ynyfl~b0zs;bzW*;eyPOE#a*Ebko9J<@v0=B z)3n`!zBw?PA@qpttmtUuZyq#?sY&mz1vEhPl6Id&11n3mzAN7}#8{}p8PhbqLI(nZ zj^d06*{;T^UAX{3wl8pj_##6L@-ct)@*(j1)fMlV^CU96=`ivo>jV?)Jv+A@mY#5q zj_qFI$y=K{`?`Xch`DhE0Tyd2^2nervfX-mU}|GrH-b7nqs?GfR$nl`1B9*)krL!j zKDr;cfNXn9(l7xD_$cHK>Zf9s-31vT+P4S+lW*^p(e22<3#L+qxRy5l#S;jWvMS93 z?f3DA;^Xa1_}kdx*}{Lp_`A%{zsk=f0wjrz29fvAQO=ar(5UTlC*6X)8Ft?>$mO^m zQeK?=fe^iJYTGHW))D@EV~B`Gn6JM%AgaQT`xduE(TNV=V$bgfnUH6l6~40UUMbf8 zt78*kh_yige75+qJn?S7)(TWz5PEjF_ZBKv=y0d=i)o)LgWf;dx_Dwy5S9q69C}{->Na0)H(gzA#YoDXA+)@1A z{&3VcG??^gmYgh}wHjcab^B>$A!oIHG7@`~ZFZH~GP^VDRjc;!(EhNpHILoks6xIL zuNCNs`Wn7toi#6#uvG zQJNH`f}VJhGh;?8Om&l6OhGncCXjk@h=R5>c+?G#9cJj1`-qBb17ePzSdU`akjvkqHR_iLH0_6}98)Le>bw(;;n zSafxC=Q{q=G>Loj1tavylz%Nc-~AOnwyV|!c|goa&>x@Q#$m(t)EssC2BfCneKsDohb@>FW{)$*`()mN23e>VJna zAMy2w&wov$Llf8N3)3}^Ne*!Cb?86XIWSD4twfnS4`>K8&ZSLubF3#`+)Kw<%S-tb zs)rZlk-A9ErPyxKLj188k;OuwO>Wn{GnN3gj>DbFr{L5$(63dvjHBEU5=)X%Q; zswd+%e$u5A5wo2Nm#&uSMbp{(rrtHiKP)FPJGRHF&^4F_H}Y6soqgO6DiiafJhKVn z8jp1#doX78QJzbo(F->;E!`wkAE)YQ@DHHPA+>g~+oY?t&t!9+xJTsgnXaR`q0p)! z>A9u?Ge7w!z<=cdAlCw4`CjXcjEpd~l%t1Q)S11!7j1c0R0xY)T}<{Gim)1mQ^@_j zo#T%V;`W1qxUS;B@SWEv5WB@rZI48R)i*Re0D&+fM;PksftMLcp|H{6x>3OJ$cXr3 zeBi%ZQKA9_3h#87CUa+ZXXjuxxh*KxiJo5MDRxqfdvCGRzpLB6Hy{&Dc7WUkWRd% z#Q>Dz(*4`RgM_w_L!(Ze4X;}dCQf!1#n|)ZJ^R4M6)kfI#p$DM+mw)#6vncN^)OIZ zU~Rn&`?eMM`t+;T^CHRCS)c&C?(Xjlg=yTs+qtj67*T#eq`rag^@m(4F_Bc*v}X%E zdX0_BBC8KrwKEym;_xmV5@v?!8El0&Tc~zKH z-nui6n0 zYIXs+V9N(V&Aza*zS#d~oIypS+nlMxxizlp5LN>PCWV}a1dNyg72&(YI38XZ{eZnr z=|rzghfLQR19f@<9-X`O&eQRPJ2NR*99!e2hz>GTThT0(vu?@y219J)pn^u9F5?R* z{ybOq+s);%1UCI^SS!yWIpKxnc-5N+V1NU z?NL?LdG`0oA=`~HgCqa<>FXrG>VglP7vuD!yQ*C{amoCo|NqX1KsA6}YQ_s)9QZ2-s-y zUr7L`>kyE{KTkj31^^RU93IxkZ6xU}>gO$L7t?zRM5q{C<4y$;IgkXfTzE*s5ES-* zf$Gztpxx)qYijNrpV_!y>9gWutw202D}B$r@v`s=FgI*3LXh<4D?sFxDP{_AAoDYIpGMFH#@Tv*58Y6toSVC@*}=FjMuW zdL%VAdxt}6gH%QCmNH5}j#{jYLP>cz?_Q(gRvEF|F}XV)Oo{G;|E~RstUS(AbEQLS z^=AB^yth%UF~9DDJ!4UcIPQ_0WTl_1LBD}-nQf@^bYkgj*H3b;=Ic@%+%~E>97UMR z6kZ(264(utaxm-WS&6d7jXLxXzAwMwyio19JhqsaJ-*g*6Q0*k__X|(yn07mvuoZ2 z`fCRHB1r?^*pgY#xd@XyRU{+t6bwRB3F#hnXxuF%(&2bUk}j~j6H;I|*8K&LwHtU; zY(r6>aI=`Dyo3(~h?+couRL(i`Ts)%hE)RZOVl41MIfL^3i!L%mXMTx=%q8ho*f8! z1K$1(M{dC2e{%=?)>vWeBo)6dQ>Vi3#`((p( z83A`2_>5)tAm%As^$HCfzIPNh_4q`7z7GTruYAOP9__se27ElzyqyKUv1GjggY-{4 zbO$6I2p*gNdjY6<4l4=+{=0LVE#?&=83p1XB5cB%VLpEweG+%aGA!qg+C%!XPKndf z5?`FHa9TD5FBpa9i+Y=vHr5Ff&8-QHED4z@h&5K7iWNQ_iwt%^g|mY! zT?7B$zDfGnu{9HWen_HCk%kQv=^{QPu3CN>w*Jqc3uC_F?Qw-y(=k3u$*&U7xe()> zcBD``5*8v7FG%dr(q~rbC?bwhX;X#8+gt9#H{PHWMCTjNrFrXbjPgR!5m?KTDE;o z!)-zjg)IiZrcznohswCeoOeHi$zL8g!jn8xCzjj3%f`aBAnVl{>b0VdfMNI88jBbB z9N(_6!|F1D0xh!SV_^v=*cjGR(z7e(YH06IrW|b2lVasB#dBR%FGJFdw)D>Xg&bT` z9#z91IH$~*{I&5t^bgi>R#6;GWd`W^LcmNV*J;h|= zkdTGc(Ov0*&d%U=K7bwwbd})AdxQaiT;L!7T~bcGU)0K3^PZg8mt?mGRyZ|7g&dH) z0<_XXR4Yoc*nR4y_f%g@*8k!ue*u=yA?8eI=p5Y+im76>`*79I1-_Z8v%Z{$* z5{#&*gInTI4stvtzc)LWeMYS*UtqUd$GH-u@Wb2ySQ=Zbl>}FXX z=66v6x6DizK`0F>!-gSETGMO%Y1+a{^y%-?to!)ZzZE4{ zWjjTBeWnS6YC3o7uzzj6Sy)$A+IGa~)6sRVLcm6s$xZffTs*W{;J0vT;27wcfiRU` z7Cf->5e5|B2?z;bg=MWd!G9lZ478Iij*ig20tV(tp$MTHpGe+ z`r=pKIzCfF9APqfcLg+%;S*mF6ANjmmHg|zI}PN|Z~h&?OXT7_jfMTE*IKc&%kzn} zao6F$n|Pn)^RfXf2-qIyEtI~wSdEt(m!WB$#|?M$@aCg9r8a1AJv0L(8}!%NEh^vZ_`+i%B2-t_c|2(DL7^oAr%}6DRbs)W{mAC2;8}&-nq0j}U49 zQ^P`MZ?|Y13&6E6JlM{%MjL$gtH(e;>0WV%X?TTnUR9=08o|$8?*PtP#hln8@w972 zwRopSOlAQM3V~@M3##nqL!NxFNPRvLXo;N5JKs1~@zN|kpIfK1HPlY(Vp_TGuU`-b z*h_l;vlySk3?HgONL0%rLB{&mi4MKr@RebE-#bRtH5`XFxc3Hjm6ZpaFkc-rL+c zJuaUk-CZv@!2YDS!Y&QM7n{^#D=i** z^NnIfc5JTmKOL^pW}u$NDt7zr3{!lr23v~p1hEpEgo?wi7i<;cb$xs}2>GmO>(TRN zJ}Y-OI$U}#B|NWCj$b9cG5x1Bb_xiSVPIL0XV6b&et?g7dK&!srxaA8oG5F4-Sid} zR9^3wZR&$L0o0SyrxDzrc&UZ^L{In{J5qXsIZSMgCsHh$U--Z_P*A1`GxQ$*#tU^g zN_@9`#4q^wy@BufU(EM5&Ciol%{%dUFWw&uvzxt3lKEfB<;UD=;N*XPYnpK5q)d-M za630a+JU`XMaXZ$laiKm-a9h&l(cnpeC5T{d&>i0*IxcWiqA1eDyLQ1Bdymaau`Il zDN3)fzfvqZRKt3I7k{MluWRDUH@_U549s9){Iqxceg@bMVejtk904MT8|^P>;Du-0 zvy);#DUlZe4nU`3P4L*Kuig03zxk{l{cVg?Y>zlPKsqB@yW|3dd5{%fg4t=_v|`82 zH&ZW{c+!A>-~gfyAR^AvXFdU-19&aHN*M*)A3f&9F%mGczxM!FHGsR1rLTt1wXPd- z>K9qa%%z;^R1^W$W^_bo)@c3~eYM45f0Z3VR2oy-mo^yVIs?^GLhq z^qPMO^m0#NV=wfxRW6P3+zY0N>GV0W6|eFbeoj;*nYCb*fXG0I$WiO^&6N*wkdqn( z!X}cZhD>#9A-gA{mLqbdX|d5XOchk2o+G<%J|W|wc8C=aL7MRa}*Zj(ngiBX&1he_(q8>N)2l(<=C zd;@(oFI4R(U)-d?8P$yCGoL%d9sxP^ndoF%0sk#S9W0ypEyz6qVc^oUq3e&NJ>{#) zkXJ_A5ZT18_Zy<&KiBr=V@R}{_W-^`@p&&Nh$bw|(ik8{Gj$vcZHY@^xgqvdr+9;$>;hb1*Q^r2_-4%!c3K_eJ8 z5L#i^wgOYxXa80)&o%r_`HYfHR!?Lo*~mGHL;5g+R>61Qq-VLIv) z{}(YBxY>4t1XcqAiE5=~MFCrpVGS;a>>Z!*9glb${>3(fzt7`F6{Av0O2=Z;+R$ec z_K7NN`C9H_s3a;HSlxJN6)uNb5I+}+@t}oBFSU0cC{Bw=P+5d>lT>2PTEa=`1}!_b z&~ts|Kh6O@!IC21`RU;y#*L6)=+Or-1p@cg+gqMq!+$iA0id`X19)dyt78am^f02j zCMGI7&7Yw~{S|3pI_0l_~l(*&krvO<6R@DLcE_S5ugT(mP0DaQYHInyKbaN&Q_ zMBbamX*aBEGIrSu;vQSVqnb3_95@9%fdfd8T|T$`A(H`VC?}v|vyOaTT-M{5yilDH zSWYDx4HR{7<^dLQC!v)5<3kWXDT?w)7T@~y_+o^{U9pJEXxW%}b6^k3#_kB=sG5kz z*Wf*zUvAfZzu@d*bB;3?ti_ua4P)LJ=bdzgI_V1xU>wKrsybP_2{fkj$%`X=Zw~m< zd7SsTG%Og>rg0XMtPN00=EO#zVEM}T>-NtJh?LH@`K+Bw1qzRdlDSJK3Q{S>;Z#Dp z3N-&oR2&Q^JZfh~&c7YADw@$3A@IpjlapJ~{nL3Oi-hF*$L)O`OGQ147N=2^ls;Gv z35RQ)N1OK!0z;OjMv(d{5?Pr#HqGuG;ty@q#Qqa)V{}QJTkN4q9|!2b(L#rwwOjr#vVw2h z%_S4WLVMcL94lLqj9#r!JP0pKQSmcm<5~AYX~T>)6b;`C)cE=;mBlw1nhliHAdW-T z>BdzT5SI1JXv(C7%vb4j0`M+irs|L#ZL0bETe@Ww#Zuz79Mbjp(Iq8lG-P z8xz9?=>iMA>;4uc2ZQQCXmWui+eMohT7&^3b!%lIc{Z@}|N2}o$Fn6RKDzB$ZIYx` z5iP^n;d=G=jI5_|Bz-iEGPN6v`c%mlNwT(1G(nIZ2{23u}Zx zI~kg5PP!g`?=Xpn?NPa?a@~apHr!;xF*&0^z#?>2d)#->hO}aCepN)yKUUs2Y1-1z zj1Dgnn!E+++V$hE4}j)-?qBDL2OFt5F#K^F0*Df%{huVl?+=*c&Z9?16alZ-Ja}eK z-rm`T2k!xe0wZ?KK8^0CctFz%kiG_Vib-w^Y#m!}LRyR4t?xzvn}?^cUvlpWxHM?x z+Ck^*3<~{7x&=xVZzQjpiT4*^X1>~WCT^pD=cu%Ha8e0DirFsxr>(mUfEtg5L9iLuH&IDi!13xXh z2Zt{Rx)jg#RX@-|LSsnYyV10~Yzz99fy(6k>!PItcOL-yN<}bln~sP(WmRtF9l)E3 zLn&2va)^T95 z7>xM(T-VgMn^bNeCSXex;d)?$X+PB{oJ^9#stEMi?EI*k|F%PHhBSO`wPRt!u%xT| z+nx)LzKZy-U;K1CtOJt{P%g%fJ74^0w?a1cMd~->*(Glm5C3`@?b*NEqDiS@v!OOV zDGMFI~#*FxZm36a+D=vB--NDCeaI{A zPvWLhYr;-YY&tm+1HpmPy|z3AO-1c9@I|zSE0+|_db;0L?mrm85P8C< zw@NfCk9|h#hhJ|YGm-)IZtQ~!wCI9?5tyYWX&XCq@OSr7cL*&_fBX|N&pp`oOOh9l*GO}WwM&HQj$ksC$Xs0`CU{l1by#TK} z5F3sBE^ONN`#(n+kP`*oP+)_X_p!#yiNEYSu(Xee3?F^JKmmQM_8vX6_XYYQaT0A^ zy}hM)Pnpty&23SzYwv8tNJayyok4{xaC$0vo-c16R>G^dSK#2!DZ*Aj?8-&doq(kT zo^M)q<&j|9%S*pet4R8=%n90;GdYv}?JT{at92p3<o|o(o%C3~BP1P9cm0ygLJ4th*1S^kqoKXL#F&wI|MIo( zk15DRD!>3>9i}T5GfmPJ2t+o^yvq=l96?Ge{Q9+jmSIU|ajSLDH(Yt?-|{RrD=pop34(oTP&Ku5w-5`66~i z>#vz}e~;L9(sq}{AtRng(E`#7oTDLzh8DIUUMFkC5s%s=kOOWXRuma3RsfI7#$&on?fIUeGr= zFlrEaOUAf%qlOe#bHx`9O|fax&T4!wNJS(YOspb_RZ99U$69FcRHN&zhQJKLa*p z85WT#Nq5q;CiGFHPm75CO2%pKkeD5H2PK6iWamqR}Uw+o+IPh9OA zT3OI#rZm9FL#l9XA5&SJe^Ms6M<8p*#e_%Z?7@Ygr5_6TUU`(cF}MQH?n3z5JG2X z@95E}Q8pZzkAqo84lTAQo$xVq1+@49>|)SiR|_W%}1( z_iaP$7oj-kvoMNwaX6=t<-=|5D{{K9LqBq^4D`%Ak6c(pMV{P+sx=qv{rrUwsAkc>^J12i!$b?;yOqfIMh<8F4e=uP?v809L8trr!7)*uw#OCk*uiAXj` z__!(z#u~>jNE(|rw0`vSZ_h5Y90=B;Tj)Tt7h#|h7ZsaLs`K0>Hh(V^5uBTt^;zdI z?CZv#3bMxf-+rxkk0fmnbFa4TJB|A|0{hvK%JhzL$ygp`=$iPj=-nr`^$+pCJ>5qK*M~hQ- z#QRd2eE1{0wm2r1YE3I0re0%LsD znK4=}g>ZedaEtvA#{WBqYIO%51FQB+k>AW}jG$)G!6bi6`?dvIs=t69p7rRV~4q+d%vW^D#-aU3hA5&^;dKSu?xuko?*?izLm05z$}UzTUim` z1p}6JXC}j!A8|7~(0~4XcXD+Njm1@~T+bzGP+kC%>wu$F6s~pX>1$|!1^RFTObAii z;Zp<6_V&(@lpK6tfB&3D+I2=_M90mayMG-lUI9K3rlVdY%Y(;J^;@Mug+iD#c+um9 z-g{5Hc`{T&`ATlaUV`Pm%;YeUOUTDn-z<=eeP>k>vgyGYi8O1{=L_UeLW>m_F_TAp zjTM?Ur^_w^QSGe9jRkO9Pq6+A7!8Vzc#(hv1AKjBYhva7o#zWR z%k!q*iG&)RSOKB84QEq#(3ju=1%1Rx%nC`1L2ZVw+$Yd07!`A$IOP5|Rs1^>gkS%Y zj?OgZn+m5)x?i)OaGlnrpRgmho|jS9i*CB`%=)tc@~U7iqH^7SUc*Q2EJISB>8^H{ z7mF(&&U7Wcepq3hO%6u>_@byeV|eTKAS}<&CJ7Kx(!zx@h9l{j%Xmax92b73!)4Ha z>$ZPq=oB%mnCdU4M@%s1u&Z0NNflVeS`?FH)R9hW<5Nw}-c}HEng?uQBEzHOha5EE zTnIiPayH)J1pFQAU+YX#e%H9hQ?t5dxFBr0_gz}oky0mWW@9lY2c%Mv;t$CKeOnEw|Fi zo&FXVb}}p3KDes}E+=5u>;ge%E77noh&D%{>dP+cl*e`6wrrL4DEgtBEzFbx&nK!n zlihG^g&Le@P0apB8Kn(>$KtaGi{O4c2ZLNsC`uB;210VlH5ng6UWWk@XJ2uh=77~) z+3Ar~eLlN!7Op3hdjo$lCMDgL$l9^&@`9t7C~diq?bgk>2}W14TRQx6H^+1fkxlFw zODS#bsHl57LJy_Ir2V^(a%erq7EgE*dcHmUY_a0}5&_~D>R1z*NE@d?bqyymmFRdp zUKpc;On4r7Zt6O&h?S<2Q{FR%lYI2_JU3#opnJ1BWBD?&N^?Ru1pex{lp(_1>_@C2 zqZ*-TtX?Bd+l|nbO32lQbRD8EX@>bgn6tAg0mjnEx<=^ua4KpjYFwCU1flds{{`)2 zDzYnv$+O-6dvo37MMfQa3N|11?s3?(ctWe);$^w;il={j+GKnaRwuGoAb5@X2Vr$F zeS6Vlsso|_ysZvga3!e_qmSU0Q{kpkiKPSC2Vgd7G0KPyowJ0d-MxL?mV06Yf;l*S zEm)CTD1qsh7&XU@RHMc<``C#-Unh0?VHB4k*_0%_M8MvlB%pbG6hcQXyheHRik7Q= zfHN|309KjQH-57h2wBGk#AWY%&%FStTVI9L&~}nbN5m~V@_Ho5|D2mPAe}0J zuvc@IH$CAI1H^}}J#y<%IFl1~rVCuL6kK_Uii)Go`nHC2L*GBJ&zvV`Z(ZIsEJP9S z>aq^CndY;Z$yL0bb86TnN!f-Z7{vJ8wC1|tjvMG=J^MSfYBX`64ULRU_+tlNdj>}C zyoLi`Z$2T}GRQW8PWgmrN)xajG0?NhDC$uEIbOx>Br~#|XFpuaz(@^N55H3^q^sen zC20`yhKf8wSZJg#(qfN3;%8pOvy*9}2+Z&i$JlafMh0p68QPt5pse0gtWX7qSYEvf z#Uj4tz({*U^#56V!XUTOq$`db8?(tar*QD3#Lj^`*Tr*abWJi2V{!RLg`FRd+#f^o8w{Vm1oWNn zuu#Syvq%w;V-=hAerK5rz(&;h_Gd$T4Sej$jbB^j*uB+5#oOzym>KCuq9T;v-AWA< zlfLeNhMIDhHPSG$srwhU zwG(>?h8qc4(E`D#!o&(F2_ft0Y|6qgelhE6dSe#ci78mhP#Xm#4j))Fb``*^WaS?B z_UfU@7-ga8e0x>}1}{;u%9m*^Tt;o?ECPUi)A6(J+#>$oa)#$Xs39z{B0DRZut`|j z(0;dBWTq4<&q1aq>ws|gS!|*DijI$k6@nT&g1W5R#QEi$S2zBl3M*fZpJmL!ZB(>X zHi;b5Fs2F(i|nUvPTdSI5w>b2d6Tvx`DiiZU*9{$cr)c+$W`0MT>#=Fo{6x!2UvM+a?6yRcnVFgT zloD8O71x{*&SG%rTd@p4djLK#RLkDA0rbqHi@d%QrLxkI(#l%`F7IzUunN6*OR@DL z@oFayIVf-mo2^8-OxZ2fVg7AnY%A^=o3+a!-#Yp)Z!1%2LK2RnF#E!>#?kZx65>?5 zqAJ>EG+;|jv7Os0hjJ@xnyQ|Yk~Xh(YctAChDHLhxH+0_~h{ zrq@EmCN+DYR^JwxJ|upq)Nh#nQ4{tHD%y8B*uhA6{<*qIt4R-r=0IEM6Y{i+;vN+K zveEvN8_U=#RfJ$nfADjWLV2jyF}_A?thF)aqJ<-}eLOQ02X|qfmog6FOG2MU*8=>bc~PbFo;Yj0fg~&{ zsqjf^OYUUA!^PIk;s#0J^NdmBmf_)_KPV&!EDOE_Yd!tI_?Z=f!E>R4bqm-m&!mt> zf_i$s0*|rdA^tybx8Syh=38-Rn*+VWy8k^NuhxzoNFz7^d&-?xUTRR-#C&PzZU>5( zL-JlV9fBx#T2pLg22( zTILv%EU5}JpIT~<|sGHxS!DK zl}{r*MrRuWTArs1o(;`H;T1!OX4PL;If-KUk^mX|Pr@02mlGQdflwX>)$~|Wn8N6Ub8tDR(vJXVj7Nk*@lYn!4l@6_ z8^->T{$~0zr;@r6trD)E_iaiXQ3JUOV%7Sq23x0qGX^ z;caKN<*xjPGgaDV*xF87HOY=#91oYiD;e;-?QymyTQ-}E<&q3Ti)R2;f#ZF3Em})( zh=pV>6z<4FNc%S}0&7jofCcpeL&@IehwaUf$No4i0fwSt!|;=SNf%^|^ z0EPUY;p7PP0+66rInpZu<9bWYg86udBI;|1Af`w>_J)P)w%ZzKr8J z`}@bw%*boo0VCz@i>^J*ij0sEBT*^*j&!2MBXj?qGNHsW&fMzyYLnZnS`Yi}L4+oI zYRawYd){pe0KxpPhjVAwIEPvQV6x^!DX=G4g+;Fwokyo&6gA(d)C;EQgFfDUff$9> z6D2C+^qE+*u{Z5E3^}hklZ?&>;TA!;a_VWj2{KiezOx&-!yZk0E z-HpBcmqh(W?u+`Ac==qHAZ~Jvaj>NeqKUkx&}ul~+X^a9U_6s~WWS=6fCx`1!ap>H z5uZ_Y{OTkiV&fhOnm~}|$NORnxw8Euob!0aumq|;A!0W_QH6fVw;UKtLGL*lZv;Cg zaU{CVPvlyq4Ki?luzWDksihafxJx&`!s5|q=)=LWB}El^6DtHuU#Z56D70{vtE-TK z!DJs685gyZvG5{6cZ99!PQ;z26r*DfemOGYnll-#ED8g4wq~q=CoQ8qv&#KeP#_*@ z>|~iaD@Rzsd?YQOYkhUu5O!B9aYqp$i~BK!(4Y`+C^u_gSIz_#^rtQxy{!48b=n2% zasx{OB?zz8V+E>VT&{NCch?ndUFOM1x2Pq`R-t&aGTbK~bFfRrBChdC$TOr9b3Plk zE9hjC0%GNOA5&@py09^}HRRrhvw4`=AuQ#+V95rYew6d|s3r21mDOSDo2!r7KAu`L zYamLOk`{P-OO2Zkd<&rjd!t2esiI)bze@Vv=)X4Na!48^S7jKv5*7#fm8KLsKwB{T+71D=AH8b za7fSvuw&)uyrfBXBPUq?z3n{l(dTgo&>vzC`yC1${0@rpyxBbf$P2$VRrvg!T_DMm z_{un5ze#9SPZ#TBTVCB1k=9rRebuf-Xn$S0sa3^@-l(^E`&2%IWR8?4qKO0y({U9X zXvF$rBJoFHHwOJQo6qS09E=|sIL#FO&!@S)HUwsi8!5~DmuT$EGX$IZ^Jl-4X4kXn zWb5#jeB>`1>+5|ipEv6JR%+>~cAFa`POL_4M=jqS5UnX92)0I4aO~7*MyTyzm%t7W z{n3tD1Ca2)%G*WV-cg@7+Vp7aVvo{BG3^LF)k-akT2?sCnbMVpY!F6DHMaT$nJ1~l1P30*SK6v96fz=~`d)B_ z5(w{Oh{DJhd{sQJe&%NBywjlR0-V(JNOmH(X3u|kRg>R}`D;D%r$#K^o)_JVOaeBr zzsqWY`qkJ@2uiugDARk0uNH`(!~NMBu@x&{82OppGdB`<5ol$0($K^S4A)j&3+!+; z85!kEhV)v5nj24jl@nH0*LE@DhC2mmQLI56)Itq9j0H}0Fku4XOYRKT4pS`1M#Nvr zZRC!*j8;)L_J~p%jF51A8lJ@`xh)IB*ndDsDYtm0_i;jN<7=+dlPu?88y8g%54ipE zACJlqSE^E`<&1>Vd2E__8ZNfha*Xji(5KBUh-teUQ0zMtqhL6|exy4#@5v4!K)7uA z+YB1ZK)h4?T8QX}U(l!#H*np+1l>(!S*qTeFNi0P*Di|%S9-h}H`$Io0`~CeQ|-6& z>q*|$YyBeI)-d1L1ZPW}J)12GM+s_Q><;l}hRS5x!X3>rFrTGpPRb(^e*{74V?LE+?rPEGE$XnCL2 zZVruhJA2mlso9>jOe>VyC$PsBI66e|+88+er~Da)db4-5!b2LJ#a6)f9OTS@q#XEy zS>NDz7x*ds$42Fb-tX#g;Ih4(b8XW@c|wr{Bf5ER8V;N z`HfyXApB}Fk55`qG`v~%xDX@rZ(KgjgB0V_Z%6vw&ZRGWf7nKFJStN4C})w|Uw|ph zBH86>9^JHddLXG|JQJTk2KDTd?|S|%qux#fE}0wX{mirC;}0gbP(!G>-G$8xfHqUP z{+9AWM$wx27}bAs4`y=^KXc2}ht?Th3(6l!(%Z|9(r|7cb1E*fZ4_+Wb?x-kGDFv6 zNba4ey*Nxo|ZS_Qs?yBROY#uWS=KlgC+tyUdJrRXRi#F*U8PFEI z)Q%)@4A~kHLxP{2ZaRc+_OZ*Er49S`g%w6olUUN5G(3FtytlqG3AG{}nX3-JS2}`d z&v9SUiFhMW4CMgcBnNv9^qi7^@%z3?ds%3u7F0yvw!-dDU4D7!PXS_@mD9AtYiK}^ z9SNXEHY7~v{bfRqR3v|ljP+G&vc2U{dTr|Qv~R+iYkUsJzaykg5Wwo@qqui$!{??W z+^QqAgwVYG#sZ<0t`P*}?4NWmOuuptDPyKFRUM^Y232wRC=HrnsKlYu(5N<>MChlH zSH=_tFJ8s6h^n*sD5zVDwUJ-h1eW09m2;lV#2`X#TahUx~I+@ zHH(c}%*=ej!Gn(~)pW}LoqJ8U_A9@v{7tFGevBsz#P6r~^=1`jaU=A#{lfsB(mNzECm+=sjK$PPPx3R9Y?^cWJVyZZ}0h^YSpFn z?@!Oot^E$M2KVZdS_|o={LD`vX6PVE>MyHEq;_ z4tgcxa%=So&D7+-Pd|NCHiTWmNhegdo3l|Lz=0P;&Mbrk-<0*i_IB&~vpDIi!5+M& zsII%2g!la1l|?NVj2TSV-Nr`S%&1+*n*X0scx-jmUANPrJW2xBSb@h3jpH#DHHZl{ z7c~>QpJMJd{>6tDd)2Q+;%zG%8P+OnSgc0@#YWYl1u~gaI_g+>@VXG93)dIS*CHB27EaKtc< zH1jYFSgkhDw#%PU9@=bbIE(-^b-iO{1&tZEH;Mw7hYy2%&PHE7Z{ANiQ$Q<)$&a&{ z71_a$F=Q<1BInzQ+QuMR?M88cNr#gpP;*C%-{=1imo5Z_)QrEt00000NkvXXu0mjf D)eSbW literal 0 HcmV?d00001 diff --git a/doc/index.rst b/doc/index.rst new file mode 100644 index 00000000..0cb47559 --- /dev/null +++ b/doc/index.rst @@ -0,0 +1,88 @@ +================================ +ROS Teledyne FLIR camera drivers +================================ + + +.. toctree:: + :maxdepth: 2 + :caption: Contents: + +.. image:: doc/flir.png + :target: https://www.flir.com/browse/industrial/machine-vision-cameras/ + +This repository contains ROS2 packages for machine vision cameras made by +Teledyne FLIR (formerly known as PointGrey). Note: this software is *not +supported* by Teleydyne FLIR. + +Packages +======== + +Spinnaker camera driver +----------------------- + +| A camera driver supporting USB3 and GIGE cameras that has been + successfully used for Blackfly, Blackfly S, Chameleon, and Grasshopper + cameras. It should work with any FLIR camera that supports the + Spinnaker SDK. See the + `spinnaker_camera_driver `__ for + more. + +|driver_humble| |driver_iron| |driver_rolling| + +.. |driver_humble| image:: https://build.ros2.org/buildStatus/icon?job=Hbin_uJ64__spinnaker_camera_driver__ubuntu_jammy_amd64__binary&subject=Humble + :target: https://build.ros2.org/job/Hbin_uJ64__spinnaker_camera_driver__ubuntu_jammy_amd64__binary/ +.. |driver_iron| image:: https://build.ros2.org/buildStatus/icon?job=Ibin_uJ64__spinnaker_camera_driver__ubuntu_jammy_amd64__binary&subject=Iron + :target: https://build.ros2.org/job/Ibin_uJ64__spinnaker_camera_driver__ubuntu_jammy_amd64__binary/ +.. |driver_rolling| image:: https://build.ros2.org/buildStatus/icon?job=Rbin_uN64__spinnaker_camera_driver__ubuntu_noble_amd64__binary&subject=Rolling + :target: https://build.ros2.org/job/Rbin_uN64__spinnaker_camera_driver__ubuntu_noble_amd64__binary/ + +Spinnaker synchronized camera driver +------------------------------------ + +| Based on the spinnaker_camera_driver package, this driver is + specifically designed for cameras that are hardware triggered by an external + pulse. Images triggered by the same external pulse will have identical ROS header time stamps. See the + `spinnaker_synchronized_camera_driver `__ + for more. + +|sync_humble| |sync_iron| |sync_rolling| + +.. |sync_humble| image:: https://build.ros2.org/buildStatus/icon?job=Hbin_uJ64__spinnaker_synchronized_camera_driver__ubuntu_jammy_amd64__binary&subject=Humble + :target: https://build.ros2.org/job/Hbin_uJ64__spinnaker_synchronized_camera_driver__ubuntu_jammy_amd64__binary/ +.. |sync_iron| image:: https://build.ros2.org/buildStatus/icon?job=Ibin_uJ64__spinnaker_synchronized_camera_driver__ubuntu_jammy_amd64__binary&subject=Iron + :target: https://build.ros2.org/job/Ibin_uJ64__spinnaker_synchronized_camera_driver__ubuntu_jammy_amd64__binary/ +.. |sync_rolling| image:: https://build.ros2.org/buildStatus/icon?job=Rbin_uN64__spinnaker_synchronized_camera_driver__ubuntu_noble_amd64__binary&subject=Rolling + :target: https://build.ros2.org/job/Rbin_uN64__spinnaker_synchronized_camera_driver__ubuntu_noble_amd64__binary/ + +FLIR camera description +----------------------- + +| Package with `meshes and urdf `__ + files. + +|desc_humble| |desc_iron| |desc_rolling| + +.. |desc_humble| image:: https://build.ros2.org/buildStatus/icon?job=Hbin_uJ64__flir_camera_description__ubuntu_jammy_amd64__binary&subject=Humble + :target: https://build.ros2.org/job/Hbin_uJ64__flir_camera_description__ubuntu_jammy_amd64__binary/ +.. |desc_iron| image:: https://build.ros2.org/buildStatus/icon?job=Ibin_uJ64__flir_camera_description__ubuntu_jammy_amd64__binary&subject=Iron + :target: https://build.ros2.org/job/Ibin_uJ64__flir_camera_description__ubuntu_jammy_amd64__binary/ +.. |desc_rolling| image:: https://build.ros2.org/buildStatus/icon?job=Rbin_uN64__flir_camera_description__ubuntu_noble_amd64__binary&subject=Rolling + :target: https://build.ros2.org/job/Rbin_uN64__flir_camera_description__ubuntu_noble_amd64__binary/ + + +FLIR camera messages +-------------------- + +| Package with with `image exposure and control + messages `__. These are used by the + `spinnaker_camera_driver `__. + + +|msg_humble| |msg_iron| |msg_rolling| + +.. |msg_humble| image:: https://build.ros2.org/buildStatus/icon?job=Hbin_uJ64__flir_camera_msgs__ubuntu_jammy_amd64__binary&subject=Humble + :target: https://build.ros2.org/job/Hbin_uJ64__flir_camera_msgs__ubuntu_jammy_amd64__binary/ +.. |msg_iron| image:: https://build.ros2.org/buildStatus/icon?job=Ibin_uJ64__flir_camera_msgs__ubuntu_jammy_amd64__binary&subject=Iron + :target: https://build.ros2.org/job/Ibin_uJ64__flir_camera_msgs__ubuntu_jammy_amd64__binary/ +.. |msg_rolling| image:: https://build.ros2.org/buildStatus/icon?job=Rbin_uN64__flir_camera_msgs__ubuntu_noble_amd64__binary&subject=Rolling + :target: https://build.ros2.org/job/Rbin_uN64__flir_camera_msgs__ubuntu_noble_amd64__binary/ diff --git a/spinnaker_camera_driver/README.md b/spinnaker_camera_driver/README.md deleted file mode 100644 index 09d23594..00000000 --- a/spinnaker_camera_driver/README.md +++ /dev/null @@ -1,269 +0,0 @@ -# spinnaker_camera_driver: ROS driver for FLIR cameras based on the Spinnaker SDK - -ROS driver for the FLIR cameras using the -[Spinnaker SDK](http://softwareservices.flir.com/Spinnaker/latest/index.htmlspinnaker). - -NOTE: This driver is not written or supported by FLIR. - -## Tested cameras: - -The following cameras have been used with this driver: - -- Blackfly S (USB3, GigE) -- Blackfly (GigE) -- Grashopper (USB3) -- Chameleon (USB3, tested on firmware v1.13.3.00) - -Note: if you get other cameras to work, *please report back*, ideally -submit a pull request with the camera config file you have created. - -## Tested platforms - -Software: - -- ROS2 Galactic under Ubuntu 20.04 LTS -- ROS2 Humble under Ubuntu 22.04 LTS -- Spinnaker 3.1.0.79 (other versions may work as well but this is - what the continuous integration builds are using) - -## How to install - -This driver can be used with or without installing the Spinnaker SDK, -but installing the Spinnaker SDK is recommended because during its -installation the USB kernel configuration is modified as needed and -suitable access permissions are granted (udev rules). -If you choose to *not* use the Spinnaker SDK, you must either run the -[linux setup script](scripts/linux_setup_flir) by running `ros2 run spinnaker_camera_driver linux_setup_flir` -or perform the [required setup steps manually](docs/linux_setup_flir.md). -Without these setup steps, -*the ROS driver will not detect the camera*. -So you must either install the Spinnaker SDK (which also gives you the -useful ``spinview`` tool), or follow the manual setup steps mentioned earlier. - -### Installing from packages -For some architectures and ros distributions you can simply install an apt package: -``` -sudo apt install ros-${ROS_DISTRO}-spinnaker-camera-driver -``` -The package will bring its own set of Spinnaker SDK libraries, so you don't -necessarily have to install the SDK, but it's recommended, see above - -### Building from source - -1) Install the FLIR spinnaker driver. If you skip this part, the -driver will attempt to download the Spinnaker SDK automatically to -obtain the header files and libraries. -2) Prepare the ROS2 driver build: -Make sure you have your ROS2 environment sourced: -``` -source /opt/ros//setup.bash -``` - -Create a workspace (``~/ws``), clone this repo: -``` -mkdir -p ~/ws/src -cd ~/ws/src -git clone --branch humble-devel https://github.com/ros-drivers/flir_camera_driver -cd .. -``` - -To automatically install all packages that the ``flir_camera_driver`` packages -depends upon, run this at the top of your workspace: -``` -rosdep install --from-paths src --ignore-src -``` - -3) Build the driver and source the workspace: -``` -colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=RelWithDebInfo -DCMAKE_EXPORT_COMPILE_COMMANDS=ON -. install/setup.bash -``` - -## Example usage - -### Single node launch -The driver comes with an example launch file (``driver_node.launch.py``) -that you can customize as needed. -``` -# launch with --show-args to print out all available launch arguments -ros2 launch spinnaker_camera_driver driver_node.launch.py camera_type:=blackfly_s serial:="'20435008'" -``` - -### Stereo camera with synchronization - -The launch file ``stereo_synced.launch.py`` provides a working example for launching -drivers for two hardware synchronized Blackfly S cameras. It requires two more packages -to be installed, -[cam_sync_ros2](https://github.com/berndpfrommer/cam_sync_ros2)(for -time stamp syncing) and -[exposure_control_ros2](https://github.com/berndpfrommer/exposure_control_ros2) -(for external exposure control). -The launch file also demonstrates how to use the driver as a composable node. - -## Features - -The ROS driver itself has no notion of the camera type (Blackfly, -Grasshopper etc), nor does it explicitly support any of the many -features that the FLIR cameras have. Rather, all camera features -(called Spinnaker Nodes) are mapped to ROS parameters via a yaml file -that is specific to the camera. On startup the driver reads this -parameter definition file. In the ``config`` directory there are some -parameter definition files for popular cameras (blackfly_s.yaml etc) -that expose some of the more frequently used features like frame rate, -gain, etc. You can add more features by providing your own -parameter definition file. The ROS driver code is just a thin wrapper -around the Spinnaker SDK, and should allow you to access all features available in FLIR's -spinview program. *In addition to the parameters defined in the .yaml -files*, the driver has the following ROS parameters: - -- ``adjust_timestamp``: see below for more documentation -- ``acquisition_timeout``: timeout for expecting frames (in seconds). - If no frame is received for this time, the driver restarts. Default is 3s. -- ``buffer_queue_size``: max number of images to queue internally - before shoving them into the ROS output queue. Decouples the - Spinnaker SDK thread from the ROS publishing thread. Default: 4. -- ``camerainfo_url``: where to find the camera calibration yaml file. -- ``compute_brightness``: if true, compute image brightness and - publish it in meta data message. This is useful for external - exposure control but incurs extra CPU load. Default: false. -- ``connect_while_subscribed``: if true, connect to the SDK and - pull data from the camera *only while subscribers to image or meta - topics are present*. This feature reduces compute load and link - utilization while no ROS subscribers are present, but adds latency - on subscription in that the first image will be published - up to 1s later than without this option. -- ``dump_node_map``: set this to true to get a dump of the node map. This -- ``frame_id``: the ROS frame id to put in the header of the published - image messages. -- ``image_queue_size``: ROS output queue size (number of frames). Default: 4 - feature is helpful when developing a new config file. Default: false. -- ``parameter_file``: location of the .yaml file defining the camera - (blackfly_s.yaml etc) -- ``serial_number``: must have the serial number of the camera. If you - don't know it, put in anything you like and - the driver will croak with an error message, telling you what - cameras serial numbers are available - -## Setting up GigE cameras - -The Spinnaker SDK abstracts away the transport layer so a GigE camera -should work the same way as USB3: you point it to the serial -number and you're set. - -There are a few GigE-specific settings in the Transport Layer Control -group that are important, in particular enabling jumbo frames from the -camera per FLIR's recommendations. The following line in your -camera-specific config file will create a ROS2 parameter -``gev_scps_packet_size``: -``` -gev_scps_packet_size int "TransportLayerControl/GigEVision/GevSCPSPacketSize" -``` -that you can then set in your ROS2 launch file: -``` - "gev_scps_packet_size": 9000 -``` -As far as setting up the camera's IP address: you can set up DHCP on -your network or configure a static persistent IP using spinview -in "Transport Layer Control">"GigE Vision". Check the box for "Current -IP Configuration Persistent IP" first to enable it, then set your -desired addresses under "Persistent IP Address", "Persistent Subnet -Mask" and "Persistent Gateway". NOTE: these look like regular IPs, but -to set them you have to enter the 32-bit integer representation of the -IP address/mask. By hand/calculator: convert the IP octets from -decimal to hex, then combine them and convert to a 32-bit integer, ex: -192.168.0.1 -> 0xC0A80001 -> 3232235521. - -The "Transport Layer Control">"GigE Vision" section of spinview is -also where you'll find that "SCPS Packet Size" setting, which you can -change when not capturing frames, and verify it works in spinview and -without needing to spin up a custom launch file to get started, though -it helps, and you'll probably want one anyway to specify your camera's -serial number. - -For more tips on GigE setup look at FLIR's support pages -[here](https://www.flir.com/support-center/iis/machine-vision/knowledge-base/lost-ethernet-data-packets-on-linux-systems/) -and -[here](https://www.flir.com/support-center/iis/machine-vision/application-note/troubleshooting-image-consistency-errors/). - -### Time stamps - -By default the driver will set the ROS header time stamp to be the -time when the image was delivered by the SDK. Such time stamps are not -very precise and may lag depending on host CPU load. However the -driver has a feature to use the much more accurate sensor-provided -camera time stamps. These are then converted to ROS time stamps by -estimating the offset between ROS and sensor time stamps via a simple -moving average. For the adjustment to work -*the camera must be configured to send time stamps*, and the -``adjust_timestamp`` flag must be set to true, and the relevant field -in the "chunk" must be populated by the camera. For the Blackfly S -the parameters look like this: -``` - 'adjust_timestamp': True, - 'chunk_mode_active': True, - 'chunk_selector_timestamp': 'Timestamp', - 'chunk_enable_timestamp': True, -``` - -When running hardware synchronized cameras in a stereo configuration -two drivers will need to be run, one for each camera. This will mean -however that their published ROS header time stamps are *not* -identical which in turn may prevent down-stream ROS nodes from recognizing the -images as being hardware synchronized. You can use the -[cam_sync_ros2 node](https://github.com/berndpfrommer/cam_sync_ros2) -to force the time stamps to be aligned. In this scenario it is -mandatory to configure the driver to adjust the ROS time stamps as -described above. - -### Automatic exposure - -In most situations it is recommended to enable the built-in auto -exposure of the camera. However, in a -synchronized setting it is sometimes desirable to disable the built-in -auto-exposure and provide it externally. For instance in a stereo setup, -matching left and right image patches can be difficult when each -camera runs its own auto exposure independently. The -[exposure_control_ros2](https://github.com/berndpfrommer/exposure_control_ros2) -package can provide external automatic exposure control. To this end -the driver publishes -[meta data messages](https://github.com/ros-drivers/flir_camera_driver/flir_camera_msgs) and -subscribes to -[camera control -messages](https://github.com/ros-drivers/flir_camera_driver/flir_camera_msgs). See -the launch file directory for examples. - -## How to add new features and develop your own camera configuration file - -[Check out this section](docs/camera_configuration_files.md) for more information on -how to add features. - -## Known issues - -1) If you run multiple drivers in separate nodes that all access USB based -devices, starting a new driver will stop the image acquisition of -currently running drivers. There is an ugly workaround for this -currently implemented: if image delivery stops for more than -``acquisition_timeout`` seconds, the acquisition is restarted. This -operation may not be thread safe so the driver already running could -possibly crash. This issue can be avoided by running all drivers in -the same address space with a composable node (see stereo launch file for -example). - -## How to contribute -Please provide feedback if you cannot get your camera working or if -the code does not compile for you. Feedback is crucial for the -software development process. However, before opening issues on github first -verify that the problem is not present when using spinview. - -Bug fixes and config files for new cameras are greatly -appreciated. Before submitting a pull request, run this to see if your -commit passes some basic lint tests: -``` -colcon test --packages-select spinnaker_camera_driver && colcon test-result --verbose -``` - -## License - -This software is issued under the Apache License Version 2.0. -The file [TargetArch.cmake](cmake/TargetArch.cmake) is released under -a custom license (see file) diff --git a/spinnaker_camera_driver/README.rst b/spinnaker_camera_driver/README.rst new file mode 120000 index 00000000..176d9c26 --- /dev/null +++ b/spinnaker_camera_driver/README.rst @@ -0,0 +1 @@ +doc/index.rst \ No newline at end of file diff --git a/spinnaker_camera_driver/doc/conf.py b/spinnaker_camera_driver/doc/conf.py new file mode 100644 index 00000000..75dcc980 --- /dev/null +++ b/spinnaker_camera_driver/doc/conf.py @@ -0,0 +1,54 @@ +# Copyright 2024 Bernd Pfrommer +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# + +project = 'spinnaker_camera_driver' +# copyright = '2024, Bernd Pfrommer' +author = 'Bernd Pfrommer' + + +# Add any Sphinx extension module names here, as strings. +extensions = [ + 'myst_parser', + 'sphinx.ext.doctest', + 'sphinx_rtd_theme', + 'sphinx.ext.intersphinx', + 'sphinx.ext.autosummary', + 'sphinx.ext.napoleon', +] + +# Add any paths that contain templates here, relative to this directory. +templates_path = ['_templates'] + +source_suffix = '.rst' +# exclude_patterns = ['_build', 'Thumbs.db', '.DS_Store'] +exclude_patterns = [] + +# The name of the Pygments (syntax highlighting) style to use. +pygments_style = None + +# -- Options for HTML output ------------------------------------------------- + +# The theme to use for HTML and HTML Help pages. See the documentation for +# a list of builtin themes. +# +# html_theme = 'alabaster' +html_theme = 'sphinx_rtd_theme' +htmlhelp_basename = 'spinnaker_camera_driver_doc' + +# Add any paths that contain custom static files (such as style sheets) here, +# relative to this directory. They are copied after the builtin static files, +# so a file named "default.css" will overwrite the builtin "default.css". + +# html_static_path = ['_static'] diff --git a/spinnaker_camera_driver/doc/index.rst b/spinnaker_camera_driver/doc/index.rst new file mode 100644 index 00000000..6ec95466 --- /dev/null +++ b/spinnaker_camera_driver/doc/index.rst @@ -0,0 +1,397 @@ +============================ +Spinnaker ROS2 Camera Driver +============================ + +.. toctree:: + :maxdepth: 2 + + +This package provides a ROS2 driver for Teledyne/FLIR cameras using the +`Spinnaker +SDK `__. +For hardware-synchronized cameras use the Spinnaker synchronized camera driver by +following the link from the +`flir driver repository `__. + + +NOTE: This driver is not written or supported by FLIR. + +Tested Configurations +===================== +Cameras +------- + +The following cameras have been successfully used with this driver: + +- Blackfly S (USB3, GigE) +- Blackfly (GigE) +- Grashopper (USB3) +- Oryx (reported working) +- Chameleon (USB3, tested on firmware v1.13.3.00) + +Note: if you get other cameras to work, *please report back*, ideally +submit a pull request with the camera config file you have created. + +Platforms +--------- + +- ROS2 Galactic under Ubuntu 20.04 LTS (no longer actively tested) +- ROS2 Humble/Iron/Rolling under Ubuntu 22.04 LTS +- Spinnaker 3.1.0.79 (other versions may work as well but this is what + the continuous integration builds are using)o + +How to install +============== + +This driver can be used with or without installing the Spinnaker SDK, +but installing the Spinnaker SDK is recommended because during its +installation the USB kernel configuration is modified as needed and +suitable access permissions are granted (udev rules). If you choose to +*not* use the Spinnaker SDK, you must either run the `linux setup +script `__ by running +``ros2 run spinnaker_camera_driver linux_setup_flir`` or perform the +required setup steps manually, see `Setting up Linux without Spinnaker SDK`_. +Without these setup steps, *the ROS driver will not detect the camera*. +So you must either install the Spinnaker SDK (which also gives you the useful +``spinview`` tool), or follow the manual setup steps mentioned earlier. + +Installing from packages +------------------------ + +For some architectures and ros distributions you can simply install an +apt package: + +:: + + sudo apt install ros-${ROS_DISTRO}-spinnaker-camera-driver + +The package will bring its own set of Spinnaker SDK libraries, so you +don’t necessarily have to install the SDK, but it’s recommended, see +above. + +Building from source +-------------------- + +1) Install the FLIR spinnaker driver. If you skip this part, the driver + will attempt to download the Spinnaker SDK automatically to obtain + the header files and libraries. +2) Prepare the ROS2 driver build: Make sure you have your ROS2 + environment sourced: + +:: + + source /opt/ros//setup.bash + +Create a workspace (``~/ws``), clone this repo: + +:: + + mkdir -p ~/ws/src + cd ~/ws/src + git clone --branch humble-devel https://github.com/ros-drivers/flir_camera_driver + cd .. + +To automatically install all packages that the ``flir_camera_driver`` +packages depends upon, run this at the top of your workspace: + +:: + + rosdep install --from-paths src --ignore-src + +3) Build the driver and source the workspace: + +:: + + colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=RelWithDebInfo -DCMAKE_EXPORT_COMPILE_COMMANDS=ON + . install/setup.bash + +How to use +========== + +Topics +------ + +Published: + +- ``~/image_raw``: the camera image (image_transport) +- ``~/image_raw/camera_info``: camera calibration +- ``~/meta``: meta data message containing e.g. exposure time. + +Subscribed: + +- ``~/control``: (only when ``enable_external_control`` is set to True) + for external control exposure time and gain. + +Parameters +---------- + +The driver itself has no notion of the camera type (Blackfly, +Grasshopper etc), nor does it explicitly support any features that the FLIR cameras have. +Rather, all camera features (called +Spinnaker Nodes) are mapped to ROS parameters via a yaml file that is +specific to that camera type. On startup the driver reads this parameter +definition file. In the ``config`` directory there are some parameter +definition files for popular cameras (blackfly_s.yaml etc) that expose +some of the more frequently used features like frame rate, gain, etc. +You can add more features by providing your own parameter definition +file, see `How to develop your own camera configuration file`_. +The ROS driver code is just a thin wrapper around the Spinnaker +SDK, and should allow you to access all features available in FLIR’s +spinview program. + +*In addition to the parameters defined in the .yaml +files*, the driver has the following ROS parameters: + +- ``adjust_timestamp``: see `About time stamps`_ below for more documentation. Default: false. +- ``acquisition_timeout``: timeout for expecting frames (in seconds). + If no frame is received for this time, the driver restarts. Default + is 3. +- ``buffer_queue_size``: max number of images to queue internally + before shoving them into the ROS output queue. Decouples the + Spinnaker SDK thread from the ROS publishing thread. Default: 4. +- ``camerainfo_url``: where to find the camera calibration yaml file. +- ``compute_brightness``: if true, compute image brightness and publish + it in meta data message. This is required when running with + the synchronized driver, but incurs extra CPU load. Default: false. +- ``connect_while_subscribed``: if true, connect to the SDK and pull + data from the camera *only while subscribers to image or meta topics + are present*. This feature reduces compute load and link utilization + while no ROS subscribers are present, but adds latency on + subscription: after a subscription the first image will be published up to 1s later + than without this option. +- ``dump_node_map``: set this to true to get a dump of the node map. + Default: false. +- ``enable_external_control``: set this to true to enable external exposure control. + This feature is being deprecated, *do not use*. Default: false. +- ``frame_id``: the ROS frame id to put in the header of the published image messages. +- ``image_queue_size``: ROS output queue size (number of frames). Default: 4 +- ``parameter_file``: location of the .yaml file defining the camera + (blackfly_s.yaml etc) +- ``serial_number``: serial number of the camera. If you + don’t know it, put in anything you like and the driver will croak + with an error message, telling you what cameras serial numbers are + available + +Example usage +------------- +The driver comes with an example launch file (``driver_node.launch.py``) +that you can customize as needed. + +:: + + # launch with --show-args to print out all available launch arguments + ros2 launch spinnaker_camera_driver driver_node.launch.py camera_type:=blackfly_s serial:="'20435008'" + + +About time stamps +================= + +By default the driver will set the ROS header time stamp to be the time +when the image was delivered by the SDK. Such time stamps are not very +precise and may lag depending on host CPU load. However the driver has a +feature to use the much more accurate sensor-provided camera time +stamps. These are then converted to ROS time stamps by estimating the +offset between ROS and sensor time stamps via a simple moving average. +For the adjustment to work *the camera must be configured to send time +stamps*, and the ``adjust_timestamp`` flag must be set to true, and the +relevant field in the “chunk” must be populated by the camera. For the +Blackfly S the parameters look like this: + +:: + + 'adjust_timestamp': True, + 'chunk_mode_active': True, + 'chunk_selector_timestamp': 'Timestamp', + 'chunk_enable_timestamp': True, + + + +Setting up GigE cameras +======================= + +The Spinnaker SDK abstracts away the transport layer so a GigE camera +should work the same way as USB3: you point it to the serial number and +you’re set. + +There are a few GigE-specific settings in the Transport Layer Control +group that are important, in particular enabling jumbo frames from the +camera per FLIR’s recommendations. The following line in your +camera-specific config file will create a ROS2 parameter +``gev_scps_packet_size``: + +:: + + gev_scps_packet_size int "TransportLayerControl/GigEVision/GevSCPSPacketSize" + +that you can then set in your ROS2 launch file: + +:: + + "gev_scps_packet_size": 9000 + +As far as setting up the camera’s IP address: you can set up DHCP on +your network or configure a static persistent IP using spinview in +“Transport Layer Control”>“GigE Vision”. Check the box for “Current IP +Configuration Persistent IP” first to enable it, then set your desired +addresses under “Persistent IP Address”, “Persistent Subnet Mask” and +“Persistent Gateway”. NOTE: these look like regular IPs, but to set them +you have to enter the 32-bit integer representation of the IP +address/mask. By hand/calculator: convert the IP octets from decimal to +hex, then combine them and convert to a 32-bit integer, ex: 192.168.0.1 +-> 0xC0A80001 -> 3232235521. + +The “Transport Layer Control”>“GigE Vision” section of spinview is also +where you’ll find that “SCPS Packet Size” setting, which you can change +when not capturing frames, and verify it works in spinview and without +needing to spin up a custom launch file to get started, though it helps, +and you’ll probably want one anyway to specify your camera’s serial +number. + +For more tips on GigE setup look at FLIR’s support pages +`here `__ +and +`here `__. + + +How to develop your own camera configuration file +================================================= + +The camera configuration file defines the available ROS parameters, and +how they relate to the corresponding `Spinnaker +nodes `__. +The Spinnaker API follows the GenICam standard, where each property +(e.g. exposure mode, gain, …) of the camera is represented by a node. +Many properties are of integer or floating point type, but some are +enumerations (“enum”). Before you modify a configuration file you can +explore the Spinnaker Nodes by using the spinview applications that +comes with the Spinnaker SDK. Once you know what property you want to +expose as a ROS parameter, you add a mapping entry to the yaml +configuration file, e.g.: + +.. code:: + + - name: image_width + type: int + node: ImageFormatControl/Width + +With this entry in place, the ROS driver will now accept an integer +parameter of name ``image_width``, and whenever ``image_width`` changes, +it will apply this change to the Spinnaker Node +``ImageFormatControl/Width``. + +Enumerations (``enum``) parameters are slightly trickier than float and +integers because their values are restricted to a set of strings. Any +other strings will be rejected by the Spinnaker API. Please document the +valid enum strings in the configuration file, e.g.: + +.. code:: + + - name: line1_linemode # valid values: "Input", "Output" + type: enum + node: DigitalIOControl/LineMode + +The hard part is often finding the node name, in the last example +``"DigitalIOControl/LineMode"``. It usually follows by removing spaces +from the ``spinview`` names. If that doesn’t work, launch the driver +with the ``dump_node_map`` parameter set to “True” and look at the +output for inspiration. + +**NOTE: !!!! THE ORDER OF PARAMETER DEFINITION MATTERS !!!!** + +On node startup, the parameters will be declared and initialized in the +order listed in the yaml file. For instance you must list the enum +``exposure_auto`` before the float ``exposure_time`` because on startup, +``exposure_auto`` must first be set to ``Off`` before ``exposure_time`` +can be set, or else the camera refuses to set the exposure time. + +Known issues +============ + +1) If you run multiple drivers in separate nodes that all access USB + based devices, starting a new driver will stop the image acquisition + of currently running drivers. There is an ugly workaround for this + currently implemented: if image delivery stops for more than + ``acquisition_timeout`` seconds, the acquisition is restarted. This + operation may not be thread safe so the driver already running could + possibly crash. This issue can be avoided by running all drivers in + the same address space with a composable node (see stereo launch file + for example). + + +Setting up Linux without Spinnaker SDK +====================================== + +Only use these instructions if you did not install the Spinnaker SDK on +your machine. + +1) Add the “flirimaging” group and make yourself a member of it + +.. code:: + + sudo addgroup flirimaging + sudo usermod -a -G flirimaging ${USER} + +2) Bump the usbfs memory limits + +The following was taken from +`here `__. +Edit the file ``/etc/default/grub`` and change the line default to: + +:: + + GRUB_CMDLINE_LINUX_DEFAULT="quiet splash usbcore.usbfs_memory_mb=1000" + +Then + +:: + + sudo update-grub + +If your system does not have ``/etc/default/grub``, create the file +``/etc/rc.local``, and change its permissions to ‘executable’. Then +write the following text to it: + +:: + + #!/bin/sh -e + sh -c 'echo 1000 > /sys/module/usbcore/parameters/usbfs_memory_mb' + + exit 0 + +3) Setup udev rules + +.. code:: + + echo 'SUBSYSTEM=="usb", ATTRS{idVendor}=="1e10", GROUP="flirimaging"' | sudo tee -a /etc/udev/rules.d/40-flir-spinnaker.rules + echo 'SUBSYSTEM=="usb", ATTRS{idVendor}=="1724", GROUP="flirimaging"' | sudo tee -a /etc/udev/rules.d/40-flir-spinnaker.rules + sudo service udev restart + sudo udevadm trigger + +4) Logout and log back in (or better, reboot) + +``sudo reboot`` + + +How to contribute +================= + +Please provide feedback if you cannot get your camera working or if the +code does not compile for you. Feedback is crucial for the software +development process. However, before opening issues on github first +verify that the problem is not present when using spinview. + +Bug fixes and config files for new cameras are greatly appreciated. +Before submitting a pull request, run this to see if your commit passes +some basic lint tests: + +:: + + colcon test --packages-select spinnaker_camera_driver && colcon test-result --verbose + + +License +======= + +This software is issued under the Apache License Version 2.0. The file +``cmake/TargetArch.cmake`` is released under a custom license (see file). + diff --git a/spinnaker_camera_driver/docs/camera_configuration_files.md b/spinnaker_camera_driver/docs/camera_configuration_files.md deleted file mode 100644 index 6ca28c1a..00000000 --- a/spinnaker_camera_driver/docs/camera_configuration_files.md +++ /dev/null @@ -1,49 +0,0 @@ -# How to develop your own camera configuration file - -The camera configuration file defines the available ROS parameters, -and how they relate to the corresponding [Spinnaker -nodes](https://www.flir.com/support-center/iis/machine-vision/application-note/spinnaker-nodes/). -The Spinnaker API follows the GenICam standard, where each property -(e.g. exposure mode, gain, ...) of the camera is represented by a -node. Many properties are of integer or floating point type, but some -are enumerations ("enum"). Before you modify a configuration file you -can explore the Spinnaker Nodes by using the spinview applications -that comes with the Spinnaker SDK. Once you know what property you -want to expose as a ROS parameter, you add a mapping entry to the yaml -configuration file, e.g.: -```yaml - - name: image_width - type: int - node: ImageFormatControl/Width -``` - -With this entry in place, the ROS driver will now accept an integer parameter -of name ``image_width``, and whenever -``image_width`` changes, it will apply this change to the Spinnaker -Node ``ImageFormatControl/Width``. - -Enumerations (``enum``) parameters are slightly trickier than float -and integers because their values are restricted to a set of -strings. Any other strings will be rejected by the Spinnaker API. -Please document the valid enum strings in the configuration file, -e.g.: -```yaml - - name: line1_linemode # valid values: "Input", "Output" - type: enum - node: DigitalIOControl/LineMode -``` - -The hard part is often finding the node name, in the last -example ``"DigitalIOControl/LineMode"``. It usually follows by -removing spaces from the ``spinview`` names. If that doesn't work, -launch the driver with the ``dump_node_map`` parameter set to "True" -and look at the output for inspiration. - -**NOTE: !!!! THE ORDER OF PARAMETER DEFINITION MATTERS !!!!** - -On node startup, the parameters will be declared and initialized -in the order listed in the yaml file. For instance you must list -the enum ``exposure_auto`` before the float ``exposure_time`` because on -startup, ``exposure_auto`` must first be set to ``Off`` before -``exposure_time`` can be set, or else the camera refuses to set -the exposure time. diff --git a/spinnaker_camera_driver/docs/linux_setup_flir.md b/spinnaker_camera_driver/docs/linux_setup_flir.md deleted file mode 100644 index 07929e11..00000000 --- a/spinnaker_camera_driver/docs/linux_setup_flir.md +++ /dev/null @@ -1,42 +0,0 @@ -# Manual setup steps - -Only use these instructions if you did not install the Spinnaker SDK on -your machine. - -## Add the "flirimaging" group and make yourself a member of it -```bash -sudo addgroup flirimaging -sudo usermod -a -G flirimaging ${USER} -``` - -## Bump the usbfs memory limits -The following was taken from [here](https://www.flir.com/support-center/iis/machine-vision/application-note/using-linux-with-usb-3.1/). -Edit the file ``/etc/default/grub`` and change the line default to: -``` -GRUB_CMDLINE_LINUX_DEFAULT="quiet splash usbcore.usbfs_memory_mb=1000" -``` -Then -``` -sudo update-grub -``` -If your system does not have ``/etc/default/grub``, create the file ``/etc/rc.local``, and change its permissions to 'executable'. Then write the following text to it: -``` -#!/bin/sh -e -sh -c 'echo 1000 > /sys/module/usbcore/parameters/usbfs_memory_mb' - -exit 0 -``` - -## Setup udev rules -```bash -echo 'SUBSYSTEM=="usb", ATTRS{idVendor}=="1e10", GROUP="flirimaging"' | sudo tee -a /etc/udev/rules.d/40-flir-spinnaker.rules -echo 'SUBSYSTEM=="usb", ATTRS{idVendor}=="1724", GROUP="flirimaging"' | sudo tee -a /etc/udev/rules.d/40-flir-spinnaker.rules -sudo service udev restart -sudo udevadm trigger -``` - -## Logout and log back in (or better, reboot) - -`` -sudo reboot -`` diff --git a/spinnaker_camera_driver/rosdoc2.yaml b/spinnaker_camera_driver/rosdoc2.yaml new file mode 100644 index 00000000..12796451 --- /dev/null +++ b/spinnaker_camera_driver/rosdoc2.yaml @@ -0,0 +1,42 @@ +## This 'attic section' self-documents this file's type and version. +type: 'rosdoc2 config' +version: 1 + +--- + +settings: + ## If this is true, a standard index page is generated in the output directory. + ## It uses the package information from the 'package.xml' to show details + ## about the package, creates a table of contents for the various builders + ## that were run, and may contain links to things like build farm jobs for + ## this package or links to other versions of this package. + ## If this is not specified explicitly, it defaults to 'true'. + generate_package_index: true + + ## Point to python sources relative to package.xml file + # python_source: '' + + ## Don't run doxygen + always_run_doxygen: false + + ## Build python API docs + ## This is most useful if the user would like to generate Python API + ## documentation for a package that is not of the `ament_python` build type. + always_run_sphinx_apidoc: false + + # disable breathe and exhale + enable_breathe: false + enable_exhale: false + + # This setting, if provided, will override the build_type of this package + # for documentation purposes only. If not provided, documentation will be + # generated assuming the build_type in package.xml. + # override_build_type: 'ament_python' + +builders: + - sphinx: { + name: 'spinnaker_camera_driver', + ## This path is relative to output staging. + sphinx_sourcedir: 'doc/', + output_dir: '' + } \ No newline at end of file diff --git a/spinnaker_synchronized_camera_driver/README.md b/spinnaker_synchronized_camera_driver/README.md deleted file mode 100644 index 8e9d7a2c..00000000 --- a/spinnaker_synchronized_camera_driver/README.md +++ /dev/null @@ -1,99 +0,0 @@ -# spinnaker_synchronized_camera_driver: ROS driver for synchronized FLIR cameras based on the Spinnaker SDK - -ROS driver for synchronized FLIR cameras using the -[Spinnaker SDK](http://softwareservices.flir.com/Spinnaker/latest/index.htmlspinnaker). - -NOTE: This driver is not written or supported by FLIR. - -## Tested cameras: - -The following cameras have been used with this driver: - -- Blackfly S (USB3) -- Blackfly (GigE) - -Note: if you get other cameras to work, *please report back*, ideally -submit a pull request with the camera config file you have created. - -## Tested platforms - -Software: - -- ROS2 Humble under Ubuntu 22.04 LTS -- Spinnaker 3.1.0.79 (other versions may work as well but this is - what the continuous integration builds are using) - -## How to install - -It is recommended to first install the Spinnaker SDK from FLIR's web site because it has -tools (SpinView) that are very helpful for finding the correct camera configuration. You will also need to install the [ROS2 spinnaker camera driver](../spinnaker_camera_driver/README.md). It is recommended to first test the single camera drivers before proceeding with the synchronized setup. - -### Installing from packages -For some architectures and ROS2 distributions you can simply install an apt package: -``` -sudo apt install ros-${ROS_DISTRO}-spinnaker-synchronized-camera-driver -``` - -### Building from source - -1) Although not necessary, it is recommended to install the Spinnaker SDK. -2) Prepare the ROS2 driver build: -Make sure you have your ROS2 environment sourced: -``` -source /opt/ros//setup.bash -``` - -Create a workspace (``~/ws``), clone this repo: -``` -mkdir -p ~/ws/src -cd ~/ws/src -git clone --branch humble-devel https://github.com/ros-drivers/flir_camera_driver -cd .. -``` - -To automatically install all packages that the ``flir_camera_driver`` packages -depends upon, run this at the top of your workspace: -``` -rosdep install --from-paths src --ignore-src -``` - -3) Build the driver and source the workspace: -``` -colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=RelWithDebInfo -DCMAKE_EXPORT_COMPILE_COMMANDS=ON -. install/setup.bash -``` - -## Example usage - -### Launch the example stereo node -The driver comes with an example launch file (``synchronized_driver_node.launch.py``) -that must be edited to e.g. adjust for camera type and serial numbers -``` -ros2 launch spinnaker_synchronized_camera_driver synchronized_driver_node.launch.py -``` -Note that the relevant camera parameters must be set here, in particular chunks need to be enabled that have the time stamps, and the cameras synchronization modes need to be set correctly as well. - -## Features - -The synchronized driver has the following parameters: - -- ``cameras``: a list of strings, e.g. ["cam_0", "cam_1"] that gives - the camera names. The driver will instantiate a camera for each name, and - its parameters can then be set in the respective name space, e.g. for a blackfly_s camera you could set the trigger mode via ROS parameter ``cam_0.trigger_mode``. - -The remaining per-camera parameters, *in particular for enabling the chunk mode time stamps* must be set via the launch files in the respective name spaces of each camera. See the launch file for how this is done. - -## Known issues - -See the caveats for the [ROS2 single-camera spinnaker driver](../spinnaker_camera_driver/README.md). - -## How to contribute - -Bug fixes and config files for new cameras are greatly appreciated. Before submitting a pull request, run this to see if your commit passes some basic lint tests: -``` -colcon test --packages-select spinnaker_synchronized_camera_driver && colcon test-result --verbose -``` - -## License - -This software is issued under the Apache License Version 2.0. diff --git a/spinnaker_synchronized_camera_driver/README.rst b/spinnaker_synchronized_camera_driver/README.rst new file mode 120000 index 00000000..176d9c26 --- /dev/null +++ b/spinnaker_synchronized_camera_driver/README.rst @@ -0,0 +1 @@ +doc/index.rst \ No newline at end of file diff --git a/spinnaker_synchronized_camera_driver/doc/conf.py b/spinnaker_synchronized_camera_driver/doc/conf.py new file mode 100644 index 00000000..75dcc980 --- /dev/null +++ b/spinnaker_synchronized_camera_driver/doc/conf.py @@ -0,0 +1,54 @@ +# Copyright 2024 Bernd Pfrommer +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# + +project = 'spinnaker_camera_driver' +# copyright = '2024, Bernd Pfrommer' +author = 'Bernd Pfrommer' + + +# Add any Sphinx extension module names here, as strings. +extensions = [ + 'myst_parser', + 'sphinx.ext.doctest', + 'sphinx_rtd_theme', + 'sphinx.ext.intersphinx', + 'sphinx.ext.autosummary', + 'sphinx.ext.napoleon', +] + +# Add any paths that contain templates here, relative to this directory. +templates_path = ['_templates'] + +source_suffix = '.rst' +# exclude_patterns = ['_build', 'Thumbs.db', '.DS_Store'] +exclude_patterns = [] + +# The name of the Pygments (syntax highlighting) style to use. +pygments_style = None + +# -- Options for HTML output ------------------------------------------------- + +# The theme to use for HTML and HTML Help pages. See the documentation for +# a list of builtin themes. +# +# html_theme = 'alabaster' +html_theme = 'sphinx_rtd_theme' +htmlhelp_basename = 'spinnaker_camera_driver_doc' + +# Add any paths that contain custom static files (such as style sheets) here, +# relative to this directory. They are copied after the builtin static files, +# so a file named "default.css" will overwrite the builtin "default.css". + +# html_static_path = ['_static'] diff --git a/spinnaker_synchronized_camera_driver/doc/index.rst b/spinnaker_synchronized_camera_driver/doc/index.rst new file mode 100644 index 00000000..95f29c11 --- /dev/null +++ b/spinnaker_synchronized_camera_driver/doc/index.rst @@ -0,0 +1,156 @@ +========================================= +Spinnaker ROS2 Synchronized Camera Driver +========================================= + +This package provides a driver specifically for hardware synchronized +cameras made by Teledyne/FLIR that work with the `Spinnaker +SDK `__. +The main difference to running several instances of the +`unsynchronized camera driver `__ is +that this driver will assign identical header time stamps to frames that have been +generated by the same synchronization pulse. + +NOTE: This driver is not written or supported by FLIR. + +Tested Configurations +===================== + +Cameras +------- + +The following cameras have been used with this driver: + +- Blackfly S (USB3) +- Blackfly (GigE) + + +Platforms +--------- + +- ROS2 Galactic under Ubuntu 20.04 LTS (no longer actively tested) +- ROS2 Humble/Iron/Rolling under Ubuntu 22.04 LTS +- Spinnaker 3.1.0.79 (other versions may work as well but this is what + the continuous integration builds are using) + +How to install +============== + +The installation is analogous to the one for the unsynchronized +`spinnaker camera driver <../../spinnaker_camera_driver/doc/index.rst>`_. + +How to use +========== + +It is recommended to first get the cameras working with SpinView, then with the single-camera +driver individually before proceeding with the synchronized setup. + +The synchronized camera server works by instantiating a number of individual +camera servers and exposure controllers. Each camera server is fully configurable +with all parameters available as listed in the +`spinnaker camera driver <../../spinnaker_camera_driver/doc/index.rst>`_. Likewise +each exposure controller has its own parameter set. + +There are two types of controllers: master controllers and followers. The master controllers +regulate the brightness of the camera they are controlling, while follower controllers +set the exposure parameters of the camera they are controlling based on the exposure parameters +of the master controller they follow. + +Since there are many parameters involved the setup can be tricky. It is recommended to start from +the ``follower_example.launch.py`` example when using a stereo camera for e.g. VIO, +or the ``master_example.launch.py`` when running cameras with individual exposure control. + +Topics +------ + +Published: + +- ``~//image_raw``: the synchronized camera image +- ``~//camera_info``: the synchronized camera calibration messages +- ``~//meta``: synchronized meta data like exposure time and gain + + +Synchronized server parameters +------------------------------ + +- ``cameras`` (list of strings): names of the cameras. Default: empty list. +- ``exposure_controllers`` (list of strings): names of the exposure controllers. + List must be of same length as the list of camera names. + + +Camera server parameters +------------------------ + +For a list of all parameters, see the `spinnaker camera driver <../../spinnaker_camera_driver/doc/index.rst>`_. +The parameters are exposed under ``.parameter``. + + +Exposure controller parameters +------------------------------ + +- Master exposure controller: + - ``brightness target`` (int): average image brightness to accomplish. Value range is [0..255]. Default: 120. + - ``brightness_tolerance`` (int): how much actual brightness can deviate for ``brightness_target`` before the control parameters + are updated. Default: 5. + - ``exposure_parameter`` (string): Name of the ROS parameter under which exposure time is accessible for the single camera driver. + This must match the ros parameter name associated with the Spinnaker node that controls exposure time, which is + set in the camera ``.yaml`` config file. Default: ``exposure_time``. + - ``gain_parameter`` (string): Name of the ROS parameter controlling camera gain. See camera ``.yaml`` config file. Default: ``gain``. + - ``gain_priority`` (boolean): Gain priority means: If image is too bright, first try reducing the gain, + and only update exposure time if gain is zero. If image is too dark, first try increasing the exposure time, + and only increase gain if maximum exposure time has been reached. Time priority means: if image is too bright, + first try reducing the exposure time, and only when ``min_exposure_time`` has been reached, reduce the gain. If image + is too dark and gain is below ``max_gain``, increase the gain, otherwise increase the exposure time. Default: false (i.e. use Time priority). + - ``max_exposure_time`` (int): Maximum exposure time (in microseconds). Default: 1000. + - ``max_frames_skip`` (int): It sometimes takes a few frames before a change commanded to exposure time or gain will actually + be executed by the camera, and the frame meta data will indicate the change. After commanding a change of exposure + parameters, the exposure controller will wait for at most ``max_frames_skip`` before it gives up and sends a new + command to change exposure parameters (gain or time). Default: 10. + - ``max_gain`` (float): Maximum gain (in db). Default: 10.0 + - ``min_exposure_time`` (int): Minimum exposure time (in microseconds). This is not a hard limit, but has the following + function: if the brightness needs to be reduced and the exposure time would fall below ``min_exposure_time``, then the + gain (if greater than zero) is reduced first. Only if the gain is zero and the image is still too bright will the + exposure time be reduced below ``min_exposure_time``. Default: 1us +- Follower exposure controller: + - ``exposure_parameter`` (string): see Master exposure controller. + - ``gain_parameter`` (string): see Master exposure controller. + - ``master`` (string): the name of the master controller to use + - ``max_frames_skip`` (int): see Master exposure controller. + +Example usage +------------- + +The driver comes with two example launch files that need to be modified for your purposes (update serial numbers etc). +The ``follower_example.launch.py`` can be used as template for stereo cameras, the ``master_example.launch.py`` for situations +where each camera should run their own exposure control. + +:: + + ros2 launch spinnaker_synchronized_camera_driver follower_example.launch.py + +Carefully examine the camera parameters that are set in the launch file, in particular the following ones: + +- ``compute_brightness`` must be true for any camera governed by a master controller. +- ``exposure_auto`` must be off (disable the individual camera controller). +- ``chunk_mode_active`` must be true, and chunk exposure time, gain and frame id must be enabled + + +Known issues +============ + +See the caveats for the `spinnaker camera driver <../../spinnaker_camera_driver/doc/index.rst>`_. + +How to contribute +================= + +Bug fixes and config files for new cameras are greatly appreciated. +Before submitting a pull request, run this to see if your commit passes +some basic lint tests: + +:: + + colcon test --packages-select spinnaker_synchronized_camera_driver && colcon test-result --verbose + +License +======= + +This software is issued under the Apache License Version 2.0.