From 93b57808bfb1663e134918688aa870a4b2ade844 Mon Sep 17 00:00:00 2001 From: Prashanth Ramadoss Date: Sat, 28 Nov 2020 19:14:49 +0100 Subject: [PATCH 1/8] Add ArucoDetector class to PerceptionFeatures library --- src/Perception/CMakeLists.txt | 26 +- .../Perception/Features/ArucoDetector.h | 142 ++++++++ src/Perception/src/ArucoDetector.cpp | 305 ++++++++++++++++++ 3 files changed, 465 insertions(+), 8 deletions(-) create mode 100644 src/Perception/include/BipedalLocomotion/Perception/Features/ArucoDetector.h create mode 100644 src/Perception/src/ArucoDetector.cpp diff --git a/src/Perception/CMakeLists.txt b/src/Perception/CMakeLists.txt index 280b5009c8..23b886855d 100644 --- a/src/Perception/CMakeLists.txt +++ b/src/Perception/CMakeLists.txt @@ -2,13 +2,23 @@ # This software may be modified and distributed under the terms of the # GNU Lesser General Public License v2.1 or any later version. -if(FRAMEWORK_COMPILE_Perception AND FRAMEWORK_COMPILE_RealsenseCapture) - set(H_PREFIX include/BipedalLocomotion/Perception/Capture) +if(FRAMEWORK_COMPILE_Perception) + if(FRAMEWORK_COMPILE_RealsenseCapture) + set(H_PREFIX include/BipedalLocomotion/Perception/Capture) + add_bipedal_locomotion_library( + NAME PerceptionCapture + SOURCES src/RealSense.cpp + PUBLIC_HEADERS ${H_PREFIX}/RealSense.h + PUBLIC_LINK_LIBRARIES BipedalLocomotion::ParametersHandler BipedalLocomotion::TextLogging BipedalLocomotion::PerceptionInterface ${realsense2_LIBRARY} + INSTALLATION_FOLDER Perception/Capture) + endif() + + set(H_PREFIX include/BipedalLocomotion/Perception/Features) add_bipedal_locomotion_library( - NAME PerceptionCapture - SOURCES src/RealSense.cpp - PUBLIC_HEADERS ${H_PREFIX}/RealSense.h - PUBLIC_LINK_LIBRARIES BipedalLocomotion::ParametersHandler BipedalLocomotion::TextLogging BipedalLocomotion::PerceptionInterface ${realsense2_LIBRARY} - INSTALLATION_FOLDER Perception/Capture) + NAME PerceptionFeatures + SOURCES src/ArucoDetector.cpp + PUBLIC_HEADERS ${H_PREFIX}/ArucoDetector.h + SUBDIRECTORIES tests/Perception/Features + PUBLIC_LINK_LIBRARIES BipedalLocomotion::ParametersHandler BipedalLocomotion::GenericContainer BipedalLocomotion::CommonConversions BipedalLocomotion::System ${OpenCV_LIBS} Eigen3::Eigen BipedalLocomotion::TextLogging + INSTALLATION_FOLDER Perception/Features) endif() - diff --git a/src/Perception/include/BipedalLocomotion/Perception/Features/ArucoDetector.h b/src/Perception/include/BipedalLocomotion/Perception/Features/ArucoDetector.h new file mode 100644 index 0000000000..112a807bb1 --- /dev/null +++ b/src/Perception/include/BipedalLocomotion/Perception/Features/ArucoDetector.h @@ -0,0 +1,142 @@ +/** + * @file ArucoDetector.h + * @authors Prashanth Ramadoss + * @copyright 2020 Istituto Italiano di Tecnologia (IIT). This software may be modified and + * distributed under the terms of the GNU Lesser General Public License v2.1 or any later version. + */ + +#ifndef BIPEDAL_LOCOMOTION_PERECEPTION_FEATURES_ARUCO_H +#define BIPEDAL_LOCOMOTION_PERECEPTION_FEATURES_ARUCO_H + +#include +#include + +#include +#include + +#include +#include + +namespace BipedalLocomotion +{ +namespace Perception +{ + +/** + * Aruco marker identifiers + */ +struct ArucoMarkerData +{ + /** + * Marker ID + */ + int id{-1}; + + /** + * Marker corners in camera coordinates + * in the order + * - top left + * - top right + * - bottom right + * - bottom left + */ + std::vector corners; + + /** + * Pose of the marker in camera frame + * cam_H_marker + */ + Eigen::Matrix4d pose; +}; + + +/** + * Aruco detector output + */ +struct ArucoDetectorOutput +{ + std::unordered_map markers; + double timeNow{-1.0}; +}; + +class ArucoDetector : public System::Advanceable +{ +public: + ArucoDetector(); + ~ArucoDetector(); + + /** + * Initialize the detector + * @note The following parameter are required by the filter: + * - "marker_dictionary" OpenCV predefined aruco marker dictionary + * (available options: "4X4_50", "4X4_100", "4X4_250", "4X4_1000", + * "5X5_50", "5X5_100", "5X5_250", "5X5_1000", + * "6X6_50", "6X6_100", "6X6_250", "6X6_1000", + * "7X7_50", "7X7_100", "7X7_250", "7X7_1000", + * "ARUCO_ORIGINAL", + * "APRILTAG_16h5", "APRILTAG_25h9", "APRILTAG_36h10","APRILTAG_36h11") + * options coherent with https://docs.opencv.org/master/d9/d6a/group__aruco.html#gac84398a9ed9dd01306592dd616c2c975 + * - "marker_length" marker length in m + * - "camera_matrix" 9d vector representing the camera calbration matrix in row major order + * - "distortion_coefficients" 5d vector containing camera distortion coefficients + * @param[in] handlerWeak weak pointer to a ParametersHandler::IParametersHandler interface + * @tparameter Derived particular implementation of the IParameterHandler + * @return True in case of success, false otherwise. + */ + bool initialize(std::weak_ptr handler); + + /** + * Set image for which markers need to be detecte + * @param[in] inputImg image as OpenCV mat + * @param[in] timeNow current time in chosen time units + * @return True in case of success, false otherwise + */ + bool setImage(const cv::Mat& inputImg, double timeNow); + + /** + * Compute one step of the detector + * @return True in case of success, false otherwise + */ + bool advance() final; + + /** + * Get the detected markers' data from the current step + * @return A struct containing a map container of detected markers. + */ + const ArucoDetectorOutput& get() const final; + + /** + * Get the detected marker data + * @param[in] id marker id + * @param[in] markerData detected marker identifiers data + * @return True in case of success, false if marker was not detected + */ + bool getDetectedMarkerData(const int& id, ArucoMarkerData& markerData); + + /** + * Get the image with drawn detected markers + * @param[in] outputImg image with detected markers drawn on it + * @param[in] drawFrames draw also estimated marker poses, set to false by default + * @param[in] axisLengthForDrawing axis length for drawing the frame axes, 0.1 by default + * @return True in case of success, false if no marker was detected + */ + bool getImgWithDetectedMarkers(cv::Mat& outputImg, + const bool& drawFrames = false, + const double& axisLengthForDrawing = 0.1); + + /** + * Determines the validity of the object retrieved with get() + * @return True if the object is valid, false otherwise. + */ + bool isValid() const final; + +private: + class Impl; + std::unique_ptr m_pimpl; +}; + +} // namespace Perception +} // namespace BipedalLocomotion + +#endif // BIPEDAL_LOCOMOTION_PERECEPTION_FEATURES_ARUCO_H + diff --git a/src/Perception/src/ArucoDetector.cpp b/src/Perception/src/ArucoDetector.cpp new file mode 100644 index 0000000000..875911ada0 --- /dev/null +++ b/src/Perception/src/ArucoDetector.cpp @@ -0,0 +1,305 @@ +/** + * @file ArucoDetector.cpp + * @authors Prashanth Ramadoss + * @copyright 2020 Istituto Italiano di Tecnologia (IIT). This software may be modified and + * distributed under the terms of the GNU Lesser General Public License v2.1 or any later version. + */ + +#include +#include +#include +#include + +using namespace BipedalLocomotion::ParametersHandler; +using namespace BipedalLocomotion::GenericContainer; +using namespace BipedalLocomotion::Perception; +using namespace BipedalLocomotion::Conversions; + +#include +#include +#include + +class ArucoDetector::Impl +{ +public: + /** + * clear all internal buffers + */ + void resetBuffers(); + + // parameters + cv::Ptr dictionary; /**< container with detected markers data */ + double markerLength; /**< marker length*/ + cv::Mat cameraMatrix; /**< camera calibration matrix*/ + cv::Mat distCoeff; /**< camera distortion coefficients*/ + + ArucoDetectorOutput out; /**< container with detected markers data */ + cv::Mat currentImg; /**< currently set image */ + double currentTime{-1.0}; /** time at which currentImg was set */ + std::vector currentDetectedMarkerIds; /**< currently detected marker ids */ + std::vector > currentDetectedMarkerCorners; /**< currently detected marker corners */ + std::vector currentDetectedMarkersRotVecs, currentDetectedMarkersTransVecs; /**< currently detected marker rotation and translation vectors */ + + bool initialized{false}; /**< flag to check if detector was initialized properly */ + + cv::Mat R; /**< placeholder rotation matrix as cv Mat object*/ + Eigen::Matrix3d Reig; /**< placeholder rotation matrix as Eigen object*/ + Eigen::Vector3d teig; /**< placeholder translation vector as Eigen object*/ + Eigen::Matrix4d poseEig; /**< placeholder pose matrix as Eigen object*/ + + /** + * Utility map for choosing Aruco marker dictionary depending on user parameter + */ + std::unordered_map availableDict{{"4X4_50", cv::aruco::PREDEFINED_DICTIONARY_NAME::DICT_4X4_50}, + {"4X4_100", cv::aruco::PREDEFINED_DICTIONARY_NAME::DICT_4X4_100}, + {"4X4_250", cv::aruco::PREDEFINED_DICTIONARY_NAME::DICT_4X4_250}, + {"4X4_1000",cv::aruco::PREDEFINED_DICTIONARY_NAME::DICT_4X4_1000}, + {"5X5_50", cv::aruco::PREDEFINED_DICTIONARY_NAME::DICT_5X5_50}, + {"5X5_100", cv::aruco::PREDEFINED_DICTIONARY_NAME::DICT_5X5_100}, + {"5X5_250", cv::aruco::PREDEFINED_DICTIONARY_NAME::DICT_5X5_250}, + {"5X5_1000",cv::aruco::PREDEFINED_DICTIONARY_NAME::DICT_5X5_1000}, + {"6X6_50", cv::aruco::PREDEFINED_DICTIONARY_NAME::DICT_6X6_50}, + {"6X6_100", cv::aruco::PREDEFINED_DICTIONARY_NAME::DICT_6X6_100}, + {"6X6_250", cv::aruco::PREDEFINED_DICTIONARY_NAME::DICT_6X6_250}, + {"6X6_1000",cv::aruco::PREDEFINED_DICTIONARY_NAME::DICT_6X6_1000}, + {"7X7_50", cv::aruco::PREDEFINED_DICTIONARY_NAME::DICT_7X7_50}, + {"7X7_100", cv::aruco::PREDEFINED_DICTIONARY_NAME::DICT_7X7_100}, + {"7X7_250", cv::aruco::PREDEFINED_DICTIONARY_NAME::DICT_7X7_250}, + {"7X7_1000",cv::aruco::PREDEFINED_DICTIONARY_NAME::DICT_7X7_1000}, + {"ARUCO_ORIGINAL",cv::aruco::PREDEFINED_DICTIONARY_NAME::DICT_ARUCO_ORIGINAL}, + {"APRILTAG_16h5", cv::aruco::PREDEFINED_DICTIONARY_NAME::DICT_APRILTAG_16h5}, + {"APRILTAG_25h9", cv::aruco::PREDEFINED_DICTIONARY_NAME::DICT_APRILTAG_25h9}, + {"APRILTAG_36h10",cv::aruco::PREDEFINED_DICTIONARY_NAME::DICT_APRILTAG_36h10}, + {"APRILTAG_36h11", cv::aruco::PREDEFINED_DICTIONARY_NAME::DICT_APRILTAG_36h11} }; +}; + +ArucoDetector::ArucoDetector() : + m_pimpl(std::make_unique()) +{ +} + +ArucoDetector::~ArucoDetector() = default; + +bool ArucoDetector::initialize(std::weak_ptr handler) +{ + std::string_view printPrefix = "[ArucoDetector::initialize] "; + auto handle = handler.lock(); + if (handle == nullptr) + { + log()->error("{} " + "The parameter handler has expired. Please check its scope.", printPrefix); + return false; + } + + std::string dictName; + if (!handle->getParameter("marker_dictionary", dictName)) + { + log()->error("{} " + "The parameter handler could not find \" marker_dictionary \" in the configuration file.", + printPrefix); + return false; + } + + if (m_pimpl->availableDict.find(dictName) == m_pimpl->availableDict.end()) + { + std::cerr << printPrefix + << "Undefined value set to \" marker_dictionary \" in the configuration file. Please choose one among \n" + << "available options: \"4X4_50\", \"4X4_100\", \"4X4_250\", \"4X4_1000\", \n" + << "\"5X5_50\", \"5X5_100\", \"5X5_250\", \"5X5_1000\", \n" + << "\"6X6_50\", \"6X6_100\", \"6X6_250\", \"6X6_1000\", \n" + << "\"7X7_50\", \"7X7_100\", \"7X7_250\", \"7X7_1000\", \n" + << " \"ARUCO_ORIGINAL\", \n" + << " \"APRILTAG_16h5\", \"APRILTAG_25h9\", \"APRILTAG_36h10\",\"APRILTAG_36h11\". \n" + << "options coherent with https://docs.opencv.org/master/d9/d6a/group__aruco.html#gac84398a9ed9dd01306592dd616c2c975" + << std::endl; + return false; + } + + m_pimpl->dictionary = cv::aruco::getPredefinedDictionary(m_pimpl->availableDict.at(dictName)); + + if (!handle->getParameter("marker_length", m_pimpl->markerLength)) + { + log()->error("{} " + "The parameter handler could not find \" marker_length \" in the configuration file.", + printPrefix); + return false; + } + + std::vector calibVec; + if (!handle->getParameter("camera_matrix", + GenericContainer::make_vector(calibVec, GenericContainer::VectorResizeMode::Resizable))) + { + log()->error("{} " + "The parameter handler could not find \" camera_matrix \" in the configuration file.", + printPrefix); + return false; + } + + m_pimpl->cameraMatrix = cv::Mat(3, 3, CV_64F); + std::memcpy(m_pimpl->cameraMatrix.data, calibVec.data(), calibVec.size()*sizeof(double)); + + std::vector distCoeffVec; + if (!handle->getParameter("distortion_coefficients", + GenericContainer::make_vector(distCoeffVec, GenericContainer::VectorResizeMode::Resizable))) + { + log()->error("{} " + "The parameter handler could not find \" distortion_coefficients \" in the configuration file.", + printPrefix); + return false; + } + + m_pimpl->distCoeff = cv::Mat(5, 1, CV_64F); + std::memcpy(m_pimpl->distCoeff.data, distCoeffVec.data(), distCoeffVec.size()*sizeof(double)); + + m_pimpl->initialized = true; + return true; +} + +bool ArucoDetector::setImage(const cv::Mat& inputImg, double timeNow) +{ + std::string_view printPrefix = "[ArucoDetector::setImage] "; + if (!m_pimpl->initialized) + { + log()->error("{} " + "Unable to set image. Please initialize the ArucoDetector before setting the image.", + printPrefix); + return false; + } + + inputImg.copyTo(m_pimpl->currentImg); + m_pimpl->currentTime = timeNow; + + return true; +} + +bool ArucoDetector::advance() +{ + std::string_view printPrefix = "[ArucoDetector::advance] "; + if (!m_pimpl->initialized) + { + log()->error("{} " + "Unable to run advance(). Please initialize the ArucoDetector first.", + printPrefix); + return false; + } + + if (m_pimpl->currentImg.empty()) + { + log()->error("{} " + "Unable to run advance(). Please set an image first.", + printPrefix); + return false; + } + + m_pimpl->resetBuffers(); + std::vector > detectedmarkerCorners; + cv::aruco::detectMarkers(m_pimpl->currentImg, + m_pimpl->dictionary, + m_pimpl->currentDetectedMarkerCorners, + m_pimpl->currentDetectedMarkerIds); + + if (m_pimpl->currentDetectedMarkerIds.size() > 0) + { + cv::aruco::estimatePoseSingleMarkers(m_pimpl->currentDetectedMarkerCorners, + m_pimpl->markerLength, + m_pimpl->cameraMatrix, + m_pimpl->distCoeff, + m_pimpl->currentDetectedMarkersRotVecs, + m_pimpl->currentDetectedMarkersTransVecs); + + for (std::size_t idx = 0; idx < m_pimpl->currentDetectedMarkerIds.size(); idx++) + { + cv::Rodrigues(m_pimpl->currentDetectedMarkersRotVecs[idx], m_pimpl->R); + cv::cv2eigen(m_pimpl->R, m_pimpl->Reig); + m_pimpl->teig << m_pimpl->currentDetectedMarkersTransVecs[idx](0), + m_pimpl->currentDetectedMarkersTransVecs[idx](1), + m_pimpl->currentDetectedMarkersTransVecs[idx](2); + + m_pimpl->poseEig = toEigenPose(m_pimpl->Reig, m_pimpl->teig); + ArucoMarkerData markerData{m_pimpl->currentDetectedMarkerIds[idx], + m_pimpl->currentDetectedMarkerCorners[idx], + m_pimpl->poseEig}; + m_pimpl->out.markers[m_pimpl->currentDetectedMarkerIds[idx]] = markerData; + } + m_pimpl->out.timeNow = m_pimpl->currentTime; + } + + + return true; +} + +const ArucoDetectorOutput& ArucoDetector::get() const +{ + return m_pimpl->out; +} + +bool ArucoDetector::isValid() const +{ + if (!m_pimpl->initialized) + { + return false; + } + + return true; +} + +bool ArucoDetector::getDetectedMarkerData(const int& id, ArucoMarkerData& markerData) +{ + if (m_pimpl->out.markers.find(id) == m_pimpl->out.markers.end()) + { + return false; + } + + markerData = m_pimpl->out.markers.at(id); + return true; +} + + +bool ArucoDetector::getImgWithDetectedMarkers(cv::Mat& outputImg, + const bool& drawFrames, + const double& axisLengthForDrawing) +{ + std::size_t nrDetectedMarkers = m_pimpl->currentDetectedMarkerIds.size(); + if (m_pimpl->currentImg.empty() || nrDetectedMarkers > 0) + { + return false; + } + + m_pimpl->currentImg.copyTo(outputImg); + + if (outputImg.empty()) + { + return false; + } + + cv::aruco::drawDetectedMarkers(outputImg, + m_pimpl->currentDetectedMarkerCorners, + m_pimpl->currentDetectedMarkerIds); + + if (drawFrames) + { + for (std::size_t idx = 0; idx < nrDetectedMarkers; idx++) + { + cv::aruco::drawAxis(outputImg, + m_pimpl->cameraMatrix, + m_pimpl->distCoeff, + m_pimpl->currentDetectedMarkersRotVecs[idx], + m_pimpl->currentDetectedMarkersTransVecs[idx], + axisLengthForDrawing); + } + + } + + return true; +} + + +void ArucoDetector::Impl::resetBuffers() +{ + currentDetectedMarkerCorners.clear(); + currentDetectedMarkerIds.clear(); + currentDetectedMarkersRotVecs.clear(); + currentDetectedMarkersTransVecs.clear(); + out.markers.clear(); + out.timeNow = -1.0; +} From 8229baf73aa50dcfd63ba8f52855c7524d4656a7 Mon Sep 17 00:00:00 2001 From: Prashanth Ramadoss Date: Sun, 29 Nov 2020 00:31:52 +0100 Subject: [PATCH 2/8] [Perception] Add ArucoDetectorTest and bugfix ArucoDetector --- src/Perception/src/ArucoDetector.cpp | 2 +- .../Perception/Features/ArucoDetectorTest.cpp | 50 ++++++++++++++++++ .../tests/Perception/Features/CMakeLists.txt | 12 +++++ .../Features/ResourceFolderPath.h.in | 19 +++++++ .../Features/aruco-detector/aruco-sample.png | Bin 0 -> 447723 bytes 5 files changed, 82 insertions(+), 1 deletion(-) create mode 100644 src/Perception/tests/Perception/Features/ArucoDetectorTest.cpp create mode 100644 src/Perception/tests/Perception/Features/CMakeLists.txt create mode 100644 src/Perception/tests/Perception/Features/ResourceFolderPath.h.in create mode 100644 src/Perception/tests/Perception/Features/aruco-detector/aruco-sample.png diff --git a/src/Perception/src/ArucoDetector.cpp b/src/Perception/src/ArucoDetector.cpp index 875911ada0..78fb7d2a7d 100644 --- a/src/Perception/src/ArucoDetector.cpp +++ b/src/Perception/src/ArucoDetector.cpp @@ -260,7 +260,7 @@ bool ArucoDetector::getImgWithDetectedMarkers(cv::Mat& outputImg, const double& axisLengthForDrawing) { std::size_t nrDetectedMarkers = m_pimpl->currentDetectedMarkerIds.size(); - if (m_pimpl->currentImg.empty() || nrDetectedMarkers > 0) + if (m_pimpl->currentImg.empty() || nrDetectedMarkers <= 0) { return false; } diff --git a/src/Perception/tests/Perception/Features/ArucoDetectorTest.cpp b/src/Perception/tests/Perception/Features/ArucoDetectorTest.cpp new file mode 100644 index 0000000000..dd463e7739 --- /dev/null +++ b/src/Perception/tests/Perception/Features/ArucoDetectorTest.cpp @@ -0,0 +1,50 @@ +/** + * @file ArucoDetectorTest.cpp + * @authors Prashanth Ramadoss + * @copyright 2020 Istituto Italiano di Tecnologia (IIT). This software may be modified and + * distributed under the terms of the GNU Lesser General Public License v2.1 or any later version. + */ + +// Catch2 +#include +#include + +#include +#include +#include +#include + +using namespace BipedalLocomotion::Perception; +using namespace BipedalLocomotion::ParametersHandler; + +TEST_CASE("Aruco Detector") +{ + std::shared_ptr parameterHandler = std::make_shared(); + parameterHandler->setParameter("marker_dictionary", "4X4_50"); + parameterHandler->setParameter("marker_length", 0.806); + parameterHandler->setParameter("camera_matrix", std::vector{922.309448242188,0,664.546813964844,0,922.194458007813,348.770141601563,0,0,1}); + parameterHandler->setParameter("distortion_coefficients", std::vector{0.0, 0.0, 0.0, 0.0, 0.0}); + + // // Instantiate the estimator + ArucoDetector detector; + REQUIRE(detector.initialize(parameterHandler)); + + auto imgName = getSampleImagePath(); + auto inputImg = cv::imread(imgName); + + REQUIRE(detector.setImage(inputImg, 0.1)); + REQUIRE(detector.advance()); + + cv::Mat outputImage; + REQUIRE(detector.getImgWithDetectedMarkers(outputImage, /*drawFrames=*/ true, /*axisLengthForDrawing=*/ 0.3)); + + // Marker 2 is detected in the sample image + ArucoMarkerData marker2; + REQUIRE(detector.getDetectedMarkerData(/*id=*/ 2, marker2)); + REQUIRE(marker2.id == 2); + + /* // uncomment this block to view the output image + cv::imshow("outputImage", outputImage); + cv::waitKey(); + */ +} diff --git a/src/Perception/tests/Perception/Features/CMakeLists.txt b/src/Perception/tests/Perception/Features/CMakeLists.txt new file mode 100644 index 0000000000..ad6586e421 --- /dev/null +++ b/src/Perception/tests/Perception/Features/CMakeLists.txt @@ -0,0 +1,12 @@ +# Copyright (C) 2020 Istituto Italiano di Tecnologia (IIT). All rights reserved. +# This software may be modified and distributed under the terms of the +# GNU Lesser General Public License v2.1 or any later version. + +include_directories(${CMAKE_CURRENT_BINARY_DIR}) +configure_file("${CMAKE_CURRENT_SOURCE_DIR}/ResourceFolderPath.h.in" "${CMAKE_CURRENT_BINARY_DIR}/ResourceFolderPath.h" @ONLY) +add_bipedal_test( + NAME ArucoDetectorTest + SOURCES ArucoDetectorTest.cpp + LINKS BipedalLocomotion::PerceptionFeatures ${OpenCV_LIBS}) + + diff --git a/src/Perception/tests/Perception/Features/ResourceFolderPath.h.in b/src/Perception/tests/Perception/Features/ResourceFolderPath.h.in new file mode 100644 index 0000000000..805c738c7f --- /dev/null +++ b/src/Perception/tests/Perception/Features/ResourceFolderPath.h.in @@ -0,0 +1,19 @@ +/** + * @file ResourceFolderPath.h(.in) + * @authors Stefano Dafarra + * @copyright 2020 Istituto Italiano di Tecnologia (IIT). This software may be modified and + * distributed under the terms of the GNU Lesser General Public License v2.1 or any later version. + */ + +#ifndef RESOURCE_FOLDERPATH_H_IN +#define RESOURCE_FOLDERPATH_H_IN + +#define SOURCE_CONFIG_DIR "@CMAKE_CURRENT_SOURCE_DIR@" + +inline std::string getSampleImagePath() +{ + return std::string(SOURCE_CONFIG_DIR) + "/aruco-detector/aruco-sample.png"; +} + +#endif // RESOURCE_FOLDERPATH_H_IN + diff --git a/src/Perception/tests/Perception/Features/aruco-detector/aruco-sample.png b/src/Perception/tests/Perception/Features/aruco-detector/aruco-sample.png new file mode 100644 index 0000000000000000000000000000000000000000..635fc39cb9aeb31ed6449fca41d0baa0e8254184 GIT binary patch literal 447723 zcmV)JK)b(*P)Px%j!;ZgMPOoAR$Nqbd3kJXXJBAkU|&;dYGh<#R$*dY zWM*J_fPZ0QT8M*wU}9BUV_;ohSdEE>iH(e7WLJrWfn8u#Zf|F7Ze(w8YG-e5Xlh`a zn3|}jrGI^SU}$K5dv|AOVs>?IlaiF4nw?{6X>4g>m5_^mdvtDhc3WIjW@uh}cXF4R zn2?N!c71$kWm|uRg_o0%d3SD%jfkwMtYu+aa&BjYgoSEnUTfWlw8YoR^h=e|Btia${?3qMw{vTu+{xmvVM? za&u~>p`~3|QHqRzQ*>O7je}KgT2)w4TnYt?ii?AVc!q*{b#-!M4+>^zTzhkFv8%4M zue4}xYHV$4SYTaUVo!&NdXtlnXlQALi;G`kVq#=leSvUHZBJ8CO^1bsjDmo~z`#{r zOPHIGdV71Ao1J)jZaOtKRCHCz#Ke%3hK-e$PIXj^k&u#=iqFZ)93Uc@m41bdfPsj6 zbZ%vOfoi3ws%d3ml8AGn?w22n~wla6^wKRY%M z3_K_!Rvj9ooQJWgm~?4mCM+m^bhMNJ2GRRTL_t(|+LV2PU(@%sHdtJ(tJZeT(NNkY%+=P}dK<@9^#(8Y$E3rN ztJP=|0^Mz{Wh%N@T3$A%iE2mL3}~fd#rj_LMY@7~A_dMsE z@Avl$s@?r1gd{{%NS-|BJkNPf(F-qp@WBgoJo@Mh$3Ohw!w)~e@#b4{youwjH|6u2 zZ=O8)+G~%#_S(t+{N2XAXU_cS_g{SR<(IiHb9^-NM?BXUr;B(zXO3(x7s};gxmY|L z9^@lp566*@NTlEC=Ocn!_+v3#ghE+8c@HPj-;?l#(tM-vi`jT6PG>sd?z9thg28^A zqH+ZLlf%Qq{ry3@I~k28qsjgx{jJepFqKNtza^HYKN(N+_n<$I1GnOQEtN{A<*&q< z9*|BZ68U_7w0T=o9lixWJRWasJc#2cjuU#E=i{^UpV4tikH22}>%9+s3?5H^5Z{8o z-%|U`qa8B$0gfG)!x{|u%hz9v5#XqmQx+tB#sH5{2OVe0FVlkXUxG;~4*+&2)ayf@S$^CSS$AAG0 z8f9BY*RMHKyYd1bBNs+S=;K1^2wgAbt0TCIdwb~^p^pnA{HeFMuXm)iwUxe%`}@o> zVz2cTz3{>>K6vYc4^AFG{=$bJ9{=#elPBMN>jQutD12 zrJU~?=<3RM(T|Jpihklrhh9Y4?9nVfaIKMksB~cX^%RI8`}*Z~4N_yZ7EPhSEiTJX~c(-quVTEAHV@CFd@^v%

C4 zmze?$GH8@-Tl~ZWOKN9dxK8+Yo$#)nLGbAj!oLe6ts{JkE?Wuk2=M@Z0)KSbM*!H1 z$9MtIa}@pJC(QazzD8$afX7dseCsV{fq=S`pPW2N$VVvn&Z(29PW_HPo9`?)a+7bQlnSN<1Nm$}QWpMF^g67jPk=vwU>)$U4y+Cz zQH4K%A773F0(}WOCzuTq{%sQmxGm7Utr_$uF*-1(s~aqkeq2@lfUhBt4B{oJa3%~e zZh`NhT%nVJL-%gW024j<@%sq_lgt2*j1LX%WBOOVrF_d4kic?-X$*C^-oemU4-712 z(8H}#zEUrokp66`Fu?lV>;J|8NbtuT(BNMI{M{r3q449*d z(Gb9xUo*5e74*U%NMO*xvojb417rY9Ch|)O|3Dh?B85%%iJWC4t}pA$hb* z?UX2l7&SdK#S!=u*bBvDTvEki4&!2+?^KxN*EIkz7O{jU9s^{c3LIqK^u^Zs&z6*o zy?tTCoJIg?e6-@)_3QK@cQW)b1oAv(fq{VxsV@966ZCLETkxi}2#&k;a6EQd`b$*6@syxo z0s1Kol=4?zM_dQjHOVLNzo^#0D1w^<=bEypzfSn|%3hK&S%XK)#!?k4}t$-GqOZ z0|Eq_@a{uD@jATMr_j{Fo4T}i((+fK1U3kmGUWk1!(&1h@Vv)m%!NR~J^{`U6M{5D zn-UW5E6)kt!2#onlCd~pUR;Xb7z3f;pAbDK6p0W3^2?rH?fk9rbpRsw!v^c#oByk2 zMQ?NIdqL@*K;Y9O?(LBSz_?yiyg)wYe~N;79Pr@Z0Rw;ozXsqD;bQ=#`u4RKUU(B| z2fTad)F-Ei1b)KEcZ!hjHHO7gr(XQcj~;yRx#s|Y_GoMrDtHGAjO6-rf^bUwhWm$I z;>Xl)SkRE6kh+5SG0=NLOgLbUf8w4Wv(xbE+8!->vu<0?TPSCRD+1}j_oyTYa#>df z{0o8?;v+~!ILcojppy!l;=sJK;T;c85!~e{07`o>%a02N{HTCOeE}|k)7lhaY+|so zZNT#<+#aB}4R|m3WBmKfv;e2}01W^N{2gqJ^JnhI;2)flR-_?;;H3iNU&euc)QqJU zMmTOD&#i%l0^-M{g|PMk`2!bCTmmx!D){*r{}wkd2Kf0H1c8fNiH8v7VU7qKq{olu z8U4E2nFJ;RO$|wUWyJu2Az^@mhK&aGvYyKKXx0|QdV?4s@vLJ2!H)txRW&sXfS`bc zejCb7T?;OV(zl{wi$Ywz0A9WFLW_Dr|7Xoi<`%(pjqka6 z?VFGPaSND~NC*Km_~+Ka=;+bcIx>0mQ*8N*=VDNwsMMfAmnINM1_A_t=&btl!T`JS z16|#8;uhejob5rs1$ncnOX?d}DkYumAo}c%0o=5`1R6543mH0wQd#O!2BaJL+O~egGcoc9!-DLi-5Qp68y_@iOVH1;T(e={s}R@5~KSf_-g}Z@?`ML)+_5}YT zWo7+kLi8g21t@4~A)15SVThUbXgn7ye6xu;!Nl6iblL-U*}E~oSXx@l^xUeB(DMOJ zFJ^z{i3heB0srH7M$-yTn>Gpm%Hu{maDx5Z1LX1-osV=l*hKA_JW8EpRPiIOO~6L4 z407J^KT`%X1^ny%IG`(m7z8|ef@@$cgXM2~!FlBH+x_*Rw&0O?x?|&P8xvmNIUvm@pzeEZ_ zC$NhEkRY%s4^T*=4(8?)$e-{)Tj(Bik?-i;M39Dr|Cs+6Vd=3%4*_61^#BF_L<12!q z#R;K+fgYc)ClKhN&pm+#;9!7xp+9jZGfL0Fv{wU>qaXcfG^tSm2Yg-Kqbx1u{r-VD zV18Y6(dG64z4(VF;I^$zXuhfnA{3AgdWu`{Guj7TiMc40jw#Zm8KJ=c=stNdgg^{| zaSUhFVvol>JwNk0jTvg<;eV!=$1OfSg#P7lrq^^1%`S)40qy#u|Buo)4$27d z@d?d4PH^|;2d}+$it!HTQ>Sbx{MyNr&r=VOE(igC@X+)JfA(MDK~Kfoh<>0^g$oad z5wMIZ;Ie)#fB93c5CcU8k^eWh13&`f_Kiu=j-ES#uC>v0C>}3B#;l8d(z!5ivO#Kt zM1rUX!qj|;nCF}W_Jf;g{K^^hLbgGy<**e(==%_1WaPv104SJFB@^5NL|Z?Vj;5ri z(r8o)RY63+U<|Yr@Uu(zD}pa60vZB%UbSTYhFMP+&?|#@z|Kn7F7^TR`0ntRsD=l@ z0Z{^n75c)SCSYpNu)i-Lfe`eW#uU9SlS$kmpoUr(1dtAD|0SB40CMju0086;m?B`n zsKKO!bgdu=T#+Y4fc)g}%S%e&Y&Lrb`rQTpjtT?x`>Xsl1c1kSa0M#xki|c`0GM@b zv6Za{0;L}apu@FNm-ktqL=C)m-RW)yz#9T~r)>%B)j$jbv;a8DBCsC>(5J$0K&~+v zq+1<3nxjEO%Jl7+@eiH^p@4J*5?upC?4$xF0PL3jA8F~`-FZ~NUI3&TnD{u$?@dDg zQU?Db(gK8d;V|@h)E7XL1D+tgKZQUKwBaUwm9>$OHpOG1aM-d&7xaLqBA?{4IV0`z zw{b)bp+7-Bi|??=!f+?LNGmFH#arM) z2CivO!mWZ|P=OCdev|UPMVglARbbr_l0C!b`G6zB;#f>e1Fzz*0*Im^-^SC1TGRl= zENDMBghQ#M-;drGy~L9uCZxFp7Wi|8V7CQm0r0c?J7F#r*1%Q<&N2XI4|+rpImhL~ z%l8TnQv6(z1PU+^F=gdoZx1l&sen_q9f&hYlSwc@sezjU+eqUu2jGutUg`nT%b$y} z0EA&hKyl5WV<04O1%04S9Byb35(oyE&Q1|J?ofW+BjgbN`Kzk(RaM9QJ;!RQ+Q-kK z2e^+5VABNb*wV4Z6?rSH)?2EmXR*&JB0>R~Gj^1o{v7{8tUyxy=#0hw)H4YNIu25`3K^c)_$PFVu-_^OlK&> zwGcs|^zdR{$3;l-PvMXOQqT`C=A6jFVO4w`Rz_p&d&z|u1RcGOQ%p4xE`cM}1c0Zf z@1MmM7`Oc=m2O`vjy~pmy$p%`)jmKVSIJEI_!Hl1?c;|T06cJ@=&ir~`fqQ&$$GE! z_lORD!WA#b9)AV~QZI1k%$cWV&RjHe(X>TRZ(g@&_S^-T(;rF`&{aOXT|iF_4C@Qk zxCDGu1V_B8FC(5;2!=fd^c;OaW!Jzy$5og>#%fkHWLd((Pc)=5m$?5tZ44=}xVb@{ z;4m-{-#sR{mv+LYGa{l%TKQwvJYT}7g2VE>3Da|mo4|3%|5?^p8n~y^%pyn-g`}~; zun=rTkUJ63$ROX+1hhRsmO+jx1w0A}Y;3gMK=~Wvt{3nw7-+R&{C}tjCeu$i#jWtL zM+gz>P>qjh)Y}Gx`de40O0eo0+qN0_Lk9|Eg?fPK1>$uWAO_gXRuFZ-i6GkK=Z;oa zJL|!IKtvCk5pE~2pa8xP7&?AAs6HeBJYH490BCC94cz=AvS%n@ef<_!5#Ca2dxZ6+ zwk^oza=8K{*yFm>zgGa%!vlW|euV(|%{TwU00<)>i?<0uJot114PpZ%3YgC?Ia?># z#Q4|GEoruEC2>X-Oc+SYcJ}~UtUh|D7-jM|r+dyo*BosE7F58Hf$7w2Y%tenh|Er3lZ zAYCyWa72J_gaD5o#w3tVy#T;oMnY17-+2cN@DnC_a)DzJ;7+h_5uIOLM98;j8Uf&< zr|GCK-L!H+%k=5L8N55?`?8P}!rcrhxY}sH!&>wj=qsx(D~o6u%;sqB9f;Ue*y6)g zdcyd-^66|`9Luq|hmi9xQ+_`&q5XPh%ww}3m%aGqqA%fkLfH((&ks`$xP>sC2>_ER z#u9j8`0t7Yqbz$ii3*%HGKgT4VSuI$c%pyF>5!#24W%~4b1AtTm69;4wgt~w?u6eOf@ed_1 zi6DLkK&sC_VuK<{H9dlbiiXq&ICF+ubZUTs1k$gDRf0dVX$?0F4-;V=?M4aQ%o;Ei zzJz?;OR4%rD-dLm@z14z^fZ)itCYZ?f2e__xk!IkDy=k7v|yJ7>Pv*_AHQtUZZT|F zoujCi)~Yz<#A3z1-u%;1qZu7Sl%jS4xYT|iR|qcYBgv>z}HfK5NI0-~D%E&N~TG za8bwsr|2Fzu6S`KiK4oU41$q9uh%8(u>um2Xwr#|xVIr;DLDU<9H#B~ z4Wo_WumZ*X2Zlbv#IRc#pkhwjn%EK3JN`hNg)&lJ`cVTjtc2vRb_f8Qx!$8^G{3|0 zSF@^69QBsKh0`FPeVY~VQXvIYC*TQUf6M?69&Pk^U=9{q0gV~(&O%u3OT|ShW&})! zy*`*|N?$lu0cIbxnql}P91vBl&r-nV#l%&J{E-?=r{8x<20D@r06_A+P+!lez|;k#SsK28ozhZ3fk2+Y;U9X^ZCywsFo zO!|7&7G1<9=ij~a$)EopAMgM9`t{8?PrJT(=ld^SfAKo*xxVQA7pd%Bw|&}naujT- zD6gnkR@*Xn$By4`EmS=kJ^1Ijp9^52d(!xe z8MTdt4-g&#M5%=7wM@1^jKKu}fm8$w3MPC_$snxIP=OELxA-ma0aB+8NjQ{;2aGdvR!j*F}&=J;1Ixgn{gd_R1jm z=`#YdV@a+3YI8!T*Fd1#2b8CO%sMX80(>k5#;g}s2%vBZ5r*$DTnGWlO_`x{R0qL} z*ikDC(~FoCzqy=ZpG?X|1Op>n2s?%k!UYrg;=R9}-ZiTh6|krv*7t&&05O6>XdysB z20*Hgd$sY$Rv6RrYvqrTRus@&{}Kx<`pt`f{`2+!_x}jwu9KPi`kp-(_B_69-n_@J zKmN?)^B#Zv@p<3B{{4CLu77{eyglFFym|Awl^bSnD4#uhc5Q8@ZO4x3Z{-H3l)W3h=?5!7KF-)Up#j=vkN_O^6h@9fOX==aX~QVX%_0x zPE0^egm@>yN)&!2grH%Af!rwMzApnKKXVlQ#7dQ92AHP)UpCHflCelsD!ZnnDS_#$ z^v}|9-J{+jc&ZL!RFF&eF+y7aJnxZ#kBY*gGr?GB_S_Oyf|T* zk*TmI8eL0p5e!ox8Ag)XI~m}?Le@965@r?HpC>%2^7Z&@{Ovpm!YYVPgA^R)UJR^P z`->_cY?r4MrqF4?1=0OuX@o#Ke|9%L zxvGQwv=a0azbaM0B(^u;49x@p2-}QbW`OhTfu>8$)bQ;Aj}sa;7`!JnL8T9}3lPp% zW%rJb`xpy!3glA+!nEZ9B6-NmD6OJLOaU;)F9fQQO!E&&SUCO095L-7fob#2a_WE) zW&-|)c~-_jevP9KNC1c#SRjRCY#_{>Xb$ARfA+Iw<~=@l*|KML zeIH*S_}lcr-XA=*=b@D=%UABBW2`un$?VwiR+*;@$fFx~z@KXdL`6>*41V+(qrhy1 zjKt^^8I%Xa)EgAbg}eiBg%xmcnBEcDr0h~Z$Avw;iQk;*_bTa=H(u7FcwPsilJx#a za!ATNSRRkNwLameQV`wgerXBDWl$tUs6lq$0GEhSd44egjGG?d!J~zd2qy}ifcFBx zOLxe?9soS(0-&)&TQf{H?z#c*CI|~hh4Ml6XtqPAGcnpz{0!9;yNhrr%K5>EwbreesYavie9R|REE)GF3Fvxa0 zW`NXjBOl1Q#gwS^ja1MiLo}8HYX+_j@P!Nn#@rDkc~65eCX#|3ny9Ee6N8u^=0YNwi~#o7 zo!S6#P7DF@tR`ioXxmC;&h(t=PvLFf1uBOaOx({kKd#FjD!tIxvRZFb(VraHo&p zZ?PXD$l}G+0ra6Q01>2_nU5p`fEOABa8MF8<}0p6wP5*npoPU^3dDv`0@vLjpe;CXtx8Bs$m)=Et)j z-GYDlQ44_};5>NU6xE)sv;c!V4Z`o{X!t_z;sQ8Lepnk0qd`VO_R`{q;M-}ffF09T z5{eg#8FCjh23=ErrM+_q_A5DcTsztUq}O){O0S9@X!@b~Bsow91O+rAxw7}(`SIyl zEpN*ZT&tyjBdu?=nr5JtLevU~R2VbxJK~uE<~)QE4vC?`xC5*L6Z$>AY}Ye$SFU`h zwzhUz?bujb+gS0~+(UVkjFXNf< z%;eFeb}(#Z=pw6_N! z%S*S=F=iyKVbh`jE6m~TE@n#Wm}deV7u99leyJw7TVBR41Q=1N5P=zs-24G*NH;VD zdKNYeCmW0l)WB{R&@&K%gN=dk z#bi|n$?As@WeSyHR)SNeA(T#qt!I|gNP>!gWjIp@u#8S<1v2lmHL#fbH2j5mAVxt5 z{m=>o@R{KcWW)sI>l~S7@&SO4K56g!6Fm(YHIkj`fjN3F8W=(eTtgsJ!dZJke zp_G^cCm^B_j0_yq;U08%(SC8xK@gB3lPHx zGCE>rhIPVY%4~4V=)OV_#R20$-az?F7csW`DFUJ|#ojk3r{f{w1fdq-);Ul7%gMPp6fB)S5EyZm^MC#fO5$qNJlE~em zLz#(|Oj{9o{pJ?!`qNnL$~_g26GL42Ol>W}U)wkx=O!j5CwBbqi%9NXR_MmN;$TE= zKicTzAA++f|sWfa!`Ud5=vc7iyY(R-N`RJUYVa(R-jEKiaK*8{xsB^Khc43VGvS+*$a47F!rG6EsY2gU=y}2 zfej%Q^fMkon$}CR2QZwzGYrsUezv7=5-^BiIIV(R2!y%ChcG}+1ROO|h!4pyKCXc= zABPt`=+LO(K$C`}NZ_5wAb|k8VA2I0z@zu4fe=Be=$BFh6=We9p;-j!?6jkBcOK#e z^g>^$O^I=vg%}=26buE&kPXK40Lce)+fKrHp-<;Rh$4Q>Hkdq+PeD+!0jvB{|4OjI zXny??KQ&bxvH$T?Qfz>TYEu#zXc+b-y7EjK{Z%Z1aMjzz)vqKXOc{ma8h9JOOX(0ov@xt0oE5Gy9rj`)LlQ6)5On*T6U=!dd$6|@>3yIigi(p|wIvNttVLH@=WRgp; z&L8{V1fqtB0TTSx0Aol6UO{nKnKl7HMzQiOcVeKixzt+@h_T;#gNo&b8;Tj40q|2Z z3VhwDAQJvpm)A*xHs)mDMC+&`gXp>xT zaOJ99bm?~ol}(_H6w}@}SH9LM<0*SJS5=rG!e6q&4}qQG5W1c@DTKKm!>c>TK0ty< z2mv`$0@MA2kuXN$$Oiq=i}MzY)n3>m6>w{-N*{f#1>_GY39YSfOH*)!0dRyhUkD&0 zQ&Rw00Y<&tTXgZ_#Klb8#6*UVi|6PHRkyg4Sm1Z(;usqv*sEQ+vZ77W-Ay_#0|c~rj(-TAIp zDl5AxD_>o^cI~T`Yb#%=gm0rMs3|d7$xAQ{ur4(f0Pl>2wmz8i9u@dL`1jWW1}ONK zJ+A|CS_B_e!wq3zBUqq-UA7PfNw#LeoI?mwVs}%=5IWXdV(E_+mEHH|I zl=Tc7bn`Z!)W7V8h8=oz@nVKQn}df$W1o0I5+)`TF$s*K^qp|84*-}gWPsm_e?k2E z{198K5&?gEm6X6k8_EmmpNHO+mMgrK>ez4j78m?njkw-a&h_$7K4^oEMn|{F>pVkgd_;$ z!etA8^P73x0Yn9CC?8{da0 zc~qfS8i6tr`n0Z)Zn#4tZsGtiWQY~ymEL2!5#4KRbbxX!-qH0>G0w0hYwHN zh$|b{K2h17)VS2F42GxE^q$?Mg(E{?JY_PW8}E$8_r#)J(mg2I<=7GyUYyYKWziVC|ng&KoIjD znFXd%kPV%JfaO*OE^PK`Kd@8_-%@w*!*#`IdAzQE&F>iiuid=u+FQ z0K2+PBo<6Jo+7xJS#>m-)CxE#IfG#dLXvnu`t3V##n1=9U1g>!?;w|)5f ztg(M11gv*Ef2|`0atQ9|wQax)#u&r1zhZrE6+8s|@faOW2l|)+5|sUAa&i)EZkz}m z5xXPjjxZ!%ym)Ag5OCMBW%MytJGQc76ZHv;ng3m-(~+x3E+3iLv3qem_w7g4`ebr3 zR=au9gKK{JzdIuKIx#JUWh(%aXPMk!(kxy-6)}x#u3TM-D_xbV*8=Vc_0|&7G0+`8ymRBuog3GzTC-;F#?9+G z)~)N?8S8y2%0|FcK_=kTM8G>{LGD)p|J7Kb4Fx>! zQGyx#cre5gK>B;LkU_Gx=Vue~O*|@eU^YK9V;wX{ls~G2!RlzRx_|*fQfyKabkYvN z5&Z)I1~>+vw2#C~i(hJfiA*prE#^r$!vMAL3m6C-6+=kC)WQ6EMV;ql(PjT%mB0&G z1Hmu}p^FJaU>SJB23ORup;+YwewfnILM23df!;(wN`v_+GeAm0umteNZRLE7d^c~J zPjpZoDoWsA{Gvv-f(QaiGJ@aWV1fYb$`us6K^ui{5KzI7D&QnD!0u5Pi~OSak^#CK zz&Bt@-~qutD8yC>=AS4sf1?tyZ&!^-8BEVsZv4pvyugqBBP=qvNQ zOhRPp9uMO7pH7H~QO5QHO%#F*9_THWjU7|6sdt8(UVy-esSL#kNEp%Y3=Y=)_dCCt zIP?bR0M=h<<$ym+16%v7_TehR*G-4ev;+J4Mhpi$(8nH`K064~S44nEct^*PNxF7! zl6l<`6t@>A4lRR5{LH*%%l0g*r5boP^S^N_ey=hCyi9-c%H}gz4OtyxW*Ew;51N&sh)(WG$0X9P@0JaTUp%mJYXgr?qQXrw)_p{Wf8oN!!i9jl zLDb#ChD?Cg~L*6hqfQFBAH;x;~+15wR1uo#m)v%u#)v%m$3SbzPNKo}PQ zPZU}KkE#_$;Ez2pRt5G@z__kLGCM)iw)+hRsQfP~9FSOGHQWC@5(sAjCOHQ>+2qYa z*tU%)ff)cXt^g0j%bg$pNJ5^_fbQuDZ{hV8Fk`Q1zpiUqGAZBbvM_KSh?jDSl`%8$vYn-ve;vUyCY8G5JUrMykq!7r{e4$FdhKL4gh6%uX?Y=xu^N^4X+Q%xq!aRT< zp`SrEVuKS!%LoB!5M&P><&?Csa`reAz^i!JW&U%MnH^7*Rbz9>oy2bn9y*?$U_=c- zvI0)@3xzw!Y{+D)2WvnO=9GqEUM3cRY`d^$AyK@<#*VdB3Bo<U^4K66Cyf0V)T)^zFI$1x>)I zCGf$cIt#}#h)F|`M65iG7>f}GNSFvGG%*=h4e=#35!vSG)Y-Sf2X*Xu?oBX2tOU8uGasme zZ`#hEghHDVnBo9=6pjE8|D?P>;a0x>g!DlP)Yh->-n~9$_A(d)j3&Ww8Y%(cFl<hT7TUFe!3Tgeb5D&SoA~Z7m1~SHVcNkd*&~dfWU&W0O|g@vvJzg(@|j# zjEjfTjuCIoA2ewRX}g8TL}|&WDNCC2E!3@+Qz#5+SSmdZyU4V!T(v) z>yO+q3Mc#C7zmMvkkgPXU5gnpE|uY7)6nzvP%=hCpsHsfdGP$hVyj>1XUVp!a$`p) z`govu&#$gz@uG4ym9!f-Zk%>_T1WlUgnad@Jp8VslPDg+UP;M}&WB3Qo*j~dz-pvjvKd45kbq@@#uAM_9=&cux)|l- zf#J_&BcQLRip2YK?kJqZp|TX>A|8=Hl{wTQQ$Kb1cgs`&{P_oLgyzX#9)-K%C4D9p zU+Li2q5`uK2E9qQ`PU-|2+I!v;QHMI_<8pS9asN|G6o6*M1KA-SaCP+nc{7jY=1G# zkHHVd7yzIM!OcPeF$v7@R~EI4hQa<&_y#rm)X{W6$KlVy&eD#%rOr}0A#XA@tc)s7{uxGA|>%pJ7Ux@jX?1}o7rJulA2r+({U|{Du&|A`@wlyggIx94Kq&J@~yvl z{q;kS(JUIG3S=X2t80L16}_X+W~BDMp@_(%a7GOtkst)u4$~_v5C8}kclk1-A2{9B zt6BsTv`w_NJoel7UtIJw1pz)?x^LgmhS@9uA3@*n>i=b^B$(W>I9E;hH)y6j+<6Z> z&LXMMISzr5wZJACYgqTfd5@3iL@EZU7a)4lgDqCvf z(LpS48cy5mH}2d-x&`pA6qtv~m04a16}FvR&bAGaWlVUU9vSH1ki)6=A15{F+!6PH zEMzF)y2`X#3xf{3i2;ChUL&AnLLW4vYDeA0aAq+Q5b%=CgSlT7Jarz}41=&2+GxNm z0eiP&8UPHtHE`P0z$s|~st6KJRdXAVnt$|BMk6t0OaRMx281mzl7eq86a;n4Eh8Gc z|72z>;is#Mn`K9^FR)ctp#{tmbuNSDlrWLW&^uucNuYy^>4Zk!iuCP75Dbv$Urinc zb)?I90#PLjW<$YZ5RpO3?;wKpcj1Qe=POE|`@PA3kr-6j52v;7wL(J-^#Camy4j9` zJBY?0IEG;v@Z2hDDZOVus)b|tWz;kdk9#h7~+$Q7BXp&PCr(kIm4D#wI z1;2_z2`~}N$(+7`q#*u-N*BcK6)767kJJkKmM25R05wf=tpdk8Q_woe~edGQgnysj8iACV+KJTX|+SMXVaK6&KYjy zjbpHd(QXLVM)(`gozqL^bw`fy75Wb`;}g~gHT;~kLoEZOBA6NA*^a$yXc`1Fn?Qyr zgQ3AcX#vIyGNElC>iN5jf)Ka+>pwXQ^4VveVYm|~4j#2OXm1lR+vpjDbC-dHCGsyW zwQtyDAeiYlhH&cs0Rjp40Dnm?hh5yGRkL*fYe1C0LI4|*a6w}!CZ^zI(hU-bINtm` z4~$nj&%$kO3aA9EeL(dF8fn<5!L}ss!J0U%Uc7hf&s+;R$3z3pv+JZLznXrtRHN+M zXG-9LNGy95hQIQ1Q~LraEi2?ygbki$a_dh2SQ+4L-2p-(@XZ1SXcr`L5AYuxh>BgE zLjMv8o(Z;UhydXFQT6GG4W=LdXK?|_Mx+M3WB95h3=0fUX5a|+mUerNDWUkI5;lgn zDBvjD!;Aw)_JOew>~Ni8>)(`+zOYURr!_bxrBEo!tn>iWJb5n*-qIqAh*uZyuSj}v zb2fEQSk@{^zKoe-5F2mIjJU>l`4NSn$an;1U~_yS>41^ytuJhR@sY7*7cQ8E=qv?K z0l+?vIt3+^;<%4jV~X@4s>z7Zz7a3~JHUH_0f3X2#RxNbm3h$QMM6Nb0Zv?Onf1tw z@BCmh!QZ==NcEg=8Du|r~ z<|;UAWMI#RIO;CP+4r25Igqp_0OBkTXxOBm00rkn$nQ%90R*>p%)M6SWEO z$NL&(7EW4v9C>eDZrBS#qOgx65Sk?SU>oS-HnjyxhHAnxK_8m}ec}@Cp)WTi!7%PY z{@go5p<(iNk_c?H|C&nrHB%s}T?)dPfVK_jR>P%sBE-c;6Npu+Gjx&;xTl@~@KY&) zr3R)xptb!m0@_%ZYgPpDG5v!@hr$Y}N6B0eG!XxB@-kBsut{fibt4G(|DwnO3A;+eoVbp$mY5h6k7d_G;KOugH{*aV9bF4J-*k z_zQEu1H3Bz00AIvM=t``yUg%6F`2nY2T1{$LnH_6m}qO8`^b!^_O5$zCM^RdKzd_e z>+F3HfsZf+ROFbP%>3{@+IHCwZl?{sj}-KV8$Rk;c#Hv$KaPEL{P;%;S3gRyxBB@< zpQmFcZJB#s^b4^hPovQNY15wG43o;{RT~e(rLu`++jZ#V;XKs2iCcO@XWP)Zqkpbx z5AAX|zQ7 zdFJj82NZ_Wg&N4gyQKko8Q?!L4LoHv5}RsVE41kX9%TAwbl}EDBZ7n(`oc;B!#4hp z;g3Ez1DY-XfP?NLq#zhBfuJ;$>Xy@qURulLLkuiT0d?3{q0IkBKL&vpa~_Pg{M9{%l9wZ&u4$UYDt+68O#>+R*Sj|-9q z&3k{P@yA&RBdzXi2q7eb5_+fPAy6Q~$bq8C|GCIhAD9WI0pLugr6oh35RlN8nLBq` z(KFvC06cke=JQY2zw!3$4dX||0)1KJVl)9K4xOS^mo$EHtf5Dl-bcrQcepry{824x z0ebJg`~36AXFk80PS`F-E0zdYNy2~`dDYHU>-Mapcizo=Hm~cfCo8fssXPMxB7^d_ zlc^r!7$9JPsG@79#}Th~aoJnOUR7xq?;c#R z{}?)ebS9MP@l)w=?y7ey9JK&9Y$-3_;=#9aZ#^tEGVZHTlVE8@#TJ(=(q%=(uYP>{ zb&m+bRzTMTQ?M6Z8DR5h)nd~S;6`9xW`q6wL!v0G^~?a>0T3mCL9Qn>43&mKni5@= zGz#n+O_0!`^B+qI10P=c@KURSj27fUj|OBb68V+P8*@-c8)fuZ27w8!f+;ib!6XkA zFb3op$x`ZqPVsI=O>dC}I}zYtM5nQ2qdH?AQq}G9Ur~`cE(`V+6?~=SbpW4^$*(g@ zDq=DQ%v;eTITnK@8kMrJ2DkqD#ebnN0u6&^8;qIuH2_Br>9<=Y1ezCs^aASKxGWWm zb(e@M1WOne0pM2`FaFO(y4Z0sv!jJBE>b)U;ICymjlq4F#^9Dc{@d#>5==c$Lhy#! zv-h2251@LcFH05toA>Bg_}($@<}vIYBfvYpnkwAYz`WHnd7tpBKs};&(|~!KpXP(~ z<;~kSZ(c=);7)j#84{j{W}b3A8d#QL6t|pJo+qNt z5hLnc^{_q0yCbGFHa$VAmIe0YFUc_J6YmShUK9B{v*Zj$K{g(KCGRtNPSSCXnqfH1 zTE^2Z1#B!_jeh4|q|ffFgIu~}7=#f}_@Ac=);+!srqzHM|4vH_aLQJ62Eacs1DyYoQsOFY03sencBT7A2X^n? zy?%F{h`>zJDE>gEIg?3~1;`{2B5=ZpzysKeZjYtngDKbv(#%ajA%M|3iF6E#Mi<0_ zkd#R{XW_0;2cc($BLl*yex)c5d6uWM3PJ%*Obf%3NG#Q}Stt_Y1&bl`5i*;4WCgkg zoR~$MQvaHmK>BvPs4*scFk>1o&} zH}mQG`f2o0Ur)ZmiY?_89Nt@Aoq=B0t97-4D20Yq>`4Lnb$kVf4fev zF#27!sBA#+h`0S$aEuF<+C$M!KH*={MnVcPKkELKkWHG@7MhmZxVAkZdytaaZUF-f za{4%`3xU6QmIu?!D6n$C^A`Wk8y)zw`>zGLTNChTVGYa^!Hwz%)ZOR`g4F*Dr;P}L zcYj+6r#&)AwM|bqL8xMdVH*tkfXG2uPW-Q~Z0mA--ntc|z}paq8bJ0H`h9+P?4Pp` z1j;N7GUQ=Lq%DViY@k7qi~^t$LVED^2Gqf9i*5`Rw*K5}{bGc!Q4yqOngHOw4Ymp{ zR~XziFsFuV1-&?S`uZV-oJRM*_A4&;`KJ z`BK;O(soUShBA!sYZ?N2ADVA7e2TU?&{`D z=+RLx0CFBGDibtkxF^FKu5jjVAn(1R?behI6BJ)y8qOGDe=x|18Ia3Xwob<+Wkd&q z<7^-`7H0`t*KyypaSuv+PmF&+xNuCcEu`WH$G1nA7~1J#exz*10Kr5JObjqgvM@Di z%C^4wo9Sa?#sdQYyr79#y)5f$m+yk&87Sb0dYuX5_>s7`cS;(JARynQIIN5N_g`#j zd2o8m^!?K*1aSXYanamm)2B}dAkHeHD~~OkN5v|k7Y2>?jdKf70md`}uk%jznX5tc z-UaAAO`r$=;IwH3c2C#SDot6)g(eGF-bz}oL>+60w);9WnG!N3w`EGk#e?i^>Y2(` z%iD8qg)7)6|A;%KjdNP+7H~b!_jX}V9D(>e1kgL%Mn1uz66!H_p2c_whD6SETp{}R z>`o$pT~*x0YN9NBH628g5*&qhS}`3n6U*K!56et~SSQSV5l~d%^WNofb{^Or2L=Qx z0kjnG%lKg2>;MM-1ydFZE&dIr1pK1>G6~uk{4&hJp(HM&`42Eav;pgua}dmOPJ==I zdO$>wW*hg1SrATv=A+4Hgb?-3G`PGFUvJhDTIyr*NV7SR8iBMZiC-bvLR*a73dt-m z6F@qXHJ*EbycKTWhJDrx4XEQ}1nCF5AqfhAY=$Lf>VpGS@e|6dd z;5APV@TQHz@&MpB0)UGX(imlzj_^NT|I~%8zE^HtxpixOG-_PRO#iS94mEI8vrySI zlvvv3=c1XY9+tq#I^d<<>opE5&x0TZfvEV6h-WE^f|_@n^6%EBArS6`Mdd|b5Xx_m zZJ}z84r(qShvlLI4qAJlej%lvLFIZn@}d4_RXSvbPF0VvK913lZ^t6)1mtd^8wSJ2 zAOf%eni1&2R003@`_DZ$Hdoy*pnn%k5DX(=t4_F$aQlyn-`+m;Jxf2(j0bxF@GlI3 zy*3V^sO92CTD#t||KFz*22O9;KWqP?v7))Vc0IO#|E#$!MU;ot(l)k|u#5n$l<;rp zm*Z{`%r5GSB!nFL?Q5rIigr8m`9)OT65e5bIxS&<;fhT7RAj)Wf=1r#4b1dt$TnjJ zFQ^1%Y&w@Y!Z_vis(6aqt4F-}cf=)mE=+PiZ&K8mBa=$>COvFVlMmSv$W(90421B= z?^$4R2@5S9pnZV8E5!ZQtf8!!wUi1->6QTre6pIG)EodnbwUdk9rUcm^u%Eq3h1Wd z-wgp}T}Yu3(3OEbnOHUttMLv9i~|Cp1INRIgJFoif`CDbfl&@ZLcLKWK2!8_f_r++GXKi}=<~9{1|tRw0?Muo4ahR` zuzFd9i3#w#7azDh?L+tj4y*R9RXT;=?#Xh<(PT^M!e)u4FV0@4Ufq(PkS&tPLUAQpfT?D70sIuZx zT7tdO9c(pr=MiQL#Vr>jg^!(!9EzA&(aw1KC;ntl7V_j=NVF)Nq~X&e1+;>g1?PFT(joM z!xRX(mY$cRChJK7&?M-&GKeG-C^_>A!BaP5-oFcI_9ERu0X@@jh6Fa+c@WPi9FK#1 zN$>{`AS91L4udwU!88n-C7h@?2vDZtqGijMN6TCjbbz~n1c1x8ZZla|~4fNlx= zIUAvAEgbp&IK`B(Z|Pd79?uf`(Q#$>EgYlLos+;`34zfttbUe&aX}?82jcTeOtL`F z(dOU7S_z9ZoG-|P{ySEJG>JcfSGxqI*T{4;BEG}0Z2pscRQeReIFmaFCxJ$+l=0?N zL;sw#OAXT@-L7MHPS^x202#*O((nKZ?NhKs@}Ih@!$v<5IR$M$&Os*F0|J_NX(%Ao z%gf$-@v-S+e_{YM&}U|UTkS*~s2-30Y6_|>zwB#Oa}2is0{n!cGIUn_uzBSJve>Vthto^S6f@OYu2u!x!;{tG`E;mgb)B;z%pqnfeFv9 zTKBNx5!vrL){$_wvK-I8eY7>$e0wPr5Fd1GU&mot z+Yd`@;M%n>ucbPs5(N#Fz}uSZwr$&Lwt;X0rA)%5O(1GkmzEcLp}j&#VIs`kwj*6C z90v9T;~$mPNLgKy?sfvR8jI!Dz+pb25GD#J1y9&zfP<)eDF{Kpuv+9_CV!ZU<9T3u zG1ZwdI1U2bia>nqt@X+FBkTlb`Ip_kgn_uHnb{$^V44Dj(;xxe49w^kFnNJo8_Tv# zQwa-R_6%cfxFTT4PJ+;jYdC@6`5J6(p<;MN;%xW7U=gDeFb;TR&wm0LG&-f)+olM1W=s70`mM{X(rBJG7LUUs`M=ewfd$H!N< zzWVAG0brRX0qP8#FhR2wQ}!n3D`}n>3qi1>p?knWA1=D22gow8w-3nUhX^eb4wwom z4^${53D*_>p@Se6nj^DhYZwNGQ{swF%V)HU9i7<-hjo)uoUh(BU zxL7JA$w>l=Sl<(hSZhrrrh9*!km$mam5c>RVXVomE_?5ZpUzzX5yZM#B-WtS%>^`8 z7cGGMWG=3^k4s;HMo~Nt^o|(*CwVXjL<9lYEqmsfKNZb={ISP&J@(kLUCSP)1pGfe zvuxIPi$DWs6&H_Z#%5QntgpXNQOb<&oC|-Gm&GqUk(sdxZ@$t^6UEllrpA0{Q4g1r zJ#)3dmwZ{jX@N~ed@7UbPCh3xhTt99prxfpw}-f$w}W$C+Ss`Vz$>A9i0G9(Qc@zw zhZHRMSq$`D=^&%^8cGLTvt~D)pWOMcnuJfsS~{eji0+cX& zk$jSvF96rn;Ip$J`q`)H2nj|)?hhhFi+#X4Cr29$8YnBs;GU-$*xysbB`_EuLLd(x zxhg8KwL*&yY|3A|DA;2REVo9%3ey;rW*|R;0Pu&qZxI8$Z2<7LSp*^(s9)doh#)r@ z0N2Cjg41rsJqvw;e|+2`Vol;lR21NT;{)Win8pSj@U_3nBgJs|vbGtV89xo z4F>*Qe9-bM6G>m3odOP^A|-d?i{(<6!y0Mb6-*(Ea`nz8J=vt}(L2(10? zSnVUVj}&7a2uUC70egXKlmV%j}$ZUuY; z00KyVwP4$gLYe?jDpBEYH0%y17sdFhIcpI|@87 zpJJisn>au)Kql=v%@frUIAsH(EdZui_(9cACMs7rwg+rjrX9)5D;lN+CXa{aSQ zUp~wmLJ0d_MdlW*hg;EwGX-&V$+|B;@3sa1i`r(hI1N&qGau#-U|du2y)v*H3Bz5$ zOPUHT*mvokfq)(k=oe9sZ3HR;61dUo7VIMpz$I<`)lvld z7Sea<@nLQ0uo%reKIl*=NF{K-o#Vf07=&Uo&Yc?C zq_n~!ASU3-x0rF@ii)2;`|0jmw~Yt_0K6enAnq`*^+AIHe*D#~!s9DteGGmCe*}R4 zv!1hNZ4QjEKZ%1j1TdNK69WVbW-$d(&{Gawid5i+mhnTxcWVvInJ^*-d(u&L4WJ#y zGpW%`*iaaAV-OFdwDU-WSGdPCJXO~pi6@ZeKg=px9(}{akwBQ)@y+ugY;=x^y_v%m zB8DXDgbBrE$!=h36vkvMSQ4Zf%G%d2Sx_=|;q42&5=125R_^er{98IA+tLLR`}*uo zI6&ZtC49Xc0Nu-b;6^Y8d_WKod4MH!%qW>LW5y%I_r5!ewBNaNi{};>Kk~>Uv?;xX z2IE>^)X6J>WqQXDAdhGsy-T2}N7XHSD`(E2$lVLZ2h2mY zySIMb_Ep&UK_{Re2;WBDfrONq!<8?urw$(-)L~gm9UR_{GBTBKfwS$^O~VO6LBUQ+6;pfECo)p z8#)ac#28=bUs){xNMWc^m|qYFjTo3R*$PsoK?u_Qi+cFqRuMle{cAQ0kF@^>(DPda zG;#RG>}Q1$a{>5+N16_p|2WZ|)AzL(m{>?lg8`GnNdtijgHDh|U__-MaG+-OT26!> z8gh-$N(5~?&?FrI>kK&*q}u@CWB=a<{+a+~#g+$N{&Y9z!Q9X&glh#h7;goP9^fB7 z{^qN%3V;vTS9pB&)oyU?evMS)4VFP!_P}w_vK5#_;8$g@FgvJC80vaY90D`I`Lq|r z8ey85pGW1LIT_^Mv@*@8WN+zyOrHGZ`QU;hsG6gw6_x&VWb>95iq5VGut-Z~XgV0R%A-`?EyAF#Q7nxSeK*(JQt4|Jr> z2!eni^+P*|fT?+x(jwal09RBVre_>KIW-ZBD_n9UY}g_zLIee+G`8Lt5q&Fcyl4+8wQ{uI|@GNQ6=S zuq{g`ZNbsHh#zwI2jd@ zgJ(gx=)%?rJ$-u7+&1EX#cd1bE+Cj|p>@EAiply{yZ{Vv0o}^9ARLRX7e7*4 zj1rhB;5h-XN%d%XD0XxaBo7;Zvqq#(gl&sHg@TO zn-bvhC`T(EA*y z_wnZhesZRZk3VJv>`qbU7}As215H2(u;Tic!l1Q9kf?&&fR_RT{*VS(i8;9SHWN$H z@4p6kGaS#t1)6o+e4SFjpvU;)1Pux@)#H?W&Nc_vBA^R$AQrEC&~Pm76a$eW5i>x^ z&Af2hbA&=RJ=!cc3Q5B-E$RqwJyMxOz82Cgn|9r>O2`mDI1mP3!(Uom_KTlBP*VKR z+ZW^j0#Y&jhFt4)SD`Bcn#2PPhWrOm&nfW{m(=#oZHkyz_72HOhK{%N+Y{HwkI6lb<;?2JK9vXEh)*A%s4xvMB?i^XPhbNpq}2DGgs(Dyl-!( zw)EDpjzMU*cUAqmRY1IrSmjHfo_ylTf2H%rC)d8Rkr^IA-pgxI;8rf}0^9-j=n1tJ zj^-}GzRLD0vXOyF%*p3}0>almr;AaKciRZFVTJRL&^tNkq)CP@>vX0`e9&yPv-s!P z3vy5?+a2?8Mg_jB720*dTyht~6*{4_CKZqwplBdG3~W{+86OM-AQ!@{|1ktsv-}}N zQnmR1@E=)T#$kXG0LXa{$U((=A52L_R6Tv>O}%*x*~p-;kDIfd(Qk)fk~2TJ=l~z<25QmZw1w z*kHs7O%#xq!|ekEYAcXRTLnPYJ}S0YI25GwHVbupgznz++^=aV(xEwHr$Q zzQ!TDFd6;6zV`Jsl)!)Z!^d)bt{-{`1r+@IY80)8{%Rfp7V{rB0Q-kI4O;jgxnP!Z zz!;CwbI9371#A2bh$ zM5KDb+Dsi13Ue+@P=HE;R2|L?3~~Ia3DTE=kdR3?2-!?jLAj8+1!Ed>?=nFysl_$O zsR}XK(G=rCJJ?U~H&|Bvy`MjDrkG3Mw_9}*SmFTb@_@Ssv$ao2--zr0AxrcD{t}M? zi}oR~HzEoM7sK2LBpXZ%4mA4+-zM4!{3Z?&1`__YaPO~}dVm?aMKlnd!P;7IGa#FG z?U=#QxdrjdxU$1kvEvMkEMN#i0wB+xCBPe^fC0Mx2*K+kZ3`C6Sb#d0=-v`=y%`Vj z92zCt1M?pE&X2Bikelj9SN4MNb&xxmX g+jmlxOB>6np||tdjZe_0jccEv6M^8; zS6*4V7Nzalm+8WU>2@vcs_Z7vBa+AUEfKvr?Of(k6_uBIm$!LU@md?2VMnkNdE6-G z1TX4lKRbMN1P-m1q@-Z!PTfJCv=~f(sUom?p$i${`MYfgzSlH}XEWxMKm>Of#JB); z78ukot6S0C;#WdZMF#OS!a@EN0JZlg+u$SzwTXv+n=}f#DPRcT)_|pNyaA4WJb7N< zxR?R~|L8XfpbBxMaJVt}+A)-U=?RrbK<^*~H}FB9l5&m7Bky?DoCJDMGU;dy>_7ls z-PN^v1$8KB(LHQ18V9paGGPoARJoTEvNo7H*9^&7iNqGcwr5yT@$+~7Mq80+FOovw zt!vkA-TayXkU{V!A)kDvJHPn@AB1;*_?$ld;p4j;K)}%^rrNsZH7Od1>;p;SzYaPK z8=y}+fau7uubQ&3xC{6&6Tt3)zkvXHe1O86(VT8_n1u`jg-;}5#tO@ znM@eY4G-eo(h0_FhJIQsFuGPcZB`^Xc9*4WeskQVA~FX8g+q3qivc=}eMb?Ur87CH zV2^MLir~yq2+Ozr_=jz0i&t_9%+QB3jlC9puD^#9rfZj&i@pei;N6`0^pD@|WlaJsRKWWcb{gF_QUb_jVd{sjG2moJd zZhlD%--OTSZgZrknSFu<2}sDa2|YDsVhCh8dVv|b002eP;3nW_cddXgxp`QgwMggh z^Z|+he6Z0ZqKXMH?Ty6ZOu(?@o%8Oxs3!RMWlIg)#5+$y9dN_?gRqB2*OP2JuANM0GtoR&c`Pff`<`@ z*I+O(z~oT(YV=4~(a|oTQw3q3b^=16qBy{506?LDm^fGRH(SsQ3{cA8aut7VWVE;i z&A5n+j%*P8t9b5V#y>(p{I^)I_180g9hUo+sh_*ml*MNGVNPIig7@W(ra zB?lFw9wFJN8PVxD83&1(-Ej(lVKop&VB4?Wy7WgoN@^AU3<7d2LT|6AADsO>(%0AO zD#5KIZ>SE^tC?47gl=UZY}H{9YX&R=UUBhC><^i!8Q>pM5n6}|QYB1n!L}XKckF0s z87tmbyKks?c5N*v9X*be5&A=!HfkL%ASURKnDZfx{i%ISD~)`*NyDXTmS5{ zPyFk%0(cvZd_f&N@hMj>UE1|B;oad^q^t$OLn{wsYjlaF(rldXVpqKi8))qj1kSHo zJpUK}pRqUokFq|uMNueKH$`bHZYC(sw0O|bO`5UPU^JYV1YrmFRFH_tV4@~4w$o@x z0D>YDp+wjqD1;k<;O8V2u%LWC`QRljHFEFn4?Xp6=+*75|IJ-%Jyqpj)GUQQ?LaTcRe@(UaMjFD5pDqio;+f2w>3O~V=t00n>) z|0xJq_-FKw{XaJVR0)iJ9AJ}rR?ahsHv+rF z;2>#9Wy$A^5JnoAl$E~{0*V8MRk=b&D5#N1D(lg@LQ&fbd9taO0JwteXw9!@K7r1iaV6K|-VO*U#G!*xHFCY3IDEr^FKQTfTo~o>oqBiBcLi^FhI%x;TS6w3`!OBZwv#YF>o{i z@m09R@au)V!NRtAj{OLRRBe9&;TIGU%7y_?KCa z&RswTcwNL#FgSl={^T~UzRB&yO%YB-v2bB!ctmp$n}AFN%(H2*c_NJ1X7CIfK@b49 z|Lb;i0C{KoAHR>S;P>BWC-7Y`zwiI@dt1KuJvg(jnmhNYr=XZoiXQ~R*GxMI;XU^Pn55~4nzj@EI_doH(vrlVMyJ6w6g(zn?EL?~^wAIV+yKkX1dT8UV zgDVRjJB+)_xTC>W2as;v;bnIXEIX`|CSNzW!xzwDoFf^aiq&z{wz=_0?~Qw-gE2t3l6tn$FI2GSNGpmo)xsB6ee2bd247%5?FbQ|#R z!yC5YV#=3;5KCdUyvyi5zwNI zA?o%;5bc1p&;Yd#9Ia$yj}me{dgy>vl#P`fUwrvDJ;a5rsrtpZv$%fol&WBF`2q3L z#6W(P6$~2Q0n~y78tpy8pwJIvkiu}Lj?F*dUtOkfQ9Uu!*|^9irwaJVCj1XxAqI#v z8N?|70RNBAgSAhP!rU8;gM&qCMExRU44=J$-eCABr+1}bv*VFjGFPF?B=3So% z6cC{xhzF+g%ZSFjbOKZ&y63=6_^xojT7iat)c>8*dfZ6T6!1_4fbWCjk)~~j{^gJF z|M7iZzDH}+-~5piVc;2j5^!Ki?(tQ(Z@PWeowM#_P5VB3gTH0_5Ebohi*9>x1{O(v z02k>64?g(d<7 zAnP|~otX;SgFxgYYDNN*0S=a9H-sCdfR_@+(9^nrq3Dfj;V*8o3R0m1e9sx6mf${1 z#G_jctj$eJ1c|cYRQ9^@ec4N2UiF6IuRdE!Ty-J%1>+V~tVPfK?GpPd4q5O;H4(5L z_{TI{PR#Ka4FnK>v8=ArM*fD0fc~d6`lo`J50mn$A$R!49 zE2x|gSU9N65OKjK_YGuWoGV8h(CA%zF!6gb*qYjdO^#`{7Hrd!cHj7IH+L+uyWo(e zu(*gghGZl&NT{mn*}DGIC3j9f)o*35cL1S%R#7}6ZS*8@P{vmQ0OL)O5sSWL4U8|N zEI9T9=?i$s+z@6k1OzQV3^+Ie`QvXi0{JZ-Lm5m4h)s~+{PO$X|Ce9PU=Wlv@ z(^I#v0taM$%hup;mi!nZLf{+#@Spzu!37H*od4kL1vu_muxQWBMYnR6Bye*{TlRn&!O0TVngklZ`R)T#6zo>uU?0d?Xn|lmvcyq zI`+tlb<41dL8x2TIcNEgIJmfLKp;3UP*YRW$$s8lck!*a(o!OtWyTBqgP}MrC8ri^ zR#tskn0L9JZzYhJG=~~PQgO(~Sb~nCZ}PL%mkQfkQI=ySRjAWAfLPIC5U84xV}!EV zWke0QcpL7$_ogWUKeTw@OR+Diquu}YMLYqH;qQy9m4+~}3Oa1T1p-(R2{$M@I+%~< zAAG$l366?CvxAo5%Ne}^>3`qh(_dm=N&n3~_%PPz&?g6H#$OTziA+Q2{B?o*vGm3N zg`uG-Q9!SNSpcW9#{7)yWiw6%9RdlBT@nMP3N{VKKUX!dm%WnEbF0NTa z_&dgiNb}m)e)W!)&*Ltj>0qKsa8wVQV@EXVb?ek$KOc%>FNk^nCs>8sy&JqQ9A*OZ zcl)RyfXqaSkxx~y;BQyJK-0pI0shYxK@-gnH2lzqbkLN+AQTgSlQeB76$v*rB?-*o z!^u=&0pJlwzjI*|E@J{!yexZ@>u`pC4Z7yaNm+V8Ujp&1I5&uq0wyoG!+0dGonYA_ z2>fg*xG7hyKWBwcwks^t{qdWg^wcC@2<8^@lb)~?HiX+1hs1tj`-Qsd ztq*LuZOKz}g>*!<0D-m_NA5RiR)F+Cl??Edjf5v`BiPKL%@1ER(b(UJZ^d~qI+!0O zxId=+5ByKF-}m1q0Ez>`9Oeg)FZtmQzyFKJez9Qw-Phlqzu>`t`lnTQ-ahM27Pr_I zp7HN2YH{2?d*=Mv^B;V0{`~oO-!uR9duGnw^W4+V?YaB)dtSf$^#^|T$}3O5e$PFC zx+m^`=!pmJTX_G5+SRMye9hcej;&t3df{qtJzVCH@qyh52Z?meOhsQ&qk}5FyB?l0 zqKCo@*tc@=N)9rnriP{@RjzMV8W-zZFhD>a&~I^dMF8xe;eA!vT~96jvPI*Ljuy>4T!zOiqaxdW)c(l) zps0H?{S)`IiElbRG^GyUWon1&ZHwQufL#ISfPG!VHu1GqATG8AhnANw3J;rQ>M&uC z<_LvUDr2KzI%s7rXsC-`qPeERvKKrm8tJKb{OYxL%n_04~g0N$kj#qt0C{r^s|za60n-c>ON z5d-YurdqGsa$AyjIi6RU8FnWsdx&DKEL za-j$|28e$mfY9Nt$wM=9*7cK6MgqW`d8fAK0fDXMoM))!lRG13k`-l!_|C7#$a#~` zQO_pD&KaK!WpB{GgmH;sAfLxXbgBT)RQ2?%KKt&ww_y#KAF&T0WH6gIZyp(OrL#ET zh^+vV>W%bAJkWjeCmi|QDp0qFP6cbM8Jbg|495D$AE5VxJ^uT@l?vv^0Keb-5H?v0 zX1q23v7bKn*ki}&7NV_wwaG z`q5nv{|J_6oMF_nyTmPAD896bR#WrvT@Mcd^;Y77&xao#0{l%~Ub(Vf*$W!sX0vJM zAT(*BPt)aeYA6k_-l8&ls#W}&opI5UdAQPQy)7nPWV6J(4tKLN=XPyufFbRW!|Ai9xQbGn3sbDJk-+R;Spa5%Hk>)4eXX0kf)nGXTJ0Qa@h^85R;+6-+8HtU#{A926&~r@=twR84jla2bITOA&`rcE5!hnxKEhqqd_DlL<;X?5H zufKnjguHJnhaleq0C(&V`0a22bOsntLC#e@GEB5u*WZUzJT$C(e(pe}0i-IZQ@ znDaR5piu+K4qq)m9)SWLQ4xIke_Zx$I1Z;eBA0Sn?B^o0HZDB!uhyC~9cWYFd?u1< z(^#0jK?wb*k3N%=BTL>zG9g91H9nOxAt}$bU*8W&idveSBa$%Y&E3V8+}hitIf_w4 z#Vxgm2}yv|R&zq=ynoMsY@fUB`EC6Iz|FSyVX+{me8fAU51;KS9({z%aHqCy+iVkH zBID*m0r>jkV5E?fP95O;@7{9DE${P#ks$AXkH`mk^!I-F!yo+cU*7t`e3H5aKY#3* zSMI<6{_FGaz8h3<{y#nbPq)E9;r81Wq0*hr*52&d_x$Wwnt$3*fK;iM0O;GmIkzCcU~`6z(@jw$OPCLm zmI#+(2o&Chu}9>El@tO7Q~U}B7-JDue}t z5xX;3v_>EA!Qp5wAu!$?_DcEr=QnLS`*SY#V)Bbm&VPY`Ujz8Q{kyKdZeC^9^Y4L#%C$@(Ggs*=r$~- zoxNwzo_l6vjC=n*Pt?`|?e43s-LM>RSIgrLP`z3p9cH&nmn~fYfk1x0N>{xf{b=h; zeLMU5)}gJpY}uM+OV^;Cvu4HNyV$rxS8t`b9dND&S2dC(3(@$_Y8~ekQ6$ETNwMsFW~zZ;E%XxJwdC3 zQ(Xps;M7Cnd}zPcTlcj-9Z8|Px=`tsNXlbG1U8e{29Im?CA*f&px~Y{)?BuUw!>$OGYDL>Hj$Oa2uG5 z+5_Pf9DgbRAQM*Pg#{hgk>!a@bhE_|i*SFoAuus8>d2GlA7EPwY5E31CCmKt&+${=fWv3!O)W8 zWQyPFHZul{rnAvqn4z{bRxgAT%qERJg2l^(S)=xE<|IQQa3F`;_82ijH!)&XfZLQG zjOrNQ_S)B6vikcYCqTsnpPKPww)=jtYTGUU`iEP#(*pIMX3Y34I)6WaJ1RaNBLcp) z;BFjGYrf zfT=M1O?7zlPgd@Ab!^9TTNT1M5~ixe3Dyb;wM+8l!F+`&V8R&M(=n%M0TZS$ks{EM zFdl+jx>+oo_5T9-OGX06A(-ZU6`5h0`xSS6rDaqJj1P@{MIZ1D)lv$-%n$*4bWZ3f zxxZ-$g0og?wGloe=!pW@{Gk&Bnx!2JUHyN_rtA|MnUtwuWDO%@Ku$y0037zGk~{L7 z*w%?gvv6fn?4T8Yu_G~(kFb4nJhar2Pzu~wy6uLjLG4M~+7K|*UBPT)i2+y9S zmEYgL2Eg(2?-BmpP1DIfd0Km51-jIMq7X*QzuL6qz@(%?aG}<--j(Kobf>f zfq#FP@%WGb{fCH!1MV$&3|I5#zcv5*-FIJqqIScvS^!|}@&9)H?(6ffKZEJ+?AiB2 zy?4(&ucP9{_cx%>t?gdkT~o7sd3QH(Z{0XPI%~SSJ68bw0D#c0K77~8ySDait=S3& zShG^IjZu7}nHTl-s)>JKchwS9;MI=zRkkaQDMc~c*wfR4sBtRg`Uy{K3A+;%FPijXt zk`oneizaIl7!$!{4Fa{^;WJ|6dMTR&3`b)pe;$^Bv$BU#dL|QdK>@h|P6oK=odbJq z5B>8fa?97^_C_eUHx@_#dYVY^UN4oSsjvwH&p!GMEM30#8u#mOK>@!_(7qc1aF=Lc zB!!+Pg3%P10NCKWZx@61MLf{zjbWt$FJrV4XTVeO^mjeH5Y{^cx*b-u5PbQvYMKs? z>3Vx3{Ob(@Ex(oppdtV*FsUuCSoX3t038Pzl@uUSG()wi zZ@&cto4&bU4)<0QPg*a} zIMjX*J`URV*!=mrJhtF>^NDuPy#8h_vN0d2t$hStzUROKkH5Zv<6aO$cKkpOp;_M9 z-Pirn8+}`cx&dzZ9K%hgFb-@F#(EU#t*o(+&XufoQRniTK)fNcIpChWr`S|V3+Nh& zPXIrItPI~exWZd7!+u_o#c+xouv!BRd~Jb?rfW$lz0n}gd-wcx8T&G0%8pEj05D1< zv-d2Y(UVczKNE%84rkmPrMInjn%FewAqx2bfDs19O+b%GpB@hv=VL}77!$%o1?)0H zAfOF^Z?gRn4Sy>}AI<>zs^u306fnFiiWr!DxW9SHDSSa#0ECQHHnSRCx$9iHq&L5tF z4E`9`z_~dD{5x=fOX{Cc(7HX?h6iVu8;M|$0qSyqwpr1XIGTh!HFqum@T+UrVDWP8 z+i$OV(R=OY{O?;4KnFmZhKK=1V~}gU3jF0?>HPxTr5PdgUJMARMG!Z`Ua@ux1n_bf z1Ch7_JjWV`(;1;bL zg(vX~Qc2nzI6Gm=HyBS*fJePAe@_p?ADQjQ7gmS+G|{k*W426hReYXx)3vsSNC;C= z1HTs=<4=RX>At859+;c}PjfLYmH*WX^0F1VT{fUo?0m9~wR)6OSe%E+c_jxVY+ZFG?CD~tM6J&?( zU$ae+-8~(2gR!{LDw^P*32ne$^8!RsvUcs1uwD(oIc)o_4?|#I203>m=?2IPlbSO; zm8k>R(dMtt-h?91!duNHzZ_cExiAlI(mbRb8N=j587#*b&_GW`GTVZ@X9e5oRmes^ zKg;uA8SBn}^tsBn^9Nlg)9TTfYWB4oZ02qMBkyq_*s7}PdEm>l+i&9<+~&=};FKc} zKp;rpwh`^c;qJDVCk1~Khx#oH{m_K$@Yx!qbu|4@4+Y+Ls=q(VO_EXcApjsceZW4H zyYm8k=fBcnKo_Xb!yXW739F=eF9go~GHa>pGm0OS3UJ)eX zxc~SQ8#L}f`MYy`>(;)VTTh%|gRiFM1kmpE&}q`YmAC=qjdHBP7cjef4=-Lx`nDL~ zL<=2Qmre7%gi;ruc$;vX8?DiI#W6eat_A_D5gepA#F->eL5)EC{p zKCuq>VKN%TQLu6vlC*-c32;&a_`$RZ$n+=>TmK00zj?n02UNv>w9%4@gwN)MUi-Fm z1lxNa+IsHku{t;v#z9V#MXIe22>%0lz^D*zjvImcUs7!?2Z}Gdtn#)0dqOiaO28-3 zuZv@=E@OLyzbtp;xJj&9S^%gCNI*bmfKbq*2Z&6+O-Q8K8z2zEuFsiFCaDV{#6@9G2;rMqxx%BaELj4z7fFgl51g;dq007tjl>@XhRTsqq zIr@k;;R-IgPo>u_pE5U8s3L%VbC$;=;Pp3gL^UaNQAve-jkd+7<~B8FLUJ`h&+}_+ z)ZwbYT-XY3^4QFLXcR^Pf;m+;gZU^}Q2ftirVPr=BlTPZ-@Ffo+rv&AOJqffNDLiB zF|8Vg@GIkuW(AnD1|WCis)we>3cpJr>5j;)M!8qB#1HpiR>d zO9+mlF#96`jEtf!CvyhpypLg5?K%g&V118Wf8`al{hmS9d;R(|$DaZA%_si7T6_HX zt+fEarB}wsuYd&}1T7>29{+E(ciaJTxS@7kcW2+$t>AzsaG=FU@&^DMJ&mi=x{uD? z5Z^2Sz{S;qKYzd|gE0rb*3tO3xh}s*%NHpG@UXjw?S#;_bNIlSpzqS0-}Wy z_JJc3m`n$m9uF4*U?u)d|0Jwo= zFvr-Y=3zM;+z6KEym>edpN2<*M%Y^2ayQ+gD zmH}WYtu=9PqW7t*k5KiWiJAr0VNkq^YuW9d%Dr^Zvgg=$0RHz31k4mfluTk z`N`f{TvNJ*Ajph{PeM*+gl_j%mcsW2nV>C>L?(jIBUMWP=-`*Q-gWaM8Un{Mz+Fix zpcvqhzn1Di|7g0{D;^jMU^JHt4uDhZ)(Y$C28b2VBkPx|_xD`@s2MO$-xgPDI>0uq z*X4przb#tVY%51aOF2}$So&=;ZD6h(mV+so_LoiG%3+<`d8>Ms3vz>oflV~W(tsn{ zWNWf9@RLtQfpPhq-N6&^%51l`w0@ChBI*IQ8+F7=J=~xl`st^?nK8M55Vy^3?ok6n z6u7OQfH!GeFakhoq9-Q29XMfYaB}}kmcT+m@;=K%`n>?~F~HqpkNs}`?{M?X{Q1{^ z2js&Cntot+$06*ig^qb40I+uF9pg*)kB!{{B6u8SFpFM}MDS7jNbMtctX{aTvwQ0a z9jEzu`sj%vg5S{4(W660adUbo3k>921h99yn(Pl=EEcNGy;1yM_ZNJYuY7Vsm(X%r zm>G_YHI3upr{vZWCcH%t%XQlkQ1utUsZ3|1Zj)UtDy~eA)il30Yer1UP217{4LEq9A!p|v+(RkYu&`T0Vlk|0Xwz<~gQr2oUW>?fY z2svPN{m|4(d~z`u7qf^F<7RATbx2BzlrfrZ@c%W%Eh2d81V;NJWPZc;aMnx#6Qb*t z1i)o5x;-W@Tr83U0U4BlN_f`ZS+n-uNfxMD_+6)gu@c6~U~>6`Q{cICD}*wlfRCPy z0WiV;SlL!`zi9iTq6j{J1O6EUtm~}<`J>_XMZsSLfgRy>{el1x!b$)jw&2%W&~P|h z3SGGgQbaDMvZ|fdQ={4&)X+4%ZM$H`x48yikZZGkU_=1RVGbNE$8jAvGLJ0#NwjSH zapnjZ6oKZFr9hC_+tgO&Of0B8U@4MVk%U!o8)8?C$_Mt>ptv{O$ z!Y9asCfG#6J40K&#n7KJ?M0VGi&-}?K${8wWNc+`WD~&<0ohC>2TUad?u#D=Aun1!Tr>!NZ<-wXYHW=4#nqc}z^m~P_``%5 zYE%Jx5&T(X1?Xv*J_XJv6fg~re}q8Ifi=%*5&Tuv@zPrd2&~f~W2!=lelS{!Q`;|N z-2=n1l+~p41LO*DIt}w3ti)j{ScvEWajpS$Gb`6c>(KwbF5`k6@9NA)3P|jefr6UB z?x~eZbO7rO0AU1qAM>rq1euL+mH?<@)`8oYtUwSX4-^U9n`rJSCnRQrSdV)?u{Gkw z@mw!~&&Lob2DrRmqSC)NFVMD z!biFsMD&&;Y&@`R0La|){F9D?5C-N$fE=Dv;e%!IzwI{S)%&B}6fsu*n*OgntbyQd z)wurbZJ*wGdt?O|<{ytqYjk4 zzxy4a?-{iFUIFxR>T&&}`PUDE+THrZ6Sy7+5K_@Heh0QT#&8XV-}vgCwXg1cb^KKT zAY^|paJ6k+cMTDc?CWl?7Q@?&@R$iYzKlm#q{5O%F=Iw_w%HH{B^sSr)6cix zQf#MS2;$4XT!%ICXJ=SeFl_)pES1Sb4-oj*Hrec10ihanFu$=P9w{b)P6I2`LB6<&HZ(}{sH#))Kdb% zy>nwD)u#dg#`t$Fu)iDne@PL{4xa)W1+-C!8=?XLO9l4*s;Xf371$qFTRIAvkO`k2 z2#X*CTnIg~d=9Me9sJgt5XP-wEEz7iVX+3rN3Rc9;`X#hAD~N9rWbWv9FplA(7`V_ z==+ek9Iv-Whnj#KeP|kzQ+#?zNm6QhQ#9la`*Bg4lERf(B!^#S8R+@ekUV0ENEm_u z0H1yK?3PteSsaoQ(B0{eaUdgJ^zupt%#1N`Xv@hi30pMJCU>HBM69p5=lSzqlPFRWR*v~zrH4DyzBT=7_4yAFG9 z1VHTec6Lh7e3Tu(6GNnYA0Gvj;ZD~0-_h*JAz)umw$TZoP%wC~q;1w`#ZER`0PCkj zfqRVlWjqRq;8*Yhn6FqcKmZ^&LPDm7CLwuW2v+wk-U)s$Vu2rim{bE^y%Z|o8}aXI zQ~@WvP~#H#GgAV-7cGJa{5}g-sFsBkBrqO?bfJv|@B+8u@qTDg$Ea7TKs2Qab=Cp| z{mVf1O&_XEHsz)`nb;D>#pIa%8u%@)zf6l+Il_Scu?~hf)02Wzwi9d&E=I#H(Z96Z z0!ab2!Gjvuekf}$sKY7$EjAYmOC~adUWP4lN}+FM@ZXzHlK~q3y+gCzv#f@f+(K=P za%d9s;O8rLL&C1`Tvfq)D`2v+1omtr-|_gaE})^{j+=;~EfwwvUN<;*LI+rP(Twn| z4rYbHMc`orK%PJ9(*yEBodeK&qY?l$1^)BpcoKa1oL;}Q6zp{bWS65QsnzG}v#LRb zu+KQO1IIh91XE{WSLKD8}GNSEEHs>wA~Yz6vVdPW<~qn~tBloMjU2uk@7#I?2? z=W8wdpjZ=-R$W;TQa*2LKt^;G}1$O^^)Q2cM3W*u65>)#yW-zFmv zoOt)( z_{hQ9D?3^8-Z4J*!qWXKmURLF$HzLm$9L|0b!T@skgs-iH;8(7XE!B(E3=KLeMgTD zjb@2|0K$)t_VC`(o?+9!+GImk>3sd$rd8Iw)79|7>IZkDvRR{mrJgMB0ywQBgdO>; zZAz(NW`!j5Gg{Xb%lQa=U8djVogj~Kb#BQtFR311_;(l#H#8W}1oex9ATxV9s;qLX zs}uMU0^uvrAdAs9cbk_Ox6S)>AL;Y~&Y@02h`s=&Q&lN!tY_9h#GPu7_9hpClVKsP<%Ik%K%!O3EOiG11Ed(5D{}%s0#>(e*-N9-|G&4Rps8Ks`mmuL(2yB#!3U=+I_{f@8)2t0W3I48S6 z!h;0Bg9kD1tvxsneIF{_aTK`N-CeO_9R02O^^yS+^NtP^yhH{8TsG>h*W}OUdtTS#Nj+4A4QH}`U;#JVSSYbb%Fv3>_Xjcs z?&S_+S4yC1?erAZ7z$ruErx*FRJ7(MR}(!i;{aHU!0&RSVWG-m?LHJu|G})X zUd=!X8H)(w+AOe-DCj|wMgxP8N;N`+fA1wDf>pz+1!y7ZaYAO$!d$KB|3z;2mtqDe z7laS20~iA!G4L~kz)%G1U&L$R239t$4O|Fr;1sw)UBHY9VYm^85lEFR@LO6+w)bZp zz~mp$+@ReIM#Ejgo>B(D18GwMk_MA)wE?R=P%ogKj$!4U4`;igZ>FV!aXcI*(tVuP z^FHnh$QWXW>uu*40QiDsJJS$h!>zCV>bX7d#K$Jq!3KdCi9jAr4rna!URwj1cF;c+ zZs&7tdpIa(&XNJ1KOfJ5ubIc+uI~iF9Tlq}$%r^hhNB^Lrmo85&prYn59|$L%LKrw z!;%4F3OsO^IpM#teoklu#;Hj0Hr!OCxagGoUZ&Yhg}un)lAsm;a&JsHk4&m$&kJ|zwGDFGo7QX`Ol z+xTV03&t3tgZn2A>2Ono8K`wX0{s2#`1M!7{D6S9SME57xySK?wa2ex+HvK|&YeKH zoweiRuM+w?1%I8;1A+&F7{1Ee@#X8V`qr)8wjuTX0Dm8Ue6+xB_E9zSj`pw+W;H9$ zmJT2%2+IV+B*k9X?z2pn!|(X-P3;43Ok+3e~a8noQx; zWq7BRMhgl_pG@O&vWp*S-}t7sh7tf0zpRjPI34jpH^it<3jk$@Wx3C&f}eiQpzk?@ zKh(pU4pcM)-<2fhX6wPB>-Rj-&n{YiGl@~0Tws`LZL!GX#DpgyTJqD)+dJ`Z^#efr6cEFdg&!M#b1o$GSAti zo{nh0$33^e?!)Ax)gxfyrQnDGmgD>7xciq2{Er?AfdX1o68AW~eigyX3j>42-;-7Y zYY(nnJW{f?|K|Oco00W_TVGH zy+^?Qj#Kl;f$#Wu?fBTv@v**cdN8Bg2halx99v2p9P0!N>?8nUt9O(DICN5T-;a6K zqe@mNND2r5v@I%Y_Xz<(v`XHWV=5pdv1D}i4D9|20DFdeV2+*&s{>)pv@4r&)Ag)| zE5tzc^6Vp8Cyh_A_z3b|Yx{}p6^rprvB&&6Gr_vzILTp8VsB5wMmkAGS01O?1LOfF>j{r?o2hSB9MZCN9&}FzxZyRHz?+=@ zZQA6mz}t|!b>KEkgg?kIfalCvKL_}S`uE6@ zm&^|fV_;j|ECoG#Z^8{m+P^9@g;rvE(kVaYfd+{l97wfaP{Od~r{P5iiqqJ()r}3j znP;XiO_4Evt1W>jEZsCQI3dfS=mM|t!3l6V+LFWQL%)&t&RiV2`)+tt(b9?#*xx^y z%zZ;+&^Ch2A^{cc=3ww*Ajf{-p;K1&_S+0Z4q72DWHa2d1d9Yfbo-11enbLTdj%IB z2d@zP9s%%~=H*r5+*oH{clXxLZlE7n;C>>Y0pU0w=oA7DjW%lVd-UXK)4l-u&=qV1 z^c9cxl<*LEm->9R>0#2Bl%Q>xsjzq*$RP5|hA@#GjLx`* ze@yUfF!&>ax7qHfEMfHDC3L5zHX5W0`-(*qUCIri%Vq1-L8t4Lz_PgBBKJ6>MJ`f( zS`~10WR9wLh;N_}|Cmg6Ny@F+LA?crrbljdU-*9j;Y7#vTkP5zEKGbOi(e z?oo8K!Jo}T7%fc>_{p6%5&j&?!0pZg6B{6`e}#CYetT5}@71G^KKivYzzRXjKWYLR z1WtE^x#pX2#sEtf>kR)2yn-DJZq53iB1qaiEHi6g^1o$Amal)K0s-fs1b!)2LnG}* z$(Th}HuUsq@qm#?r|*(KMzPZ=RVdgdO-$$nDmu8q9X)~#La1kmZm58Ltui0*3T16B zH1ArikB5F>Q{?pQ9Y7m#u)rO(P2#eiE%;MM&_8W5!fUhu>l$C5{qFWv+n%?EA3A@V zX>4kFms}2hSr8bTKga$qY7?3-V6gv_JIshc5Zyp+*1=NR1|bAMJ3#($MdZ73<&JTF z+zMDz50E7=01%hHzCI3m$B2J^Q2f_D-p#=EERD|CRgCC!?Yyl6wDR3Lz9rHN9lVc5jxT)o+%2CNFWTF`)Oe=;r zA%*p}S;!`oC6u?Bkxe1}P0PyVBUtK#N10Xrz&C1^h`gTQb2$31guIZUb z9d%-TVF02Uc=)26z~~6kWdO)OuQoxz|CUc1f<%shB!F&+0Ow0|tiv9UIrUl@?2gbm z$pUk^Tx69mSTypN_dq!B4hF+OI-)i-*eb9&{SJDxj6jQ!1(#^F^UBTun{utb{-KqR z)+QgDRX0prB4RnCi!29$63osuT^qIqqorro5I4!s=Q|Di%&fim9mn4W7^1 zJTUJAJtJxY3J-f4`TRm%N)5nb)B^0a7neE5t5%eea+P|2tbQ9b_*tN=FHBMEd?C=M9m=gE`xC%qa@TkI7QF_&2Zyg?-JwPzjuX3yL+n*cb|8K7$7 z+i$vCdNK(4}|rvjX^XMnH2+IB>_DDokQS6H5`wDubmH#0zd2cASwn?9PBUDmeoZzOZjWsPY4j3iChdcR zCUKGI&oR%7=5`Ut*7(qUgx9rX7T>>Q%l5}Z5PH8)KPEgK#8Q7X=hdAFF8op#^K!r3 z5Jo&Jb3*RWr#J*TrF=|u1~+p`d{4Gf1FKw84# z7uHe-^T@5YLIv~MhUcC|EXX@5g01@99cEGA&g2@L5&oQR(E`7@wgorW z-SRmCo~s$i-nj?%e){Rxl@;)}{}BE{2Qb`^ETMP(#VH^Gu%*s|o|ph4{Iiu1x`1*2 z83XZwV*o(50H+uT7YhKtV;96s@w>FMXpI`7D?BnL z1>l&*z+*5qh4%sH!eE8G9b-EX-UsLaW{*1j6?%@^2FS-Kc!z^Dn(r)%U50hZx*2AH zj%WohJ%_1up(oO?jbn?lBTW?wVPia_fbERg2HSpcnD??SE(m1N#rNTdoa`*0TNQ4W z1_<8tYb;tru~9>j#zyNp(q4!cF~5{;0TTlm3rxz?rVQN{+Xn^(tg=3{q@?bMAVKnr z8*eZ~_@E*gB+5v?n&5v|lYy9#A8Levks)9-0C}-;0x}p{F3~DTLpZ90fE-|J^Ns&S zXv}j4+!0v<;!!4*dwOM0WC0V{ADesfK@jnKSThhL^EHbBHWLL`awj1N?CgLaRZGJyj&Srog~Ije$3)2ME-&PM~gQ1{}1^LSi5St#9E# zn3h>)m>>3l=Nc2_DA=xng$FPMsbGNd4CMTGB4Fh%+<7+zj7s3IzAUyF=PMWiR1lJ- zf$%lYl}`cS6jdANucZt8V~E26&LfkLU;Z+c|!499=*i`@jIp53HJNI_~884M^Oy*f4C+8o7Z`I^aOU{$nri`#}9QcA#n64p>BBi(h-%P@fMtF;I<2q1W-kLm0O}J<3wRk zHrXlpE(qU}Jy{!1kpxPYGUUTtR=ol>=%C5$=Ud8#?sB z=^^O^GMcq2K1N6D>qqNH!2!YlPNqi*eQB$Ik%(}`RxTz_uv6W?KkoWmVlRFwv6|F*6 zOKn6(b4w@>vPQNVS3eXr5gQEia%bENh9FpO>ACA!1HkzsmWMv^_Qd2rBO7E=Sx0OJ zj<6(FDmwTb=D@@ww?SBKsG2zY51@a>Cyq(h%gJX1;*GojY;C)fEEZ zxE};W(LVwpk#OHQU~jB%>xs@WGy)-uq5P$LU-!;2%|So_YvzrvJe?)~WAm?sxo?j( z{ys)Y`>~lG$>$^BAITa*!T4w)6_hF_JxQ77nTVz9l={SlOyG$f+-{R+lSTUWgdks; zjSLT4?skW9N;g7qF^nNyqqD#$?ZWrqf+!|sv*M17J0-Ic)}Ann;NCVRBemEI%e2ti zFtbdpSPH$-R4^eMAs4-; zh#f2G&3w10WLpM34emXbM6YAEP;#eThtL@pLGJO zdd<1*Oj~bNE*D0^VI8C`7qLLAUwo%M=VwlH`7K8fC^i>dkMI%~1Zt!kMABk}KGEf7 z2mw&TUp*f7K^*(?mKWkr*Mkjp)$4aZy5u)+0RXZ1_OcbiyxKNtDnNAsg>n5B3AlV29AmRbxI*UHjamAgqP*xI{Qjey>oalZm0(g=bnAHPW zo%A&LCG+EwTcKd-L-J!cb)beL9uKQ}mmT8>(tJxblkw#b3v%pXg*}{zc8eVmbTnG+ zTO!ZXsKl-7%VWL5> zVPDc4`jR^$ga%+d0=atWQfvnk1EBW+JrKB}0v?nbgLnV(ia}x|T-nz3fPOjZw}IXi z@^rY)TYy+n50F##Opgm;kR0m5O_!voVzs>tMwe*^tCh0q;V#u>U}Fe2u3x&%;N(AaI^)Z0dtG1AYwv89upV)55yOhN2ovVS!T(5*V4Hf_%*gNaCPy#2Z+;=U2BoZ-W8dw>Ot|@S) zSa2gOyvjiVGhP7~6o7Y3TnG?g`k!eM61b=3TMHiz?PsS=>M?iG~<%-a7 zrb;iTrl(-AIvQ*HaNQHf1K4Fv4ZZg1jH#RVg(>-}b zd!6f`*lN8)j^tV^hax^BsR96YtbcUN_8&j^IH7O8++eQjTDJH?z>)r!!2vg01JF{C zq=gxAztfRJVu0|Cp6Cw|>IQzaLhuk_n*zhy6i$D}|40E3?i-`*MI_J^e!S{N)(6p# zED%zd69m6*2w%2pBvJ!uV5h`^xP=({wE15hl_c2#FslNXMBVgR%`simiNaFiMw4po`inx9Aq%@FHvNn_}E7379|q{KFeuY+7oj)AXMY=R^i zVA2qppM!tP%MD917}nw!E?5y#0qmasApP(FSJVn!%7Jeu%YLr z2Oj-&`waQ~U6<>#n_~5&44(9T;B5rL%|Qtm)`k0>06O36@3;7nQ;7ojPzX?>3=loQ zJK%NoDm#BWIsYIF92@6_vygF@I`e?wrE?$Re7E)~@2G}>N8{jpI@i z?61%O#Mq<27`K!t{xF+*qT^xLEj0fF+k;P;PuBt>Sku3$BO0Fg+lL z8IKkV#4Z!kD@6Vpdz`)%X`LXMbx`m^DTQS@4m@ZlfAc^fzh&UW)49OBG%S2~SiH zMiSaG6L{m_%7c*`mgfQ!08#l~Xz)GYDt9v^mZS8g;TVmuIxHVkQ>T<0l4jkwxtLNE zu&hoObJb(Y0m>#HQ)~g&G-D7<9vJ4pu}!|Fxa=6ZPEY_iI%>0y(fV{H0veFkTS-j- zL>WxZ*gS7^|9(`!FSs3++JLV;hl7R)Y6VIW{dS@d4hzD9K-9yt?wqw`yQ*MCCw(Fb zpaviufoK?fU@sZqH(y`7_P?is*|8%wLx_5SQ8w^jf+6%*-+*k__4e8v*mpp9;x`vq zwOOaut_K6;5SRcsXW^W96=b*JA8Fx{yG#pnMEtLs@Yj>cI0Fo}&>92tj&*)D{8t=8 zL&F*B;gQOja6`yR$N)!D$@37InWrI4J_Kd@G`KY%Q@7T96!6CV4>t}hyLq%Lr=0;t z%OuMG2y*JCCW#E&Tcg6bp{nQHk=X1PnVNlhHazKQ%4pa-b!U&HabW z0Xm|5Y!mj!4Zw*Jw}W;Lh_7a_*d^ry=3yHAr=2_h#6F)Ed})0@-i>=pyRF0>_eLLu zF9JaMVs#1(4Fj3~HbhG-vp+qm4j=3cG{(>v1T;{?j;wLOl!Y&reC>j@W~pSQD;j$x zi>M_H!<Kmk^FIj6XWmph1UANs=*vz3 z$rIW1llrA66KEiDgA}T_sx6FxrM7Bo%SC<&=F1#a!M+as*$1B`Auv$D%5;#cl^U3< zm!_E^M5`bX|BLLfWXFF&6cD&)TX33!w6PE_>t9uG2GsC%RVIb5lkf%qon(I{PTf07 z#gdb6c~Y=D<>uS+fF6ST^Hj6Tl5O%kAbAR}IR{zkz&FZ6luvVA_VemPqcC&}eY_h~ z&h^3az(CYKNA)ppKNuhYaM?1O0<#Br>oHg%{F`duclKB%JQJe8nLY&B6QQ5h<7RKt zJY>nNJKvREstlv|21QH|MIQhVVhHk0aD&4FSkclE_p40nBTLD z1S9)3{Y+VcX&a8%-mtoTnt>n&q$w(o%Sx>7d1LpZ?{2@Hfk@_t`p+tVH3(+?D?C(0 zlF0ytWwsBp*>%y8E8xo`{b3$_DnOrmL?03$&cHVB9c=N95$>-1iTH<7cjvw<`^f!X z06xAjzI1F|O*aiuJHZsGc2VFPwa>ylFu?Amo!x@T6HG!nK`jhAfN({ybprM7C~rpn z%kE#n@DIE8?6ak4b(N9Kr6byK>!RU-I&L~ja7C3ZYPL>|LAD1?I#7uB^u5@15DRbG zP|Y@4qHuL%T;2lp6r)*_V|B3HU?h!cGbv1q0MK77 zZ9ID>0@63WSdow!%HIkKcqw6w8X2Tkv;ZRp_~DIqST=1@(cR7(_yTKSR=~LiAs~zZ zH3en?+~!S7X`$)<5&#hA8S6k~3MH-rx?)Hauq(=^_qLr=JO?U=KLX$YsNht9GyoO= z5NvPsr22UdX`JVps3kyXeYEHsZ@eV{a2|Sq`vHLaaW!xMnx(V@1OmSH8XZxedzKXN z9S1s}VSwkqBMu~N0S6`Y z`CaFCP1^(k0G5ixJk3C`0HWSEmOnuT$pP73XdYO*e2V>r0R|$)d%(Lx0Sr8Z8NwTJ z7Z9mPi>tNMM1s(3$(Rm;Zi>KLsuj$*D6B4_8QkXL=$tEJ@KXkX!74v*QD00HCcU%h z>vC(nzm~Ts57DG6C;~dr8!^P9>``de~tD{ zu=1TWPgFjJeO@{rNb(Zt1N%kpa2+TgA5p(=#A#pT4sDKrGrE_m!gb9bMK73k{Ap+3 z6^=uQfJ^1rbfh+)A0=B-(=pB3;Jdw}@h1_mzwAf`}Oig^;L*VV0rpdwW~gw18}CpbD9H#j5%Q3J8VWd&FRM|Cm{F)0R#dP{?G%&BFNfXLH~3h z7KA0QVILrG=1lB^?6HLqe62MRT&V;`5lmq;T7lHWY`54Dbplxca|upU;8n9!0$=;z z+XQw9jFRD^RFJrZ$RWsX2+KMD%@6}K(m#6#P-}1;uMZ#;v!3`zBZT$IMY!Ew0}K3K z@+t6Txgk_HD%Q(<5ZV;p&=J(oaZ0)kLJa(>R1`;Az_KNUw7Ef+gwPk_*tlFiGDqcd z5uhz9cd*<>;ld5g^Z6z_}RAM!L1$HEy) z$GF?eVwdpN_a_~gc0l#4_TSQ_HA}}}0}Z*K>7OwK9;4)0)UQUxa7_(u5azAuTtNUF z!_LR(kaYnGgBtnbe>I^mn@MZwL-Ic}sp9|HxoTvW6% zX))yh82W&{vD)4&u`F*v?O{1y2mp6Lh`*8k78$}MvOzxl@Plbmn5zk2z~lsY+9vP^ zAIA9S6!5bbr%3_Z^X`bR7p$$pwN*(3Xw`3(?J&30m2mN^lFiS-0ddhe$<4voIH2%( zNULkrU16}%92P!86HpL1<+lcnRuK!u*uN8Gatz#TD{cDmf%<@d%?VOzU})c)H;NDN zzIkg<0fYYWSV{uODF`<~;EDgV?}6AZ$ZP=M9&W`s34{!0CXcrPfO`mli-du5fq=lj z?eD4%{v-s07yv>DtsdaD3K`6<^WR|v9pm4wL=*5Y3HW0VaDA!hTOeF}*9Kg{Y+!~J z=>V2}7>OV}O%MW?M*z6HvJL1Bz`M>peD2)CQ;Vw!fMf}!jGKHjwTo_No_H1dfoK4# zZ9_o}JHcE5X^2x23=fqV6P)pLY6qIIi?GKN{Do-3K}n#lbF$2$^sCH1BE7MQc=XRA z=rx3LIN%)vFy#yrbkI4|2R1Y;zP$U>EuXI1MEv`=$!(MUNjogkK$&8J|H&z#Kkz>r z33LBLnI97h$h3ktVF(=+!S052XvVtL05vXs+;L@$V!uD(g2lI;Fo6dCt%J&$uecTa z2Uc`;x&?x!!zh2}(Hg6!W^0X&LI8nyXn)PJ|3|m&P`64u$={qCSH8YmHz9*H5QzFe2+GoLZLugA(g4-fXK>e?k z`I+ZqP6xmne4#7nAk&YVcp=0CkZG$R8odYs2VDuH5;(C4;!f5k`vdr42BI3csCSVs z!UgFi!WjYdJ+%l4Z8~fQeqoQp(Q-dn-AQR%_K%v#Pg3XR z`p_fPU6Dz_A4=cRW&q%R-VFdqAt3qRn?VV^2P<)Aj1@1%NeperBACUnDX21-2>8^U zW|6S{bD1RgD8vA8?tyQn?E-%n0`7?UpEUw^#G4>NL1TVcU+wNF7A$Xy#z%xd^FbgR z=;9(Udw>H|;?7uvTfK1o`up&~ z$z-ImYXnUtSdQE+^U8X)crBX^`v5mDGb;~*&3W#sO+Qf6Hp$?RBV$rPvsj4G&Za3B zT3II9vzlBA*l?k=c=w}QKK=27lTSJQn~co>Cntj;0%Xvz{oBUxZgWEzjf5@t!-9`S zOdK5;;30FwH+}S>5xX;^d-Zr{9~6FlV?;a*K(4R_2>ja#l-t?exq2OH;592&EL+yO z;)Qu9Oc=BE#8$+fcLMR){~Pnk$QZ?eHJ$V3u?Rkz9rcYkc%uTj0Ai(Vk6c(v>Z!}{ z3ZLi#)|E0A^Gk@aAhMKsAZT_XwkWVmnQu6`pt^{B3E88BvaDGM`s|iny{r*C6xwR? zf$0qu4cVL;8bqeLj2j|jIF&X$Bt~klgwxO-6PR`sGais0Ss`>(c?U3xpsCUrMEK|X zaG-#}vDCAX-n-c#`0Ax3;#EWf$A+kvrpsXDhPBa3V2^~$2P1@hfWHR2V9VUJ5PyXk zKEY43?2^~LL_BOy+Yo-Z5G@eeb?_u*;_pxpGN+^JHERD21TBn#Uo;A?ccgT1s|W0H zuuEynJRL^#tkR|I#ldo59%dfdEnT|y4jTdA3IKdl0BFk}1i-fe zdT+nu^1pXj0?*VsNR%3~2@VN>z(upr0KD@Pnk0PwxwQi4+CW6Rz$Sya_P?rtcLeQA zOamPQ|KbziC>9d{Sn8qd6|Y-0TQ3&ub(~TtJhkNnKzd=p^6T)C)%V?Z-@^MA^76n# z53PUTfe;M*#t{J^j=Sz!{P1Emtr6+f!MB6)T806OdD`U|NdI#E(lf8{MQZ)>l>Ljka3Q!KWoOqe2ZzO9N7#c zDbkw?;Ac9(6}-D5MnH*Un(OPEZ#?ig>sdh^0dF34e)>{Uzh=SX0O_COA)gQE8$da- zV$HH;P5>DTLM7nS&yxRn75p|(?$NM8B{TB7>{V^f`40K*3Vi?nxC;a6gHU4?Fffp2Fx&*D z6#`HZuF$7f(i96WfJbG4AYX)|UR2dVeVkFK8+EqBGJetKK{NtR=}oAu5ZNXSXA8F0 zHe6RwLQ;mV(HXg?W-_5w-<6T8epX7pYEFF-I;UB$Y+pF=CHisT0obe7oL7^J~V;K9%Z46}-8AFk39 zE0K{t4gZo&z~mx`GB%?~kd1K*(8wQ)-;Md;0^@08qAm>V%f%*jht2o%x)AhXim?v=D&MF2`us#KyeT7 z5CBNmd{{=`$=r}nOckizU}E5`1JiYY-=%{N1K`RQU~GnPUdGVc1X*9=fC-V9b$spO zhQ8-0>G(rXaO!?y?!kK58Us*-MCu+PzC;(4Dj5P%n+#C>XC~@3(Xzd zdfgYs_JMN@a&5ETpj9kZ?l!cA;Pi$DPfLO!m3bq0V!EP|xDuRmfsACX{FL)0<$^lb zx`nh(y%4Kc_Sz<74cENl6?1e>$a2@gl_fCh;O6}Urh$PS{xa?YYZ>ks?XZr$ zDMM6_ejNZ4?Y~L@^qQFbk8@$u#%#jY2T7pKgFm4k4E4|lf*+uQ(Eou7W=CZrTs#F% zY{U5!cs+K3>-cKdx+k)>F3Jjve`t$F;ShL$$?sE8Iv-iLdM)T52q5?$QSiRN0M{n~ zP=z4uH8c4PgzAa+t97W{SQGv_5DJ zPUDeBbjaRf=|Kp@lq2Uc=T_~uM~=_pgSng=-~(4#S5p^rhBB?X#+M%Z<$v7r_#d|U z8r(K|z;N6Vh@eqIMFKMrX~IM=z6K)K7mG%>tq_*Nu)zQCwgu+^XgrWV1^}ExqBpL@ z4=P_c3I_7+JJHv7;)J&0I%~A!MkD-n<4Yk595elkmO?NCh9y?F?aj>_8-+^@ThNF|L^cwh5#pk6s z66sRK5ah-85){x&VBl@pX22m3xPcu>W?-W6*H9G}KxBkfqOo;JCnRz}oNA=_GkbQY zAgcb0r zRi8c@4?%YQuS(zu{2T(q2Jx^L>E^K<_%hukrCLu?{yc^<;1b(fq`V;u&lpP{4)l``!b*}95 z4-_gb#W`=DefJL!ZkwbV)?1SZ0Up`*G9WAzzov{qag6!zX4bsQL{gP&-lud&2$^tJ z6e~7Ua%oy17zX~{Y@)>g+5Thn8&*5S@V1iro#-Ri>!#49bG1BQ=z)cWxbf~WQveeD z`nK+aCm^0(<6fzd!C(pkUuZd?p2i#^EBzm(Wj!>zvW)|Z&3G21IMCX_z7k~1!FGaF z`mfn$ai!Nb<>=;|E!pIlwQ|-C{>chJ29qB<1B^Xk;&7x76ME=N zNq78+30n8huHqv2gQO*Xya)H<#%Kf*&p!x%kaQ6MJ-xW4#R0I6v)?*;AK<^RWc8S( z^QE&!{)|#*t+g7$jM9;BLA0;o2)N>~>R{BThgVoH&<4U`9x}i}xp^R5BDIXS58dZf zV~>vYCudsO#HVg+6Z|^ z{xDF+%wB{GDd5=y&;>F&NeK9fToP98{pQiH3;+$wz71sXreT=7Vgi`tfW{sFa?OO$ zU!Q~VhNd4j0+tapk1k7s$Dek^v1Rhsz6)lkz`ym!hvJ7jrAKN#-6<;VncTz_i-09KvJRUswh%$c?@^lfuHELtUq5xTjh$Ap+5x}0mz zyX8SyyCBhgqa0~t%7eBUVs`sLwuZ3kD-6wtF))6h-5(divOUw$@$92Z-o52oA$;r)=HtyZ#7$|2z*jm{V2*)7i1w-%W5$Rt5jjr`OB-0#;JMtChf4 zIsd2(#k39}(vWcZOfwMc|Ajo@!60CeITv5jN^a8l!+L)(J}?_-h8-7zwn#~R_*?gw zs#5v&q=8Y0d2Csg4!di{?*@Q-0ztwbZVw+G@TmxSpdM~^+*<*n*o?1NxPB&9&kTfL z)@*~;yP{-Z z0if(G3)a9!6iCJ-(8F$(s7<(agg@Fr!wVHUm}B=H+u%*Whmwwf2*z|4xL8&Qwg;fp zny{>7S*PTH4ZU>*1`w-DjXP38v)LB{;>vMiFoz=zW^L*5!JeII2xlU{kcQr5d%fjy zA~cD4NFg36*WTn+uZM#;kF+LWE^osS)=GI3X)WIK>6YztR|NwE7$Pv_jh#Qi-=urv zGyJ#TB0o-9NU%abMx+2FFFfU=VgcbPPeM1;WAXcYEe8J{yTDxW9q0OQ-#GPvTj_oZ z$3FwWG4=M$?_dm8sOkfDj-x*A9;XR(pZFiTh;E5R4hZ<0cbYB0AzKF?);@5!^hj|* z5X>s?EyLjRVYLE>E$+8qwl9UcpcJ(!uq0To^GoFLa6~wg9(>-#&%VGrRfkh2Wx;~iRN5kEym_2M52=pTeM$9g; zAfjjQ7cSz?;rgJNHgFs;;Y?tT1JSKea0Sa>{$koehZ-1mSX_t06!_WaeBz;c*Ec_A zveE?r;;~J(5*M4K+J(;%FFcC?;oGPQltluYfuDZ51%{}V74UcD0ec!q7=qX;+>Xj< zObVgDJ_jvT#+HB0;7yHi8v=6=uD*HMv2|1DrZ@vp0laXnM!+b5AKGm*kRzc5$Yqdo zFP-xWxMY$6V?MnJSGK! z%myyl1{~jSCCwc@niu6P53_`(&RK8BI{KjU?a7&j)d_AN$YJoX4Ja+f7hA-UuYQ(8 z48DcahJM}w^dT>Zo-nX_Xs8+}X!Y+(JcJWyWA$RrM;eje*%*3)ksnOamn5tZM)-8t zn+@k#B1;Dq(Eu3%V6WQ?Q3yR4*T6vz{lPR-n1nmNcLFb6y`cq|a05)N0+ar2#3iJ` zasPPGbO}1AYWwYi_MUA1p*&-7zur1^9Z>vI?9$`HOCn#F!pXzJ^4>={YQcg@63z1VA$c zJhoQ&cPn%-&ru1pC+h$0A;IHNWcE9YHqE9g<{k6Ok9I>AE!u<+Ja?uT;5$rGXNdZ{ z?^+?e{nIVq4|Z7J4S>5M@Y}U(8Ufr9&w>9Eg~GK__9Fb#49{v{D4;*KP2hC%vilH< zd3g%O?J{hEEL=|=AOVozcc04u*SjC;OXnDlzW6dy;mi?Q{Y99~1Po-Smp#Bb*`nfQ zN+fKvDTooi(EE#wQFA(3YBKEgulj*)p`MkR8P#p8LV)E1Xp`NhTtl$J&xa7<@SRrW zB)MEhtr^tC4Z&`|!M6seRwympz2%cFd!LF3AX9!3bh%BYsO>J;QEjT2892}<&7BPZ zZaBW0Jg-j@=<#mOg8R0r9oW5<8o*8n1JMMeFTM=%%@(Uio51Y)()miUFeD&&1G0>z zG_)}MaY0XDD4aTgTpVFlrUjDJux+Pi6^Z1VA0~Nr?#IPA=5D7r5{>{cOhCNTC(8p& zLWYJ!`-ap3gqzUi>cvH>W*RjkHrZg0Ii|`E3mYmKMW{O!EXfxdQv`LKZMC+osyDF? zk}I1ZGiSjjhED9mnU{+z0WVcZVJ=15zpJ4gIIRY*ScHrH0L1|ZHwON9!J^cS+@pt`001Ok5 zr~w#3;9pz}?L*+Nn2IUkpO)A!N(5N2Cg5-gnt$QgVJKVh0o%XjYWkr8h|k@-9|}6a zId8xXAsG!kb-CE(`}1_#0s!`Q6xjRoF^JB1B!XwEY#`DbFNS4&e+apZ`RsQ}_VxGYhPJ#5^eg35Qo?3awluJg^gOKePa;eCg}n*QYfQU?6Je zt)>{PfifDKASi;}6BV65l)7~={Yx3UD=2f4*FZoB&I*J_R=vXpfR>BN5Ogzw)@Rmj zgLo+BNN--tGFOgon%nwm<;@ZRd(8Hr0t4A6QM0((CczGZcuqA`RD{PNJ_G?_wPl4E z0Gc68$+LqkF3lz&m{}`Lyv{E~rE5{%a_*DdA zUUK}i2H*#3|4my19<=G4c>tRGfiTecUxV2o^s4^lTZR7z^p_mYSRi~+6JPq>bB7Rr zSN=_g?9lDXnzTB9D+y>*wEtrq`T%QFz~8cED-N&lUZ9Jj33Cz4OFE}I>k|ythg!Pc zi{OEJADIcM(XW%(nho7`a249tLYTC_Cb3o#9IU6VTJ!rZq> z_nPwVli$SL53mAkim*FqyKfCzl)C_R7U*9?o}q+;0x}S_PR5#;Alw zz~5wlERYu3vHhp$qs^Pu`U@MtMgk{-2fil1zqeF$Z3WNR_ot7pu;$&jZ!8c#>0-7D z^2VT!VH6U&d_cHvgo7Xgjxeb>xUE}jbW2yP6LJJ31dcKnqy~#{M^6g{sav7UwxB2@ zZ{=l}YGioAmSDzo0a}sF82yt#)R#Z9DIc8`v?<5`)g}2q$_`(%Ush^Vv2h#DO%ED< zy`wtpd8kz)%%d8Rk{HcFv^T;7Z}FqWFcH2S4ECka&SWydx5hp_B*b)q&H%L)5_T(X z6~qv5W5N^W#pEFP!$=OD0Ku!?4ZIW+z(@jf+QRoW6v=W#s zuux~GA5!vyFMPPA7)&H&cfe+#h96yF^c&mO57nFLsTd&O563d={W<2Xh>P2S1PPpq zI)?s@`l!!0%~HnG-=a<+RWP7`Yt~o+{DRRxrlR8mLl9Y_$_s`{zdf`*0P=DAyU2Tf zq=Sn#CF$S)PuTlERe7gr!cIDy(UjAp+f%#!axyWHJyyRSvYZ9yY*m^Jw+Esoq3=vG z4Pi5hft$iV13=Ub-jswj1f&0RO|3mw(Mnruw>jZ>0i0(Y(lK5D?ff@oj{~j)e04W+ zvgS|X>3+Jt-c}e@g765~8zNCh-4MbvVC)DkMe$d`6s#;u?Z5~ORBs$#Mu<#Bc{Wkj(V4A&lGHu#jQ!sV4e{T0U3zZ6pX@$)Kz1jreKRxBWq>^{<~)} z?+ughRr+5v0m2$*%9saC!g?^a?m^JQjLBEzpHG0p8UTflAp`$oPeG6^4$n;n^VQ{l zr0awFJ~ISg#tN)`7q6%nZjd=y%e&8xUq%ZOo6raQNP(av#4@4{|2jUwvCtx+`&#$5 zw6GOUiKzHe%k=Q%KEiW*PaTx-BS1zYK^Q&T%?_Z;)1eQj|dQ5 z$5ZD3s95MxT8&%_O=BEBXE20OnrF}_H^}2HkqFn5JV(+&Z`ALAc+sQ9gSG9ADP`6je&AsDd`#P2j9vUumM*@k~QPYv?e2pvPMw| zbsY0lcvRzudLW>_U~$Hh|ASxASa=I-_9S!18rcv)-VN$w(s-ti3q&y~<3gdJrPoV{ zHEh=DVo3sow%~Rb9HbBo!$_=DkXz9Vm>2+k2zNj!Df&a>FQCuz?`tzHwYAwm zfp~X^`+FmEhn@ZG^p^uZwTAhxH8K76Me5llbm4lKOu6HG*964nI!GKVK%6B!$xKqVYI z;n@Dcy%*$goPnhzgoTgQh!o-B#{xhR!K^{z#qTS7LO9H6c|ry+gCxc~I0X(~Ci9DC zI81__eWXT~;1w}T++vXc*jU7u3NPVyBH1KOSHHPkKkOXqZQfOdL zXn^CA%gL`M+KGjq8N95?C=3N!7AA^|i{fY^5NLN;M( zW%zaxEM<^u0>E;e1K>!w1)@Z^nM);0g4^9#Nzq-&W3f(zBVe)_gpOcCu{%!{!zAax zZSeP`2s*Zb{L&@RhXVXL_sirz7(Wux2c7}#|8wgYhgwmlHil@1HfQMmEieNC6(CjB zw^fV9q6b$6UKg0xYB8n4r^$d;tALsMi{SVq0<~Ba74m=J`MWJ_wtb5nHT|89fynrvj{)?`Kj-|{nk%_ z8UX+Q?_Mt_Ipl8K!d-N?u5e=|2_i(#`VBpe*t|>c+O2_C2!K`d{dLB808)R zR@?@XXS-Lvi9=uBJAy+X{xk*5sFmYIkbdB4k|RyZIAzG60ig1)RR0Sq1*GvI*S#bk z48_7h(EiN!wW&v^3;-woBjZs29y4EmKg?@%bM&k3*U-__(Gx)u193FmzNk9qM~=ZA z0#0~%R=Lk(iB8}U5$HKFJ6y^ZCky znai=%F^%Lv@C@hj%tr`=Q4qYF#aL4nIVAgS@6=bS}+-KxiKXOGaYMV@JXWSj*$qmzhN+3;})!|p;8h8 zV_XgeBxba%13*vP#6A==diDU46;%YlJNOYzB~18XaxC# zGMFtI=r|5$GY-ZNPPnOZm7h;HRaod%uLF7@U~!UB2$OpzZ3ILV!h!t<7zAxkod5Q# zByN7UQlW7JbQvJmp5BTdrX>c{3|LA*rlRLhDU zM?AhwfJNQdOb1w?5d<2(8#hN3zpnAaU%+FF$)t{7i)_OjCH+x@Ef`jijH~Y|gdX_4 zu@N&xOIb}Y!DV={uf+iifiAUJbVc&=mWSAbblP>#_C};2C?dvi(e~rDK!cDV5eLGd z5WjmsnRozOhT_|s{=L_co0+0`$tg=2fs7hZCW7>#F%SHh`zo<3QbWh{-xdH&2mm7r zBpLvtD8P5$efaJ}*Fc9RbWeb0>Px!^wnF^uV2u=*k;E{_?>r$en~@~^S`3+|7y=WO zl~{tQgP!y{kI8tdBMM>wob&l_&WAg|U2BvV7~CM#N>5(#>z<}PANSgl;ewRZOm^@E zaw&72o!y3k zjef_#e@u}D0RkET0{?bLhF~C|9l6aL)eB)l+~CR!jj5j6qo!aU|CkIz-)8(s=?TlR zO@JH#wa&;RVgQJm5M}^U3L2xI4S@Y@LGlpPVQFP-6SiaE@IuG|wApVM zAqj?Y06>d^nS~V&!oPmVru__PNcic;1VAcWmb?RaIkaFdMbDN`J18nMa5?-6rEsTPx+73773Ah4$rzT`scu&rd zqA@i!}`G`g&=qbh`=xU>96?smpBAIQJzUeyl16w-)?TP zf&9TZz+@IetcBU64EloW0FT)x71N7uasc%G7j7FT+cyjV@t;120nmic`;i1aB>)5z z?$;IYoWq~Ze?9`1J-RI}Y=|-|Q}&8|5~w1CQ{br2eSWlY2;}E2iZaCj>qaO&jC2iJ zgS``&F)vX1H91GzG~MJw;A&p#Km$Ie-1Bm%X_A*g>R-AX{+gn#IA7}Bm_K&#+Mlko z@;Byvk$k}Ddz=3Ngc$wQ567HT>R!0gG7e!FhTjJd7TgJ9F$q2Zj(IIyxC2rNh!yx> zA@J*qvi`mbt>}O`=mWV96ZKf1x#Yv*I8(Ds3}~K^4%0v*BWuxyK>K-n@%HW8pV;`v zEL3=R&G5kpgAt1PGyn?u%6?E|Ry1ByBtiwrrWwwE8UX7m8U|gBERRMeBV#ZAIXEPj zF}~PWu#KO^B5!%wqHAD)b=kCs0A>@EM>Yf|kOu|?QXa!|pi<&(p~iZsyaiLm2#U1^ z^JxTkz*4&~5M?v%dH0fQ3r0xQT9viFWKh%|16@nUOz$$RC>T=~6sHFV^50V2P zGMN(;MkWs++*~p*ngie!4tq{fHADwwNFX-w0!KF(M%X1&Tx=dLV7}oil&&^7cPNA_Y43(_Z#4aL>j{P zMM7^^!fXNoH@zQy(@7A^L(TFtRpR|Rq*`M5W8T;R(@;O;fAd^trvV^nkNs2o9RTg8 z@b6q$fdzrk0j^1+5aKEm{nZ}cTVevVI)d$!A|LL4r6>>(ye}Gq?FP6K&Vth=FGW%< zCLpd!NmzLWT{U5;MQgAp2Z9^n)kn!!`Jjfee<(KLt}qmKC8F{Fswo1%cH@ArJ-a^P zu`k?&CzyL+z7N!5_OHLrrb~6fStcMxLCeOPSa8Z0%rafn4syykAbtU2J{)w zhQJ*TZw6_5rGxou*=In!{WNSL;6|306K_^Qa32_9SV1})a!^2WJI)VnTfjmAD;s}5}%z5E_C$F43;qcxb|1xz+vht;IALN)>Lmdnl zV0<^_F|R7Jqo5`v$pQTas57A6sVqPp1U)0GEFdHk42Fd-aG0zS7fo3V0}KKFxo@{<_i zXpndW#4&KwC%`ElU$_Ay0Ge|k7vLJt!kT;W!yNy+J71*+aKFubQ{jO`7?(otMm5~O zArFB7xQ5&!br{wq;cvvW2^L)0P92N~$y+cvo zHR~~P%WGPp);YQbqCY9f21RdlG3bvlnb$QCgP%L#n*OROsz&FBnN4v1-sji;VZyx~ z6LB&6#QN|9N}!GXSmz~hA=IN=U7U#qk^BeG?*bzcLK6tifFeGW4LJL$PktEwhPeVS zeMRm!vH1EceA{IxWWGAPycEC5SmI9j;s%)oWBV}z%KKWEIR7Cj+U|hH6W*w;QU?u( z8sX{&e7_)gIWtiN-K-`GBpTQkqm5cUK*bDM4kQQ`SO}acK&wXNsR>gco?|>D^NUfD zM>=G`*agtOf?@P zC$}_#%=rdv=x0AMs2PCm3FL-n7))+?u;7RYxYtKW8wU~oGU>CQ-b(!A17}48*j9*O zx*-Fk5d;*-QTX8Ayrfzr!Jo=634)TsT;*t|+n~LLY{}5fzTgu9L(Gr8r}+;NS@&!L z+}y^2JWU3ZSbi@gSdi$kiBS*};J4q+n+|~iJ8-Vs>6%qYH59SpJB~>ukH4TRs)=Bb z1ik-2IREjn-=@EF$v`X$0qco?xGru{!I(0u7qPv~od3Kb*m{5YeGt#Q&B5;^qVNnH zS0o(G=XnkEh!}%F4SB0l#Fzvy&zj#Rl?ZnUC>5P0eRNO+8W3_1p4K(c8<4dBuCO7* z>$=)&jy;uYRx;NJW5_r+Z zzi|Q}S&-Xitpyj%>Pi;-mNE6=&WGwF&>p6v!vJ!#GGgcm%W#2pzdfEr+{4wmKpzOC z1N;hQNAQTlUq(-LMpu^0YVc9X8(bY(hW}+nWn?LeuE72=&{Cxc+CmTt48dO;$f_uA zz`&4I>I1H!DS$ctcdmwBs6OJs(CjRx9}cyW?cOj%3@o8+1K&-N2&jI{NDH{d5%+F9 z0w&1d-)woFM8K_mAlJ7|fVec`2gwkg0ZXfvfp2r5A^-t;qvnd|CLA;|z03nt3!fC` z8QxLL>_ypVi7X(R149p{F(AdT-?s8jr|}H%2dL5>oSgPrgUmU;`&qaj;O~l%u7mid zG_6*TRUn%ZY;`mlx90r81=w`ZSb$9iWAJzMQnCh4lO5=fT~~*Et{V!fz@eeQdIW|< z#^HUK0I%}n@68O|+x6Xd-}w#j!e@Ut4B^ZZW)MK&CRX6ha0#>t@H-Q%WGPuyN~Vgz zK;YpAsHM3VUc`U(+}t25(f4!y6A13d58Hpw9SbI4Fd$rk;f3RIhBpoTrH)j5|K%rV zyXX%RAuIV6!#)dzk^3X`gM_kl+|t9JB5E{nk(5b_n>1H1e~ru`zg zI*n6bo*97Repfjwu25*$70ID-4b(ra)I0y;=b!(}Kg6LgBzW14J^>-%1Q-zpAt=~+ zL39XYf`GXRW&Yv$tYj{%0Z|ZwijjQ!oAuy)SmA7Rvnr&2ynJ~%T87E~E-4Rz;aHpm z5ejVz7%K)DL>e?D(RTkc0JKKnMgZXL)0zNH4QQs(q5)urNiDoFWk&pR*6b9BPJ3Kp z{Z~Bz%Nq53Q11tfFV^4<#`o7M0Z`UBt-*D@Bf%DIb89a`<`FT9 z*@{~QJVh7+SEWu~MJ(21*+EVuE`hNgCb0=e!(hSy2mHGpufW@R5OK}O!@?e{32+)m zKv+GonL~L=^ph3Xso-Y(yCZk8#zaRXlt?ROz$Fz!@Kx1|&~g6TXi?oqTYbQ?Hm<)p z0$?lM!1fZ2S$&P5GewHTd#?tUFqX_`S%Y8G1wtYjpuD&7Q1L(a$5WEmg0y&!16R18)h7~npoM%zj}UVjp2 zz;TEHi&Vl?y`_U+S)wzVE6p|vD%Ze`A2m4r-9)ezr;uh0dr-908D>(62P_PPFIH-P zx3f&Z4DKlf#UDr#JwQ`<+4G&VY1Mxe#Quu=%_0vgtsGRm$gb6{4RCWV+bEc=9Y6=J zT@md!e__7~#Yjw4Rl$;718rdHRWh_l8^?6Op@Cp3$YAnXBUWVyJ``m`$H@p00zPd9 z6!yg-fMNW*9vMNdKOqD3Jgm47Zdysd?Gi)lU#+>fT?;XjQI&3OjIdJhZ`ODcRvBAa zRpm$GK&obcV-{dNgJ8T5j##Go5BI+urOI=@3iEv+G+TpI=E|hU#I&|D+T}_I!%o{s zfp85Dni|JGO^fyl;!rzs4b}%7@`gfk#smXwnUr?2xEf5i$+e25fatJ6Zc zJYR4L=IfF4rHOAjq*8VRz~+u`2$eBA==Z&>IS)s_WeBEHLUb7<|@Y1Z)Qx%)f7@{V?y07r7L2h5M6S^UosUxGOK&ATgo5746LW-k@n_TnpClMtWqNg z%nX!Wm|?|iExiA6|1D|>HV<&4J;}0x)1RN|L{Q|wh3FpW!sv)7p2VaV&U)xKZ|$Jh z!(Q2oH()D9>K{@MI{1ErJ^VrVNX>udH|ajo9TkE+a~>)fAfP=cg;6AyAsCYWp5w)j zBLYsS3664@iD8PK?d1Y$l0cXA&w>=5?GILuk0Stl5KO?cvyt^}!Nt&_ z8EJ>ge*u6N`EnU`=%+&zv@O7=wd-<12Q5VOJ1hFZw z$b?bX!qjBs=pgGmA})iP7P(S0blvta<8K6{M#k$u>I8rUKXw6oQw8Qcd|UyEbp={C zq~DX;Sxq0vxq{K70=L^5!=C|wu&KZVOqPTuIdZ-xrb^@cGh{T<$dt3*o5(_ z+cpyCy;cDl2R{HHUho5mt!3PfBDg&aA0dlJj=ySC?*;(S z8iCOUcVG(*vOmm#=R6aYEO46iT|r?8bza#e1q=^=z1|RvpDQu|r$~Z`1;K0x?H1+x zgh5Vz*n$-f(-iXZX%GqJnA$VYGNLV*hd`9jlq5s#3On$0p0+yN4QU`&B5GGYOo%M6 z&gVzk4;(yr>eR(ICTs~Fo^Tl;OF%FUN)od$F}CGlfT&(f2>nQY_$0`YP_)Oeq<>nG zwJQ?{`|X2Bf?Q@5@G`(Jupg`lS)%#l7r$UK)>)ke`&fTz6>;cCvT&>=2SL0YF@cQ8 zT5Mc2KL`_+tA$!PH0)Sc!R-#0JL;1ua50XzqE1>|qhN%~0RMFRbH)|t`2m$<;%k(e zmx3CTGPYvFTjT(k_4$s-7E+y&laYp&k6Pz6$zV=>1@(Uvn2msG4~8P${s4nOe7|H9 z2AooL<9{w3Azl17VCB0JF=@St5Kz7&g1dQ6854B-#=J`8iB$`=}RUHZu>#eCN%c%uOA4g=x@4KUspQ zi8lJTMNdWsZ%76>IT^WnxunkdjOR(Ed_V+1l*cXw! z7cC`vh|{0_fM$@`XMqVboCtUAG8Xu|Z@&Io9LOKe15C2NiDux435E{F!eGAnZhoy; z1<~H3qA8pGu>ac5@eu)Va`MP=hQUncI$wPYDF}>$F+=dw;lnfpABz$J0fFZ{5Oqxw zhZ<_L0Dz;taV|cA&uwufA|Q`}pg~A_;8UZ-wiu3jnEKG|1ql_;eCQSAPgKjWX9mG9 z%sUlDQp!i|mrcxHE8%mmqzfO%I|&I_)qKQc8BT&JdoK_Y@5L8NW$MwvQ=ebFh;`Q- z91~IkLiIex@sAamG{AX7-0+x30?s1de#|qja2jNY!h+k~JPS+9ZvaTapml;=US`O_ z60#3YyU+!}Fm!;7pS~Q9gqL*+1khbsg7brLiHo8A7*uuo(s(0-@%s>mP^1jSZgjNQ z8>)=}rZN;aL-Usba1_cxRa`;tUmbe6GcJM7pw<%a_B^bcq)ga(={-o;C2BeSR}0Z2 zfLFO3;7>__$_(-%OuO(&Boh+w?Vb2MN@szQc;WF_YD_N|m@+d^jvg8SiH1H9lIAwq zfq`F5O)s_4&3;5tPx_%lhvIA9!*{o>z<0L$LGFa7_zIXj1l|fea1;mg*c``NvW*1s zTaAAc_rp&d3ym}RNP8k3q0XtD3dMk6f-neM2$nlSs!%?+#3dkc1@L49a-xB?1h=*} zp0ngK5GRGM&lkJPUE3gWPSktU_hVkzc&Bn8oE6V5LRFt0TG7v z!TB)%MX}IB?EYo>8H0AF9%YX6QQYJB$sB6^iYrlnje@G;AQ~5fPbGoEe`+5 z5%5f03b*NQ5U{}WYb^+w$nY>^;8)8oklK$#GTHyk504*#6VCo8S{=xN^RFG4IuMV4 z7K?f;JX{D34&;9Qngp%9%+w(Z8jm_oesz8U^eNEKfGfECiT3cG7@n=&{bn&RB@Tc_ z;ia0mMMw?}?!&}?;xTXmJfytnP#=QNHziQoGq!5F4dUh3Ig9zA{PHyVd;(&0l5N4R0y!IJ;cI{^wfnSVBjDffSh=#&1iE4G)ELD z09#ulD_brnjv^!GU~a&i z{_JYFYu7>30e&3<@xN~ZJo7XS%$YOs^tVYK#M5A==GW@Qs1pM%1l5922X5YUuZ^{& zyl_0X0Tmzs5K*YFz4Y4DmLs6^Ae2Fa3`P_TzH`H32OSKSV9OIhxNv|${_OP)c+@Q+ zqt1dL6)PY4*Ynzl0Z=6dRM}X_OSZ796#LzpyzD4X!3!iW9>Ianx!=Qvgh)8`et#w6sVNaG%tYmNl8*T1?Ry1dzM1`!#DtycfbjCqbK0cZh*s@{3afRMc6cb!#egM z4a;Xd4S{$f_KoQn7{$UY{7=MTEk%!UZoZ5JwAl`dzSGQt;gRsH`arM(69JdH2T_h> zPLXkxC=GH3S|oGD`(Cm)te%$;f`m z5*$?yEN)mYvYwfhRgeM!v0PD$NO>R#tD}h!4!w~w181m*2eHqdT04l1t^T8xi!P@b0mfj9*mtJ7cP812Xf}Z({+I1{b2&!v>V|4`}I{=HZ5@bBOU_T1!pI~k7_wu z&wXfCU_(IYd|r3~8}Q)+2VOGRyX#&!&488#cy1m~T!0}1G#zx!Kp=sw6~y{RqBtxi zW0i=0C4WUt>8goV1}a}?ZF)&-17<)*!btIKpGhTbs-?U_QPFG}I^(=JB*^diZFdzO zV(!8AC1Ae~b#SFfCB51thHw>JAtt~TlR>W?K6UDkel`}4e*ynQe~=iS@HYbp=>p*% zY)8Ja;h&=)P7QG%!!W$SEWwF|*#`tWIYT}LLTdCQ4NL%RTwIFWA1p&66fz}ieEc$S z@bYQZUoJ5<+IZlG=VcUuo4K}0tzrS4_4LxYxtHf z6suX*!14WsVv#Gbks#%8>%%nXvO(e=o}~*}w~-X2m~mM(5EIw2LODpI3&9`a#^y*D z1D@3iSyTF)AR@u6aflbdhg)*7u5SrO4fzKF`;w)=Tk;Sh1O)g!#0W^qH2`qcm4KW8 zlN4|>o{?bGS+Whr1@jx^C0gg>;)qhe^4BNFbk*ACu$q!VDA zX|*!Pkb z-g?3MfDa#d4FDK(Ap4^eAP<1^|0XA#QFH_P8}wqho}OR-+KQ246pS9FF#Uy34CV#u zM#64a_~ck615Vgm;*|Y|GaiDQS!cxh;1HD{>0dtjoC63l5qMf!7$!$g>o<@$fy;!+ zF{{!*+rE8hqkQ<;ext;wG>y>+UCJc)q+oM-tQ~3FUP=Ij(#>A!pva!Ww2J1L&T7| zNIhV|1%kW`roAOStqb5 zRaK{~#f(&d8On3BwcdQ*))L%d-K+1xwrV z9H+iNrx4I%Qq2)}2_l(Y-jYuB;1BfiMuHrC6a_**#Rw9pj;9>}lSHuFLC6A6t=%so zW1HTOT8g0mnR26#cxq^yvpi^J$>!d&LiE?pA2>esQeyqJ2~cSW$VA=EOnh^~K?q$y z9{zwPK->UPjyd{ky8!l#_H4nwUgrHl;=+!E_LQf<$Oo4a7~%{#tr?9S>6-MK7>eH| z+M+~iB&rwzS%MM>@1U6m)Da#z;ej1#a`*#KYB`QnFl0mWHIw%bp1Sts8>#|Xmkn-R zhTsPPKV(018HNr}-VYxE$9|4P7=u7kAPeAzC&pYbI038!HUja+KA!br%m9KrT;r_0 zcImVyUiB@7pUY?jKFxi29Pf48a0t(`-#*AXq}{u91l-$*Zp=@t7q0D-jDgP$?xp}Q zCb!V^(NhVvz(x)8)tj)wnG?j&l7q)%^0Di|VGk)T@7br)-e!(zD*)?)Q1@oLC_d_m9r z1{f4ESb_C}l9M0>JR}+$LPC7ul8F>Y1v**5gt}GKvbgQ=!kUbr3ZE?kUNHHa|LELL~{mWdgGsjV_At+aP z?z0iELktI`E*)1K(>fabBG`)Ak634rc*TEXZf|Rczl{zMoc}NbVgMur9zRYi99du^ zfe*hOFTcRRp_$0>fmebjE;!?^4h2RSM6u!CE_@)$lmLkb@7W4`YV+$YGQh1-2#GN0 zCj+4`BvMh$42(FyZ@>9&?S6fcjZ+`l0gzF_10aBzI&1%rTMYma2RJwP>RU&SeTebz z!1nt@d%Y)r}8*Roz%$1U(p$I%1CBrmG z97yaN3@k`v-zU{iss@6$Ef3+gCBqcR<`x3}-KgAG2BXDs3Ctz-JUf1F&BNk%v%VPU=7=E7wPWKO$fj5;wFx7TNe{0BAT@ z3@5*IA?<3w0tA9Z{=TwDs@nS#d@w1Hazf)h(k!j9;x$SMJIIMc60F4iaFGw>DL24) z363E!?!|O9bhHH9bcq@8gz}1}<%Lr~e?FpsiF^S7nP-Cu5Oq~Oy#6Uy2SjB?Iqmp1 zfjW?mYOcS%JTfVDHHZ@cV1w?6D~VWYafbO@NQq);6lOimo)Jf2M{#HUs}0X28k0 z7a1A`72u0+yG;1_&C~s|EEZh5Pz`j!j^HpVeew!75ik{Yr5yfMeF_* z{^1^YmI(N~bTLbPor8n9R)8O#@aSv2-Dtg-W(T%@ba>*B>w-h1ER+HAF%L8`!6g*o&$*;IImF%|#T0zP(nnX_@0N?E(D^ z^Rh)#wY3rafQV_li4d3$QkksxrW^hhKo1K&DYW*E5&kEAs}FsbRIJtKuaR zkq9T^dXQTQAs`09c;yYJz^xqcovk{+>*|`*27H2dKt4h;bjq7S_p14Wsq<5>9X@HoFc+07Xik6__7)p) z`s1Zf;=j{D@G`g*Z^w;bMA(aT_Oj%H-F?g5OBfReTPN-KH`qDYCj>MvFzYcD42YdI z<0+;iOqnlJ^m2piFy9P;GuKE4P*noI>O~#utrQoGqM`vMR>gj`Am&pgQkHS}90V=P z3FWrsaNEO6jC=%0gJ!muq#XkZn>qwK|LeUW_B&121{27gryKwiJMdN=U}T2_{yirAO|zYgnSiNC z1;aQ%y906%Z0>c%4t>o?XjC#;l&xscmkCDTwz%8Ut35;j&nX2uA%X62Gl)H#?1qO8 zT*#F$%=zOANnY{64uqTra|FOvs{U{XwBL$10QVZYJBWW|fNcQuJm~YDhjr;vLIbU+ ztC?gC`X%ptn+eD#(=X>g=>Z{tVQU;$U|WLkJ?kv+g@h31`zkS?QVksZa2g>ujRg75 z0FVd>T|^BefSDSfvJL*M6n*ZRES1E2i2 z`49(ac6J~Bh<)(c_x5lM?B)L3t3j|t0EAt$#0fAZX4rkf?a}_LlvI2I`xRx?2fo!N z79Mg8WK4{AKX_)$A<`tWgc!lQ+Lf2eMac)QiDr_5U=(#C>u*T)jQLL(*dL)EheE)bEw-=syGxi;;KYK|fA;)A|Agw%hZndf^H1t`r?4l%xI)GN z&}L3@}Ot+>U?ASZJ-lu!HCb z7*W8OKY8MgSYWO_Df(1^f6YBeCIbkXfuN#Gt%j3YHO*IHTYwZMG+assE&0owG=M<^ zqbI&b9Gq)#^-93KfPj+`vC*;Zp*c_lGC2>CAJ~3*{j)ldBS(S}*hWC+0iORL;ewlq zZh-FohytMF<~P0P2YS;z;UH0u3TPVy@oZ=81r9XGg{O>wXU;qw0>l1$X44~~Z3X`B z(J_N7d{dU0bAWA_nW%$m19{Lq0V4DNg%^&Wf9x|u1-db_+DSkd^={HNDbp%_yi< zJbeiW(>Mswd%Yh?2xB0IvGH;%w%~iI|Li^M3*3N*AJF?d#^2g6RWtx_%tP^+lWIcf zMM(P=Z30{*1fKQ)1l$C}^hZgw5@2W>MnCXnl!7cb3@(iu1`gWZ3lQAXx2L#gPkp`p zG!V3>?CslZh_h+JW{Vrh{qs{^g|3iF#?{dkef?EvKP!7gyFv}hZ1#Y%C0mv-kX$cT zTxs=q0yGF~sbw!_710GAVP{{#Nc4=>Sx#^8s0aenMJb=t!Tez_>*HHtp;m2OaDmkp zbyzHfQn^A>0|?I^Hjid+9soJds;SXs+PuACi30OODe?OWr9RMf(Bj4~k(N8>Z|1h`?d)MnEc9n}|MR0(`2gy3ji3MB% zKc0`ce1{|o|%AY03ggic8;@M*bwlBYy1k(HHT=^5ji|60aqlhE7QJ#X$u=_ z)l1$y@+Hd=P>U%pbT-1Zh|nlPXpm9HBtcLJiQjF8H~l`l0CFj|-w&$@{*a=I;|9`R zAcuzyL1i)|8vsE25bsbYAMEj1p^X8t%2DmE3>Uv&jRUc4EPHt99Wb>I!x2zBaI^w% z6GJB=v3}z!=*SG5w1GU1cVKeBTSq|u{0bu=WYCI&k!`tInfQ3XMpY)^L@5l;^y~wv zIsmq^2Pps`Lk;G(EWmSf2^};c5MEvaUYuGyfIqC%g4PC(Gl#Tna zCXgdXybex}XFmAg1Db&Y1LEgDCPMF{w%KO7AE@(VC~7?N3DDpV_;>H>%+;BDS3ND- zMnDq=4#61w-!%bxqRSIHz!?6X%)@trc+)8og~5FN^{J_2_v;b2;Sta`*<+KrDLq21 zB}`xfq!2pymcieF^9O7IoT3l-FbBW`2Z(*#fq4S7O#HR_jkUD_s`>5Hv5r$9AaK+h zlG=Uz>%}wmB9#Dvag#NDaEURH46xFnY0U2JHqoJ3RdJPbmqs=8$16!nOimxw5o(Zv!xFu`ybN zmj{J=dn21j-x9~dv(|)k)}}u^tS$++!eubVhM~(w6c3J{v`78Pw24WI)T4=J@yU zF?kRNz@!W&Pd=tuX)x`CJ>C9BdYhHc%}{72!Vvw+6v7Os4MgQ2ZGixpj7%Up0tV3Q z%yooUJ91%^3v>sMc?|+b9|}7t1Kjc;>0wZplk%DH*UGoxcXtZ>tPhS!fVu(N68!$# z$ikW-1}56wLM3|qxHl9v9?gUf^?M;K|K3oz5Snm$*UqcP0{^k)p?)1U-|Yv$IQ9N% z8bFW9QXfbpg#PZBeQ~5!GBvFP^bII-1KV*nDuT;W08O@JElaC#mR8C%A(fZFtU=yD zxF?!8rfPGdof9oNHOo}3KvEkZGlo~@F_s#S*yY*a#W0Zlt8Ro_4Lrz+ciuU%B@XL) zOoGHLNCN-1YrJ~}g#w89PP_?PJa4b-o{`<};S>5cbXBKY#q zt~YiK?L7F`27sHNg-nCQ2E0W9ec}7|-#~;g4C{i$0U7|Fn}-aBIvD7)YP}0YdE2%D zpJx=pGXibe!we*W?(*eSK>Fg5gh;n zDU2adP3i6EG346oxTjQ9yAlExN25UBJT(MJNDvMxz^VxzV(zd8fLM%6LDz?AP}td} zu`yLrylT(`(qyc)m~)~9;-{K_e{BBXssHs)JNmf+4-@?QH33QtL^YV3 zpa*1FkuYN(@wb53=zhFv?^839O9h9SifXWEZ#Vx4gfTm8$^!&m>09I!NDrKO;f&^J zRQ~fKy>YI6zU<+tFb6L)4-i%8$PBdI`1DEg$kqumelm?qV59J_dIR7F!E%`ZXi}Im zwqXEbM!pV{Oq<5VL@x}vrwNs^W_o!MT%T1woxPnrE#v&sQEUseRRhinbA*(*zyzlQ zu3X`?m`3A=SY3SN8gmjj1!fZjFaCT8XA15S$!0h3@oO#aAzt&tA21K5*&0D$oi>h< zuv)hJH90TcfE7Oa{fyt zj)2X0@9A843-QypRh4{DJ?K0MHbGA3kqSEJS(+G8m`;-~Zr)qd&f6KQ1OX zU&lSSd<6Wv7vi3W?nQ5>D0(J%gt-ip5BaZu9R;FBX1FKHkiN$VlH7ph1^(>oZwvsB zowSH;B_VutlgZGU1(65S1^_(1XJg~O>7W?}Xd=L=mtOjB@BPJJym$D$!*}1K4(4B3 zi+L^t!jJ_{ml;%q8wNiO>pbXNpNzdx7)&WHNauHGZ-m1t4Dic)Gz>*DO_I;+Q;3-f z_VHcVV;M1|n7};q52$%j_8*X~E0D%6p;=`(Dh+R%0ay4A#7+lHY;P{l&s!trKm97K zzY4;K@6Dkwas}H1hzDN?g)l@v8|j8o8|)Y;ARI$65+HCGQ88m76dIN|SVM*-gl+`M z3*_7DXxAt=9DTh@HWi`(#O6CRgCH}DK=_MaoW-lgjhI7@p{bYY7RCfPXr)N_&5DJ# z$0yZ~Z2qg3m2Y6^C9xT_ftKi8gJTmS3^ElXOYDoU23vvcwDu9%Dtd~rBxfmoF~fHu z#IzU)vgkLfyk^0pFS_O(&OpM!$bz6=DPxVUDf9YAKE!rk)O}zFZoxl>Y)FtiSCtW% z)pQ7mM3$B&z%>tqL7G=^&{pc?!|c`i+a7gJW~+>V5(x6;1ZL-90{*L2Tf^nxCsK{sP~hNq`?>D z?ry$@w{`~+jDerhP?>}E=9~Zd=zq2W@W)3T08#Jp13BPOhPeyK#*xrD55b=~Lwp~0 z@C)`hX$7wiUH$I>z|GGDeixqRgxh}jdx{d8&l!o2G%QPVZY=r+OqQK`qmOv2wm|&3 zBgb=l?pqpa?$vo~gtIUh41ISk3gJDQ0^egXFmm$42&hsxm%$JLd&_lR3D+AJ#EtgG z0Lb(|(7;@C0etOPf+>VSdrZ5}fvCqsWEKJf4WHx(X)4*qyFyvB8$=Rzj<7IyrBZ=6 z&bti+V`5j>Mi_sPU&+ULsEFQgF5jOr8T8-(zw7_WOdzZR0l8~9=jT9`WU3K;0??;q zXsDer2C@SkRUzz(TToMoEWluW=@JQfG2RP2%vW{*^dx)+8;oRxMVR00s#j#d0mZ3hw@U&XtEEJVm7(S{5w;PIP#*l}=g8>gVg+$t`EdhyD zK%=o@H6C(R#Uw|mUsf5qVLeN$?Kh;gKnKu*d!2S+7pa7uS79$$r>*`i+fuA|i$@52 z0TEmn@Q(%8i}|nWnb27q5bZZGPmnjjgbZ4_p==A54Qa$%$4BY5Q161e(K!TS0z9GI zf~XhiDMG+4M99|hZ(A0^RvjSc%R>(%1mwvkwW>t^BAlVrY+Wa;jxNWGBp`R z#`6D!cK}1BYiKs9OsuG_a?bOgMRVk~Jm%yQ2`^i{DRpv4@_FbE&{enYCfbUR#d#YF{4VKcrbi=1A( zF{H$-dj^1iOaS~WO7`2Dg>c5Ruo4u=h3z|VnE&kQ>(49;!7z)VI>0>pmi^Ci+b9p8 zM!4fSaKIaT=4}K#ru-KRf-wNZkM{t8Q-K5)4KlySS}|P*SW}LbfL;(h+8b4ZkP%Kr zL~vi$dQTM5Qg8B7F6Nf?{ z^}75!veFM$)D_I*U}~gt%s7x!>p#_y$CdSUJO}K3$x|Q%e^`nkYhh~=0`e{O06M^h z2^{sX4lghndZPbzD^Tai2fN6akT0a;&kFw-kF^8)?l@s?Y3cS--zTPMVZ#RmeS^rj zAC&fG{4`Tiy&;LsNtUHbW5{LDB4^K9H^?AMkxt7EB1ts5;R<*T$1X}dvgicl3`j0G z!;z4Q2L({YW?qB87dGNTrmEx&dUYXfu`f+3Q7Q$Anx$T5zO#xPu>hxCGAQ#KsSX1& z%ypJ&kK10f6MO8HhQ72?5^U~q`7f@H91pnw({RLj(t}{KL96W>FqdHV1ox6^kioLV zB_ZfwXohcdkF!u+3g~>Vm=27AxlS&`iEwD* zUxz-_93IF?Xb@A}Ks#Kn+jTGvob__VKD+w)cFf(k!98%%4e$eG!JNna4;!$KfEQ;j zUPKwvKA!<;>)q$lzexMc%b#(-;Z%rO@Ln|dF&x2c!&k2w3G$7RAW^Vsl!kg{ivjp4 zEAa1P9>fPg>R_xAMLGb;0_&{24BC=1zpo8hv9!yVMbpNYU7FLQ>@MzO$Z%PD6DizZ5 zx&1a{9yDvDr3R*&XozcKT$XZQh;mGRMpR5*(WxvMv9dWd8?92<=ffc4w3_lO3Fj|x z*5md$26p93d~4m>{3GiF`RT7Fe#PuRh93au5DZNz4D`=jj3F5=>YNh&n|lC|D~#>ZydacZNG#$>j3!* zqu<^oT0RCb6Alhi9B4JcXhAd@#X|8H6$s5#RDocj>YbEWvkJ1BG9(}7Hs1OMGIa)Y z9_@@dFIxzrJMqg|!v%oh zA^A(OKxs@d*YxYCkW=hGtvQq1exExhaD@N01fz% zgP=MP{0}xG+;MZlZOqNj*^Kw%i(Um{5n7(1xCPC06>{~JGuXMcgx<^9S(s}^;`VlZBX+cd0?kN zFav(@flYq~fA9MQ2sI4W;OCTuPbJ{cK0El`vxXyDJ$Mw{m7sp3rC1pF1_5y2PQ(Pl z31R@a8IOR80r2S=Fxw&UjBm-*LE8#!c!hLXcfV1oN;LckLt)EC=Z7CoLIyLBPT*sS zF#Jb02;Mz#;JpJ=`xBY?xB}ic(qtpuV&`#wUiubH07MW%T`eiT6vWjt@!*V^=%O(?HBD$;rf@-@?naZ6i^be&tjEV zWvj#21Wk3Ol)yCE-aCKq)TwL#;is;G1`n)&1EL%NY@Id1!yyqB*th=opopOmBwx&r z#r4lpvL;Y?G)$6&cHxi5KIH;z%x~z0V_gye(8fRWfGjR9`VeTXZhdwbG$=z89J3E7 zeGvfK6bMnE4SZlc`uaNi8Z8~rHswLo!G$~+a3D7RL8lBmi03OSPi^%KJ0< z3nHU4x(1RZ$uQtqj<%4A1v!hc$7Q~?OwX=q4GVgQ{Jh?BSpZQXzeWhR*TiQFHdb3_ zcLjY6K+Sp#v^~O?e%1lhPJkxsb}}Vf!@3MN0v9;aGP$}EdfzQ*-lQhXTj3Qj62WK( z_B@0r$WLqV(}>{YBXnja8j&0TC4zbQTYxG^5W51ZhdLk1S5x|Q#`3F5bjyAj357^5 zePJ+#O@h>B3=~`{#BV~F|IF3HJS-re!k}AOSkB3AGBSd6CkH?r^L(VsMf|T}pFk12 zGPEs}{&jP>6W7tr!B0!CgP(R^pkG1=bNmBr!1gdB@X@!y0sk2IHxnvBRC@UwlU)x-!mv`b-t`(%Z~1bAUH41gE5$Y2}=FMK}$dL9fXKo~)60-T?O ztEeTT(a&;V23!PaN>iHvFU?5=WAk5xes>=k`r)U0;i!Vv8PFmD_iUs$HlS7o4Orus zXn4_k=>qAI53V;MgBi6?19!#QcSRy0Ud@-hJQF49ASNi{>QXdTQ?Pw_j~tS(90bV^ zd$}g?EENtf0J#)!&n8Jb_;rPE$J3P2xVo@i{7UcIv4fvq`@28;@>lCzc-8pfmXKl1 zd;~!1qWe7~YeCvT3I_v8Y`t+d2|lm@)#2HXr4gJ35I&e4oAqX3mV^ibjRXOVVE`N_ z2Z96ypqGUl7yu&hl#Ouw2@v$~Kvcq+V+1bXPMrR19z44^jz!sqKtsO1J*I*&{A;YQ zhu0!#_0q&0rYsQwD+LEZn*cEqVwZ(D1~VShvkJ9}gTZc_@uj$GN}AhM205pZ-%?0d zJrZ95Fwxzwu;%~NbQonkC96;sT2{sTa`5w)c*+JIn3HE2EXYQEHfXH}u>P_$15ts> z0c3`autY{+nt>^WPBDxsJ^`*msPg!oZN+f08}5m2xTk5Lw;Ta!slxzBjiC|Ehfugm zOZp*gzbni^__clF+o!)_Go^|lxl5))m6mb^w!atI3@s{x3oyTr*$ZW$=5no39j3wG z9(xku8z29=fo@!1No!!GRlZd#j(VK}%TB(xfvDM?bFW)RBK0cQEe(ukV2J{;0Wivf zF%U!;{?Vgvz6~45k9h#J6&R;LiD0k?JD}~_iDc+~{>y#NcepY5>P*PWze-04JCSxG z4=^G@wsOE{{x34XF#ow1&TE0cd4vhDjhs>~GEqMw|M8Ik(0m}B#|;4OOJ}!DfQZ9~ z`tR`Jy9R-eFa$~mxIZRA7>8vxkPVQ4bPCj{+R7C9CdscEB@xmCwR=kGFujH~`0HQ6 z_?P16gME6~lmFVD*=I|BH18_tlpBVf@-J3}~}VbA~e9zzS@Pg?+gxx1OpPXfMp`OIqZH zppL+&qaO@z91RQA+ZM5U+*%xTK|h(HIB@g+k1wFC)bI=wAo=`EEoUyVW#SXt_k zVO3rKsA6g{KMxMNjjF~+ijBiYLV@ak0o;1J)4Kzzf$ea}AYGMEdo8#n^L3m3kh1Buq(hz8*VXswv{ z0f237;@ALxnOfB@*V1Y8){Axnv{Lk(#Q_2Vr`!T}`0yie!BHgY{$rjB0{~pJ9oQ~3 zwP?~ z%NqVrgATG+@CReaGSz~8ya!q!AQUk6e0hA36J*<@eZ?>lrjb{`BEciga051*ld-Mx zq(?yv5im!ZLEjXkCDjEOQ(|2GW|B`7ii8$1dhIL5QBRB$fp>}Wu=f6_;tkwga zVLc=8zwuwXh80L^BIP$7+!3nP0E75X<~OpIB7ML-<>3mrXHspz_LQ585&)0bld~V4 zo&*$kIbPGa}I?_Sb{MCk^^~UW)MIi zDd7FeggIxS_@;u{xDP9^^%YW*UjqiX&dtF1!TAq<;AZ@?C(^{23Z^7sv_Q}e!6`MQ z=VcBlx!hToK6?=afz$STn;i4>!lC@Rifc$O434WDv{mX`2ZfJDH2h zkwGJ%5RmY}t&w79=Q9fGxWq4Y{Ik{9=09~BK^b#{eV6ui7`i^h;IaqAps)Nz0aM_b zy(oN<{lWn23;SicNbkUf>okiRkuCRHN5xZ>pm2N6xFI(UoS9J ziVVQde$B>CPv>_4tT+)&6~0G~d*V+*2NOb3y%;V5e~DPsKQsegj~3v-0-x}Z8Cii( za0ZN|`1-7FRuH}t0FnP(r@$R4c+kYhJlYI>)qKLON=i=5fNjOLMvj0sx`ibeJctd1 zuJE%6CxbEo8|ObwbpW*n30XYmCCrGOd=EL`Fy{HoZmFYv{f%qjx)}s`1Yyv0!Qt`t z+aJ7d0C?%g0KlVE0$!YnV*rE8jb}aXzDoPsxf9QTdWL;hfq?f&0ONy(@a~;Rg#K1H z!0kKmnLjlACAblv6hHF`@SATR&F}sZYvo%!{=gv+kIA+T0bm=xkG%TUf!7oPgXPyI zz(ph}5|Hd~C>1PG8lCr}U`d68h`_hH5Yi*57ywf)zy|_SQiu=jqKrDlKxs74`R{4( z9XVz;kW*j&FoYlA0O%%PWdV{08J-AD=o2oKMr$y2F#H8|GSa;aht9aDAh>^a*lW_U z0Dmef*j8Y>)r~I>GSPrHz(!ermlYBnMMcZ@dzm%p;n#4@4Zig%vt;^^iDi$zPL6;G zM8y(p)XJhC-!fItEx>|HNngPM(CXrF3oOeJSI8Kg-JnkJMpZf%yvR^{hah?q8VUwn z!_0X5i!6{(<~Vl#Vx0w0!bVbCn-**l%V6c;%qRYXFRI#g5#D8k4tL{p82@O-L*!bv zo`EwVBp<|woGpbAiqDdC(je{R7rcNs6+D%!26idnq2Pzxx&>d4rGSC;*g}FN)1Yr9 zL@*EEbt8!VsdfXzKgGRAyuOeE5&zLli@Ytt7Jh(f)qO1G3>DDu(hSr_5yi5Av=sfj znHM54_&M~!%|%K-p8&fX!oJ$c%{G@)k{|RevW!sMmt(n`9KLw9v)fl-fE_kr{5~T- z0I4XP^D+&lQGnAu$6cvak{==--`5zVLVH1o)YF5MzNi0f0aH z5rehc0{YqOE;YArE*o#2=S{)Ble}els8hNDPCYXCvmZ7A9uokv8Oc{*0^kPB>sWvh zi4|?ZQo>;NvuVE<;rG2!I&^!lw_}O~#=^@LSb>p#_RACNG4#5z@g-VQwLV(108#9<}gvFGGC3f&q9iCE}@ z8+6pO$3K3xEbSlT^3O^JeVV!Xp&{;Up9(|HPHpi4DseKAlF;-Nlko<1=`h? z3tWN~`x3&hG!quHK@Mp9aIwCgQ(%=Csv}?;@P{2({<&(^R^GMP3K!~-Do>mNd(}Tl z*=LH$y53Zza=6EFEb5aq$kQjlz=0$Nz;`1fh=#yJ;W4e+Y3jCCbcta?7orgCG=#w5 z9sppSBOsfQV7Ja92EXbyV2mo>2JAst(!u}%TLTZGDs<;RhTm*zac)qy2}z^b`t&U*|UH8r=On!3mgjp6Dx2u|6SOQ ze9;CR$p9~eFqm(?dt{_-Uoi=QP5{$hGdK6*;Ymfz+70l-;|Hh#e8e4?UXVmD=CNY| z|7-`g2b>^qCDEA)XSY3#^hSHIG=a_1L&fwFO(Bn7*a%@<% zQY7q^ZIlE80&&X2h*2qLz2Z&U<*X(`NuljWO8{j+n!l!2WJ$RW0pj2$g`Hl=i(X%F z8LSP-gknrlA56SrLP8dwV6{AI0nmVsX}N#b*0R3lVzfgdLOo_c&41ORFp;-Gn9bAa zU>>0!x-2FH5A~R610IQMF?&avy?Dlxp*<9E_0VI+!X%|IVV#XV!M7seUkrp>4}b|D z94A1V{vKljJoHQ9pV{y9IV$bGOdu(0V1RyLLP87z@Nb|-HE_73*CGn1>eqR@PLTs? zR1y|q0ij`;n^Vm>8;d$xy|+b2P{9gs-s=_xzh?j4Ctcq z&wlW=tG*p$0DSiI&k=~4H~_{v==l0~A?g0uUJJ4*5#SlFz@K3PJbALw0FcFSEdv95 zVc%o87Pn1yk^{l_lOxA14GZMQVeY_p4^Q2_>nzAI8DdF#RDVuL!0mE){Ci83mJa%dTEikd?<8NEE1u zK%HBH0yQxPrUL(w%F9M z1rj6c(NY`@Z-|D(AP83+rA;{Q>Rt?)45$li%@h@K5_ADfhFU--94NnlLm{@gtgLTU zMQDZ5&XDa391O+xuJMP;kWdjKe_S>lL_DsNiGotsycDF4v|A<}RJ#n|9^*5RTZ*2+050xN?6o%kEGfnywbqzGsU$G2O zO~5zneEzGI2aexpvbA)=APLaEDy#G;a7AMw@FZDZgRVK5fz|A*1guW)ETU^e!yuo$ zB%PPQTy*Elb!*Y>7HBqv@vlME=X?!s4+}6~0svn*;`5(h0ZD=U7_N?sU_mtgU3__F zCaS$0A^`FT$nlRTXYi*HkmDa{5c~DcUC$B#pT!dV*95>2i66pXqAJXI5d7Wu5+P9> z0&aj-2?BXo3-iTAe#8&sKssRr!GQhhs}_ZI{H53a!j6B3B?ELC_!z9fv;+Su&wwW_ z3AvXT~dURzp5=W1QL9pcLM=}_10ei6m zQL_g{uf#JTnGf>8`bCLhe>8_Q1shU=07kW@NaK{NYs?6|``)!vf3#!W<;>3Tt`9To z*_$zkJq%{dC%k^M#4!}1pUx4XcVOZjRPFOVH`}9+deIKh4o#UYGzbuLSbjQiv zmoE=m;fMXSBi@qFd+53}^y_3pCL-}K4=#rRQ1)OX!Jsx+h3ZQfA?=dbXdRm4Ck+6D z7cQM%ROg10VHo~sUvf(4tHr!goma z00OBq)Z$w8qDw~QGcLa>YFOm1)4PPjV)V<6we$u9@v$32zFl7*0v-5MED8R&at-6T z>dFKD@8%KyYD^a1a7UT7wiWJTk$hKmfA`y-sI9;9rIQw;I|KyrV1=zBb!*p63p%Ud%}epF2B+ zg?N~~*Fvm1Xz#$(*9kzAmPM}_=s_1K1Pn?T8S9|V)3De#;Y$w>KD>ohFk!%Qv=>kA{`OX9?xkQ7W(4*`!2cc0AoKG-!Y66kP8ZmL%@1dPrxpISj(8r{ zNE`}N2S;$CD~|f8(G?#7QxpZ}6&(pr#+5GKm?aDpQ=Ed& zE!Dgl2>?ry5++g*kSG&bG<8_4l#iJa_>caKuD11wVQ;^j80PDLGx0Z~K^~|sL=qUJ z9hfqZ#0Sm3vt#R)C5;r+u?NFsf2}ujmSFcOhChWLpbhC`z14exPoG5CJ?h@))Qf`ug#D%Y!i$jK$;E*ZVjn z2vH*zw$?1A&-SCt@YAeY$_Q+1O$D&n-=_VQDmIr)F&N@BA&?co1x=1*iwh)#zeqFY zB~7L`bO0;nDu|(F?qCK2wq4AHmW!`TAGh5AjnDuB3Hh-b7-Q`}0U3j+p*BNEO_}^@ zZHBe&@k3z)p&Nv>+3NHvyI@2EBN_F?)3)GSNjdbbEg1-jLQGGC763ksR4|zSf(}|; zgjz#ZD1>f~CP4GSVgBnO{PhG5MCt6R5(o!+>N9w;3OyigjDnft`Z}jfe6F;%wlzc| zWLn49RQDbC)T4|lrP~gOn=?azoJ*M{#p~r2Sh*wAzVTi z$k9vEKieX#P=t#>zBl3`^j#Km`o>P3`F8QtXS?vTf;~JNA{6cvKTM3Y75Lk)H@y-r z!GT1}?^9zCez&z7oy|yCfH46cgAPzukc|ic&0@2`3#%1^d}zg?xG)@f;l%^5Aq)TR z6h=P-K+wQifv5g=d<3*!r20K(wn`7k2f~nY$e>4Rl+PPQVj29kZyEn+R7$x%bd*|A z{(2NKsWgX(BLRc!Rhbk$Lk~lq)G5o0w9dQrgiznFUSOw=NMC-RY@a% za}fZzrli!Yd>x=oj8G{Tz9?jk6BezJ&Z;!2iX@k!nl0t`!p;;=ie*pwc?-U5_*rb6O1x*U139!`vnnlKfeq@_}m@lKlp%g0Q`VD7(+khz|j3h3AC1ANTDxk z{oNH#fp6%zw@cuMSN384+j*7hXZ!#h?hH3T0U&RHiUW**FytI;odAh^3HWm(T!_SX z05sj+9+(PS+Wf-GsBM*vvJnY|aC7$GeEh{1tq;!SFLyBm0{-5MGNGp=g|Rar>c{Yn zegG5*;!tbwH``OkV$5cC{v|*#+J4mzsFJ{NtS0|kA^=jqKtK%mCtb9+Wj5ziqB$Uo znQjVHZ`453&IE*&72%~K28otnmZwWxi`#v?ELk0hCBdA!_T^8hY&IC{*Def}7a;fN z6F+qE%eqGcjv??05&JL>%b9P}ik(p{F2**DP z{#^ZHY8TsLscZ(`b=t2Xco_#Ioks;DT)D0s)Y99%k`alNlo*pf!yc zI2t?x1u65ZhdHDyCEuC^&xiu_AT0s2$}n}PglDB5`SLEXux-gmN)}IOMk2j(Tkk8*B1H4l# zu)xq1e_VQv0>KcdT6Ft0S>UgI`bz|&CKS*Y{(ufJN{tRq5Ys{5w~4LZNLv>IY69eW z!KQ0Sd{{4F9I#D*FOdT|3egt~dm;>7`D+ zFHt{|&w=gDp4-cB)67OiI97Yf1<({iduLLKSKdexXDVLq z3GhSLyVnDgd~Mg~Opw7y3B4L=p&wuO6rr z2|=HhRC(F#*W5Eo2E@KJZq|)30x+bYdI&|r>t-Sz|9Mx z+1!nAXA(NVXb<-3&nLj&#rU_W4{{R38axcIT5O|eS=0C@_-mVF*rLUu(g@P|mf1jF zat3(n@L&AJfB7$Wodw>%--R$!48}(ws(p{P5}P$wOn5tkZX9)JJhgz{cm@On`VWc% zAdNzO170un!Y9;D{)2o*)RQFBT=2H72CJ_a4;=agkzAY^Jub*2HtNdv`x0({QWWBj z$eLl_iBmWM9=!HUhu-Y0jlj>4Id7G*ose{vzm`{UV+X`gz*RgnR-ebBpjZ!Cq4!j zVJk5?jq@M4pw&}eQeV`-pRu15vSekfEo4~I0T@HhOCc=8wjo#Kxy6^`KrQVFfWWlE zPQQ?wjbyT=msCCcFRT1NWcKmCR}~040xFuONGy}YMfQ&@XFL1WOu~cihx!OH>o@Q$ zEk`k+k#itVE}Q^?f3Dv_y=PCzL}*4ZV6!K}Xer2t9T+m0Lw*5#945JV1PuG{o!A|G z>sImxczwGLMqyYFBMJodtJAy!!VG6p*Hm==BT!d#0z?8<#UW7VKSs2R1;z+iHPj>e z*$*27asS)PC(eMX{-6|^I+#ws0!C3Tob${Z(jZA6-fpUv=<$5KG#?3g=W0NWf=3j8 z@I2t}2;Fb5Fa*IFV3vVk00aWYy_b%ER&InG7{k8jhTQ*VM?o6_ukPF#_F$g?^*W_6 zJO%n(cuFKll!qFzz*`+}PgMe5h^D|ZT!EE{kA+n%Ftp3Hy#8%q|7}4f+zV8}9063+q! z^D@7Q6&droJ7(6GQ{Px+eSU`1ALqbIZ^?u~QaLzFLZG8BIv}CWmuhTx(J{aDR<`*o z%)$6!{3*slzfs}`{s&=j;Rc+Bz9Ra4^k5E5=>QlAND_qgOW<2x{`{SdNrR;&c)$^W zZPqIGtN#}Vz?I8CJg5@jzG6k=de=32N&5tMz-93uTM6*vyIbhx*tEqEC?X_fn-bVK z-O<6J>mbW~L(-x$Okv<&4|^?{)h$sUjy_1cFr9DM43}sH#@!EvNPt0!U|u@((gCo* zFNgz90azzfBho5vz`(hOIru&74VWf3j)c$a>9hqgk7?q2^r|>vR)J^?gbok@Xc^4$ zq8YAOgmnCY3*gZ-11|7`%!M49EASjAz+9ezf5g8`14wx}|HGmQcxR4L2%7rjRy zAILpD?c@!Rq4-ac2!85BY{86!A*9~CS#MH~&2aeNN~T{#Ke>J^z$E-Bg{gBeLR|&7 zVwyvmvo%;wU}xf!0A^`Og$px@eXSv58A#1>j*1S6>y?z8kR>31O};{UgelS$Nh_n; zV0~z#I^^Of8k_s`o3EWYGx+P@c5%_A3$E9JSJNZT1MF=$9Da|H=^ygsH$sYo%txeQ zDFskfni%i?${YllJ~-=*T-d&yz$Zxz-$|g@r7NHTkVU{fmqXgjg;#WkAD97gASCU} zMHf(4j^cD3{)CB||6GQ|R4o|m3b+AYoU8!=k!sB++z7c7TM)X#3BI0jsF88NJK#Z| z^nfDOia}5cU|gnFaNVt>%2|%Le~SnhT;pyEiMmx-lvSKZ!hJaUvklmY2cRQ$R;@{o zGb%kG_!G|fkBBeO6}rdZ++J0&jE+7hOvh zK=Tho@iYHQ00Y|?gugygpqINpR0POa>4X2{J}G=s6AuSHDlEKa3l+|#F{iskc!Z?6 zIKi10j(4!=Zb-^L?!Vr5W9)n2m+F^E_pAi0GTA=@{`P1Be3eGH1KNMJ1!w+`EZ-F1 z#~1d3CSMtqt==s`x}7o{%=0KYp6@Ie+NX`v$$ zFjnBvQFVUs>wgAc)-yKQY*orm%ag}8kpv+CKDF)yX26}&LPG-c=}xEOe=7V#Kl+Ju z1)Q3iQd>iur28C)#V{E0z(BgTI03FKAwyJ(>F%1y3TjT5z~&0)#2`1TIn2Mshg7W< z?oh8tV_zdBGL{TdL~|w4!5bZvYS8pb34s&5UR$m54cd0bw z0`mZYZErILUn;*af3W`27W4BVT4mK(0Kzs;Kgv+}*ye(I3?(!AY?g{Q|A^=uG z^}^(Xn@y3>=k8z@w^b7Wn+h>3j!C!zcnj}`{%rVbEp}JyIsb$b`{6bIcIUB8Bs2itrRosjEdA2^P2JR<&+D(Z-Efz zBm03%9U&hr9REIw29Y8F{=+xGREdP`_hktVUvuw*HPFyGL<^=Nu-{xwihwz|zON}R zvrSnXY+MFvYL?-7Scf8LtAW7ZufT*>c*0#M#z!DFZnd|2~-x=bj=dVw-@|zGP%;855n9RkB!na7 zC3-*hKmYt`9|UENqe)nYzZm}@ka-kNkm3p)O6ZaXq~qU~0U85mOLfrc7)UD|I*|l` z{Km?IE5Fn7JFE~8v-IwDd(P(0<~HwYd6H3BKi&D$dpiw)_nt{Su+D%_WrjE?p*!jC z1Pg+{FIs`=2ysi75HP|ytcY&b77RP2mtcKw)^!BP*B(Y-^TR^93V-KzN!IY`?k*ZinyVf}*h4`%9nO2#8;PfM-A?Azb)i`v;N+ zcIopuL0;JY@n?&~WMFsYoOgLxNeG$(|DWMNIAtUZ$HS?o2EW3jXTV8(coOwVQoca? zH=G9rJX~3rfp$a~D8pGb>$U4uU@6Z5pX=8L?}#X=vx(!?CYNJ9{;kO%1xCO9FWzCPaZ5zsB>|0oi{ z)-*@T!2%+<6afFQUr?`U+`k~$g7*dI?<(vxhi!a=0F?YYzlcSS>%`jqbP(&X@$FgzXSk}ClO2xf2AYf?1N(HZ7g@)(i84#cW(Vzj=BuT(Ua z%!7>;ap2+X7ukQ7wlub?DXCRWOELnqMm8n!QI0t`ZdNq+A3O&R`1`;9H4^S61Jnd~ zINE``Mig@2#gqfw0=e}5aQfH6Kbqo3WOp0!O^<*`wwIM}bj5|z#c#M3t23@k4r9>!;`(}kpQd%416ht`)=_`?B4bY$xh9&+04@p-XLn%tO8!zs`BmFSqJp-_ zKvfW+^fo*W=9}_K{4AP7e~27zez`dD6~f_>0pkzQ95o;Z5eTjMR1x^bzrGbtfYIfzDbk>wg}Rmh zF_uj()AR=ftf|5D*I@_9GG@AH1dRMYWgO^$m+FglK`*$C10dcQ17kC;irsfZmh>m$ zH^aTqJV*Nnw_d+KD)B<}_&5W8&rE@$6&!qaTUzhY=97;7@`Q zu6?Z5k89ViEnd5JE#3@X8@z88xCnoL$|`}6fBO(vG7BCL1|&{^;D9*+-kUnNMWpY{ zsAPcRe?wvpBixh6Cg8Cy-$W72Qy2lC(GBn(#=m>)g}WClFeHE)15+9Tdf{wUk2D1J zf`kS}k+-sggd|#_XmxQ5j4VK@Uj}ps#2fJ-&CMxBvNh~*6?PQq9N6p~Skocj&y+DX zku>UR*lJ)6tc;3HwW@E-#sR*920aPlHQhBF}4FVe#dLH?&&IgEir!xw4)&GW*R%W3%}1j1h?LGf5&D+Yfa z&%6x_+Sv6L@{4GJ(-lzr<(R_r-FC2Ixf}|L)o)5-zNV&BZ0Va{$X)V5;yS~Ryhp(w z8qOCgGd{RbF!tefO$0vWJLq3ghGF`M7x+9wcl}EhHdC#3Im)v&n^q?;pN-Ay`$G<$ z#=jT=sf1P@!sj=b3Y{fl{Ua*}aX(VAB=dm<_zw@n;h$F={&m!1z7c&O)IsBUqnseo z)Oy7?KxW}%GHr_$eZ6B4mak6)u!>sz4JpAN{=7+CxvxsWB9%`JhS9dGd?O@R7nRT-ZS!2>58Jd}uFb^_D= zW*JNz0x|7z`vnG`3;-P8pI}hI&xAm!pHEx$TwD7JATK>|k>XM6_Wk>R%1V(QfWPAl zC&34tAc+G$I_CipEb!d?JOEId=NT)Z!)7A{1P8L~$H#uW83?#3sQ~5wU=-F)LExJw zcD@-)u(W_rr3sJ+Y9FL!2GIn#GLiug_B*1I7r-`;fguMNU^7B^LfVB^?FKk zwHp7ufAsU8LkNuu;OUqEdwUIV07QuXM(hfnwikpjc}uKs1Os*{29>ZU%Nr$soD2^$ z2C(6RgfD@A+u57hfF5DW1nC4J-l52YOz@>kk#;ZE_ieWU4}}33Rym;F5DtE-5a}42 ztm&B)?Db4e_NZBjtneh@kHl0y*IC(_QF_;a*l}R(80U0v$rb#$&JT+3N08Ky`#1tP23t^wk_v(br-E1Xjrl za%11Vh4o0KnFt@1Bp_q}7;EzN^Vj!X7yR+JxbeCNKxD!E<~Md7TY}{vEaM-P(B6Lq zf$PNtyA7$Y$sJYQB`Hl?!wk&7p#?!8CuHjY-+zD0j`w%$c>jGQJu~UAg~+!TE3Phn zTzxhF`5?%5mrN{So0~lzdn4A_H^IFr=fLw{RRTZyJ_vwiRj~n35BXhcODE`;1gECAPoUu-x>hAL!Ix2bi-f201!vN{<@VxesBjCMJI2N48c?@ zQ1}9QbUU|Xe$lj7gl~l3yE!UWXr8O^^4c0jn!fL)x1u^N%9X z5DOWH`d5J8U%SE&Cn)UlVUR*V#$hep1v|%O0^Oyd6og7k96mN|>cjj8q|Vq7dkRCW zjg#38KV*{DWdLIb``}b9htI|>5O(0<;mTYmhe0-~>04AmlDm3B8d4F)96hX%)WR6Y zI~wKGR(a40XDa+qn7P9LXF2`Vi|IuS7KDDpFrMrq&A=>3J|; z#6E%>{)7cacMTf>hlzkO7!m^wgJU93ste*yDpNA5lB=6iOGq&r^ZwVwaYUgqpXq`I!gxR1o(&Z57Hl*M!J{=CX@$&xrcy9|gUG*C6Qo_}) zIQnH7&Mld)86cKcU5i@M@lTSOCEt2fc^E7LV7#v*;Gs+i_|kzFq=qH{J`qVUUV}9O zvJ_Jpr&;mkxQah8`aQ24tVd5jzL+E5pn&fVUgq!IzB7NDPxt5N=b>IX`kfQt(QoG= z%pNV3Lv#A02rz>2zlIL*#1uN=MwuBQQh1EtIN8d8vP7{ ztCfe4T0xYF-~sSgEJmMEju8!1+(s-;&6+_H4bommMmVAYkqymu7>D5#6x*A9{&NUS zSmZS5VeE4?h);yAArtf~Vw$hasS3%WgNh6y(`!dUYe^m`W=3-c?C;CJS&J;d7k^G8 z2Z@c81K8`SFHkSh!(H*iEHRKoh~g1A^L@ba?_&`rDnr6zY~70+Kte#coiZ4#zYSo7 z7g_6)NZq$j#T1A{{22b?r+S8VDf7w|ayP$ z8tGM>;*yVDS8`@Tn4vFk90YA+1D|T$IRnbXEcTk{=Y?2MIc8X8{7}IP8+V6Sld}#J zOH*JVzUFXl>vuV3bDdc)c9nw(mLC`m!D245BOot&9~G(Kg^TYWN+B>QW>OMNWFhbb z7*PoCysR*UaHgvflh))=#*z$CDZNVxXvc95LR3@~W12<{fLk>HvJU<1==<+)UAAKf z5%B%3J9cQIlMfCMNC4a$B(N6Upmp(fo1TLJp7;*9OG97DN2<~eTosd{(2qp$p|}Eq z0y#h<2+?o+-6s@?=EB zg+mMWgmfO;2AqwhU=_(a5C4zvM7#CY<4VJyw0U^Xc zoB;DrUb}tf(HCC~NQ}|M<&1^lG*!;!vAR-GQoQ*g;LlCwYWom&G4G(;QkU>|aLVcy|AEx36=RV{dK3Kz z5%_18vbr?5RMTIMpx05T$;b|G;j#Kk_y_KTpO#I5KKK>V63okAehMJS2~amg;GjQ| z!T65%8cXHjfINNYjqkp0=3*-$05AznbyRK?22!M#DuP1`nB^htOZ-L}_RjxdAs<|l z22%{eA^^VbbeU9&zA=q}_@=F;qfRckItgT#!whT{48@iQrME2J|NN%Do_Y8MUg^`2 z!Z~HDLjbox1*0<{GOfT;Xm29}62cd|fA_Y8r!BD@G45^S2QM#aDM|VJ)&v-*zYPEU z4)$NZI+TS0LI{0`eQ+Xy$pW8DYQTrBe^EX9e(b^40CMOP4}upcUZC_F)XsY!b06{U z?)=@mb9eEW$D6tNuLXco@*VwCDGmHj_TSkBE3ib+JOYLjUs>jUZlu5r&%f-)GDLmkfZrse*Ao@HusYK%#)%sGc;idNG;Mv7TRqA1?n8FEqrp zYy4~D88D%rV-bLNYDO|LN($JTB|I-@DjEv-N>2O97w1GB0Ky~ zQ(&brFkdt3IWU)t5>G>5!LbQC1J>k6V^mBGGP{FkG^_F-t-7WaeGCS4FCmL*SUl9O z6JT?A&f{x<_u+TQ)7laIvfLoW5wIAJe?G&yKRmbtyFH{RgLWFAKwT3CU( zx233GE=rkGp~qfxzIuO~-xOnBq8XvLx(Jd2K-3~^U}NH ztDYFo3ekQ4dyE2TuE6-A%8pq3d(~7hw%^6CknOE(FcFBg?nFw3aU}jt0N|Kz<=TH&#w+H*DDon{_2G%9z~-VHx?~s}U|_V^5AD59 zM5s_YOtZIR2OHs4YjTLlBx0q(6$K$EdV?Q$N9F2`S<9vYFz$tp8f1U%GnrAur0k?#gsxey@5k=_YPyU}g*;?_=7E z|LW|k4+wx=5syG?a4&_>r<`)iomUV@B*g1UalA;189vpcjC(~#4>9)-!3XSp!!$T~ zDh9-1Z@`|q z^9%IQ3&y{Iz>hK~@QsLrem&&@#ssJ|)QTeZ4JZpW!cduF4Ht-%m0W`<0_;}i&WcQ+ zMho00pKL8yBb3qr`PX$z27r9aW8bD^T}#Aobhs(X%2K}#OO_-aI0CN{EEcD}pnKCw zTtbFam9QX~kII+_cnl0ME0Hh)K7l3p-6wG43k0MB2GZt-9RjU-bnd~A?N{+R&w%?+ zi}WSY@w<7>e8jxFU*4Vj5|3HD%<=K{*CibA(LWt8^1uHC05dhTk#E)zc$6eCOW~e; za?{ydZiXYE5l|Vk{Om+4vCp=}HM<=tw&qqlLRvG$bP`x|#_aFEd2ZdcGv9l0w1N}bkg?y$ot#!5iXhZN)#M9v80NKo?+n5Rp#qb5=uBxb~# z%*qA(S%ic9H+Gp)K6=*s^rx+^_73c?x&(mf0G$dlStQ6jT`$2dhf5f^upP-D_fg3l z_-!X}34MGc3&WBIMp-Zhz);}~{MjpTTQDJ^f1v{)qrQ3o8&m3!m4Wp74;>`ios3E`HKpG&NW7vieDON!u^>7SQmD(DOX zkq3C_zzZG$U!@sNsnAIVI6nRpt-Jz0z11-Ill}1#R>NIgESaB1KaG4}V*C^G;lXzS zgG4RJV4~J7T>&$B--D;WZ)GB=4n$k9CcydmZ+4z|@)-V;&1~ITy#BqfR?(iG%}@U8 z9q%WR&*nGK5D{x1L zKIIfof7~;<{pRsH$GD6ykTn09ep{{}HdAoTSt{U0ZUMN?ZG<6?OE8RUDzbdz z0UeBY;2=ZJfAsCg0{FX;O3^t4S_McJL|$M^`0axmupL+w$jVd%r#v#A0EK^!L#U6m zcD!XFFs0B%oj8RsY({qn9Gi_=_EN6AsU?N@WyW4v*-GNAQu0AIBrZGw66p43jBmz- zlx09D4NO%;A%qedC%}`=!%vy0nG~?38hu21b*o;D+J^O zm_q&jR3w4FJ^alsOhlMXADD|HASb~2Z?4{Z;e{XX+I)6YmsQs6@f!-WPziwR*3nko z(()wx;4uIF>=``nNdhAh_{|eZ2S|u~Dg!`{fc1(OaW1rsaJK&X8?g+*E<%{q}Jp$-tu zB+{4wr>@qX8C>*h=Gk|3`2gr;csla`Mw|p=3!EC$bskKkq9_vH^*kFMrhRyNq=6G2 zKdO9G8tNpaf&LFEGG2iFYEg%zFGEAhd>Q50QA}m{2QxIy+%^R69@56L~27pAUGW4h3Hf{Q$*I19X5L zIp2Ib4Dth{O9X<+KbLQcnkPl>^G~gg;#8AKX$hmqSxXqn_|U@W3n;3jJp&2>OUmJt zinXsOgE{}vcf((r5sM_qjZ_KjG(e@nsH8CJ9N7DnI1uH8ARA=4a-iAGvVN>dF$n7; z1YZ&uo3yry1|j$@%iyo4Co_I9|HX-Y9Lid<0`ny$*`_T%^x5-U%sAbfEy@dpFI9HG zE#N|`mgoprR+Vmmhaw8$(8)u`UZM(G%*V;1+WBO(Atm?6ekKEs3jiN;HPTh#pBUe{ zInR6Fddz+~J1YRpZh(9)X}x?v`8QjtgyGg3C^=^mghD`^9HB$p1D{yP3TXWNP-Od7*sINtbXQaKf5Ol;A&Yx5)1OwZbze<1UZXu@a%r2sJ1B(aHWIs z``h`&sPDxBKMjCJzJR}0TH@MO7{@_S z(m>*O#GeVkL^~2z;tM0uB+@GYbPgaxQzarC(I|L9X)&<`M@jl3NZ*E(cc5Byo&p7c z20v}ZlQMen_Q#|@!l0n=(lY;z(C~O_xFA;ukAnp+OZ8HZ6}Tze49Dbo5e?Ckt}vh# z1*4(ewPPVJ!KYGN7uznkT;>249L8rVq8g!+({nBI(H zT*!y>Q+mcUm}8(m7-dLE4aJ~csiy8R~*Wd@D0Lg&-VqeJ(P&$~6aRF>p_bcZ= z8{t;Q{O2xAk9^Fd=uTZAW0?wOYq1Lie?_AK>8#`bHtmWyR5HGFtF<`SenU%3mgy4n z9i>KSmDagfdr|q2LdJ?Md$zzYWQ2;Z$}6XAeaCL>cSPA4uAv3J5PV132aV0FVhUN zX#Bbg%UO+l6%LNB$o#_i3M^e{j+;u_x(W6ZgcWl2g=fX=T$X$lO>qNn%+_J>4B zbgyU;0N^C1K3x7TOUhCZ6225f^H-6~{tc;Hqqo8(v?mc6dQ5HL@y?nq)`x@uP+| z8$N8+aEKqqyUt3EcnZMsRj*+Fmycl$tQ|FZqaCx@%FB86E2PCYATi!6Fhi>_Gv<&P zuJLg?a}t9r!8D`$_M$OxCAEN51BS2ww~%)>ex4983kEE0hf6$2T7(nvn=!+BKmmQ8 zGUzw1n?=zAY#vxUHh7RL6`|4+4brA;8veB)1*|fs<=sjeYf>Dv5pXQ4f-7NsReiL@ z9q3!K5|CJe8F;{ude>NP3J=`gNJH3As*Bzbm%$~O2s%)1Z(4h+mXr`7OFa5jWlj($ zAsi~IV6ghS6NEMpw*jAgmn263pFgypH$n2i4?7TsuHS2qU;#$f%lvwYE?;~x{?Z!!i*4b5VE#8&wLH@RaRNLG`~wHP zXV1S<1oN|pu5tjh5u~UCJfREVI#wbf4shz+4C%mn>1efybay8X#9xC1!S)D56a2Le z3?wQ<&R{#@2!o79trI8$!P;Bh4cr`yZY;Z={94@r>=BUz;8zvul4}*;C&>J~F-*Ub z3RXn!7C!we3v9k>toW+A`R2N-(4oKhV)T6=`tPrQC9=`QD{ZrWg4H0L;ig0I%q6)& z*@18gb5ZVfRKAvAv%+B&kq?-|-(jL4^v}I%{`=tLUb4Ws95-0XUbxPp6W#A|4D1<- zPz2M#20(DYDuCOCSS0)qpHbt$80!SlB!>Y(%FYhgqYGeiDPx5t&=@VoX2=ECuTam2 zci`%1ZF3HZgw2`8Pa2vUr85;m-=fgc$ae8?mSu0{MSYM5&RNVXQL`X0m+1nHdKnrT z0E6_^T$l?AIG4*zbI{z6&D7h`QYhFmixr-MfXqdW@4ob6_V;TGCIHe}1Qcve(kZng zITtz#(jkV~w=fdnqlA6uOW5FSFZK+0J^d2QfBRlfB0!e{Q*9_+Y7_!H4X}<;Fe*c5 zafF4>wA!!*Ns)^#Lg#I2E3t3umeJ6uo!t@wz_S9wU7KwEpzxX4#-M_f{I_ev-t5?C zQM6L=g^K9_m@a>eJ1t#yF-Y!}Pk6$hR~BI~B>;HnP)Y+-6oPFaC(($`=hOncYSp`| zV0YWEY9zdV_}zCo0ooLz1^63X0I7EQ^2`4e0q2e$FEPU<5#aF!h3MIHHUo*FOH<7pH%D;6PbR%a$0gSuzj(^RYdQ*hXl??sX@MWgx2wf6rP97*@D& z1KSD*FK`YcU^l}#oD9;ZRA`%lm-l-RzMH0+8 z7=hRR;0G>#6Tfjd)th_s)jUTC97%=2)Co=t;w~HpM-p|yDi01Sn47Xf|0JL0DUcg5 z>(W0^FQz(yKPDNxs53uF+25pv&v>QuE62iI?yxWT(j^lkJOTD-xa-&jCb)x^IieqI z!syZL(ag7P7hLk}cOH#wm4c8)k*LJJu^=+2(W|ixM%(VcRgPUOr2UxsXaL~9UA&0Z zchdNmHv|&R+}{CxO=Ui18f39nX?XKEm><@UO!VSsr=-d;=nY%_*C80paS5I|tAk)o z95XxR%g&88FdgsT(Ov#!my_8<`tq z-?!v|#p%!E;Ps*r?goay$U?Z0bkMi~zP1sn)GIQb52QeRSwOu0vJQmWX9aZgfTYQ9 ztmw`+L+Ni;qe4QBDtJyUAiK8gYT1>-U6k13aD&)>TlQ|qnBWJtM5h#D&4-TR_$N)eDtEj_RCCY!yhvOuhu?- z!b@iT%>n-YGX$KQ`_pVVL5{oNJe8pze;^6Eh=PVci(yOw&lv&d2!OA^czpWw7ylhe zHWP<7alYPq_UsO3E4Ca005S}9+d6W<&)icC;A+l*&k6xge0n0WAY6d?WCVn?uoB;g z4S>kx(6?YO!u&{Q5>7gKoF46zt+jGBSduffUBQAQ8btq~@M7l@@SYhtMQyoV@ z;#U&;c_gf`eZ-1s$z9z3HV_( zIy5jcfmrRwFhJG8$p|+c_%|&v^hjnSo>rhLD}-5|$u~&BQdh_ahCo{3I;TisVCoxA zURZ$HFoBJgn0{~oq%fNKSUnU24i{>AwDt1ycnKV0t8k5Z;j;w5Ej?)it_f2az=RzL zg|R}4sWR5-@o&`^nLQ^KRv#^3`MrowoV@6bwlGPH1`sn}lJ8upi4JQlC&NhMQjd{J zey7fL7DUSAW0R%7Bd-Ow;K9y;FL)N=A*tJp*z3FwgXx#X9z3R07*u4g7@d(YC#e^e zM=c$`}gypZuD_{RXN0|!`uE?g@Jz$D;ruwaP1@CWB|Aj{{9%R{uuAhG7DxdExpIH41`h| zcy{3-Q23|q*D63xfLwr~swMye{uaNt_=_)2pFRmOcMHervpaZL-P`g4op77CZ9^ll zC%|Vk0p5FdwT^(FG86yJ;teno@p%KRoSCtKk;*Z)D^ir|Lx;r(Du(0#eiC8J+tdVH z=S5i2SnU{O7_XF2K{;jt?iF zu&|H$r{056rQXHUUyOf@%r9gWoVj<{$lKch|0#%PxWAx)li1JGaol_Dj0kDSv zi24tVgp>&OkSE4tR}YrpU1vuLgq#Td*QmZeL?#7MA}On-(oWtcQoi1Px!;aaYAoY# zB}6%abdzQ}I@8pL&eRE$Hj+AinLcWHFM? zFVv5wa_B~_z|4hC>XiqjFsUHve31`cn1pcM;CDUFfNBMfO1Nl7Z%px%62e3qCVT-j z>zVrC0V0|yil>LMg8aV(KrO+e$poh|%q>d7GMlj}D&T_j&{;K?p!V%zy7P5Nnm5BJ^PY_+$H@4>Wu@ znn6$uLI6bH8}YBW0RK@>e(UEydIdge-LrC0=Z+Txp})ibFAS&RGognW<72NZY{2UuF2Ex<~yh=aw&|_MF7Y=}b{4#^R^u*^`H=BC| zOs$xqg86nH{=$=>lrY&HkVn8rz~^4AMLj11r!fTr0(ZW!=h%b+uw~Eq1f)fq-3Yhy zr%(Yh28++n1`YD*n^`$J!(e{J32>=e;bvyS#Z5h@zYpW9k#rXaK@5J&+p{H@WUz$+ zd=uR@&Bj2!X9Zw9l$U^`9%L&z*_rRHNPI89qCF)l<@uc;ItD6IM-upsifF$K4_$?W zpb3-s4g0%u<43+Y(;HQmDgm*>_m-YVX!+1i+sn2$DFFR4!b&96`r0OPm}MY304g3P zdWEq~ciBhGTi^wQpVWaLTLZ(7EyBr5gWj@Bge?3um$(J+2X3RLhhzwJ&XXw`Mkv_B z&%7)_AVaV~jBo?S99ifr&n*RT^e8zCa%em_O%x(hg%In2X1$D6_Bkg@xF>=Z|7iR@e*CmM=lpEi2=|+OE{QOwKV~ddvLe#4~eY|l5|YJs2>@McuwGw=84uEj$-iy+$~t`!Bsb)MWYGh@3UUlo zRY-FRM5Q)RDnMKjQ){0PG17pmeSsF#-0V_y!0F92@S@%tz&4PfsKR(izA4bJN3k z764)lk0{6ZH%lfW=uB9p@xXIp^z)gJ*#2i=1n(SN^ZRegm2jj;f3 zS)n)q*4M-_Fx8>&hzDBGG5_%?$(e%*5fdCC2)h=RBe^NPwEVm!LSH7l0u%Q*38q(N zk%bQkEYlCl_Sginhe-&>QW(DQ55u1?fU7j}txAW$=hgmpI%?qb<}u-)Dd5rpFhf2* z-~A8SgYVAHrex>ffr}2{e`W)o&FayU5hPSFbMv>qsRf=vlg;wE(<)v%{n+@)od;fM z*)g$a=gud$?cTk4_mix|qzoDe2>iQu^;ta#fVcy`>0*!*+JHCz$^bY@0PGGYh-}^b zKfS(9rnKNP^97JF*sfp%B}AJB5$Neu6IF2oYLP*-3&uoXT6ja8ZyuUx-3F1K zFc8^)e(n76KkMs!K+A8E2zj4)<2cwLC5yp~ ztVbFNA%2$Z#m-;CA_dM}S$v>--###_GU5_AF2Nu4h7Z^eA>g9RVmda6+?9~elK&37 z+~@>(dx*Mc#zFTa`~w#D3`bz}+rud}b%+Q8C0#k&(>sYG{bXg%g;Pb=)|Q*4(@-kAo& zTvy_s573Gts`CVxlJNrqtpt2S_*ZPm{Ko?L+m{7nozKXS^9zO09Q}Tg!JmD`NM_p@ zVSoejfZ$tweEXLLWc~UNy#$Y88?JZ!f$m5Auc+@PV=jmqEgk{4L<&}2J^D%iIAx(8um`C)Jl(zfJ3jLXKR+9JrdC4#X|A*qeSr(E z!~wT}8Fnn-tetT8o(8Ht^boBmNTfN9)+H2>Jo@PV({CMMo)-Xc^X4bX0{`?Gs-Um_ zZ1q(>o_+S|XQLclxzO?iyB6*o78QOopQ(>HXf43&ZSx6R`tmmZ-(SAmPM{Cg5(!v}H#BA6o$3P13IYwh!4ud(5UlY%dl(T5dvz)p|e2teqy>ZRA9 zXu}A-AY6MxEvV%;*pCLc0;hD;ML;+eAzez1ujv)!(UVaSj58n?>CL{ZFID)j^ z?vYjaZLPiX19u8SI<3V^(elHS7cZhQ7=OXoi3%RUDF$+}shr$8K%D}m{fp3-i18z$ zjVY!IV92XpAZMhNAf=@yHdd&gheN)nk4&MFiDqO4a%uLPVbx_WUvzoo(!=}+-gFAb zIRGYHEM%03W>`kL=2^JOKX;{~@t3P6onM0M1%3xtsv*72Gnl@zntA@f1}p^B1o-)H zl9jiV2tHpL51n}6Oc}_Zb|C&QYy`gXMhb(L0+yAc)cp> z?SaF;&nK|`j!BkY@YNy!aI4{OhdJPAK@tLn>}9W$uFA?X(F=Rwg8T?hSdO^8Y4(fN zxk^vmdkJuSPqQCTFYr)pNWegC#mqp^_;*O`2W=oPasNH}syrb3i<>X*ea{!suebq^ zKlUgzfY}MKh<_aXH1z!rk2`)f&k1lgIYH)*AOG$k=m%!N1=Z*&8iqH(`-1?$hgSdW zAxd$6vj1xBX~pm#x%S18FWx)7|LXYWbDMVmm=hr5pr3i@A$;;`L11toCy)qpFH-_O z`6N{^ywvb-SG8l)scpwABOn3r!{z$_?pJLee&{9m&voK^C5Z6|D56eVs{2JX zkdMU64jW9dtoZXsAWRZN3j}d!(d#-p%F_r)41{AB6&^_mv!Ebzp%|ug@_Rr7eS`B~ zO2k(lv<`q*qIL$`$bc;X(oPkOJ+`;8{ z7qu`90o+i`{HuZ`ST*K*vv4dofS3thvbSXR!&@EvH1KJEUNSMUU<_0Xu$s{0UE1J6 z|H49$R0xOpkFQQf8?Y&0Q6Fg&KFt~s7NVct4;P#UK<=bA0So^E`vU&(bO$f<^Rsia zvw?U2X$&-RPmiPVO1aQkME)!V)pPf;0t3*V`5D5xa0x^Q@wGF5!-GvEUmQ6zcyjY@ zpdX^J@5r8~-!}ng({_4@nS$9Ti!EKN>+e z*y%ds36N!RUVhO9LdFh3_*#Ak60S8%*3#c>0IV2r;FS!Xtq#j#s(xw!V@&=)V{4X} z5Wcy(R@vW@I;O7TVAHm%i;o=no|9ah?xzt@)JN}o)9!~Gi7j>{u7eE?4N8qkmSCL* z4|8rD2?`md=Meq@_8PWtmp1SN@gEJ!Lf!6iILAVNu;}l9A95kmGHLptcp>z445-DUJJrN=i^ep+FL+!nz7M$2;WDG9Xx%CL)AD)zzgPJ|w0P{2U0SmZt zod2ph0a8PlPb5c;z!JC@f*CmC%FD|=CFZhXkbq$QQB=2{w|^yN?4rdgvDdeuW8;B*;5z@MVip#)7<&Nul>;D{v_t64$@$`>X=Iab5gz#Noe@PJm3E zwjcdUqyZ`mNdsWyq^B;pZg=w)A5N>?n)J_Jf0q&b+yv+BCg|37s0ug%V6Y*ibAe@1 zin%w^5Nv+)IGDA=DH)&m7j#D){)BsnCbA!t#T_t}VzLwt;CGB^fYiYp-~jlp8-Z8F zlSaXJm4vWreBlI$&9n9!wEf;E1u{1`8}zT?&*)e3n4kZ0wxsE|qzP`}d{?RkoGqb* zXOk9&D=^Zq?t{(%ukrBe)ekY~w07~}-|qb7FL(ZS2e1EvTA(MF{&+X~kYt0~i9|zu zmUm!`fKPh@#QK{BLqGWxb;vXR4>S<=0tsIn`K{G14H0`K+gs$IGCoG0I3&KX z>_eo8>5>>QDT}$_8{max2nGOlPM%V>f%}jchkqIHb~yyldL}UTT&DAb5*hq7$GjeZ zUdPh%r9caOAJYGap7P=HQw#^hg>YyRC>Z4%g?uEdh)7rgsTmEtDYA5o!T6p(nrd_m ztd`l9d$I3-slLdIXfz(ln(Gm-gAokW{pDCg;(wkZu_}|9&AW5nUn?^ZG8dA(B_dyR z1dMr*!{E}Ma*29sZ2z;QJB2Dx$-}in09dIN*bR0oC_xPpPEu6RAhe=896F5TnEomR zft~=f4Y<@29Jb(07@ZXX(*|6e09gtgF5owugr!0xiD2R^Gmw&?;e#U`NbFM<;PP;S z=w*d8fh&>|xF$=%$6G32Ab;Tmh#Wwwc143=4BS95pi&Sb*O@b5%MzP__m4dv+=cK>+B-z1qkGJW=w%2)KFk zQUaj96FbT=?ZL~}1OM>Cr?~y_F5-Cf2|Pv$p5zcdp1{DzSqwUxX%8! zEDu4{o|6Izm9!E|>8z_^d$VLRjo|_w&}-Z0$P5Gjay!SrIP$%i02TN*a`=}%1F9Wl zdL)xarwnN2!!-0pW?*mcFF6LfLPT|Nj0S9A7}f<{|BQiMhsCgT1p`6~_+u)ffrE=W z|BlK_8Q?B!!M*H@Aj^RnipmZ5QqQ(sRJ;%dFZJja$dV-V!S!tB3|_vJ34l12F-u^G zsraCThib}E4ifI$Tp@C?sJEleR;;db=GE!vMbfjOu+Tz5Fec(XBA`#92KksLGo@ZO zp$TFGY|WAs0^p2tp?{gtgW`dlC%+C`LwF~Q-<3lktRea0sWATh{(u~Lz-fka$rvm` z2Va4-1oznv(nlT4L51?-`>!Ig^o7&tBVY&tg9XlxfdAO{pd6+oCN-+XaAzaD= zR2XVZfS+$P0EXs}-^eurVh8?^0Jz?h;PR*g<}UmIitSZ)Yvip#NpsPzP8${7YuM$j|m3(e9Vg3TJ9qc~}j-@fgw8 z%zfG587e^hK1@DE8u)C~z)mi}1VE4@$`C9^;7WNubDn85eYv7ix1&%@wby&n|K;R{Lth{|qYDZsOf*N9Y!J1Vg#>R? zQ|TPo$wy9vP%b%zGfG$`>b^zhDwC^O0O$zoF$Kf)xgxXJk9m*{A(5&Uj$pY#v;>~@mz_Ud{W5Eu5{OGr&&!tahLy(CN=<@~)&iU!uS^!`z zwSC-eA6@*HJNzfl^XYf! zhjD)U>UO_9FEQ(_`&{`U9vlRf0fYq@V!oAjz&RT*{BO7jN-mHJ6c{4eEOB6kmR{gt zg_C1siqjYJfP8Whan&lY6g5nK*E1hJjO3R(-v;ZVpqeW(BLp!M^xb3<%#Z$uaty@l zW(0`z&u|D&zZYjgANrh*de{RXhQ-6NFU#`VOS>C$0Jjt2#Eu+pAj90?RG8iiDG2|w z4-Rkt>;pBWs}+t%J)1r*NBF@d)uq49K6FIh_fYo2KBS%=0AMGbAJ~k0v>A3-pDe<+ zlLSQPWCwT^k;O&e%LOF?j*;6Ve#KUeQ8N09Nd-GxFF5ogW$qa&D;?od1MPGn1-PVu zs(e0~K2-VPSx=Wk{MIx14ERza)>t8pf-%qW3EJtz8!Hm4C$`?={FuDLW@LDPDc`>XlvHT^V&Yn2W6Fc2_u08{c+lDv#3MmYPy_+zmEdjr0!71-p5;V(VZlX-?c!O+1J zWql>;=i|q}LjZU*@gG*jBtj&MgPFeuJ|mV|0ATIaGo1eB|27{Gc=vDD5a+e?r^o*F z1#ZCO_Z~9(#TtB1<(NBJm+3?-kRZF4c4mepOQA)BfZpl`?pX`H-0(L5@FNDYs3wJC z@eVjJ@aKVnHjRJYfaQ`KsA#LG$odS?Y@42UOnWvZEW-U5~KF)8ah=4uV zdwBtb(uE%tBXWwZa4bKU8n8p@_*70PC>1Z9C%FKhQblGV-%}F|NW?5(#3Scmfw3&d zMOr$_&&KTab-=TxL)t=Itd#3ipnWw_won+3(o5QX>3dTi{uK3pJOb)Wn5&d2ZYoW0 zdJLxyq^OGP>@0o>r8$ou=`a9x@K@xd>KPrKniN0o4CG-?lixmXQSdI&t9Jrf46XN*XYB-hU?0%4zA!25y(5e=+JXr`gQ z)_5hPfU*L&rB2{}ZbQqx{7ShkQ!t-@UtdpEG#{UQQoq#`_Eu+hDg^8O4QRpKuthBJ zCaYn%>t=pnTYH@jos}Z#U5T8tr01%V2Ba(n##Xn~{SkM+i~`=Hkr1yye~|kH4g6|S z0gk^FMqoz)8UV)=_>HGVbj*L$0NyXX01E!@Wcc^*g1s~8ar^eyB_rVR2U1W=sE!Bc zzqAP}5Rh+l0-PUA0EnFydc;S?G~cQ~x<`_mRIDOltVA_?Z^Iee!% z@}r->_}hO$9xDC2c$rqJl>{)iMt%$Qqo_|xL5Jas^-wL68ic1~Xp~ACzvl2rCUpL| zmu3pf2NX5+yF;MJM&y?eFL=a#dHX0j*jGhONE&rIC@ME6DSdm z+C$HLRK{5)-Kkb|On@CdL>MOm=JG++0uVbBeqc(wsR6K(R#a-y3e_c1FU73C0yo;u zPC@9fp2+|c#Kt^C0_l)*FeL`0lTHv$boPT#%2%?)X6Y_5+2u0?)DQB`fg!Km8J~j> z=8~*2ZjJg^%@+ayFDkdt`Tc#WCTvnmdY{+dgZ(SD1+yI_T;rYq8$%17!Cy>(|0p>F zE(k|R`)^zTuZMpmy8}ikoRom6q3a62Um z{51H*gN>QDwFAcl_#gn5(7+`QkOliNp-(Tfx&c1@$Rp3zYWhP*(_^*QZj*KfIXtg! zlKDIQhY#u#o_U5@_#{7!f8WFsyfY#Jcj^fEU@%6xkRwQ-5JZpJ$Sv&fB?XO zc7{~SoT(&)fi^dVs3!sM{CU6v86E2y31Lx8hF2L|9@i*_g`Qy`PjvRUMu^+s6YvhL`KLp@e>tdtZt*()u+ZktR zG-WT6I+NKD@*xU_S{ZJ}Ohk}BYksw`@e7BCv zpR7@r8+~aQ(W<=x7u*-j3F>B(!Vf07&Z^e3z}2>r0au&^^PDlM^`i?;0neBUVfd9d zc#7bM$d`O40Wj`>Q<;_p$d$`Np4l5x4wj}fod}7r&d0~&loVEJ`OUl`5t2GAy$w%} z&Zp55uicloG=QH@flW=Z1Rqo|KD(*)71CHd0#Xd^A@CoWBkqk7Q(PMPvI)>TaET50 zI`Z%p2J^Cckk?+$Zh#vl1*D=i&3}x8X$$OIE&^nQ6wxXJ2JZcy!yiO2pWyYft;=M9 zTgFP@06=jcnEeEUB7-;WH4hw$KR&psY5=Ut4t{$h^RKL`r0g;pKooRPR_r~B>Z7vs zG9d(X2n=m-uj*NIAjUr>!B7M9))P;xT9xt-V(%S4Dfh1nF(3U&?N!F0h6IK^NU{G0 z_yK)@djEc=h=GF!z}auRKNf18XA|5l(EpWO1aSqV3g(g8ryqfC8WOdTOhy?Na3mqV10e60i+BmGhn?VDE1fe(q;{58=>_?Ng z$gOVa03n2F69Nt>7LZj9QYCo$TiF&Ofwt6~S(k2s&GrTd{{5L#;FT+cK>(rCu@sdM zaesAb#`D>5K=9bC5CnepD^5X!<&~gS+WQYKtvzz&izDwnKmCI)pZd*a@9D*cFt+qWbAg&~7(P`W@3%*T<3 z#aHYE872pU0E9~lLBQ^N8Dt0J0BbJE1QJOIsWqJ*U@giK0=Q`t_eBmxr-Xh4KubuR z2&glj-Sx5>SE_bAuaE;4ovUAROn(d6_IA_SXFMtEzOpbS+4Gc3%?p~nqy6ooM7_Z8m} zBI*Dr_|pLRi_{D(0Q_8OfKH%n^w;J<`Vx0aT*P*z5ilYF`M-cQ=o|!>Ez4kUS-c>& zGj!0KLIZ<0du0eoi3fpfWl8KT0wiX`tn0Vf{*je{82zfs-27GqzhVuXSl}!Q|3GOL zDp2q(@E~vD0U%suCop;8fI-?W9((N3M@vj_n*Rd-1b_gZ|0T>ja^}qc)-y)H+k^0e z%pIN0#DK@Ys{(ztqzfrQ;cTXij(326x3K}^@$CQj?V{g4iY$b|#iT&60?*^mgnD9r z2C6y-34yggdzujlS4kQ_EdacVj?5EpzWHgf8sw?nOMgZD<8_-cy$WZe8hS-i19B0L zj#g1%zJ#<>nAJ~j(8@Y_gQF>!Um*+$6am74k85mmo4}AOvAiLQdI1DpX-@U%s?X$9 z*PM1{X<_PQ_mD8AHI9ZA0>Oxx#>>I}zRG)lI|Ccc^Y6Wf+3!|TJ2SvV-nbC}B4bQ5 z&eu+n24SUGkHA6J26wqrj&HdHZ|59HDAX&cUx=U=F31%3K`{`Ot#Dj(J2>+p-~O_E z9G83G`q;t#b9RHU5k#x;P|qn!pIM?ribIH~>?@n+daREgrWK7;MFg#ANK27bDxH-5 zjlhSOshjRK(!Gzjv+9I?g~+%9TzaF8l;+_=3d9RA2@Z40Un8`=vsqhTH=Tt6|Q)OVL4m!rgVf{v($RR z;21|hcf|D_^!bmWym3)h95|wbic*+jD&PY2+qX~%{ZSZ1O6!osg6!i6_zO;dnHJiH zIEhi|O~;onuYdj)-^NUs7yxY?wF*$^_le8kJ^=`Rq5*JO>LPyPgvr?Pmyp zNBC#Cwz#(R1c+hKK9EmOq;fcMz`Hl2O=J}LY*ufI$yYX!AInz=0Q>t91G&;}aCt%? zPK7SsY8U!~Q5GZ2s~Z@IVCVrCpeq_nz!$ol1=!W4s`SJBO)qHj`;2P9k6Db4v)-kUJ>#kesmoIMh+Y_P9v%4 zUJ!UwY=??4{itL*e(3j@*PP&z6h|7{JpN5ZCPL9?LVCD!*!laRakiO*rjIEEN9Idb zS^0fCBmX5f-IAY-JeYi%33JNFiXZy(hDpS*brUzhi_Y>ZUfWZR)h6^w$jT^!5mI5G$!7K$P8v|nv&ZN+J)QsLqCVaYt#mGawKjUy{v-*<*=+v>^Antg5Q26aWvE#z3#}4EeI09i08%z{^%=*( z+|v&1G#IpEE@k-y^s4T1wi0@IdRZQFRCa>c3@lN;_F!H9R;HB~6Cp_voB-Q&>Jv#} z4!B+USIxx|Or@k&q~;?B1M0NXZ;MEsSrAQp%oiMRs4BMMI>}?2qjT=7_WqmqUKu>| zy%$G*z|&p>J#KJ&OvilJ8@^wH*K`Vl=ET<^u7tF%6I5A(sRN)wqv-%1VdkkoF9J}v z^Z4g+v5UVG5%4nw0)8w21j}oxHsdCQNSbP&5K`ftN3t z5>ZjGlA-x7V-YS+GL3~0QG*|I<>gAsX^?q*{{63(;pV| zfe)1%{W=l=^2MRi4o%f(_#sVVVUm&^{OK=p2K0B{zU6)K&;?Kch#Me-h9r&$0=~n3 z;CFogD-lEEq9>C(>KixqSqZ~PXxV{Z&aQyGxBNL};`dt&xSSf< z?pS~&ndp}OSqf;4fWSVU0GIg)IO;Mu-TtTmB=@_Qk*M5ycbNx~7jAD+%yOtW17;_` zcw1Hy`aBVEcqkkE4ppTy;Gql!4+#L*tP%Vj;0%b@FKGz$1c)SC zm20&Ez{l}ed*saDZj%MRy#W7SdF7f%Q9|G=k30?OG`40IBYnE_(@%H84EH9_fID>p z+>JQEvuATqCe+`Aa2?;lW)c7j{koO@EiFuY+sYIU(=KP62Evud$6pzB>5xV%CC25z zya2X~0cmbc#t(0?5r(Dr1{`#*0`!XJIPf&{o4srxX{sEsT&6YU$Y=z_%gx>Q9>KSs z_pI^T-s^!+fd?pu<2`SLi!q^#!axmxOgRMtPLm<-4fF6Xp@OE;Z~B6Ng9b4lY zRWX-`Qcb!_lOTVYRF7~$3Oe(`PN~WlJsaXqX`;~OjO=Nplckzc)TxYad8eo*c?w(I zD#!9++0buUIUJ4U$)=lfT|A-TNgQuyI^*SHi4`*P;+KbqkE%Z@|Fqq9D#My~*Ru@9 zPt#yjeC9(Jm@huKp%o4|+8D z?sMy9B0oOL=D-qS1n74onTW#;@^UnzH%bTSM1(69p=|K68-;KmdhlCbJOMiX0OzpHjUX@45R5QrHp1bx1ko}CCn7k40H0?W=3wNY&Y1%V0Q{Tb z50JNZ?I2+=n*+g!+y-X?&+r0Dqj>OJp#S^l_@@OIaCWU0n=KvzfDl|`0luGTU@Xbk zUU}q|S6&eS;x0MJO*niYM8Hp>f(HGe0dTj|ur{Atimz8iw2f`8HvldVJDdkV0$_Uz zM{P?3psgWkC-7GW%HZ@x(ynSa9rduY4us!VI0y3@qzpXjDL>G0r*)B#Z{Hlh#3*!V zO`)m!4dobVO{1X-l$zUDPVK&iO7vT|?CW59a~Ell5jF%%veFPqekOts2LS2=y!XjE z*ZZDkMldE_7u#Ta;0BJoP(l}!PWCTo) zFMNQ*$;+-iLi0zBR^LlXOfdc_GLWCCX>eFOujDW_HI*SY4z5B9=dt7fDOf(@1Q-r{ zoChlr$i7sF#EJ2`EswLDBJ9=To2et+Jb(;Vg zOECzaj9CMdX1`@y{C3kOEy3^e1h|1p7{*;O4Ru$lKF?B40d=Bwv9MCIr86L*k8|Kl8UX=-Ne%ca@(`Y2A|MCA{oH|5J+NoN zM<102aQ;CC_%C-f|M6*UJP3uJ1EmF=FPQ<0PC^1aG>p`L}9VQR-`=Yb0PS-$kxQ4fqP*hEE6>|MX znR;_D#<~@z@T2A^lrv2%v=lcC0KIt*wD%z3F5*xd6kbXM6cxf*?ZUJc_^YXkns=EqzosW9L6UNGeTfkTtVuT z3=f&$PkAsr{|dOdL)Bcx-@;l*->NQ)M)bmiWVuE{Kg7t2rWd<6IDHKw(( zK*kBBH1UlriD7BcJDvb-<8U_;FM7W)#T&6NrBukieGiZzZJ07$?9Y19D^#W8dS1K8$EuJ&532EfIHLSXA1O@Q-h0=&)7`u^beuYKQJuq-JU9ABvgA^fvvo?$86i8mt@ zf1PfC2!rw0uu2+cZqDEYb92Sb`kQeEOrbx{M)lf@Zb0@ls3b{_IE{c>g4Lo z8cglI9R3J?8{`M+A@)H5xM6RU0Po$fKPP04r{r$DAbzbO;kPQ6|y1pL)fA>b%H?=v@HRKo06T|dT# z!tU$36fV)50*U%&?P7r;pH!wa9eCtn2XfwU|7-dvS5tRQ`H9QmjLwkd?#z?w-} z+2q!-TE%p4G3dY|m@x&UR_4c2cB$q*(ZPC~vwFH931GCs+37|XTt3>*dDi1Unwk80 zVjzi)@^i|~#fzBSd^XZq=u#fi=knsL2mH$^4O;ZeR0e~&EDlhE;LOa{dU=|iU^v#7 z-2f8-(x3LgT}rj*^N&5{ z2>>S;4_MU_y>I-W#L$6xoB_*9NMSL=hdcqUS(C`$(Ei2hi&5|;-T@7Oj0Ak*iI-ji z1^mP~R51HJ_c05VDF_)8a{AH7C?oj>Kr=V5@o!EW@L!037yt*?a`Ho8B^oQW1e2uw z!WhU+m22=^hHU=?{Jsp#<5Pk{{Ig*2AOK>!eH0}iT!CL9)r$#_PPn@kK}!d7|8_v2 z5zvP~{KEmz&yoZ=!R`0c)QY4LaOt_F`m$s(ChmavK8A`Ke(9M9@hi=L(bMHbnC12a zv#`2xLd4o6TLg_6oc(b42+blTj~S$R{To=V6Vfn zdgJ%%QuYfVuq&eQw_k8-zN#@Pg#MUEK`;M8e1<*=xrW*2mjve*6K!0cmX8jNtpVz>15*X9)i-m2^xFy2udJX}xzs*S#UM!y z4Gg>SKsJ79FhVgM%K&&Idl7Jo1orgzxd{*lLOT^Y*_m_$WIPD>q7T;_0F{HaB1K@; z#|ljUhZTTZq<-cSym!+MTY#y4Q7Q1QREWe5Oy#~TY02`OmE^(^aEY&f+>PU%vQjNf z%7PIV9y(OiJ0A-8Tf-n210ZSOH5LNC6l*X85wHVO`0`fbKK7?{XwQMCAAR&1BlQ>r zBk;>I5Tt-1=5Y00{P0B}%;K%*pwK*|GGGYqvP3~-%D5JW<2IRXBGxnf6QeYfHr zs{;Ui2#k`}Hs&I%R7mv7XsTg#b-QhG$jQgcfKu`afR2f2jq`DoD~K3zM-nf6^a4xS z)m+zaSmbq&L4mEQT7*_&tj&#)7R|o{+Jymt=N>^F$cw>pZ~?y6b?X-O&;YpYIQ=Qz z)DeK&xgj5p+DoEhWMT={7m@zRC7Aad>(=m0V7wi=VmQ=Mwx84$G?cWDXFLAYOXY6ESejp#VX` z;DLa_1KNTQ954rrJS>L7ye0CtXa&xKpszl5_1fS!dJt>wh6fl72*E`sK!D$34uJr_ z#U26IS{QgH=CFA~=WNu-8RQIjen}rsc*uXkJcWLg*#rVEepE16`$|lJchNiI$Jgl! zs2LDvz*m9}=0BT5;NaEOB>=dNMiBG@Z?<1EzqLLk+19hBdPVh$bOcNt4dDpE%Rz`> zXbHw^Rkrdb*ygkh9E!F6wmBxNJ+;OSQ1HU&Q(~8sTq>gFFcR;hFSxZiq^>D3FgO#B z0KtVgZ3`RlZhjy5UPG6ae!#z5)V$oX^u>x8-}S(6;BZIsLJ-JUn1-kY(T5t69ge`s z3DDKS7!whUdO^BB62Ex<;4suLXvjpLCep9~x(!{6h<-!FKXqdY1gYo4WP}fE$pr*5 z9m`y=ppjR?i%N>oXJ88VaYQxi_`nRGOJGL~!z;vC z=Q_$Qm^l^jXOOcKWOF$q0Ms&)&&rv2 zxd{ZHKKI;nd!DO$?zv->E@wF~#=s@T^WT!-g3HQ^Cg8F)u>)K8Ow5bbHv>S7e`~Y= zKk>u?y?zTW;8*E`d%`Zblme4t@K29J0)uhtKH(1-gJDiN(EoAgFG3dJ&9$|HKOxlP z8vnk~5pXa@6^nE;VFcbm~Mnu=EzCaclg%!<|K+So6;Y;8Xp1q>)Kb|oH_v!%>TZ%UB$f@EN>A876s5F z)I~SY&&JPb_#lE%N34K3oYB0!aV}IEY80nWTmC{e1#tOSei)nYVbvj#|M=_!y6gae z#J~S{a#H*Uq%MRsCRs_;Oqv%22`4`aoQExW@f}bfn$%|~$3iT^xm>g&MH)26NWxKP-ZS8or@MTl_u1ev zOiU!ZQC=d5&c($KoNqZ)E^+U}^4mG&W1+{xo~4=(^Ns-UWuA}Xc(f3_6_8_DRuyz!i zFDI6;{G2aKwpBehQMHXv6TrFWssMp1u+&@@o$Eqw8KYJhqVeue)KnQ+Jx+evKDiBP7w{5vtdyUw) zc&+b%_|aMb4+g_f!UzGe%g&=TN&dMn|Eq^XX71ieIWvRCS^oY%TD0g#L^iI#ze`p) z&48Q$2LqA6|H>=h|NbjJ1rFX8AxsI)J!b(T3PDb|-Ai@dW{gviacho)O5&f6S!%{1-;8Dp2A8?Kf zO9;ZFrxk=snY5~er`;9I*g*eiMB&oFKqO=7SN8sug_<}3Zg1c`NTuN-VBgdStAS10w(7_SE>jdS3qX>DV3VAXH4XKG1cYHPUXVi zp~){izh{}@kIx-C)tMRLSO-#`FG-Eb;<9A#WBq2#wRxQ_S@JYC7N<0pq)UpLPJk;z z3ym)fYOU~{ROP5#f!~1=aO3AtLu&#o)?@PddS-~*mwJ%W?wfRi`>x-R5Kz6CG{U`Z z^!uM^Mi1~~w<{t%2J~IsPT-V3jsIT`s+1#gM@&t0+IWJ z4Ik?FK-~QVCO^R461BTI#T4092!@%6z`xMI82_U4ym%5UG9HQjU6U9PtDw^f(C5D= z1cbo9aiqXJq4|%QSo^aytgIvR^l8n1a9qqgd)^B$fb32zryR`|8v^N4`{EiVKzedB z_)|lOroi~c|2GJDC&f%>R^w}H2ff;^jT0b>H-iNET5k-0xB=pmz7OT}Bi|26j35v~ zn%b+`5{ya^;~&5E8vy@*#@_z9>iXOo#*jkb><2fqA1e~ACBR@y0^A`WO>+tXnphGM zAV>vbvv)MagOLc3V5-h(fx7`Z07u}42~DQjj-hB_dNQTpjQ${1Imc(5GdgFc|IM>r zuFrSx(BAjlJMScV;FJ0p*a^IDeBUeDu!0d-&xPd`Bm7k)?G< zqR7#s0z|I+e#6(yiKda}C{pu>eS0@N0|>`CcIZ7k@qJ}lO(fQ*cen!7$UDZXx3L6( zd}F7J>$I`^8$vWny~N+fpn&zZ$`vCD!6~9k>z#Jc7`2k^DJenk;t%8f`ZDu!v72}v zRGNIM8^!=UbREwe%cIqt-WQ#BBwt|27|HqP(N~`b(h>iTP&C0wTrr%1z{TtkPN}J? z(X^1`EoN3~TtDhAPnIIB&j3)raIFOEhiyQ;gFXIH;>^$)8c0?R@?qs3@Wo{DGt?zJ zbc6sh5C66x(BWBf!Egfp@sEEj`~$46<|Q1`+um2=?=9y6%KqA2SMCMY7Vz5W`fJgL zG_Ju{6fm-|2!Lxj1(OP{q!SP@xJMAUHmWc8Sp8)T^ra}eta6b3r59M>ap{uyUpfIv z5m?a$S5+AS*ibeCmSK>i@L&SJWk~^kZh?j11*CtA7wZK!!2J%zU%a^75e)4Wu9I&R zIQ2zBFs=Z<&HzvkfFE#Baxg{Ugn#Gml@aiZEB{vj7)!Z!&4~e0jNV z;1>2+{iWPnC-$ept~%ZTt2RlgfGsKpIrP5mfCNFh_uZWyNr0Vp_r*P1W_!_vZ=4Tz zX5E)O6IO5n{yNV;2KKgSBY5zY_V28N1_BqfV5rsgzla5-5e8=+tR8gem!w@@Xd4;hO*ua0u^Aqe&bG+kRQjuA5`3r;xKPNIgAn-UJfffl#G2I`>yuBXJx1U*_31j0S3h}+w09v1#P8hz zK-&PF7PPlBd0_y5yB!HwIR#f%#Qj^AjrDJp?ijxUQ%w9Xq5!Rcyl)R6A@KcMe01Mp zD|TJ5KSaSSy1eKbhu~|A5CJ0q#PB;V@;5I03;j2IFwfHZ9CPpNoSl1?kz+*x{;UBBl69>%lU@{7bm!>A1&j|#rhrpN(4CFbSeSkTY zBIVWHM*w7?=F6*6B9?-ovkE}>K@V^M9*`*-YDjosNdD9q!-LPKAN z8Y_GMXYV`YfOm(>hL)IwTg?O^ab$f+g2$)^@hPWSpf@Dh|kk0olmuy2*Mxn5Z>4rolf;iw5jJHFAanM zn2IqM;b&02aP-3HM@_w$12W({6N`xml{Oe5;D>;}|GNEO*>LaI8O+R_CGC*RZRM7Its1Qhy7 z3Et`G`<*KI)myz%#jmP-J-|*&L@0+|RYbsCYA9Qt%lyw%FjWwQzvvDaV7Nd4xPZhD z_CN5z1q40<;9`Q{6U05q!5oM;0sVl0H9(KAP2GO`TcOi^+5yeHz`MRV{EeK-FrRF{ zx&0}M!YPs99wH0wB@85EBY?62+;LW_-$Up6B(es;};Bs zu0+6lfq>+I20$ig$rN+*oLL~o;4fd&1gu-&^UT8^imo+{X{~qWq0xZLbbN($23{O779#{)jqtmVpQ0)?j!> zw*-iHd=9MGEAc;ppsqhUj-nX^@OP9E`1<2kHmh^Bh{fXYjN-G!ajfs)>Z7oMN8@{j zxrqr;!J=rMqz|K?KZ{YhJxLhCP>rvW2TUFTfI>0Zs)0H~{^|gX_NX;i988*yOL^%a zNf@!d5Yu&gv9bK{JenMO3`i}dhlrg45I-7dzRdHimjW{0DY)!hXZi!T7-4w zodPq&ScJTQu~{aViXxG=4gMKZBtigk2KkNY-)B8-SR6VQ(FU_z0Ek`?*-j|}vss3l z6paRmkklAl34kwtX#V$Kx5L^}F$8<(7f=7DLQFRz`3{a8a9gOrcmVwP*oXz-EubI( zuv-8K7_|NY?7Kz?ymk$JNFact<6(g2B}iM_hWX>#0G?JL0)=0xAEV(Evs#Kr;rS;S}Qt91OH0U%H0qJo{n z^TEyaJ0=kZ{g5wt?~0SXGko=bQt!PZs8iaNQlR022?R{uKf|C)fz1K6FO-?^Dj|?@ zg2cb0&e8gf^PjI?{SChJ9nRaZ)aZ-Pk^zFOO?b~YHY78Q*`Nm9i7}13Y)v|1(KqqK zM*IKPw-*h9qq@=n94(D-gfUu#+x2OZr9zyMt#^@-rbyYFDI;)5ZfA;BDX!Yu8?zYc zV1BfvSpEoUB$b*os+rhXZxeKBNPMqgnIoUV3{-Po?9=$0BLE`eX)V3bg_6J2B(jie zrUs%2tfILw-i|~+ZZY_5%=H3uEiLtLgbYzZ{4&xCIAxJkHGX z4)DqsCT%2V$S1``9FqaR`U>i+KrkNvZ8qo!5%3;Qc0ZG88AI)r|4%)dznzA5(>{v# zIBJ*6<_;@h8tCVo8IRWbe!^w0CcjoWiPaJVV0ASqAgVNHn+JLhHU#1{?q8XP(8bWA z5&nLrj=$bNe~Y5-^ksFw5c*h;83kQ@^0+H7^t(QVGxWjHJYcK?+0*Z9%)C84>5S7y z9z7}I*-;7n3;!vzKMUYGYZLsr2(EKLm{{8q5;7qbhj9P8=HqiWsQJ?RBKu1#hTw>< zlH3v5_jt{mD}dmz4n#!pTFdNDN52kKwP_H!r%{3A9yuf)pd?rt$XV+xt-Y>DhgA@f z`13L5P6*a?_(Aw}A!z`jkz0BO?|hbdRR2gMhrydfT1t4F4ZV!EzDKf)6?ongF;kVu*x+{K?Atfzvr0*&ilgQ$Uly2dCi5A`m(NqZ8N+ z@I_|9hyeorc8dUV1in@4R&-b25CCHW2K!sC%^xTr`JXsou)xT`pT8l9-?Ps$9AfQx zU%@E`CM!Z>?)@bRzdLuPywfbxN_h6%bIYnC1V)V^(=t)3swxst8!BYr2KS#k1#nOq z2+zp{nB)(_9|@ozuM+t@1aBe{d}7n4#el#4^8kQkfCRw6CwWfpCjiugB5WlLVj1_% zITNmI{5AdiqD%lQ08evpB_2+18^#cf%ih<{z2<<0!`duIA_9qd1YT z32}e|zor!{R?KEt;5j*BAcpMN@qKiHbTPGUMBSz9*GH-SqNsdp$A_VB`_hdhl#x{KGkT^FYBIK(>ijzcvl8M4aFXGiHdih0d!CshrpB*cYat5)N_gf#DV;PYGA06n08cq(uBH5CG}@!=P&b z)H;yszY_i`?|}Olg`l}U7@%Ifnao@732+`QdmBjxbyk554D(f#2pAM_p%pj%NOgL) z=uGW!DHlIz;ET8a>%+JSP8T76cN|Rcb0yrLqYvcvi!Y`qK!)K5{PCr>wxSgCGSi^D zIsIOv073!yn*Ou7HtI5@bOW*>yMjv(_F@79S7t|WDt(Kv1Ha=rH&P9h^(CG`1zQ}|T27XhCf)70Ied9y|+h?wL{rA8O{NTI609`jiOuKh4+U5>>!X*W~ z_wl{5A&07QG;~_)Wn7GcW6b~jPSXlHXm0ZF0wqsPuG#UO-1#o80Koyt-vj+@M>P*z z?pmang>?|O&;b(@1sH?af1}Fhk6E6VE~P_(UEk>f0D(cX1hNnyZ{0R z{7KQmH~`i+mbhF?00hfCxb(u3n*zW)cYA+$S66V3`BOVOLkmRmaIp*f^RTOsq+Tcn zKS>|`W`cM6Q=oo_gJmK;D_qkIKwu6&(+|RN-OoUTUV-QgX&+-#d^1HGw8vh;AVINx zimLCC@B(VIwMAwu##}2Da`)vGc0Z)@p!!g3i;4xbna|!~yPmD23PIZKt|N_ff(s$g z-oZG0E2TU^E*ptwMRm?KBH6h;Utcb6ql}RNuvsCeCFESCK$w!?PM}zbWCRgDMnXG6 zfzz=VpyFVr?EyJT_i5Q#toIhuo6CqS)Ggf0Vt`bFUs=dhRF#6fl0s1_f^ZMm!-n)u zAE|BJ8?jg)u2wFfgH1&SBk0ulce^6~C3`1&(c=(qTRMb$|NU$LW-YpWtx=1O^8Xd>Vq1tCZQk@%tOU%yw@cB>lZmZjY)%D7H| z$qdoi^>4!i$*1B!I653N8pjxHthIbYK(^ox4|7 zDR9)LRKO4T1mMHm`%Re(RxrVP-#DpHjcu8I@VEb93z#_IbQu`%_orxDKa36FF{vQu zlrbY0Aoq!%TQLa;{7lB|?Fdc<09I=WX!Lt}1uBKj0S^-d4>uj2oVnv)FFa4fLebL+ zmPXKlb=y7ahG12zMD3jMd;*4yw04d!MG6jIZgG zbJ?QDr)D}6-@Ko$5g^h%AGdlduInW6=$d>9g2{57={Rv3lF3HT>JxqCNu zcf!98CpLH7=%-Z6%)Snu^!~e?E&Z$miBMCCz;|>KXA&n^!$D zA5H&57=dX8?C(9=N(P82cnaqrkS`|qffSGL^8|P^vGx0j;9clY6=rpjci}suYuS zmg6r25g3Ud0GNehxgCiRIG~ksgkxl8z!ZuQ*{J)nlaNZ(n+AblfAJaIJ~v`+;}NiX zSCs{WBj8&&?o{F%e$OvVXTaA;|M1rPKiz=fxgr1|<-k1a9*{T&aU_CHK>&htc><^E z%Pn*5h0eM^2xeL1Zxx5wSOd;2%fR|ne9>SAfN}W2*D^jQ-9uUU1ixM309;`97ez>? zTgE-D#l++AkN#r_pwevBm-;wP4~q-E+&q5P#=1x|^hoUfKmtdJfU13FKPE@u%hZ9Fb0bYT#L(Bm zKkIf#P+bJ$Ykwy_L<_iPqCl&hCGUKEDN@XUzQq4tPku%P3 zBWYNH`<$0c_1V%95SWiCm=`eZPIp+PFc=;nAro+Pl_LSm#ps@b-H+bm9|YQ9{?ki9 zbc3um07g4z#6t%Od@;qIR?t8!0e_U@Q^N(g&pyBu1%1m)XqCK%;Q@u13$qv)24P)u z705NO|2+S;RSv-O9fi6!QNYv&w}(UUrR04{Ucd?pC;-e1F4Qk7YT%+G{qL$TGXNY6 z_DAmcoY-H8z{`C7OXxe!1VD(u3seNhCd^aW9K4t&nEj%Fu)>_IsRmwrkug9b8LK*w z*7r7G@cvi8z_0xL)!z~u{M$4__|^UU6||9kBA+J^tZ)PVR@mqHmm5HdARnjF^~?xp z0Q?geAR$kw2}+t#M1#!I+5j>WOHINcfPg@PpI?gx%3F;;+421yO1T68GL}fytfM~6 zT*V34iO_(*%hE%bh;aEJ-#aKe*xh0<3@@OBjFuKlxCS;NpMHh*@T3+sZMa}u6;gYs;&hlCFb?PhfuI9RbI1Zj7S>PLdmh;@c)nrrL&K_skKVw$sPeEC zrqv9P;_uP4=QS!xapO=0_K0#li zf_;d-ACUn@3W!)=?oFAZ`4vV`h00h<$r?1Jj?`zS#C9dMk_JXBewK>5ipA)Wj2{3< z21wUvt#lItek(s40`4Q6qX#(7re9-ULCK5>OyQSaa zu0gDG4&ZXAAB#x-=zt*#USk_3DB$U&ek2*hxVOPEFl&{BkJ(puAl5;G*JXzt4Gq)W z&avae%5IsHV5$-}HaxieTUK5HE=%!O;eQbtiUzU=i6_7!f1rOVL1!BD2_3)@`4-Co zxOg$~Z_~UpdfYtr@s(^z$Gn#Ndis?3_xAk{1b>3S4}^kW5e5Io=dX;5AABXr#4ia3 z?|+_+!$!R?%>7LN41dBuWiH4As8`W70su7rIi-~p5CC|OBoP#EcAy`&e^0X;T{LjT z3Xs4RS_+y3p4&dTW9IiCFSxhRk!*Uc37Cz45-%f z3;iQbVAOD@qC1v?tlI2g)XmY3zB#Hv?2wWQ@}ESgX}PEZzxy-##rt|U(FnZjp0JL)e=$A1DBPH9t@DL)*}gl_7{mDVSvG#(|A6uJk$+b`mJ>$ zRz#t8tyC6FS0rK0O}fV1%;r*_a5IUQN-#N~Pvxqr5>C!-s6@fR=>gCg0Qv;j5eSh0 zxM0_=(0^YA|05bMKCUXH#cskR2=WR9@b^=^rV;StKV7N7KPC2&1b%7|#47LuPs1LF z35Mo^z`(!hPw4{P2D2dSX{m`PIqu|3I`7~$e-{}GcX|#>%l9OqM@_q9b@9RAA$pNMBFgA@2iw!U-+1*COR3fgXFeA||2J zxmWxP1Wq0RcWRfY3pxC3Vgla0>iMRd=Z-ymS6jSZ>ap_wQKQ9rPK!Ovtu(Zl4pI`i z3J5&QUJrR(!v2!Ar33z2U7vI(lJbRytvZ5pB>q`N;9tdnjY{CF?1e)npjBWHzbPAD zj%fc!M%Ye!w4jbmk2;2;Tqc$(1;(}+zFs=S(+_)s$MOG$p$I-GHm=8wwrs=7MlEuq z$5Y{Yen~-GFW;U5_c#;RTR!1N19u-eaV{G1#PSTN%yI5gkh8*^BkJDkKg_-Pf-2nz zZzTs^>FbJa{cXfzL)Mu(p4IKvw~~3uNb> ztnw|Xz~v#hg5trzqKXh+$z96G;oRvYFgu0w0kByh;EyfnLO^vPaRiPxrxv`5Q5cmV zjKEsF-;-}l!JG6T0G_F?J_*RVawQvrvtVa~puz0zq>Fqdv@_`aO$dl5<03HfgE!v( z08ase{Oe!fuYW!b2Aza;#U4Nc;Jw41egS>7LyH1hRtEXADUpnl0LY_ZT;l-%N&f(V zBz=THRAWAkH%p#g2OM0oWCg>r_|0(~{ML>wsjHB`hex>se0ejm4~G2Z&i}Clvd|Rp z;AIabTmkwTn2JaX7RFSA4S@rOEZO`7eG)Rl{-VI=PDfnTh7#h{A8vtrA{54f2?H?| z+aAL&85sD>((gBs0CJ6|v$Xy=cjFnHz^z|Ht2{AmbL-c;+!m4$_WH!bHkhORSvg3D zwt6fC3C%+nz`#HBe_WOGnHhlKn7;u6;@z_-3As8WSl`sxy8(Y=nc!hAIH3m^UL#xF zRxO(KgXgb>{$}Tdpp-nf6%7RgVv;w4nE$zxGt<}JB5c^Jox82%lmrCK=2BK7lO%hp&P6(Lb(EZo!U&1n!O6SNd^ur5I$ zf67v8pv*8EWdz*jCk(SDfVZ=f^cQ{fd)o%+KmRPXC-D?c19QONk7a{d4HL{p3LyN& zObU1_qkvk3s}h}OAd5T)>q+^i@&LLBX}*(S=12br7k{b*;R6`BcF)f2v1RVg4Ep9~ zDo0gS8ifUEz^*}_2lG%kjmQu9Uv&E$q|Xruj=_pJ1YCcR0q!~u%##YDAsA`+3z&uP z1cb$YF%WVKh&h-eaP=P#-~1EKIDY%vL;}l1Fjalr|MU%z!4D)2-zU~-`1Mfi9id1d z&=2qzgz)}@Y*6UO1Gg(*rzjY$0G)*Jno%$tfenDPWvi@{stS!Tfq!xU&V~aT2>5h* z00-B7iC4d0(gat`Y<@2oW+wmn`~Td`)jEC-Sx>XxO@A+E9vG#eBJgFoE`hrjiUWp6 zwcAnQuuJtIHce6a1Kd<=-sLd}-=uRm=U^Gzgm}s1B3Vx%`~1@ZYAK4+>gC<9J0y%jspA`G6(>i2%IzZqv_>HARrfh7i9+&5ge1-jeZxzp4vI>17S|X zF8F8<@NzrchPL%1xGJ4L?xZYOVE}UV^bh9p$-XCB4Ay?7e0`R==fB_AXuqCOith{h zSk4Xr?9-h_u^1hfDdR=PmV6=nEjbRreSOVcz`I;-2(Z_ukDD2K-$gJiZW!4>0312* zztY^y`5KQmbH6J6>H@T6&c!86#bki6-G>%k{|WAlM@H~}kopM3QZ67%KGk!a6@Pz$SXEJe9t_Y0=m$a!(JM{CyNGyro0m`LEfGbjJ}N0{&K{fW*yW))NfT76o9fgz1(B>q%maSX)iaX-Bx1^nRc z`+oZLe#L`w#@BJ$8;8L6A`XxdOO^_}k*R04sE1W6#9Z3A57NQ63v!bk_HTNr@|0}d_MAZ!f0 z)l)~=EGrE@6h^+RQwA%&T1Ukk>WtwRQCBLvX))00ce~wwiiaUv?39l>yQ6z$^U@37 zkp!XxI5NK84pF(*)-wD>1CpW6dH2G>vqHWb)Hkr+Q&}c6t}F#RC%@k^vD(z}?R)8k ziE=mwCbZ%<_~>uc5XWM4?(~3V@4^T3Zt%S^gPuMZj0gzz&2-ryy|*Yz`RfKVjRYxsi0x(BNbkH-x~+T;-3m zTM+}GVh9FZCO8fM-qzc<I;RGs+9 zJEg7Q*x3BB`Cx%#7x}7@ zUO?u-_3Q2R(bntq=K7S}XTUQRyzX>U0-)_G8ez57YxHi9@0jXo6fQJlqes!BQ5SB+ zyrS@~Wc5Qg9);#&;NSV;+Vg9>){fxJl{|1QgkN09dECt~(3Zf0|Cf?vQeU5i<&Uz- z(+(dt8}lMWF8r5SkIogKUNS#SRub0|DUw9LjUQ%0$Zfu852*WI>%5|YynXwT;ZWXZ zh$BDJ*X(m2T!O#dt1$$xRuCXzFn*%zE_WvdII4mg$pO9K}80ruvP;0;5t zPAd;uzQ46=!xFfXulC3e?LDAQL3Yk9w|&qDSP}aYO7IKV%!sL}qB z5}-i=t%v~pmPHI|*#*cR;8$e?i~ztVA_i4r$eH~ff2oF?sX^zjD%L*x(-+fG@PSsh zG6sJ7hHQfOKPW%Ht@WSZ_z&*C4HPsJeEWXoRBS33S*N8Nq2FJmpk{{-~0vuNb)Cd zO!S8cAsvU>>WNqp(g3`p{bGMNxb_3;4PWKv@5WhELj2K;cb8590jH+MlEu#g2M^wg z0J`}Og)aK!%~ua9#I#!)z%XuoVt$cFiRat+mHB!C6#pFewi=2{xnNB|LWY=D#EsHq z!ays^R)?fG66!5Wb)@<9;SPXKeB_NB=RpKGM>hqegD5&dd)>JDG47Cj; zyGC5%TDA9x-5~ttV6nFwuz3U&~7;T+RFF|uhCbnM;hRw zsHNE)LvRQoo`Yk-+*v*d)*xJN$b=q34w%}~ZyW3WN5;{5xvBT-*g8iGOrN&N;6E|1^E-pNn`8E`^E z4`FVgyCtK4az9HBu@xGL&~8RzP@ook&VU){QS0H}pn08XBo6EK|VeF*4_qZw7z0nUAiV&qMf?F?bg! zFqevMOV`Bh>lFKUnFf;OLAwvc5U8#%#Q_rk2!al*2?i(<$SV-z zpTKW~aR`9F(-DOVw8P#{d8katM>l%c9vy=?7KYa#bN8eyEULT#fa%s(K*xCe1IseQ zbH%0H;Igs|!V_TSKp#l<7iuA?6V6#Mazfh&1N%z^0pituz25ZGO?V*}6bhaR7z6-5 z#FC?XA6G=&tCgc7kY(ClumS{a83Yb~`t}=d0ORmpARu1HO#F7DhZu=J5Db36!IsZo z-;d1ugoR&yEx`Nw{&aUCYf3!-9&;+HhTxkkW+xrwOJZLJfI!2UYt}58Y}#IZ^C@20 zHJ#eg{Da4fqmfNc6ZAr*VlDI%P_HgS3E?l{<% zrp3nt?sYg6$H0e7|Ac`(3PWInIu+kqGeasSdz~x8T_Il$ywZMQ2UzPv48K71IWPIl^v+&QZ_jES z*sAx5iXAh?xCCU1^Td&M|HRL6)NX22Qc~*<~0&klh4@IB26( zD?dzMq2wq77L{w>b$5}~4IThH#gF?ywwh=}WfD5&^i}NpsSwbEw6zGCJ&+TBd#gbg!ju`+dCu9O3IAVEA=tE(Hq?H~0 zqvW%a;7`<#$+;JSsGqD?9Iq5O5kMMYJOXnZMqehAIP|Nx$14%rp<@%6$spTs3yhav zN(lK;B)+747-j#-{^9|6n{u$q6mX+=fNBK>{3!;t`xf!9JN2Q52J8zs2*C4s1Sw0L&JF?gMci;N0nf&nX&<>3&renWq&DFm-?o#!MW% zkF?K;_y^JwaDn6SIRWn?15DQ+yaQhB7*s%?)DWBl^CZ|55JCtMP({Dfn~pyFtUMCq z$m0PvSOJ6PgP*u^R_-<*8wtxG%Ggn;CIFG~kz8nldn zbrFqlFw_qM;6ddAV(F*f%9$0qr6uA4g9<|2P%E%xUheb`3EO&9bOg|I(noDNBDR6h zBk$f?-4qWfHkH5mUs-y6Qa0#e_n-p+aS?adcWR`0ifL($SbUK{#{~BGhUCjs=knd# zF!KO=Q=EbdF%^w)^=jxGH)w;oD)_rWCrqyi;0@)&%ouwYM{q;*z#N%Mw;%8E7H)#M z_e1>P$XKcc;r5ROaf}X>3kJ4lfnT4p0h!Hs9x=?He8RakF4ZDfB_Hrtid&C@LI+Al zzacX}P`>L~fh8)p}kYVo_ta+%g=rV-F|*7XGm+>64}50&HLEL_p+mSO5+Y znAitX;6VZ*t7&?A{FA0%x3 z-?M_g7=&33vd6io(mNs$H3DI(%4fe+JC-pUP(J9Ysw^+CA^?9dnW57Tkk&s;zRP?I zj4rqZ*#vxwSuk7z2L5Rj-oHPM!0~uuzl0E3VNO2vP=dgZRI@e>1+RQoDUW>q`LqUf zKwsrd?7{dA`DVxk-w^7(eLp5)(ZRR16ntCGX|lj{Q>Q4J51d6);h`ZRR2V{(hw$Dv zlA(1FGJD066&!&*46iW&E?Kj6>lzHjn1q{{AcI){Gbc`+xU|8EfQrR;1(tEIPJ#$e z;}&xMtrG_NDmbPRJ-38imDqQSBd`j9Rh!;TmkSFX1cER*>mo$tuEmk(E#3{f3A48B z9PISn9P_f!2uz&+W9v!zp8x0O?|vrSvI`xEZ9ngy2qEeuBJmFZ7sa*m9V z*n8F;bHYH4zsx|5+4rnN5wsX2CdvnWL#J>PuJ;|Pu*2YGN;W@yj&O(rk1@6%6&aF0 z#t;~{BdPi*%rBHd^7XKXutq}w7*$8sG8B?k%G18mUd&tCkcTg4RLN)RuVYx)*>Qcu zLn>KV?gAmOl%`g|V}#)QbWLtOP`E8pa%p~%VA2YMcS zC8-$taY^iwt42f#YPqQ31wPajhei^@-(MJrxRmE_l?;;=lTf?2yvec$0Hd~k8-J?pwfAYc(U9Yq#UYW3&- z^r3QB2Pak9tY7k9$h0G$)*b9O?sfaGj=Nj5;d>C&A^Uss4F zDLzn6M7gmw@bf^gJ>1Z;peh&8x0vZBc%jQ#7p87%2BX4krPYe7w+MlBE(-vEp`LWl zwA;$~7a0j!2<}T8LSKz+izJv2cW>LMJ2;>pA@Gn+LAurWni$|g>mW?RcZn=w5auff zL8l-L79MYNA{NhpqZgf-fGeMkQs9*ui19o(3Bhv-fXGAD_&ZlSK$o7Y8?GUhek5Ew zFiijn0Bm>w{^BAo3gHeo4ArX0ai_r04-Fs8;s}9xm4VQNVh35xYm{upp@ng-%S&cYG|x-!m@&( zn{q+O+Yi7PSAR@8;PA^CS&Bz*d0(jGkzrLL9ql*$Q>^M)fgPTXA`wP(^6GHf3mOH@ z0R57+ppQ8dRsKG3Kb4xZEs1^@7rqsXLrgy)1MG81bFl~$a3hb|K9O54T~3g6H7mV< zd%a>{NT0>wMxr2cU5W<4RPs?zS@*n4-OlI3mqPjn04xanu+sx0#8W)*Sus4pp#H*} zUCn(`PCUZqp66AYbFfSTOW~pJixc7as}zfwscIoPm(LnTL|Iv^l(M2zFsgdeaUw&J z9H>{{p6DN60Dzc%4S|^rrX?CuaGg@4@U`QfYJeQ_NeW3Nfzk6u&)Lgb)^ z0wMuKm2kC6gfabd9|)2V-~>yJaLA1tS9+X8V2;9|gCpq}Lc3_R$a|0cVgBo?gH^Q|9I-eTaQ1!WmM-#Eat+Go|xak z<@iCsj{%Sm=Wu+F=tlq~{~IW)zbO$$73og(<0j>h7+_CrtO9$K{AU1qK!v{mjKYW7 zp3MBx;r3=U*zi58#k^dQP>RdJ^P=B;^d=T`>Tk2 z{0BcVK2a=2FFhI@ZoizNIXiL`7y}@(AatFNgtZ%Jp~)a4DATQUS!AFQ)Te zeayV&yrU5E{v#V+E)=pMRsiTOR6-U`)%d2_v$1e7@XdR_oNdhoABZ#?Mt#;s)x&Zw z0k6ax5y`;%d|$3Byn}twp01G9l#*&eq})&EYdE{1$^U2!OsO!d^!rzeh-xw;Al0!5 zos0>O+|rG5uxuoei)nVZ#oc`rIRt($-j1jkVIW14Uor%1TYTX*?GZgryAVWc8?OLq z{=cksc;`1lj|L7zBkOI1MX9zgNpB_$v6{lfHnP z!#ViL{d4Bbslf|KApFoj0Rq+l`q+N12K2)O!DDLcB^$hVZ@M<39Q@Dzx0}JgQ%K&> zllkD=Z|I}9$pkqIGi>mKa21j=>hdmIDDsL<9dhBAeyV8_J3XFx+$8>0Zx0C6A&6Mu z~`#~@aL=vig zHJSmo47eS$rF+1s2rWJ(CjjzNuH}$%PGw2aa3j*kcq12QYT1`slQ`$#hp<-Bf;2_< zXuG)iFT8^T00RH!(agskUvI~7uWW&M<#xUn47yt0n;0L{>D!pkd&e9En2do#jZB7C zDE^U*C^F)p=we7L|F{usWZ#GG;Z#3aucNe)`n222QMpLySM0K1FH-&rWQ0<3!PADc z*DDFhoZ_skQl6y|=1Ldxf;*Bvyi+g*3;-m^(fOC)4*NYAV(^cXv(OPSFll!v4Y`?` zN^VQ8@9{3?zMs!!8ZgnjFL5HVz(3GH zioo0gh8NnoX&hB4gs{n+3~n`vAW?9ekK!Ejl6c_0eaZOD)aY$CK$rV4wE$EaLak5X zYBg#*@&l1@DGg>+ry%QH1Y#|OGDur?4F~9x4d&U?;(^G+QVig;v_U5joV#+a#@`AC z80D99%TDKt@PqQTTUCmLZb*U9<@9`dpv3_Xq&{>f0s01nUcdv2!y^9K1j8KY6oa~d z6OMxC)R_30{4LJh(AAKFPo6nheG=&i57#{W@WTpM77>*0;EaO9ZUHIRp&JJ)+%gYn z#1D``Lm<(O2zXyRLSP^O@GGC$@e}v;HR<#m_&^VogRV{o^AX5wPKGrRjh4q)w}jbekMegTCdgPn)`rqhtf&nXIe?_M1e z+f5D4gjz6cU?rwOAL|zbWb~D5%8h=cgLega9*cSY*6IL2h`o1)T@-vbWuvB(ITwN4 z8O{Pxbp$+o)yWF2CVV$4y@37z>%bZ0e~oneP0$P*w{Sx#2@3}4BS8e27IUN+xu_E< z|5=%!%>0{ZFE^Jr_SqWPhU-~fwiVp1)>l-H0fB=XI_J2g-JqlFOU!a+wOgq#VhF5q zl>E*GLtr}Xz-NGh=S2;9xGQm_5PQ8OjlkcWC(0=RH4>orvUIakDK}FJSwsbdGRVtOmcB4i zKv}1;B$<_K7I=kB)(){% ze-h7gVgqOdJc&)$(=mtNYs=8;Ff{q3!feEX3{XU>{abEXEsIqL%+a2 z{{Vp3zhpBCHh?5@4{@b;x3wc%1&Z}`+;DN5oGoe1*8y>t=9oBnK{9xZmM| z=^(Dx!7%unSE>0L^Lq7sRX%7A$1~ow*?9sikWqe8dym-TawLY~p^$^M9z?nov|t{` zIT6amMq^`rL&~Lv6DC!uQC5^5jFVin@ZwB_@IpFP5pp1BaXz~Mrb6*108sdJfyzfN zP>T2$$7zLJ*jI>wQiDALV=ZWPH+wkvFW*cN7abt^^L>%*;`jvhs24;4F-kwa1&47g zfXuB`59EgP<(jw@xd7yAclA17tB?@0qr=!ng@Emh;~@I+HN7zM0j5wko}eole?T>H zu1nY(54!=gvpB5-S(b!pcbj2Qq;Q}2fieMR>%vGw-MumLu-?D*ejKnX?H6l6JmL2~ z|AVjxaDA}A^=+{SGy&Wo8#FKw@TZI5XHU<6Hl&Z0q5XpY?O8dug8%I-?*UWwN0qLA zcSb{c48fspWL=n56#(cmVFh5x_je$PzmbiP3*ZA$i!LKH0B}JDfmr$>9M!ZBu=ga! z-%WG&bNF>IG~IxJzmueY00_V!r{fw-!kC4bLeC)jr&1yCVW8kg_tK*h1S_lD{(dd^ zpgs~3$)_fL4?Yrfa>@900N~+c{O3R^u&Ut*d_ZfQxit~};wFSL2qxZjUw%mrxRpcj zORqoj`s=R)1%ZQ)c@$$d(RjC1;1)N- zbqeolV!U6XT<-;Vb|wq#It7hc1Z3J z{^7tQB-~sMRnfi;(RYaCXV(1E-dsS9biS+EN=fLtIa5oo1|c95{|e`G2>v7h7Ci>{ zSx9l-bis|p0pBd68QD-j;%I+t|3+C5%E$7}2>_WO1}(&DT%Ge^!~nTu=}`?0enS%d z_HJCgT0XvX6PM&*`C^=v>d4d=x5Xg5kHCj5AUB8GtbnZE7?p771346F&eCt9i(kM@?eO6eywu!O!}BB<#+B}(7%vD=4us4*sIFIQ8NG}1ab*@ zXLTUhjXZQ>N1hzc<6i49zoVcsaVhgwzJU0yn?F0k( z2S5FXP*_I1^64?2SqgIHGZ%=c79GT|THKEea5fWPW?Ke%`g@bU2;oKCnsqWl!v%xK znswiO{ksG}yvGZJ+c1b+g& zZc;#DU>(5kkagbj0#K%YDID?&>H~JdQBz?~YF(#VMf9im;eTaS{r4wP?D;SO5csDv zx7OCX3_j>kU&k;5uUHepwz%Qe=Rx=rp*k zU6n@+d~RplRlc1uQ8H9)01Sfm@l8ssD!=A)F4U2%(T(6&pZDS~9?kqPj@9gDrrRYS zNd>??#{6k8mdo!=XIV8jr@wz*%#IsD-1ss*ra6~SsnD4jP)EW1I@qB3wRA$m2csE1 z;t#Bb;LEa-62DOu&4?JFTTNUKhhGdHgToFD7MOg1W`J^_MxhM7qrw07{({$V0>Fp} zOokYhW_k-4ipaJggWD_{@6PVv!~x|6WQ9!%guZ;adgu3HcsCzYGIESB#+I^Le3i z?6Cfkwu|>wSO3$mXK$APG6$?~a*4}9CK-nHCC@=%h1n`Gcg!@MGSAw95HRq9)U`qp>7gv??C3HC4C; z1MCpU+2yQ|z}D6~lu^pbf0&NvQ6KRxP&ahpka7Mq0Pv{&(R4%iasoa(<3Ii~1+=?3 zr5Ef2S$=s$+rKGH!b4<-Q)ANr5s=sJ-rjaKUh+T$fq#uU@u>fVCj|t+k+pn*kyidb zPND^87UUe&rw9Wgi|)&86;zIMa5C!;dBrx1tr52%)LOV`4k?2mm~)>;EdD6z!T{43 z1;4s*6Ll1R1}#)Xesk(f(w8(hKmYuj&HOT1p}R8X$M2U*NEqk`7C59ft|C%j>)YDe z-R=Y$s6d!e2_ddV(ksfq-U6m-kO6x|I~|M_82F3TtL+CA6n^L#*svFj&!PyD0Qq5H zWTXjd0cah>nfNwB%iwxB%R^Ws8=#9Y9fsuznD93~zF|X~HDKw#W&C@#Y=mBE@z)|S zZ{fTI%vvw!mJ81xbo_!5}r_&&oQndW}LCDQC<~H&TCIiIkBdedX&b_v8Qs{yp_Da1XDZ;%tt8y4g(* zMO~qMXuP2i{NUECP6$ zG61;4fJ3 zQw{>+XZ~^>S%4ouj4Z%bsT}n6btwI%Rh4br0pdJZTu^JH}#(NU&f*m z1K%a<8n$~ov=PKbrKZ{|u7+!7v_Twk-o5eRR}M<_%ea0+%# zI&i^vAtk{d?nauoY)SaoEdJ;8Ed1kTS1ZZbn2#8LY9kw1$qM&34*)+|-!3s&dq5n7 zlo4mkvQR00RS2h#8fbx`qq+!ycIVItU&)U0DiTX@cPmu-AV(Q!_}z z+_}@bkQ@T@_p#4bJ3!NJkx|HeCEmO8goFb0->~4Q+TN6_<8g2w-B~`vjPDR zyVmX8N9VHDpz=<`J$)sF;;)qoJ&g^1TJidUjbWCcAJrjnK*OUAVTR8SOR0eX^24SY zn_!x_38WlMFEqS>l7(l^gc^d!4m{SZ;d^Ul5&?NOOlx#gP0cgUys-0pV>_3>bO5GZ zba%W>18`JdwsglR-03`gvN~*PIR759xSOS1xg$MvUw(bu{9?digu0^|ztCtLtx@@-{=3)g=AH}Kl1$9AMZLu~+!f8dA#g9^uLO{14ED8Tou`vU0xdc0Q@A24-u+Q$DqCDLA=Lg-j>a9MSM)wpu729^0&2bGP42+(*=>>7Rj7-Xz zC}8bgUc~K|6s+Z*UCuzcA5E8nr40-EWSH3|{}ZDy9T=9d|1A` z+zGr$2xtz-JcRZ3!T2Rsf2XN}s0&V&z{bGr0FH0wRy<7n!UtXDIrsqvX!bXl1>~2z zkUaSgx)OL$sV{?0KCt=OO-OvhE)ZOS?Ak^4=Oh?gVIl{06N6CaN%HvVPjLy1R2ZY5 zIp913V6`yt%%q;@RBIIosx=3A^Dt@PcDj3SHq`;i*L+oW z%iRA*B1!p?ecjg;)k)N&pE4lpHDzimz;l3olL3RW!pvGSYjT$CFf*YB<7o*Y@EM~Y z*MjSmm8I{r|I7=QpoWa#ICvqI;N>s@F2qEjU>I6q>U`=}=O|Qiz;0f9IK&q*3Nnv(EaeK8Ci1i2#(H2dpUfWFUxDFVX<-P`Z^S_3uz z=Vo94Ug|!$i%5mR(?n#V0uY%KGm#V!s>6{ML)Ir@xLr?;JPzg;vG$U3uDvjtgf{>H zi*6nQbwc*u+Vj*$3i+yhU!ffP3;^s)CmtMushGT3=sVKY=gdMP8?mxk3{V3zzLxO0_Pj3PL=Odk=VgbH zi>I&bg>F>!2|(l%zFA-IQ@Dyy{8zXIR3cUuisdXeg$MCB>0aaCMw7q~Jpvm5bs7h( z`%xN#<1obR&qA?J;SvMXVVyGZwbY3@=W<$vivf<}nQK7Hz-bOv9^i(!g_~c=0N0jT z;GRqmt~3FLv9F>J^B?fP?B0!|?O;{q3COalWPlm0VhC!SzdaW!h_I02@2&+=33pry z2-kp>Wxx!=pSM`}hghs97zU$j;P3$w`?vrk_UYX-WLW}0y-g3YLC(Tu4){^X!}h6| z4*~^03fExF#EB1nq3z(;(@yH{$5Bbvo`kQ9;t-F&06-4E4@;XS0M3~+>1Iqzz&wcy z7@W0arVP3Ej zLF|o|MYN8BMTB4R;*IVpb%WU5+~R8wmz=ZdO;K3ng$V=sE`N}f_7cC=HA{17)**-k zKw4U0g4r>t6`+z}cXWlD);`j3IJIK=j&a@9VDBK(*G0;qiE=kh)9U2=%d5_ zo5a-sK%*bme;rXV=e$8&6jN;JpRsgm>aXrWx~LZwBu#)6suNBhF#(m{z#|4g>;xg2 zjI}cz8YF0lO7M`3(~V=aiLmWWCK$jSwt(l0aZvjS|A5iUcwUR5F(|~q9}LcbCxu{L zU>r<=tjxL0;E5w6sp&&2KHYby-(0jVXR8dK()jGWQ)<2fzb#Jqi~G2o?a(yZlzy&z zx1ykO3%_#9b@vH;lCw(FzeU1L;9{~WNhQ8N8t8I zMA$4T1VFf)EO7bqgO%yfEoozHCt$6XfP_E^8r#YboBsm+w!QeFDIjeyyY*_fgpk$J zfNg_06h`QPziD}>qnd%oaSJ?pZCoH|L-hQ%_4DUfB;#WP2t*_Ro}Oldp%5Ggq~ELY!`{GzfaZc=ffPk<8v9-|4t_K}-TtG@G6*u5 zK=A9&P>S?L**FNImwj;M3m@7g>gV+zdgG2kw-6pD0{BDx17QMg`lqH}H!=SHhfT>5 zxMXtXV8Gv2GQc%2(H;{Bh+5E7r!GBnY3=z>7Pa8V5G^2= z>4#o!BQz!izh(3b58mipA#f4hx}9WNn~<>6;Rl_8i>?6fu@R6&uhWq-14&WoOl6va zKbT++URY8CxbNriOWU&>F3r`<`&0|u-*I%sMJE2qLfHhBMI2 zjL=>na{RraH0XZXVERL2Im^F%!>Bn!Mdt)MS)Hd${`hemy=n8OLi90zpf4;gC}FY8 za6wGoYjbH8nWL_fq80RSM)1p<{c#1@*1ld+2pOO}fzCys65@-v&6}aZZRWGmc;yG= z9Bk7RGQ?dH*9jvGj4Z#fni0VWKJ{?y0lPvzjP2jHC<6%}p!b09TLkt1tYhGT?uta{ zKV*r}i&P7;NOFjL(N4#Q1-k8Ylp?_axFOizhKNAO)_{V)=mn1SgN7u5RAeALka3{I ztEx!4(ij}KZ_AcNHOR8Ta`sD5KOMmd{EqK>POuj;Fvs9mnTj7A&_{5ZdBFhB=!w%X z$}#c4F1B_5bqpef+tijNMLC*tx23CCh?2gUQg z_QzK~oAxmJ-IM)=5m-nz)jx+Im{#qY$pAe?!jJ``8j~$a>()Is>#@h4ob|}eCn0_4 zc_z=|B#8(Bbtp1(=95p>)L;}Q1a|Fg{)E;nIRO=rx*YUxKzUdqf+T@n0ov|t=<4oK z*RO_M`vMhl?`yZXc@w|mX-E_crzF9+Eba_xL}94N!ut53;D4=Rfb+uU*XmWD85+-f zN%-W0aWa;3@!4xs5fl?xh@*}aES=qm4BwFZ#aACBfJe1M3`JSK!m|cIFuf`F15f!1 zcuLYQc%JOfLlf@}#j&unV;cQ3?!qK)|LW`UE;ZqZG-!0TOF>m?9Ax30E5<5q?RlWf z$XZ4RuFXaD8!=CjsIb1os!iUL3m2~Q+C!ee>lbtql3saXmvbmq;9jD71+MbI>9z>C zbk@<#h^#&myu9QSHJ*D|-tsuoQ@3>e?&tsVbJ!H2hQJX>6*!k70}EC~0DL7zSC{%? z{%w~HhGyvX?Tgynlnw&8UMF#*E~;MTSdQhyz|EUoMX0-A48a@?m>u2{v8bK2z|`uZ zclE{;46`j14|6`}(z@2;iSh-StNKC{h>RqZTBVfa{goD9y>u-bGKB^3W z%gO-Q5UB^c17;PR6QMN)KNt7Elt1*Y{m&YKkFy+|1kkm>#J_oJg2Vhv)C2#Uw~6)W zc%J|`52#mdaYRB1-_`^K3InS(5Mv$qFexC-f#2fu;s5>PUc7u%J|Qu(efEEP=nL?K zIr?zif5?qkJ;wyJh8l2nHO<=4Kz^-B7?CjQ1|a~#1Vb$ZF!waG0oQQ)WacbT#fNLE51)GGE!>9W>PPv*7%g$jmlOM#gCMkuhD=+YJ>xnYrpKpl z&i1QKSqHrOB^uJxZ;oe_>lEJcvbfuth<1W43d7pGwDctb(Ad@bPDiW(74&RSljxf; zOfDGHK=fF~ZAeGNNb{*RRf>Q!#uyA4L_l~)enMZrxgN;_wp5W;fMYA;VrGna^EVa% zI3<#IF_i+3TLy{3;6|S+cl@Ua4PB=n+DqMvjS6Tmiez!46=8yt(uLtvvIlTlYX3ZDnTdt3&B zC)Z=r3O(KW(onhjYiM8;sUzeGS4zybcIrJybw6#fl{9h#<>@JXX#NM{Ck#YA`Vt|aa{<>l6?!IC zf1rT4id!f6+xpVhmtJ}av+>NCxQ=_0p2wQW6EFPpcbcixz3iK~%M0y-(VG^T0qdlH zumnyOz&$N-8^@|(!CtLNU(!HS1~*{rYw-q<(WjB70FVEGeF&b74<7u>g-QIYe|)SX z#XS?tFbwxI1Iz9|%(4zV@S*ToCc)Sn$jDT=Sm>N-%>wgNSOQ~Ujqc~%(6o?rmrM6C6E`71Wa-CyM2WBtdW82doEUg7{$z_`7LY(uE9GkpY8S zX7+=~o_JpPUT+@QsJS=Zs5}oIn56_k7limAZaMcac;WIz*k>I?9(f`lr4S`zDb>pP z&`IP7CtwghCB*FJySKdt)B^BB{arX-KdK_55BR4ZZ zIsmJdP5ZRxWFw%0pr2c|YZnz_0O4_#q8~Q{)F502Kow#d011CTbuE%eA=uw0g4~=0 zeft9pYw#Wevk;Upuci!uguiOxAH$g|f$kf>nfpo^Da2}Uz~=# z#0P011d>M|nTZ2oj>4yQy!HJZ-)Sz6E?UT)uoPg{1P`P&AUlCMx4IrlB1n&%(U_Eb zbi0YQ@}cO#td;UX6s&VX3@M=p-cEJDswT+?IUUg%}x@ZHdQ z(}3Elu~r!{t!WP!qc7DDf+A?)aBK2PcZfQ+rmbSH31oWak=>ntM|8|@It+hD1)(!M z?2gI@I3*8^iqJLkV#{|CNm%}1EHlPP2OgbBCP3CCK@3K-QM4V2`H3d=Va^o>8t#ZH z0zl}%&CR9Ej*`=DNM9C=Wp_;BJdscS7RBSct+Ki778LBg$!ico-t$=ODL;WZS-CE7 zzEUQZM9y=U?aewKF};)0Apm?Fx8qzHLjHZ6BQbd)IcNmZ5TrE(Q_>Oq)!PZ^hmK+d zg}RPuXDR}@;ChuL;lWhES5~2eVR>SJ1 zB&6{;vS3y_5RfhyMIrdC=`sVMg@1owDJD!X%Uz6~?m-j{2q4rkFfB1m!g|*B7g9j6 zz_ol@i9V#RJ#I$F_YltM-X7vRRCO-^yMEX;W~01u`;8;c(d{^O0YYZzh5V@5Kw@53$sTk1>|(sc&t6 z3Mark{e^jNdo|IIqD4xKzOdP!M;>iRH?Yl-s^iX(BqM4xm|OG~1H zI)0OHx-(>u&PdsBNp>&gEv#xUAqnQ=kDvkDjly~MuCq}2Ck`~|h+<&n;`dwW9Zs4^ ze}CE(b}&f4m6stNf3sv%m1Z(uCc+i?jdUDrEFGpG(%%vP``7_qylB!lB@yJ}gfUM2 zN1)3v`5FCaeQ_ipg^y9*0k_i^JtTAl18jFda&(3RI?xO^A~W>Jd4XPZR(7en4f`}j zyyVF1oB`dJ{C0*Ooy!&ad^eYiLpnCS6`6F}9M`^>b)AYp>PPXT^rpC7bM%_0xKs6> z2LJ}22pG*-EXS`_HJrXjK2B5Yg^qvE`icx3L}PI+*obVb z(WUF51fwPsG)pCM1i*tJf}ntP&R{!u@bba5F&6ka7z6`VTZ?1kAt z*`A9);NQwUU3vlsMCvI!;daUc2<~@D4Dgc4UoyeGARefkt7Tc~uiVYY)%ljNuMC0} zSm-P)M(I~I{NV8|zx&{?eU0=_dNaK@7=gWs#O&J?0(Dc(uYdSM!e0h{ssvFUv~p272n+lOg@i!P!Y^&5 zEe7zXkc3%}efzN|`R~^B5{p;?j&@7 zeSMA5Y+lgrkGALLTow)ER$ok-zJJR(uepyz?SiA36|+hv2ilgSSV2Sdn{vX~4#=rE zL7oB7DfeFgHFxF35gj0CTaCQZTkv3&60i@R=w@4?-6_WwIO;LE>7^wUdYlH`n2o`j zgYjNuI^txP@a;i_+H22OO3?C)k~kIw#h_Dwy1>u`lItkIS@C`PCc?>T$=9dkbuz>jFI zQ52WUk8lHQ%meFt^2s^e{!Px2@kQr) z%eT_c);R9|vJ607c-Tcl+UVFTW}}7y(79T@I;v}BKECy0Lg7(j>d}5Bt#&{Kw%HGF zu+)POa6|cuZ@7w3+GU*^=%3V^ajulz|*dT4SRlvmcm~h`Q5+#;Jb3d?BWsd@l%0+$V3h2^G~S*;}wlBhCaQSCm_rOU_P)7 zoTIGhP4Owd)YK$LAVcZ>2-TyEd*#RM?XzzpvjzRVH>U~1=fXFAF6f|`;kgX`UJLQ} zH9j2^0P^e?WRE^*{1ZUCWx%s8KY)M)zV9&xMqw~dFOdqY`FG|T-T-s#edN(cpLyo> zM_+&D_17PLvr)kUp@PH&oK388sHE*+ zOKseA5dIVZ-N}F#0bl@Ki))ZtTGB+Li5KS~bv@>krhtfo$$#f#{uX$r9Q7>F>oo^- zJ#gSxgybV9Mm0%t{ppge!%Byv5u!@?sGZZUND7SP_hXrGZ!}>lNQP-y_{%q-4hs}J z0Du>-U7Wb+Ak^`TqZiEuFVYH))gTVuWP|3qPoDuC!u&^yvz`$EIE9l^qClAPbp)Ky zMfzMun4a8to*ltLz{X;8KJu8I#-~2G!n95}10aXozPMG1O(tW%LU!Xskd2u!hJutJkqR+O$#=>-z%!FPTa4c z0k}~^aQb%!@B;wXQxP@^T+bPJl%fL#Sf9i36og*DZouEdIKLG7z0U|!r=kV~#xY!S z!}u+@Ao2lY6&U)*wpbdj7746%A;_%+fVRO%23h_GK_LH$RGk=MFggXH^?BU*$9D;O z5&X~{&!pPS>M~snV@yqx+<;{Wyy>-H8h&F52^@Z4c1%W&@pI{1;m z?=@;D+vR{!^+!{6Oy6^!oUCX9AqK8s^V?+Vg~K$=DHzY#{>cHTd*Bm0OaS9GsUQJx z>r3kdkxQ0*?|U^Qz^4WYfg_3uyzB|MuDeHkt=kwzZ%pN*B|76eZHGxNzqG|}(J-7K zFi773J3v}g1ly^PS1sN07M1|V-g)P4#GL}u?)JVT06g14TV5*_kR)TYYRQN61At(M zLIQ`aki^1|pB{EXeq;jP34Z9I*>-3s$sNSNje&SU}!G*9**hrG@3~0Z8m2MQMM3e=*`~e=^XC)=YfIOnT84g%ttv=TzvSbEnm=I zz`QKtxTQIjgEYGe&Z!AoGzO>BVa~wOEZkhasOu|67hGd818T~^ZDj~-HwZR*{uKa@ z5@m>hn1L6qVj_obL6*x8*p2Zb0wY@pf5gA{#r=STs~HSkhQQ1d9T@08-M2ds(0!P@ z-wy{2N8np6#y^6eUN5%>%n4YJ@oP$jCi2a9GBh9K^uWxI379?ToPP0;3mP2o**(b# z$Q%TDVYW2H3UKb+LCYVPJpNY2eXll>`foPc!sEg%BQ0_`)9REf?`q`|@10Fna& zFXxUC{y+kM^@Fz_1^zJ=8W3pw+i&(qBIvhI1h7&4m=^>v;BS94Wlq#6%)v~@FK5C)6KP>Xl5q^9@TtX zoZx@q+yW-=o2+l`Mg7Mw8K6CBA+C56TAVNU#5q_L2f}@h8AvoR8h>SMwrwu}P{+Eu z>rlLlR(+2@AHfKPk_jNKd5Xi=i3jj8uQ-=dL`ds?`1y#%BK<7)!{r{&FtE=6XxDR} z$8`xQUQX6e+X2e)h{s61$Nt8o0dqsp=7uB@z?WAkhxz45WOE|S<+_1rVQmosYzYP! zHo%RJ#ZDX!z6g8_%AC#}ft`1qp!TjDk++ zCpTc(37vJLlL5v($WFNcWrdDJtSWB*(gjG?bKc;pw*$-U{7c)tWxDTOHdwAm_dW37 z0rNkFL2FP3SU$6dL6v_c0{;B*M^Bts03C!J&=B|l1H?GI*vMAKxBV5cM-Oz_0evQ= z=2Ljx6w<>SDhAckd4+URKSc6wdJxXU5hOPg|I7rpry==Vb~=1++RO|BB;oNsc{7-lX?6V;n%x?|I9}w_=*b#%! z{2dBOc;wr31wL7`|ICS9$Vfm$f=tmg#BkaL8B7J~us^fM63AB9l73F(s<$&b&ogkd zFUF>s_~P#FtYLj15x|2>OI;9wc?itSUx#L221EA-Q?mffM1%emjnE%C2fYa_BOc!@ z5C%d`(*APC;-{Vvzv`6@us=1V(-^34+Y#B&@Bv=CNSvdqj}&m6Q1{-L?}3$yFy+cj zfFm^zDZir^NAaHxcSxIg54@_8cfrM=KXL&!h8w!xa%s%Bat7ulFBH`Pk}F^73J3jF z0>HRE!~9EKf`@UeH_9m!O9L)y%zfFWePWub)e~Gw1F~o%zg7aV58Dc1j7c{mTqz0w zwIjqIZxP}ai${(WvYt)uFO^-*vAt9b0oeb3^#OkR1>p-2`=NacqG$x@z^^P)HykSp z5yl(g_;w2DCyRyB@B!ygyUJ&7)u#Xt%>GyO5!i?w+n34D!;wEmb%+PywIuc8XFi?Rn8U5x~ zq#!ulJ{ElGGa2$hL`#T;k%KL1(?{qFaC1P6_Jq1X5|r|% zJBh#p1OIWb{>>)FK0E~2QvNA%?QTTk$C<89cvCb?472@A4diW{Lhfk}>`-n#+cPoc zb}&w>BZWgNSkT}H@#E;Q_kRffGYWQ`JzMTZ!sEsa&cD}q^CrNv<8OjDaT621hzkG| z8Ei*w604KO=bQ9++rO$YlYqGsyk6h#Q;aKcXCSd1j2d;l zqxdZssp|^QBRauc3@~3g0`qy)D3}sq41lY64FVWsD&WiNWH`u{j@UexYl7v3Aq1}8 z9b)i@yLVUI`)S}s4L>uSfgGyGXV^W>PC%~ zOvIU76CDv-gA>$bo+ z=rIGt5PbU}6u!(sNLIK6fGey6#HSIC>hV{Km@{Y60VK#^MhW-oYbetM0%8hYDH?`l z+!4*CCCzWi7DuAShW^+L={|JMci}`JM_etdIA6b{lW!7PecH?h+4f5%?-ue|E zp8)^LJpKy$R`NIhwNN-!!MO`WF)-6Bp=vHIl@U%8a4^7Net0I}BLvn0_%;jrKGzFQ zA>e?EYHr>vE+xL-J#%OOgJTHuU@8KKT`dFg7qd>lvbnWM=iL2~T_M@Q!@f6rfJ5td z(Mp)r&`ZCcrAtS*2;mWA^5Q^a<9^AY+YMjsy7Bf|sM4NtPm>w=by0J>g7Te%m9q*k zet-&Tp=3m0sWF(rSX>|Sm#`W}_~%@#nOsgT;T$8f-gq4PmstlPOxh8m$E1Q1^i_Tt ztsy8*>e0EFFz9uc2Vkjx@vaUH7Q39|ZjkO@E&cMjf$R;wcFl_H>WcoVl-^oZpao=F%`W7ie)fYpf~9{n2#%yo)F$sr znTIu?V1$oZ4F~vJnyP5pyhnLo-B~J1-?Pkzkazbu8}Q$P>-~FP8kmys^M&Xi24t#a zlZ~v90KQHEiGLFf0e^4=YY6rLjK`?C;FE0pU7$3W0`%h$d}!+_*P@>?4yF-UI%uk2 ztb%6f>7`2wdro@jlR9%;%D4U6>2Vk!7TUkUz=WbpE(ewh`n&+}eC@HvM8F?$3ch-E z2LSNGiWNk^JCO!M)Z43AKmy>3H41~?Yk^-nhJg94Al9A91K?hlXi_-?{M);-JP05l z@QC(uz&-On@;r~YFYZ@pK541g&G213}k1kaan4t5U0(F_8Q8Ue8h+>8enfS;eR-YX_brOVq^)i=K13LR!C!JanCuH+3{C6 zS`I&2t?Mt3zun6cZ3IWePlocfsjgxgH;|b(sRGQsiFb2n6$+RO_~TO@JK9qSK93?f z+l1%1@XLkoO<&B}4m{MCrKX;ZOK*DlbT!9CasSwz4$fOg{y z!`IbAD?fguDURyESzUu|2!{J@3tm6~M|&2)LcmfaT3!iu*1)kHvaYVKSLyIE{BG%F z>fV+>km^QeWc5VxxT=m^`x{W$f3@c-0tc$4K4$Y9a1%w9Dbb)`bd7=cCUiU%s|jGw4X`tkERfYyts^ ze<=Ut+Ebbs=>SJmjt(>2s)1d*q=bP8X0W44iGb0{rN3}jC*{59Ut9EJE{j{RZoB{X z;s5jDFGk*YUidlXgA~E&0?ZtQm$Co{3+&DsLHLd`=%9aon-Ke35EHR(AgTq?3eYSt z5)t^=>Ri-Rh(zZ1U|vMwhYjS?rEIJBKdD{J!1b!UJbZY~n#0itT%Qles=pMG`1SP} z0N%L4ny#zDz^m7n-#{yz$=`()iw|EQ{S)aE0GbUV5g`Cjv4DFE*MNMiFexNZ>b<95 zLf|w2aN6{*S(EQuX$pQ#2?P2jW+(t8`SWKSj59c7wWS(}c}KD2S=A#)B!02}g-O)S z)6L=k&0N3%fPO6DbEspG|AGvxg@C}dkT=)xw2^T@kHDt^fS-#2k^ou_UW8?38qnPwyASGhUyHp*Jg>P*4gM~=+Q_Ku){w{mCG>Tjqo8sdhu zB_sw8MHmd`;9R6T_i0L&;!g+Pc57gADnPn7({9f&e~A3gp!mitQcuU>|CrR!JLzZ` zf#0O=!n1k}D@YGGAU5SsMiwkUgWQPYPiX#43cw};U=Q{G^`|^4?gJf(<*JW^W^DH>hA9Rdw(2h=(bc{A z63iry_7+gTu1_W|1JPjJpKc>rs7w?HSM(}VwLq)m>DQ~kxP|QFzXz=a;0A6~ClY%> zIR7^BL(^cBTS5eYC#1NbY;CE#S`L};daOd395AA;2Q-FXDLX{T| zAqW6L;a{|YbSLaX95i^~6H1}U02BQS036jOFh*eBL*xV*-D)MwZqdK3TeCB8Rtjtr zh=4E-AeXWm$fXdu6#2HR&&&Xe!tMqNc)mWn7t0iEu6W*&FbqP_A>?;Ac8CN1nH2E) z^&P*14FtHi=EC9nd7J7NGY^YQ4#6h7mOmWmbBLliSJubE-lzX4zW^MI8 ziu-Ruzd`H%uGk&N@pw?>!m$AS=>3ZwO~Y@!!)g@(AdkD!wP=>L{%^)XrJjU6;X>Xr zC$nz|2I>55KO4Kgp%m|oGx1QGhQs})_M{=@4eIvs4UQf&F=Fdta*tpCKRkkv;Ryi8 zBM4#E`7r$Qq|*_!8k7Wj3(v({5TnT$IcYt_`5JAAa2h<@fvQI2hKuun(yjVq9tH!f z+PxcLs6CB_7yw{n@|#ubq@i@vo*wpncu!aL8Oq9iq=0H~>sAV3qT=YF8-tw}s5cVF z+tn`2tZ*}2Yf44%;kT-~H6dbZLwftT@U&kY!CE3_3&d*TqP;0qanMfdzn;7aE_8st zijM#QIRk?MGI4-v=v`g~sv&rQL-5k2=?|FZ;FnwiYJlC7PQjAI6nNqa>0bf#WzM-h zA5OUx7-l%6TE5Kw{4xk8UkLK?#FK_!5WtBi0eyHc^0y#w1lb)TXrDmXkDd@P!@mdf z9wZ;|yp2(O6ec*2zfSt|d85c@-dF`vBf%hXr_)a z`1=0KCtOk;MMm+R`oLqmSC& zZ!5e4>vA$Uc(CNim;e1AUwxIcHBHkj3yL(@@|J4>UxBGtILYQXV;>QY(3taLPhTQ@ zYUyXq%$)dQ)Mw^ATq6yJLKq{gtZ=9xx#ydR08p2Y@eJqagmWCAiDA;h;9H(>28LRY z9)bWs{Fe^47ZMl*B5#oZ(8xzT0NcCP@2r=`Mjt{j)Uq;;3qffBxi9Q>C-CrnC7bdL z>jpV?z>W3B733J*A20-}^`UgJB&NPTg}o2~oflIS5pfdWspgrO zc=n{|i!%yC;1Y0!R)R)9n&T>M2`(_eiSb2Y=HC1{xGbgPvy~0yZ0j_+66c76M@;|B z_f#Bbh0I%QlJj^Ae&=`?48(xGx0>I|)4U@uB>9u-|dCPXvKhMYeYisxKyu5$^ zqD6qgT1G}AQng&+`!{Yp*t&Jsz$*V~@ew$5f0~6k(>fgHeKxzc1pq4YVDMr}0>tLf zAzG}>_z{tqhng96mzdxM=04n~O8$E9QhBN`^0tRzQ>L;Nffb1*g#N^25 z6oLi#%7Ng;@kGyt&f4=k)EBLCGLqnJPS+K-zi|O5#&?!FKp-f+AY23j02PD(*lce$ zIfC)T_$QGJN8$0u*Ww4CJW=bn;ZJ6e#`tev4v0>PpTPj@(C;BXF!qQ2(f{EG!l1X3 z2JYs7+^Bii$JJ`4{t5B6VmQ8iy=KQf%d z?L2W?q47eWdxC8y0O|yy zqp$A1pS&y=A#Gv-X?gwvxzSEDB3f5LOA2Uw-{-0N}6RqXT4H z03i5Zv5p{oftuy$QN~~u*8mNbho#pRY5{L@2Y7?;5Q{(~oU#Ey0r%qt?CUe+AuNoH~-A`D}cibHvrz2z{YhghiNhaU@pusTO@h-^kU=pDHLE zik>$X#?AG`{*Pbzt9~Ye|AwggV>15Pdm%6cJCqJ^R<1WK|IiHV4It2tF5vN1oQydL z6CQAXZ0{@71C2qj5{bORt;e{eSvDd5&E zxCN6KDi@k~hx-K6t*%~G5P?Hs*nH$D7kYX7>0YbucR^-_Iy-a$Q7BAx9EV%2ZaIED ziY|u%bQK4saXzN;+2@YobLU#461^hAWzuZSsI0L#*vQdh2yd(oc_a6moOydR0C#T5 zOJSIhpd)ZooPh%Y34jeshEX6E)PPb$yF38_Ll6QI0{_<@-$Alu)c+*w%c?IUAAw)x z4^O@OVPO^mf94fBfnT=eXW%^iX$jcCqYSLT(TW*vVD9|#8kkT55(3Qt^^o>O4Dgr| zu~IA21HH~mU2w+0jS4|6$`Y?^3I_D4|40hI^NzgdF7Ny=;sBEbut-%)7<2K@0PEu(XA>I~+FPZbWU zO$Xo4n}&4^HstAavTW&U>0{mxk>H?cAkKjgcma7cr((zSXphRUioiNN$!-C$K=eOS+yPNE01(SSHf07vG}f6dMT$)fPg+36viDY)e?+h=NMM z|I8FH?|k+KkZaGl3XM1oCQ-qlfZ%{lO%1AJkRgN|@S`kWZJBeS5sWG+%N`}eyuJi{ z_q9)lD+MGAmAn6M(Ta#P{@lQ5ND9X7odeH0KiL5 z%hxY_h|E;Zy=U570`TxxGT{$6h`*J|aK|5x4~{o<9NT~Mj*32%1x*BuWI$`7D=SYp z6@lSc@fAF7-2&=8zh(GiZ)Q~T&Nr2N!9bX1BH<_8;Q`{_viv!j;ADRb^$U{&^Vi=a zZy5j+?v4UAi_pNG3 z2uS2pNVNTMZ9)9V@h%1n^oYDV!p+lTnT>N7(*f8&Iym;=!E*#5yeYb;ux4oib3p)g z2tMm)ZpsYC$8KP$WipSjLr~`^fl&vXR(pMHLSpQ_9vqgD0rL&%A3YyB{6h7D>j#UH z+EdyzoFH8ADFhI_kN7t(>5Ck}kH>ur9@jX`zi%gnk`vC08NutwBz>*;uUzpbTN>+( zfSrxh!qgE6d$;r`2hX*$M#sj60!jB3hd|xK4`v((HR4Ezf>^Z2KHKVt)Q76KGUKS zKuxsXx|;x)-F#&O=?v?$)Gr`@jU%xHXo@%(5J6NTCH%u7xT8saI30nt23)O9)@}lz z%eLP45InWa18q#V=>nX@&%S(2eQ2TJo~#aJN(7K;fDwhS3D{SVEDyTjiNav8{9A<# z7-iu z)_^?a;;}JO5d2Hag1pJd_bfdoUUoM~rTP#Fv;w8@2r%62Eaax1Jw_F)=^p6g+$!2eaOE=1ZcI}D%{7Qmv16r!G%hI zz?|xlz9H!4m^~O(BX3CT=Lgj<qrmEFI$hrDcF6OVH&};rH5uX%;|bC z(GaGgo+NkP5)c^czqkY&`8#7ZngS7;n({P|Qos&9bOnyb#g8O3h(t+c5=?3y{LO=$g8UhuE>PHI1w-h?{qSFpcZ6dNz8HvR_e4c|xeF!E6Jd~$@ z20@>HH#rdcn5JL^0e)Zr+^9%=?ErV=2jGaox@3LdrM&vtwMXfxz_6ZL7rd-0YY8RCimy-26tX5rgA=2uQND6`Bu zE-n1<#v8x>!>`}4`p+@YWy-`NCwxZ-5C`D%fjs=RU~GWEo5eTrD88A=|B7q&EBdsi z<}v`Vru63i8%KqLE=r;f282%wK!P9;aC5Eb;bkU9FIoHI1zgd0?p)f6wA5Wo)farF zZFPtN@fS4XQsWLnA&i_IQcHitzr#5fQyrKkpGG;Hp;21tj?Sv(G)L11EV`%VT;w76 z-8~&bs8_k?p38`EZkNE>4&V$nm6edS$^G6P=m{LZA;u1=5rp6;eIRDunVIw@Wigy3 z2Yh2Z@Q#=U-Zw5?H2!`amlP%@-|=z$M~ipkO}OQZk4)%7f-h;kHH-6RQyn3pt}X__ zM)={LVjPAjy0?n^u~?gBchvrVA6RwbU~WDT@tUt5z4@?$-d+X$^+pMjjKHly23cY> zHl|Ysn?b62L$&7#nUT?S+f_I`5Hs-c<6wUWLng>Jxr*5J8UBvNWE}CSTshja+!L`j z&V%WRKm_98mK1l`8Sfc`5YCt;eb_RRe>9|mVAW$L0E8TRDgTgtLo zmw2 zn=T=nLj8QoSy&E&`QU*yFbYAP7mdIti;@t=O_yjo&k|10U#c&}zAOZF<0dwW%#+E4 z-??}(&KO{3dR!QN`OC*c{t?9t{1Xrm{38AR{U^u+&(%`MED#jot4y2^xQAcxmOkEs zC0Ng%^VxGx=qm=k~W6`3c&Ol%i%=Ru)KmcUzB96h4n2O;USy^jaiYddsTlNJ)Vo=$* zudO>;JiMb`t&ZT;zHo48;pbT4d}P6l40P$@q5j{CgISzbL|=Av9RK_U05Bp>+h@|; z8x}X&fzj1VIkb^(Xei7fszAyYXQuvN#RBF9Gx|xt&*dE<-?$2dfcK3mK>&eV{Q>@R z2oBV-rSIMwq8kUY|00BQ8~+$l+E{`BvQ;^Kte4u>e4`L#_4V zZX(r*fe+0G-nGj#%>2oP{R%_=|T+@w1$H?R2S3c8*(6 z-O(S`um6JzKi+#!4iu5UGGm|av*q%FtX2Ns_F#fyfH!&l1)5!!v!jNofHj0aAs_=$ zZ$j--yvXJ_mZkd#PIC;dg)%T)!kbl}$r|;eKUA2k;H) zFp_J}1>uV&AiW~o^Zh>jaFR^7CokOZlXqD8&-lVU_b8EY2KmDrj9-69=M#M28yy|Q zJVfA+i~5aw?lt$*F@!kSG2Ve09#e2f1D>NOWEW)}1H`@#-h=Uz>n4eMjn_E+e*g6Q zIxPYV;zA986#qe7qGm~D9;gMFaibMZb*}I!*K;inA*jW?pJXkOh?VlA9d@AatI!Or zsH^Oo9B<0fH-~7sEFBk-;|A1oZ*wKcSJb64GMe#${Zb=l8G!jGJ${huIp>SO_gT~e zZ;|{Za{)UCW+cVpGc`wcI82`(Hy|5-soH@f8H?-U)vJ@*^vV_V%e)`(w`^)pHV7N_ z{xjV`_I$XfunN-vXcZxHVECf>_ho?b70#_^8{;5)0(mY$utUr>uim1D+&QyHLS2%dED#8nfrZ=$QZiY&S;6?KbxPO5gp1N>Q! zA#k7C(bMCHrdMo$01k+0{~2;??h+-MF|7b}4wm%KC*uMl_lHxlblb&um^JcS>+7-JQ+v5aU7{V~?@Pkqt5-t4 z?|%OJyRU!#`RDJRZ(_XHOTX%^8+*WUA>dDVkEA6tLL%VRtLJLg13V4@0I}bz492Gm zFg^wRLGM?>q4!p0WF(Z?1#%{Fzvzb3X5xtPxZv#DoP7lTy{8oC z@_?Uy)d%0*) z4V@iqM`AljafAcz*EVpG9$5QP0gcf7+RN0$Y!(1+rdQ6NutKSrb1<0j^wEQF@96KT z>o5TF@qT2QdS`6{$gr4;3QvHH)sW}*^DF_?6L16Hbu=~Jf9q3(!Oj5!8Ex>D)^G~O z*YYmsus>Sja_!l)YXEFdMZr21bHMc>1%q^K1&0cv@MV?jqdP8)BA9^b3ZZ)#Bl65l z{OY-OTtonXxg3r!(e#) zwH~lXW1$EWz%G(up8oI@Qb0t%R7w64V59Cgr&KZ98ElMcrq$$tTKzdJAtGKZRj!hg zSgdcjBKxud(C3kUq?>tqKOXiYUl*XeN;(4@*guk_-?4KZ<_L zD}q0jB;lkRJ?B0Jy8t*{K=x#Akd%fXFWt-6P9UigQ?+mm1bp^7158dhIJ}ekZ*;-# zEdQ!-2KEk6){j&3q60YJ2C{=PXuf&{c(SPeWWB;&in6oEM*LzM5r42^O>E@6lk>9g zRl>cmfByRGpT86I;n{aYzza_b*`FTxqe%7#4E!$)!v8g%4#PkGc>DVG%WwSpzyUG9 zyQvK%=w7At&Wr`bmpCGq+|3syHJ6vYhJaB02>`+UUPR8HGY^91m88Ys3x6?VfZPaL z#WKwxQ|egOMx37n%>cla<-ou76gv|E%ib&eoy+KWW0S9=Y4H8)34ow~@lv{0au>;A zaQ4+AkayulN{5yY?x?<_R{mi3BysI`v^J5y-#RPn^UVT4WJm85uhc)^ojbpK(0{D4 zk)VL&a%^dM&z0S6aP?BI0gZsGwGmW+!o|qYCt60IX2e|zMLRm`djC0%(&RVizVbi{ zhlla6JuCZ7mtdislA&dRn@cQ@1~#n(4V_W=M)ix%%EHGX)q+qb$O*Td(=vZNCtV;R z5&ZA}KnTM*n}zA$yfF&^)ENXEkYWNMp(3CuexCJ@&6)#}DPjyB-xYYbY84TXH{cPA zU~mKm^kEa&SSL$}^udZog}f!YB&(h_3Q(l|>#_QUZVMUN$P|e{{TxU8S$7l}reS*1 z)=yrw)+$-w_|;+Mz-ZIwTzqBYyAnNWK0GAr1Tq{!s<<(;R2VF<+7-ey*!8F6Lbucf zVgk15;};C@-GIQji3CytG_Uafk;Qcy5N5R) zKlA+aAbi9;Kp((Q?_LoQ34cHT{HkbTD#2eya5b)o0TKi8;ZMN7*~dR#y?*<84FDxm zJ7>wysVK7~ACP~G#}9u8(Qj{tLRREa3-e-KO0{wjOkU=vN48%{<$0AL?$F~i+4 z9`crn@d?>LW_1pZ3-N5sz{0;Y`tk{bPJr%pT6pOY(unh~FTvpj?y2hJF&GLzM`Tr3 zb=vfCO=sVfu6N%@VSChI-epOM?z_GTXBb%F!t^R9`UTW64hu`fq!x53NUI>U;vgL) zibhb6Ixz6Iun>=Pc%>J_%ff?-=U1UHMb!#tbpooBYY^4d)6*+abYoU`vL&gZH!-NoJa^i>OmH)-oSKC~i(8 z@Vlu1_}@WY3Gr$&&eW$Kvo{QEL(0M!X%1avKCJ`7cDa0}cAr;m()$+XV}4@U*FK^viabfX!CQdIF0%8p~@7YuV0o0T3hnj+kfm{Vj82!_qa0r1K=3H(0 z`~wFJfhqPL1#mKkko58FQRy1YTV>#iWd~9QUx_Br5;MRO#kerSZ{3T0C0zJC=#SH$ zFpEGan1kQ)77!4)K8rIg&a*(aUW(dD9jySY63b)eykOcDEJV2`v__r-Dn1q#>TYEf{XM?FQ zA&>Fl*Y-FiC9pTCo#k-mhrEyE9Ck0~hZcwqeu+ADvOi`54mm||=$oOWqIR8ddmm+o zP~fm61htssw!RVSCdZ!{@2r6-PzPoR$WeHbm`8;#WgP>2Ugvc`P_L=8&N{fpJx`Us}-{E?{W> z6!<6YpM@?cyc{0BN(elsqY0i|ZzcE*pZhIPur-QDh=2%1Fgt-@G_L5qN(Lxb zOVlHUK?Li+-H8P569>dSL|edJyYiziKLYhskc0=4q1DKRYLLOz(YKXW$!3B&=B8w< z(741gI1hTfjqLf*?+AWVQ+j6~NKCZW*z$N8n*1+s_ zQ0Z^^JC3`uINFU!5yD^QyRkv9Jl^yuCjG+zJpIq&f9m;mFaEZ7ZC}!* z`v3I;UC8+3_gcJzqbZ`vU?432kHwK5B^{i_szid7#oU5I}a#>};c57@CV zHpJN?+$SGM&iJV5SSSf(oZ|}-?XN=~aAE$Pn>#QxrAYT86_+v!zs8w|weqjnxx~Umo zRg@)RDCWA)nfZQ@*J<$dg~Z`5fqShEa3TC@z1OQMBu4t(uP~icWn6S#k`4NHOn)zh zFscXUH=R4qC%5^@a%8}qlN&gN4KgdHU*QU`-GKY`j{*P>Jq*YC=!ol&19uvNck$l? zaPJ4epH_dOfUC3>B=OVxrFdN`IZU?hWoSHJ-^9!@D zKIGS?{5GXVOuS453+!eox`yCLgnpJPku(Bx`R6j=1*`(ztqj!NyJ>r41>B~o8n zE|-QcjvM5F%~}ZF%}yU>Wu$=R(+0-!fWY#Eg)+in1z0TfD^?{s;BWg{0ALN(FI)o} z08e}TRYX3rp$UMSse0+s@fV+LhBtV#0Fc4a;DDdwfv;{xm_l(Wt|52t7Cm@y>VvUe zt2)v-Sc*R8MF#*T>X$CXgJyu~d^~9QBLVE(P)iwfoIRoyI2V<0&V07lLr&oK&_L@{ zfd$@>8KW~_LJ{LAXjOvbzRHOkwlf@tElWcOXc*QCP=SH%ar9-O$dG+;_huM}dXE4& zIh!4MXAO3~d^~nCD)rCW21*e)+mzwt_#pH#9m((zL$E&e^|vuG!E4Fr8xhS8Q>nWD zH15MZh4eP2#akR6g3tLn+gnkXYnt*}q6;J>f)N6(#t)6eSoZPoJ1of4d*v(~PgfAB z0O<{>u<&I}T+ja$Jpq6|hg5{nIvs(xB>ETipIgEsjOlluCg2e;z&aq`h+fD5c?MQR zrj#%&h#T-Nn9&=`-<9N4u^J3?4nbcsxJ^YuG(SlM&}UzLrUd^&@Fwj2+&PPr{+Zxw1t3HKc^y)jgk41P_V%5!C>e5#fJ}1 zJbZS6qb^=wtpMA@PeInpyeBrJWMMR6etY?B^p+Qc&+DJX2C#4zzBq2&`$ zFsNYX$Tsj(PO>O-i$G`W?g(O~D~W%lx(3G(tdTh8UP-2#btlQ1F;`0XED%%{0>@wS zK4}9{_N$Kc7Ck?jb%c2Q||y;|u?CZzu?1HjirV2Qd#66b{N~8I$n{N8l#v0@Wa_Z)Xw~P9gbzkVYxtgn`@% z);)d7Y4@o^uPlLqC!{*^l+6lVxWS5G`h2UZJOMhdFi-KyP+)LSiSizL+H zXzLXMYR5Nx``kJ2{*K!O68LwU3h9H(moINstq8quV1Z-4fmASmu(hYvA}hqhkP7Mz=tejy%>h0ZkI|I zz;Mcm(3*f#DR5hmq=((U|8fO55uHf83cyb(_`5Rz+?|47 zHXUOCv??$Ur6X{J|DB33{78Y$gJ8V_{ha$!lrpa_+4qZND|8rboOrhB*4Ntief^wC z&x}TfWT~h=;hEJA}WrS=~|dHfml-2TMx{hj?9i2j5$!H6VUgsbf%ungGC? zH(7}UwCm#NOCY36gdb!Lj(QNXKAuGo{6aO%A{gIlrGe&qylw8{(l3p{xB~Aa0B+FR zPR`E7ETk)Ware%R2N;y9Mn+g>xH?8&;NMb)!mR#iz|(GCEjXC$zaI@|U&C8dZ^h|# zUw%3BRf_%dAS`6#iIyzwY`EVz`_9m-d$v6TN+V-%#dh;Y2Omw1a%c39B4|R2wMn$ zBaB7R*o$2t&%bcM;T+N#x$%upI~$++(MztU=qt+tt2qm^Y>mCZjahRXrciv})#|I& zw}Sy95yr<631m{_RTf>vGcYrt@B7ZnwIFg;?`!TI4){A4_;-6abJZO@hL^XO$C~h% zT1OmABQxAFRJJpvfxiuJH`M}aLSTQtC?NB(+zppqLQ*-pQ?VMYg4QN*m-(?SzzjvD z7;tF=q%cdRg-+cwZBaU7_-hLq_+bP@^XyC5GYyPo;GP7C3I8|&7YG4`e}q5|z!O;? z+^%4NVgJSIFO9&5QvK!DQ(MgfdH*E<&T|#!sd=wmfYk)Nv8a#*x(cK|O3*K*7GSl& zO}v~qPlX>Zy}-T`7odTD^?U+I4Y-?ncBuXW%Z^qo9u4#FMA0iBLQZV*@cSA9(i1`i z6afANIK&i&|MJFn+&se_+g;ps?`9W{^1RIDfZreR^AdiJTgV?OvoBi(NDZK--*xE% zLilU8B9KT&e~7h!Z@C>fSwegRVVcWysx#udX>qvewF)@(hEOh$&<8dr;UM4N3Gtu~ z$fAErf#w*zaG^mD#7`KweS3{XfGrLNtX1X!ioHC ze)I?cxW9G-IpBuR35Ku><;u#veXbmtl4VUad>WMKpyB4h+PlBX)m& z4GoMQO-;Q!n~{c(EWli(pvFG0ug`dvZXCQ-gbk!G6}q+C4&p9MfnzjEaDQBT%(I8W0hNRRAz+>4fbxL!s3sW6SOP(sKRT;=0~s}IHcAkK+|kCYY^~qp ztdOTSia973WbV~{hQqYFRB8pjV@QGj^~-tLPP-X0!KmtO#2Yjk4*FZo;m2q`sw z1I8q%sM7!_)ir@m+>hsABBA+UZw$T)0)&Cj?Vk)th&=oh3JA-b^PnR&QQaU-Tmgdr zEghuhXpjMc4NBDQcB`~Hg4r?+>|^H)MKO6l+`F7{H3;j;R388MNy@_)16(F0OgDAV zStDl9Kk~nkYzAJC0MPyq*MO)3m_x5%(Bw~7;B^165HLpI7=Sl2?R4WMr=FS&MzCMx zKi4bV{=(?9mrquFZ2%0-^UvSC+LZ3Q;D;wJ5ESc21L!7j3YI$N!jq|~qzBAEaJ-wh z;6K?H_g~}x@AyUjE&Xu8rMoZ$m)-pXCDF9Eq4Eg$2ewy^H>zDKg@XK4*AE6=TA)|P$ zCSwR?e!bocz7&|y93Q9GMlB}GfQf*3EGb~r{4jX7X#+7tzn;W|Y|f=1p! z&A)6&;#7=n;9w$qm|q5B>W$OL;DE0n107FmQ3?MyWiA{?Aal0M zoox?{%v>Jro{3HP&?-z42>cuBvmwrlK_7^DAJ%X2d-(3YQ94ZI!@wQVHS`sq`|NZ{ey!CkMmb#0M@|@cXReqeqG(m0^0to*ZN~IsRIZzvU<`IPziy? z^3JO0gi{*qKHY&_ksh{S(Lc3fj_?vPB3JI9-r+=+N@t>D>-{ztZY4EzkiR5}_N$H| zY5o-??uiqy7~quhutWj##lTF%ng|Y_*J& z{2>S|3J6TamWp#epOt=GdM)J?WAKH;qZ(_4fI4qT_jfB252mI@Pe=gxos}=-fTNWb zMZbb6cq+^w1$O5_?E(K3*)SI`Isj+irMq{|l$BQ=$O9m+3>|i$-6r0D*t}*~~l$ z7*zg23!@R_0)Y#d3{YuUqJaN0{oC*N{s7=30B$e@?pL{bF$}_YaS=vdG%^xCLzFMb zUWi~;a}u@^&_os)(?JZ)-XIABxY-k<8~9_tA?(LR$Q@W47FU9_p`2!i1k zwm98{Ge-z*AdaC|7<5IZeCh2M>T$W(YT{?xu#;gdeXedzp$WGgkZ>-BU=++50Qq{b z)!EMkK-@v@t4OJ;I)pGijAa<^Wgb5oI=9dPcTGd_7X29cUzK-&JzJa);~(@A3z>B z{H4g@r;k#prQIKwE)^y06BZVwDHuwaji7)R(hv;rqv7qlFE2bx6tJEL5@4f8UJk;e zuPBA#A!Op0hL8|M#~lO^h<|^!K`&Tbc}7f+cMSm`H+*H42P*d}DWt2F~W-5}iLh5wBB5K8xUvsLt|}Pn?m}?AT}CK5Qa>$0ES>O7)YUS8v6_ zLCKjF^s)qQxIX{^5lI!<&+jk{dYe#j{SxM(ZZi!80IsKZ7;SI>K;D17^`jYNA-o}7 z+q=3v2X_eo;R{9t)HttmfRwI((5(2Leb3NJr=Q-`9OF@~87}VPjgT0vikB z5&C-tdnyBoq7Ca>s@VkBSd{>ZgfG=S0zrKDH6;pO1px#ATCCkK)r%6bwkQfKqk_r;GzD}Yz(@?j zjt2Am+hG*c{nzYokV-(dRWcQe3uQabLkZ{^Sdj>O0_Fk(linr9-k5yl0v2JM@(nn$ z00n{FnG^U~$N-rIh$QHJ=>i-#kV9^Q+Zt3*HE_niQ%MJC_7`CYk$aT{e{TKA!mnN< zfal{DjEgUByN7NC0AdWLCFF2XeUiCMP2Bofwvg{GY{GZqHu7Xsr~!EhDG&l09T|=_ zZu!f9F&tsAyG^&BXHV)G2uNhR>tL+Py*9(40lo4MmCB2$BrQBJpW|;ynRGF?N}fMo zS5lTqp*irDa1mG%{Yb{@*;gE}%Mn;z3XAEg zl>i!HfGyzzA;Xhf1RY73gQ1;Hs27h7Z*SP}+YOt$6t~ap>N|Ii-Z*(|>(~#lajxdw zu3N!a-HM7?oi>1p{qdP*o1}v77&ty%^5v&9TJY(9VfLpxuwA`iBbdq1Gb%}U9~{LneYrPg zWBE5bn?!&P05mb|CI=i02vk`x#LsoqKqK}5NJzRjOZzXjfiQ#!548YPQ6^5JiVLmU zvWu(0sMF{P<3ttKflr@GBPfAim2`mjc`$yORh#Ps!A%_C53fc?%cQFrWM83(g8po- z4GQS#x1S%bdlqh0Hzt0Z@mSIoA_M`2=qYClXI}!~F@1uY?^RiU`?p-{2OYdt#Zc>h zY5ycs?BAk8@Rpvj@Pa52#sN4Eh;}zfHU%>my2;{kc7u$N{|!1BD^g*?N!}J`;0yw< zyhi-8cdkH6+Gj!J9y#ciO-&^yaA6PvrO+u026524A_{dMxnEucxEl!Q_*2QB4-xsc ze&F*5H85m>^RgV&!~x^+D64f#=C|`ju6}d>k;9)a)IY&LN&Txpz!UZJ4vnhUEd#YD z&nbO|0q#W6lZ{35>JMLtLohhtp_l(ZkKll@2kcfI-a`;a1TB!}9k3@(@OR4%aeEH{ z0{>9?9!VfQBLKfLiD62Bf9OLp0M1X5STEQL_X*X2&%G0*{7<4~VIJjzCB6xlIQ>-O zW@e!R0?T8dWs-}wddf7gsdrjAe`bE$6!@}DMd)CTun3124w@MQV0k$Lp_lOJtGpLB zgAo2oO$4?2gC@G`G^>#GA&wtiB!^wKvIMgglT&ZJas$X2c)uJZ8ihCP-0<7qMp}Z9 zbQ?}R&C_>|?nH4?)n^~CmVEW2h(>@a5PyQ1ADAw{7>S|%>mUHe06fq%_IC4&Pd}Y8 zkvl7?a~gs3iGWENeJ>YZ*BGp29(qK42Fb{|FY!NRp-R`MP#AvQpD6?Z({5D?#S$r0wsZ8O_eV>*CfrsF zqpv#lMgBJmV$RtIY?Ms7G0R(*w}#fR!dh#QNtsr9Jl~?xjskAl;sUmHtjX&E^Jcg$ zBdS6c0FH?DrWIhPD^z#}aW6;%aB!R$h+3r8gA~HpSoBfm3J&;tnHb=n0_yi+g1xl$ zrkD(a9Pz7_@Zkc4W)5IDgh_{qLP3OKsk4DgUPfQJfl0Of)EpCagu zSq*S(0qfHaFdzDSnAeZPu0Mhf5b;+<6WHrzL-2(|DkPcE2rR-k?{I7eU*SZ|guv(D zX$MH3+~J7=;Cq%2NFARIJs|gh82@!Yo_GF?JRZ&j-0L7{;osg$;bNuyA8(eFSq#WF zxDwXE8340bf@!wBLBjle=Y?f_ZjVKP`s z*i+v9`fXAEHf=7retjfj#f7+3LcmDIS}V+};mgg^=myq<{BOG`;A!BYPQVU??y@^X zS7Biw>w*1LTfm){eIVKFjbKWQIW6y zf`NMR#!m*SJ~(;z(=R{G&3R3i(>R-x76$KUa%mM9h!}nkz*V2zzRXBXrRgDvwl~JWh=%7{d8yXl)s{M|NKF;|UTfGQ9fYk50(hiJ(*Uym)1_nk?+(8xs zNBkfOVpSZJfp}M)1K88UAgrrbs|)h{aSExDAgu4nv%ZGOsKX4{Xy=`|i7ecT=(Ti>Db7@~g`z53vqf zuc;BPJ1>ML3Cyg(NeI25;1C=YAj&{ENm*RPC!49mi8`0xc3 zB~3hh%@CY8;Gi<{{fbZEXvgHd@%)MtE=0QJFc{6k)cgtg%6K1vTKd4cXyYx@-D90w zk;+mu{)^`5#(Yucqc9hO>t2NXkDVcqNlO$>+L!Q;n&xfqOq<}b(}Rr9M_oF2TV!e@ z4m#|Qai`moIxuMAHsPOb!x0X+ZEX_%t=*2fSJ20RK>mU)9)GvP&&C93TYpaz2Js9& zxneH$T2eHEJ{(0n7OR5y@2tHH?f7Qk-=kU~pY<_(2v!}^Fuh^JhPSs?t)h{s?fumk zIk{+lX<&$cbbk!yKMtx74l0<&4{qG~^wp=iH?xC><$dkZ2a=A#x_ZoHSK*vQ&fs}7 z2EdePz$-^zE&z}rr_=e5CPQOa6Ad|@k z=Rm+LD4}U~d|-SMD?o@iIL{3XeB1=b7dL`TL|_M!@=(7Q1iB!tF@!Lpe!2hvZ$Oa0 z;~K(_@oJ%=SzuK}L^~Hc$RDk7bkN;bB$i(9Gsv$3!>hwkz5MH?!NWm-ArBmuG8!LR zvqNy}_5SPU)GDI9RE8uh2LeI}-CF(H1HUjXAn^V6$JK)mV4!#^;tYGd4-5-j<_(E6 z$PZ3|6$mmHL0qsiy8@E}b~N#C4ZPwV{{q1ulhsbe>W&tgL<7?na4KrzdPkvNP#$#Re-Q=K;5*1FYoQke{sHxNA6l>=RiPisJAf^Lw)%Nf z3W3=eQP7D2W=^*4b_{OW7xzC7PJYA`)~0TMt+18=?h zj!J3TgYgxXrsH>IErk<0Je0g z5(#;yUE9^3bhIVHVNR!{7<8pC;w-!q00{DjV+iu1HwXgpL9RJ?=34&AWNXa9|2%qQ zIYKyhjVxslmZGs3j-^y1GCl_&Tzowi6=dmT$@5QNJ@>KWtko|DKvtB`B;iW}!LW;f z8X5rm41BrBg(l?niR-C0Qz?K*`y2Xe-<&mmwwCloz!sqp`Wql$E*CxNX$>eD%uhDF zJ&xEEF$ad-J_B_f1B^UD%8A?2JL&$d(;ejdr;Q2(#HS;5 zG569FOn|f^(6I=enuRm)(Y2%ETE*>N?*kRXGE6`mmbs0-H-VT^p?Ud8iO`OO87^1? zYWh7seEc9xaL0KKxqf}Pw>nfX?9Xha6U4{i6ti#BGH=fP!SHzH1^ywix}vH#{3X!Cy<@ z{M`!1LPPs^fsYf^Mql7rM6#Ph3l1H6LTB9QlV|uR9`&T0XMfLP5N@D;|4)AW`1q=^ zx&Ff56Onn!yYH=3i-b@1dMRkvhctlE1yWKnKWj(Nm|#gdh=>8MdlC5OCSPAaBFAbv z!C137pr%>fch{C$4((1O>zVnWQy7G9+qS~w)HF8}_6Ue8oe+pONMN>G1KnaOsbb)y ze<2O*YFP+haLr}jL6`+iLYN$K#io8zO7Aoe+_@-pFsJ`@`d`pQGZ|sS20$MzA%ag3 z$fHO9`Omfd-}ld>M^7GX9UJ?hX<)TdVlL*V-qi*@b;5P$+du}J>h3SUgGS8fZ)W5# zq|lsbXZ)<)^w4);4##sAyeP|0=MNcqor;>%6{OD_KSx1_GNwI9UteqrBW@7z_l^6J z+7*Nq==V1{{Byb$>^v^nN6N zPtzh0=+>$CRft4jDnjG6Yjwy5yw;fJNx4Iml4V50o%dQVviqtc?ts2FMf@q=fCDiz zUizz3Rv%k^D~>Dt>i+#~z`dUiBJ4(I@8!Ye*aF6Jq#|+wmxBZ@x3|vhF&Rr(+R0+L z9#^7Q_dpP%F<7g>DhI;w>nSMTEU-$QaaF+pSvCm({4CXkAT0+sV1pk2w7On5#f}KlISkk__@l{Y(tYG6wj<8$X>wj#vj6 zd=DuGWxq(k&-Qs-0qW+v)`pH!1>5rj0FL;#);5vXATW3!NFR2Cu*%5{vZPeT56b{U z2eUTdkJB+*GQ|jwc4;3NqCh$1WDq``hTxsbNImN7?<1Z(9-V&l=n+JMn-);}aJGQ-X%F}}tO9djfN}enbtR@4U_ls`-_Ql(q26ARaq8MSK=nFV6Nk8K&Uhmu z=?K#4a-`0>UdvxPor?wByLOE^fHh>{K?QA|p9JsO) zDSxdrt)&&<{o&)nJ5of!pVfeZKek~WbR{NU;S8zhzfFHgzwRSU13VZlOX(I&bq%+G zz_w%LfLphIww2PDt9h{N=|w6Ql3Ya)Ee7n3bihL4kD{>@jnKI(OU3$F9l@y^6Mr-Y zNC*cM481fulDr5c3FHQlu?S4Y*D++7SzjuRlkH>AGRyxQ0V5G$Tel&wpbsvaf$0R9 zc#>@ZpDZv0N(Z?0P~pSV?>rwqPURy|qr5Veoxdh^#`bSxrh!R<=<|o`3josac=#{~ z-FZy9*zVyVmGCsv1OdR4r;wUd8;SkPRfnPp*nH2<2C^m-aS+oyt-1zs$guWmD zeD%lMx6kc3^TiiyR_ql3IuRyi7I>X$I6`vp1Qozh~sfq{M+YWXD|HlPVyn+HJIHKEi7RF(ASKn}gH}Kb=Ohh;4w_#--4Y7vF0BW<;<5Q?Z3;`J20iJ$zIuC%> zNAnQE^n|~x6$fm-bM)xvl*BYr6i8*Xv5v+NIX@x-CXOI*%6Nb6#!BnNcQsm_Z?d7I}dQAL*Uog zK`z+oXnZ`o*2`)5aVODFs7FFr;czUxW6OCXuOU^AgGt@M?uheBkPJ;1VWnLm;MoAk z9x^)U#-mnP5^nh~8$BhesF5>4)hX&C!tLZEA?F$k}A z&kQdi*25?pI#c^)A*mvOiTg_3Zo{C0FoaA@)PwgOE-Kf z^zD-eE2^l6)5#;^PqR+o06*K^lfqK110?A~u_r0v*cMnM z_eC;RN=a37F!q0>e~yM3i7XffqAEXZazy8JzA+WcB}r73UTjk`LYr?POvj&UQ$)VV zpNOB1B4UNh_89pR1X2p!wv4ILZJ~ko5>P=f51-|e0P{{b-#|u3M=b(`33#jX0Jm<< z7lF(RE|^JQin0JKd|>W@%)dp61J+*(SQI%tpKrsoC@|*W#ivO1HjXlmMmoTW(L$=1 zjk@_c7vFaX#|{1S%wv%-*O0OpQ(m)p@xt1_-`4-VV1R%B`;N?G_q*xj zXLCR?J(%QLoQjXj@9ERq33?Jm%O-N!7GYd_yKw&4zjMb)h9D>wp%4Ot0d7!0*5`~0 z1YQzBi(80*P<%Tl1j9D)_#QB1&C0k$VGb9>6P^7hZTM*4PE z;n0*ZTOLi!v(Qfh82#W`UpKe~oMVo(w}rm?@>SC^K7RAf%su}6Z&V9RguSN|aNi6e z@NcvQ&p-%`GvvTz#2!qJXWlm(fI0Cp1A!UPNQ9+(ze(sfIqN;XZozfocI_1MH7O#M z*AT7(A5#f~Pdcw%lOpEYHHWGI4XwB1JWL4eiA%7Zx7_@B{B}=)tb%Lxicmf4N&2FI1jV7gtxC-NO{6tgqc6z;c|D2j_4mYCgyU|; z09on&*=IbIjP;~;kklJ2S8$qum5;AHK<^4@4Z&Y3(86>qbuO0Tp;xaK^x0xWQ4CHY zSK8W^rFxJlHzle2Qrs^cKm>%8&AeR394uyQ83G%+lMAjP%fo--`^N%T!QpLz^nV0E zDxe90OoK`6?^G6j@3r5&qJkmVQs`iPGQshspb7JQ{zG0H2rR_U0qiZnVOQXn2%oom zeh!j{A4V=Tw~^LgC(g%zkb0Ia5&BrGxp>W)Go`<)Jx2nl$Mti6T!i!~?*3x@J;7k; zy`G3;F5X+2!cpmxLwME!6Tp%*1(zB9GD=7WsDQx#P(WZzz#M>?>}S|3OWHjy?FfTG z-8cdl-@Nm?o8*9+eMJN{8)Fq%8lI1!g>JnWSwEO@zz9$k{Na1&NCR`ugJI<9kk)?wISd2jeL2@212OZk`1{TD=?;wbpYAJf zG;|DhB&o~DxFyhe5G38B{dcfqM6ou&LHIv9CZjNJ7Ha@5^_xIyFy8Uzi?Wa=7R6Eg zLO_%(1k*4UfEb4xIR|SNehRY%$KczU6Rs+92MAh>c8Mq$&ZIm@v^tuUUmUj1C3~bM zq~m-_Yj3rNUdJTBC|o5qA!l9&1m4yWK>)VjG-B6_in~w_4hmtIBnu-4xUY1SeAIgbZrd+L;eE%}P|8p|6ez#f1{ zeFK*FO&l;uptH^2DMOxH;5N=HR6t)Ua`Kh0A%ei70Kg(M!VLEg7imV85Gd?SQFE8DaC}4 zH)HF^RG39IRJ#=b@N>A~0Dl`q z5Nnw%EfEc+i#&)=-`s!a47=s=mSsZ!ah8tD1=;6#H8pfI!Dg> zK1|~qWPp@H6V2d3dK zn%^=Ae4y8PKL17nOt8U-0ZfRfD!7<|i^LAk|BqA{{>a98VKsl&?bY7sp*XR`&s0=2 z9VYl4Qjh!OD?Qrc z^-iq*bQ0leusAIQ1KuEf;pEGoypRlVVSrz02CJp|^@0d)FU}r|*bhv>i$Y))E<_$o zSC~Txe*7FA!tlRA`v>zIf>Hr~JJE>=)B^;vI;m^(Z(|My`f&z6y@3pnopF4*Owl0` zkbg^{Kp1mWRaG6O35Pk9K@IT$3Yr#hN}tC`iJ(7)UF)%UCV zbY)=O*S8ZFb@u4TM0*S=f*_QwaT)GcR16{Tdd0a+G&5|0jB>Vg6_(Uc0nS2&^Ypp>*-E@h#v_ zK*$Z?2Yh|7abx}voaN!;<&u$*OF@Od6rE2@&mBq1#Frz4Qo!@9Nbld`8Dn;G0k?aK z)+&k&RlPsFc*TVxCTLv{@B#DiwiqKXG0^x2+!Ok(z`+A7aLvL;*NJ}rxc-lS{QZxA zJh!71d~9!J6k;MBW^bjQ1}(f>X+ShY9*BU{%235{{LQp5^ZkS~Fc*Vw{6=y41ptWD zlrlv-+qV%mUgDUDTd^oyu^@|UKAeFQ64n$4wZq#Y<)%UsquCehKIi|fUs$t*zYf0_ zw-ld`iGLh&0eRCJh{5fOsq|~n8KjugZkLrXEj3*WQ5&}qABsf)i}zy}*yXlN$o-TJ z-Nj?C*`LfH8#n?VWkf1oP@5^)H0ss&mvUpN#pj)yC*MA~d}|dpIs(9g9U!!={0kij zIC=ZGZ>_@w4A_~YWM#(f<}Up3)z@WhwgU?j`=T?%!><11g#@tY+LmiuH2gYEx!1>FW~JI}F~&*Py+#hX zude8ic8=wq%~a0S)yGBltaP~z0KBfO81e;$NDuo= z0`A8H3$853vMUIqq2ay5KY@Z$sRnc|4EvG%<6~4y6Tho0fhGXT=aK>7z6iy4N`3&} zDktNU0d_MT-vHRHhz-15xndG{g%s~fusqJc#=m$I_z41Es!Zvn4#9GQq#KATF)4rn z1{M@zrWjP2-wvfiM@qlfr%FNiMGxkK!Z7IUk>$Z?3+Q3^yg#WgO47jdaStZ{`}SD> zpC7wtX3M55Tt-Z9@!=qMSlme+z1U|CLZCj?(r@wNHN-zW_}(0FP4Ue~*Z;v6Fu;HO z@sIy^#}YU_DlG%F2QKDbJK|DNu+GGeMZN1Y@PWJ%I&e@QJOUqyRp9*j1#)RT{!kVR zzv-1Lla0;nu2}26K&>>#`V8z4Ka1kXj$_`w@i5393ej!10VT}QjKeeVb;h)e{ zaR`D|0N~A=#l*j2)FTyll`iZGgD`!;;D8HR9JinC!NoPQg|u+KJ*qn|9dj)$DI(vq z@MbhCkp*suG59D`WG-tNh!f283(mnOZy;2iy6Az`iuEXjKqh?*cFaEh%aKpNe8r*H z-9~ZEjc6=I)8}TKhSitC0^6f3Q&*EdMZe5>fcAzjXdnPEDuhEUnCjoOCsgjAFt0Dt zv-}hF^qz|0mW@3WLDE2R!NCAW9xzD^wdA7|`g>`4zi;~f`|oih{$7(W z7J-Vv}`H%(|?@gx3rY~6UFc16At_;&T}2u(0)tWYvE)A5guZPm58 zRebN5o*%moxU)%E4N89W^gAVsgM6d=(({tQ$jDbF4EKJSB=BQm;K#UvG|&+O)s(b= z-71L_{OOXbbB6A~SEk}!TQ&`+1~^r~O+^))q%hh5zD!XFLck~kVG!06X^UBhz92b& z3m=Dca!4uArwSB+^S(Xh6x2))s2cQ*5s4LMkb+dKdiSF9C2NM07^Y|kTDS4XVDjpI@-tLyX1g(t%xp5d{6G+EF4w9H$T0Vye1cX&s|DMuZNomM%nf2 z3)gqdZOKo%enMFb-YtAjc(+}qkhN<${gVF?2>H{Q0I0pOnWvB&+szA znsTPq8zUngT2c5C!brk5=iMQd&SxV$%a@dPhe0bW%Q8dNX=*wqft;C<Apl@6XI=nVXRn4<#!XdMY#pmI{Ee{&uEL8sl>%q7XOS>+#NI3-p;bo^xrZyV zENCO+aROklK3#c-of=II^f|Qxa}?I*Z&-zK{IwDQiU#Uqx&kX;p}JzYHDys(M_xiI zN^(>}&u&FyZBZ(WVqq3Q3)B)ghj%iZ0VRf36h6(dFCTVi_Yc`Xy#CuYQON$n`76=ip?J$2!1I)WpbS(WME*w} zLUs$elvIHte3w!*G^yYvr^L7t#F?o0+Kyx2_Wb$k)yMeT@Xvq#^E`Z&JTDQv#lCLf z;|Wnf&%Ppp2_f-h&4o35Yxb@w{bJ#{>)!$b!T%opYta%oebo$1FPyr8(^W)m znRm0BNIaqy9RSFLz)-`Km#Hsveu!eU2An_Nq%b9?mX+BG?9c+Q0yFhqf<47or4?Wt zemNbNPPeS&4sRs`Vw9Lqs8de#!cxU1K>17b-sp0gVcPpF3> z19TWn1YV_f5KO<2JLmIYya$~1Jy^at0w82C0|vqlV4$t7(FoF1#rtoQ+`$ya!4C%j ze0ohud$@#zv9^~!5Ya=f|30e%VH@+1+bgiDj>^j3qz8=NHx8q{710?douEW7k%eki zV5{;Gj#c#A6j$NC^9r4OZ^s0jGE-%gYYjpv!kFgZGz?=puCBO!yB9x)7ZsL-Km@>9 zxGI9PQnD-IuyY^aZ=ctJyBrEV;!-%*Cu1R~BNF1V2AvGk!9OzH76Hb?V{F8PVhDC8 znoqv=zVYz;G6>wN@)A&` zaHlrDZVAa_Af+&(eMPEG(P9+L6TuUe zd)HjZ55C5|3wp(aEO5<=0u030zWCi2fBg23fBfU4|N96C;Cghx-I*A9_Zk8Tb|=o{ ztKm-URbLz?;PMz~&G<@$bV&&_za$e#8vv0HFkQF@d`}>_GW0L%a|7{P88?s87*_R> zu(*;}4nW*H(=B;HbOgkpQEmyHZ%f#D$w#T!-$G@oQvS@<9}W`5>;o=!Fm&E)e@`dIU_jvDQXPXE6q(X7Qnz6`8i85h8$k!b^ArU$qrG5`9u3XKGfr@s zYxg~OhLvu8I`!t{<3*Xr+4M-IarboQP2ed;sA+eoPlCg0)Ng%H5nK|+fB|Lz zm~vre!}FUDgXS=7vk2gCgquJtJu&rncnL^Pm#hs~0AdqZ*ZIACaCH=eR4F8Z6EX0w z(Y+v!Md(#3J~L4njQ|fE!WN+`HUNT<-421C?ykOtC?&ez_@@NG>Wqw4$LH0q31(58 zZyBO~N$ltAa)quS=admB{c~$ILlF+@oB698W9A?aD4ct;u37N211U~7cFL+n5KfeE%LcpYlj%=)lG6n1SVG9T6;5KnO*P&gp z?75&8Lmj{|3Qx5q2FUTZJCdL?|C`3%CzhV54Ktz;(i$*P!h8_SA)Q3R3wJ6#V;@ok zBA5VPicqXbf=NaYt6+*G3e*=o{kkaqRYP{#dl*QmC01A6}f%zzaTc zfVZvi=Zgh~5vH?)B3!WJA?kg|M4%n>Ky>%lCnG981PQ@0Tw?~xIPin(}YadrSn zgKKdy>pZ~fRu=R6k++8tIpv6`wc%_otuco_n=77l8=QK=^7#l-6rVoyW;6TcXc;BkDeDwu0Gy0qv;PAOfj;4&zf@nZs#sH6T;JrT4OxJ3o z3Ta?f@3m+-PN^`RsVB)zA%;F9pd>N7KDHfB@Yf;or-bOi)ggp__^^NmhO~td9zc2s2tBhS}7=Y16l-JP7+O zRRIV2o0pG62>jE^k65=+<#0NQXe)TB{!(TFF$A8!v}5BAyq-LHa{r}E=amt&SS(Pd zj>U-s5&%!Eh>Rif+?fEl(t2ht z@QQ0ngA8KIEu~hl22_!i=WCgf>IM-6BDnI>X<5olkO!Cu=l})4BvFrya4n)>)}~m5 zuC)$K@C`TvKvF~*#u+Vuv_OFb8 z4(3I_cyagbqdVV*gbbl5{IkrdFRguM6Wl%kN@H18>9mA_lcM13QupR0fi z5)eQF2U8Q0TY?8Vlz~bq4E29}X%YeKn2jqi&LFgcq<$nN!_XDH3f16sosCr~6*^^$ zHg*!P2!Q&E7k~snhMeXBOL}NQTq}8@5Uy7pAl23J<3Y$`NY>TG)m2*w(agw-|EUbf z@7zM*>l6U$8a!e#;3}o#W2c(x6ZB5Ukk!bSy!dc+=4X2eO*ABdFY^PhqOY##Xxt`= zj6A?E3k1+I07n3za_}2g=>*~+tceAo1=Kpw7?^G%hc+cijPp=+3O*$k7+UCp3-Aul zzn*TQ>`Oo-^;@CcpNHTz zfr~N!t|0!c*?R`pfMWT{nD>Y5d-y;Memr;hCd@3D%G3{>tpLk|0hX6#yl;M}Us6C| zQV1StHsF;f2uztUkqI~*O}}v!@$74*bMc}Cf2EYW6o=7mt(SYO4&jUW9Q!{4{MK&M zbM}F3cak99`KJ`O{Ii9xEm01f?!N(m+yMpxf&(t1QDjj~*Xs}O{rEBM040tgJH%VQ zGsHjAa{BYrU4Qw@Uw98@TflTFXyx0>tE)RP3BonTEgAl7k90P+{(o$}-BXr#mNl%x zAS679A%Lg`QE0UxhNu7{BN7lqT1)_<+M+FALZbs<22*rWrW>usV5t$HXU4oz)$>wn zsHojV8JbkZlRP;vIWQ;h-}COZ*8W}BZMtva<_45}%w+Z2d#{gHQ$gS6)T`n*akuV3 z@(idr0?X&Yr+%PSe+WR3bQ&|UcOyv=$ha&XJahx8bpVvl#Oja~9SF9G*wsa@5@Cm< z5O5Lo==PIVSp}R2q0V?P%>0m&@rO7E54{irL@B1lV3n2*FdPeh5F((>zaTQI0%8d! z7W>G7*uBII;>WSXxMdX}Q2k3)-dSRG!Gd&HMFe~bz6SjZeh{X^M83EJa=-$v0I>)J z4B8NE&JdQ)KtaG$FhI>n9g-17xeOEwMC_FvNaiRUg!v8Mb=jYO@%Bp`#51oT_E)v{ zCC#^CP)nBWEbNJ*aIodsRh zWiS;B$KVUW4iajTGNx`g15Ayp(<3GHPGf%5^}N9 z6z1pB6=|8XQ^FXG^n(soNJ|LC7aNp1P#lmES%g7Dz=g^R`=_^m zDTQTLF1)$w{8%GOuUQ~@X=t)BtM#Gz;9U389RZlWKqR`QVKuS^hp>eH@P$QwYsH%~ zP4Cz5Di?PYyRPs*C6lfVDKgzEQ9|gIalQWkTqLe~D*i2U$7wRanD^o3{5>xR;pZ${ z#hb~bnF9#pOTE3eY7iBJ%nV?gzYGQ#qK_L9jMWGSFksIXfeZvxDt;6W%|O&I>^O`# zES3Y`Nymy0R7&0CS=s|ug(?tON7BQABP91ZLnILODb0na;5gt)6`ENVymhqC9U*3k z`_LYyhOQFtgVha7Ko+L+BXur4m& z#2J|IS6rYf5Kh5SAlBy|37Dt|Jf;aa4uj@%+iR`?d@aNQu8Hzchy4b;Cc?kS^G5y4 znuMYxm%|M69r^j!qzCldFm1zyY!6{?NMXVru!55<01!==wQ2o53uK-`1z?ZO`BMr+>HG+d_FJv|En5F=qst6~Ig z7?xmK9MFPnP>ixKEqCPKO@;K)nC;5kMOI&w{+69U%m_EF;kJ7^MmjfT)P_jt@V*!W zVMtD8>Veo@=mri6333j@@^+;=G%3~g`^FFl58E3q_TOs$Pi5fa_R)=25bPRJiZsu_ zmv9O}^V=(VFj7V@4Y3y8Xe|wJhJVYHLC-gqEtYq~9XUeW^P3(NE$JFW{qFmTWPM7&|AHZaL?L?Rsv>zz z6^Gcq^z%GrWM)<|VUX*?s<$GvGs>6Vj$|xQzpPKxA;Q0gX{p=s=QRrV`9lpZ8i9d+MgdQW05TWQ9Ut-i!^2_hG59ZX5u%&$jzKF+8tjL86mr4p zgYB21U@ollX#6JXo!1cniGTaB6+|kQ>W~zTuXebH=moZ4`(g}a0(9^Ir>MRyNshQA z-9tS8APooMlxwc;v&bxyw)i!eMM@9B0xL)YD*%9ejhHNs!uTT|lB(~QDI2Sj3DK23 z@PV}OBAi1dbc;%ptS_D6F+CcW0d)-2B}lCRaj`kX#c*ZE z^cQBn=swczD#3ompGx(7MVv5n2fKR&`B%WZ|EJmahu#dwi?WTtE`M245X?QsArSe7 z6bJJ{n?S?B84kNV_%0dwvuu3hdGvxTQvrjUh>gF!rO3yZ3&eZS-4YCl=n_2wNZ4m~ z0jA+Yb0js+Y@JLG{T@=afZ+)M8ItA6_I~%EMXsv6oEK!ja;V|0inrmuzN765(8@%F zejfmE^HI~USD_Ka4kdJ33;zFmUP|3VI3)5x~;(ohsfVXA-g)X%($anG`g zz%=JKkbs4qQ5LEu<6`H4>O`s$0)DPQ)R+Pui?uMPxdUwTL{zfCS2uvKMM4-`=dIBo zJd8K+yH{dihKFMaWINJvrR9VDp)pSQcRX_WZji`jJ7W$qP#sM4+a4W)qsJB(!8iy8 z=68WCkWLT7K9s1pW+qp#M0JtTMw3oQ%4 zLi^}T%43)UV>|Tpi;E^Nm{^eJne9~1?#MIEnFFu3_=JvFOJl9g?!q!X9 ztdhOx(h0X# zLu>=_^;-sjCdWq*YM^`b;TXc4Kwl5~Z5XrfjGcl9UdRDgs&2TUdR{=V{^JhNxF3>X zpaA49kP|Qx5FP;)#gvdFC3pmYAsMl5U3 z!MN8r_L1b*xXz?!Dl4^*%SQv%EI-bWeD-C=Xh8A4d5wl0gVNo0`>Dq1c0BUFT;F_qhLJ5 zWl(K#!5HELFiYb^|F$~`yyzpYF}*EQ*RM|r^zfAp2}h6Z!3u)Qh``S_fIb8B14Yj_ z4fEEyB}?}V9Q0PC52C@>-e2FhHaZG( z3Ah`PSiuHDpi7FBfU>pai}YQ?S8oKdAeVs#fR%M-~Q;Ye`O?MkL|dNy3#+~2LNoIp0=AT>E9yV!2SK92lEz> zz%Yj>`la8aVibX2D`Q8qgn`{FG6HKdMqTDV78%@Ty zs3vp;;vz?231Q~%dH*jOLY5*OjMG8;+7P9F(rz#Xj0nhxKx;_17l=R*5ZXnAvX@5$ zKn{kMg2hrKpB2X+X=J1VS}6!6jv!f?%$GV3W(Dqtm0y*BE?s#r(f&_$!W2$d^&KiV zoNCwBFAF{Dc0v)#Z8iu@SLYlJamM^m2Vx&LWB%1FEEOObWl53ugWem%ALv8iK^4}2 zSy47Bt#MWD=b21+US_!Sd%P|rZp!4^FHFHI31%FiUivk-0NF4F#Y8}!gy9SsVm1uh z;w&i3zBRWkj)^h3G?g)N7rqN50$LhOaRKfiHR{E*J8+OihfFL! z-U-HF+(2Xo5eL-xyB`E_HnxFyG(L4Or-Xh)K@Gn<26^#y{x|4$5Tv?*0kSR_0+@~f zfERh{4I^-*eA!|&Zj0-ow{Ld<+#W+HnaR$@g?DbzG((IQ1dD9?Ur~ButSx*xpqpXWeos05T#Q-{25|O(dIyuZ-xIEnPJB ze2S-L%MMJ|G$gUc3LTHFk5S%8{*`6%;^pr48(o7}sun9;Xe77)>D|AX*k zUs7euyYK$~_ttvbIGI`XR;mHu^lGFxH&1sb^u9&+U919en(bFipx360FB&WYE)f*i z>?dNrB$ja>i0$ACRnoQ0IRFK`f@#?YtaC66<0KEYQT&K2wSOXSQ3BxP29KmeGynjCd z{bY{&U%+3xE+Fm&e*0AyoJQaMAsZTsmbasNB(gwhUF_7c!Wc=06yZjUd)ntp@X!^JM)VE~v02B;jSm$upmA1_l7yd$yX7@KbVf1b~#cQ1)mt>1+WYKKj9!F{aq~*>6Tl zK4MZu+j=Yz&`iUS#FVu}!z=+1V{SN%Kr8Jh;uc;=wt8gXukmq##}b3dmP#h(+a_>l zYZAWydm{|v&+oKa81(JcZyNqh*DiK*`Ny8$1V0?NbatrdcTtV@T?UC`E`;W_pa`|-3V`mS z&d;z=k*EL}V5B@4eq&`gRc2PWyV{(J4r2SET`C8zs!}(wa<5eOK^3$zPlbt4vl#C) z4E(UFsw(PRcRwApg=0nZKo9X>N6|h0wZJU#ll#0YuHAD|+Y=HIf-N|%3O*lA!qyJ5 zhcRJjNv9^Jak54j$XGzcqT&VSVHBq`MXgxPNyP=Gi9tvLh##^LM!hna>X)Y>6$XQ^ zxF7`4Py|+s{sj??4ZzU~u%IAl0pk;h2H|5agXz=$?=_bJMu`YP2c6)93u5Tdl0+KF zAXK{ELL(mH;JG!!n=SZq7>%H`zt~4Yqez)% zT?fBxeJl%i5SGD(NCY_GD0e2>m9@YceB{X1BVn7z4kc{+wxT<@C)NSdGQyj3OaM`r zX?cM%5gRZX?JTr0c<1Hh(NouuhW{}MV7K``rWd{RygOF-aVo}M4pVS~ zO}I8drIG^s^^t_H*;_HaHq%#tZ2aJ+Fl6pCGqAZ^#Yv!-G!xg}Vm88m2QTpa%zSKv zi;Thdd=klfv-;Ag;~t^b;=3)4_AHFRS#8p{yy zy0Jp=zoseGB3U_zXX7Ih0VkBz$W9R2KsHGcbeG z*PyS*Sfd7D9emlA-irQTeZC+ka1R3T)hn!K%^tn$_117G{>*WZazQN~3oC3hu=C@~ z`*2Zyx98N2smHg!`~LRy%4+NHfD~q$p@4F+aS6AmI2gBQcnV->OTrAiD3J?mk`@io zj7d&w4)(Lhm495}nvjhji?^;^5g0NPx*Ms{*#31dcDs67IErW7gy99A2hF?ZG8n!j zBSZkg{3Ngu|1nar3u!m%;ff6kDF_rN6zo|l*0OQGN6X7t`zZ)e9F6609)*wkbdAC$ z8n?Zm&cp!0a6(AeDFm9BtT4KEb%lPAFQ^8zZ`;paw%DB)_E%3AM0zql@Q=}epM1iY zEDt@c@;v=46~=u?%)(!*By)04LBU3JZ@l;Zrmw%=^qU{;L+T6e z?EIZh!2mX8o^FyHaFZfYX%CS$P;+s72L=Lu6%de>NJjo@Vi7b{fS(fpN&g~4aAG`` zhXejg09+I80fz~Hr{0cOpyptK-te&NWY%ykczlPeaQh0>S%Y{ zl5zbyPat9O=O4Fhx!^81R$zhyhRjo3L=<C)1Xe&0bNTY+ zwN}SedE>^D+uwb6d-ZA*d{E4+4W2vVnnlZQDYB|omtan~wVn&pTpP~AGRVm+0%o@& z{99>84M>ncW30V$MFJS60!}x(BkqG;wng=G4r|?cQm27NGt^QGLX=S^rf6|(f~pO zqv`ka^`FPd_)#YaBT;z@c_)+t$JKC&Gw^U+6z6HEp)gZ?PY5_H1PnSrBA~r@m-T7aHon57w^Ty?fv8-4COh zq%_Al@5vMc1PortGw4foWK{VFvCnf-g@;@NR$fa^!Op#S#bzX=N*mmzBo$V= zXSk5@sEkE0`qAp)=j5d(TW8+o-Me>xVCeUq`9O9yt@c98MQ?y3@`aKjzPm?` zz-N6Ro*1*}#u5KBJoHA#jb=}Y#(e|uhN2IPoi?ti%ZJA!)LxPP2KVGE3euAN#`3Th zSGoEbG>~WDdF}mXn0*Q<&phC-SCLILEEF3WmXiAo=qzmSOg|_!0=QiA2>O?z&FnXPZ16iJ6SR^KOYqpR(ui>Z5eC;;J2(46wxb--}B>@^R^2Q4t6r zJs`A-e8FhIPrNMY3r42e<2k8iiP;s4e)C(?j+}V^{S)t>IC0|4!Gk9bo;iH@;K74u z&b)u(y-fyyB`7WK3jOO*d%Er*650R&J*^tzMUp~Nzj0B(L*oth0eo=0MqUuzLG}<7 zDV7HMg^a*nbcGb7DAQJcgul+AYEMTsr5`HdMn{$XA|9w#OhrNSi(ZH>Ge}5-DSm|l z7JupUZz#p&5jde5|N5FWo{7o> z@Sv9)b#&MU5co$5I6>SK1Kb|l+)iGy{zadl7_)-IYC7+mk(J>|hr z@B+x2A@TEsKuY~k4LpF|d}+O-9-fi-RZj}I%mkPs1;L0Bq7T^1KrjR2Y-@}tvcuU6 z7GfGr0wgNd6w+u4`?&2xKvrf@+>J3126$#|d__e=126t&=r?2}5ag4!AQD0=BH!T; zdYec13FFUuH}-DaHoEtZo8J4{MqR_c_YLmOo;`EM0MOpPIe75gvu6f@Uw=JN`sj;S z>~sv*QipKZOPcr^*$uX{l#mD1P@^wd9cdkqQ18|sygqJD^54}Eb;a=%-0O!Ai2EjcE5Od7hyfPQB@Dq|$pZJKO3`ruW-ae}r+^FvR61aY z#KHw6ArvbdfnSSdF#FX7;(36l*6iOA;oab{CB1wapFqg}B!Q9qIRZfJ04I)5U=5gf z``C~ec3^Voj0gd@Y}Yn$O9X*iPVxxiK?h#>rhOph+&VgeISFgxh3LhZA7p}$DKGjF@%)J!gx=Kl0d&wj6>-fN2J7EtS&# zm3fF@g3g5zff#!$fp{%Mz;_KcDUB8z6bAARykG!m^l+iDkm4GPcPO+m*Z}bI_dk4h z`(q29?WkM1ex)|Zo~Ql%K|31!A@!T76@!bk? ziNa^YK;3&;_sf=a-{tIzf)(JeM6a-d+eC2LnNuU`Is91c>zp6%Z zJMf_p3CJS|rr>v?5jYCMdQBDSTmimK)))KX0CzZb1pHGfAOoX$_N63R0Jwpl9rxZ3 z(m)tNU<28Z=<}^J3dp(EcYb~e0UVx0Ba%)ab*g*|Gw+nHz>z#q-y{h%Hh7crn7Rxd zd>IeeBnac13?b-(1I+D=oWQCBK}Z&3QyH0`>__9&0DoQ*oFA$|V$h3QGQI3vrxE{p zN;q+Z3ME&@@U9D9$GDh)i{N`EVhO2PRtCbH8DOO^0Kxtcg2mnsr~q49UP2IPAqEQs zz%s4%lz>ncQt_dMw$Ffk0zCcph3LU8B4^<;e*ZIEPvs2yL;2(boX5k!qMy2xWNgWjCg+)5iKf`rmn|g>4u-zo+s1d08j2V3;71P}huW z1~}Unx??alkd8CifDveF?}mQ^R=@W*0ibDCmJR6a-eCjv^XF#LFgE$f&M`JpZro_d zcX;oa!w1itIDF!;E%}V$oiUI*OXxfJ?Afz#&YnAW;=zLxonKmf-rU~9hY$bpkH5`i zRooXb2UJ2=h z*?=a5F3=I=OHe?Jzk)&sz<1;ZDaQ&>aabOOl_&v>3_?m8rd~$mXCv(%hYf=|t@pSkLrrW`Qn>E|73E>_kVbrpNT4hhiC&a!Z%PlBrgaHfl-GEAMj+6GVz&;Z=*5)GiO1_ zm_I0vqffX*M34Ce*rLe+j9_T+IIiu|zp&6z8ikREiuo8P5ElPFf&#_~;NLF&_~ONj zzdriER;K>wxecT>tR?vEZ%6n3>HYWj{^{UBgS0aTIppF4pT0Tx?A)`1XN~Zgj%3p% zW2WVYuyF1T+<_a}s)E7w?x0o4 zoO$h{g?GROaqkF$s8KpJ%^vU8tGqD3Fj1$rEt*%{3XvI>-`S$d9VU=06wNilm_T+Ag2>_fUhNBphv<) zaWKTYPor>XmLgFEqb=YtdNG{=();TyaD$G(pnns=O{Ex)1?mE_hpnFmH0bkTf z1YJiZpxuI}gn{CLO2LQYEvkW||E-SsF!pAD5Hm5`Flh*O2t+0{tsfx=ivXCsQ=jj2 za1`{VDl0IReVAmBJaa_tn4$I(HxOlGS^Gywj7f<|8fRWA8HakW1qi}Q7t1hP-Q?~lOP7@)i-Tf=I!7yA~+aEuaqRN6L z`}y4>p{q>oF+=|w3E+&sz-8FD-#pdO^V}2C8wb{cCJ;k9@W0Xs@sNi<>2m0LA|Sfs zydmk{*hj2`J3rQUer&9WYM9ssCmeKth@8Qcv?wY1Q5X6?y!MTXlrQW8yu3X0;zuWd zFKh`ofWL`>qM@Np)xX)a_x(TFRC|sWjevT#-+M;%JA2ON+{1ehA3Qv|?RUM0<{A#Q zo%;0O+fV)bsT-#T-#&f+OH}Zl*wmQGlo=r4W(EklZ$!JmEERUr8fQvCW)T|bmBWzS z)~=6$zVdS9!T|mZ{Yo01TQuq<-k1^1P<(?WoS2G9twH}-lFmq&p&_w9j>6SA0~_*H zKV|qSK7r^3?9Ve0JUl-LX6C#TGhzM5PIS`0=nO0$2u08V1CRYe1ry?6PQT{e=m~Y0 z``1LxNPPTdN2CIbq7QZq#wXw%lt=r#>k2@?pPX>V-2gH%;b)Hc&;j_v5d0V%(Btpx z0v99z3j6SF5x*(q|0(in%5$LWv<38mIKwhxZsHt_Avg_C*c4?Vghx}T1@=3zhoYuB z^d*NKp}ON#A3_LBOTD>k*MYROp!wsqH^3Z)&xAgrV17yh1R8Y7B$CHo%$z*-xCsHX zQDm-Thq~PWbZ~#r2nSP$24k{7X<=A_i3t2$WMH+Hu_y`ka5=fThJYz*je{Gw#d85$ zTKvMnyW!sg>KoGODLPvk7>iNBof&7B9D}Si2UAn00CSBe@+f zJ0=cfzz|m(ZXh8f(7hkr{3$2P_JPy2p*vFvFOu(htp^Xi-ClgztnN5A!GYj4t3%Ff zWidyNl-!a1D1e$?nxTR=Xz}em*#EnM?>7eKyQKUz)Xe) z_^BfV!*8QiKvMUHZd?q&_dc?m`+Lp=%^BZIjLsJ0$_~Xw%COm%g+uv5d|Nhs8eZo9!_`>5Gn{=N60gVzqFn1WjP>z+i-D#UW zW&dH$&URe8VfIT)#XNp&d~VLlCws@i@jQ#GDzwU_hirXs7*S(!A56hVHzRW9XqyJ! za#f~t3#hDrd-43a9YtL3S5Q-`P<(sRiy?}N6pK*oQ}7TDAVvb8Rwq6z2J1IWLycRI zKn6V#3r}C660Y;b+*p-`*8y1J20 z{7q^6{bGUn`DwluWFBftbOugyrkBF`mjy^kDdA8;0ZdBhPm(C+TJ*?`U@rh*Hk&bJ zn5z^t;_k~YDG#3kFxlCz0u=vic`3gf0v1%5*+aivi?)FxggtClDqA24)F_Of_Y;jL zg%C*hkQIhD;g*F3ADk<>1uWdXyQ1O^MC4pHA(8zZkBq#W$T?6~w*r`3bVtadw|3Cn zCSi0f!L2!DL^A}d*87vh2qkX8{tu@U{Rn=gzq>X{-3K>ROHvGiwayf&7jytL=48&^ zdC2Sx58(S_;UC(&D`r~91EnPfjvX#;5&KgE*RfP-4CmxsYk^5K(B1rJ4g=$%v!dq`y zr~)##j#@b&Ct$7taorC2Hg+j_o{$J#Q0j?*#rRigvZDH8?*0q{5s3iwyTl=Qn+IaK z|96z{NWdRO_CYv~bUsy$Fc=_Y&`;F|Cl07E=;E))0VhENH38EK_jy?V@eJatkE9CKAaO&Oq&5(Rv=Eh449rRp1tFj+ zGll61_MJ-L)`F}a4t`7nbTSx-p)}D*ml?6s2SQZA3cXQ@62dYeU|}V?o~~NmlPv;w z?_T?Fm;d8(s$q6cZcg5T12zRudm}I%xnZuI_7^ME@&Wx8bp@&Qgy;TSAx@tm(FUZL zWTTY*+Ld5}lZm8TDg4Zr=~s6!LssQ7hHV7C;Z+8IMf2wArTAG+;3Z{ZK^nt=1X_X# zfI>cf0NQEmSI;~I47>aUM-rI1YHFT?1LDYW9>|9>xG~^g7uC?JMFQ}RDbD~$-Yiyr zunQ>*EbtLzF^`~;epEz7wavW&e z4z<}XZnmw>-r8n6j@y5yrc$>k^xF_>e)rwq?Uy}{w>32Mj&9oceB8#@cEA22Mf%TG zgup6>4I1hJ^z7}_eq;)6mN&%xA?Fzm)5n0AtT-SmRHR3F(Bgo0`6yr@Dj*OWRt6!c zCgjqP$6;{@)-F&^;89>7#nE)WRSWo(kEIo$Vxq$mP#Zu_z+{0@9zH2xPyr?=06%y4 z$LV)?|9vNNfy|2fDGULTsDD`#89{~>jU_*@Ct{%}DTJWzVD|HIVjvR$CpN?x&_M(3 zRUZjqS7FkvJGn)d;4NE18UkRi4seJKAa5X=gvt3JeaRsF)p`1#WYQdx<$=3N4+!&M z*b>*|IEF+Ry9hUFFW4jiB>mf$9O9y1PiRF?PIfMsuTqf%`*a4jiI|X==9iEQ`4>|7 zloE0g_|25?NlLyenZrE<$ymTXd-^ojU!dAj5QxDx7gA^K26g$BHO_4tfHW-m7DNVt znk~Kx%*oEnR-%?Req|~;3WZ4TmU(6ZZXMnj0>~@N!7W*Tp%!-tvt5b7fh|f|#ShKN z(=7xS;meo*<7R%+))6x!XXmUm(G-VB7B>1WE-D_?zPPBA171tIJtDf>lb@q3K;_8T zZ?KTnmFaHHy!eL9Ar+@B@biF1`1g>P_!$`ua!v^>g$%_w%{vVaE;5yGD{86mKiA(G!T* zHaxqgqhq*jc6d$Onzpv`hVq8-Pp?e@`hb3V*sIw?Cdjkcse;V*@-NEM%QrJW)jN}{ zNRFiMt+(F#H2@F@_?8jBs?7{TXb=6F=lAr5K&DxQH^4*X?s0^esb zTtXPuv117eX!5?(p%f00__J?^FoaVf5=+OAQ)_}CW?1RaT>AMQ5G2uK0FMXB3#@O) zDf>IVeS0<+~}h=4JwhdZz4Vd9@TLfG{o2B?$B zl&b?V0;lO1oR+~@7`_GzJYe``BESn5=!OgXK<2_I4~8~ibA9YPaFflzQAiep0#ny% z`1KK3SO_ynSOh){zBqfjkdhL4fYbc;5$^((p5>tknt`*gT|08*n&DrreGC9N;?K6( zQ!Oy0GOaB_Cg@Rc)kqZDlyTaoSWpQJOd-sPs zr3S2x0uVS3uP7q5wpPI{guHGAxnK}p#I4v65YOF`#AxxiqBF4O=VnNxnJeh&fJmWU zM6vL#?r96>H}A-*`WKjh@39SJo+9XZ#-E0+IQo5;hoE$^1n5StttK1mLogPkfUJv~ zHwt*~UgNw0Vg2#|b74xY4wHEZC8b5^|1Citsua*%{So}eNCE%cMc1zV>QZwrJ#UXn zmV>JL(r+&P<~Luz_s6gQ_@}SG{`%*y34cGn0)Ka(;n%ZsXZP+MEf}wQUS59c)afNO@C1LMK?$2I)=&M%U|1mYJe;Fx^icVE7<6vQ(R z9P11K%@dqK!WR+4En&46S>NhH(p3h9e;F4s6dZjk>1k+EtmG zbo{#M101kh@e18K3d@gY%&+^_^z^sg)8DSLO3Nk70;C}rS6=(?v)-|fED-#!{>1>Z z0_Ph6Z)!ejB=rM6F$|%;NC7Z52FnwImXIRWf?#wlLON1sYg1eV#|3=mB2!i675pAES`zkl}UKmGjk*9rXZ?zy{$e|P`K0PybJvwzyV zt)T75XP^E0EwlODczEi@!y~8K+8Z_&jE+9odw6v3-oy5G_`T7MbEVc>Qz^$r1{pedq-}<#ZEJOb-l*Qrk;pR^es{i|=$eQ**!1fS_wTEf0CT(OW z)|ma;L-mhm0s;f)@gAk3mSPKt5tuiop+K-_LQxWGLgHBbQMf`n)d1WXg`Xy906Rkv zwB}$B!}`+8(FK5R1c~}U?kA)H9*Y7|IRiTpe68)Y_X5A|DwzEYLs;W?kiP_@ue2`8 zK5zsS02%?rygTSTaPT-6f6@4Raf3sjauBvBT7Go{)`)8q5Nkkt>BBMb&-4ExR z{25f%O+^d8j7SF~^Bd9uIs5|u>TXIEgIbWZx^<~o2WBW2hL_+siGb#KTlML~B!p;U9F-6*dK5 zHskc}9FWhgFDIsP4^|pXZ7_XkzMT%DXe#~u>k5DYpxwg#qTA z6z}7Y=~fWdVzaxDr@x)P_3gK}zFlP%M@2J}oO=xhQGBj7pZ&)Gt`0-#+!i~;SVn1BwPdzh?&-&C3fLe zS62}DeADT@$l?+Z-!7uxSLY6KKG40hKLZ6{nSbvB{qQgXXluW1gDrxIig@SOJD+^!p9#8}ROt_yPM8 zC}5lf=sfT!Z@`|05HbM$3hYS;E`#=3%(x8cILprmV+r)}iyHy}iU3~pD8LPo{26^9 zbrH|o;`==yptLW%eux3qN$_W5?@13ou*(*6ureY9oN`S}h7>UwqJaDWRbWP{jBu$z z3ghRF)P!B1z9!ut@&S{>iP-7j%>%1$VvEQuz*L`oV=Z7>$N}_2hprt-Do#&m%~Uvy zAs^$f3U$@B_pKu=w9GYOAA8-Bvco+@AK-<{<<*xl_?2R7g*u4<>qZPX4I*3Zw;Hi) zVW2+aQ(=;m9WD?&Az)8-PVNy9zy;}_?Pmeq7!=cj4}5&4OEL6<_WeS$j3B(mz^?+Q zV1qw9(U>gIBrzYn&O^*Z$IGUbD@ufM^iyRefNsT`;Nq${50LdTTKhjM&)SEdVsj+9XdM)(||8Ks-DUTGCiADYW)}I0G-0 z8YwKASz-{X{Vqelfn^?1mS*r=G;c^)WE2lygb2C>y1++Fhvq5}@K;h~7hR+tQ1QnF z;79xrgePEw7?DjeSX6Ivzi{m}>UZuehg}1`_;L5#T|J)tkNvv)?BM&=+n&E=i5-_s zg!#Q?k=f%^P4Cmg&_i3`!I{GcC5L{mpx~MVpwGeIwH<3{D1JJ({+;qRGy@++WWN2f z@Kg&>-F%b*(!Bn%E>k)f#Nv06`<>SVT1I}NI|y0eSm1vO#|QZBiN|1`LW;ow5wVD+ z1Ac{iq>V_$_iHdb!J2y22GU6}4Dw)N3WyoFm`dp4fPwJ9QGgw}fbH(laDTnIk$DI? z6xV^o=y%$!aIZuGx(skO0N~q1zcsNf#4+&~4^urK-w~mo=ihtgX;1(<0rZzZHUMC_ z@H+n^0$#sfCsKG4w-3pnp=CMABXAv3U*rJ^IWUSrPzA`z1WW`NrV0Rsep>svu6ZX^ z(5dmH8;PM6gRpa*kG`p#h*w!Kg3-fOyLRomd6Ud9wt$2*gtQn41#>n8+vJ)bjB(zU znd1I8Kp-Np)cFgp<&KchY?(ychkYTNz{uM3+#FZFWUB?vc%Dte@a_WUvcue*k~`Ak z)#%yTVa?~N7QY7*1np;9a6St(4g6Z{sYiH96Nv?)wze*`{p9EM)gZ6 zKQWKO%(BrxL%(_mqj5I2&#Vk{`9*z^@}cLkN`#`u5cRKI+m#>>%UEBLV_+jmpdMYW z?n6KVCSbO`LH>ec2-@N7Ks;uD@ zJDPl>LZsLBdlKLpm%ca-dKOkZ_$D@CasXxrNVEv_4)pLI9e@2867BuA;G#i+%Slf= z;1HZ~a!dU1%qv;pJoYMnOpyyti2+V|D`titg@a#Yiit2}ep8AhlT#J53HpwI8&)Fi25JG4B_1BY9*%b^H z$jKQ93FZflpNngF{Qc~+&werjXc%ayxuBRCQbeF*q4=LMK=gQ4R8~~%tN7r9%O59S z=;$y_0R6$&ZRKZKfym4Er08yXbd`_g127`<)&2`I=a*b6Swd_eW3nKm=1~MP7yE7e z4UVD6kg09hJ=i37-UMq@Do3n{1?d%L&;6ySAb^77HetU#;(Fuqvy zV&HE-{^-|^v+=R_75qDg6`&B%PQYjPo)|4S^*tWn{qVyNpn#8We0rqy`1qH_4PQPz z{J;V5aOdxSH$L_12>f07Yy)l}#dnUjA5E9i&u|cO7|=fhyrUr(p-*je<_fMt(t#yd zD-^5iPNvPlUFR9_pro5$_GA8H3~t00uo&;6fdjaNU;t(upuO7+TrXlL1`?UFVnIRJH=67}y8l2ouqf={eCmce(^7 z%*tuf&keRd=bRnCS!>h_i*lQl0;y(|6HVg}yt)KG1@&sHcY1MQtNC@`k=R;2;O> zZjIZx27kNi%b71h{U#}VW&m_3$Fw+TFcXfzLv{s$2ztp@ef9NB}_!w_Joe^yejbE>RsibTE(w8sEbS7>YmSpc(@l3r<@D5BoVw5dn;^ zy?23mzmUNA1k4rSCS!ofh+({aIr-YBpOzOijJKKQ?}lk$+RDc*>>wh5HEqeS0N~$m zz^JilbXz?*ALd_Nc-u+#yg$>vEN4iT9?0Tvm+j-uA%yuKLN9RiU<#tu02m&YBt%2A z6~s&80D$n()GH1_AUHInKzzvohb~q7C0Hk5vAsC{Ah5w|)uQX!Ls8X+#6oo3ej92M zd?20#s3@3YQ7?L+f5+Saa{9G63^k}fTfPkRt>7Z{ zgHeD?Gs=$eCs%4$YU6_8TRaJOLvTo1*_}{HhXj6vAYuxuTeY(xqcI19dl8H8qBL%oznlhZKqj|A{6ZXLMxk^%nwPZRJnGQelgPRtc#-gyXlbL;bs+xG6= zYaWof@is%i8^?#+=H^BpNGCWtx~=z=!{2}XmjH0XvGIa!n=WmdJesa;pIO|F@&!?u z?U|cZBFB;u{B4>7#!Mr3_>N>O*xoYHYGNO{yemDkWRLFvK>=mUv-z~q1H<5DTs2teTNBkDMczP3Ff@}*AD zcam=eLQuera2nZC=UFe_14s08A)sqth=A6M6sKfy8qV-ju@gkm!O)@JgbiO)g3@_i zxc55ii^32TnUJRV81X-1paYAlFUV zAa21pfxu5ft6l9a3I>sqieJ+xAHIb}AemtlwrT+Q)y(`?^Pc%KPw6vd(cw!&ymrht z0tfke2`fLkewB*_@GC8)^5w4>fei$0@-=p7__y3u-h*8U5|H=Qk4RpZ$^H)8ob4HdSBBG=Tf$lMg?X&d-9c z)HcWA_h>pR+GP-CWgLdzK6S^r1=tYKqEZe06n$t9n}QoO{x-N6X0kD^$AlQLxW2#y z&;|5{m_=@=*h;A8W=zb7O`wArj=(5|>-0W!qF+G3Fcf#jJWvM^4+69y_)EUC7#+($ zJAr(j*oo;|K(9piG-#iE+ZY8X@Ov%c1RP=zwEQy;70h>UyNToj_$SHu5FS(Jk@y;VM@B+#9RDz))dMAT5wyzpI|GJZ~n>(d6a3rcCD3N>FN~$1N=-eFFsOB=X}|sS*UWTMPs6 zO0AcItiVLVj084*z-I#4Aj^_$X&AC)WG3coGQfLYhzZLZqETls?+k4UTs=(tvUi&a zVNCrz`cxzE*%PCqz2&!~3HZOT0(?B%aA)Jj(M^{!(^;q~5?B>-VA5#`rY_o~f0&Fz zN1c)pvSQ<}G9Jb=gVxdKU#S82xFw{KqRRvfR62|%VLoQ;jc8UZH%Mgl(1&UbznvbA z`qVGQcocgcpsaAPgV+G)M?y38DasQ1D>QZ z2E;DtpNW7|QyHNbju|j${m5X_OH&$=jn`gIy8-n`0r{NJKRA?@bQ{^hF={d%A<9rG8a)0Vga z1OPVFjH73=xCE_n7AQ>+gy_WtfS!qZl%;Z6LPVtkaurym(#}luyWjEV_i>e<0RG}A z)NlsgLwj5eOG1JoP@&t!JO~fX5dVtt0)wyz-TQ+w7}-BMJq96&0y`5L;e>yz#4JcC z1qK7O^&eQ^q2K`K_AhY-7$v|E`xJy9MWU{WBd|OXM!~4j`cE4`VxXws235cfZcq)} z@x&WQ#QQK0^9<~EV33r`?`zaBib*q`B5MHT8TfiBwg+>(n^3a%?mp~m)aD1xN2Y3r6CoC+)Y3M*+VTD29<;STPu5}D|3}$!aT;&j4D+5S~%Xf`nZ4e8J z=E3o?+Vp~p6v#C9N0vG?WHx*6<%-(l>}TA9_YI;Kxk5tGNYEdyG9`w^9{A|X=P?MP zO$De*^ciKOLXuZHfXoA#f0g-60SsaR2WX1p^<&BM|BA+N!C1l`Q0*X@YzVdq*er2H z$b9B(X!wVatIWQ*5>vO;K9dUCM9s|S=me}&?>{X7X#&9s1SIh612cHcerM8`8wCvo zqle8KjBgqSn*Q(b;k^%B2Ke5_nu7A#S4A*3G#@%tVAhHT>!G8{1;~d1*ghVW_{CGP zEdC&higpedkwDVGkbO5 zjZr@s;kf>Ld;gBNhj)bg2fHtQ4%X#Y+rQ9$bX@bV+JIx+`xmdc5WL7POuXE3QF7;# zG56C9TzB#@hhPPvZig?VE}n_&-17z+c$3~=q`FLnD@PL=;BIE5HC+#u5dolq9++Q~ zl{hvj1zM^X9zNFXbPb>|Ft~u>5wW)r2IF~HX-WmWKn@tZz=8jzx*X8EfRj8CAuZK2 zuv`kAl$TOihJ-)!zoq0t`I7D7s7?vF>mwx6B$DL$f4R9GTndiRAwtrZq`BEWye-H- z7$Fd5za;wgU=_Iaryfz3M z0Omm!iDhU?&VgNA0_N?qoEWp8?7MvX^5uuuKJDnpp0I?36}s8HEG`DW=6D^*Py-!w zYaJr{qlEp%=8pk@!SF`$Ag(987UNAb^sVOR&_;|c;;rUYkU!tMNBCnY9NOXJ2=RE- zr56gxF9iTv2~v^DFiUMLwuPW+qcQhlI$o{^*p&(aOYTYjhi>2!qF<&L0;2#9yD_;y zIQ#Z_rg9c5((Of+S>l#K0K*N0>pzjeS7p#Rfe7S40KYj?y|JKR7HqEVdBfaZg5oni z1NKY^Xq}M-pEtZS+y3d1Pg8#(f*CGI6an`a?0O04b0NPP7z+X53)A}X}^lMQQ(%a$k zYuJbBcTJ>%i78;B^m#DUzy-Jy6lw<6tL-wx(FM#B;DCT+fOT6U0>~ww#X}43E^NPW z!J0Aa679gac_8qB#@{+b->V3zDP+9R>I(*F>%k_s1vjme1%z|)YHvYzBy>bf4&DzB zLRk0ao03680r>js5f#i&bq*+E$augo0_P|6#3gz}Qrs?_!jM3F%E{ifORNwpK_x?z zC)$26pNi-ttO7?kiMIL?xFh!(LJt(9Du}dXXi`PcKNYFBXr|Rd5U=oI#9Gs-3ei&+E!)MLpT;xGcM97*|r%!RT4I?)cIwV!FC2RsI~ z$V|f62Vx1h%reX|u)e?QAcC8SWg!&d`dbpUA*mpd;I))!PA4!v>GHjTK@gv&Vq(=^QpEC4i2|k zbKiG=|3UjdT|vsrpBJNPqsGcEgX#tE?Rb*`q>mR7`NhWD<;TQt$(UI7)LK}E`o{cIbyoF_+asXGFwE^^;Rqg}H_HYY{ zatFgwP>)q`?wWp&%fA`UzxM!lGmVpoNS!AsDFMIQIhpF6kHY03i-!HiAK( zc{qT9fI;JaY{tw405+C%jiDdJ$RA2U2#3H71>$@CrS2g{9GB}~{Oxb?3h-Y@V5ow= zD;>0rxi$fhZt5(*@iE5P=i|NG4*O|DEb!oo2i3*p_MhC1sqGi0p4_+%{`UhhkVoL# z&kHsdTkFua2AnwBrThcx9Ze6{kapTa+Kus5@iYuUbYB#c+NHmF6U6lC93nfMHwB|B zPEDEi5uI>kel`wk2UyUnBL%_~)sMsx7)wB`0s()K#xH39BH$zH`5f%}7cWJcn+tK! z8iVgEkGe(^u+6~O0+Innaaai&n1}%mM+tyY0>bc`xCKr*2*V7#C-g}N6GmUfVBu>~ z465_M<7&Y4B1|5FIr?td9++TI`%wzRYRstQ+|+Hk3dtIwV+40xcMALQ0v?e(-a}Xl z5~@PBhP@vLTBKTKS1Jrp6EJvPWs(D;38keOWPo%}4<=;P!a*_J!ruz@-|oVzcG}6y zv(?{$yqq^U0OuUIdbMKr8x`=&S%v%)tC`P!nLYCI<-|Yi|Gq1tZNB{T5B+lW_A?u` z)<@#*C|0_*S<$KXo4gEoF%&MbdF~bnpt2PZy|t)B1YSlKS1m8SD8ku;Nq`oJAOM_U z>a!OEF9`vM=8@I3!~qQmSU=+}woF4{^ox>UwDto7{J$mvw6`(xzQz)Z%NpBruWO9i z(4iJY390BtBL3+!)T%GP_*;Ae`T1V}aX^m0&A)fa3o!!|=TAL;x8E` zNT~!qf}oPGgn%l?1P-R@?3?QOFCi1~fzT|5g4;)>L0-jyysHL!2d*B- zvw!vjd2bZb9#_Z%F(B~rla`*p{N?4u#6KqfvBH#?XwtQcqvrS!QoERVz;Jm?gXH=NKq>%cHPZrL-9E4-Bw$DGGu{4m4JPApn1pjUb?a_c0F}=Nq6N5YUGh zKs$<<3uM`A;LQ5wTA1a(F8>uPKpKIIxCGQa)L@SRf!2yN=6aE?E-QaCz>xo=3k4xS zOXGhO0sa_L|IYoA06P4M0ulkwp4rq}(Dtzb;E_88y;cbKEI{C0UVd#s*rotfJpW); zIYOW~;Nxqv1shEUUEO;J#IFsRFGuAE>0{b`70)4?vv3oMv@gJI7TaOTF!38TwkO3Zx5~0Ht#46Dd2Yot>z@ZUSAy^Rvx(65mSQ5dI>J0}i zjGsU@gajDB0dMeC;BgOwVH~vQVTCd{+CVe}$EZhLOkHsM+7PVr50O9`K`{AV5F6z1 zo8ifSHyMGNs`fV_U50C5n*0c2+>q#)(1uQ!OBT{4(7tu9jD{)@pQOdDz+v@g7&{eQ zAv*b@|1Cdl7qBlcC3r-V@*{NQC71@0e2lx-WDN$}D@$rMGl&yE*Y`ztklb9!0X6%o z{Rp!!VDU)yk&)auFh+3+BeKlpl$ANMF*hqG$IrbylVDTm-Eee_00;}qR2>pOn21n@ z4t0xvVI3SZp;b~`NSHGKyn6LNt{$)n7_T6N$-7EXjD5e5b`gsTeDY*p%GSZbmxERa zScgjBe#YfH31mWoWX}jQZRYl_IlqeQM8ZXiX802@Rl^eZ?c%r4 z#jN6@Zic51977<9v0%Uf)k z^|XZ8Nm!xKHt13TQZmM?NJ*wn1MPiGhjt;flz=66SdLF1TK9?ny@G(W#+{Q0#)#g* z2b~3XEaUI?Z8-#3Vu zvn;?yL%X)B**37iqkL+|6DQuPzRfO+?&9f#TT6AAD9eHW2ylZC0F{bG6yy=){40LA zJ)RJqkdRtn73l?t$fq$_*$A+N0M0fhfM9|au#?HC2?&TN7}X&u3N}AQE(SnX!1x#(P9aed(qKqG0Q%Vu(6aA4lmX~{ND~{B z2S`ZV?r7%#crgM%c;IM;yC@pSR^aOlL**tA+GV4FHU(!u0gYrBgGU!Zvp)%+G&T9? z3%+;2nvYoW;ljYCjO!G?7yyF*C9mV^FD*(p@b{hKe>+#3-(#K1(E}c)3KWymBKXrE z<|lwZH-QB83wWMSz>z6Vy&)Qt^96v=26`H5k{6}($jfj9iK0d50A?c+y(9$~%+{<+ z!E{IrgwR<%N>aE$9z!8?C3ky*y0Q`0W#-T&qEx>H*?JdvInFDD#-(+kEQG-@dAdaw zINW`En3Yi2qEaM}L9ky3uKruj)dT;B91t|{>Qxg(uiaOPj4WD2_U$tSwC1>pi5(rs zJ0`AVT*>HmISf&(zu!-{I^T-C#Tr4DCP@m@-|fcW?rvR^RTnIpsMR3Ef4mEW0NU$S zHo6v31*24GwjmXP;SI3`E^bTbg9qRt6l0d69CHY#-=cwfNnnCUxO91mL8;6`g*}cZ zk48kJ0tC7s2joFS>JR_~*c7XQHBxrjQN?V)mwrz0fe`P0{-+fnXJASJ?F6#-cfI8Z zIlVDEUbAhR)xe!Ov$xaA(XE~B&a9oAK3y}#+1EJW4+eZso=ml#Y8!uU;Gj$CdJ6-b z+_Tw2^xKZMA@bP}aR280P(6e8K?_p_In4RKKiDsxK>*uTPy+VhZ=Ua&=tl?V(*f9+ z-}&?7=l6u1XuE-!45k6c;Ks)LLcdZsgA`RRSkELEeetuudnY0lwxT2ok}pVfB%}g$NkG`yQw8 z&s#vE);9p*1ZzP20vt!eYzUa=Q3%^*gOjE?*x_^vmc#9&@DHH}hKH*mhB@hdNV0!; z3%dLsB7ip;dMYNEN>Q}Z@UQFgi^t=29E6)Z0M)R~uNsI$*y;Pfzy#w>An-9^1!&W7 znj_%U1=stz20AFBQxar>X=!nhaB5mwloNxPtPuR-2{2{|M#hz)Q!XO^wvL1ec!UB$ z387^TITGujb8*_RufXXs0=Gt4*~qK;FEG9te8J5t0%%mQ(f|-BCRZ<#PIJiXLPxMS zE=83f%-lx|zHZDc1+f!IMS#G-!3V0Rn!@&rJqn3B~uI z`MZZ6BxNB`{#UOTJ{o%@V7)@y33WCFGZ}&L_?&{JgSKNxz2Z3juKaXy!TR-g zEDEdK-rM1Wvk7=V^Z#J{sLGNIu&?jWfA~Xtl{zu|j3GiY0|4aK&%$BG&pY$O`yI~- z+!M4gdpsUmnizKkzuJ`)qOt0I2WSw8jovGx?i``-se)e;0Peb0IrYI@M8dsf&gPJ%xsu~!|7v9XaG?IoU9;7sT-jZ?YAo#6|3~*5-D*Aqt!xbbsdW(cG;rxqwbPI+So8usSL3WRXOw{-_C*%B} zm==6qU~qIQ^P-cK3Z28sU#I~K%NTEvB9||{Yup2lj0gv5gcAUIW2Tcm`>lk(IKwI^ zps~HfY+D9@uO17PAc44#C{G$O&nm;XQX>Yqdtb#H z=7+obe-42Dt$M?r-{27hz_=UmXTx&E8xQxTUbg=Y>M(QgOOC;i!~{g^R^gGEK&G7q zqSyoR2>l`Y-Ys!F2Mh1iB(kVH{QfIJEx5?uO#Cc_A$+@NLg<;9MrvJf{Gbkys=s+= zq0$h-FD?lckqijfn;B3a2=WjHsDo~tEcJHGB6Xt|m0Bt09?MvrpWlNR1Y7)R_RC~2 zYF8#@F`4jzaF=GL5Jus13P$tqiv;)+-2MDdH()^^H-IMft2Q(_@^{Ff!Sbd)ojrA` zdr2QNtR+_sH#;D6h~7#wVIPv^V`{b^^6eBOuz8!+A|gbrOu(E<=@Sf6_q zOi02?h(aLyOFRXKAQ+#14f<4xq^BJuemk`O(>S~#K>`@TA4@>I7+A;OE!_TXQ6daK zmlZhNHdv7EI_L}!eDNh9F2Rq(8CaRA8H_&l8%S{cPKESmoj!sC4)ABrx9d&G8S7Su zV~D2OsPjC!d8~6e%sS6R-Rbv`R}R3e0MX^wqV>~WeI%;>+!P#+#thTS_q65ldc`v`ZC+XQZrUoWD5zI(A{x#w3wWa!>)Ky z#?@ji31M^ST=yb$J0drCD<_)%xm%pC-3x4C&i736g5{rJkfDIcM#W-qW_}3F4-3M1 za>Ajd7p4WIPLOROb_@=V*3vKm69O~Y4%}$zShiZcH)d}pgJC@+#L$lzkIHB)%#>Ly zf|J*lf|5teFJ8evV%;xB;Jdy7#PrKDxCal42ToZEG@=0Q5b~t;RO>?ny&F>x?Wy(C zHam)Mrm?-v!aVh0 z+G4O>z}N2YIEgUYKQqEZX#pcwh!PR*dn%xkVe9~67Z5$<2(DKuOfj>eEfzJ=<))!` z&KrQAIwlJH=DsrMvmRi3HwIYXeQ-4_MaKzb{g+$;etti?f4C0Ny>O@92p2Yh(g40~ zVW|7#90b$7yd4W+cIfmwIK0CPftiFA#ou!qXips*A{^Y{7hupknm)Em5EF7x#m20&VX{4hRM))yq0p_@%B( zjug*3cZ%{w%rAf;lTsO-l^Teg##$OeQZ>+~{ZjWFJ41+jX`x@;bumfd29lEEiB{|| z&ryr7W@17ha{-eOW{~Z&K$1QHV915BGl+f5e#eO73K-YNeh-{KAa_IOjpNueN+9B(b+U~ZZM`oPsU-ngmbx1nF2 zjv;v(i1AN`e+g5`kL}`=W+&_kL@gI@jg8Gi_=3|f1M(<;q2xJB{xUlsMA+9y9rW@G5WrUu z@R$70w}O5LK8J*>&W*ik-&q7SvJfl~Yii1H@6@NWKR_=}z~&8wm+A_BsUP zD;nP!pgoO`hhS6_0Z!ITf)r~1hZAr?J>H6YZS5C5W?ax0RUJiE4`Luc{|d-QH2f-R z10fC;1N=~i#4?aT0Reaz}iFS|cO_AZ_`f8;kBxCp`>S+`v`mJ`$N9_Gj;8k4wv3h56K)~P+j_$z8krD2~&t69XESO#itdd zWh=LZ+5qaTE619T!&_w;&Miw~m2jEP9+g@ER^}O+~p*Lk$0ZVj;+`*Izg0w`vvWUtS(b;2WTU=7{sht~@lu+xiqIcXQZv92uNQ z>6kcR83_i0E6vKt3eRMA+~)N!_Jh!MvqW=6)gjHX-IoC9D@3jTZZTAAu{QL@*-u+l zZvZ&26oh$&!Y~U4;iu{bp3wnh$)Io2w1D0Z!t*YJ5e)9!*VR}Q9{4)R4RqD_4E^qn zK?e;1;20axEg7|{3euN!rOX?!ST>d>Oa!Ew2yp1fR~3Kae`jA&!QAyX%3Kb178l$} zMiSQT+fSx0wAyu}x1e`pr%9WujrA2%|J%^uPzSol>?*)tyCGjWu@A-RhJr=|H=`5N z0s%1!D;=8BXU@UIL42Xl6w`kI0d%UzLAX7*MA{t|#R2z3B(R~uFTv{@YB&({1X3f3 za)I-}8XQ9ae>i`1>ZUv7o#&zUd@h1Mz~ECCzFnI61p4@u`jj0~}5%_pixmAkz<;)+Ia~ z0P)4u;W9!D+!+qPjD%Si@?m!Fd~+2LFpR*Se-K4O!}-<(@Vgm(JB+@sxZ+ZSXeQZz zh5`~&tO+OB`yiZJr%CkP_H45=P!a3q*iohU_ueMcgvdf&)nl(9^3x@Ob0uu2n|( zsD3yLI0HcFULwy2XW%8Bh0&GiJ?Z3pLjb`6E6Ox7 z$Q*=vHDZ?1&DDq@7^3KT&cXE-A?Q_T#sZ6oeI;WGz*lx2V8pUh&^%t{kt(#+cBOxT zAk`O<3&iieKmXzed`|R_PGHkOKYP$wTvI+f+}36;xL%`sn=C^9!GqE2jT_D3QBYGZ zJI0|q06<`rjjrkK(D=3Y9mT|J>X)Olvw*;(EPgwRD{!CkPOL=r#yDV-DF?X;%%%i}PvfO{)`tmQiIXQ2vTE#)Qn`YoeayO4fSX>N_;clON7d;9FR}5VIvj~Kx=#AVO7M0G^ zCrkp^h!co%@EZ4w-D?EyrT^L5k078kzlQ~eTA2_Ml_4U5wG17*chcLbF@_QNML@qF z9qfMo#RTjCc=wz#ug zAI`x_gRvq4>=q`K4d~ObUpR(b>dd_7IpE(+bo%9sufp)lMIawFaS;A}mVp2Oc?3?l z|5E!BT|iEUESRIO`TT3hXPGe3<#$-iK%Rg>2~mZq1IVC6Fv0b4JX}MJ?u9SO1H6H& zKlNbp*On*%f%+F7cbW62DL5lR6D=*EVcF`BKfaz=g%rHPVH7^8z?bX(`E_XsS2u-; zclA2we)`Ir{xyC*z+Q}m`pT*|cfRQ%fjZ zSt5e)!4*0LTK<7|A*F}`vMDoH#c%{Tl0=?GWbsv9u=#%}d12CDws_kJ8`2H2EbEyO z`3T9%F8lx4df%t4?{i%gDm+2}Q3RB31lHnaNS#fmXPnvA&T8Kr-?;iB>p$ApkNfleezEI8;NbyX zja|8V-S>U{u<}p6mY#trY_SabjBYRhKs@hIGU^cl=p{Quq72E75$EPB3Xs1JYz6}) zSltn+;bZs|i;O?d+AfT{pnECfl1MZ#f|fFdXh^)oq$RGD0W5y%*ki05MD%6oYa8NsH`Rcdci+>$X#iS{+m|YZ=XU?$pLE> z0Z2bBKxM|WX_kcGBgmh!+`o(g{^{R~6(KUY;nV+w;p6}L=l=~`FpiNQ;T^?mhj`>5 z{@n)z1~3u&+SvCiq?;uS3JqIb_zMdNezge)0gtN2ln!RHR<~f0R8H>WSxKB9?8pR{ zoDrv-#6QzyHVfZ>=fuqrMCZ|f7vms&k?B}o2&Rj$i$Qo{mmK=%D)tbs`?dWYnK8tZ z@jr6n(a-Q;kW=!0{VbQ41Eec|u`{8%hcFto^Lo=3pdG6nE?Ivr;_^tBvq%>nf0MR=zP%kb{~Ua zMm_UU^S4z~@aKv^RRF?PT}qv)ydA^n``pUW4YwUPU`@cqi|@a`W&^P<(ERV8|0jO^ z>KDKG#sBru@%MbzxS1GM-&X#g5WjTGu(W6J(j!4%42UNzaCt>$(F+n8ffB@E`ZWdI z^BqDF7KML%lnj`L+CVq$0XYtb-Ay3q7Pvp8->P2avN_7DDtP?Q#~3kxwMh z+UJoCL4aEvb9%lAYzx%$mEX9xPW(GxXuHhFp8Gx)?k;4i7=N*l5)jfEM4k|40ha3` zoUaJ;^n-#3x=Qi*6%~a5nCg@WlWISbFF4gC1GawILV~!yjTtFaVJJkI67; z=(W*9=Z_FchsjNLw|Cu@4mhLX4Y@5T3_+S062xW@KMAL=(JYKP`I7Rj9EmE3FKXDv1SAVJ( zVM25yseY5rC`me#;sl3Ti}~GmsTJuNQSh0sz$ytAy**&maB#qvL;zycNaKQ)ex!S}h0K)}t3%g<%4{)}xw$$Njn0 z!>=b`lfG8#p9OjJ0GlH6VVhoNilL$K1AQ=D`(%z4L zxP@{k1Jg*Xmn(7%%$9(7_ct?xaB9x1DC_{M^3j)^rb0QWRmDVT{OXAZ=R=HtSuL=^ z@rhFb1$J==PDxiyx)Xo-Wt5zUEACwdAV>)9gam%akynazHuN$6xmh)u(m^*l{_2eL zoE-uq;mx&Fm3~+SauN^n+VR+xaS#^rY8=YvBWevEFb9Oq_ed%PF$=70=zyXT|D3Y^ zk`s2YDT&n3mf({SWKop3W)}K%sGUAl`;phvIh~=r>ai5q9N)K%U z_+hRYOl&dseZss?9JX&i-SBW3Vh&bUo=N5G5m>ihWu(S!*srfL1_lWDYqi92{B+;0;8@m;7nKMtzb+BzF8>HL%V1FeJ7MQaph zik1x|oRhh09E_{TiLKZ`p16O%0D-{0n>>R=F2ZpHmBOsCxVYjec;876!+XAyFIYqI zcfkW60_uJ(6bugNPx~?h@IGIF8GjH_fGGoJ#Q`w+1RU`9RwU!Ul`R54_@DrR0>CWz zC1v36j~o~sK|V`eAm`4VQw-KQ+I~~`>E*-&ixV)O{W;xyxd7Z-P`<>AyDV-2B4(B6 z=QE63h(~$(jdI;L_`aS>-p=QcnB`rC6nZRsNlsvW;4ED(3K;B9<-nQfuiMJ!id-z1 zYCDZ=7_d{9UX2(*GX3@XwJC}#6JQa9_?bhyoi|m4Tv3fxHsuZE{{|qPJjRP z>-TniiGKt*L-zjp&woZV|vZoItgNa3!B|@NqlF(^aNFcN!4^bE_VJpT+xVB%mr3 zI>dilx4S8~&*4#GXpX_RCQLDHF+_*W{mrx-v7 zB-rAncxV$qesnyRPQe<8orNXV2s~jmFoExqqFxyK2XUY;BO-p+Y+*ZNvIjjMMJ?JL z${Q?opP)~^xW`8n|M&QCbS>$Y49wFpS8{5(d({QpLH;yFi_v?FU9a?JdX=xr}O4g04QWO5O{)FNrnB#_{6xbT*r|}`RyP5B?6mvLSzo{}w z-~WpNaQGXaO;i-3>qwbmPs#ZpS5_Yq-yY}^j5HVnpa)`JhE)jijBQA7BL$k_&t!P3 zq=3l9e`e%+q_+o5#3%U!0FG{VH|`~)(OSAECeINcmwT|XW@ ziqHBm+oe~02)S_7!>u0xKux>Kz=F|DQ}5uoPr|M9^Ru(9!$+$F#oO`2m4!D%@r|72i)hV=tbh+fBt!{ zjb>6l;Vx3|)A*aWApJq&=RFUz9waJZJOby~m!!~l-U|BnK>(nC=@POr3`XU@Z$<-B zVBnh@WAL-5J2&~Igo0cHrWN0o zg}WOlAOSFoJmoY@##c||6Wc2f4Gey0!G1XXIL6^_lf1MB^bSz3X?5tbq^vKgx`2Lc z$V>pJ0P3KE?O6a!y8*C;2sqT!o^=JQLQV*Xv5?w0dP9hC?Q#Y;ImcNTxFeN-Xd;#b zrhU_n-HgF{cSjb2T59p{kaq8|N`6rQqE252Kc`FshhrVFv%`hLNL=M}+J;R66^0Oo zxInujhodt1FvuTr@Z-cASKdfOm;l;686wP?79s%#2Voe6`}@5OMu`))e;? zX)voEdx?7f2pu4gAt%WIAIvc)Mj}DL-?Q&f3-Y#lKUO{EA_Vmrh~V3<3y#?r`@g<$ zgRly2l;qEq803U;1D&~flK?nb>-bP|r0og=?0e2ER6qXxPhR=`D#72M@ay03jaO^0 zKK&aX@|N_WTzwjEwf6)3M9OMa=LYttnYXpA_W~%N$sQh4B7iuEw6k&dWFZc#a0g*a2p}**|Mo@yTh@c=AJq0QqVV;n#}KSMgl*e` z3T88Ko(3%&+y@!{z3*zwz`viRE~Ga%K;Pw50^&$4M4=WJelh?P4)>-q5S@Gz08$N8 z(7!|n=J}BVAH?xv*OsgqZp)Tj3hhh;AYd}SWlO+(2k79JL;&l_{O}8+XYx6+J>G;D z5)AU4Uxhvovl)&furmRR3=lt>H-cn6afMujH1frVSO>PqF4mI#!v5ii zglRVbmJEQKu5HR5;S3Q2)b8)vj`YGNhNx-|zIH~pTpc}jQ~5$RsGblf8i2@Q%*A*s zl?%bGrP=X-hc)$H;`D0}yreJ46c5t@^7xGBV1VHnVPB?l!Qcy;heyX|ed@<-D}i8t z4L6_oKr|#T1OfsS(VE^v>m2?bYVdbQ6Jqtdzdd*D@^62_Kl}?;r(4^6x)_J0PcNQE zpKzjt={lmI)YG~nZ$Q6@#AhC=M_|mqa}0zQ;?WzY;W+h$cuVMmhfKc|J&!U4n$HM- z&))U`{Ag`%ZEmhpZePX#_H|Cv1~*6IL$FF}IJM?tPzCC3M-k3XuqO ze{wAT|6nc_AAa@KtLJOmS-cCtT-F1FG@bASYve=8qUWNe0Ow=Sc&3S_Qm*NiolN; znB(Dp%kIEg4&XN3fA73^CzC--0mA`!{~HAcm^3iy@L?KQ1i;7xR1_d{pfd)zcV`ZO zl>NnGPzo4v<>gW(2nw!aRPg&}b;1bv-^p zA+r)r zV)(D7;@#4@caQ$~Q}ds1{SNY$VL;%wpM;L(TVH&iO6>eJrDf%xhfgPO+;D6SIs9si z_)P-9=bdDL4>a{YFx=t8oVtQ}5q_X7R47|K=yoFg6nTJL{e6lX@TboefbdM-IK}|7 z3GNXEFiid1%1G!wC89nM>(M=UJ45j$gCXM8dKsvcWz?agN&WfD&PT6ay?lhXe|`CK z?Ir3l|IOfs=@&3a{Cmmz4T*KF6pgB*YT3*2oA z5GWFey64AULAc$Bj zAmKar34#}M5X@o$4_#y}5#D1E4gi!PE)xWXF8U+K1Qt+Em2vz2DNMpfz#j^N8ASo^ z(VvzG;PD87kqK^Fc!9U&k@)!yBp-e=5zHI=BLRB9XWyLnMFWykP%{FUAAPTEZ2tx7 zMGo{8x4`Ao@2)fn7pNd}UG^#&W@K07y_{D7;Q4~(BSS!#f6o`?&XU0_xcOHcuz36c z>#JuXOzZ-Ih};PB3Q`_pak_v6P>$v8AoayezyyM?S0gE45XB^8OIxZ!?A+e|ar={x zOYJ$m^WuwTN&J8phEyZTU6`TLz7RHLwzM<_02=t9)BELNeWI5)b(dSy5>7Z9=#V0) z+9MT!TvCZ!w4PrRK86ME@!x&YJ)DKQIQfs7!N-pe`{dy{n7Ze~Ng`wM%wvP!0NLY! zP9fAcmq7D+S~T(k<0dBbWT2%62uNSB;t@JT3#k&UsUa7JX1XUz11h?)-d)F@^D-%5 z^H2j-f#uFe9S#J1p^Bu_Lc*t~hjXo9glU~Voe2fgL(=GP41hdn0PE(+^<>@k&W{7J zKo9`f`Q3v@j0j3xTY$kQ9lF!dw|6s zqOfq|RUrO$7=fpy2gK$NY4TfLi@Ap13dno;lGumGG63+ov!TWP^mz5^(aUA~h=GA* ze@T)D7@Vq|S9}3TnFiTGj<&sB2Z4bHLHh941sI!m$_p>Uc)!rr*4x_)0Oati{UGp? zLomP%U`h;RJgTlGM+5x?fRiDQnH-0M4rb!%Dmc-R6#u|F1noC$B8fb|T2mho3dI^=_k{h!Y~HA5tS z;DG%T{oMN<7-%V5>Ji)3*xyq#G*nYoGt@s(M(ihK*6?qDlEC_U{P&7$$nA4Y=Ma;1 zYYaAzZ(n36_d-MQu&yE5){mRO$kO^Ybu20S#YxcL@Bo~S!T`WmCz*+_E|8#qs{+9X ze5fHrk4{J8uXY0Qcm_r?Dnk1{eU8;1UVsnSg-D%iC z$Xy>x)cX2-4d&67<#2tpiY(Voe>D#P{MWCRUoHay*Dw;JAu|I&;NSC?2oIc(IwCdm z;w}rEG7=KAxRRU2>?;M|(I0;V{2e@~85mrztrhf-43Im(HoXHM+q!y>b?F)4ud6Ga zN?OAvB7UePp?8XLDGn{*q(iivhd@_|!mYsqA%}-y0#MLj+5}S82tCLLJ)2L z-is!rx6%#xtxO1*wt)NpVgKhMOeWtG2O|r{_;-8fmD`p%@7oiwHpH zKktoL=v}+=VARi^c;Qc5#w>&xGbiLIT<&Nr zj=$X&1B(5PH8wUTzesmQMIINJ=LY7*Ah|=Xs;Vf4NsGTiP-*~Rynr`|0()|-+~ltG zc7IeR7I%Ry4oZ+Q#J5=Ymmf)y2iH{cMxJLS%#J3VHt2xkkNjlIFo6-)-!ld|%lZbS zh3N93xZ< z%C?BqaQq!Yzj9B_67J$o3&US4tUgtDQJ#ss=%1JoBX3B|wowK0lu1{Sp6c!2x2JCq z{>%hFIqmfzr(d>#JoOcrN08_2#RN{BTs*XRXcdEM48jz|Jc^jqPIy3En`sv?r?OFM zp>YwR`uWpN#-RcXRR;3tIU13kKj#jRs_0RK|EUd$b(ntF%-a`fs9RM70>Bal>50Lx;xz0>R(ZGDRp;;()F3p>|3K-d2L! zc-xQ12x(pa9q@OQNY}=>c1p((KwfWKo6&6?-)S=h5(Fa*aNf@-oYBBbJ&a~+8B5%p zIhiiN40f=3{ZsL&&Pl09TG5&%2OT@&j<7V4eaa9rPQLLcdkq0J;w()4^nikBu$p zmlGY_c{Vcx2l3mhS;#SPEacDS@hreCCgA!!Foq%+fL~)d-^aKyM zn3@WtYb#Nwy{h~A_3rMydv9O(Fuk#YSNG*8f!d2+cFSv>R+c`^3(hpjluu* zRmK2$AX$6KANc|~Ec^`|drAMKOaXdMwPI`6mH}4lY*%`a0dl;>MsIw|Zr`?qe*6gR z1OD~4StTQ-jEP{EB{LMl;B=CNfkHs;{pg_^*U-EDe(m;2ankM50W$SQH{koabZ@g;Ffx-BK0afNV^dMb zkxi)Lggw~dsF5PAA^C9%Q$2j}l1q{Fi~pg>0SDA|DG>~hyZxIF`1Elgt{+$d0s+Ym zaR@;sYT43IBch^l3vOuG+yISqT|*sm^Bab0zyoW12Lb>pfvoCo>D=z!=fDF?SWXO= z4;PIdHuffjlK>D!=?qZ_)7x--^Yk|#`lW9yiY`;)6?D&szKe6Oq<^b22S0O4Rvwdz zE66GfGZ%UI1=!L3_MkK1@9jl-<9r7Jv3&dO(S&&D1Bnb!{o5Y&57RJKg4qA@5ZpI6 zuV6qPbeHG90;(-9&tn9ho_@)6RLKJ40{rOFqcwc* zvl@Nr_5gbI;!Teq6R*>wRcDXvfgdIt#FEfi(3*wgaLn}|FT<^aM~$n4F$PbLPmU)$ zG1(wdd{PG*h@gdp+f@`tmy4t@Tm{AuoQ!eYk17}tQ}3aeep6gN2_U=T#Qi>^ta)GV z`$#evo8_|m#~#5Tc_bJh$)5$+5(3_dT96ooc>sCuPGsTx{QHJEU@-_`{|4u8TtYSs z!I$%U@Z~q1gK#!C0E_tn@1%&~)GHvwXJg-$ECyNt$m|yrKyCX*3iar5{Q%Fi^|vUG zUJo_k-LU-X`y+P~-q{0}5YZ60C8W=G#g*4*y&r`tbg;edboq_!EdL~!Agh8mw1^NL z34M3jFgKRf1b_VT$AvhUV)|7ke9rN&nqFYvKuYZ~0Jm@QkF*E@O#z#f1kEx`_kd`i zWp2wE<-Q2$E-4v-(&sn|6Z0@1U-FKSc7R;;0qj<=?OX8*@R=-dTmljd-HiEN^2h-I7m=5WFzAzVUv#Hz`xXU(qfWpNJBS*BN23pYtJ`!3Z3$uD-9P+vHe`WeBxYik0dPBvaJ33KoN-k!x`OqO2~0#q+|48fx*y?K zGz2RgpXhgrF*?jg7+opUWvVX@@b?j~x@p$^LzqE|)30oB4~2r<0a9Nrne_^Oo#N41 zbx3zoD=?tXA{adRASt2WC|H5_$3wvP=KeRi0Nn2>ILV%M{7qlk2<#A;EDv?#E!gJ| zBI3^1{U6f2?A>eTx7Pp|ldq=Xk#qqD2rfiD+?Mk;gkT8%D^p)`8H_Z6hC8C-!a_D3 z`)Qz`mVotRc@hjku)ABx*PT9B6k=k=B0#@j7EW$p0^rhERZW%4htW#MZ0Ks2gctxz z)m7CS%91w3jGvzJNbP<}(1R-G!Ij_?>aFuYnF=nU-)S@_zpi!4wAp5UuE3)Db8gjq5ypX zwl0u&kwsU+C9xo)5mxDbJBb4bA`6~pAow=QkC1#i>ca=_Ab>8w-KfoQeNltXhyq4p zp&|*}z-iY3N3|poV_G=qqTOjd2!PN3^j`^mApv}ay9ftm0_8kBX#_ybzw<=4c#r_f z$RT!i^v79UfoHSL-uNt|?!^G*ljGiRR`^K%hr=+h#b0;~mPEQWOU!B;v`kvwIS$z7 znMnxP%7A~pIKA)g=@0oe#?@+AT~H4MMDDILM-Fsh16DS-@0OEN&$okPg{~wH zyXq1di+WAhuY(dI7w~R%)d=2FU{+Xy3#Z@$0G9Hh*x9JIhhP+zAx{HRN5?%;iSm!MvC$@#pP!88X?=SDb6LO1S+6B_pHG<>S)eSY! zHdhG%WmcQh{1Y|Vbn?62wSuI;z7G8J?etNnXgr6}$x#mtM z)38|JCm4Et0?zc%WtrC5wC|ZQaPd1w!r;_#5_In*zC*_d&mnaD0{)15e7w?=&gY|! zL8U!TWbnCrF=+ypBRB$KwtDvMn^rj1+(mW3IZY3-2-|%?*sj=U0par6+9NYS55a=K z=eQIv>srDa@O*6~9ssYtn8!>!E4mg|HhwtzV|LO2#2vK;nmGnCgNOpc7m{xZ!TrXm znDGkG!suQDUaRJ0KAX~gd3HRDP8g3M1V$j-XUW`sc!2NE2mmbvyZ~cBoWJkLLq)S* zJQO|Yr}~(Pry5OY>!xcxMMRO*d7JxOiSPdti2%NkSs8w^JBo}hVV>tHt?RgmeE3~Uep(& zL$TtnG{BaGl`e*pe6ZPDMAl@+@QdXjldp(-9a6(wQgR@nFlAw7hG4vNP#AC06=m+1z}+mIH6Fi&A>nWMV1W>m4WwFZjMI-Pa$|eu$j16);I)BBz_n31t+dw zy;?W+~DUM0pbV(n1Z9@fg(|}WPJ7m zuY!Xh>v>V7NIC(d@0>n2UOgy(!32!uoGBnK$Y zga6H`5Pe!}GFjr7tVaM;Cd_ttJJzPBnT>^P81lb=lSSnDOQIi!V0X057ZH$`ky!~~ z&}oTZ;()mQ0{`gqAf!~EK(03}PU~B=QJUmrU!n~D&01bkv6*$ws@ci*cQoke$ z2t>3GBwPFu@1g}M^8Pdj^HZ{foE7iGi>v{TFz8)5=mGA4h$H92`r)!mOa8WGK?r7l zy8-|s^#$GNyMSotLl3Q)_H3j=#VsU+F8&y?(cSeneaQP! z(a3*o%lI!Zj+ZqBA++Dda_p0WniFt!^_B>XuCD&aw#-tgSQwWt2J;PIvcr{}iJ+&O z@{BBg<}gbjiriBTwIwS8vq|`jrGFfce^NB6deWPlN-a&%lN81g`i5olecaqZ^dtOr zFcu~X<7^K;@^^H`!2m4Hpl0X8%(g#rgoSS{x9Tb(X0EDfxm6Zjz?yUE3ORs@7>GB4 z85rVE8y&{8)B7rBB^1|3Zj=!kw{q&?k z5NbdmpyF7b2lQo6vNK3uT!Gn*i7!!%?g1B~zpV;x*{k7y0$|*k zlup6k0dhdLvx5)w$8dy1OA_>c9jP(SVjENjlN3gk@IXwziiAGEeP3neEtkMG^t7-D z3A1oRPh-D*Zxh|T2yY%50u8JI-c>eW1;_>Bknyh$Kshi}wp0dDB>vvytOJ17UG2Vi zqxwr6gMUKs8dG9^6AkL$d}yUh#NEf$*TZi<2p1ucg1|EAR{A^#(-23<(*&%fRP-4k z1`C&8Bwq0p(&-)$2ws>#b&~K0Jq!WwWCnoGqZ;mcA7Y?m`t6hQFP_8jD;4zgngCFV zrMLj={)@|RE$<;oDZM=X{E-G=k-z7!m@~6R5%ltuLl0~L8LXWgOrkx&AaV-E$G6J| z42(KDE&#+G7%cB#Z!gFlq3rwbTif6PQ7B+K10Uo1k9pBYFC3FR+JB@kCi5PlC9kRF z7(8Vg$Y8kOCLOcYI+&S32IGlsAv$^FuDJX7I%F_<{lrZ#0zv;)@bS2x68Sg=;~mdV zW-eiTu`d?|?#YRu^)HG6JWdIqW?u+lWI5hODtIcz0j@X+wTOSd1E&Sx2l)-8pa%3E zBujsO)7B4SA&FlE;a`qAke$ZHSpHoJ70lkfsRwI?1ZOp4(eP%$u^hN~)E`8K9-n5w1fVnjk!mJZ#X;i66;+WTz^M(F7` zMqxdTkgQE5*M!I^=l+i-#hD@x0i!O^OQSGpp8~KX1VqFh>D`$lXRL>Ax)x(|)Ew#b zyQyhM$Yz>L+WG1J!E$1{M#S~bTsrJS$QgFQX$6RcdyTf6X$j%R5990*0{~friDD!^ zyHyFz-x4fw2PUx6+q@a;z9F)}hPoOq`+E8(8kdNGWi>=eutRWchwZ3M9YEQA?_PIB zY4`5m{ubGjx5vil56-erKU8mKq-A;f{bcy*YuHEd`{t?5aAlC}ojf`B%%zwrfjdMA z%qklxfQ5?$!qr6w9(+n7*a_e}`8+ruRMhkaLkQ@7Ao<$!6cHh80)>B%Q2d36G z8%K~qMOdlvgY53Y?%rM>I^YNC(hb+fj>tw;5<**>jB&><&>eC?Tfs~Vo#cS@2um^z zM+gjZQ}0hjk-DPvu@h8A;1`3@mlX4`h~UMbf&BE2o<}~6Aux;aAC&-lRKh?+_WhA_!qm*x(*&3?>8;1>rwF@md~gO2dEetv8|-Ju(q; z3Rrj)GVt>PxXY?V&u+f~fGG?5Y^(!!CjDQy;P&oK)tGxTIiQ1~Jp>!;7PbWDDfgai zuUL2VdJD)p0WcEs^GdiZ5kHN>{7e>D9&i@{(fC@-&seBZr0#k-L);fkiHlDn6^)H) z6BzpEs1f!Nq&m#NRq9yR)9RWrW&jKgrRF$Sgj7cgKHR`nx%-X8uTT)8H(WdTG-#lH zhQ)AcG`95@RM58%9x=@1b`SuShb7tH?%4ia3O%5mb#jQ1(&6)A8tl>~#SHMV!VzHj zXy&|2DfA_UA#iQT2RD;Uc_t0i#Ugs)D2AC(Dn75ifI|Qspba<)5QHocfX|T004%FvyWA}Z1@RZ&eYLE*`rNtCK05~ptgg;{A)5Ui1k_b&ULLUTLuvTmN%;4v zs*s+m52=&=NUBE?CMFHw8Xx)sm*5=x@B~{u1jKAbF);5KF$Dwn0C{WEqJVr30nAp# zyAVPjJ$vQB_faRUam#E`2T@#R;@|ecl-cZv`oz>Yp^iKJxs`S|IDLD8X!xaLFEoLz zszx&P^NII@@=}3;`qb6iD!j{OgHs`*2}>N$!9?HpTL<9*o{R`-j>_YaLqoSRWAY2_ za5GZA%-o-GRVMU+%7{7iT2~y0VAX}FSBj;X$O+Ueyy9$AA>G5U#d#qpmk7V|`D0Ib zfPsEI21g9cO4|N;2#!L`JB2cktPq6HGXnTV9D?&fI9-494$R92!rQmc<_V}7`6~#c zuS5=(x{$7E?sZZ^BVeA0AcL@0e-&F41f$uwTE}5jX~N(I z^y^{d6S7Xk0||SK1SlyIx@Rd1#ZnkTdnBZm0td7Rkps(#dh-lPHHj7-k^phbF@CRj}UOpV+X|&7npo|YZh4|9@_^@)K)f)2H zMZnYmav;|Ky(0sWbszAjJ|q`|;C+ZPXYTgM4ku9i(cfP|2&D6wCb;T|)h6cg???GL z{9hbGU{yC6U|kCfHbEM1bYH#k^}C26#~A$O?dqx*c80hFDMLUF#KQ!@|CcV{c=?-Q zqv40cKtTdv-{=E{Ajtbc=?ef4An2|TDPhR)7|X87LeI4gg|5~VDMcd`9n4W zB+}EgicH~Wrv|sv`8HD<6&>TPjHv3G9dC=k0x6XValk+LJ3Q+$7^}C7AO;5K!~?<^ zdy*&`^nMT++13`6FKMFVvlAA2={A|tZje3dlS)vX93PBEk?~X+Cjis{JaaMVpG1JN z2Lt?OtOn%qgNS!31mn&MJQZE($MiTGg_0=S0}(|q5< zR`hMgzX-z$1_%kD!vOOYpbo$xgnr|VycYdu;e@jlE`=bZ`>#B39D~XDP=J0e31Kc5 z%0RRNbPcA&Z*&wWSUwm{NLb>B$7H9~@*qh>E9F0$&*WH~1pm<-N5Lo5tK!u=I1rroNa`eN| z1Uo~4T~9?EK@5P_%SA^Bucyfvmz{!x_c7+Vx*!omOlql_;D-@(lj<>h+fT7~T+W}znNAW0~` z*P<+F49HBnr|wyuzzsZJa2$rjuc53?Xb80n!SBh$Llmq3_tvf z01!#`GXH+=E66kD9}p2&vHoKu>MESk)a^r{NuXliu2NL#T9=>=nv&dY`WiY3T zbsQhdt0FXyuFu;1Nqw#GXO|Z_YAq=V{9HeJyiH;DZ zqNo~#z=!Cl1B{3-CCi8#=F*_-Xc&WI>1&8*H2$VVU@0*`Dq$R)in6#JKfU|Yj%K0X zZgsu667z6GT^;TyMU2*N)x(7{8dOiZ7@0ln6OJ2k3sbU6Tr(N~rJF`v>zO9GR9bE| zH*ePL%a2_Cu?dNbKs*}Cu2$+6jGONS0-_y+3J7d0<0=(Yu#7Bw3ClnJhFdKZ#*___ zMb~kQI0W195dMa`H(#%~Uhy^lpALmw@BX&b&WMB$BNFw){QfHdEP`SgBitGxkeZiT^FGo)rkUcgOlVxD7I1kDcsTuX8t%8Ry&etAmC;%(XPRS@1k1ry>J=)$pWVvNZ8;C2{6S@xO@qi z?!e}NKMN2%t5b;S-`?A|DN;x!ARAJ#LI`-MHkbE4Lwk(Nhbi7 zQeRRjb;nsFUHbCNQV3!gjL!&Yhe3zwtw~jI*RJu_!2|HSyLU51@Rz%z@=`;uuD-ku zp9uiu22o)zDGniy!yV36RSN!L-$;(A3Z4J=iH*pW8EC!*1&qs(fPC2d;W;MW0~mmT ze;9%FsN78D%M;@tw1JIFWsCu<87gaB;@Y4LKUs%E$^rZotZ?;J?ZC#K9^BoB%ABA2 zB|f_w zo%|2x-Z=qZC)I(75vKVM}!5INX0k@JC zu5lrV{U554NCDUQE^s4E@Pl@O3RD5YQ5pSJt**oK{LWXjevmH``{;xt3QEO1717Uw zdQ+Vx+2LTDR(BkKG0h%DG)yn!UjoRq0_^4C1GKL#a|R`)2$7vhy7QP2RW)?l1L?%#v}h8&RQKPSX+9cX_r%ag+yJjz&v72JUdexiZK zKrleOgXZlc`tiQ8sM-(e13yarZ^}Sb1ZtvzzJw?Ufqm%74IC!8x86!^n6!Xw=z%Nb zp+*{3Vu2e@AU`W);*_-iL3Cpe17rs4<`txUIfrSUu%~1-hP7vAR*2o4C^K4_BP9ab}*KP&%!_rSem}Tl+wr`&U zpiQeQ-Jamjr)$4*rhtybUrkTX+a@gK^Kxx+y(zJDdHcB1sl@)~6=6C!HQSXTnS{*% zx7HMI%AJ)X{cjn+90xnIF>E%g^e$Z#@!LXnVceb^L*$V zf4#wM)Vo&4+)Xt}cNbDtbn?!TFRt4eyp9;u7h{4zjkhTcRRwT>!?CJJ$?{CRUa#=L zP)o}f9GNgx^?6lrqJ#LNhRJu#zpD}Sf$o%*5eAikS2onsl1hS!i3Z3amxQzor_eyDUT{y*xtOE! zVS9oFcC!7_giM%I6rhk%&X323aWL7msikGWHs1q|!*|sE0ac-I2Dnw$RaVmSM()?} zyN0^Pvg!&*V)`YR@oEr{iAtV_;g7o|4yZ>FlEr>0+(a)10In&T=e&hZw4 z|KHm?H1qcp7nLg7=24sY@=!B?$eT3_~!U zG5^CNaMB2vWPxe^CH5&9rr4BjFoZ1_J3Go&I1GaWMsu8ja3$(KqF zCg!KHS>N^j1V-R!gj=x$aDxW=wG8}?0GQ_A{VGKNOm)Dl0_Nx9LD=|r_CLbED_jja z2umqg(GL>QSbIlqi~5BahDQ)f0Bwh309ImenHM-7@XA>*!;v@UT^d5}IRHVxn2BMs z$2u*;Vs>M(^7B1708j&Ow;(Vp1WC0>1ifxvM#2|TA3tN_XY7l3nCvreAl*HPKUCYA)sV=z_|gW|X!G4;6kefGeexwJ2uu0eL|9Gn*%_)AL)lR5|2e1pWc| zTjP4Pr%YG((k7HF9eC0|0RX&y??y#+>9*W)e;!d*>bDMp{)@HFr*ptNy-^J)IZRm; zfIJYyMG7E40TsO+G%XxOV3rcGND+~q^g(qKFuyT5S-WBJ4)Cy8FA>c#+g zv^9<(gOjx~xzxHY*d>{~gU}IjpGxTae2%VQm4ObJ5=!qK$r7?Q$YBZqIHDV|KvGLWhv5qW*A)+4 zVa5USdO#rf z7&qSmcF46*^LONklrIC7oN5pBZ*D}~6>qs@eU%MEb(H_X^LG7uTl2?_)|nds{#kdiGNebI+&d&`1KxisvnOWSnJJN5KWUFmCg!4BJPX4DTuYzdarWN#ouDhDC*gaII`1(G8-L z2=ZWV0{J9>hBKIz$##W|j&9_G7>ZA&+7Ra%oRY6?k%)%7@WbPO2m~YuE(R3p`mwT- zBcLEK)nV!o;t0S(611XVD1+I*e*+aPDgpN!{Rn!W@$Iu%{^e@GO!&NWXJUU>vK&-e zJ~;MXaUr_l?}|rYuKpAa7;?ao{2Z)o!1F~x%$8JqeqKdMBfBCWMv$20!mP*EFNH)e z=pG!xz(~;292{>%!Y!@`eo^k#AEB*kEWRjDM~|_DfE8Iwa6Fubng``)0O-(YcAgOc zrTX^dMsdhGouqUu;a{l`oh87N9=enh!A-cqI^wh`qF@MuNeozW|7G;W z?XdXIQb9y)DGZ^c*qCNwAv)yD2aiPYQCj%f3&+uzo?peE5&-!PlxSl0cjQReKPp*x ziEx*R0|dZ22OIzZYieAM#EfVDljG*G#6q}AQAGft#Lgy+m34StH_&bL-?C?5Ke};4S@({7C;LG-2nnv z8+|1B8(oz+#^+&r6IMq@4SKwjhyp%~ZJ&W~+VKaSeabXWt~i1pZys=UaOlM+2wtRn zVcLQFJY)mr!21<7E~18{czj7AG0P-`{OM)ZU9$T_060Z3oT4juN}IseaEFYihRb>4 zTtq=@4H$VZ2YDFbK-*>$$apft^>#T4dMc|$YW32Ol^{!KiqZ4e7 zlO1Hxx8STG)44DJzY{7-vq)Y_!fdKFg%K+H|oZ#Q@UW&CXqVU`!tfXal zq8n@xkFuqD|J4Ej>nm^+?m@oRbv*u9RbufI8;?t4LoZ(Z?!~tssx$MO4O_o#37A2k z7~tocaXH?O5(nqR{|J4f^aZof5_T-`!Bc#7QNox`0_7a~F6a6j|MCoQhnOpJz0SY= zZ8Tu9Po!{~YCwse)d~lEV;!cB9ouRA-Re9~7s6VvB`n6nW9&%kZSB3lX5iNE+td#1`nVX7 zb^l<0T-Ze}kPMDHNT&6un}kgQtp^nN@x9jJSPaRhDTKLz3cy1K`ZX z!V(bBw>5~LQ&LZH83-_3Tsd?cQ3gi8Q!B#1Jvw>t;;|>D-hJ_z(C0(RO2Gm`;@Fp_9h!hJdAv<1x{fxBW_I3EWlLAGhDj+?5Ux5Lbbz*2cH; z=3Pir zn$p{uSnLHPk_ReVklz&N$N5=1>-`@DiHR;aS-m1^P{Du zL5gLbHx7W)S-(7FbszpW0HD@=V8U`3*n{z1ay*=Zbod}!Bw}u^WCkGPvnIN)68;cB z5&HzK8mim5QpLptbMU>2svV?&*RI`0V*VJfA#lh={At3!;o;L8=HCneKeq&sTyIY7 zPA8C6azJoDJ%crC@z5xL3jboRzI~F>e|>K|{q$K-Kwf(L`ksdzuy4&Om_AL#q<~C= z-mWrCe%h*CAp6sp7)l7#R!_WeS%%!l_T)9{71TnQLw;Z`4xlhjWf5MX%BDj6O|f(UXP*2b~b#=Fn} z+7qm2t%}DQWJ*>Je-|%O7VXD7RtDxbV4&a3#cccM2h6*=eQ@^&DU8Fdjb_&jd@o@u@NH7kP>puwzi|1hyMQm6+?UNh%M0AkZ-B0OLbq zfc#i)L10w^!1`PdQxVljX*#YS%Sz((@33VtL!yNOKVE%@$aR>3hk{Ij0nC!<#3o(9vo3G%|35%;I%!Dcvy1195YlYdshC-;Uh`)(xEKX=7fNW z{bi8HN4p{bkI4Uf;E24x-T-!VlrjCFjyw*_Kx$by8J95tm3pAEGNwOINDhtEm|KX1 z0l?um5I1kp08*!!`4;~SB*)ZOb>pwisk2r2kqLi~E&P)v$N{_SA%om;?%Fw6L$I|d ze=$sh+=i{6G|?L$-T{8TnhJrz>iBdHH(@+`VEh9+d~iqw75rhv)tzKsF>f6Ygn=$i zpC0X0xXhZ`F)e;(GZL>N)9OMZ?rHdC+!fNGQ6V|bA#iereIVd_ntOqQ^Bi?0dzqTm zz2hsDpl_d@l|*nV0`R8_5ZJ|Be6?L3W#scLHiTXCSpT)A7=*6k0fZRWs{%M~^rQtm z+IBQ0$T`k z;)HQ~p&;Y`Ri!OPK{1;*1!$7}%`Ca7Uq8EPwfr^5@!vRo0Amj3Tj1dP7=XW5C0w=!1ogui__J`rU3L$qy>B9XK?VVZ=Nt$_wVReD916_eFtR!|Yc!VAg$d<`Kr8bTv32D_f(L1ZW$L)yIx+!VGDpdH#VO1Dd; z+dICbJ)~56(y^(Ore82T+;C~mfK_e>@lXUX)ulI^^O+VlDJC!pT!?v>j<8RYuUtAK z&5K^mQ~x?*0Pf&d9DxadB!Tn+<3-3=%CrTPAdmn!RM}Wp*H~HENatG*>yK~^o?u3F zznVh&`x^#me4~t-@OO(1aablcz%*ACz=x1nbRqLcn_-o&rAb}CUoV5Ihd^tSo)>=e16@==L%$9A_R>}wnMs;`SdSO|QfE}Fpy z(GDz-Yef=PTR1=jbn!c=o8cd##h){?j=CW(jlW1mc%R1)M6q%cIQRv(fGHm}j|Ig0 z2?zpDY{gsV54m_TLSbgO6C5=Iyr~a2c?3DN5}Bqfc~jTrqD6n?etQsn9}p-exDsBG zK))3i!L3kMlM2zd6?K4bWo9^e;68Xw5AAShL13yzdebM61c7-krsv_E;S2U*_;#eD zp5wH8TfSfCAt(h7n8{+K#^j?$~FCXH5H#h^2#RbI2;BtSa=?(8T#AU-U zn}RFiCQ_X$GAj}Vq%;QjrsW_0mF8BEGC|-XrO!P{1v69#&o={1_u!J?Z!bRMtLhTU zET5EOo@G&G3qcT1Hkk|V*pUS!$m_-_I0}}?5L=pU`fvvRnGOnL=>DZWM5hzv#zf$= z2;e|RTt&_dC=RfLnW+l9Cj+DlxUQ1=mj=5+HZ#OPDfmllK1cpv9d$8vLu`s;S<-=i z{onvGb7J$=$~r6(aR#X)Hio0R9*2)7iV;L6j7i{<^h0#dRNTXV-yfH#i@uG#z>jHo z94^M74o6VdYYg!Ba~OdEf1iI2#`g&7mpPt(?Fa6}-D7pMlVa!xqJ(qouRwh!dVt-4 z1bBPfMmP#$@XfbL47CF6^9MhsWq}*TXY#=-sE=)QQsJS7DWKZVb z>8W{};PQ`pK@QBI^@{)-$Vae5%w+e2z>nEN}&v0_unW3 zi3K31VAmlz3x+{hAAIoEYw-6$7L6Zj7~Vg4{rJphU{|3lA3wW-WZfVbfrX9dI0WZI z?(IVE3qa6^5MiK$VfOB_x@A`aLFWagd&kH~H96vW(LvsW@7~>5g|4mMy}z#88<#8} z>*?mpUoOPdA~2SJ<+=DJ23>w;7qHaN06=`(1;O>a|7KT^dVN`+`9V~bSyfTAg;2bK z9E2+7z~n7*)f{qrq!6s36_`)78dOL^#3NK|9q1qgkUC&mI)`i`^xYOFYA?9yNr{9H zU?x{?OS1s3DKyeeo1#;x$rGiRpsPG`c}hEspqi6<_M? zam10S#yq_iAz1vx+b@|Pv@k+81shwi?LXsTv!$WRL=~xYj+9U%uIAs`Sp(qw_5eD>UeyW!r%Veq z07nrLrGEONcfMAuKuyG;eqHmzzk__>w9#uDo9)2BvZF_jk?0Wsu@S^q3PLdW;j0VO z2TB~{woDy}dt+m0xlAkwwE$FHG)7%e!1v#oL?hB<+hkJ0PzC5rz>NSnsouDYhy2yW zEF6%Jo6rV||M{ac5mK=IagV`T4C)4=kc5>z)&LUq9v&C?aRaz5-9bnJ#r(1;nD^*| zyHjL9BuplYW@sYXI!{yZg`e^8;pmcEJJuBn4F7 zL3Dg5AoTzSTpl}Me<93k#aAgEAP&H){Mg(uz!+7vBf%={Bp60$mDMEX%)iHe^~XV9 zgUz61MU7Xl;`MfXtNR`X;reQ%#Jr15;KzGM6qoumKZTq={U7fDAN>Av213uxJz9MP z7Krqzz6X!U@#e7p1NzM|EQ|VQPP%qaQ!)7h2?dN(nv=WSgifr}{F{FuN1ROr zuuE1DA4FzbdjkNa|GRLsD^&*b9(>`#v6y;~9^*<7FSK2d&?RYP41le@T|SVEQxYhF z3=Jqee|-NvI3VKg-+%vmoItb=#FVd4EYrQ*3W8C%b|zvGW+EIb%ZLH~-8?Sr3xk}j zybQ?N!;C96T@ncw)qTFQXT>k=Sjyy7ru z48VU@KL{i89h7faOtFBRiLdNTo?vSOP5nk93#JN3ku50!HN0-PWBm26_qLezt!FGy zN|$o|s`s+b>%Q{xu)n3J%75_}Q4OMpBCs&|cE=!G)tzdT1b|hMi)AFV{>5aE0JuaF z2t8np)X-J}g98r15qm&!DM|+&k~d@t@)2dq=k=L{JfK!f)*}q)YZ+-7X>a+s#R2-T zX=tv6ERR)h-2as*i=jnMkp;v)m8*00#~*5rE~Vz?G!HvYpPiU$NlN#U7K#Zm`~Lm! z7=8z|20Wttdvd`Bz#mGG*!+PstOHgxD+u)fWr0JtlxK?L@Dj&=>7UJe`KgTmuq?-a zW8abiItlP}q~o7{4FKnU&lz|QSy*I(#6N!I8Dvxvz&Y#%A3b|S2%O_RgA2e#mo|=~ z^_M9zls&@;d}#E+p^FGpB^qL0mLRaxMv%2RW*;aI1^`IL*XI@xo`Pxf2*)ohzgqN3 z{pWpPt*2amo~@no&d=(7kGB(U#ELKOaB% z=~Pr8ZF3i}Z@{(!1NiQ2EQDhog7fe{$WOrqIP?baGn+y5OOik$;pNLe6CFHzIf{W( zLMi}|c&8hP8D3}ug@L=o`2K9b+j}JtP`vPp`QFCXU}Yru_Mtb8ze8K9N1_UNA+!7n z0XYOG#+O<^!uw$qTyPpz48GBLUYLf1584lxzbd0#w?j~Kp`d?`AXw!Bk&0B06sO;6 zAz&5rjrG>UX_#9=B%vthu8cK6^2`wzhMbAelNSaj!k4ZhxQVpv#XyV?AGb$wdb5f% zdEKCqttBqQQ6WN!%o)Wub5VH4R}lI{7;>eRUK9X>1xn~*-3%`&>LhL&i1rT(p``+h zKHvi#b^&_;CV~YBg3v+eM+`(R76Fjx&VM#iUx~uY_>}zjK;132BUQ37scy6IuZ8NF zhC2Nv;V%&AhX^hFkHu!j%V34rP_|SWYQ+A5uHyYzixK@dKcyj=`@XCP&U?bCj0Eb_JmdZVe!X400de#5asEAcjM_eFoh@W( zlPU%vdFGTKAqfD$W1xX;(F7bfV$8r7jC-w0n4bUQi$RA$r*dGGae@HC z2?ugGGpN@<37~r9c#yvgY7CA*On8Hzy(-V9=n}b6Vy{LhB@u31x zITWYUM|{E`bO+ZDlD;eoFcCoCfj=k&q87;?_0Su>Ood3rN2DU01q+NR*bQ-7|HVx> z!@p<)A^dp{C_SL(Tk$^;KfUke=kvwF^t~RGwE>j+Mf0ynAU;$j0JPC-}QQD1Qu3-0e{`)o{jT<5Xk`xoxt^tsWH9W)tOrJ)h7a&kwDA; zc*U$?uTn&!YEf9mn(#U&M&V7l2@MS-gH_=M$tu%RfhJqy+N(k!*iv2WQ>Q6J#}3TE zP0cD2kuFB{nVW*<;fFXVpRq(x3YZQ?ogNv8>Z1;sKEwb^V2z@I1BWGnCIlXdD!2}} zp+^?J_J0CE`8g1XHAEvw!;qm7oVKx1^skI1Ab@%NEmZLQ4Qp`aEfxa*Zu8aO$p+kj zJBVYX0g{d6#7i}5BrTgz$Ta`LND>>a0!SMLfEE1&z>11Le*N{P9q;bAcDtwNFW;&# zUA4fm4LqHTqRV~{c$=fvnX+dEBM|;pwHl;54p>Ib^D|IDAmm9v-SL~a>h?LUJx1L= z>o)Mm05?bFf&&6_Dd=!~4Z*@bZUmJ9Lp4mTYCpD5y8}dezj-=7s12Oq1T0hB_LP4x z%Nk&^MF+qT_y9lVd)f$2WzYR+<9@G=kyglwjzciUS72OM2%?iXu&ehNC?E%4HiB>n zMnb}cwtV_UB+P}jWdCT3Z?v|ix)9%iTcrYwa$o_VYBOi}&%@0i-hp`c!wus5kG&u> zPDXGy2ysu;&xeqkH-r2gHx8ciF=SEEFpDdGYVx;-X@S}4cUuTxY$XZi7oqsx0p2OP z;a;l*F315t$nh^P$CMd3OT)T+Hj6~Ktb|l4U~u=vFRuQA|Ao;_@dx3B;|ubLSPr-= zXMqX%__p`_$gaKl8N>j%#S)mL1{{gF=et?lACT_GUvuWS#bxLV+W(EY3{wEOP#!U; zB!nJ^*UN>6nFY=~kP~p=-B_A=v(&8AC0yZiZyJLua^#CmehpIq%De_txm=mjQMLFp z0_tmW#4jvA4zmTuos^0l|rlIWXve>;@icShNL%^m#Z zIQ#H;(Aj46d(6T&x!#U2hd@>A7{1B-eDmN+uw%fX_ZGr5i2va=AATE@i4`@MS_0}C z%)78u%^3V4m~J4Ch8Cz1cz0DAXn5eR(g#P_^c-AwU_$Yz_zJ%Xzjt##T_OZPU6S!b z_>*HiMnD4cqW@Uc0WJ8B_U3ENNQ)jmon->163rli1i;@b|5*d?>VuSi@OvZUDvuzx z$no`)a~DYh`xeFj;1C(*sl)zNe0V?-I4X4@E+&21{7W(PTHl=TPeFi&z(K14x9bA3 z-3QnzEc# zjDC=g;DcfJh~w~XFhFoXqTn$x!($hEef?Ex3;~dvzYB)L3#mws!t1WtFJ>8tHE9%V zo6I`WC5xWK5>P5YGQivmlKPSEyB!lx)epx3SO9qQHDlZ%$uG?W(Uf%Dz!!>WK9xG~ zVZrzIFtpFxww*YU-+{9maAe{CM*x`3z^a1#SssiU1xXq4GyM4$EEaeon}4IKojYG+It=u&mT z5gh)IC`^jx%u)#c;+_+0QNZ~dd+s=IR@b)3wqi)s62!~2*b6YYCz^a{hIUfEh6#1(i(6&bHvf{Q9Gr& zOHQ4zztwV}l@NNC`3F<;+zZZ%2>!ROuK&g}h$3OS!V0H5$BzfI$SVRM@K2k-^yrG4 zZ?8qu?80O&7MhcS{lzL#O_?Bpt!?8G28f&SWEzBH91bB2@b8_3fA{s4A4CpG2;+0` ziP-<0ICUtuh@9#}OYk8A;Ao^GEQThqFb(T2l4jqBQG_Jm(G??H-S#{TF>8k0p#r zXJxg1Xx{BO&|{rViyD6$_+%in1ZON!5Qt`^TL%UjED3B-U#7@g537R9*z!i8SHIqi z#yUeM1XGSi*B2o1Pb$|ps&bt7w?;v2gc=2<*`1=QPg*Xer;uy!JG6V+K;W@7S zbPJ}|Z?qF!4k!pO$TWs#0AT0bw97$g16fl;uqI&S+pn1dZddUooWR?afKQzJsx}D# zBNCsX2q^)}PmFV1@qG5pG|<~L_W*N1jK7Na zZF3&hwp52yxC6%##G;o%9Z04DjB*g?A*dSI_h2%>Faihq$r_RxGV?f8MPcQ3;56lm z1x8L*p%^&PzVpIBTj8AhC;W>ntUMDTYYAT1ums|Z8V{msw2u4trJjJAcV+9CwPGD*eku!uM-ZTJ9zFStwJUr|Im&)Q8 zAT3PH!DTknMSrjdTLB=y#4OygNz|{ZI?f^jL#Ag5`8EY2Ix=CCLrf#>PvV&tdqA4m zo8A)mXK{3?iT7V%;VnsAAcYxVEyxj~AMdyft0By_P+-G*b5E(oEq1IkA<1k(IpzV8 z!~uaIpiAIq0OU?k=i%#DnT;?MAu(`>ARe)??8S?+mPX~KR$he#uCC!~LnGmju`-na zyCD+8#-XcaHQlVnyjtmyRX!Le^W=}4rJx}jyiRAxy^r7h`s>@bn{MB3-opCe;V6VV z{Y`cVDZ`pi>3(z2IY%i7@b2P8(n4^!#*0dAcsvvw`g%OCrJbdTk%L#((M+5~j0Vaa~c=Vm0)fJex z;K4Qp(5nQgYnB({sadc2rn2r10$^{iP!M9kE-C`M==wPJBNdYaGWM_A z@u3@br#2r#WQ6>hbUTU38sVH-6;+*lx%z`6ieyG%8FJdY7HeZ(g0RRwrYJe zrPCJ-;B!m5zAX8}rc@S}--+AZkr{33j!7t$0^&-1+fniWd_=22t_ZCLv>2x2$m0W2 zKr`e|M-lpfTL$#j0&z`K03d$fP>Z!N{F232yCV+j#m%-Q2@VNB!V4W4w}$S zFdFWUt;_6)9rJ&OAF=0>%--z|3L^1YIjlaHs?Adg5aTx6b3#ZCp@`0 zs_hfDf%q~hrM)P;xY~EJQ%#uaf0HK;0LU9~mXeRLmyjqYh$!D0doGvPn2Ru|e0+_- z_J(|=F?T!1Ulyfv-ds3ay{Hpk6x|GH9TnKv019 zBV8Xq;tPYEzr#x~K~9tKF$}t15-K#Xi>47ibP(3|??QG5abgw)F@wnx+~z|_vU0{*hVd$GMO z9)cH=3fgjLvAtA>KIT*y<-rICZxHLciFw_QJ17Sl>Q!{6M?0o0A%(E4l$V<9!S)CT z8pd#(jv|_U0fIh`l+{F1s!gsn+5GGFq^d}RQ7R10z|~O>N9tF~@4~4;GsVQ9IJi1c zu({b5IS0R-X$m-OYKn2V*FoCN^9Zw?i$JMbR1dkVWI)*zOzw&As z7otqax+UzZ#P5Qfu#7$&q|qWkOPPTUVuAc$k%qELnu!}gJO>6KiMfZ~q>>;I4eGZ+ z0$+T%@Zm-sAb8(1jk=%z-ngbbtOuXZ2B~P5@g@cy3Ll;NkgX`-| zmNy3l>U}K*q>lDIAOK?2g$A0ZUd*)wKxG0Bsv!g~_h}XmA)p*^wX8m0b7}hWe7HXp z`7+BGK;3^C@0ay=XaGi)Ta=j#unuCTy>y8TFM?qBxfdhw(WATZ>M@PCy}pwWCu88f zz`L=#FP$a`&M04;bu(>U;fza3G6X>bV<-j32U!z*p*1QpC2jun$J`=!j8vEoKEH+9UI1x{gR+NZ9!z-r<)Ih_ zN$`45!`GiuVEU!{*{rcOe8L!o%j$-dhPs(C`6PQoyn@tmD8`2g{7B=CZYIoj*Ykj0 zXG`(btCbGYYHZ}Ggquf60+E)=$ozA+&z-w=`*sh5Qa1+U!wUB~_I8-roO6;c2|UO}QS ziKiLO$r%U4XLP6QG5LYsGHYCLK;hzvcW#pZoj7qK7ee1mikNK<$H#lrgJcu&%JFTn z77Pmbnh@|#27SQ-?-Zus0{n^i6<2^vgmEL>8~eing7+VthPB^9m^gua_E~fzMLbp* zf!~b#M?M0F@P!EoDF-W^dUx$oH?XvRZbPyIZe+xnSR*O>eoGz-y(K$_jO0z1#J=+j zx%*cQAs&1o_FM0+&uw%0fo zPLPU<4TzT~CUhqzsOt0@5Yrkma^p3ki~cvDE3zJKG1>D%@|skj0v=FR;I#osI%i1-6LMl|pOzm$TXUfFzg zvyuTdD{}(oa9dYb-+ixJDcw~(2bUQF@oi?!=s?00Ete?)11X9@XULZypZoIMj`pD? zTI13f{QnUEKmYvqpIZVwC-OHp4LQsqD*!psj?P(#aq*&OVNAuqGrT-ancv&OJ!L-g zrx^^`_ej#0m-slxo+P#);Rd|b2Va08``|d;(g~so*Z~RCu1FFQR5akSLSVT0o1gmE zDfNKh((3>$T|MSgfu%mpDhg}rf6?`RKT+ms+IUqD3J6$GFs>wsBp?<<@r$8FsgPk~ zqKy+Zbh89JgV!(#64D(BTTwfZ^dP%76E$Yyfr*n$cPH%$CUdmYo$Wap&*qPMuOIj4 zd7iT0Zz)9qXm`6im-l^NzwG!>S}6ckZ6GcgB4gMYPh0IHpGwv=LV7NlEB&<9P=KEv? zzEn&>xR}$w7j^tQuNEZZULhIvd`|y9a8Y`mkJ?lUylE*kd(k(o{FD1bV(85?DHu8v z09yVm79`|<<~ywW`+q+6RRp}Bx<5|J1B__E=SQ_8{zO%Xk**wa7m1bkE0x0d$Dg$$ z-~3Y40Us)Yi~Y7%h=i`x3ILdofJq0~QpwH2oD~`TNeM7Tz{S>(wzlY7&zhA|Fn$C> zYtM~+HwM46n#=BRf$cW{rlkD#q!}b4a?;~%?s#mwVnhH?9_j?4r-B%fA0!0MS3?x7 z>=!?#W8UNM#RXcrzY)?Q{rnI>Os+&fcc%*gNL4f&;^bmeuWv_5(mu)utKpg3;u1}Q zoLa!v)~(<-0CDwW`Yf-2aQxC?Q^ud8lJdK_I%89&Eu<903NodS5df#&*H{|zzVhGy zefmEDfv3jmeZT)d#Y`9gAa>tvvmg|^>})#-<_#BJZnI>2!FX(=Hw1=#@x412)C0$; z1aiDL^H_XTX0Evf&V|6|*3zTfG;nWxxV^(!k7aO_!Eib5#;%K%*L(1q?|$ljd+E%V zfWA@6TmF}Bk4{a0OP=mFMpKr(qU^b^zMjPTd;iYl(5&N4g>e!+>;9)1&^N*y0JF(( zG#F%j!p0ClA43w9gq7fMMI)h+kP1MFU_uWK^!u}Op%-nBy9fNE5(Y?jPdIqbvY3K5 zc%2%+xxhdHUqF@yKX!w#*-gIS8$AEHEh&iMWD!xJdYlLO$({szbI;}i{%(gA?snk< z$l;G>;7eM1@12OjFU@}!v$unM=dHfqY?oqU#XS!;?NMofS@HY!_G&|p^*Tef(2po5<5p12dOppNx zyG%{3@2Wson?n951_VG} z*l_`p@}F-;72G@3WK!qy&Jp>7zjzY>et3C6(s!F)U>Bmx45tzBWv_x!*#e@z5DQ@b zH`&{WgZMxm;0^X(jsg;6T{RePP_l)}q^!s7eIJx+dKXwu{K z$B%%6S6(FOqyB{w7}g~T0X6y&=nR041au<4(oK6b-4O*-Thj0HQPA~qY!-g&OlggQ z&z?1Tfp0f8BE{5qDdi#f`j@w2a@YMba4%y+&SzG*^Tk2%`~y=UsUI%MVK(Fbm$+bI zUc|wiNny|#4Ls~fe7z6z2dNJW|MrW}x17HS?qh#H%f+%47&V!(0?%iYUY3DHxWmY| zpZsq}*#KD1Vo!y2B1Jd}ItC`W3dBgr>{GC>K<)_+dNS zCTtCM=&524rab`)@$easfmfA_zy-N}id*=p{$0W;CcrVs1E=kOaft&I!bW8!TMXnxuCC$#5qKWCG5wN z1ZpGZpXgyF`7!p8lyc`0hd0yH`+wbU;0JbF|;`p9#f&@Uo-seMmLxX$c zj(^7YjVD?oTp&a@9Q+1{yzmZr{WUd092^>znIvVS4!|9YxMJ-hA();SF;i93Nsof)W90?Qw$pdiL|7abVlfp5Sdzxmd{)5(_bVK~@k0 z!_ZWo1kHjB&Bi=9YAqm6f+9jzMwOH`yOPy{Tub=~8>&xQvK?f=oUc=2c=^NFM;uH) zVimr^U}#K%b9kc&hAKdQ$Tj#y0H7P;BnZ?H_&ZDeI0S0K!&>}SO2D`2Qs~#N5sBH) zOYj^9KVTr>47atB4Yzcwg8h(#=H6CEoqsLP%Uer zje+$xIYHXeH88v%{r#Ynz3R4kL(W^&^|SprN3!-Y@4)0|NBZg3Amq8nXgUTxVAgSq z1R-Zu#4|FU1%Y=`BPP|+F%xDCi56zu^8kNXVTpnUKs^Y7)oBlTa>79j)9Um;^aP8j zz&zMjpMu+WB3hE9Y~i}wN2!bm4a{=-YXj4={u<$Jps`=C2=i1b`IB002?-(QPvK z9qk?5e;Ettp!=IN`8pC+-M`YlFc6=nIE;VqfO265Mi>?a(Y>h{q<8H}ul8Rqyc7t& zgiQo9QMZx;We3si?k;r`<^b08_bVk}!oVyVKWSj@W}djs z33D&~WUhS7wcHsVUY@79V(KG7I~c)sL$87|PntW)P5 zu+Qrnp62x-vt%^;+1hMjVOx89;Rx6kD{Vr+;|hd{&$p+6FR5Zuq2}>+bq=RZS8Ohb zi+-w}M{EF2v??=KR=M2CM81XTL(gf8KcHUjietEo~kb;#N<9(@wviaP1r7psUO|MP)if(sqbI--3-eL^G|LuJNaZ;$QtW0w#FA z-se7H31_^&`xbK+$c|XDy_kOD7J^5gW0{`$E)uH@-_wPUb9~Fd@K5Tz@gP)QD zY5{&jqV@xJ-t9GpVmaIXrmB6xZ(s$6vKdS8j*HLnkpiI!dhc8Vd`{tiTz>gW)?QxV z;0OeCAbu~Ee~`Vb_3kkK*-`k|iy?`j=8q;29t4#ns^&{Id`Jc(03^$?B)!X@Qo|8i z-=sgWK_eRAhPd1U{zmNt*4=O16!2)GIwnU&@U9F20eu4mT<#4q9BXtaW_<% z3P!l!TcaQ0PeY&>5g9{zZlnPaxG3P0{3Uk)&)rTz2u_6lSOk495&$n{Uf`4hlScu{ z38&dFF~aB55U3=W2X{YyoIYKogHNX>OsSqXBL-ix=;6(#(Jx-;0(izduTAZ(!@fb8J%yf zR6bX$eWhbt50CKo>~C-y>ET^ z&wn<4Y{!oO4Kif^{-6K(6O&;|DgxR5u$^0f-|T$A^!HbO1Ss4&cP>Kk9eZ%@W-qx9 zwSZjcz6lAl;tmLa=l;j)XSKlr@zxl8MKIjKb?*Y@Flz+H?h9!O>}CZB-5)zU@V~w6 zefa`cz)qH*gB1n@#`SL_@K4+Bk^nH~y+82>LjUZ|AY3u9K4PHBfb8uB)9aDXAUG)? z9G`?61f!fbU|s+AQWU}-uyaTw9x|e__Rh*O;+z@osm5q-c{l#6wRn=mFoeJ1Q5a|QjgND%no_(&MYEjWY3w_-iioB39_ zrwd@j=8GOy71A>`!M#ni$L$n_;OVa!0m+2;26*XGYC=l0UpPS`3MPEOU#5EW%nuSq zV7CLOQsBEmgWUZlN`Z9`OzEf|2R-}^Z>HtfO29M2QHpfk#*i!@HFSWq0q>vuw#g9^ z7eI`DdaGoOAiw<5Aolr#wCnzK#OgPjKd>d|OK>f+p&MZV(F@%Kc?@JdQd)`C4U%65 zE9F|H$rM~k;3usO6Jsh`dy7vs{>ZcV+q@08Ywaub9lAXZ2oo(KtV-g@H-9#}4n~dU znB!ykQhiHC$9jKVX5HX>BMiU47y?c3Baus!8!%LYn21LGLGbs3Fip^$_00Z46Ne~Ip34o>2l)_Q@AQRF@Eew7UwqYP4khSGKG6ENbkoc!y z4}RWu{I~z{&Go+zU;q2x(H;D%M84vK)Gu1q%n+4@?+bd*`zuiC{z^a30)w#~D!Je{#UN>>Qq8%zaLOA@$4Y zuUCBcw|-Qpy+g88OOv+{>u34qlI;*Ia!^L+Uaax@LVaG%GS>5~h$9 z0^Lv{31&PDaRx_5<2xvjuXX*KRcbU1b0`sEmFDay9E;yP_c`^?g22`K;gH!{SDE8DI4%4KT|FzE#Ogd ze-PsKlifFAWB{N2aW)6nl0Zg7TN(me0^^GK7Y4XUMQBTA5OE*A{&@?IhwXKan1Q#r zo!Nov{6UQdiqyyY59^%%*e23`mIuPvb-fV-`p`IJj3g~vZzpgPC}Z~1j7Lw1Zb_J{dI7%_=hU}UfF#R#1MCn z*YU5t+wVZE2*!%Ee1hWC2*i0d$8-P(Iqa$RqxD#+gFcXBT?<%_In~t=fPl3bNay=@tv^c+*8oXSOnqE`rMh0AEby4DAs|rNuU{X&{tdlxKb0;p$@zo$ zU&g}lh1d`SA+CNm*JN~4%qb>5ctYrj!vNT8g9n?C0F#74YGH0(hzW3wKX*L#5dfut z=~g5bFMux|mVNkm-ym8`xrHC07^-E0qll$D%X*nMK zl?K4C;QHMNeV?a5!r}PjkP@Kn2*E-Of@5|z@xPw`IQ{|th6s3|eFt8@#*}Hy(*;ne zsmc$;Ac%kNiUCk6=xdC|w+ebD1Hda^q-X>?KO!BF!yhRS1K<^ofP8_;4+3bLLSpQ@ z5$o^VjkF6}9%#r*TuHzor^9Db%A^X+YzKZ8ZRochhkEaJ^9a~f1d`|CXH#J2hs$Jv z&H5L6KnnesNdaxl%h3?8&bSl!^yw%_k8#k};6f?VvSOh*14a^Ra)o4RsLKFARin!# za%TBt=%7OdxSy9HMMqMUglG>o{Ow!*Oo*!;Ssk6{U=jC@3Sbzwz?>4Ha5+=Plv6Wi z+KKV(V)U?gutgn{ov(oAfsKB(vbSNtq5+Uxu$Ew?B`7=JKt_CHnsUjU$XVi`_>Zx% z{!}N-bQUh906~2~SUYadNIzroV-Dn6?DbawNF|GyV*Zkm*mt!DqZ@c6ks!**N{cfw zu-e~+U_k!!N@Iq#DLre%1N<=Muz#1!av>Tp4TDqAu22xElxV76CZ=j2j%k$xkx{QI z8jIo>1t8#LP}Q~13id;E2#i$8Aa}tF0ssV(mirDF7Sq=OcOn5$mXHMosDet~Y9J=- z`5#zI4Ri1}r|Ja2HRxad8oURdlhpt7aiv7^8xxC8kma=gMoX}aaeqJgpC|v0 zB-G3im%_0OgFFTj6`c;apDICQiAxlSwJ@v$7Wn;pZUU*~iKq=vg-7Ll2GomMU|S@k zQkLe?t|g6qxhpOa8-zZBU=mB?o)yEN?tvUy{3y-i(-kJ^>sL7h-aN=yqyyGFJo#lh zL4^fs=~Xh{^fY&76)Qzpm9eisCcMHm5XU}FaZwOwKm-m3*+C5aL6}#(00IGtpqL!R zaa4CpW2X>u4NxANj=2spKjL2yzxbCxzCAN$ru~ULAa#Ka%5C6v8TE`iAOPzj$Plc< zpnk(6*H!QPNycmbfyo zo;OZn07PH)HxIr+7y{*g7y&=*#Mrm`-72EzR{uh;@6OJDG2Iz(2LSx9N54DwkM0Z1 zCYH)Y(8rV)`a{mK`*KZ`$vXw0zT+wkbnVsgZ)Z(GFz4R&b}|$}BjJ-7hd~4FUcOv< zDfG+856Ao|19c;%-Mjs5bkG3EJy>CXVn7UhhP%PR*ORkfeKq;jP_p@^bS&Kofpjag zw#JbM7WV1s>uZXH5zxiXONw}Kw)ugDc}2yUJQ89EbfvmeQnOp&#^5b2!)ObcSR$s1eEmwE|NIgZm#dv9bf8*$?l;+HmJ20(>h7^jFRPGWR7l04o9iZAO7W z14I0qqXonpa5DvR!hYabgqt%_?`6lpi}?hYGr(>JPJyU805S*RK^}*CH|s(A#wBqK zg+8sSxQrMv80HA5P1vEb@q3g_e2qLGAz-kaM!<{+<`pnuUM-Kxk7BqA7-_7(_!iR}E&i4Go{+n$@GBv)@_~jC4XdP%M(ZXzt50^R*89*HQQ~=rm}6;h_3K;0s|~>VOe23141V31Kz(gN~bZV-O!75H~IGPkeIa&K)C>B$<oN zGhr*0fCz~}Q(RriV93Flns7D@j&;XcA9DU{RTyelS9T;VRcZOqXvmq5pHd`hmofrz zWv#WhRoVfBWTN`|kc5E4-^2G*1Ts-osWQj5USSWO#~BcR`{o0La}J zKX?!G&Px{vw#AtK*4H1eKYmOUe2mJq@Wa6oN98k75WBHLV907ng*TcqvC_?N=+4kr z2t&9Zk${tq!jjN=Xy|Lmp9crO#;B+GKWPDlfrDmEUcUx*PQG5@EI7nbZ^gT>*pMMF z$k%2GoN7}y04k+g4#u|y?$I;JUN$r4~j2MhbaHAfOMw|u(vs!y^}Y@6QEyHFg+Ym2pJo4Jw>Bl4=>2| zaK;rPQTKCk%zhyd28f0+&qT;cksm_3EC>JhN`X!g7#nYp9}Vxp@h*o#i=TyKmC!jS zy2|%2$C=;3=&s!asWP-)u81un>z69zq-_d8Uh>{bCW|-)}a{vHI_2SH5SFD1X zCV_zhM=SpTfSM99c_Dh)!j~~76>uKZK$y#wcX=Rm>F{qD3o|x078gRk`+)^XnEHN* zXaq)N$ukVSA3_3m?Q;W;;-8O8UrG|37;#II)PB@5GXmO2LG8w%E;J8L_v^o?i=dat z5x!>-bStHR9Njnt_L1a8aP+b40mv&cElZ#V9S&0R`x>y!Rmv>@z%6P4g@6m30gq8v zxK+h>LND`AI78~~dJO z5tsmo--0+4`b|L@)G7I=5Fz>Qc7 zt(;V6<_|kPpZ!P0O5m9Ia1fL#P(5&p$X{;ufP_LitHD(IA7c;7vc&!J95=q7jxzBd zzTqeC!vB6$EC7i%q{1CA5D*h!<6)!88Pbv`0GjgsSQI#~RD>2Sz3Eg~j0yBdKspnc z9c7~*Um6sd6n#kOb60Ti8)Ix%SG6RA6(kbW&983j2-jqdh{V5B{VAl+Nmc#9djtZG z^`|6#M#Zp2?&{UwMq#=OGOdKRVA@d#u*=~$BFUj!-ZZDkYKRP5gXn0TNNzac882~y zHOn(6c z_EHieQOG*A&(yuR8N>ycfJMxMoC@(hGcNl06Kx>afML2FE@#Sd5WQ|e= zILi)@!RQIO=9DZAfewleDtKVPHaL%a7R3bqy%6eA5GV-L;FphpbGi71kT;hrqI)d$ z3nk3kWDHRWa04%!R}W@C1Oc$qUCsEW_X@g-T!+f}BsJ zaI+7@SqOKX5bXsxpZ=mL>2xlR2@VA4xT)3m^cex+>8v3xMWRL=%$bY~$(G;clW`Gj zj>A8hdf}oJecubOI+C6@_LBuzAox>33Zt=4Lg-u|-7peb1tVaSLD=@-N~IPxNFn=c zG0)*ISRx3M9hPAJipsAaX>4q<%RdPNwFVRR=FJteG)dujb-y7t3gaL^&;{xtez8fU z&C##uedSLe@-|^{hBOr@|9|4nT zfy{+5ghrYRIF9MDACYeW>gAMjujJUSi&p>^C=8X ztv^-TG{(YzLKppfp|up+zeE9VugU|gg4)X@fwyo2kWVv2(t5U_`jzh;BF zJJJL7bWFq~ct0fva!nq})G`qYIJn}84?d~h)i3!5*}uoMY> zDRIFk?xijG;)!epPPLfnhv?s?G4OoCzq@xo)&YLB44;mw^fRZ29SnHg1?h@R*er6v zVF=FQFAK(sj<{HQvryENg=~CIfGH!NOR&#?N54Nx)tCGTW8m)%bCr~cRZ|LdBhG-y z2}0m&6zsv}EDF_Wsc8%hDU3-HT<{#7)slZT{{XM-3$7_Iu&>frN_()fqt%&&u)E!= zoUvUflib}csaNFC(;>#a!yrSl^n`YegEFI?3c|x#edI!_T7x6IZ>$goBOXL)sO$qV z{qZk8e;P)(WChLw65M|T?aS1N3?{&#>43N(e3|&y%1MnkILV+}Wd#|j>xc-9!+%*= z+EgTL<^nQ8{)gfxV+57_S6Ap2L#Ba=*njn>26YSr0ZZyg>Y8fhN9ILPp$;?ff}}7= zlz#dY{~*c%IT*4*{ozB%U>NYH1ZWY$06De5F$-(ebK$wayjcgE`^HKcsHERSP=a(a z1i%YxqJb@!5dijf-_*Fr2n0%B^y#%V+1@%GeotZG&Nkb@$^J_IGUNKAC8geXIt_t` zKnERY?;YUyH@GyIwUZAbxM0?rzL)?3fTKg7e-2ZxqEHp=7eQEpvK+_0PM;Wz4y3)k zgnzHcg?<_yiGgU6!&a>8qDW^XVs)nHc#N1NhP_ zj(_0?RxV5qeYfXs7vL}eFmr|EH$P8c=cTPF(z?P>z27*CU`_6-;mm^-?BuN(M|7A)5@t-wZdL)qtm!k$NVV177#r za`-`_9aB_D(+-@)LZ3_u7+(Q1{onq+c#s(Sj=cB+`u3CV#deIN)Bsm@RBEG9+>aZ@ zbQp_rTT&=$28Ve(z9{1CP8e}lm0(C9XQmLOE}TomNMD-&sQ>NA`a*WQV7QoAKs+c{ zTjQcUatu(x%fl==P~sRY%Q)zf2RY?*mg9Da5L58nAC5Jz#`Rc>RRa8}+b^dThl+Rq zLU;lJP^H1qq3*g6uf$Bqg0o`;L`XlYK?s0iK#~-OaV~5Et(w;Ge8`wovM~BL>Pli2 z`hf9qRAE+?4b#tWQ0A#WQQd7t)*pBL_O=fB38^FGUl@=N(ohU}G`8nbt%bTmalyF# zJ$?1_Q}&G@UZ!QCh5f<*{AbB0J68H`8vq4_mv8=sTEOi!Dqt9hx=pp<&dvej?FoRg z%k5lnVfQL!F-ST91orka0(xhMeQ(%#J2@1pIFp&rJH6Yz2MT>=7|faqe*^h$^$PyH z1BdV9i2-maYTkJB8^HccaA7L_64uNV%bW_%W8#|~-1~eF52v|M>pVJ|Ew@7+0WtS| z{k2Yd07QC#k^VOu@Hga+U?$0=NpgHVz) z1Pbc@_qHdOLf=*^aL^zh+kr6w-peJ?mzo>Vb1C4(FS8q=gT#5P9 zQ53-;1|b|DxePEcZ@#FB&deZ=S6u(n5o_*dG=Giu3q12 z5<`1zq>8YM5MF2SOY4GL-_Yt&rP@!GnN{JRW=MXi&S21Zt`$RQt4llK(kw5l#ydiCn*Q>E=M)L0vL?B}0L3$#DB^WcXbOqsSW1fCRP+(P~7!-wtGcp{U;B5wO<`3C@0OKHG5)ekb2O zp%H{_N1cn}J9;U6?wwie-H70;ki#(j9upMiDZ(K4UqBzEfHO3OY>c|~E%|(5+m#g# zaQ6B5o;uMT+3b|l$)I>=C2LWri-pY$%#s1vd@&bj4vE;1)fcRx(MGy)_pC<{e~M$! zKYn9$AaY@x41FsqGO+_w2s87=I+f5f>I9|%F3p0x1J21290167qAG4bi!C?}fIYu^ zYs*JZcz}B%1M5Z#KGnNt4npt@mt zA1SFh0E!1WnRkPnJc@ACUm9`p6E`AGq)eK)ne|BGXWZ~Y0wZBeBdKB%0KymS^){~n zDT<-FEjMa`hV!u)L$8sS#L*W*0MrIN9|k$LEVVHvu%#tQXiB^TatCC4rnlcQ)uv%I z;tB9G+pvV{5Y>NIy){}4rTiosYT&M}Y$PJyUb zTblq9_=osZlPrX2bHS|{3VIpd1ps#S9TO`;84Tl5VHugmu%|Uwzm!v+QV_hSSGnz1 zIaG4$n_x+F-Il5ufF9d&`fIGp6k!6VhNOF}K zs2h=Q8m%54^(=_q1FFpqgg9E~y~)&%J`MvgaPRA{XTO%tg`=Pu;aQtQWEP&~_@`r{ zUZwc_2vbeX!=tf@lZhEfc{E&t9f##y=&U06mYu-)>5r4(3uB)Sg7<`hz&+L$UAe-$ z-Q4Xg73Rj=jcoQyQPEM1DFKX3!W2U*28QFGX2Rr^dzKr5BN!`Rh4VXLrU(oMI8J~k z3gzg6z%NrR$d_L>r(zW|0g-#qbO}@sNJ@m>OdTQdQeg=E6yeW7S;OIq!{j%7rilYN zb3L^qrIZ+axPLM$$UNG2@L$%0S>Qy#1jmpE4Rlh%l#3*AEtcPMMt6{0WQxP+hufEzW3V5G z9O7vI#}e3anD>CRN04fo`Rett7z5>UBRA4NrXEY-jCRmNoa2af9Op=xOhYSp^#|vo z{!23-L2qK>sw$Iw1tbpMVWQyF$n;ofs>kX8HhDp&r&IEQxeeX`!P?@V6;_Z|vBv;3 zcBnn zf;-qPLJ=SUa0_?9r^uJts!ahcp9%mKa?q^{p!nbqZc2YcV{a$1t-JRE!&{Kqa``Vp zKR_Rgj&714rb1?Q)kJVYzqK7YeJ|K1()*9@N0Q`_hodwCBz>Ui#L2>+4)6 z-SK$w@vX-*i=7M;pyU~|;Q-yh_^u6i9}yb)HAFl|B8>YxMwN~4H0MEpA24fnfXIiX z6!5esXxoTRII_UvcEj2BndE@venT`k$&5f~{yrPZ1kjVDoN)?_1b)367|n{2#%~#> zSN@F07wPe5bpnS2#4eD5P{A-4CYj(~cnQ98`x1~45XiX?VwkY5H7&p?4nfiQb5=wD z?stXQz$^z)2q>>y91U{>%v^CszuN^lU`j@9@`9X5=fCC|Q2AJ25(2+0F2F@Iu#Itv z|2>_zfec#;mFdz%!NwY7SI7pxV-xuR8;wAO-x^lV4K8L>NN$ z0SqD9bpQP*6`?mRy;AsF>jpq=!c2#j8>B7`N!2`X5=oPnfXA(>f$nNQll+{5FJ`25Ix?^TgCb6LC&_={o9dA! z13O$?|0crwYaT=m!2Km+?Xl@d$C{1UxDZv2N7Ix;XE>~xY9jO8W358ovx3B`k%^`8~ zj(J|z!yz2zuZ%$um~jQ}weM|h_44*k@W31iIRSQKQ&w5hWgQAJ`N{a!?e+IX_di}D z;q=jqUY-L*3BP;i*7KJvJW}Q4+np70{m%3$f~cJ~TUg)dh%03{+C%OmU@Bj7Gh8hfe+H_(~f@`KApOea_F-=*y&ij0lF$=IVB?uXC3J= z|2ZOm`T9o%!TZS#cQVGmxcn6fVVwcB&d%o$m_^}h@~gxcXk$ntJ$Vq!l+Y1hbrjjD zwIEK)eU4IfVR}U+bf_g}-0Bfk&@#y3m*fY-`AUwF1pq{lR$J-_(Zw)2LpTAd{DOPz zArk|EZCq=|p#S@Z!B~zD>>o>r$C*!CFgr5Gyb$A?N>xpPyan!#krbZx5ACz3%+dD4 z3&P3JeIVR-C-iDWnwshq$}WHW@$A_{8uXX}?H;5l^S>-aZ%xE6nULxsq&p5nRa$h2 zrK`FE?uscPTJcQ+Zz{g=pIGW3y+J+~*E>S#F)IJ~Cjcr~{D-V_*nHo&5EQ#;p`-X2 zSu*_1fQaw_vpNLmhX9^HVZZi}SBV^b!d~40m4Dyq(5siU z`m*#5#K#j;zQ8(cz}K!tk}^Q<7Gn_jjZZeB1w>mXMKA!s(ItQp0LepOin*uSHjwV1!%h1Q!0ic=Y0h$>0~lKp+0F`f^RR zd@lenlSa>_Ou!V2kUc+p8|OYR!udq#HsEaWbt!P-fS+B;)qrUNyp$aQgZj;4vC`^$ zK8ptYGCTg=jX>pQs2sE6KhuN;&cqlroc*1oKG^!dj%wi?9XqkW9#7 zT}aSTZ*wr#So>iXpgNY*A7f%X#>9h=^WF8>MOmPD;$1m=CwK|m4Vy4s!9N)Ipj#0; z;`vXdn*F9S=%iy1VRhP7=vSv(r>3I=6AhIK|Davzs*h6a_A%2fmQ@|JqpLRWc zwbeM*Kp@Q4^Piu;`g!Z;t*uuj7&h2ZxhC-A`R`zD=Ly!~gM%3M1ZfHa1Q@Pe&;s0h z&Jp)K{9RBgjI3_iS+JLY_u|pJ7w;au{Kr53fk}`g3GaStd(-2Io@D)1{|DLLC0zg? zGeCe^7dN4c2+@XX${}Phx&TJuxresV%=UJlg_vK%+M!FH=D#5ge&Zo-;mwfCZ+yrv z7yv^qorKf0epo4^VUY1KsW^!M$h3SZp833}_yeazUz7OxRyqJ0^5PbFYcchruP?r^ z5}MDN057dOubxZrZD0Sw)63_%o{v?5Z!Pu9f&!EF#iQV}w>|j*P*lk6JR3SC2iku`jcOe3@5*a0x~%mbHKnvPkIDDHkw3KM(>s_$7rvXER{L!Z<0K zdYC8*Ia8FvoQZz)EFn72hz8yc;8CJ%E5P!u4A%bLu#M$4Izx5%35rFin3P6AfZ8oKWH)GhdEb zCn!Pmh`vrycGX+3WPGv_OJF$V*nDdL>bvHK0g=o*C>_!S($!Vt1jtNjd@Cx`OH>6; z9HR}62zX3Anb>=O=KmR=|NPJATaBMzy#gy-+W9M{y*Eh&C?*6?2iw|y*A#}OIj>um zk2f0dkm`cm7Zw0_?wAnK6;Z#0j7WFqnn3VT_dA3fbpPW8m*G{VVevTV4Y+d+g}<)8 zRO!)63ts;8Cpq5;eX2d;tEDXcPYoRamksCJPo}AlUm;+ufOsbc;V6WDn=!%0zq}i+$qejB=#Q>|DHO)Xz)u1IHTDq)wf6e>7uuJUhU!_c z&g7~q0_p~MRTaPL#S~EjWa6(@rP5Umlh|pi z6JmEEh`~#id{iy^6V}n^K^Ei3sg@rV0k_##TP9ng;aYgx!^U60XpT|%%z3uIZ1Q7s^6Y>a#vk@IV$(!IT zw_+OPh=uGIktsOMf2k8L)uQt_IV07x-5`G+h+>dMiU46~j!3L*{#&OBh8XA!1T(?X z{!s-;ptBQ1W#%_x2n-W&;SQLqqQf5YRvk#G|2JG9&zf|Afq)T+6=5*9FBLk1Pkj7H z_?HC&rX~0R^?zS}sch&N0@KVF66ib-Ml48#;v4NGg((KY@J5&wf;5eQSx7XJVD{7C zhx_35c(q*A0(ub+H%K0gS^z*iYzUc;5imJ{WehQ5RVs~`03#Hk%;A9;c;p@UNC+5W z7{|tl{(aB-VSj3Vz8uC9ey?M;D#AQ#0prwX>o6dYW1*5hzonfmMnBJf20$yPA$L}% z=AkTKB?2JH4Bh=C>^pRfbUk$=wP`aR%OCxjFHYn~EXc=oGh}7bv?<;Yxm?wvyQ^nS ze6$5~-5m+7G$+Yvak~!ro1P9ohs!^Z@CV0mt5{qD;1mamlxH%V9)Q59X^F*wV zf$x(~LI!9<@Wnzok^`YV{Y5#5`QOt@hDoQtycYBB=`8j%Ou#Awj@>u6iWu`Yt^Hfh zw_pRH)zA2f2oSQsXAFS*!G0_|5+)_WoIII4aRvN4DnHi@SSe0`x&MQ6U?tV0hwh~u z6X22FYX`RF*TU$S^T>99dI1Q&FRNQlpRYw!YN)0QQ8CFPB8zcZw6P{Y>X_vcX;Z#k z41xB~(eDv15z)fh7o{AbutnKe{7QRW5eZpioHC>9(!j)nMd|$vRDdl6Lg z!2c0jaBGAoXaIB+f)&uayN4EVBjW}A9}}z%sZvnAi}VCcfTa!!i15!qu5?Gqia$LV zo67WjdfsXeAL8uSAOnKA4`)EOhd>dH8E}gL2>d%B>k;p?0&Dyu7Vac(h}jKZ2B`=9 zz&Ct|(j+Pc)&I8RD<2=7?zZH`kA)xI(m%g^sa$AIdYt__WA9bcGe3g)7a+$kDEeUZ z$>Y(-Ds&6QT|`|4?hOo%j~6mv#+7cboM$YnpAYe(7n#q{v)s2(CWzfx1E5C3A$5Pu ze)bt(T$?4SA}Mrof}kI6JVE7vLa|l`Qz!7optGRkfsYZ7H6YYe6!fAZ@qGxi6ec?e z;>C%@OY4`I20^}eE+PS$gP^>sBJa_Y`qAB()KlPs{l!PYbJz=F0{E@@keL07fiTbF zAQ<;Qp8{j}yL9PS#lSfYk{lsTw6;gO&=$CMaSL+^}nc+mk!^EKh*-dM`Vd}q~P>~?ZM0fG*V6k@tbVF6Hbh21@ehA=27p* zAN8G65uBiOgi~WFN`Xbc_1zBTebMrQaIX%Y4{NoD6XZdvPDEhg2a7LT`rMnR{kRVj z7X-oB^DEyk+26)7C2Ap3^(o;G7>L%Tr==a%VgmTQ2ZxEn%m*g7?VSt*x5bJuKp(&d zM+g8CNCCuK00`bISc zZaD6W&y(_4jJ{U6<)7&I#X`Hnacg6=P;oxF7dAB@-RJ-IZy4V`zrQg)=}Vy^VZK7u zWwz)h!uPX;h_m4g0m(}M9F+A#?IF_5;5(>vSy@SS=qt0)j%g#_;HWFoIsYvh`0{S_ zW+C9BKU`e=esS@;b>a_?e%Al-13h2vNkd@f{(a;qEKY(v`9;@x%E4z5TqNh;5WuC( zm@GqIjp)xvr0B4i9|DUiz!M)KV8(-7EcoGsfsu%CF*GoV2F{_+=fD8K%^-mj1PLrA9K7u~`tDE3HXTbS# zb1|mFp@X4i1=2mqOsMQKb2bM{b)uHjFTn7V7@6sxL_`wvx~ z6cJhONs`CI7Ppaq{p*J`0dhs1wg7MQ`Xi58A&&W0n2Bc7PxKF)1^>~LW!!oM)Da=NQq3d6K$Oo|JdFBfR^#c>c@?i2zL zN?ltF$LiY>%x%4Q8Y)a5wN}LDgDbHbhOS`Ff4l;|dRhYN9US~G*w10TDA zx4jp?fvcAgx4m}IiS73TMmMya8hNBVlrD zAZ~%K#EgFQ4Ezc-h?romz{wP%2rPip?b|#8uHI%V*gT(9bFRn5T>3fR*$1qJ{X zl+q50NuOj4%-pm5mjwP<2ben2$${Ma)%`C^f{7#G#bP4hm!F(30^oVmzex_$+z4{I zSd)}x0d7k5?3piQFlUB`1N}Br8kTIpSwEa=LTrNL)5+WrtTv?Oj2+H1Q8RiZ&=ATO zo&hVx32IBGbmTm|eW|!>Kk%07xGOL1T=%=tCnQmteQVarfo= z%ml%DKW~El9jP&-s`3!UW{qU3=LkdKYpeS>-T@kAjFSw8xv0pHxwGqEL>wKFy##_5 z7M({ZR_ladbL#lYYXowov!zF_3<9~P_e6+0iPNIaRYqAHV~rV zcCf&JHV%9rwCfuEycioA*ZeJ#&R}g-)9>0^kioPLQy;j)hPO2VV5eLl*>U=zWR(y@Mm8E1A%sw{0+U9>`$*>k6+^l*BE=M zBBar1N9R3qmJPv!*IuKa^O`bHHwNs08;Ek?#WVrx3OG}M!SzcB$9DuEm(Xa$h+oFf8W?zwzr=E}$gCHDB(wG~8g1JokM)B1R@4b9_R9^k}*Y!-LlWv#lY z@@V;bN(c<7%j|IW!=;SqsDImUipUos%!L;_uo2MlfR&;ju2QIh6NGJ{lyQsy`|2|+ zZV?b00e-cLC&Nne$Yseg`hApQ=fXyNh51qu32nLo3fEi#LiLN*VB`QY5rKqWKa_yc@j zng9iYvG`{FNceFH z?I5?4BxaqKkYIxWa)duU<{Zy``LY|+jenUG`dNVsHY#F4es&{Az#Ex;m|x=z_$bOU zpJhW}b3f9F6U8iqixCF+N#+7^Eu2E}nT-!7IB?J@_#FLC7aBqG9Kg+{f?&X$l3)Vn zHixe}12EV9HJ<=eJ@EB-zHR`#9+6nrQ!dPM&>(39j3!`*1?DrLlkhPD&L{0NQ&RVf z0GJ#fi0I2~zzzOyth`m;((t$Cj`Ugz&M!9uU=qM6$x|peKkxYbmSS^AB?V+repuoB zhqJ&JkE{_R)MWKTIhD>Y!G-(q55QxC+d)Pooaa`r} z$8GgEOF9qf&Qms5|MYZfk>htvO`%+~1V9D=YEy1w-b;HW(s1Bxlhk=?`bW-w)6);R zOHZ}DXRe=w>ExyG$6b=>k3pzXPA|xYU8;7uON6&WN?=~;QQ|f4-~cv`?e)a^N)5ez z@MK$@2;9M-KBx;+R*W)IdFnHsy?l8N@6QqQp766kHdDU50CvJXqTIioUbe$=2*mHj z@edHV^kl=ly9^AP7j60-94>qnj4Bt&i=~buR0{UVM3@Nm=F!#Q{L;w`pNguPi=nqzJuLJ&8S9?^^vYG{^ z_N1M-=mN=80)sh8Rhn;aWS`H5Mlr&-6AzLmz+yL2UI>yM0Yd|QzQBKEDF_|_l>)*daNhB#T3Z`gEQ}^V<6iky<9Qw#)5w=! zQ6zbyVAwN_7_*cPR@P@ z?Dt($5FkfCGQr&}IZE0;<7E>V4e@LNr^Ep3~16L_=yvF#NC%`uq4&UTTO8=x1W790Ll@3FQY#SZs05oFhO7Z_@vN{=@%Ind^*Vh zZ3B)6hC8wy0JhVy19RhDKC>C~;BXQ?=i{II&{G6VQ&3iVS|2P@OGh8JLLoGKxj?A)HFhtT>h`v?O>6i5dAjard zw*NQPqSs;;1oE|60`2+GevhPgae97!4D{s3iHRmS&Uq1;FHvBXE3NEsbr%MYG4Kyf zAHU_|THg&;MBAv3d|ZneCvzP0m!vRh^_3zJBrmUmRU0~J^Q|jckXGZ7>F|F{kWs0t z0CS=>leb6=4KZIUzmNDi!ruhr$wH9A;mN`Cc$v11C}n- zCKjGQf9}*BD4o&&%RjR=>PO8UE6+Q0nEXZH729#QfQYj;0zkRogLMiud)3SqaG`MiJbUfGi#5!MSyh5|Mo;w zh=8$EDwiduB=ghfW6zR zbD?^<{MIyxZNiSB#fLuX<(A;wCG2{*XA)9}K=7G(VCi4xQYXl>U%{W#0JA{oJPAgt z@F%Gl&NE=4893g5(v*i^xCXi)E|nn-N8qVg5KVa3liJzuwIW~Vn#{@XdVGiKfzJf~ zEh{D82#Nu5CV;6F{Vr0RsS$7o7t4LlI44lv7@b ziz5>QEQmokmKxY#rU(NZZ-sb?(TOSdOmwDEW1?;s+!!u+s#52L@GS3(EQnJn99Lg6 zA{qzrdt%B1z!K`nGDAd&-{JU}S76S2yDk~7Mx|vuS_3v6kWj5+d*;8vbTu6_0wzd*RpzGOE$i0v7mv3&qt_{;OfD&)&I* zxGFLk5Z{MEoq1SYED3oC0rXY?;7_IPOyjo}iCCHL#qN;D&i~s^V!&;Wg6reKD|#boc+2?4BQwmtiS2is6f2p=NVfb0|F58ey@_^tc{ zsWBLzpJ>&}%Lz~v2>_7t!H37FfYuJ&WdPjv3XC=P@pkq&;QvgK@UpJWSbXsIn>T@v z>j#uXOBTH*;+H$_8VTfsgZ0(#zh7Us{Dt%3j4CiG1?=p7NdP>s`3)s-2>Y|-PoG&@ zvgso$K-WW`Pza3P2!rf0UYz+ii+Y`qCU<=cR+=}Xu`Z^v&Xe@XF%hlm6!mfe$fo5U05HH=9#(G zwEv3u0OJb6!w@Lq10)F0Z#7MV-uUTnkJvi(T>2zIgliSxnLj@aE;q40g)@E3gqgHDxDa?3^R}#MP#~+|A}od?nlTK2$C>&vZ9+JfVW-%;!sD>SO`N0Y1VN7Q#ITrY%%5ZRl49%u zX06IisInPY&&0jzbgN2@Fr!UnanTbhj8kA%Uxz{$Cfac~9GNBnBI9a;=m*S0&m{n` z26qRt{t%%}y>|()-ufQn-onEgAdmqGB7dh^-xF1*TX7@kqdT~3YnL`+ASW7zu>_Yn z0e-jrT?&FG{t@MP1mtF{Nn~3gR}8@lW5^qQ<^bPHHQ=_e?}=$%&WZdrJL?DQJDoF3 zQI+(iS2gH-ddXW~xPO=M`C9`#`z#+;J5ctilCgS5tlq2;-M^cZZfYQeh0%Ib?K=?LT-yHX-dAZ?AxJUTak9r^P_<@IqQz@K5uh5nE7IE%e}WOPqn@?GbpZZarH*UuAO*sdm#P7fOLTOCbg(0s)77p*N^uLM zc{qYnslVfJI3>WFmJ)D;t>_Fv82J&VHM&9+Ap@>?4FBdxYOcnVrz;=;5K6=@%At9O zoS;zV)UI_aw7d~SH4RQrh@sVVXQ^OxU5Ytb&@eZ#ph6>dS`z!fbKnhSzxV^g65QHR z@d^*iMHJX_~f1d0E12jJcjIm_&D-x{1S z76Q)Qcr;hM`z7GZG81A4mS|?~Su|tvb>yKY8FVoWfhri|-@PmnFa;q54pRJbJ_f*# zV(=e4h)h7I0xAjmbXE$IM<1jdR5zhVBq~x;69J;xZ}S_De8bm+1zA=qel!9L?m`%o zMA6NuFv$XZGF8PTHyovbN&Vaq6Z|)m7I@Z`P%sz+-%mwDT;v_Z23$_nnEti#Bb)z1 z5nav`6%s(!vdJ<;(lUt{08?S6V*r7a&bs5*SeL}&q(e@HL5@)H7p>`s1QRC^OifT_ ztVnsa^j51;oX#bgqGvS&b6r&@o4!<6V047oJM@64H{tB7k%&RCEsjb(^3xqP9v`PC zqWr^C;>2#<#ch75WCRQG!h}O&d?~D=r$`#UsYI11Hp_`wq;Fd%Vtv)}+7R~P6Ntmo zp9i5)(WzaOiq{$oq)EW}!XR8#nP};-hJ1X?iBep)`>&5_?gpSCM|m&QtpfE(nSPcv-_877kfb1 zdpR?ZJi#PoR#FlAt>Av~pRJVKo2o=Of?z z7?Fx>z_|UYl%#VPZDHS!v1JWIr82VC2rat_(0E6>+EBfz+P|yGNOG-o#HzIsYoJUM1NTiY(>q1u(>n`4x`tnC|iDZ@!NMULk|G&tp97a2~Wn52$=*Dr$!z z2Q!bD59^V|%BmpPk1C7XXjYS;kBKYdaTOEjnU7zgRK-iLk`YqEAN?Qr9K0GGh^2y4 zg=av2hhw6lleRBU2-w;+p|E>48kysz{$@HtWB4y16L4r@WN#zJEjT;%A@6)#b{%N2 zKu-rp!%~OPZpxW~SZ*urZ~`m#6i@Xo{y9P#)W__YR)u5XDo7yY6nIP)xGgI-fqz>i zdq57Dh3Z!aH*t~25pNxuJ&byo01t?VSZhQ7%*dE0dM|&+j@Dl`T$<&b;im|ty%-HS z%yf6pP#V*_HbZlW)Bk!Ua&{1m7h>XFcJ`CnIQ3nM1|h?{5imEJS$ro|)|SdJN5yLh z0Pl~FN(#+Q7MhkJ_xh6O7@G8{58k-@_b~(B`E)4a@hOc_oD5!g3w}*SAYpGsjL0IQEvzlGkko+nk8NU=eQ9wW6M{-Z1zh^z!N77Tm=JdK@v5vKL!l?#q&sA^cVI2Y(5Ff`G zi8V(3iS;j61OCP)v=564nVvoj^y6+VT^=oR2Eq{*VEX8X(;Y5*jNb3Bx`0@B!PJw< z9ej#m2-5W#_gWcYs%lFOeYHmG)WZh#FLV^Y=Qm-ipMoNWOD}srAQhkQ&>s=+e!$!< z{)K{(4@__*0xtCRHShX~b+)r+{Ft#~FU&U@HPqGe17B~!i68_;At*ZE(GT`+!f@7!R@H=@69A*Ex)A653 z1{eY4%Vm`+{y8jevk@#MS?&E_$jV{O8c9gRgi(QTmWuzwM}Z& z3v(O<(4R9di=ZZ--0Lh-Yj)^sB|y^;tf5byj}^xucqJYjP#A)s&P~Cw_zuj_z8Cm6 zqXBSTr$D#@IR=sg#uOObuY1v1i^Ne-+wYtJ@NyoAa61ap)BYQ%muTT^98B3UJp#a< zI2!h_W{wD`?|n8GwVSCE_;#*?zL#7e*%){tDPX(-J0a`hM-$)!|I`YMMfkLXq3Mi! zkhcP7Lg*Ov7=2*IBSydB90ije#`i#}UWQG2oH>(npk)R*lcvFwc^q^h0?Tcg-^K`- zQV=2vKMQ+)o~5H^gWgfL&t@t3DH5ypu%TLX=3qGhzg#TKY;G5BxIn2^3rAfjY4Q<} zhB#W@YJENhvJ;r7c37%O@NE2}1~4nz1PrPLt`>#CPR2TMVxAVXzX%<0q_ zSD;swn4iAaL8qMQR7AoOVw*<#$pTOKH@2JC{UDBfrcrGHZ!~vcU|Xn7xd_BpL1JEO zeV4JS=mvo{rd}lu^UBG25M3cIL+Wd9E7f2S#9syvx6~qs%OA0|j#9WTP{8Ql!|4He zFqi;$K4|%Utm$ucG0<;aLO>0L(*CXQtao+_0C!kuzJ~4h<~c^BN(8elYX~;owQlDg zaP39!Tj%O!F`hC%02F85A@^_X<jD-S3PG*GD<(o#(k;;T;DJFcylM8+duLiR7lGG6$p1RmJJtM-H{srTRDvwB zBUk{ah4|6jdfI{|jZPSMh568Pw*v$plBv@@0D)^8{$# zm%rQegdBNw-Yykt@ZNr2*xC?frHb@pg7=QGLpkX%^wHv0?|O*Ik&W;;7$W7MLpOvH z;8N}9U42MTV7oHxzhHi!Z`B$PIZtA;JSG7Q0kDhNFt4-%BMISy&Ay!T*0)Jke!uwr z`gX6lUnAh-H`{BGc+jb+gB=;))a=WYXQCe9t&_2UOn_D#AQxMn^ez2eRR1}1uy88G z&_@s?`YlNXxWs}a>H<3%1fy1sYsL~_;f8Y%6zr0PB8=ztZzgx|)7(Zy^bdQJpS~Wt z#>?Jpn1jb1|LiyApJE;aAPzb1RPC6U0P%=utj|9C8t=beQGMnp0q|O6zi|D%HmfwO z!9pUm*^g`ic9d6`LHM-3jso~amB8od=Y4p6HLnStOOHqKHWzK_x1%a9g~2@PY1Tf6 zVmc2HH1*LlmkDVMf^!jtr4=}Z0p2b&178yE-79XvX%)U$fWX28_(^QQob@sU^wR^$ z0P|k-NW?esJDedNQ%{Gz`RX~%dbu<@g(8>{aTBInF^k;Cem(#e-sACY_&-E}%7<5}m26}lL9NuU;H49Rc6)r})qe^pQTsB`ue^Oa9U^)ZV%mkOC zMjdjFS}ogvOZJ9n53UFR^^!CQ2S#b3%>?TX=xvw>K`+F8ty2n-Qbat169j-MSgT!$ zfQM{}tB>`2DXlvufttSG{K&31H3##yc<6f`R$A!)K(AC?kv=g|Qr-*>i1eFua9I0DxFkkq7hm;JfcH z^Z0amW_=N3VCVs126@ck5CC|vrXsj^HpOu`>|{RlOA4Wph`_!03AbPFzY@KGBknw~ zy_HiXS76DZXCmoQ!ToG+MA3FRK1T-1E$|Q;e|4o z`}co<43J?iM6zp0cL~Or?8fV4{ss1Z_0?C3K=|tQq-R3WzOx2Nwxu%^bx5hHoE=?{ zNp_gOtG@MGu)xfKwh4HUS@;7pc`DX`!XC%~1Nb^44?jg=B>+s`5Z(kIU2)(6mf;Kl z0ee8I3>_VdI#&Qd4}qbDS2>=xFOZYo|`hnokpLt*oIHN&^Qw(4{JQ7k9t${E?0Rey^2@DiuGrHB!IOrw5 z<6GYL@EI<+1=CwL_npiEFjE0C8-_4srC%oQgBB(gpcgG~MP0KLfR4iA^!Kowe|ur$ zjft_Gd~o^i+9)?A2C5a)u3wBVI?`(k4%e@6FTjtnr^>!BwS*a@Efmomo)!gw9q}vm zzkAJwgvOQ@rJ+Wi7Bl#ynL&HpS=Xl59S!Y3)FeO#ccSsKs+JA_pf*~O!LoAno8@Jx zItEJB5oIj!$n=j|lfC0|v_l+MJ#qxy5t2$WbqD0XW$SZz*%q+(0_2Y2^K6HsA`k#L zrtGXkYx`>Y!=U7llOcogx$*+{^y(O^;-Ga=WoTdhu&-gcQK@7*-17!S&|AbnBm$xm zi2&$CXq@_XY`I^YA?vb%&yX2U0k4PBuzpO^$jj(eE_=lo% zvLct)b?aJ{RhXXNnG}9cKd`IMS^GPPMRJMAp)=qheHNGjH<0xA8X~@p*mEcI2vh=K zguD0}xTn{5?hpX)1J#scHQDsghtUA?nI^z-2Bb0~i(mZQMvzEI9nVF9jKbHM(Dd-N zm2?ZV19)j>a2!QQ(F8JROUR-dk#qvYnorUrZw3zF<8?szcW?cYs?xCo3*Lx+eDQ)L z2^L^RM5k#kQlX0@pd%9WqbK5Gl2y1+2J9?o2LooUAW;d7chs1Gt8c(Wjd*-SKthr!KkDojx^B0PqRk5K;s_H+gO_N2HC zeDrN*`QZMWFTT+bqVIA`+z}DbDrmWW^JNuGa00)hPzaWrj(~Qw9XSD^lD<&OP_)J= zP+|GyM#yY3cBIKW=U>TG1Vf;mzX5us#0HD+(8kMiAP;^WvdmRdBC38>hdE#>Vd~Ng z#!$$Q4U9;I_5j$H*+*Ox!soN~QkDzNrnuu$0os|-s`~Y@s{C?`pM6kNE~2M#E$k{z_mwoET+xg6Q!S z^&nfk0Wt~yfNU>N>T*b;fqIX16nwm$asm$ysARsNZ0AnagY>RNV-od&V1Y69p&(t$ zFalt-0Qb5dL?*DMWCo!dSXJjVf`Aqw0Co}z2_dvtz!Hb2(E(@SPo^-ez0oEAh=44j z-KbOVl?XkF`H&MJ@DE8aB0ItWry!VQh9lQ8`_;dFmP!5;gD(Pj@~hX{jfa9j9!kbJ zVIQA30bYwKkX!Mfm>LYN8>1Nk4A>jEHIM}Ya>gB)K|A^)D$>_)6*@83V+6e7hIEyJ zyfFUFUGclQAd0Dl$+BSP;@DS!LA_R9!fGOlQ*HX~XURvRPd|G0$OB-g07Ze^GxFWb z%)nN`-1{gO&|<(8iBLEJ-hFVsKnABwET01J7OFv_`QuE&HCx~U`ch@OIpN{qlnY2< z^kyhx82lFx!r!;cfAh?k6+cznAxas#JdY+b>7a zf!=6tKz|-{-j?rwM`;CaJdAE&4|hl8G#UjFbPk`5reQNqi(A=gP|_D403Dm^8IP^# z^7^;iEEmE1E%bkoA0`MMYUZ1oI%Hhlq1)0FjLK#;`6^282syN529s1>;rIxY#xzLE zm(>&_3O>!uYgqHjIS)nKN9_+$d&z_=p8DvZBRi~$qwdQ9K*a$H^Z;EnZHnJ}FH22%o{B!HN4QHVs0`yz6o*VnT|K#E={fqsFn6aP?>PEQCY zKc@f9Ss!yd=>UWC$f0j;F8{0t!MT)$<=RXQdOb-G9nsJ|bI-CwRIwj{eW8I#Jjkzu zp|ecDNX2i~L0btE#Ymh2ALPZr9s*^6llob=z92kOD&TOGg5X=u*eDW1qNFeqNjnb9 z2nhJ&GauJaI{rQpz9)@~nIT-RJC?fbA1 z=8wk5(b4;rB5lGEFn0zsPZ|i?S5~B!vZV>3TVbp#S9}Dl$rVzHCg4Z`bjxjr#>2AW z0`;a?m_suF#5URCOrOv)XJuS{w;KAtdTDoz5m_Kc+TA!Og5pKSy5K?T`zh{)HzlE9ZVa<)P*MBt0wFc>mfC#sbJ zfFPGZCLucpq;U<%xTVV<+u>gE8UB*e8d(tL{Q&|W?;v`3@$vVZ{@zX z)0d<|F4HK7FGvQB)?jVWka={+tk>xP1UxbMZV`*30FZiTXhH^ONQ=nz<|Nd3;MDZ7(D$%PWW%X5Yy1q zThKorH5!Q%Ze-4niolD#=&1*!RwJ4t2PhL5Jq)vQejKC-Q;pj!KWJ;nr?UL1csaj&t3J1Ee zdYg}dOnv#ySPExOZJE#r)^}+s>Clx8kA4~E>PX3I?-wspS5Pa;*~i%6tMq5+Rajci zIS~YL9rN7uRiz-9C}B#fQ(<6gLr>*<6?SNJn;--ReSFMKmJLa_LkNdchylc zJDp4f1OjTN>Fq@~I(FR7UY@_!duj4oTqhn5ApYPM5U_XV7Ikq0vVKq+jXF3c1P<~j z2rvPxEP0s9Ne`wV$O1f`rolZGx9!O$$9&U0O@Ked+WPwclJ&MfQQv9X_>2n$d73iJ zdPy=)N%S6vxi29Y3c`decSyJvt{|bZ1b8PgGyy|wB!&o$BwZvIPJ_m)Kbq9I>FRFU zz8Dj8zxmnft9rdN>7R5T$8nyY&-Y7r2NOe>UDioX@J;#DN1ApDi`3QMImqiv~qMDExi>)OTWck(+@nZ6082o$zoB5w>6Q>p0tA+cR|~H!PL+$WCFK(c zGn(bf6!n}8UXtI+X1Uz$wtgk@+>?aI? zZR#Yv*E(%aZZYjN?ZixC&^rSag<#>Y0DmP6>w*df0LZ_qLd9f8fIw)V3pi_V5d0M{ zGiwU@V~!t{d=#L)cnN>7lK*yhU%ve17aju{fx7J`I55F%^xacO&rK@|F=g~sN!X0k z*KqwP&P($(sG{H$CmEvIC^T0-q}%X7b2h zS`LB-p{DUK7(&Q~oWB1_{Ot5^x)sg`zca9=>_uPJCD6E#0C!VeE_n`<;Un=MkNoqGl6`na8TfA+Hn!m!xby3; zxx~xX@ClH~35`U*$1nB)Fs5F`;H#a8pf>t7%x-K!sasjMAE;4;{{rzLm86>|E|iC4 zGBd3PYpo2&r|m6^1-RV^6D7+~+R@+cI%xHYC`gcta6VtL(9|5Pak$Sln^XjqX*l0; zdaJ7={j2~G`sbQwLPM+fk>#T*DB6Mo@j^SabHQLtbV=;RRS#SWW?iN z$uh%{qG)K!T_|6cl^0J+JivlHs`vs4lw%r#hhEt^uZ7d=g3%uJf^ts*=jgr+nF*r< zJP{Ih7kD;=XKrDX{*ac1Od$w^3M_})f^xh`qQF8k@vox)3}p*Ogf;;`F7}&iW2SwW&F5lzMfS=@9Hu}6OPvFiicjxd$U&G8@)pZ0NP=+%Aaf8bA%98m zS7Zpj{J%x1d?W9EZf#JIABNYHc08};tN5999Q$j$z%OhX_yUC<9JqTdB zQ|+0Psit)AK=MdHg64f8BvxU|LOt@4FTkLYz)S;VR$+97cpOYyTha}DIcCD}^?9%% zo0l*DOEki~ks^vjm=7sfo_1jOzJPRL2-F&Eg24cVic7U6M*;E&JA1P9;)7d-Xo zwCRIyJ_<{)kTRHpg@Q8y0sqrW;b;mDf))4n0{&=<3+XXCLD9lfV7vn6vPtwaCr5o< z;}neyD#c|s-m1A{QTmF$(l22c%X~mNg1t4Q$;vVUaKf_^rFecye3S2QGI4}b4X0(;FwkljOLes`7or#!$zs||ri7+U5-Mx9dFcc_v~9s4K(T;Ijd zc9N6pT?eD#vHQ*{_P%GfsNHZ@+PK--8;~5%B0UOuf6Byi8(fL2a1m+v;Di-3P$DC& z3@i?D>IZQdG$OEQ0a@CYHx7{XM}`50l@^8Q8?J*E@W~a&+Dzi6405DWLPPpc*?q)(h@ft35%G^oF# z5!VCC5#s3fc+$vVd!iHuwQ&Z3!S<0PW5vT?>h)ykOA2$MHwF8Mc%<^-Lnai>d<8Y@epXO$X2G# zPoBSMLYS$klomQzKYSMC+WSbHuLt5A!W|e7JQc(+!of#fNj{8v;j9KJT0dsq{d&BU z=$CgI_SiWlm^FfM5Ik^Y$H%}_NLG^a=doHgMmC%aIZiAkJEs!&0e}qLw{v2J060^a z;V-2tpvz;3b#+XJt+}iRr()r)2hsx*AQ$Abv}KU()g}l^z}QiyvpjfUwV5nSBK`Zx z*&i;kn7p@+`yAp>zxd-hYf7r?<+=Wk3*iOVm=esS;_hT;pLS88g05JR-nPx;Xz@;H_L`1Qo1C8f} zxvjIkW?^8|_)+x759fuG43chEvpOe6oB-*klkN{d*G_$4#{P4Hzt2KDexfXKG6RDQ z>69c8EATck%xgesYom@&O-Vcg9$GijA!W^Lq>0yWt|`~$N3Fe@0DEjA?9mSmfJXU# z3~va<&oF@Cr;JPWB3cBuL41(Y4+2324{8M7GXj`bHHE>HGz`u%Zd6&Qq8myRN_w`G zzp}T%m6il)U-Vr+_XSiiVfHIqU>4V0K&C{0<$dhT@c$wU3#+eU5X>^Cj2LQRn1Vk> ze&n}4tH$K)XK^qS0>H9Wp_lai*}Q7&@2nPH%6dXMoW{SR%V8*n<}U16fFpJZ9PxAD z&Gq}t$PyF$*u5Zl`q;$K5CdwUb18F3wTi}(kQUfIc`7c(wSPx}4AJ`*uHcm*yad`P zIOp}4ii7rYxYf4MifL~c3W^0z*5K2LfM+f%57oOtF8dA~gfOXVpRR%eLcjanPNikt z_H&`8z6&0RWj5dx06H6D6X2sMI|+ud&!)mhQ{g7~D5e5-g_s1^fV?@t_Pg_+atF^u zOPp`PoaP$R{_Rw}{Jc?dR-+ma=wg3Xt5-TyKMwO z1p)S=Dde1}keULb`<1b30a|=h7zp5_4jK#zsn~uK1`epK0|1Eejbdd?ZG@Fhx-K~O z9aG(BxvHG&hOJ^r@dr5K@wbHQ8I8Y2B;$;iw~!b;86x6W<`t9G==pffB&PSC%h%i{ zjD?sK@PGogavZOl;1t%EXH>_MsWj)eh@C9N6c222=!aXG(09r6o?frf#d~iLHV!`4 z_PF(87-ZA$?yiY9XomYy1`tX9dY&vPA)#kn>Gzmsijw>F*mm5ZmxxRt{oA9sd%Wis z32BCl<0^!sEP6@&$E=72JFCr>JZ#U1hLYl`$}Id4LtEw$2p~kT0bCt_1OWaUWBf4i zDg5e$VimEyn*CT9yw4y&4S-6_QdYu5)yWP@Tvm`9h#qwVzrH@>eKjg7UmEsgH^4!x zs6(ZD;k*Y)%!f?CdUM>kUw_;fN##PrAUvM%!H#{{f%V#yfVczR=iWOv8I^#O$?h9{ za7jvx4S|zk1~llKwBunUP9~4y2pHXPNjS8%1N--`{&85lxdXEm%H|EDg1od4ngXF-5`(a0*^z`Ve5w39bZ*cEE!tZ;b8 z3X@y~ovVaAEkFF_a;X@t9eISUHVHUNEwe4aMtKz8ym?coTT7$>FsB8NU6V=)#NEHZ z{QF@A4YUj}4w`g|Od-lfkn2swyfUJpARQm;wM2YYD6!_~qq77*3$jwUDc-^m`C!1f zhL#rFR4JMs2C#|CP*;e-AGLkQI~@L?y}N65Z`4q8xBcOgx#@&fpiijcE?^dvjAcRR zyi0ZuT+lDu%ptFtfG5X?WY5jbW@H9AO`{2BUH2#tYq3U+(ks$H_-V-4FX-;a3*Z*z zHK@aE<}>xs%`8XC+?2+TeMpB|cel6q)}FlokpWk0j6*;r5~5D`4he`7OM}pr4u(50 z0Fc$d_)@&r!whH+Kp$h6!(cex;cXxtW_Ei*2Z%^tL?7UlO-hu^u@6bXsI!8=k^rvC zVQ^f|3Ka0JtOyNDGUQfu%`5j=wFk9<)qUCEkcHa!*%!=l(a=U&3$hLRk_W+0K)7#c z=%3>R$S}d`*hx|i$39@7Utej=f6ua&GZ6r((~%2~C(9*6>XKt&$GE|u8U1Dr00Rcj zj=1jm2AV)PFXJx(e{btO9)rri->X`C6B_vbWb^?iy1&E%oag`}E-C;4_@+DHq{Sgj z9=RcogQV~;;X&eiK?gJFGMMxo@JdpSX|LN-1(|6o*s+j%?`DX@kCA|O;5(HIXtls8 zE;!Ku8UQXE1I!+z6aqpA2o?k{M2A>oTvsX-#sXnx(ht6e;~x^SJR1QsAV$F8{{Z5> zdkw6@VcuE$&Qg&Zg#N@IG6RZPj z@0wbR1&lK}+lS2`M}OChz3V->IPtKl$k36mC)T5QQehzpcC0 z#33$%JtTn1Yb+MAfpL_KGQSP_i3#xi2*Ib0MJX=}*VGy^Oi|wgk{z(OBC<<%U(Re> zI%je=ggl216mHkVzESmVF6d}D%$hg?YV!iWp@NbC37u#{$7Aa$0uew-KV&ib3;csq zDE{^ywSb4(h}rk{9`CR5@W%#Brato)NX`;jS0qA+d{5RCa;la1iMSC?eGCVrL5>^o zUXP2NJCJtpL|?-oKn;A%!QY)7FPE_;;^0T-S5eBC32gu@YRN28?L1LcFoJ@sR-}OD zJf>u59Zf5xwJ zqB_hn8-ek=5l&5j!=M9vw-UW9Ss1Ev@cCWq&tRLd!m!kcE&xnyAb|aKH6(?Dsm*{+ zAn6)NH=GFqgB04G!D+!uS_j?jW;uUL!7mEJQWC=Ckttvd5iJi(BcB<8gCdZ=kWh?7 zKiuhJBwK)k8^qNxzr(;yw}UVOW^>cy0Re!w)4k{yJsSUF%!Y>7_k0qAYOz=`8s>tv zUM4E&&;gRd!zumfI*|O&(_aLDUEv3!0B0!wdtz8*#_O>x1i|~0#>!v=BfC4s?bLfM>u|PrsNzi~grF7MqEu+;} zVKJK0hOO9~0GzK;DR{}~8iwIxniD(^XbB#WorP_g&9wX?8=uW?o%}GqAEDiVuutjI zTBGSo8NSQ-RKc=2O_+m^zc!42Ee{|5tX}k=VFiBpG=uC@=w7yU?4u}pjg4>j*50o% z@!*hg2v7*}J$9vo9ueJ(-4|HKWSF%zD+BH!HG-Hw5+l3`KC#H>y|4t64|u{bKzTuy zHcbDAEa)$*Oy(99FeVP9^TWbV#|+}C9Qv#WWM$&dEJ;6c3S^8ksf9^f_-g0?iNOc6 z-VLm)rGfyB|FA#=@!qph18wsl6q1kEd+gy!sG0&j7v}!tV@nE5roZka6wvEGqC3Rz zf6*z7&&}D{F!(=gB_`@wK$bvogzt|G&ZSk+tAnenZNGb5iKgIyfI$ayB~}BU@j^Iv z0jnK2s9>TUF8$Ei@3wh=FDMb=w)sJVYwlv~1rZEd`;ou$V3>e^9*r7S+)x0gx$j`6 zwX3VOi{oD-#za#Q*w7L1P4*xr#QchEKu&-`%!gqwo&||=$Ds~ATZzhO^MzPXNTqVh z@Mhd`<5XLE=uCHL%w@A_t6a#+cg=Ibih~PgZXlNSfMY)DU1zda2E3cYwXYbDCl46su4DYG}Onfi!FXm_KKz z`g?H`v8PM~v`l=qgKY2Zaqm53>gGc~VR2sB-K^7T@IzAgsAmavwI0AC{ z)!lU66@fy*o7#Lu|K5LmYVn;6NvLyPdOn#VL%O>qoVG=meh-B}+bn1|z+~<1KJp20 zkb;dX|w`!bA9U6=3i{)UD??>q_V0Ra*o+f@;C#ky6aRo5=GPYhe1)? zD2v}1j}Ib*6KOk+p_z8VCB!;4(ke8Z+^sM&t8=GQO2CJ_0|NRC0v{RxD(fX!ey#SG zcfUQnB8IIg^Ip!79%A3x;g4$f;Qot+m$6uEhBK3#La+7^`UmXXVCE_JU}nDbnDLD^ zVRQnI?`~}999ZV~r%e)JFtbh|KuWSy3`B#4@k@~>8?ZML{96A+%9c7d7p9*Y(8UvA*R7yfRLLQ4a~80g1w3;vh@$ke~+2~M5=wD)>H$n??l zbV39x@6T?AejH>2rgef$CslCjMW1vHOu~Gew!@v8|11$Y@qz?H+!?9?ub3F-4&hHP z!v)X<(Wi0n_ak8RdN>Z=4m>fFqumD_X1@!*^^yYS;AiZ}DPf>jf{5VYsK=dmMkQ}L z{_)LJL9oA#ulzscDjMMs_$vVr4iG!`nPN{FSlM*vWf=a%iBxtf;lk$~=t1)ru{B`d z7CmuqD$>d{g#z-wA!dU9L z0WliZSEM-l;U5r=)lVIBF94A4UXw)=11%p54_M(yG2}x%2pt;>4A*Nmnpcw<#;j&< zwZyLtnVxpi(P32lLUzN9)gOlQ5){ISXK6OA>O*2cAlx0~e}!q<&`FUD*so)SaxE0` zS^7Z>GyfK7E0GP@JA)U7duy#q$HBLQR!+*sGd1?Y@qu8~LJ&T03Ho-P`ULnCt#J2V z+%vQ9p$TF<{QyH7p^z~zYd!z2kMC};k^cSh#~*=k8Vr$ay2jHU3X%4V8de}`51k_T zxsdl!5d#;nmSHx4kO1!JAmr^@2f9b$OHj9DOC`RpRF)%{@Mr44a%pIzOk^vYmQOdo zvSnh~K@T-Ye~_&W@ZnL8T9XEW-Gst9iJ$LxA0?D97~sjc3%dePyD#U!RZjwR z^5b+vum|ENvCv@@ymIA^q2Qf67J-_epLN28$L}`aXazAni~#UL5I~b1Hu0ae{`wGT zNvN?CNp+ba5`Wp7K$c@57EuqeR|Gh_24)WqPFG}xjC_oN|Hskl_3PuX^m2BSkt3@~ zP}88MG~0vuLd1x_=cRE8sjHuFVX2KIB!5eLE&wp+(W;?hM8At7Um$>SO^gkG*$^IR zutq729sm3V>p|MRAx<^x#Fz@x^W~Hib(>eT!2=Nrl#yp1 zmUasRt8C$0MZo|hlrq!7ac2g@EfLd_zYqm0uqFZqvuuS6VF#A~BGsQ>?@1WACWSM3 z4Skl8s862g2FNGYdngl?#t@wj;Sb?Fh}eU*wcU-~^^J8q09poI?-B)pGH{fmYeUN{!wWw9^wZB63}`)= z4uF~uC!_-O+TRtGVCsUnqTEvt0Q6tf0Z`b-Nzf)fnv3-%?nHJQh&&*cg=%A9XbQ%- z>Q}-=8RM`8^X(g!im++`s69BiXY2}SrRXdO;r)+hIA)>hZa0@wLMtFO!9q_t73_s! z@xC$zO%8M4*JU39xd~4i1Rl+WyI&FtJr}HSgTG6IX-neq6FS(=fp;!D0D2U3XahMv zf9mo3BjD}mcuPZ~jVN5ABM?KKZas99(}0Z<=#fWeCNt_9X_=o!Yz4kKgJt5=F0#G8aYTc`!w zLi)Q4DofIBud-0D7cjDpsy`E7i|_{IMN2B(S*yq#ZQ+O*{wh$zG~;g>|AU$YaI5eJ z(;puhwf))%xV~+7K;@vSCP@u&YqshhuJ6h*j8cyufqFl3?jsfQBj05`rqc1B7%Otv zLBQPGTL%D=6Y0Sq37}*0{S(eZ=I3(>kO31Bs}Hg&={UaVGHHincZbNw_~809X2~0FL8e3B?~@Dh7H*w?5C*;>4&A zGCW4>uadIBk4z{7&>s-zFac|&WJy>d!N2HjcBN8!J)U*$gBcJ)L)hX*)^!zh1bn<6 z!x0wOnTf@G)DcU=w>;>%BQ3w(@g|rOLU&u%ftX+a1obmVmIC7~AsGKO4^mk;X9!3x zWbpK3HMC={uCA^oLYOf3wZ(d1&xJ89^c|o7F1s&y)1#ozyD?b%ua(0k3vlR3mm$Pn zTSnmRfCZ zR4Nez1*Q0>n#+Jul?#NOaS;IH0O*V4*;ehmNszQ+Wo%l+jOkxQ_lI0+m=incm&25V zV1zn>v>lQeYv)k*awU*py| z;F@EWD}!05OoZ^w;=DVJe_Fn!4_W zz%mM5DDqoSI5bs0YC6Z)HN*P>oIV4a zV{*d$LNX!D3lt$N`O6ZiVl#=&Dg}YfNVWs>Wl;)}D#d^nu~Our%{E~MAdubA8a%-i z19Pnrx4xif12fpoW%QuU7Jr zKvCnLBA_`GmSQ+pk*WP<(bE9A4J`2E#f?-hLTT1@j%n)G$wl>W#QBR|c~ z=tY^Sa^Nd5Age8Gzu^X`DUhaM>R@yXi~tzNKL^05h?x&m$b}FM?F6u^pqC8>g?!?G zFK~7<3tU&wzW7xze5}jBFiM{-{nYA^bO{s&HsUeRcVQ=j8!`pc5@+H-CBam(7XH!@ z5t6mIK*P$=Fw9Y~;rJEwevO?Z03XPhcdb7p!a0M1xy){Gqj^(Cx&`{`XS z`bTARv#h)oMm7U=7K{<*(U6lOsSP#7jhaeOVipDVje5AgsNV%MukoU%SZVCX%+=zj zfA~RCohIPlFip(XRabjZr$Sm`teHGBrRmCJF9;A2b0Wzg;9ST4B39+`g?g=#r~#KHG(!GwU%SX*O8 z0u6JAhu?81e82YNd%mQ!PZ6nh|Kr2^kT$&VcgZ?H*n}h@AoaneVh>XP${S3>Vk@Qq z(48OvK-hz|MwSFmeA6Vzgr>3>4XFJ3h+LTeu$m&nZ;0{tqt`6*z_?u1$0;^Hq(Oht zcVdChvcHidkz`O4p|mbzp+AHRFqG62Y9b*fPACI)f<9n2#aT-`c;zu0^{mCSEDet| z(Is)evl0gi?)2WG2L(zRok~Lp0B92+z)uq(X27}VTcdGfGBxo{&OIKnw1lJXIVt@j z>>=#nls(uzA>Gjz>{)mZf^YYfyD zEC8Ib=}#Z9{nre=ULib+y81OPViie?e_O!f<_G4oQk6sRS8 zh)sslOOqez|Ag^Zg1cIV)(9@b7K@6HusRsC9|NwWnXU^s=;@H77a@KNlAO@g0jmZ= z134O=JD2~cci`Hnvi}5vATso7AXFm_c#V=(A~E;*k~D-&d6CuyjUfQ%9B05+uSNxb z5YP0sHi1B9?GkqOLV>lOqIsW+>&_0H%AO}H#-kibMWZD7DyWZT~QB1yf4_tJFhy?aX zgzmrtI{^}z;1NFIw+W&6$vH5XLHzXRgWnYk$dVgQ2zbf?2j!oa#03J_Q&Hz*IZ`|Y z-cA6}-5<$Y@&1=QLJFY2K284;2oDZYWpD=}Aj{ca!#yp+SxKV9_G?7Qj3NvW>9?1OQfA5&uB{b3Z0o zqF=LFdyVV{$}&S540?u}G$XicSblRmMr7e{yOYAWoCZntV#XU+7dki) zh(k04`gFK4UUFFEZqW(H)9$g&<}#>_z1~>2?cVhB~y+N z!^JZ}2a}ZQ3SU`n<9)!?PO}g_R!QbYI2aRmN zHGw0wDm%eioJ~Sesrk!glNH##9v&meRk*Mv_BUrP6Ws$@ik49|NI3X~6JV23!%a#; zwNEv0tGoqAQS9g}H@~lpF}b~L z4*3WrAKGDsfF^AQqSe6jGB!)oUJJQlnSIs$%kHF0DnXLug_|&`UM5;eC_`lZVS&pp zUyRbKLLDE2R_pYbDEy$4ns0&`dEJEyZ=l)i*_pGg@Vij=Cw+8tv&&1PlCr8^^j1WnMA*%7U-9eHDf%+UCHQ2uJN8!Fxz4 zpE19Jy`KO0Si%?Y0wFzuSFBLNue!(QHCCx>E_|Ze51C{kh9Lp61j>Wp=YjZ01zck6 z3%5wAO@uQgZonm1KpPC&GsQCe7{F|7==!y5w=4ud=3#OAyKWT8bsGqgkTn#T4oixu zR;~AqhL01a%v22kzg!6o=!8lT9-8+Ab7gz3Dyq6W8HEy(uTBWvN-E$ z2BZQ-5}OQK<^U@S$O7147A#OF46O(!Uv?yCD@b={MxcTddYKXk5cHw$(j{+q8`XmQ zAm86h035Ygdyl&3JrK|b&oFjm>G@<=(=kwhxWHh*(E+&DhF{@N=RI$@If~3?asv)} zYt~j>BJz4u-Kg#PS)IUH(AWN9Dfp&l8SbVx)14BiQ$SeuvqwF?1*8JOgUodVC#+gw#_p;*)l_R^IuT}e(tkiN(b7i-}zeDxO;0RDBR^-)j-rZ0mH z*Fk$Kg0OEUST&A+eYc}*)5dYb!%c~I_Oc&lEy>0$0sCQk>C~ z(JqLkI0P*41MHS{9sI}&9B+~Ormq8Z4F7DO^eP5{jIcId7(>Wm`~&!REzcHUKk!}Z zeSkcJ{``O>DQfmmL=0YDx^@lqnAVV~+Kyq&fSMXH$~EaD2n&<|rU@s&1qSC=)PKyh z>AXT*0nY^`@8eG-8yuZ>K+7hzuq#?$Nq>ryQR+0lffiP`TaZq6#_~`zOok!y7cl>^ z7!GUj&&UHjRN6hz3h;+$7=u3(#Hbwey?|_&xiE}HV5VQs$N%d`Y5#iGVDJFx!OHZG z5P{_d=*&dm&ydP*LkNeFk8v?Yf*(C`5cqY-AHpM`08cN0fxtFLKp*=`=D-l%mF@kK zP|GL7@=4zx&oK_4P>JW%dorXNbQ8#oF%ZVJ zFD1RDWd15&5fBxD5QFilXVemJ1;O5z{!P&`0?qITHe_`qJl2z%;1nU^P^dllvFH#j z!2W|%pb^E%MX-B%PItm1%RcQE`77d=)UR*B<_7U;FAjl&2@}leux-$qF$Yuaz;O+} z5*)#aB}B2Po2Sfhmrv8be*EJDgP%2o2m-%~rN2`GKx+eb4g>(m9~UGEyr}Lt4+T`> zL6?QZI33~&LAl}Z`r=oA+5C-yb^PTvp-rVL5i`Ow_-GxGTE@=8XEN_~NU{&L=rt{wh%bgHKW5TgSib zcD8Y}bG#!PnrXELxv(tj%BTI8|MX|z_L!;9^k>>*`LGUZnudV7iu-y>@FRMVvF%i| zT)plQ(GG;Ym*nsG$H28q*K`e3&70&d3?rqpEpHyVfdx%>0KH3)wbZEstUVwT(|WeI zAA)G{z!r(Xvtg3}@D-$hj4)uDb(4h5ok~97O_RI~q5};8iL!TJfi)g(qGTFqUTIhL z`9jmeD|`#gmgeOUqL_B@;TQnl@UH>C%+?MhK!wWF!WJM9*)Ud%xx2foDAetH>l6es z1)2c3t5y)k<-cV#s#Rt3vVhac0oHv93Ki8qV4Y2NsOK>VcKc%` zaA`v8ux7q7O?qRz0aC!IC0O$xz_B=1Dg`_oFM2{WX1`Tnpz6>^e%FnpMR<}`NSpv4 zYYLow)m@V%RkT*IPKHmQK}+6T?P`@;6azbtQst?svdatUp;YQ z1D5>xN+JXF$DPZe7v0`CANF5@-=O{1N+f0yKKqsSxO0UcYY06MU>2pvYZ?z2vk2 z6aM(M61P;M_AjlGcI|VBfZp*U;GC6+SlydNykvtHB-Eh?z~iE)4oeJv&VDq}`JwDT zPlP7np_o+pe@!HK7QZUbc?#KA!?{8Z+LPHaBjh_)@PjF_x2UJX$xcgcjg~r70TTTP zfaH3mcoF3h=n(C}Oj%HxGXn_*Oz+Hu0@A+2XFutu1p5KoljuEW2){*_j?x~tpf~T{ zMR)<4w5~rKa8GWavWxB@Kf-$emn2cl|m^kTSup8~{+_zgt7T2Zx%ta%u=P z&iIyQL8}eHK#2Ko#qNJ{15Yp!+B|S}l;l9Fo1eWdZKxM+Y^7xVa8kn96gc+Hn8#%) z`EWKA0#Fxo~~{=%50;d^sJAKW}E>IQngFrqs{# z@%6j~zE}q8?~2eh0#2Fu`GNtUA)!r*%fS&6>5gC#Hen!8@#4khsXu&4_x3-({_W&k zhE7_k09_p@Qoi^IY{RD}pD)`0`ZvDb5YoKGg(ho?fNhSCt(&l&E5afK?02H=aZ> z&lVa3vCT?J0n!*8$CwQbA^@11{ml20rRXwo>x0VHYXv7=~ifH_S!UU)&eOrZt z0B|Mz+%$lT;)CR0eV(!xm%fTCDN%>2<7Szv=dy-JEfVm5wUew_iiV?7{AL;9wRU*_EpLb1y!9GrJA zNNhg`09x;n7r;sUY{+*(TQEO=`$7=G_#*3?zc2-QTp&iusn7ey{`ob2;Bj)U4mbd` zF(rRFgk>eMFmWX0Q0OcM@aq^onLD-vi_c&Xv~GXEz+6M{$Di|vKU3M$jYa^#N@@&L zbe3C)qa)7N-<)=5BQz?e0JLql)zL0cAc8Ne!BkOtr2-@){?*L}Ow_B?-3}-1U#5~Z zCIqt)8bdfoGEOTal2>ydCO=qt<+JT&@}E2x50n(`s5T(&H z7T#JATVWk=Y7WjnXzpd$b&aJUoHc=eKXCShoCbgXEM`Rh4wQ^nK$hemGC{C8&*`wU z0JZ~B_?-{mQ1^lqRHSNy1o`=AS>e$9`-?5X->vcJcN6p7%|%3HaR7u0W=%rD_1%~2 zMf~IJ=-Fm5$jy5SlIBm4`B!#drk}1!_Q(G7j&UU8k4q3O8{O{i`q4M)ne z-DwdGh3)l_B?wZ3+G)iZ68WCu1#2dOeU!7**qKy|mB6sLF)c>%&v5u&BM1)A{07_u zse${QEx$@hP+g|F3b3y^=P1i}1PGX+M4hXvqY z9>8Z2Fp9#$JM2fwfav{Ym+j|k-;wxWIN;T*FIkR```?;$fx9Gl*VlKg7+C)>@7+{< zmX3U!11S#dv8+I7q&GI!_K0|Uw*CSH*O7j;F}AUR%@`QCv{6D=CMwd43^yq6QT|fi zcw7GGiJ@Ovh=<5Mg&&mJmMM|3w*uoVSkmUJfo!8}g_c-=uV3>vUvs>bl>$huwC%+5 zxw$2-%=4hS;N1JM;?0*K9;Oe$`eRH=U~aWfT>HA3-=PJC1;lkOd{A@H$B1zHZm zQ4B<#OqGEISBP`KlS;#yR5ggoMdl{06=c#95k{g5Sa&}eKvq}NM!2?9KHxLq{iGV$ zXb{6bi$tAIOu#A4U$P0$hwOuJ_M5W$w<%*m1bJ)&;SYU!IVfC04bo}w16W>MHdEZ4 zDRVFG>DwL?gq{|0On%jueRkNajv(w zheUiPe|jV!SKEr?qH)8#4TAKPxUW+A_1GUsTQCb94}+vOkbbZ5XN!H|P>0kPg{(lb zGHQ!3*I+dUvnSZT5U|IfXym_G#~V`%&|Ha+dbBBnVu*SAm8_snGg=r~`R5b*W#kXm zVvCRiRL8X}sQQw$MW&_F+@dU-1;*IaGzD{n#PoyZPx(Jg1`99%&>X--I_mup5eNX}2FxTtLYzYWdhXFI zeE8x8XFz!8K#A-zCE-wNzYgUAGAM9w0|W^G6FD#pMdbl-9Fvd$P&YuK;>I}huYCSf zJbtxBp6$mQ8wP+jkjWc@>hhuM>;yL7MwKxy(n=%8s%lq0 zGlx)AV}oIzKJQKuawjK>ged{|@R=3;0wpUSDH^K!?^k6j6V=(pV#qxRZ>?AsLNP$% zSaHmSFtgDX%$KFvUI~=qW znC|Js6l~GZrhv9M=#aBuTdmr=?D}f;mtVft z`1khhKeYvaeNKzujHTl9{1;7xSk?m<6BvoZ`Yuv(rqWr!`q z`B;pO#1~7iZf3W~LS^8t4U$q(ciIfBh9@}XF!d?_Kq>j1a*W^?rOBC#HK4b}72)bd zuQ33I%!krYw-ks906aW=LBMY_h$hh5D=ZjGW@y&#dENDcr3CjsbrDW$-@FsV?`!OVU2(B_-8_xVvI)^ zS8*_2q*O43zd1awj)a!XU{q66oYiICe|$f*UwU6ssEpHI>`QWN&P?2MMtO0EIw$zti7V!LZN!oY-B0If!~f8fevDuISVDeqma_ZNH5Cvj?L6Iyw7|(wN~a zNCuGvz5N5yxAZjT*iTprDeDCtm zwX_)c6__q7ck`P!oe#x*Xa+ofv$K=I;(BtmDiFmatXWJJ zT_P{296VIP?^>w6JnUdvDgbefIjG<{RCOKzaARY3V^_eY-~)=FJ2(lk1w>Qc(mr?K zjjuP}4)M!<4UVX@@2|ZBDX66VC8pNLRYYnq$1(nZYb^j$ zsR`u(e{jk5QTT!qr4>a;uZRwjIy&ZGc^p3FFIDrXluEI!lVPYXhZYY^RiN=7qJzC1 znD5=V;Vp6Fib%kZjvlKUwFP)YE$NGtNaJblag+-_z8^gxXvZD zYEMrkM>_zH%mpX#h^@hK6IKF(m!zMT!Gs7b&4ZUc{J=)QGocAM)sw#INzj|~rzzm` z2{~dy=r{t(=mA}f;T{lBHJ5-xpxdLMe@Ovg90Y}y_I{)Bmy-?RpElsP#)MpdARMtU z1Zzq1nm8*+XIgZKMPMWhCo~wSX)`PbTRwZZWeDEb%RXVsplel+Qa%}g}bHMQ#jO^g5#9q0l;+B{T>i7%>UYL*;W z>r}`oSlAj3ZF%{G^HvEm+RIrF7^u2SmHrMG?`!o&qkJQ;NIx~o;S27n2ZR9#3k&s( zta?0CvN$f&EcG7OVB+P1R$#^C3;LSxaxxqkwUZydL;r6xUZ~jEG*NS&khb zasX2`z3rkvTnO3z!78K}ZQ&))yUPWbWG_+?;DWRM-%urlcgp)B zKsfOk`%w)~ghG6Dh~t`UY+lQzQBmk8F83ewfwMc z@E$5piU9y|3Zyj#05}@~kXY!5_jvMgcuV=HlO~V3X*4kcqmyU^7sUwpp!_ocyzd2Z z=|UxM7!LdgaF0qD@*uPWy9anRWdcqD0WAY2)?*6euB5wwH|LXv;7xxs6@{-iVf#1* zi>3$+ZeM%YFvza+NB*#bU`#v}04{f>`458SBfAVf>gsm@B>HIxyfyS7L_}HcL08@S zd$U;^2;qurxOG=B$WJn>08B70dyT32`748MRFXfpvG1tu^6f_r^ay|W@csASf56Lw z?q}ebE(FRXYks+uI(obUzrU_$OV=5Lk(5;VJyIN;x{+(&9i!x9&zWyl6 z$CvcQLJ&0VY>DLkS`9qrHv0DkEP;31JYUU^jixDdbaqQH$<;m}b>* z&c-EUb(p+`F|*mrM(_*4&erVPFO6<@Uk%ha-PQ_7v2JSBrH@0NGXC^dUK+^^;lCMf z65I>9Fasw=20{0e2H{jTv=hJveiu>zDCjdBG@{1nhVnPY*YQYL z%bXinu)0d=T@WT)^0i~F;<7t{WU@35|pmd=L~GC$PE93&TnXXK87d9_+| z#XHcw`AuUVCqBM;*IPdnNVwqPUrN-+dC_{}IxQ@Lzcv1@n=)zu#xLC5jD5Kd(GVjg zC>pBpZ#k1C3{nM20Nj!c2ErDo{%(r)!0VSf1Mco_Kpef^!Gd5K+F%F4a(qwWsC!l& zV*cSZ)_*+N3*I(zA_j%bm+=_<4H-c|_DTx9!~)$?2NM5S1-vqWQHa)G41{#qg5WUs zN7?%)vHcF&1qSW zP%7eb8XXoDuz<|L39|!Fluh(3{WE@f9V1Ub>x?lvt7PB?038D*5Wyshyilid*k z8L2flx9(VYG^vB&hzkMnnwP-Xj?O3;EyJ7(SKC7VOCp6vClcpB_99)0LYR45gNcCi zm(PbpR6F`@+WQuVI-kTs(+W(1^Mxs+fXNDfjt4hiJX54)&cmzyJOzeUtt~|X3g#+SvTul1|02&EW z2+XnZsbqioFPf9zuQc=GpSa>fIsCQfHOx`kLZX7pW54c(_$-=(c@J~|#1j?QeAMmJ zP$Jt%XL>;02J_9#y??-Co+4F8FSS@Cf>l*|V_O*99zu=>`ZX4J7@7_+Q#!9+5`8_} zlJFZrKx0jtEheC8Hnb!p!X(mM`TUcqnX}YPVoDXfG6#@RFnmeDbyJr1IVVK6I(wVj z3vPVL3@jkm5QK2&4*t8q;4yigDGJQ+khe|zBLKd9u_5>q7lO!w9^-)b4qX(jW8fa~ zuY(IPC%^HJJD7j9r-L8>aa<8ugup#3`yc{B?W{u}+Te=X4%LA^J{xg@=>c4lH@+sn zfr}q(AFc=t7r!AN0v#7OPVC((8Q^mHAD1p&zsCEXzDf|b5B7t%y}mCz7T*9cV4pGp zs}p4_3l42aJO~bXYT%e6@R5RLfd}RZNn)_7(nqiG&}a2_J=ZrzfxVo|zuFpsqYk1!wAra_K+kJXoSRi#PYNpGC4ebY_= zdnSS#rJXcd{h39AX%X22u? zA<@Llr-d-;0ls)@2^RPP%*cd%Zajzv!4UK!j0?1FSK^3sN3e?l`Qk)0F!oZk`c5X21Fh(TE{f;L9Daj<+aHGlpx{t~$Gisl9Barxr%fyO?^ybodc`#yl+ zyS8V~yPvmpQB0ky#DcdCJU@s)4KNILTCrhB`NvNfLQonbcW0*KiWz%CDzF) zy9!I-@vkm&L5x8`LK!3n$ScR9^UepRaRC4l!#dktOfw^ca9!1J{Z4+gV+v$b9P8B) zkzXGjT_Ak5P$@{MOh%>*ks~cCt9&rZaD$dnoBR9)LjlETK#RgVpar9X)!_b%ucT8= z0BGxOvoLR=CBaU7VsxQ-Kx3rB2qo;EIm;0he-rhL70`7u3!il#olF;OZEfIxSJE(M zprZybhe#~MSmW2Qz(6a9YgR!fnGm$X3Ei;K5&(Yz1Y-G>J$RiBA?rQ&4%aLo`n@iH zRuux>A24u_u?QVSPJxm^_sn+me7r^g>|r*v5g@yeyI|{G9On>Nsw(ggD=(_Ui#9lo z&01=dY!kZd0RZ898w$n?Cp>P2#>zlQRGH->nie$2{-uB1x_+I&Ca~idRP8kbqi^xJ zH#8xMv(0}KeP8?;_TLHR1sW54qUH}f3Tig&BLE`v8N^5*l`q0SQzGhHQYeg6f`ms7 zf6&H!Ge-RL?Y`_nm>_~F7L$IYzyt#VweUVxEZ{h8)Ez7f_86=Y565RjG&+Ju)RbZ4ajs*!tj+M^&Kp!{~H-eS}}S5lNN^WiuWCK;L{M8B%-F$@XvTC zY7oP?`cD9e_s%Q#AVgxFPb!gayA$NLVW6j?x(|3txmQ5G&utH$dgLlUJX;{XMgI8+ zxEyh>%jU!bFGv4^K9IM3vP~E}@byfs%akx;K)M>i3gSJQ4QZQ~Z*Q8mubUI!bF#c= zE}vhKBf@9r7^?t1jg zA;d7-jDhyL^!HvDY%zf>iQ6XdG4=o;$gIDQk&1R#1jiThfMOI;! zWP`B7m{RX&y*R^?1IC1BT0o0&^b0(2YUhoTyrDA9a2(;T{p0!<*QN2BP$D$HuB3W5 zocNe$H9`ItPksM}LZm*K<;vD6tfe<`iQHoTvsBV!D-&)8R&Kr`^Gl^jeBkxUm>Yiy zb7P9{ry(R11DE-uIIW}OH@AOdo+9;+#s|0MzV;qR2%7zqKL{~!Ry)Mz^Z z8UO+U6EY+Qp-$5Ud^BxkAj-(Uk1Lk9qbpqB8!?ky1RMWW-3ZcVy6C|a84}wuue8N1 ztW(8EsZeNa!*=IO^#U6Q;upaAQ_^VbL8k=9@~!}WpK}Hz08ViYHj8gO0D2OBS62){ zI28hoH~LSs{=SW?FrI4tGp$kr3IXxO1lLCgP8~N6F3!)NaiW932c~1NZS(eWgG|Q< zUv&LB8T--*_+gnp_2^>58s8kf)R(S7P%dF_RJXY=>kz2okeM*`#W0vAi^s2I83LG# z`b5LNw_MIDwLjJ16Gl6O>M&boVMJ8 zA);h5It*r7gkLN@g7>YHtF&#cderjgtni%EAJ8aov)?OfnJpa5^tdz&zCaC!a8O;HNwP`80#XKRoSjTi(H;wqJ{ZQ9?c!;#igG6W|{E-o*N9 z;$uycasbzR*oUO?@5$j4wS4gEN7iF@oK85pXo+-)g+~7+QI8NwW$;Qd?2mZ%%ohUS zlEEKTGSKo3?JLqWo(HS4=xT2J$LO_xT)S=xKbHc60vW>SH>5gq5FmYDq5=+mn9#dW z8gt9~GOL01z`E?JXmxIqBMH+TJ#rJ4P0d(@s_C93i7r_j^okf@q9y*QTy+6;8)AU* zX}b^FMUa0Li%}I#gRmg*1`}bl{=!mC1RP%{021~dD=tR(XWYm7RRJJl62c6q3EH4Ei`l%jnHOT{XU37wjmpvES zIbhrZy%N|k@N#BX7}`FjtO3cx{M2e0vQH(9KKLC1E-#<` zWcL@Xz@$K&4ms&PYhvgwUKTw&P&xWtVeG>SE3O0Pj?0_38*%0R@F6wvaRLmG_&Wr= zO(JA&`B)T)ayy+0_Kx*PgLpJ5l^Ji|*kRCFkV=w;kdweqRl(v)__K(6ZtBoYG5Fme z^rqprCK8tbc-AO`vo#q$#)uUvme6m!C%neAuNN6hO9}RYjb5GPl{Rh#CBB&%t-0f$=pAc^}VhIs{(Q$Aa;|DliNLe`J zu?dO2z)ZYfXEOfB){;&)2;q;FzZP;|gyCzPNl}CXZGc7KA}k+Pfk|L=83`P4E23Si zA#4EmzlUHKWU-8A|we$xRRnn4E^|e(-~lk!kQ25z~?<8`u6Qe z3*Sy9qQ*S@po8((u>;tPkd`9_9IAhp4-Wp77N(=5tJjn;#)5Da{^uAdPauK-&@&Yt zEno0!pVAUJ^%48dbL=zl3uyNtz3U1KKYaW8U8C!E*SD$9yl%r1{Jd=@+vMjz4S*J; zm7}oG+tvM%^*f+<#o3S-WiB&0YkAwM=xBeua~vP|Wi%V&%aj2Fc7y<+eh(y0wbvLZ zbygwJB0@64GAxp;<6wkLjfOI0>}Avi2X3TB^drGR(xhhG3B=F1_vLxOYZ;1z`d6OY5Qt%z`eXr=5-Ln4A|Mv+M@;LTXB9> z4g~%Z0EW!VuCrX-9L9VmSkhc4JO#RXYBv7ZHU7r};8&nF1{_I2QfY>v7R)fmR^Yw{I%F{Z`o_yck{wUP`m!2buX{8Mj*qhuWRD+I z1*TroGCRxQ19N;p^+y*7?P3x@)8$bOow`*m#q^q$v`zv(mS{u+0Pd5m*dN;W6}W8V zZr>QW+P*(tA4MMseI9D}u-F6b!N@m7VdfW~^%>=XFaE9Xw_Bc(FP!AgJ4E!`-w*kK zeXkNJbaTYcs1b-N#J`Iwf{=}hXcS;2u9^zJnM=;Y`}K= zvrdqa#VB{iDtt9sf~kI490^+J$r0)Qu2TN;I3(lWHw3(SL=ZG1+|jg$0UmJ`rZEm( z!1t%EB3N5+gujt+1x&J_wE?dNUtD;cmPN;Ggwu{-CgVEde)sO3^6K@K2)*ym zM4Q(PmC-=AnHi3JxZL5kSMRq7d@RK^R-m^F06EhQ50fIUQ3ps^1QLSZ;5`pW#AFzv zWnQL`j5g=d7R$c3ek1p^G2=epGD)!%dTTsZo zoh^1UY&L03v#y2BA}kpC!1#mF0W}sg0^-rxEG)bjN`+~i3)0sNTTv5tb9@gG_ddxZ@n_Wl2v_*d7LpL&&=>ON4JJUw-fzDZ)*WgNgdccuarfn} z4~6>BFFFC@UuAK9ZSOw_d*dDIf?L|-#>?CN$Kx9+3DHoh`zBgZNWC$aRpwf zDl1iSfJO?h2my;rfdVe#hw&iM9>>woSznVy+l$ba6uICL8xSAg$5C)y)8Avso(%w} z@9PS9vl}n2UUkmnIf1WR{g|wUn>PH@9;||Nhd+yfnTzvZw87B?H`o>t5Kx!$1}FWP z#)4=Cc1N%*!7&YMGqk}e4plkO7jGL7Uc4Rafnyb>yucTyrj}FlU%LBkIR${)jHk2+ zH-v#fCKI@kUL%6vzBM6?=D^9(* z?`h~mwzGj8>yDnV=!4`hbkS4^ZX^009|4+a2pm_qGj?KxLVHaxgHUOV!vKhJ5X!)! zIcq79F4I6kQWd~BYsWyG0QUhHF!lc0@lw!`#uDCe_ zi|;sBeyzquEWJ0riPqrRMehPx_l98Ge#83?fL@Ufz?h0Po{@iK9I)BpVkz9woaey|y70x~P~8#&1>mZ^o75v&K`_;T zrh>VA$L(-d14mo%`OTySDRRJGge1^&0gN(H74~dl2qp=%j*kF`#JjG9`RGz<@RW%H z4@?)hESe-3hClymgEQdU-QBlR!|<{3V5aq}uRwL+;AbHQe4bl{tK*p1XVaad-3Ld( z4x!4as(uCfwx<&BU6_^oBj9(Io%qoji~DbYSx5+{ApZ)@oJ_W_p-cY zxsWW*lN4q-I>s)+B9Tn)HfCP20>r=%ezk?sYo`8F=t17F=&pr2w**ySr@iJl2+_IGQnsTht}26+B3#34Qo6 zyzoQoSzP`KnJr7e*-|0;(}E!&)2?;)1D+mtKJ{QM0N_goqQd=#XTjg@wiMAXw%514 zB>k-+Be2lMl6&iW#6MO4n$QnAz@8p;02^Hbhp@GrFInGP@U5})V^4ZONCWu+od6La zFpeb|tr`{tQ}lLSgp`(fXxm@fw@jFQf>^0+ie-brp<7>&v;D&#KKtx5gcwZxnL?K_ zYFVr;Zpcg|>U!h5Jpb{>P%I3V2+$*>_lJ_ckUj%Gss+mvY9T50xiH595)1{)kU@j~ zEol{ADFrJ?7-_}(Quu7?2*`k*yE#*&mIW_5=HY~1VEF+$QR5q%*UPxO-b{d zQNEL$`!ob{1iUJo(*&qJn2T_CyarB(hG5IXq8DV)OF@hWiAe~jgn+3|q_!Jj0d`|Z zV1V)Z&K;2*<^tKA_iCj1s0eff^tq33h4t59FysLO+%8_U>2BG;Fyugo*{>_Swpi$c zV2o2%w3P=>E&p*$xVQV(9^7QU9@|(Ya6R)!8(bam^1gQP^QrIDgYUn7{f;V_0Dm98 zKR)^?4uH>p8hm$(2~cbpXqB3(>q z!Soo^kd0!h7S4F;_vLXO zKp^0W5Rj+8q#ndz@>b|l$E|RzPXVdYPBZ#oqV#2HC3u9ZVGu-ULXqc6=>RP`W(E9C z)r0Y&_;wA99RR=i2D@+(VnI&?3|hd@k^UI@(9#5^heLCPERKwXoCDRu-S74WOiX}; zzvrC)zS9`U8Iav@&z%i6;1d#tn#^u(!DNCdgEj|9H~<<1rT}p86!(#&Vueh6^8=r` zV-{fLL2qtaH^`={;O3(j*iV1AwfCM+a$uYVS)RHOs^2aK2IPXzgg`Xe-2xrr%W*0Y zW?2A;_$>S+{z9z)z}-Wm@wm&d==yKpJ^x!kKdin-#|h6H*^O}f)9Y_v!wYx*%G}ZU zpnlO;92ov_jsya>y-t(C7wH?BdxUZhi$Fa{-S;Z#emL8NlMkd=j$@}hc1%$SU0`cd zx(Qe*Fv2o09_@1W)-~i|PBM7o7Hd)XRJu@i*C}cP66hIGzyeJRQxF-;OaV-3{CK07O6aQz=hOQ1gZyE zaGX;nPu}z}&7%|(!arQ69>b=w}`bOWzpuDgYdAx?8~vNR@OZQ`mxWWMPY^ zK3P8mfV%x{5&5WoW-eCe!=FhBXUqcUDEI<;XpMv~X^AuXL%Qf~xv-F2x465$ySR(i z-*Qifsa#}_)8mO5e^qw`L}V(KFT8seaZio&E!%{x0CPjuw~Z3lV37ls^-|uT7KTX& z;5b%FT%XbZyDt^YL~I52d>8b=5dc5!qtKZ{7!hy7`+a@#3jjy~AnGnfYJA2$*QQ9K zVL5=GP!ZfRRL_*Y_&E?k`Q$(#J6tK3LM?idgTSc|GC-UAfOX|!*oMV>GY?gJFahuz zR>aMkA~0os!#mh_7Z-tni}J_a6abDyNi^Az2!L~s&ErdoW12*WJ-UH|&#wyfj!Xy5 zbvQJ{O}j@#y1;JBLI`STzD{H?Y6NL>EAXlX#CQnSnM4zP#`#|_hC9PjqyT{PmW>r_ zfP?V)cFaG(-aCK(b{hUJBqN}O0doFZwsm;QpTkv9cRn5gLnCnNQmEdfsf)Ki|7z@| z>0Bw~e~+iXzuz_h{OPBk@Ql~<--i3%hg0as2T0z7%U7h1AzEJe_WRU%@bGMTLHHnh zn$gH-Sub_*02DV<-p9BB?y}UsDBsrKkBjpL;bSuMzdjvfHfCL!6H7v*6usYKf5ok#Zd}gQ>x7HcW zfKav!v~1mF+a*ecFEI;sm^dvtGyEfr{9+v7SxJVP1b}K)#|n%x%?wBs_G2!vB>;qS zCj~EvfFS^8W}rIK`YQx{3Q`0B$N<25ggoB)2!p?<|ATO-TzpDo)(`p5aNJil1ir8n zxIw>zx)JgYFfCyUEG-Gw0AS!l zgBm(Izlhhq+)pD@Lfx!g;p7ec++?UTR{vOaY6abLfs4TW*tH+7=08`f|08}zU z)o*|0a+n6~_n^x|gon%@Wd^Gf0FjY3p(NC@1!8#=7GaJX@R$e=mLKy&OQz}xN^b?h zs2g3*kQ=jYv%>oM+2J+)f5&+|QSeq6P zt=aD@vwqBfg*U%K4ViraMYdaR zDrpdffhCzaT%S; zGT#b6K05Hjz$La9K|e?dp|bO>4f8?XkX7GVr}dXW?3`@|uR^uTUGCnn*RvB zootQISwj?>i_c;@_E{7U#C_q0IIO0Sg@uYmBVvG5>cJc801H_SfLTPMKKxlbFypXp zzP!nhD*@oH5~6p3fx-8t|AHdU0RK{P#KHo+&IEkw{RC`#0>F)3jC)Tw1a^qr;5#b4 zRO>mhkZA}CI^9>gsd|9n`z_jJs5HG<&Q0F7#@@;Dm+6B8bR zT1~9P)FNmK2SJQ#egMsvDGvG_q zFPA+L-x1K(Un1b0JDaq{2>?lU{Kek94FtSMObmsc~w~gd-;2&`B1yB(4AK(7l|NYOR5{B`)fQ1MS%^NW)dE?w3JM zfQ&TIG}mcCd6}BRVCoqQX0Cg@K1V>@3?-T209cTSSQ8&Dbe&dE2>>*eGhK0o468p{ zhCREFu>^T(s5>F0!SAIF8K8IR5`R(B$itG;u=Nd2Usjm6m>RlSgJ8z;@hb(a-&(PU zsiD?^5r|ov)?XU}8F!_{mx-oJ7W`KZotAh#Uga^ZWNZR0X97ZH4Sb_Vaf}`h1!4^) z@)qo_K&DHdQs-Az9eGu`F#!M}mbRL>69d4$AZwParkrHJaF!(JYhPty2oV4$7%hnR zt1FIq6UG7)3};KOa|UlsU0`v8cRy64t2o_~vBu3Xf`&}|>2L_-1i0$S(CYyLg1m2Xdip<{4gT(`<)A*d)1SS=eoPgmcN+$Z3HC_9pamSU z`ES+25LS~k=uir5R$v0)8Gms(1%rlun*Q$aY4b05aQeg4_mu@8SP?Ms?=Sw|c~!z$ zABgJE?at?Y=O%Vp);wrTh>KieAG)F8fj$o!_yRKu+uB}Uy=mL&ci#c?{{DAPfP%p9 z-a7yqvH=IryiVM0ByrD(Ax@AleBra7{y%_aavXf!xPukGLB;fkQ|QOfFGE=KZ2GT6 zza{~oBC^8b>kIGkukZNd-Me26`evwoA!lqAA>@zc{H4P|_7J}X68`FD<_MH7+s~RQ z<|8doR}c(+AGO*?{R%&&<*k#jgb5EF0!x)B#8Q1!NCF!-Z{PUm1FLJ53#sF+K+fnH!+M^=KbIaW* z^??>G2ssQ3L3s1~nIV8%tVR0yXPQDX_HS(aB|AJ|{dmblR2Ri;yZsIEFNb@kiq;y8 zm@I|h6XbOE12Vou(&>}10Pj8FfXF;R?Y|fZc@uOQ;2xj?gfH4I32_tT2|}!LQ6pT* z3y{oPMlkK@ zRa4Sb%Sn%1H9Y!Oa z|C9+G*k9*D7y=yv5*AOXVg!yOb8{j6Sqc`fg6r=7)1UtIJhXpY4N@4}k6jJe9X=52 z<2)WU6^TD6N65&a)xo*#W3?>}fhqA{WPr^LtS$J8Hv@-W5EX;`1#{p0U(Oo{`W=w` zFQMgEJJacX zCj`U<_yXvMA9(!jzyCWm*!}cuIng=e>B7;oupx)9(yA;dJpb(nTaTA-BME2z`1S8y zB4G=rCk|-}pDSl3rzh98WEEWX^Sk3;@q$3kR|G_5LtF28Yg0{Y zua0<`{(`!J3;kkub5aA=1%5mWek22My`2n4O~J`J63Pizx2li4KE(xDa_Cwu?`J=_ zC^DUDWCO;aWt=BF*>GLm*Af?Cn*uvSKwpNFpu{d%cniAOWoW6hKJ)=Ds3L~3Mbk}} z$LSG4_W531?3z)M*)sgY55o(unuL?1V1x&H*;kUs1ej@MRs1L5MlO*eX|Hb)0T-0| z%#3`^z7>wR_;WK(UrL;2X66^bgLEnl8UVQETEM3QKrFSEhQCYun}pA9{ykKjDPM3w zUMDNOdvlTXNQc`?PdxCMlilw4E{8wKUY_s)cgQ$|Fzg79vCy#0Q5DhwI~nQ*bE(uy5b$ ze{EXyKtFsPYC?=1CNPeX7e-{vSk;ze37#DR@!Y38Kw3ch`13XQsjWmg2c~@1xzD1p z6b55^@2pLRic0lNm?A$ti|e18fkO+N8{)zUI2%xJU2oI-yQtW{ZZ#l{Sfn#Yygxk; zaWBL`!QWLQey5%P?T+~f-7y>g$bU?FJFq7ss2+XwhFl+B1EK|Za5X@mb;1b%!x7M) zFQ>~f?e?ctc%CDmUjgUS<#4R|bvYy3l9);&9Ke#JFox`k(pyX-(Euy4U8MvqsHxVstG(y{_x?#C&IRsHK*7-Hk$=`pW!( zUQK`CgMnGCIa@AV=2n(64=-bJ&6wbnT@ce>42VUIj{ra=z;xkS2$ls`L2??(#Ud%f z@vQ44N;Kz2_S1=6z}DOt=DOWrGbXqbVWr|wM~X7F@f*Pfv%mwu9NX868hNuGJYir( z0jL#+AvQ<|7s*k>|Aw<)#Tf`%gMYq@4fsCOpb5Sl^OIQ8ATPGCGQwigFI;Nu=DUe50^`q3Q%8?erRv<@o_6?uS4$lEh9IAiJn za47Nf`g!SzJyO9TJYX+yojaq{C=eP`8x4J*;Y^d8E`SiIyjHzct$QK^uni3QWT!GD z<{i|NB-+wGwt-mC$7L71aAd;}|5SriXYLg}zYK&n4AO7HH`UcgtTy6i(+1`Ngff}?Y69HBarh=kd)%Gqwe(X@g1h>;?)Lxr z(YKF2e1wi`0N|4+n%f9~j~@Ld02B`D3Yfp{i3x6}`#s-&X0S5?#`qT>%DAg|nG@!L zBpuul5u-1IaKQfl$4BqqVLH3yzqEuDDT&4lH*O#mD>ngB;X-U98*&l6nO9(OAOt`F7ohI_H{cE-0N!Ii zrb1G=1w#?-5pP1}N9Wfu^x=&>0>0sS5L&=J=d~JhYSIa9!Y#U!OMrukC`B6ZEs(n- zfTdm?R59@2;G`!jzJQzD)?})JlL|%@$l&~I902Qsj;#j}PEOty00R1kmXkA>jY!;# zQ?P;hK*)CR#d{zK1#uA(FRx8l zRdYNQ!s}afL={voj%#tQvzXSok#g4BK>;&)TF!t z``-Hy0a)vp`mPi9-q^Dz+#q~Hki%84sVUFls4&9esYqbNL0bup39(5{oE&e1f(>nn znEvWP7ia<;Fv{SZ#|?8*Ir9po0s?Jq5%}tL%bk^8diB<8ubp=M{h+NI_2gmGK3h){ zpvulCPoIupR15nQp*p_hqD;9wY$!f`i!5*eAnP*mi?ZmfC64BnK@YNOZ6~l9?gj?3 z2Dkwo5}kXGqdRhzTUMM{o8U{x;c^>90HMIDFs!#08&|?<0%AihXx?27tkT97)A+ z0zlh8Bz`vR=_UBjay=li{3;585||b0V~BxThVA@F_P0fPcVi~B(ZeyODb1ApFW8SO z+fN<|{y6UO>W2~VvDn@xm;qk^{9ft^=n?RXj~_k@P~($hzqSWBCc2~(U_!tIf$5R9 z>+Q$%fV}!|4uQ}45&bK_ev(an9XC=PaLw!Pj>dErG-=;`ZUF2IUmL42@dJ%+s!@~s zmkKu}M%fc$0AcH!lrzp0lxUC;DmxtI&6xLMbH?Ei@YtX`1oKym_dWhFz2S^1mP>jp z#Ab`|DUqx4qUnA|Iv4X`)LG7X1xC9YJ#wT%6xR&E!eY*-2B~vMLnAW~hG3}qPR{8h z*wsyLrw7p8R{+()-vK{Q5&*mO0gaQx4XwZ zJD65UUTL+0Fojk9C!@xgEMhc;FrbD3fR{jRTnDYO&g0*jMf2o?34KJsz(vGE^C;+a zeEK^s-DC70^H2$ZL;>|*!q2fllkfyd5&|G(&z}DHl=_fCbH5e}*Wvz{aXtEZPK5)L z^#SAIAYLT0)Rn|1S@IHL%`9*PIWzC{1O`B088pg+L)8=|XuY)EY?Cnqa?CqDKOa>f z%sgFE)(hvrErXrn4@PeT08cL|3ja$DfOHpc@pWS4`4mb$TDRVLMhD9o4}nX*08S|7 ze{gafPd$3a*HHD(IPWD7?A7`$Pw`3rLn+1DfeOq%o3oDfa-$d z@efLviy7(#4kiL5s}q))PPmtaV|f6~Izf)*D=|ra@a|_hbYeh`Wb1FdC@V0y4+p5WoximUW=e@4PI=AqB02Pjw1u_OdtIgyDv!I z`0));54S$`SBePEj(~obAujP9N7`X8fU@VC-h10jahd|tuQ0(OI`HUE@tKrOFFxN9 zluB3dV^jr$@VRlG3KIIUTDbQZ00_W4WZ@)1DKK{aXk0(zaJqZ9L z4~!8IOK?sKgD21P-5y^rCIEb#6AUIUxIG6#>-Ttj-%nzN7k3?-WhY!d9Pq1sOk3D} z;0}TjY7vau7r@uy9;Ch>X>~Ia_5})}R{ai*Z;bf#L**sYeOh+0mevC2WB_TE5-NJb zjCW|xQ%q=Q5AT7To?1dX<=?kzvd@7{E@`qXDLRi}HnQP5-(DNlWLe|>z$Kg!#4j!Cg^_r1RZzuFmQJ zDo5u>?gs?2BffH%QW#p{Xm$JWdSw0)0EvLIPpTb6Qz7Y&W)ofoz#fcl>x@2N<56=B z|1Kxq=lxHP;Bj!lxM*RhJWrwDx;9^+1(h+BM{CSGKgc2K{NTjUdAA|~4M8N#1dwPj z9OAYpK_JGydesZCq%EO`1|Xg0=1MILWYD*j-dFd$M^_tIjcO3T;yyU_)o;&J{ybT| zJ%7tLKRSa?zjamB!OOY`jw(-UIR?b4*kA6z44x*W+GgC08)Q?>AOrr+`Gn%;)QnDD zw15u`PPz?_vlT#|IF5lcfIp6b@_j5MbMQoV3gqjq3HB*af%r;={&Tj?2D#Cn0MHX3 z?|K;yDjS+Dahq+<7-qPeVu3fOOaqT)v4HM~lM*Jgza2f=mO;l`a{R}Y$U;Z}s4!IL zAiNj#AM$%}&5itLT?GU52!9C-4+Q!hG7lVNa29lm5%9n%lfZY3d?_AlZ}%n!`!fQVZBi*9j zsk2|Jl@ei8eP(Az0~kRZwAO_P*>kX`vtUC=Nv&|Q$W?~f87DRwK!~qYnR6wjLJEK( zk_Gbirn?(ga!*|hwJ&;7^x8?#q+o`!975Y1aTGtJm=5|sWH-+hEsUWD4j8C=B?i>F z<3Iig33C^MYE_8B&+r^7dtF%xTwr|N6?YQVN0kQsby8CkiNS^x3grN6K$O2w-)Lgp zkn5$$5?}-+{#@}42x|((Ii!JaKnE>RjAp=s#C{*T?gRd}ZwY{FR5yDSb}g{%zHgAv z4a=|aj+lr(TV}uDoqOJBdIFr`zu^h@qBmvwB@4p*tMe>H7Y~X9-wdnKof8Ofl)P>- zqLzh(1Cwf{Bn``AqJdOZPUN9FPpd0H?w!MbKQV9g^WID1L+wUTw}8=|Tqw`TJfb z^y|;c(r1 z#nP9Lf(phfhh%{}Boc(KxP3;y9S?M39x~(W8F0~^zsh-D+#5UaULXJ3A<#Xqq1x*= zjey@=r{#?!;FFI(CVp*m0@QmfgW-7i@fUIA3wS&GD(_``ek{8J{_+0T#=Z-?jzAUj z>*9qB85yR(_|+dk)ZMFDE zb=`R}+Az6KD?s|BuZ(jX22Hxq8Aon}^XMEkj^sb?_C~ibzp>sD`$UL=KX=dpLI5OQ zg9nxtri12S0boQvi~V@20Q?861?H$Q0D(Mlsp$xWbybNl zF$NoO)CBJ#Rj{rJaL+mfBP>U)CMw$5iW1U{v`3ChCcij{ccu5ju3Ns)8kXx@XPyHY|0x}_x(fGSBq=9eu(VQE^E3lT}BhiZ9 z4#kQs_^e|AfqEa&100s%j}9>z3unKNLJBPa+!xz0{cw7cEFNtaa69UGG1J9FS6l+X z*8zY~yGZfODew{b-Y?oq@FRIaB!m$*zIgkKHWh3pxUFP)wYZ&$V0PeNXkd;V751qc z9j=f3`)5DN-vOU*!xj8^H&R)MXSnyLYBwVwe|5A0u)xYoWv7N0WIDp}g__gs%A7mi zITv?8&3F~AnT9?VqLI?2DY#WBrJO9rKvRfZk}QzZAH^mO)~S~o;z3{+W5^!LCwti$ z1Rz;0s$RFeUm9uYtSg+kxKRURB{A;0wrb&@4uOOhcfuL$Q1gok65rkMh|hv^(pPt- zreEP-r*`s!g00zMEG%_w)*Rc28!Th*a?iSA1k1Js6ARVJZU?Zx<03{@esLxUnss6L z70C9V33W(=rdftFD}JJ4pu!&pz7xH%+;i~l%)u)!YlyN1yhkPGZe2nlNCp6? zkOYw=3+;MLKZh?4D7c_@5YBw(+C;FiQ1f4^EuCwrWr(+ zzA(h4TVSldoCi*cE>?In1}1GxuBkRX`sZ&JVPd-iO*O%U(?b!Sf; zkA=q$Da#a4cc;&`k4lG|jwGPvu2{R#h;yUfVgAT+uwYwChz`7J#t`jeCOjPgjK-9l4jI#_mh3F5YT>OE7l#j2V zgoSuRB*JL+J4SpOV`c&KOUIHUINN(U`)wym_}!`KMsE**==$;DZ!>8D0|g@z(DNV3 z-!Z#^&s|U@W^`gk7iK(7z352<6ECGqm;k`&!`v6rm$Q}vMhXI7IJ+<4Pop5>V2FDM zlE-(ivtS|tKlOn`5@1$*q^D>&a<%XD#yz@y;d=Wf$PVCN^8Hc@qq|_-0ci&bnM^hX zuB6sWJ^5)fQ~o6ggnRmfnESF_`IS$GkGI=f@UvZC{Q&{DAHTi%5$fGLb@j6!xaNV6 z__rz}D*>>g4CxN@A=9}>pBF?d$<92L1g26*;Zwa8+It%U5}gJMrG|-L#alHhF4V0k zDT|Q@%04JrLdb7|5%h>psjcc!1MABGg5%cwLEusmy^=O=+uS(mU1Owy{J>l|)i;T_ zgjE5cc3x5+BV|7~r>{gg-?0`Sst-1;>zh{hky5NE2VY2&D(`Z(xtIQ1@I{NdBI6RQfDjy4c+F zVRi$gJbKT%E6*hz767VXob#W$LQJp10;0u|5HyOItENJ!2DNzl49A5QqaV6Jc&a-M zAUk{*0C;stGUGw%oFma7P|c3HWj|devSIq0KXZl%c!onDKM2mcl#pLd4}f9B$|zcJ zYfHKqjd}wS2>s=__Fg@Z8Kds>Kta7dwH<5TqcnPAz{rWjgqhTr?r^NQ1`_u!;D=rq zGXm-?haZ=CtwVklldvKex<4>5ZhK-pOb=%Z@}@CxI|qAy`&4M3vF?st5b~)T{TOH& z;Grct=XMkz#U!{Z^8vS?CLzpOMIp2!@Z-r9A>e!9MAG1A-AnuW2UBn`AE$DCNW!^% z?{9MdhAw8WyMjpwckf-jiV^Tzi(TaTnoN0e-K(&Q}A!`t?|LDCCE)r5UhV_}QlHlsxmXf13xjHD4%ALO z?GLzN3vge;KP=D!u2Pu3I5QPw;bnu71%8#FfEzl^3{YW#?P;SqUFxN_qKvd<&VqNY5i82##8ht>Iu&J&D%MgIq+0?pyi zmFa1Xl-hwiD8E7I0oy@V9hA?~%vGKNKSwT1!IhYfKY;T2dK9JmF39_zii2M|R#yNh zks#iQf4Y|_g;5|h69OT9nRsJi;v&~$?8l->So#4Pm}xLP_pRdzC%`Y4CMhBwY%&;Y zot!Gqfc5h(JHi2Q5(<_fi;w|;q(YV$PRe83Eg5sk;?7qw03Lo_&239=YjZ8gr1#h5 zlysGA4&bxy#AG6%!m#*MBjBk3!4&}F%7Ftx0=o|+K<>bf0Kj(TQRL!l z6LubcVL!B6za;?l1o+~`7jK*9;0{dah$>X+@^ zyUw=T(Q{K``(y9y7!{u#$hU~R+O79(U-@^=fPLZlt!Nr?qc2S%oB{iyMTGA|QAl6M zv`xX#0pfEC0hp5bX=-YenB78oTq}^QR$){W4Z=!5peRN~!6J+00%i(=IO3L_Aca=1 zGYpDEPw8I-fQ5o5K-}_}dLNXpO2t=!OG;Uhcv|@{#UzT6bcP@WNwsNYk{WYzj;K)1 zanME0gUE3Z2p>P`KR`I-0DLE{t#Fj)!KjAV&zA^*_UMg@ z%FzIrQ69v;nTUpoy*E-)osr7TH%35dVyt}`8#@>Hhf0tsi(ps}j0uqGsOp64&ygW% zDb51$6@n@Xc+)?!+o8^Xe40yvhVJEm}EF^z|#UyW7W(oIUXT*RQ_HcO!lM z$Mh@4U*&Fv&t`Ar(Gl^e+K?|?)&$s1WlI2HU-*CVO3iz4$Bn4EbToo|z#Sd%cJ#Rc zy-g4$ed1h$B&PsIypqS z%;`;K)sPe_&OPW-za{&JQM`_-kfMdx(J0bYJU;Tn@sqCQOf_`CLQb`=fI@>@_bJdt z5Wo1K>RAvr6#Xq>3udSn0I=Ab23@bf*9m{uof+;V80%sl8Tv?oye}~{vjX`Mc*-?- z;pxl*NRd6#I*S>hy!U+|+JydbWA_EB4fr4akTRsm`!?}xA%-80P+QIB7IOmClBCIP zC>Y(k0mb~r;CQMjuQICu@HD#or_|vkI(&iX`QVO=$?gp5 zL;eIlM2yIZ6Inf6LQ8dJQY0-RIXIG`QMZ9iCjE=&z;;b0X25#tYafguaV9w5L7Rf9 zi1`vSzy&cW{LjZyx(50Hm|5W*lioa17*cws?fc;1*Ebzan9{?n#x%%(!+k$biwIFN!n7Q24u>ZAWm_>Q z42k$?kxS*6#J5U=5eaUI66py(5?V!5Hh0YT z&B1T-1NY#=CslY(t)GO2C(FP_sBjLybC@+sE|+61Qm@N2yL&DJ059Y31qP6A-!&zI zffuAuK@1iviYxNSK`ul23-GY_Zdm~M;q`X(AG;I$GAF=bKi<~_h^}iCO|LFD@7$p9|B_<7s^8)Ic^N@^k32#&|44#cQ*G9*i%D8XF z63OczVTKzqReLB#=L{$}aPY%Rp3kaRUw`f2-U?V!CLnHsOIwkEzib{uTd-qKDSSSC z`qnLYeNW?pSWTC|Gv1aXHlaEy8FbdADKh1D@*C@Sb8Pj{_+%{J;{x5G$$FH=IS?k< zooCW9(0I2LyKewtRuk;P%qWVB!7mPh#yq{CNPPU9{d5*XAUZ+%bKC}Upf&gP_owLR z?Z5Pk^wq;hKmwmrP>F!;Hejv5v!;I|6d~x}-P!oJyRCxGrNLKOqb?|`5}h=5>wAMw)n z_A?~|`uLYtWZ>if{GZRB{m(W6=5Q<5i|&;Ce-L_=R}Mn+oOcSZe6^z~Q`iWt^uIsn zq%!?S6EL+f5<`Q4sCBGnZ|q2OU}qZply}wF>1aR#UudDla8L-HIzyZr=#~stb@YlP z6=Q7eNkL1i0MO%Gz!=|F>{j9o-l=)<)`ndA*UGG0f?0z&*){hgatvtG zts&1ZRhg(d1fC8TnkVP5LJXWU&1h)e`XDvLGwi>RxR_9$^ZI;JvCs#5_Cr?fhPhrO z`19N947)P{@bw=2p9KGfDKP1#QYqj72o4w(P?ftFHsgHCO&;L4S_Usn9U!VKx!B6% zOGn&?z5==lZcXN2?ZlUS69oD-*T!d_Uce6)#C>R?OOqkdZ1*6idk8lI8^Ddub6e&oCaGwd zpIlO~^Rh3919c^*W>-CZ(HH?KbVkq%FpyTb)75!(VrGTt*}{C4m%ve5L-eBKwD8a> zKJHp1&a^xMY9QTGWK4a~-+G-n(9Gu&`pFwYtu#hJ#auf@Mw0272uBU^OVUZ_?tTjt z0dfeGB5=yl_*1$A#{PS=4S-V~05$PVr5j-I9-Cf*344UV2*ZzNbfRBsNLLk7^nh3e zy(@V^GyyXGR1kRNNX`ovsnCi7R3B1Ie&PT168xTh!C5Dq`!IJHK$0Pt-EN`u6BZ`* z%N?HqU7M8f53fvDHokuV1bj&hj1?FF_=UjjZCwFn3f6n1l*SeC?PvL5m;--|blKU5 z{@*_ke>I!YAQ6<6^TfqH@!|jT-t+t2n%`=!h0AK<7-(DpLrf9Os+EEe%(x;QLye4a zi8JLer~oW>!4dt~ebiE}AMJ0%1FqV9p2d)CbOUy_}7UQxRSPVF2xKM z#CsGX4RS&tR$M=#>qKG zo#GCF0(dM5xB&K?at$a_Wrj_0SI9N}jEZy&fI2fux`>vzaxd`@NLV0utI-cg_n{mi z>yd?E9JCT9+;O@KK5a7B{poJMtr^x4m!0oX(;FY>6&kfJ>Vw3`lCtC3oW@O(W>|a` z=|GyQMH)3s2>`tT<7NnoWLk?%+`V1q{L;d_iMh)PZp0jpcVL*NWuF z&35Epn-JObWcY5T4|M*^rnlcs@4$dN&48&9^VqS3hU!4Su#*94r(*3o`aw#8-j#R3 zNdp52Jdy!mmV?UO*AFbeA4NI(fdqalaRqb|j62d7m5b^X*rJ!k|Ieg{b%KZ5_!kRt zqp_780TT@@&&S&&JER5t#tIo<1HZ{F!G3H%-#O;J`p0>v|M2mAJ39ly|F-$Oy#ixC zJQ~-*?T?-t|7x`?0w$(C6TyC&Kl80{-G)CJGCHRt7qDbCpA5jI;j*HfaolUr`>O#_ zNixJhE`t@VfC54yGB5^Q6kDp zU%coXgf8sAbZE>ezn|SD%3tVm5VVpM=DK|4yn%Zm4~j(zYKqhvGIC2ftRr2fUKqo` z0w{!dZ5%w;y1$7$KtKe168H#!(oo|?0N^Nv ze>8Sr3aq;U#Jz7b40?eJ4*FsKqhA`}h=|RYOQ0&#+5Af|8uIu@DNKD(b?E1H69isJ zYd0W2?rkMH57ob;q@_MM6E{O7LhEy#740HmL_UuT+Jtf;6x0?w@6i0w$jic#ysY2d zt1>h6tA@Ydm$$@`4Dq|FPQn#TXE6RKOHNAQVh-q|`>q~IF^YL0g0~}5Jp(&ED_Vmo zfBEuU(!(rx_RI32Eq)g8jeQzF4S+YV@M8@FM}WhMRtMM`+BXYcfzFTa2J+r8g18dx)+)BoOn{PCj~0gHmi zM`D6^N?{&e`1St;>;B;g`07AT3WF4wPhRDF;$lO7`!5GL1GWJWV_;3X=Noc{_^s1E z40c9FbcYUrA(-n-V_=~a(Jyk`VyYv4l?!Nf>t=}v2hGTkX5gq=Lpc2P+T)=lz-R@= zHE=^zMz8XrX`2N&sSeJoaRr+(#xO_Rw;-qKAhgb<(*FOhh-OLJuJOA19l40 z*oCPl6yp#FIRw^lqP$V6wR*)dJGdTkTXT_fHTQ$&Pt*%C@Q-Q(AO0e61ngyz9ai9Vg}~fX;(d66 zQz6K@MbPTX#Cz8qm&Mw2On|^aI_5kY(gxg=?@j9FraCV}6~gBOWI`v{4Gs&~pi-1^ z9b1|qgKFu>Z5MM8JeU(h)H|=Qb>3Z?%^^i13?>^cr?)dF=HUarwd62ps8rx4b|Qjj zHYXyO%r0|r3d0}nX*PaWrr?b;*r9VCVofMu-=E`R9)$Rpr%?*m)`@9_#K zo>y)Vi=iJrd;EoHkR*fglN|uaOW@g`{sz-z$=O*H$Fw3l zhGyg5;4?@DQwCE}pQinEx+oSn?1408y?NP%;>Du)i@4n++rR|cO1nxiaX zAV^%qlw$hhuWOxRN?eI~T#9T$5X3ce*C>FgG$4GDO?bqatN7X@vc5t1*F`T|p$4U6 z>*NS@i&)jWwcbWdcF%FD3UPC+fg4s!W>3ZZH~ZoQd1dPm@fXFvGQ?p)Ha;@9T69@2Et2EX&L6WOZXe|8VmrW z@VUtvOl`x2E^@eVLCi=WNHCb0s4M+ya$;QbAK71++y+zUhKq*?e&?GBP_W>l{bO># zsn5Kz;j>P#4&?Nb%G1pk4^lj%`7bmqX%v*AW=K{zAX(aw34p{>JgdevaM_?qoi*!_ zxBz2>{Qc_Hl$EN%GGGv8b3FY4#fh~HUohm4ruKAmAp`dJX*pI%j0Zx;rrHENlkR^E zh@LUzv8Q9qx|p$S7#th(2K=dOg8TCva26E3BmK|bUmpRn@%G0Ke5|bj^yN=4?!J&f zk<#ql_?0h0Pmi4YBQQ`@2zoHD9En=skiHQ3oco+z1C4+?(qG7VSP^r;2neh@aH@@f zdl%gR;%6NA?q5E18K}2t=))8!N%U&UmlVOffVLNHUNGTOz;=E z6&U!`zxYp%fDV6ooYe@=?%tal0bhN6M+o@rFVA+}>FlmW3``b^>NqULp(-+PTCp#h z`D6)UGaU3Y_78Ikbov$f4d&q&viK?>V2PhVN`y*4nSPlbSg}sJqFg=|A(f*eNnc6R zAcw+|r@o?yQ&o|RiQwEu6*D)_iljKy*Hj!t-I6q=tdGQT5Q(gSs%xDLt{1z@nCCef zm6gXJV5^B0k?>_CRMUx#!6!N72GCvVnmZivfWyO`Dg+j)A`M#GG+^`O@q!eT6&4yp zD~LLGB&${m20#vfoTT+ld#_8Z_{axiC~d3k8{s zB`EyxdW?VzPZ=3=&y7gq901pbZ2RC2EWO`4bFe%H)3+ zU}`|Y_U=_{C4seHz~ECQfln6!?j$)WTx zYrK@o?`EPk$!b9Fz7uf+^bBah%fc~+;xAmVBIZ+F{-lAX59Cv>z&F8pXcbP@wk#uN zYN{Oy6UFG(#%yM3sJY=UgTf1bit<8pLNn z4}gFB=5H@vNDKJz*~2fMym;gt_)#_kKG}H%WIFUey##;#D~-P}ja)dga$xVTpL~_4 ziIJ~haD4ZJ=l46~-WNx{fWVrvVy1#l?UZM0+m9HrGDnZmEsOFZS$YalF|xR8+fWI5ulvTW3v48>L>;zo$K z6db+K!W3wbvYP{+eq4qT7nwsP*mK;Rh!rs#8~U!~9O?43%3h;VLlYz(`-fc#3IN0x z{_%&1W-UuRJqOuKiy|Pm-o0L8WhQ7J@;!9Gbhy;B*I6)k<@o#D0QlSWaDU(g2pSmT zm!~v>tO@E&hCEO@0%($_c&eixAn+1LK;|7RaI>8O9A4UkfBNSqm;$)otV`HO9@ywc z?aBmCfs6@cLAq95-or%y;zT$wcpC{>bw|Z$#zW|QJ&jULA)c;;5ehxNb>_@FhcUW= zgwPx16TV#+ZOln+sIBaq9G{FxX@)=(0)4Fm%HHNOjEER89ya0O@z!a<9WQ*e+%2EE zdX==usG_o}fp=S5P6`YHWK^Ls<8Iju@u1Vb_}5SmXcrA6Iw+Rlfuw&)T(H{WRF^bH zYZ_I68~`bWPQ-_TpScLXt7TZbu;#q6*{Lin-?>=*J3?dn-G(mzhfKz^?fYK_fWkjS z!EpG?*?@QF#eYX53)(dBkq|?-0gzglEc=?1N;Rne9APM7LU;T4CFmdizz`C`AU%mSJRZcocJr4Cy0rG zTHlR6MZfS#XBq-)wUiDhbxX}Ey^8#8sTM>*`M@IP$@F#NJ=2Bhj*8*H*FtLr$#kHi ztz7odXx&S%2Dw(5#pcCG*K;c{UIu~@wjf|(EUD&08qW%fEa(zxvRafEgrtn&IA%uj zzRL4+9p*`ZUv18jT4ZN_Xak`7lp2kwBJqADqH%R8!!!u${3LrHGa{|<7vnvGj zhX0TS{)I92fxmmJq8QZ*!}j}baPZxL^bZVhh3PO#eJDaDcrS!5oc*pl8d}a@=c7hH z@LFmMQ6S(R_5)w~_R<<%aOa&2GeG?sgdZR`W+nh`2zegz0^A%;r$BAC1IkI|L)sUq zW>}TZCM52oR!!GEGu2tKtIc?*={h*MGNi!Uf*$5ihYwd3lS&h?>}s45*#@WXq>Ky3 zY&R+Tqs|&(m0ywo(NHvmLN1@`={VE; zzC8l|%{+*vyoW?UfZ?NWVhT(=@xT1b!#okpp5Rxn{@EGum67k&tFQmSCbLi2VwlHo z@4_E|+@!M*0Dj;>kVHTcj5AN~^l2IP&{vcCr9B0b2*IqEf&iU+N>8mM&oqZA8nsfY zgf%##Q5}BIsfaq5g4BDB*gG{w4%^Tn`x?73dzC4LDeR>2OB<&=yUJ-EQ8r&$-0G@u zu_VTpS{yZdP{<76MEJrmL9C@LXOJru^0QcoMdI5DU?NoJpj%xoU&(UO)xJx!*1fCqc4Quf2y4GP#jZM4JqUqd~90b6>g9Je_ z<{&R~L+<@h`n{QARcERgGuv|ODuy!v)*W_LzkN$-f#X#x|5&7MX1Goi1m^t-bKvh> ztD%pnix^Qv>Jss9$ur~9q_d+ZBfX#6XrtqJlS;=?7uHDy8TywZ5Al!mK{`gVG1KSt(4ei2tBIMaW zzXb1)Oux$b4i&h9s8bl&}w;LOV3N%(hMIeushX{nP5Fx=wBZWujoEf#ZD zlnoP+3&gv|21U;iaI*owNLga;%a`x>brXUyOL~=-bq>VKH6$52I~DI6Za@)u5ZMo? zcshKNC&^xgxl)e9c!Wx?XWO4q28VbAmZYziR}1>DrBQG#lz$Szun>;VUXm5oK70=V zxc>gSTH%_OK4TvI>@(Ql6!4A|XmoqP41$I@9{1$$6%*odZ%8M?Auh#3DF=p02~8&C zGZv6>2vipjRULgrRSPF3n(CZt5LAXdAXTiLe>(gfRVbY8l8hO|h9ArLncN`tyd~Ju zKb`~WF=0v4Ep5KQtEz)g`3ZnJ#bRAW*34B;f%>$`stPkF0|1vIINt-H@}s2|TvC=b zM9)=qlnmDES${|ZK=R;BzCITrfSD&GXyAn;f*xD&Gbx{EQx=xv?^Tg`GpjsrHy%yx zjK0dUqWiNVV1nK3W^ViSF>qG+Cj`83E?0}WD;NIq0WN@<`q@zE!=Jd1%m>%rfW?D| z^*!X=0|Oz;fYa#5flmmyH@v^rxn!l7sTCwip@aNQ6mV3BboX9;nZE-5O}NR$k$nq{`rYWAZDB{y^w+RE1as!f1ekr$wrh(UPViQ1f4d zEHAWvx(*g&2t)}vCO~RkhWA5*LI7k2Oc!l*gf>oqxWAS6YxTA2xKG>;dV7ChZ)LdN z=6YAn|1yDrG4|e)8x6zQwYdnu7w$RsbOV^Y%FqLRk3Bt?FGK%)kmi>LCc7@Qrt1pG z&s)8At;;7sY{zqk=gS4UyThRh|D~-i4Opb&YUm zZjat3y9)rEXEAzRXcqBU`lzZAknp!GdCM&nqBCLNdu_nvi4#@E2qHo7D$6&onjaxp z-jY+e>iZxyGgoaGOToP0&+BeGkw9!tVuPk^atzBN`VHC{=$qh-YeFs% z`4+eXFIW=o0uNxADc~t(rM8tV5()NaMDPxMpzyLkCP2sE#~5hf3s0Qz&nqyWq)h0X z1y}(10V$B9mP4l$1li$^wDm9XD;ouM@jDcin5hu>(4ho?y8OiyxYrHni%JH}@QyU^ zGz)>f3E#gT%m<%R5rcWKr>8Vb0Q~JG4R1*cjUi6}$SwHMlLUeO0G4DT6=ugHZ{zqU zurG7XMO|i;&3*ONSHIpl)=!<_v+YCO(+)q7@(&{*aFAPYEgIcYOM0JyuZ@HFH?B7c z%u1o!>($Au!)Y;!yW$>LsD)6_z2s1yfFk8`d_&=WlunzxAndhPnIE9?NoE~Tl!EDr zg1_PYukQy277|dEP;ahqD)#hZ_~O}+V4{S>i0AJLMW2noyvnJ#uEaN4or5)%XGI{G znn;RaMWzg<$Vu}WTSv0v;hGMH!3#s{6YRp& zba;NfnMFt?BQOR%2x1%p!<8|m52RX-EvNQ@0-0QzKXI6#bc2V?6z;geK}RTX@g0{-_)9#_Q45U+!Em9S4+!+T;4rMQv4}+w0FH^})xD2zm{p_4 zl!wCpo56>q#>^diaY90qAZ|p0CGMDz4=<)k(D8td$I9^UXs!t)X267lZ4ca$BOgR9 zdQ>50v4A@M@o``!t-(e=yu}8%Gy_Hq;G#*7Q%=3VmS;|lm}^VhHbNiATzUOn>>bM*V^*H7-R zoV{}N=tMR6_F{k)fiz8LZ#dSJRs*tlaQoL52`>{(*1~+qz zejB>#B>*hD-}qq9!R~|I;!(QPnAznV>4H2SfNFBZBbXEsj|v+I*Wlj$(gYPZoSmQ^rhd@n(Gh1vaS~xh`^RQs$;5=!2z*(lgOsT|@ZEiaXlBQB= zaDRVRlr)>21ZQJs9#ayQG7*S?Ne45_jaa8Z&VOPX z073&Yvi!Y6VG`S+D_|lz7>e*sgdrqJ%%ijfXM6CGU;mjM_|@01@-6AYzOR0LerMm2 zeHW0*y~%#2Z6~b0eQA0%1}0nJDvT@UFj$yQF{tqnS0W8_u%i_PXld57^pDUoT}szK z?z<2}V`Wq`T+1QSr50Txg&<9a`L?(X_LBQ$I#g)!=3Eaq!nXoShI^G-HR7;lJR_JY zl3?yfudl^xbHq;>i80Alz}pi3Iz0hGHFFIuaJns)#YfY<$GEQHBKv%cwK>wm5;K;2 zb)k$%Rn-&kAI8MnO&>6~;FIi3Kgn-{u8*38KHzI0mT3T%M*X}aj!eKG9xTQDTmbl#0Ql`MzX1Ebed@=zEC+ciGGy&~Gn@aI0z*7Z@%QWN zuKHjDu;Gvz=n3s|6BFL&7=euY;GmdZodN-f6Zp3evCR6AhQc9;M+VoD7I0|UrRc~R zXgbMdDAve&%3e;}EQ1i}1fIM#xHRb%co~bY8h~$qH-CFM5?;dHCPrlPmY{7u>0{bD zL3V*~$XkwhEO8|v{!<3E9CTzlmRLzreamGfOA_DUL!^o^00NvjNmj=lY*UW|ApanY z)n}f}QUt1E^78=5QY83+Cl*8t52VJp3rMPuYv3i2vzOFd6ict`+@^9BAw-Km)zET- zJQM)h6CBy7eDM)hWCPz{GegL$|62fjmEHRM(pNwI^y{6oM|U6FL>|TV<6NmQUj6v- zzg!wt{}8W$9{zC1TkQx@3?Z;vE$YqIXMPScO2R*6VyVB@=5?)Lvaj_YNq*wAULcfR=i_Q?6OzjazoX^D$+zR2rMed zJJ8o-`hv>fK)_J+ToDyS7N-O$Hu3hbYUBW&8{l1Nq1)IPMztK)Wk6wRl^KDbe~xIt z)z6)Xl>wk|4=|Vk;8QDMIPa~=?@Q!c@O^Miie~|!%Z~toRJQ2U$0!3~UW)r18~|#F z31RdzF@YTM!1{S}Asqb%2C#R-5=Zx3bx_4f0Kg&k?rMOOLwLwRr(5GLF@mBQE|7ow zH);CF@50M#bDO~JOlAOaNfNf&Gt#mk3F|g_UCea9FaMq`yQB2IX$Fj{Bq?W9pw9eN z1E7>N$cyFz{MK8OItXsHr8cZF0R~ooSDPJ2z@-Szl5$%~UeWcghPfbvc@=aJ)&%X+ z1ImSF5-KaxF9a716eLkQc8qtw?C6*K1&ZWm+YK@mc*lI`*;&e+@J_(YpWf z$)+Yiv%$Lq2U90pLcyac1oi0AECzqa1HGf1Utk`ps5f(!ZznQV)G64ul54PyTdIBcK9bUWf+yo3DWX1Dh@^ z!5{kysD`)@12P)b@b}lW1i$*fnE?~(#Zy4v3jQKDX$s!_uZ5cZ+kgJ}$&)562@D@q zDI5W?gX$LX!nE*5bTo%TTf1;-qexk@KMsw68kbTI7i`FI4m?IlHz|cz7eD)01tPC- z!?oxQ1!;kbZ5aR&nyh>j0xDm_jjbF>sYIj(ZgnFg(!p?mY)Ni|WfWYnw1~rsmT8>C zvb(>G#l1%W*iCQm$XxB(wc3wAmRgR}2f2auw!k>*VZW^`dqz#;D;>w+f@yJ^qs|e~ z$PQsdH@FTR&^ITC@dyBJnBRtj960h(D5JpXljW0T;q?9zPM6NR#_3=f@y{E*KmYtW zbujQ5V5a#mty7x_Vumd=Nj}qup2EaR7g)g5+0? zi3on|bo}3Pf8PZ-BL8xJA6MYWKd5<@BBrFpc3M9;`*p+ss7wU@#LEo^#ZUoA zwR6GEa3y6$Tl@!=Tv^L*up+FR9D60qe2FUTgKg*W>3y#06he;gUevtfWc;rJ$J3ifA>h3p{K6tnTTHjuVLOB3a1>Akhlj3)POcLTAhFGwZq7? zTD~n&%j6)xgjAA)gEGQiOj!YEFF2*Q%dL(bo2O?%7M2dX&p_HsK%hFwW@-v@08 zKFw3#r1D>?3{{03h7;hp8c8O_pvXha7eW?e0339r_2gvg79P+nI5-fWK?kOfC{(%RMQF>5TQq(0t2TVAguyTuA$Rff{_sA(jl^=C3h;hN*EME zgAjwk$@8Dnp>c<6A>YN5W}$#6QFWYS3gazpwWi-*#*3P@I7Da#UI9Qi%ERWdIsd`x zak8saQ^t&N^lq<{U$~`$q$syc*?{`kPp9zkeuf*i?AYU-Qr{7;i;ZHJ8A436@=sQ%{n*;;Nbe z(XT!~A8+&3P&v}|Np%T(1y&acc$c?sfqq%KHL4&~ExakRKMI`qqAkny_{O;ZroLl- z7y$6g$cp|li-t~A$c#lWM8dKB<5SVUQ|<%#G{pkmY}1m0ylXdb zoC5!7h)bbZDGfSngv;^(x&0oEAp9%2B*3$0(@X6LXr28ad->>WlK!ov8=zdklmf~D zoXC)P+!xW22f*maJivF{zpUYq^oPejK05F0?c7Tm-OHS{!tie(z)c%eI$AB95{k=-{xjJ6fmJ))C)g*)~*fNegsoJ01%Vv z_uo-&0uWj4=u26EmFy8p842g2K-bncb-B@XAq}1Y(04<%%F#Un#h?NdrVW6yx=|j& zIgr!PG^>Ie!&I=S`?Bb2kA_$k0^jlD>ek@QSYU1fW2IrbSY35N5{I^0&^YoEW6S2+ zT#n2IgyXYH7}?M@MmH4qbIn$3I)1Ma43+>u=>w_B#;nGzymb&kuMWZ|#1sCG1E8sA zVKOvZ;^ZtLk)j;fR?B)EO|kgXkySYiihAU@PMrY2UH~``lq5tpIQsztWxl)Hg%jXi z0H6SQK!(3G&euO&YsU8b^yxSO5Nc?a!O{K(a>I##4<3LKe$W&EHpkbn1}}i~;4yGu zTmuilZ(xwI&rCyb3nm+ppo>A{n*b2eFz3S=hl)5zW+;xsdj>S+H3Z8sw-O{a))?rHd41g#Ci2;s%AoDRL z>fO!&JfZhcN3-lM%w?h8{QRK&AJupQ8sygLNuTtXhA`@j-;$e@mdpSX17+x&tjc*Z zq)w;0^n&cnbaR|KLZdg6MJY4m16d-LlL0ST2@_24rxA^6OB{jF!GQVU4!^=EcazU< z`fa!X_HV!YZmv_^fmpMV4t*>s0^OSsk#)~I=WAD{q=u9lj0gZik^x_?nBHi8P1CazKSXD>zz+`kR3n$^n7szZ2`RZC6r63 z=UR0?`vU-8m&BF``1|q*t^5jwmf}zNFnPNo~RwB$?bOoN>-R%^=f} zx5_Wo-7QUEgBQD=zJl7}C{Ovh5h&_d~iYgak(rd zxcfkW#9c+F!K|iU;OiHkwjaMR4Cea1UkG|HoA-1B^a%Li-h-5Xy0*5kHX*#jZhKyP z?!@2{?Qjzas!}5`5RGK#gj(UC2^={8h7Nx|?yV2Z)Y%EbL}Up?nE2Nmch@-I#%Kb$ zetr4_H1ZC(rBnjm`l^S2IFWS5+%ly!sVf9J;_Nl$efOQ(-&~1q;~Jw9)CqTjZ?|}G z6rQ?ydOxZuO8>SrhLpZQmq@3`l9yk7iK|r`Kk!QGEGAuydb%a;zxpZ3OPv6y+*G;Y z*xaPjVAaYcQ(P7eJ+64@3B|!U62beg^e|&|!l@9BKY@irK}V!|)Ab_UKb1vf5gpx; z6jwpBA87-YBSc5VW62V?+sV+mHF)>AqxmdAmw|oSW8(ZI-2;MOQk_L$# zm`iYO{EJY8Kggl~di2+%XnB>RIr7+trFR$RK8<_Z(W04hwc@qM>DjZ#&k{Cn_kZ{; z@$cpL%l`=s1S(WYp>*!cFwZ#&x(q6<1$JTT0xdLd1u^XY$7zp#9R3&#uRh^UWeJ+| zEeSwbhy>X*7sicHtY8CPt(f`HBSjMM+St;NS#eAtxd}K%)SA@m3>kWbF@9p;X6+Hi zHUXefl%HQBS;43({2{Q`@*Q)wtq}$1dY#IpRywb%h0;Mq{rxz{Kz%sfl*|yoOaLr) zb~jY`4g?f442y6KfT}`fLDWY1O%y84z0NNQAa1<*=Kc*kTM&x?3&_tXNCF4aC@KyC zFj!E^Gs@8Ki3afz@F^65->&`g%P$~7q<`iqkP9&&u=!FYAnQy9_ zXC^zC3*F>&Gok2%^XqTCFX;=taOc?;$5D}*z;UgCgUZ7f1UB_cdD0F@1t=O^#`!iw z;OOZ5i67>*T~3BQF2WD4R+Y@6P}Jpkd{= z2vhJ(Dn&~1Fa*Gu1IM@wa~1w{?B-3)e(CY415#rRzB#rd2S%eH=fHPwrt@FhAu{V| zKmi|L%U0mov;n&%iS0hcC2RGgXtndoBBlO^lw-XKWECBGgyc*hW zk+=eS5M24`)jxQA?WOnm%C2MExpnt(26dhUA3x5zmY&6In3~qNH+f_y0{-Xnci(^a z&dDwbS7d`rpw~$*_y#Y4w7=Du5fiDYwU_~U6KqlZQm_xWoAwd>RAUG`f|V&X-I~TG zxS!TIk|sz<*$~y?hlvJZA|Xz}_m;Fs90=Ud@=X9_FURUN%T^?NLH2aT;rvdaF;P== zE&>#U8sG#xlI#??VRzXh%*cDfE^dF=Z$a%~q-#;J!x|F>NzYw_#RI=>BZf(SD`hr< zVC`i-G&5eHk8bSWP^St01A?rq?jHU*AOtMG-XQYh_kR;6mi=^u;QPRD_cN}L{Q22+F~RbLuo~FiANTpmIiA~bXKdXP4K0(^A6ey zJm~dzB5E;HPISt}k8J1#H3oA7zDX(cnAY2=D2*GNbw}n@hK$;TXJY_Vc0x2|8U~{u zj=?Z;gW$#4%my-h%w0VRiC%-sMr0ZI+Sx$pU%obvDTDGiFoKJzI(2e(Lr{a5_c+;;?I$L4l!;>&j3XYDuTs?yscKn;MK-#&dw{CoNR?-&8U z19Msk0PJ%=FglZNAR9&j3Ed9DazZ{PyVWQTCIB`nPJkxaYw4f>uv6~02HDdR;R|R~ zh*bP=elRBhbVfHTBul;afCMFBt+YN)B5M*F6y~YElJ1P6mvgR^3a4f$3uCUj)RI}V zrmvS{rYP8!2GABq+JZXL@zFTq;aei>tT~cvJfW}K6>p4eU?O#e-)W&3$z0`fcMmH+ zvGpE4J_oH$PdCC3hWAs}gH{j}q%+%L*u!dpKY@(xSv1o{h43y zuJW!6d)~kI;l)e$zP)(K!S)0^QXx$|X+|KRG%(v4#iJE{h2O{J-at>IpzFarJMG&eD zAOON;y}~!o^Cz-W`JU6amN*>V($qI73$ROx^=T|h0@pie)RNq0`3-8> z_sDlnJ~+}L!atP&2MKIjup?2&T#2rN-_6;vEGqxzry+XYbTW+h-J9{?9B2?!EGp_j zV1`ptH0^M<1kXAdVfTe&*$SKhaEA|$NeCZU2EB_f(hp}6IMcuE%g=#ldHdt&m*apB zq&YAG5KeLMi;R2&qej2QoZr_X7jL_1EWGT%1W_Z5P*9rc;-OQA-rV}#G)OuEa>9F& zYeCy20Y$NX{=50uY%|N&v(}IZR;LzkiM%;nkW0 zt^2yw`-_Y!fZjF6xvcViOg!a)y1&;DS_4<224jF@*YQ&6pcrbU!=SHySbjUWj!D=k z+rGP}cCb{y00;owV4u-2*JKWXOqBsS1EmY;;GXW+VSS?rvZj6#$s4%~^BZp%Gf~^l z(H0PhT^|5A4FIfs{yBqTFbeV-Somz6QfI6Bu+-wkH4T6SK)fM}faTPH%X}R_$c*p< zFx{;w5kV2PopJ zc>IaY!t~fFY2kL=pm%%JT_BhQZ=cq|@OBD_Uap?D2nNtb5Cq5JB$yz9mqGv|Xtp<) zr^89t)zt?$s;U%@t#Is%8{mI824~L6`_bNoqZ>Hw!81%l(7lhTfKwj#n2;L8a8v~g z0H-|N`Q~@?)0=<63alwGV}>^!if?P&=4@7xc`QtDP6Ira^T9b1wQT?~?g9Ad1?CG^ zA_w~Hjug}+fmv|}CXmfhSPA3~or>5OYN7Q@eMkntQ(<|d4em~oLhDT-5)=U5mwtu- z=&H;hQ5qfrvsgg!AQZyHe*5@w3I@z+Wg;>m?}gn+W5o`DH;&ysp2*NgD{f}$7*jquGDNvrs> z*lUAG0}48D%%v8yRlGZwudNnqM(1vKHO=80uN`;dV5K7YA4)N?c8*xM(kIA^d_ur+ zrPSTil4E#7gJK!0c#k^GCEq?+!(Fkjr&5D>xl%)}0^5s;XQVY4wn|$v1<~*aA7o}u zABr(KH-ghv(pO<)|3+kLVFV;SvJpvG5Q+a>=}2DS)z8a!3-7=G+xwWy+;}AE-&*Xz z=)$xXMvs>dc(i!HA8XNs$q&}-7YIjsH-(+9uQe&=1Geo6_#@=atVa^+#GZ&g!38h^ z0w{u0v60gPhr${+^xW_iWz8OG~r@GY`RqnH&O%e&@b4{?Q8p0Gu!noF(L6nu=mzYhlO- zOAuo!Wa_3#;+y?b1~>B_UVqy=SrX z+QyqMdXJy&Y*Ts`sF%Ur<7h*F>>%iEgy&p-&N=qRC(rw)YoGkb2B*O9zk}(lm(yRZ z{Sbu_OD{80$qfhx`!xRv8)+XQh_xaY8sHgMyr~8>Ulv?_1S&*=s)8 zl}Q!d26?mF;B}7NaiM~1o`fXiXAw+~PvRNSCpqe0Si8=-v^E#*zKRiK1ttLz$@vJ& z8rgs<871oc1BlE9PNT9&DrW*2+Kwc>!M9qW%Ui1Lo*H4bo5x2+>=#GOgH)XIP@qkZ zKYu*V@1SRzi8V~fDX7P;urXY=HV}V$su~4^Y#Htq|6Kvh-++{djd1D({_MB^_5QkP zj@0fJAqchr|MHY{u=4R=uC2dJfS4j)x-9`4!OCDG=uAEZ@`TZT71s!ILlE&&g z9tbt*Sb8M_E{{49RnIm0DK5c-Ahu!M02zQl+^d@&nGC(lWJvyuf2YO&>YYgfojn2x ztC13ua`Kz)Xc%q4x>VBRB5nkAP_#^uE1o0KA#-?`Eh2)tSDT2w+7ij1dDb9P`+BK_WoQ0FPxeU?3oP--v+W zCLB+A4&2vvfMfs|%*RU70`7|(1TDbyzzMoi4`!%eJjW>qkQ*;o-czye0{Z+@k5kHk z1_~~wl90>(68kX$?%&!JAjKZA6@W}xg2l9oD2bJK zH1CPSt3pN7!URBy0DtE!sBjrPIeq%->C>~gde%+B+wVFW;bwqf0H8TwMFC!Ppx`Xxub8Z$z1IksTYxh~bc}$+zg^yc zS^FV4lVd-kkt|43x-w(fmL_kp&#@yW080Jm`?)N_*KQjkGS-fEeictC8&x`aaCPqWerwH{Z^uR&dwBq<_PX~ zT!G8@3<02e=z8f=L#!%trIjuSh{ENN>#=%_@af{+POLh^t;5rl?u@gJm473YGK=t0*4J>{WBkaGVfN zk55h}?7Nk{RE?k2am7N*D@VVFavPMACA@Q;vBF_U>*(+~qq1ayJ_bEz!mw6_9Ei_; zaTSQy7cSmpFZxuv`i&92Se5SUA6w#Fn|^aD?Z4uFdHcf)fAKJA1e5~i5-XGhnMgo& z5t0EgY`_-;dk)1)X5eT)N+uA=pSc1%3qODRi%wu+;7UA`Cz!Ti$z4_g02j>*%i3|@ z&}WiYQkh^#4n%=4=f6{z_h0S-)E$a5V2q8lhj0tl8+v-m%N_xL^Z4f@A7~KJzz-7w ze)Hs;oe-EwVGMtNwQBH>yKe6Cm-oBwhG$dSI^+C$_V6Y-Mx3OOMvB3;gb>F{f-j= zm3JWhUkwu=$&X^$OEJDSkDU!J`VeYYXrWuB2nMw9Doi2-Knb8(2y(3p5C{@v{j(3> zzefm^?ZXAZ0za+)Wg0D*Odo8(QPQfY2iBWSBMAV>%QDElGejT>khXO~l}V zCk7<&U}QcW!K{wMV(k3r8I=WNRI)V0)oE1EB<`1*Ji_0S6ew@qT54`_mcsxz&r~V2 zYz~}Pjb{CJYULfu0PuE-YO%PbiV5&Ly=N* zu`lCw;N|$18`JeZ&wpv$58VOSoFb{#8`_5k3;RB8wXe1(N^t*h( zGocHSF#hqHCt-64TvyZ6 z+ldI6@c#8*+axbWz&s7yj>mtvGaK-~d1Pn5om1aq4}R#zyaK<={k_k*^J4LR{>cq0 zTV(bHl=ZQ>my4$Xuu^a@Twi)TM?bnM(c1vX>8_7{k=hMz$rMI+Yn0=S4;ABtBHrj4 zE!*U{5>hfl3~VU&V3=ODqCt?`q0WGi)$}3{pJob2M0e?4#-RMhYRz+^=ED&!!OF|R zVyUd>E(bHnF4t>!3UQS~XkobQa0S}g6pw%0t(cI(T)RfA+Z=|uhW6==hP&+)n_6LG zTr9%}Yi#1wkT`Pk@CXxD@kuAy&p9&k_ru*_fgyrvtoG7eY;XnKVKUw*yZyZa;NuN6 zYr11E94vXoa@VTeAkYDRc-?U?L4jcXec((cH{1z{nY76dIIJeGZ_zO#nn)61Y@d*SIeu2vr1febn-oY!0LiZeGDLioqWZMGO^yXAoVm zOcF#tw?>VN6wol&0AL8ft4=yuka77}gBCgc*6H;9)LGH#pc?A0V+PbI&>>!1Te0PH5I%8r;&%ie_hK~xqz(U!#|41_ku$Gi7;@&{TYvb{q&>% z&k>d7xWJ1}Ms+m4hrbko6<5Dp7=FscmlRO@?-fVlCnua!V6J%XqZMQY&foXmdr$M; zM@FqfM!fWL+Gnx+=IV~%i1QYE*@0O}KI6btrAn_{c8tC*fi!+xwsH8fPJsGs=EL;# zwEiR__DIbU;0Frx&? zMil+sQpsHro`cz#?t{~#=XK10$DQ5EVRd|P?m&VfD+a-$~;teQy=`~$V z@pOehdR>6hkn#`faIaqIx(hZKEAWQ^zNdQ-^b&#>vB6q$Y5tWwdN+geHFTiqLkqBe z-fKz_jeoW249FdL&xE>>CY1e5XB=l503fQ<*CP_JiS%gwTPNyGxF%?vHaf0~lau5^ zCgX-SzBGhoQN6p2DFr`^63n5Y`M+}o9#n0dA{BIFQ}AAH0L(UEMyGOIGaDkW?-{A0 z5sNiiwNh}o{ZqfBj$z}608gDDRLxwq3>q((bvf;2m>l#~CIz0R3b0OjprLM@v*Dy{ zA(#~L=klKnRZlt#Xa#mFk|sg70}mv5;EcyV3u5?8C2(pD&b+~6;R=z>ja%*%0C1b2 z_vedZ}?I6@6*-uA6rvR80uD!CttsHvq zJwPA<(AbxIsy+6yN!u*!FKCSWhc0`KWlBOyQ9Y!<7-^+xozwd@0$#T9&6D3{?!=jO zWbdizp5Lv6`6e}_69KEea@z9{yXQ%@J_Tlejnh>bVpKw!R=TwhGii2?2 zX#g!Li=d=b7Vg8XLOV@?r$mHdDNCWG^a5ql>uxyGMGAroVOeMg=?cCS;;K+(UL2uV zx)PnkBQ?c8tHu|*FH=tON(ou6oDPqhr~prl1XSGD9Hm7Mu>2*ekYiXD7iX1#p!5S+ zDE4?&{BB8M|H=TvNY_JM^Fe31^1J6W*w^<19w$${Lte%EE;trU(fc_*;wzqH@I9th znpS?cuf^bs@pctFbEUh7&B%8-2HuqjdZd>V;GR7nUV0in5GVk71AIU_qL`)T+ zJJgXBGa1qq7(43oCr*qy>|oR@?lS#wqrLz-3l-b()vaZ2#Fj}@|C~q^`#}hLr@@T? zLK(2oW`mO^5W8;G6>*5m+8UKrgla`)Mof+??yxSphamXnc)J?Y^Wfl@Y(-KeR>Z@^ zMjU%DLMWmvbIc|XUiY{M)A->NpvJz7{Q$y0_g~~I0fDI@PW?&<*`JO0(<}z?LN@f} zx{X22=e<_wP98&kHP(FMYTu4~eG# zT_Bi@BbN`Y_<9)HnL|kp7_0C7m?AIhivH%7rGS>fI2bx;kcSS3e)8hQ&W_-e8nYAp z{`y}quzmO2&O)A#&F(<-Me3%63?qk(RK{-_+y|YNqO6P`!GYTKIPgV;o1k1{8 zVe-8rnahrP#>a%RMSCo#IdaP(`>U`uogKka-Zi*Fmq#?x)m9~@R#vk<4G4OTx5Hww zv-29te6Iln(Q(w(r=rh>@&|dYgvEngFs&ZYS_=WYYXHELhYz0^>3U~`X)j$E21njO zEdKC*1?G4H#Hfd%bGYD0{9ZZp;D4@c&{fx%?xx^}JMi7R|G{6M3jnVJ!JvBHO(WcO zT7$3a?)UV12wsScm%wK5pXR-B7P|q(9_aShytFnmehC|{0MVXc#RqcTCB#i!n%Sem z;6W;;-=G)d4K|8U_Z%L$0fz>%CT)l%NCN{Jk(R2`5mV#5goZeqeTUrc23)KD|8%|I zQ`PyIExfS-*lv+&+^vuxaE9*fhD13`BldWe;(=G+|L3(bXp(z|{SXkukJ=+5%vD{ zZ&Fh9-Yh`YE1fX|6!SZO#!VpS&pZ5OpHOfc(6^ngfM2?TyQKMd(hQKdAjd-am`vg? zHhvp&^wIq%{&zGLp^v77t7t?!+TjAyen}zt*L!qg2M7K#tbqUVUy{F<24AoI{uNsJ@qPG~H_j~{ zgv+n?=UGNq4gYb2!ja!8^DiRpfqwM7MU+8JBpILzogO&C-_MPa2>{&)*GP99ae~NJ z$m-60YDUoUK^XwBkVU7aVmO^%Fu_mxdPFK;YOq&M{*h+6uOU{noYKN?>WaG8n32#l zrR|+6c_kE!PF8cO6J}2^OEkk|(!x!gH-{pH{MZ3fM~Wabn**ac0RSn738IC$ia zc4f!|)Ch@R0dVs&MMoz(wtQfKy&8Ahl{nw-0^Yy2j5T1&p zwh!7}Y<bhnNWSR0}!QP?WO<%{r3GAkCo6pR#*bE5;!OoSJ4?(z8-7h~_YyAPy#BAc{3;tDiF-_Z~p zPC!yX@Vh;0z+Zy|?ukv+9#HZ4|F;47Uy|p~)K6u4j7G$)Pk#<{Y^c4=Cd7~0$Tz^U zjwz)&>u7dmx#(ZP91uY0;aA$Qnclc!(oofvwPS?5KZK*2wXOIt+iD zZCMR>fZo5kxkEs{Lw}(`n8*igJir$_=6acoRgnb_V=r@|IVsQg3J%*RO5vZYP!QoF zjf6=)VzneW9lz`KS6)FGlGG13XNC+c=M3M0sxRz=Y_o)3fgou8Bz);2gyl!k4;)#i zcoPhNBdgru9g+Uw<)5m5M~HPtj*P9oc71G`pXxdQuxonH@y8372G5Ul#T=~Xj;P`1 z@6dMzPRl8u-;Mt(Fy9eX=}`+JC5Qx2k@&OiSy6h5M_33Ns8>)9Q6$Vg*iSe0k@yiFX2z&&j7{k?Z^WBF9A^UFK|!v55zAW0$cet zd)vrXfMRdDSi{QiE?+pRdpB`By|ZHT1%XCQevWQ~-{lC>l7kunT1SuSH5>8-b}zn^ zpb96T093!J7IbX({{H3P_f#8w ztc(be-VJ~sTZ;*4*MNXmg8z8{ZZ3PlXIEbgw>7c*lgT+zJQj8oB2ko6v-^Q-5)B+@ z28!lt8>efd_^44C^l3z{H7en{!y z#TJ~9veSS-|TgG;|!l=$oP>xhCu9j5yxg@6zqGzc>Zfndnn zxoLvknDq+c)T+{8qWGLzM_TfACDRM2-Po!a;1S{SEJ`p9Zm zOujF=#$NbFL?v?ETIvAA(XIXJnB%K7)K@y(`$_gHBV(jsr8Iv|o3dx!+&eh;+{y~J_$3W}O^k@v;@bk-;Gx68mA(u@bF9%N)VI<%HCO3T# zvM6(O_uaetgVJIUAebLNytNkrH3mZl`SGuIea`>lhPanDfzQ7D)-V4L3ivNs_5pd{ zzkGZKe;F(ILNw8fb&ih5y~f=?eR54Zz(3XmfYqA4m21*+ubBgGZA6$hr&o?sz~zse z>Uhh(gY)=2o|c4(4En9H`y=gB{xG6p472#nV7KY0b zm)dH~8DU_6Ah=tgk@)i^|sPGvX3H4@P z3YSCp76hU(*XF10{uWD^i`C4SOEUe7jR2U%t0^%R2IzA+Jl8S6<%`t z2UwtnVa8z5?x!1IKpg)y55X#P0RV`y-~$wef59?!WuPwE063?#1LbQWGND&JndERz zMJREw1ps!mYfi*6utV9Qk@(`2EVLnw@eBlSp5Li3OurO3c#{h|h9XRNa7WkgOE=?Q z*Yrtr{VF3yB_U_~nTTNN1NnkXMC~P9uIlbXn0M0|StqB%Al>Ccq%pp{D!(Ad<}o&b zAUkV*L=YHNnyN(`0dbOuaXIHR55P`3T!ZQQO9oWWosejmj( z91Jq={S_tR_ndlqW^hj*Iu+lKA~XNYX_agCopJlQkAFk{2<_u|?EbcoSN1FbSB||r z2S*boGN3sFA6v=FkS<37rf+j_qH z)~~)Ue3<&3>HF6+Gz8K1)9o{4N!a;Fq#|O`_ScLlnAlY#P$U!z$?RyUktnjK`xoGb zfBYCKr7H-*iVlFW@ukKzaa>_A%~@t@QNJ#~ zZu;QN-M}(G_qyWJ@%WH2M%?;)GA=mx|#^5z`uBg_?wg)UH47ErkgPUUBlk_H7p>&FTnvV)pCe$HE>G zC{y5HB{ldo9Wtl!gTJ0R?MZm>bXJvlZ%-ON!0*hU0stL=AKSm^Ka%*dEsQe*bQ@gc z|Lw^{*sX$d9g@3%IR{^M;wcw>mT)h>6q9esSnqwg)g*62Tf(e1I5ZP~bU>%`qc3|s zxXFiD;O3%9;G)chi2@>NVRZPl9aF#z|7eBz*84xs0uR3REm&c`+_MLCa^TncL1O9! z@#BW{IIs_21aa?fJVtSuGVWAn3c9%a_#=JYf;vH-xgg;%vg>QT{KKz)a+LkJ2%h(P zVfa%!u)x)-NV@gqdnhKRk-`OC!?m>`doUSU^sh(<$a0fhf-*llH^${3LO^Fhs|2JF zr+7JjN?i#TaynN#CC{HD09jbn#0n3>A1X3&{99(x%^-C65xvTl9Yb`kpWWVf}y<&5og8kO2Y#0f6hg`(=dc z(po8!V+dot0f5)(Yz9~An1E6WSrmOp#I+IP0;!;4L_1g*x3#si<&OhMz5@JnvcOL7 zj^*J%8Z-k73ej+sg`-|n>{TiZ<^dc`#|Jt*L5D3B< z1_u7!d+)sjfU|Z8zLyS0Wc%>@0(clsKHsW8vd4E&{rU|+=j$G?B; z%S;A&`D*yzzx6Wn`&a%4;@G)!o407QSxnG(P^r{+>0Bd%J>qQp^I9Tcy5#sdZaV&0 z4gyyrSp(8A!0%x5_(9^}U4+;Z0EuxHH1drhYq;8tLH7v(o5z#rktbGSyQkX;m9!O8 zSrXD#lx12}=nEHt!b7F5FmI4NPT06i^D0?&ZC z>^+YB3am39u;sbI25jHIDc?^GBFqLX_Dq#|O48N@^2ea994pda4*&!Uyuo>VxCue{ zx7CGGBuj-a5QacFp_kbSvQGTt_1lv*r@q`tDF|zimmX9e%;JgZe-&22=|~Ph2RPf3 zt#8i0m-L(#7ghqp1~bH@=mUoi;rvbNuOGPEFn0EGeC7yT!sG|1%R~oT)UX+x=e*l7 za-Cty^S!RsEwLc8pI-wskrKn|>v0DHq#NnoaZWUZ4?Cc5_RhyB3?A5J2VY5b=MID+ z=AESV1>A2Hy080zce)IIwmnPaP)~4g6oeQ6m$(k7sQFSqS2bC)HhskB!}k6~1{V3? z7){Xvz%F+q^+tCIN=B&H$hsZ*fbr)HJ8B;$!_PYgBNT~jENxuR?5kEp;ECP>n>J1lQqJUumx69c>59wNWYhKStau7B`occuz6M9?48y%@-s4Z@=- zB_T*40JJenhTfBlB>;>i->?4tm%se-HBRN=pe(e(ty}|uzn*SJv=49^E&Q8qkZoY9mJTd7_5onNP-n^kN zEHixB#=oM@eha%^7lkw{Z6#}u^C?GR*)p*Ge*i#*<706LHm7nVMi~?wXHYISI+isn z9nnCoMiJkU3|Dn7r!tOQ0Tt-bh_M*FLRLAfreIlejKn$lf7tM*1LIf&;tGvLN|=0W z(V6ZS_{VCYIjnZz0on&oz>x#MtYrr~jnoQH0HEDKC3^$+q$JCHsmfO3Q*G6p+M57> zufI<01OVm~5l952Wu_$;3Hz)8RXs2Oa7nF5c=mWpE|)lq!#Nz<;kHl#jHd^cE!qUP zA{=$eXL5{&xkFKSPHE3dzK5lSoMwjitiZnmghCz1d3c2|azI9yk#?6OQ48=v#FA3- z00kTi5jV>F+1|)Hp!FJ1x3;vS*p=z&&0E)Hi|M7)4&YcS#oY(#-*wKyH?gm4N^TSC8NU;F`9(d2DyK^~=2J2u^vE(7LqFDzB}r=#c9-2=bRBN5VS8wql`U zJXXgti(t59bPCMx5Ok21@4W?aKP~{@ zOVEe}!H_@B2>TRzD)5v28BQCrKkB~@K<(R=KK38a0MHm10JyTJ4}D*%z&yq+;3aPU zK>Ol`?WnR32z0hcXZg^w$^;XPwP351-pf&+)a|1VBOrz0qiKD(ArIjXy2A_@UKj-g z`X1!&Vt4%B0EnM3Lo;=B*9`cK0Qk#q{rJaDyZZNEee0K5Hgr}H^7PZ+{N`K#{3~D| zivjlS=hsN9HXnH|`x=FQD4`qu`CU|T-n}aTYu4q4_*(6su9a&XWmOaRyy>28TxT4$ zrgV)58xIEfHQsf&lVag{`4Hj;wE<+Z029!Ap8V4u6${l|6!a#uQC&qaySrr&}rNlsmu2j)H+Bkmn%4pJWDPLO!Js#sS_@ApZKH zh{eYi5Jhh@Dhyem1`H-R=b9ukzqt-!;Sdf#95an1gE`K-mG&$j8u;h{d^LW6B+(wz zp;SE%#g)p~ty`O9h^3DH5}eM;h%TkVO!jU->bS|0%bR3z(TsFfL=J_)8iDaxm5{;9 zHVV5?eOGspt3#GS53U@-b=LeL+FY+LMe(}M;^MuJj2Ym>^x~BxBS~;}MvalMH(US7 z#2DS^_y*f820J3(*he!o>@eq@htJzL55Vs&>|&s8(0ofGf4Y+6f!rCjs59_Dn(ukf zy))fH&Rhtx0T=|2~Wxgv)G#6(EUOcP#BFeA^-PqXN+~_9R)2@%RuAL`d$PtQawWGreHBfh( zi;A^_5K?0mm`&&O|9L+c{Ea`Fo&J;`7Y^PP40`hQlCLpccI3%(px^??#iey&{Zh-YtV5V01yrs*WStv5Z&SdzjU%}G%ggsM2j?Cvq=6T7Zx`T(qjSNV_Q>7AvB8tm#f zwOb{Qj%W-PU))KVTJtbR?}W>GB$|x*ONn2j0Z^bP?2{=_sW=^~$5ctktj*Bp@uW&5 z6@-xK&Gv;cQ0u!vNgDX=d-2-$&PW3h24eVio{~h74nW#9fk=H|NV;%`Go_KWuT$3ds)Qs1LlLbF{ z;t&QFCEz7owL&5mnCG^Se+(*rl$jUD#LfBPNH_%~MYI(>e2kS6^@Fpe8kx^}NWEn) z028R13c4PVK_!DftOXgy0#hK4CFCHE1eH3PN~$?!45F3@R+C}fbTAzTd3_wKhaKra z{lz1=$5Wj0GPjV7lgDtNb4;!}!I$I&Y`_+f;i(UqD?N3kOk#+Fkuvs;Z2d(JHL|w= zlx$iWXfhlF08dev8Bm{a5C6a>b|2}=1z#N=1mGT&C!IpNE2U^~KKZx#Z7$a}*#UhY z$@n~ld+=Kv!aYd$9u9n7il|er0Z|gHYv3(B+uC|8XEd4O102Wc7;b5T>v{c~U0Ya} zz}um@cVb8rFq=T65lcEI6e0~~!ohfO_4ShjVgop@>5x|vyzSrt@ci|d4kJ3AIx%EZ zU=23W?1O{zk9r8Ke{NEk^*b0J z5ZK`|cldbh{_D`@kKgWg$LxgDvV93MIFs7pQaL*K-t2?(nt>mX7jmCRQFqW|?wLN< z12gBvD?na+aQq$Axd-u&1aSY%c_H9=hrpcQ<$nS|X}`e*_f{gQ2z{TyPtf;+A6z!B zT?$*EJ%Myc1N_br0QaOtC;U5?T7p}nCHS(>hg9i}lZ7fc{^X`KeEy;_1o7`d4niIlU-%fKjX03*;| zp()iW<&dVF(_xxY3p(6$N|RAYzPx|*GuJVG0CYf$zW`jU$MFkQVlIADc5QK0lYDbg z%SUA)0QAbbs#8cHNFMK;OgI1)4wmoaUnZm&>Mp=(m=j@rt`h>@=J!ejR5eKM!N)u|bpXr~tIrYf zQZmXRBlS@jK7r!3`mea2E~|_wIS}QhQRYGvpfc#wRX9%P?A8*SQv;Phh}~4 z)-K=+1YBQt?NRg|EvY_^fq$HME4?=%jh04q1gyB{7>ucw_UhNl^;`H)^SKrFrq6*` z@$=k-yYC``qJ=OrykH1M02ZW>n~`sIw%`45YQMyIENdT$pkZ)?EuNgyHTMz#0e=@h z{54KR1%Lhr^z=!ubm889(?)d=GbK>;b7w~(3j(~c#4OXbNG}DO9ksl3y*V!i8+u23 zRu5oFxZ>>}ncwV8G{O=6h=Te_uGjaVPeU*OZMKhr&NCE4`uNU$y!03p|BD_G&%lEW z{ZsrO$KSq`1VbsLZ~xblV9ffCXHJ-X*>m7q=JlHt#iJ6!au7Bqu`*6QnZ&=zbLvXk z)qXP;nAN6Vh6^yvftS52yu=up@WixUc80=bd!jF=I0fP0WxE9lfD$K^sIa)3Hv=5p zxKVkc`n5e~Xxm(N8{+=?*91WDzNhNy_2ad}i;{au|31I_xyYXED&}W#dls{*M?JoW zV*Aw1cI{8hfQguw8V4Pevvamas<_TOY25RP8pk`e2{iv}6iCKUELo(vhUX?~4;sfm zbR?iE{#3)T!?hp+5Uye==&KUbGkzv%#TsdijJcL#lewN{6wa_Da)3g#gvdA&fmQYx z=6HH`qe)T%$5CF4fVe3sfsdS;*vsO9Afr9}dl3>BVQ7Idn%h1z!MeJK=@tYE2%pfk z)Ig@!g7|u*Q8U-3jY^18XfQ4Fn^fRE*Oy?!WPf0cn57%0)W3-XylM}lu%Ki!M+SE_ zHz-iE1m$+qeYVyS0GFwwhy%(7(}$}MG{Gs}O6KG{iTr8fM?$z&Sz`y>u2&C1bbgq{!;oIp<;DIe-Ghh}DkeJaQl6rNAkKtUf94F>xJfPEx_ zvx5tQKheQd_{(>}JM|F=nSRd!I9|0I{}&)T%2dh&HQ^rw4#en@=&*Q?m=68@g-c`V&P)mR=vGN#`~Gqq43 z)ZF9sR&7Sl8WR8loetU(bB#lAOvO@F<9v+|SAgr0&-Q-$Bl2GTX;+vT{%SKA%;L1h z^`2G6J9Fv_A%t@&Z(Wlx!f~{!tUWQ+M%M!mGZvugs}G357(xk88Xel07)gQgBu#q|ADtpDS&3m^tB)e#GeA+3tWH1_QRmO_z*c8vD?HPOpTlW zgQ?mRHz_9|*Kq8;&nRg04Pz$0O=7!c}Yr#P!RsRrN=wWK&?3O zg|6vYJhAn6VhEsj^}PiXnT3c*Rb8f%J(2s#!XLCFp%H|!(1=D@kM2uSKqdtCmtcVz zVOG?L;0!gC40}f7uV-MqzI{Z89>k9M>3TF`&TAy*SqVPE_(%HJoArNO>|!sR!cJ2k zX3Bi_1~8qtO;5vE14kn#-KW1;>b1(-TUx&W_N4_QSj& z209QyP^S^t5nE$Ej#EI)h$2%JkS|Hc-=wcUlno}ar^E3u5R!&C{SNX!BPhkZ7tsha zA&7t<_6fo60r04U7|^5&vqC8izJ$Nb_%e8AFeDFfz@&hH`<>rg|GOK5mB!!L0InR9 zbNRAPe_069O5_WLIK@Rranhx8#J+Qr@q98%%-?OzoXi?TT$fHhcrK>ob27(l_)u6` zs<)2}pk@NdyMn#iMthuTiUtB+tI^GxM)8!xj5%-4Ahesx-s6pIfAe9wawY(h>~Jh`<9~r1b|a&5F(HT2h-2uGXqH%RWPCnG$R-j)+MkQX6sZMnsHI?zDGRY6M4F2->lsJoxGTUD z_iVbEQwy8VVEAVsuZ0J3ID^ZnsA=j-Edj7rd0yo*b8gtt#3%+L>D1=~4^e`2f^+kU zs(gyNJ7#*d&XIB5hVG^|_8)0C$lfQ2JUwmr;&Bs~(=9UIbXfEKZ9d)Sy7P9O)`Ixz z@8kEm2m5Cy))p=t01GtTlMFmW>35By$kLX%;e*N&HicpLyXsaDv|G$V^PQzrTE*z? z6YWk#V9hX6|K@bv%C-yq+a7ZM>BNDK_5+-I`$YhGMS{;W-!VdR*Q=9`4)niqM07;H zQvyfYbs9&D^zoD36&w^0PM68nqdySxISViYyu=ZG zC&$ESXG9|sn$HA(8kF(!?jW4NP-f^!C+6=C$XU0DDm4jt9D745>2^%MvGMZJn2Vi< zPv^8-=DJ6{7VNCQ@fyv5TTk{z-=qHxWo_iT`vKOgYfoN!_<-&(vPLXX*rtM}3hJ~H zK^n*R(l&u%;)t@lXom*?{G`TnuWZHTvd~1S2Y@s}O5<>2bn7Oz7mGz#pvTM{edvDH zn6BqwK&hb(+Iz-g(Ea>0BqzM zuu*5tWtkcAcT_Dls7;vc@N*pmH?$x^AKwaTAS-_9Bb0@^g{fD=bUHVY3o{y)13s!T z5g$Xt3}LQK7H!!6)Cd9uTt>Jj zaKfk-jsvb*Kmc6W0|Gi{aWFRlj|)yin0?hgp%8q!0uKzb?`&IjZ;nT8XJP_>uLM&v zxH-tY^Bvcj{lWv_-snoduFSyp4i$;FJ3)$XMkV^mX%Z-PvCqwU2F@a3n91BFbIYp9 z7*J0jDMQTJC_}=pK6Dccz3}0O7ru>uAb`O2Il?JGaqhw!pS}U?d-g0D$T$Ok)_?KE z*%+Y5y0R2NCg%hGRx1QS3d3D+8OlJvlP*&%s}lSsva{Qg1rX}5S*10hS*3-M=c~_<1A-qLLq&BB!z>-J`T%zKVe`p zM5o~UA795hmyN(9bk3~TsRE)Nsi~Udb zw1ZI0|Mi{I+X}hHmv`=5eV0-1Ge3*pY(a?3OQ98|yNi>Jthg*qz8MClfmo+&(t)x0 z;}9$eYj!A=9*Tt~pc0sjp6PQmN1Roj%&%FH88c)ADloDS&-Ah0`k~WYX{*fwsGJvi z;!-wAs}55s`DJ`mp=d`Rp7N4Y%mItO2f?v$t_HACS5(X?RbBu}m7B9%)oQY3;Ygcr z^3)6G9#7MTeX7xNg{wn#4>Qw+?3mw60edr?@NIyi0v z=?8qk>?`@l6ba2|c)l=OdGMG+FU>JjNA4^=UfNl!ApT%oD?pj0*GnLEu%F?dC-h(T zAmK2WddJWOxB+qhfgWJD10(f?W@s!7+b1v@BL|xI9UatJsf*%Y|MvXM?1a~Tngl6% z$WzUAV1+5E$_)UsyMFTI^mUBK;DoG0BDgsRq1T7Qk|0!NX@6d_Gs_Rn8{o51lHN}W z$tuqa7k>Z78-P0^+!H7&{Qyg#BIDA(eD+m_fz&_*PmLKEOQ6TnMIaM{S};&#z5Cf-S{2Pb1j&Pp|X9DMm`P(PAF zxnPc(4PH(;)7{A@D05&^LiFhD{M`=c+O2T8Jo)T*zw7GSUXeJ1Pk=GGbLYv{XZ(@T zKT*K89(!Im|C0U*-VVz8N7>h#!8qL|Q#`15k_(1fZF3`LVAYvp308~%ltM8jVrlkm z%tl^!`AQ(>V4U+*>ICOv1mPP7fsxe&M{KrKtb){ylmV!Qp(+zzY9)LqyO}&pzGlY4 z4EsB4#yv@{NAalaPeK}l37!BDPl&t+c<^S925DE1&=9!3xW-dLAY z@+zlR>)6ebqfeYDq-eq-;|v=`gt-SOXn3DOw1SqIur^uRGy00G`if6g>Q~I;G9=Cxp z1J4KsiG@L@Vg=wnB^o)LIz&34G<&? z2ESGz;5q$}9n`Bt0E~&(xvE+Sc6aZxL)9kf$DR|q6v*G% z`8p7A3rE4fzKT`f?{NBk@kr<0O&=HIBNp?Eze8#Q--AE0IrznE+yWB+@{OZt2yeW5 zQ1JyCfZg5gK+?nqIR}qdV_qi4Ne2cS;&M7u}X%n=q9oU{N`!TQ*d)Pf9sVYH5h zZ>YKw=WV*47zS%on?nJHF4v#o8I;^iipv zP?8H(Hrjb3s{JOT4ICNW!{uZfO4IEVENf?opQ=y-ImKvSF7^L`Q@?L4q5?k?B|dtRQ;o!t?y_jtE1&S?aY^ zlH^_O`nuF10@&o%?_!L<5;}0(_Th(5345Oc{l0pp@d)}KO*Osi(17t;&cIo-EZ75( z6MZ4F`RyQILF}(L1>$q<7uFZ`#xaOh001ht1N13KV~y@Ur1M6Isn>sjrw{}N8X_Guh27&p+hDVugw0lYX-5&92_xMJEDxZ7 zhDTyW3Af<~>@gnN73eHh{-Io(G0sJwn{q|nu;Qyw9J-lRZ{&Uzoxok?>aS9H9DWyHghXJ%){^6*`7R4f1VEg;(dY6D#R38Y z=Kyl9MLK{n?iT_+!Wq!;&>S=Jfs7pr27n0Afz#iP?RiwG^N+%)hOot+g z_Q@4}IXj9=S^3%y>LLVLF&lw^^|;?Hv>iTt__f1_FP=So7){wd1i+{pp<_BfeD;ng zV1EXF+yd?#&g&8_@jFh!;{-7RpFz%SFYY(^FWceGdLv%@^FJaTwd`C#Rsjn>^Uc(Z z@7hiXIO9NFHm9uRPmn;y#uq#Qb8%;%U%A>7Y6x21nv`l!M+=nCVNQb89L>?Je?wR( z?JCSKP#Y!z5VjGb6CMNYI# zamohG!zTa(JfYyOoDoshoC3bmD^2us_uRNq--aO^MDUb))K6g)#?>2^er0^Fmbx2? z!D1#B^^p7jc{}Fe9M3#{`+$*HSL4Q49_aN4$Vhkq2cQ>$2nN)-2-ETx9)wYF$(EUg zC3aitz(b2bGy|&xotQVIG1%w8_Pc2S1~#(KH&q(Z;@7TtP~7$c7?uDO?X(HE$BAr* z01y!}Ea#a1{FUjFKaf@!hrc*BkkB{R5idn146A^F%a0c>QQ)gESfXL{umK>os}eA^O}!^ zekmFdaHw2-WWkiEg-aTl*iPm^0iaR>br@{7CADES#);h76c|4(j|^r4$*vkg$czLm zslfCDO8ubQ8afqvnD&vaLAeO*dkOTSF1Rn;GRYsEMP!Ks?j{AUtfZ`%OXPsmL4;%g zK*1li;Y(2_9BRm9_DD7vT?fM%b9s;ZCB1MoIitftogk5KS#%ykB6o`bK;c(sef=xI z!20@nFhE-TbUA`^Ib8S-5BHbA{o#ID+rt32cIvCF={5oe>d_ISkGU&IH0w)g&?)h> zG3el3#zX5O#L<3@=XbNRU^1k?eXnGsVbs|;Gv@83>Y(42z- zfFyRP1i7>35;(HJEjyz5sBj)72b2}M!Z&bKrb8MkaK*_mOI!-N5{~Kjbov?nu=zW{ znoPi<3V2M`_dmPD<0ru}Km9Y0?I`iw( ziu_9!84l1Ab2SFT3v-in(B2qX0jC+AC1wU?;&4||M4nuDimL2q;C`QGQ!XHG>n7IB7rFm)k{HT*>ilg5TbO2WK3bE3&|F=P{jiB z!<7e(T8!abF>1|=(b{ptserLNB(O*5LVlR*Lq^aKFk(Oen7iQ{xH=k#Wv43&1DBZ@ zQ=64E4Gdgq(CKg0t(#7c$pu;Dj~+_I(moKGfW;hp;;4_%EM1$@U7Lx+Wu7nlAO+u3 zog0rS_CT%$0fh>3;Z?^34}ypIOurve z1BjM?bBsZqpe(XZ9ta-?Exo><8#MC~gAQXyD%vPk04;J_NYhA&aPkLX*2vb({N({l5 zcosY<f2F;Kz@@`)p$by`F?m(0%3|koUyzm`@5~zrqqPHI zXFbGj8OB4GQxg*2k*QXy0j80;HmSO`;fKkmhNI?mVN&%~Sy}`p8DaXSAyg0Cz zrE##Ycc37C#uO|X@rLDPDMz|AYe*!|0ypbag^5Enx~rQBdd+z|9<>&y9VT4EyI=fcJSPkbfYnAJ%~QZEy`Oi0valNpQ03dq}fH>#4X;Tb`-}bIF8RPf#0%G-d@|D+URUv}$k4Fo{ zvoD2#Up+I}8UGZDuzui;!~mbA4Ir~%wrpgfqtM!~YL=#Vd<@)AGoV#q-v9RM;H_fG z*9b`cmzvB-n%mV55~x_}jnYi@;myyx9~k10ew`o=ivOjUtijpAH1A6IJx`rCxLsKM z`e2p8i?ImQ<*@8D+a!Cu++E?HvK{#5fc!WRPW*3MsnP073IL3Vgpfh>!m(Wx^f7Qi zAiaT?XpWX4aPrnhS^>6FBhh`_IU}D;)AS0eP0q)1Qi3-lG^;ga+oQI;gerVFr79Q* zB@c%f!U;E`Qb*k*tnv`d!1Z}`r{m6-VAk1&SoKq{_3U|LVn9vQotN$Ivl@Xvp);S) zzr;9eJ?>T`>mY$kXv4Z+6RB(A@rLiu2t92*Rz>)Zge{rkT5>Hu`Uul-p)tkviHiaF&DU zKu;=fo&3+kG(-xFu@}%cfQWtoV2g=hj^PG)T4S~;`QKv-9dQi&chHP{HkB}5> z`FJ71bswRC&)g=?v9MQ3%3UX4Ir-r~o0hIq;1cB&nrUL*b*J12;$ix= z6%+zuFE}Elx`d-QlqJpk9>j0%H3KY-Fz~<20WlpeeeaFRVE!QdP3UR+`u2=w-WmQK z@-dlDHuM5kdB8v%{i0#<)D}1(hv20r z^32E&xOV3)0$|>q8<`l)6u-vgbs6_GoGkzw6$qH;rxnA}K}a^z;vfDn|AG6xQ=c!< zf&rj~s?n5xU|t+Bm&F_m4;Ku8(flC{1ROT`=+{AjR4MS;@tIfyEMn#+jFzwla{(xG zG(J`PcmYWs#s)9RF;m-8!^2?_B3|*RVDDV^o4JclwR$WJ?ES&{^FkXRC zdDywrC!qC4mIL8ZS+G3}dcXt!8MtwqN(cfG0Dw<;2YD6je~qobceZGOq2q-BhzRJb z-t#?S48ju*#XA^v+Z}6gCvJXGD~Dwt(Q#r(GRK^OPl`u7tAYmyw`bIsG~e5?bbzo~ zLLuf&2_pi)j$YR!`9gR}lE*ra;^s%(e5pe?-hsUJ=aYZNW^azsfat!g=*p~O4~ZJ% z6p26r=8=@16*Rw{yciMAN~!860DkyoI`McGFbDu7Kl}`tg;&3PmL9t+z$aT55x*Mo zGW_JM8eTmjC=~iR{2mU#3a8$<`2hEu=S?ubAPOan`WjKM~=PdH2m|D|mheFMWqJYTkpfZ;F#xvi35W*z z5gCbm8@p)9%gz16S&5d2>pmvf&vNOfuJY#Sw$xcbO5J^&s%>%Y~5F6n5@kB( zu<44If(A98;UeL&(N{M3Q_FC_uz`v9ar|ca@ypl_A|sGF zS;$XqHlM~{)T5TBM=kf89u=3#0G}%E^T|~O<3E1v3OK^wT9fd#!Xsfa_7fQa4 z_xzi1?&%$63YOMC{P5YcFZ8q*0iS^6?I2USOQBk70zuuni6!~ni@-q~1kc<5JVL

{lUcfoiQUXC`qUI#t2%NH1B!N`IT{!Ikc8xr}$GND}%sJK8Ppp4_&l0Jlged)Yy zmc|!nK?4)@!T+|?{OiZIuYmVwtH5J2 zO6wYqKP-M&1zuU9=s^tx1W*b{tO9S5>_wE|o1>NcasxRDDUDChL}?jEr5+W-EfT$?%mZ0~dZP<8?G?=*aXwnXhw_$i$=0Rw{vIh<;5?M9jb#8+zHkDO? z*~l53IbD%b*h$AvEdvFHRa@D}((-}Nnf21(F}hA8w4z7*+68}63KVHM- z2LKSV2Fx*!A8QW+q`SH$Wn{}!FvZEGEHgDqk*IgD|96gRFD1x{1H6%&B`L(_Z?;3r zz;+@X6S3MQluXbQLp67fib=0}(iCsco^{|K!c#ipHUw+J5=Do4dYh>rw0p&7F*R_d zH|mReRc_>d5Ar``!k`C9eIjwL(Z7V`^WO;Fz6t_}7k|(7}SMh@0bo_+EB3!aLli#kz8 zA_Stn!ZBEL?snP-8oWg2*gD|k7>6bd`VKBU&N}?)3+M9;pb13+*V77-%wvELBa(ybfXUd6tb8)@bs;4HOBJ@og%lJ}BT~U?3qaG>@ZEBz)8Z@hIz) zT$xGy>rq?MV!b9{J=Je?a`%Q!;6?m@oSSbeAkcw7qi?WB0La(^Vqj-dCm?-PNAm~G zA$=k&6SM;p%;M;oA(3M^YE7*Z{cLe5Tm6W*KfQ?nh%*Y9;ff-5L@}af(dN4xt1gjU z(DWi$V*C{K}$)I83;<}#VAIAmEy?7Eg^DC&swyMJ3;b{KaZ2>Pn6 zG6c0}dASi_oo^n7-?I&eaqKm2TCVAVg2J3@GVWng@Z5OQ_@iPA0Px0r9{lB0iFt?H z4tN2dI2C`$;iw>i(#0SNUoFw@V(aselI}Z{`+`wf&+|D?B8l(w~>%0nKI7^8g92$iMe<1?{CQjZ$BQUpqy#&A# zS8ZT_zANJ|rQV392j+z@c~!k2n2gWbu*_K#2+JMdr`eR7X5de86#S3>_>=d4@{{KT zKs+)6h%~@00H9*E`jxQIn_Pcmnz%>Qi^*#cqTY2s8xsPKs5*)F!DFc<$zN~ap(f$d zi0QKqt96f3J2s4Z)V^2KHZ|s&kWAY z*fQOx&dk#ejQ;pl5x|e#m$}~^NyfoG-_7YnczgSJ@&~#zeIzJwbvJNO7Ds5pRNkTTH_%3xy#05+Ru zrl_p&-3_b3jm2gO46PcjN$y1YXp^)H@98Ot(ybV@lO>>Q# zl04umer1XuSB&EFT3%tG!4fv?qF0bcsphE8R1VCP?mmijQ#Mc2tEbi^`lYAX@`3B$ z&{lkz=NcqMHB{MKE`Pbh4##UyElLK;AciVaYih1tLunI}`^%qv0Q#i_0r73_8x8O))=Hk0K9Nuj;)wWNJ53@#UWTg zHg?-m7vVEp_Rc8)rk|NFF2bF+*JG$d_L=q)ag72ot%6iRb|!!dT!YaZQhEg=@W^#o z2Vs=~Qz|70fe{(ABNPSNPr~R&<18e?BDYfS*o3T0s5`s!GG zx!zp*f{wy4Ju_Vi0FC(bJd$fS14hlB2G{NM1COCuwJ7OinE$y^+5z)kENqbV?K>x} zBhg0Y1gamMJxSz$Vu>Jtrvm{sEL->J3;Q$ia7GAxJeopy2Dh^B_-D_Ivg!XJJR_S}bwc9@M@ zoAnzT^%!c~vR=5w?rzH?l7O8MO>5xj!O_u!?o!XYxqG&ii(4Q@oRXyK=^w^}e6617LF8p zfr9|SGV6?oiRa86Wb7%gm+ix;wxI@{8Cf{|C^S8)$<>fW7MR9`KdYwZ(KrF{?;kz7 z{ZCMUksX5(_$hXLnt#`@{{sUw08$W{z(5S)V+rfO^&|jG67jierG2fkK=TVH<~8#` z6du70eP~D#(Yo4V!6P>HgA;>fD#&nF1Xh1Z-ItZwd1l><3t|i|X#q$ZGAZEPQaI!0 z)d?qQpz>OM{TK&Ku%vd5ikOP$V+q*Hu3cL1I=XtT0(%C&7}dap#F0p_>hGT;0A{$C z7Jgqm``%B!_q})CdFPwY@el$0BIP0c8URS_>vg@H*NSI(4?H%8T_0g>ekbaJ=>?o0 z$qa(2KV*c>OFjr0sYF#sa>U^KR`AVycpt+Ho}N(=nUNWAdnUMGis6;JuU{gKqSXKKjT_nF`4|BiTgVA!-cn)8emB!*8F1Q#}Opb2=lzG;m*# zKTW>#cv_)2EDq=;;7anrfCwrdiyOXHM+6!MZy_8@Fc|m0d%BaP1h>)-bB<5(9vXD{ zoI>!%EmFRE)?>Ba+8_XKEY|bxZPX1R-Kt1;8bUZ=MyY_&O14j2Rm@<-mPZN7gg zrr#GYUi|LxVekYtPh=+=`IOz_mktURI~@?nbQcmnYzC8EaCb9^Ay`%z(;%NfI2W+l z9zsUkkCV$4RO`VCqI}*;D?f%n)?`nxW?bvO%tw*ah59c&Zj@nL*neJNP$~dnIIiiC zm?B>tbyA7|4n&BEF7dyVGy{K6Z5GcEIW=+e;ro$h*L~90gElwTx;+#N!~-E!>RhT* zZKfJS8WdfCWc$xyvOxhb7K#s%N@#h8<`(4tRe7({?5IP1%NCSiz0{VVtTGi6&il(b z^1y50n!{dbvOE(lafr^xEimHCs%=!bu`VspkMrn}7m*B4<*iH&z^~<>9ufW?DF^`= z=n)v*N9g}}%;#wQSl6gK#H(P2e99d-cj427e?mTC-51ZF|KShsyn`R_ zJpZOA;4i!;)Cjz`bMa#4_gf7Z?49qT-rJ>lyI=L{l$pC;aK!DB;1QXD;gBXF#Pf<$ z_09W6s07Dtux8^RfzHOEO&plGy*vF*q@5tR-^6|(pyBVq`H6{byzAIGg5SJOeU*F# z;wR?!5g+IZepOvbg9JS;0ok4zsnJwFXoop(FSPR$^biBwMjCR5sz1Vrz8^L^=wtz_dA^c&L zRA6*yg1#ipHb;aX95g`D@kmJJSy}SKqz59T^LKdwjE0auDFz_o?Z>nBH_gD}f5X_? zDdZRimb?{FDYBX_$#hgx)Y77NVIp!%WSvGq@Nk=17(r528z#b(?U-rdQmn2ePC-cK z$Tzjalcp@|i-Tz71k4rV(-xyjSRtnTMauLO#g*Z&`yLPRa_5wMk!F)dyXJi7nr(S7{<``aXfw;#y{ z1M;WBZ-${N4jRvpd8Lf}D2X!w`YL!m=Hm(8$*qMHl8k}4gtH(_1K`4e4%hsEslWuI z)!`gP4%Tk4->B3D0Hb%0?iPl{%xOJH&?B4lt`N<^?UjfL#DF`EFhJH`-ejp7vI88d zvSZD7z9K9s@iG@60%CSu>$xs@Ov0B;ia69;`u$hNzGniygn`eW1O5nse-H!w+6cV9 z6|=QM@MWnnqgzdEQ#pXE&d9eNI)UJb%h5+v5yD5MLjv#!c%Ovqv<}pI5Mr>zT`xel z^#U=keI~3iGvSHWt?-QgE5mJ}v}gQ?nOEjOPrZ2H*N^lZ0C+l)K9vW5d^$AX6qp|` zC+rJn&GD3(e_U3=Z9l;O_E=(8XoQyW?)m^H8HgY~c+&iCQr4G^jbwt+q1=Xl zac&H?;a0uGftGLDP+fX=XLmhcyhRep1tS2EPxTsn4SlX^AHhq?)jA^dM!Dm~LzS_(!B7 z{INCzz{U_x9IfS`d-{jj%2uTal1mwZ7Cfwr7Cq!5{f@#0|EYV%btzJzjcY)&M3F-G zlWW=x2MjM_hY6C)buJYij?ulg+?WpXnrody-JI5y1*IuC8s8ySId21VYPMt+{=)&0 zMCCrWw5Yzf;R;`OMd2(AC%7_2MTHoMU--^fKAGYlz@ZvYJUp!X6h=EhzvkZs{z5wy z7|1ESW}G{~`^)htQXr|8nGQqNj3CxixMF6+SH4F+OK4U-7;#2w!0AZ;1|S^T!p{*G>-I- zry=X`2VMZ&byQ~EcovCv$cK?pj~z(Naslei^`=yVIUNsUMsC;m%T?jJ;83Y4fG+UI zk<#?7>FKlm_72bY@|3Hh`&rV;3NVR{8|nsz2CK`9>s_uHp=^S^;|O%;iH<{m{l;H^ z^}Z0#@RvQl`G>$iFu*heXL+bk@9dCC+UT;X?cYw<+0_(|pJHIt6KDHjm$6QX&^i#& zSS%kRl^7k%btxRs$HQIo8t-`^j7DSv-nQo7cD^tpV_=*EhZ{P)fRvBp&cwz+KF7$5 znU^Xrw|?jz5%!pd;Y40h~PNP^@!Odii_G!VrTw>YClz>SFlY*vMWAL=^1BYklMvzgg5} zvACoe;OOFLG60hMZFus%tGi#m@!&zN2{-b%2gw65JD!+$sv<+8{Fc^Rv zJJa~vm?&Va&fuu>9&B{Cc`!L}IS;h?-Ds@l=0E=YkDvVMPgiPdAM(ac+d##U>g|G4 z$pfZq^0q`LaAOay+FE?Y>*hAf9n8D0GUiGVdy&6~T)l#}a2x`ii)Dbsq^v7A)j~2B z#f=(_jcRGRqS*UrtRu5+wh=k6k*5>@<$j4NK4Jbc*f@4G0UqSCgS6l<6R;CTmtbwe``2#dqZH2}VA zHpGxPHkPZyu52$<5k`GV|7FTo%j^m5>>M9|RE6S!#X>Hoe?%i-?!AGZ#J<~qf15n; zegNQO768ll{980(V)W%@9E1@J#7{UCnB}=9j`eBKL$`o@NXf@Wko6&ChR{G*cMebV z64!u`LWZ2`j)na_cV1v_Eu{w{1G(&zyBW+-QCSp8O3Dz_sW2&_O5_N56DUTSzV*uV zMV0^JF+wt=0=Wuzg}^@!!xf%_kn+uw4vjD(Q0Ha}AYAyX_x}2C|MC5QeE%o!zyHPa zm#|MH@HqhxkLQ0N|9hT|z&eBj15^?Wjy{wK$TlRHTd4a=-7p1wA>_l5Eapc~%ypL{ zjfj{!EKuXP<6C1&)&L*q2hOLQ1bla7et2?Ah(cRD0z;TkZ8~9To@T`9F}kJalShVO zS*Nw~!_M#HkAnlgdd9TRl#ee04nKaC0tlyIt^hSO_ss_R>)Y)Mkqs~=Zyl2;Kt>xs zECIO%OGd4;o<@MM@OJeKt${|6qwKbo)6%<6U#IDWmM2FZzKfdyVZAh zZczDHTx_+fd<5?T1gyt|yQru7?yx|2M_KyayWO(F;E8X_*Q-j2s0kX#dtv^IqmANl z8_3iRj8m8s^FGYz^ub#?38}3O(ia5Ke2!3O2&`7~5gyYR#}+kQ1D4JGnq7vTZ+3=O zGzGKP+`GLVmwEVbA*bnAhi;Dj)5S;}gODFuCLwrnImp0!1+Y|Ufn!KQLGNd1s%yep zlLup9hYBZXV8%^}DeS2@x$P;;KX@K+evbha=2i%R^rk+vme!TiwacZZ6?iT%_A(naZ{TSk;rn zB}L1PQ?H*orQ4ZKe1$we#w}nIj%RiFM}r@GdK`1D9u*-FDKp)0bPu6_nksJQ%>QD zhCLc6S7Lr?yR_ia9FnV$W=bd?xFQqXgV{Cf$GZdE!0OcRq0)8we{5tuA!L=ni-{_?h>=!a!~Zx!7CG=-s)PiO(7O{wJ^4T0P@# z#D)*j2e*rY$og(^z{R5gxtMUfHSZz}VN?pRMB%*bFlt+GA6W|* zN}YB90s!kf<3=|^qWRLIoPJEpKj^Nw@d!NtFRVH+ra+7{LVW@^V3~_H{HtbWd~;s= ze#he18UU-(LD;YXcH`tyx3=MFSfmbh-^xrWCZguJsRG1_S_fniAL%J{PO2@}xVtUN z3B&mqh|1)Fe11Tbj6~9>ZJv3D#Vu8f)MWc$ipnZa;jg5J6ph%{&~gPidnkr$C|@}- z#S0Wi|FyU>xUNOf(L7z7YJe_G;3FZNQr`!__n`pr;X|@ZrByKvrm8gSs!#R!7m#&H zsQ{|HtYB)T?$lss%1R_4`VIb1)+4^ozq?!x{{<`XjpM~f;|h^!aUd!qQ19O^UI1r6 zn7;!DynP=l!2bjTRMRi*essVP2p>FF=8GE8p$$KAJ_7FE*3wz9a{##%oN&_{a-0=> zgm0h|Jd-+!S}%jAy?Y`5AJ9MB+&NP zfg6xlHpjYpm1R)sU1DMi`I9oSFk5p1W|)HhkO<2{-Q~Cc;@jW&#y5Wa<8OT9?YBSp z;G2+mLG!*D0QY7rS=C!EGzI&5Xvt6qGeDI*1p*1bO+aphV}mjA`hd585YccJCer zU;UKYJ9zq4ZTsZ=do@TPQSW2Ty#zmcpg$%A8t&+#VQE|(ko5T=E-Q#zaa8I)W8k*t zVA4S7&D4VN5^hbT{W=PjRFA)|2nkn$2oeA#@X7>u&SP!2Ct&XOXlvd}1r2U(2FEx8 z$pqedy=VQ#D;xFo+3lOxeBJ3@1o#IGygM4?Fi#Mq_DcKJ*7teG!Z_SsNSOjt9q)&uU=Ny%{$w!+Qk2svh#m!szy+t^bNe`~ zUZV(dYT|a#_rE@5BUb1>FEy=qa)rjw6YwABNc%kjAEb=-&QU#WRQ_sXexUK8kL}b{ z=Y*@GDmBRpwaPoi#t#>6PRY+_ma6(qZ1`BO2Bd2k7Uto=FNgV70LVmVVjnr?6b*sI zTJ9!uYP#eU3#X1OUgLPc27v5yJ)Z3$kH~%p+_r`#&6N{-rF` zMigx8Q4)dp&*FG|J`q2J&_o=xBB3#(V-t8E!*Gt+MVyD>@Ze>?SWt|EF4hkpYPrjeC19v=jAW(6b?jgUBQ48G`-9*xIq3F zfSV2S2C2EzP=sFHKcvG$DHvxdRUb)`o3{}bm?b?u$QbsFqiE&ybj?o|UL4bc-(K+mP^otsJ34l8Uz_YqHfkROHK^p$X)Rhz!a$`=$Cjjqt_V9C7{f;9nei}KCWa-+vS zA>qoU>q>*UbZoaAL`?9QZ-URUC&?qNOfJy_m*!jGUjn~2JmK*oFc8oP5EMLidbKCR z3*9dgLpTx3AkF+MC%?pnoR)wG4=x)1_zrCrgcTTLO}{cdO-CU6e=F+NaG0PNpgv5B(CS9@#B02;j`Ng^(-(W}fJ{%_;ag3*pk^QVhc>1DXJ+Be>QG zz6xPO>%VgwWO+~~yzBFFFqVMbq=6=g8=dkt6T&*#fw`eu5SXJkL)G=MheH9`6o(-g z9Ppqx;3#+>v9Er#ljfMw5Q-NU1FrIIWKbkyya3^A>uvXo^qBlOkAMRJ4;~CL7ZM6_ z@NVkOj7L&WRBn0gPoLNb2=*cwgY1Vu>t4;&=HVN*vW?6|x9KWnUN-3-GDip~+*$mJZuAow8O7WLHfpDW5Wt zY-kXflyUH(3fNof6t+T)iW^^;{@{nHYoYp!*%&Izi8_Byh$2_Y%ydwM;nWG-t-%`z z3{>z8H-j)X>$aDFRrn5idZ@J&Rb;;0B<;6}ive6PmsP7tAXL;V;t;vBpb=WN?$`j5 z5^^YS(ei+0NlkTRfNZk^{()}Z*W-}@5Hl^8eM_Egul_cbe^3bq1LRG3WvjBoT^~T~ z&V#EJOTvJ`1!)~V%U^hJb^_V=L%%p6#5-_kLXm(B2Sh|ZBCx{RYz7GQW9_AP{vATX zIrSs);*B@L%E40UFXv*q0YR6r0_<&f5EdHJbts2KX&}LTZ-=*rzyCct-oE;WZ+zn~ z{|=kJx4-wpAHMm0l0L%UkG}h(9|;G41f}swi|{3AGBs% zKo==rKU9~lREN|R7a#_->({{o6`3z4h-p}7A?i)yhtMr(DhbYbF={onDRg`S8}Taa zgxXe5rlW2Eov2x=zoof%dpm6dXBU`_I!MaLC;d1*DE{Z?gg#)P;ZLLRAfb*=gJFr* zW6-Uc4u6io{65u&%+Mal^&eRuWs?2Tl0@r^q>z;;1qS`&G04hw1^}u#JviVoF9Q*J zztMw`J z@$vaR&t05U^Z!B!Q3yh=VbX}3o5M`QjS}qm{a-^BVu!_j4tULoui9*Ik<+?Pd+&--*Bghm8YzYLTDhrx` zzBpauo61G8!3Nm>F!2_BUYBz~4UW)cwK?I!V0>u94Zv+J?|{qI<#HjlAR~SiK@05m zV769sGi`)*Qg`tOC?Sy{fUxV3`ZX{|Mpwwn#K~(5s1lJf?@A8y5CjY`SH^mh|9RkF z7V~!a_lniwaABMYSW4nz73Q^;<+dA8#0h}6sRCa$04CGRRYl~Z_v66>+5#~Lf5wV9 z<@2qX0#*c(OBEVi9>{~n_=BPM$OQp)2bhM%NQ48tikst{hKK<)hLAx@k)2>e2)BMX z@|Y)&smxDE1;I>>j6dGCLebm?5pwO@T)Wb+My5BB1k)~Rm{RjJBH}|Qz&j89?YF=E z*HCyt`abyK4}bX6cYpfRclr44cfLc^3;g@hcfbGc9**~XF9Uq%`I|p|=lj?Iz7sCM zy#Tnrw#8C7Z0{g|P;wUZ9T|y!BqHEyzb=C@@bY&r`c=yW0Hj>9v+IljXZz3V#tLm#LxaSYQxBUH5WTiK>U>~HVm&pcnJ~|P~gWoxHX}jP_BDpl5p4Eofu!Y-(YeGhs>m3k^;Qg-8q_) z5Za*j*30W0B}d((aR3*=_}%_6GDad4mWWa(2yGNUcn!>p67s*iQ;8d$=cn~wqfm|5 z2&B8~rC;7w7p7s2f&=2TgpL@#9y|HO>xK)p(XF0y zg+?yt8W6Rc7jmhLsA$_uu~}z!d5w!zm|t2VEWX9q<`5QrU{R?q2wDIuRKZ$Un@#M za-T9scwQt+bYYKY`3e*GseDTS*Ixs1xebmOWndu#u;n)Vg9Vzf@#&ZeeLu&T$)cd6?p1Y8cW(A0jx0euyBK-R!HVIH3` z-GEZD0FWmiQaA}++HWB+foF2;3dY;x>Yr=&?bQ5%Q(pm~cp>EBc0p?g7LAAS_}l;f z-~Qph{UuTizDLsc)1SWivv=S9>6<_L&X3+D<@=7ApC0eNO8|WShut;b7ugE%5ATpI zLM7RKTcqVP51RV&j+ot!v|xE$XoJ~VeIf1lg~ndIMxro=<0KA`p{ac}q2$==k+TFiFW?T#&NAS-RGw%wCpW>VKtUcN>*$HQCQ~ihNU$Q*|_jvtwFYN_& z4}v!<_W(|qdxQE=2S*$9Mo2g!b+AcYUY-M(mwb0WfV`2bg}1M41mC0U{6 zg;|Mc=;;5D1hOFm^rUE?Y%eULYZc$)IxzNqCV&aQT3by7`P)SyUaCGP{evZDaW@9v zS@`n2xJ6TU!L1v*{>^VJ8qE+^kmnKH#$rB>f(>5GdFR{tx_Skm?tKTJgHYW)ILtYi zKZZy7YP}bKreM2_qt#}EFiplt#sW2=$v3C!BHCIC)rglFH`XcofD&j`H*Glu8~7M^ zoHdi<>GLV0izoqSGhwYE-O5S*Ehr4R%=uaISm!+|T;V1yp1 zwf`A9Luxz+`MPpNKEEklm1X7bGkZ&37c^U*fc@o0oeDx| z$XS-%CL$iN2xKAx#%qqUJnwbfpJZNzCNTLyDbh{M!NLR#9}FEtIUkS!-1&Di+&QC@YCzR2ZeEdnWm-0`f7pQ?N#{$-D= z5BR1BxDtL)*}osxziWz0RbKr9(@5Zj=08H-4s+!_I@26gy(qEK-;gw?`Apc>2hS`6_{W;)Y#FXj~~K6`2X?0{?|A7 z_{j$!{M`rN{N6Wz`X*@Kci;Wl&wloupS}CDcL9K=eZWEzKt9)&&-nNJB@P$>_y@f? z7+|+NmQgz=aJ}~0S!1Byc!WtX{Zve3p+2(eCXwmg^`J-K z$Tgfd>l>Sf!3E53n&2n+o1dT0at&r@W~2JtjE@(;BzX6-SH#BeqmOhCVkXGnDEh#! zxJL%46v4rC_2w*982|?ztFWylARd);1Pt(FI4YiT2p06|`98_Sj)Pt~mcpPl10RzB zl1_o+2JY5I7Jz>_es(+aAa;M7S{=YOBOV$zU`DV`GEU1Og*0}@5n3TY&#jn6F9s#g;#{OL&Q1teIoYId zm;qv9Jt3_(wuY_}p*^qQ_$KgOEC4d5gLe>$H z7@6OE?TNj!oR+&x&JhmT;m0H#Oj12KVY%bYV8L}L=m)YsPN8)Q2s=p4^{rP^Zc z$0gyCMqy#2ThV4^4&*lM`mJe+!gR;{;unX8PXEI{5c>Y|hd=z_haY_N%{PDe=9`>) zfqg&we?S2B!n^MZ_Avc=|M#QseuotBU8}&)zs>-82NEi9y!O*QjUe9Zk^O0=)pf_} zJTY!W(bEJ%Y9L3BymsWs*;Q#Flzh*wo@FwPBdMd9z1IgNyTIuyIP64OCp>nf(NQPU z)5uPsogiw)988mM`XyevcjlfnkdGLFFlZGdh@h5z_CU)Oh~by~Z;-QZ zT)(+R2`Q>zey&YFA7k(KZWBoI2HN`<8T%lCEAz+3Nc;4IL$55+p#YzY_Fo>piI-g# z`khm^hue?B`_eiY_GkiRcWbh=F!pQ%-u5Z#J53jFY-ngZgjCyzD92V! zOp{E=WHrMCP$?PW_m!Z97;nmhF)F9=BFtaP1UCMMaG28RH?>F z#W_axP2vkPQGN)e1yOQ!wr`T02n%t^r-kr9V{h5E5jer8POjS z20;7bumpcy)j%>pG_e6tSGpn>w~Bgt^_80ma+h4lL?sebsemo*oB%~7Br4i_RSLwD zU0a)CQR$P-asXtILg-J@Cv!)zExR@KW<0QmQnLq)%O!G|Sc$C3)4DwBBI~oEk&?g$ z;M%pTcA(yUOEp2^?7CpS1`!}w7xBj#@gCwLtl?2igO$|?D$QU61^^BeX0C{!tw-3j z%r-1WO2mx->=ssjLx$}jjNESsZKM?V@V_=Hfx-tO)3tzKlq?LT-w3|K015X;{gryO zC*MoZ2%M!U?#cm7fQzRUdqA)oANSyQp9uK!A6=S$T4m`VLV$q%WIoO^Hnr=%MAIq@ z4r!-y`j_2u@KPA@Bqf zB2R#f!v6p##t%MtM51Hcsbj~M!SOBw_$Y1x)?wl!)DiaH6a*eM_kjn|u$OPek7xk= zeC7M+jzV}7BOu=UdgKKDd}RQ9u;X|jfU)yBUf)8$z9!9r&O6;A4j2=kS~!nS*)<0X z^HeuB;KqYmdU^bN#U$|xjiT%e8*(ptfQqzISuza00Gp8D&Oq(^}$cH zuP6|`r4yqbK#*6z%Q^+}2j@V30HBUHK*b@v77QU_`a3cd7GNjq%LzR65{c%uvZ1^* zY76iv$3bqvqmIAQ#Ag5$@xeH(32(q5^H~5G2O#JLpx-J9ybex*N;AkRhCF+x-Rk#jIu&B=1Sey~H zQOWR0QKb*6XV8P`q%BYXQW^0 z&pY%!ro_B}=}#F48Wq>QvktytuEQt+)=7{cxcRA**sitTGUy78Nx|jMAN{+#&_Vh8 z51x7E%s>44x4-@6#^vQxr`qxGShoke?H&T4R^2_q!8Z+sf&K*m;{J#I_o!qr`#j{u za+d&rz`u3?;J(-(x8ek0W86XK!CX`3%RvurqumBToB^Afy44GeAec@)`mWwKb_{VINiwz9i0Dg zau*&;_c#_B>~K&;^R0RjBU);^Vgtuym>VOvYpA=(&diG>bFG)|Nt+=_rG$5eJAs=) z&QbSS;Fp%EKhG70Ow2$Q#~m1ga9~z$P~|#RK>}yCV0Tj4$YVG z*4q)%7c8gI?;;{t=1jB9X)#3-G?v#|g-mn#E;6ZsYqCF6Sg!||_RN`cj*1kXDC#Apu4jKp2NLApQaXs4?*ZKl+__p85cD zAv z2i_v7%RzeFbO`KI=rea>UjF(*U@D*J>NoYu)WJZDOl=82ISh||Wqpld_QS!DuQw6@ z9E=t2q_)5fIRF(MA)SW7&da7k_=gn4e}VJ}D!?!o1`O;J>b)GI5JDoL1EHoh;71)(tpyXGchfJjs^v#K)vS1W{ADZ4k6uSU3=h7i|gi!Yk z6*S&wUkAsZIfwlL0bPDH=N>rEYeKPF8PM2MM2WL<1GBCg;u{JvV%7RER~w_SDu?Q` z0R$_@V^Si;IRr z*yiqETf7FxTvq@ zE;*CFBtU%K>H!{7#S8zaoN zcNVGvkT`fKFulA3>c@Oc2G6HrW88WrUU7N^0`kR_j)2=8iO(&V8}9WRX=HK$z?%)xOsGMQ<>B;p9Pl{EW1tYRwW5d=ufUn8SJ+-Rl@!@)CR!I; zD5^HHp&OT2!Z&Gtl(2TnFQM56C9cq*7Yl1{@ zfGG#8Xk*zq4|5P0OEW_NEHEObF2w))@>kLb$tzy9^oIJ3>JMqFP3SceDJ2F9I#;WP z!kmKdl&}vE6hyBeRfY)(&ColyHWyphE9#3WwfNW!-NLL$%DD}c83^ZL4auDs3GBW1 z9$&dvM8GQUfk<{aeL;nocr0Gf6o_P)KVk-i9Pom~F=T=@|G72&0qc=~T~SG}o{;Dj z3gSCQxBie(yt{?s7fyei5%~chK&kv30q`kB%yf14>)2--9Uo6IJAvZ1;mc?C@87?5 z>x(D0ZGxTc*e_3k=HLo@7|2IjS7;~j+jG}wcr;==4jT0z9W+aVDfC1doFzHFgea;){NO>+rxB zkdv=q(A&8)mE@F>N;VSqFa-konwT#`^i$FyqX6+uU%@fM-=_sc|>JNLnb|rL=r&DV)})Pw!qo`q36zp zo(uudz`Zrsp1(%?3;quWzbNlnb`Zxxhw#714D79!h$l;&mtVDX2TZM6 zf>R+JkZUhD-hBKHvC%1Q%^D4>^XV}9MfA@?bK`-qYZu@sB5ex+1c6|F7^8wXWufH)E2W5}G5IXDq6kcp^V)A(8Mg_zS^)Wic|D+rm#yP(v><$ z2Fy%Phu>q3BOk~dmk5H{nsC+Qu{5Dtb2N>#F;)vHGf0)8lcks#*!AqQ+4amqVB&K^ z#0r(vr5t0a<^GTXjs!3l;CmFl5dLTbKF`ujM&h#)9TBMSg=GB53MU5SkC8^^!njH? z7nO*5_8Quw`7-11hlyd#&)@x?gPidUU!*5n;0)oZ3f*N-ZEhg|qCObPy$cuq^f9a& zfBMtA@8Ba9uz%8i;(pd?Ld^^aTzB&1Pk*{~@7@<*+_>#$$BzAMlOI5*H#PDdCX#ve zUHyn5G0+~gfB*mmd!$MTftUdCJ%YF&kias6+%N!s8{uCZ1{2_q0C?QFsNRDI1%TdY z5ApygiOZmW1eD|(r$`Tz9pQ{Pg-z}=JW?s7&w(>eCYu_kyh0<%FeJh-2VsfP&{~3_ z`i?U2RTXClJVFbwXTh-O0{2Y+zUCn?C}jkI(Zo1>tgsDLKSd-7zG`T zAQaRcaA|FvfjTPd8>wlZ{eXQ+0EGGDJBPnG1$D$hfD;-89fvic*GIJGhBA;t^K63K z&aBi8q2+SkSq9+(7#oGhBHYuzq|kM)Fl z^dNPyK?J2CZV}eL9MsLaPb8D8k`YXQ0qyLUtHQo5`0W`-NlDr zM9fZoW7*tqgAfrPm3RdDJ`x zkrJjW!k?%W)1s_QJT+crCdS$^}Ij=ZWI6$&< z=g|v{-@GP30$^x{Qy1J>Qo?^c8yvwG7!JdcPtBNTA26u&np#tLs0x_T(768LD|4Lk zXK^C+u`sPH^hN(_wEmnaM0iK-aCK!`Cp#=`Y&HRhp;VtFaefdko=He>|VES z_fLNE+&})?KmPpRetry(+qajOH!UAtUM9y2@B`|-O_Ial_vM!{_VpV7?Dq(YXH1Fj ziwXwjwO_qWJFq6eH_w>`{``k4FrB~*LxmIMb=!mk39QQW3lAIxbMWB7S5}Gsrqnzv zUoV1$4|4PaqcIq1{C4hansQtg;jIq>!JUIUiG9z0mP+DH2!He9 zM%0Tb06Zl9^GJwC;P9tsO&Ng zG*UQ&WI)*Jta^?bl7dBKjBBkHVdZA!^UTRg=EH<%qBp(?QY0t{%zrj!rF30vsH;|b zevgYYZ3L^HzJ#71tAgt?<~cGlyt&L*wU{(dWIR0C9*1pIUJ)fHyXykzM~Mdw871t7 zJ^?xm003F4w<^w21p_r=Q>g@0J`2@!9L%6|E-0$L+F-~rj_LZmD?-dnadib;Yn6_1 z2+p!Dv5<3DB@k1-O3Ny~S9_Zk(R{{jq4Cr^3 zu=cukAj+?1=qV+GiAsmS5C4f;k_T#96I`y5uhmi8)?Cy;+$#2aPGPM%o-Auh#W})W z2_dLdRhM)Q1Pb2MHmr<%%(xCdJ$?2)Y_{q~G6-@JCJGY!`p4tsdu_Xmzu2+(%Hk_% z58Q#PUq6OG0w7~waPdoJH!btQS&vR$4t2d@;T7KzM!r37hZR`EU(h`F9&TS= zzJ01)tjC*_L-#K4y?V@)2|nGqb2m0Q1>yT3s0r|f!T?{7^PpEY;Kko-{u_+J4d~ZR z1a!>v@tpv`<5LF5XaF2+n%WXZK#F6Msb`;k7IPn-?%bLDYdHxtY!X6-Mw9No(HDIB zBLb==q{WFhasLqo=!!yRYx=MaA;0?7a4^AjMj;5V>3YhA_;RPzf5YxZx~%2b&JPR! zIy)n_mo&&)c|X?nAMw$TI7sMQYaS$oz&H_=x))7@@&Zpf2Jm@j|Aq7`$Ka1}_Z<-> zqH)lJp*$eb4!m8_&>jg__+LGGoPrQ|6RDYvXJz7`piir=Fc9#ks{*&ud{Ub!(`CpD z6Aev|>b0DB~%uF}vu}5xxESTU@-fVGkYE7o|$!N=^_$429V0{RFFMijG zBlx0gKQ#Su0BrCp4b@*?nsyMNy||8!N!K|JS=KS<7$^WW7~+b|Qb{N)Pcr9(W~!Vb z;!Ey|BAsF*YT_#j~IlmECZK>Rar;tfn=N8a%jaa|A%1 z6p0>Hmf%2&qTO35Gsq^D4}>uW4w5PIj^{U)`~vvu21g;Vjx(cHO%!~{atOTE)lbU7 z0WZ2lL)uC3tCq-crzx7oc)F{D>KZ^imSp%{imvF)RA?rl#4;1|Yv_v6W?NEZD`TJ; zgi6)3id4=U0?$Vey!o3C9(*Ivdq71rO>q?dk^8;ANM@J=-Z*g(?vHENh=52aMdTiM zkzn+A>M6Xli$dnzyYW%vc`1bkm$B~Tx~KRx$0-H2;B}x#e)8O3e*SB=Pk#KxH}8HE z%17|^`%|3yXy}NmQ1UDM^h`YUaMd4bC3- zu7QYuvDO81AWnl63gZ3U#=ybBroIpjIMtZsQAp7D?5jI>9>kRp8`WS~m=$->9U`Rh z6jnE6V%ZtDq&%3eDExr@Qok7B0Dyo%SOGhO1TZ@EF%uy~;fH9L&e%C3)}wRSn&%;2 z0i|(K$iCL#VF4eXtnFW7`a%C%I}_K42PRV-8bL;*Naz&+wD^T6IO#-amcbeSm<<@| zVr+#APciRtA|(4Uzaco|wuh7i8-Q0bVblh^;3{B_aykd<+~>K?5}CkMMA~QLTPhOK z;9nxVvfa_pJqloDS-O%^)AqGGao zf+EVGTa(Fs0AFmlnH)I}amIi^%$)pPd&uwWX~tQ`R4S6(+|$BR3J(BcN#!=;eH6o((KoTROk!JfT1Cb?CpEw zix*Dv5O|X1m?%O5?<@Z=bTi}3|3g>VuZI04ig&F8J@U>wfBF-`1%9pXU;M|r-@NM2SB{vAK$s1D71kAxlxx$*XKxa;d{Y~&XP{~u2Y{C2+jDgaObiDTd_3)K~Xs!;qbAs>~( z?{4SK=mcmGv?OM9lHWrFf+T>Gp$bHGaNK&!BdRUZp^vkl zxDVTYw+rv=fb-=qkRUPZ8#_DVbbOrUw#!48R)Wt-x9s?}Dz zY>F}?0A#tGR}cc6#66*3ot$r8q0t0C0jdlqm;e_{aiDZNI{R7noW|PQ+$>$7PK25| zxq^>{9GG|;=7-3?c0en7zK)hS7I{k`Hm8o_5-=S9WyN#@Q@T4GE;zs$5CB&+5sfJkx4?q_1WOrJ!Y9sC+*2d2 z8nQwLzCh~2>hy`voJPOu|}+uir=bJ**$&uzhsxI4dPH z&VLu)GYh=?Bs(G0^a>P-y7U{+KMU+gw`s%AVA`V6|fDDZu7W z^h|nWJ{7KW>Oi;nPsm2%9Z&LMHcY4H15=C*Iw+tyOeT{iHzEQ=fR~SKAs+Q8jOJWe z7kz}@9N6S^h=U2PU(A5cOVzJ|FIhGP7plD}%Q^?tk{BjqIMPj!x$osELDPf!I# zB49D=*L2+~vQIPgULt>mNvTCsD@ARJ>u&hn8Gw! z5NE2^7<|E0SD2K5Kc8v=GcX#axQx;lYNcHSlCtKF)pl5s@h``We$ORrzl@{F!B2d? z#)r{dM)gNPKyd2^6tEypM9XhUhd|~5K2R1kBrr_H7Zof?j2n?ul{pTlNEhOtu3Pvw z9<+aW0cluFeMT|*Ze9ypc5K#OtfpXvBj{q)vYR59=YV(^|4>K%77T@$wf) zZ~2`TUQB((Xa~Tic^N ztaI({Cjfw=fq4UbGu!~b-w5(;C@JWI|21o=%FXtAESPX!#e23`|Jg(G! zjg7K>^lh2Nk*SH;r~kKkAWw4mz;jHDfKjCeb~8(6i&J1Y08;hb&9_7U3|kCS57m+0 zqJkvsr~N}9%Oe0JxujmCNCX%jCx0bbAkPZF`jsFLDCjqO5gr~^)XU3p{2$>^wvQu` z?PJL_2w>08*NOrTU6^YeeY$4J<(Rnt!5jkFb1;5r?js>=FWkfiS%7DC_tPePNFn$P z#2VQU60e|(A<{V^kiOpldT|A?%aS&@B4i}wrZUB^M=%Bmgkl<6X2@fRft>MxadNQb zHN>UHgn+@XCIr()oURi=61G=|BBaLr0UXtmfmD&*1M)ja@Yc8H4WfCoAOM_J5+uMv zK3ekuBNk)HrpQ@uU_@$Ei_UCjVGp<6N~=SXr3d8o559iBY@Y{2 zcoA6BJxgt~NV0 z6NiwloR->blzm#GKoxpyBLF1ZOHB__^rwkn(=|1rGj94;P`mJ8h;>-G(xFtdw#IY^ z-FTiuF%Ba)yWxPqv{f+>nO(ckA%{F^QX4hQKH!0pp%Pf9XN1%^5frL2xhlq90Sd1$ zU#99x1){$L{LXGt)GrD8@ZWIdtMli-Vmki$#MuiLIOF>FfZ_O3JYP^px++0Hkeucv zkSZAL!;9Ch2>_XCz*2NbrZE8WOY)?uKL~)k9W8B{Al``=*S-7he|%v8WEbym(a6S| z8@Pr|RGo0=4ZAF1Pmp(42?p`2y@EX-1DWpE%f%*~}!?To$x215S4yfs>Zp`kf^?yVb}{=N|eI_Pi&qzoq1Wj^r$$Q$4jXd= z4(`0p3{X2vIqRlN0zXAmGTnqoI44@8=9@ywY=V z0RTv^a6SxaDYvDkycUZt#$Sm>I}yVi&u#fgrQ(BLK2q1@!^eiX&jw&ID*!-@h~Xj_ z?Zwe`aK$v7uB%(ARCkAZb?A^gz%6)2t-qDJ>L77uJ4ZD?#*-KM;wUm9uq1WSS+SCF zlNyJ>qKe+KHUt;7swOl7R+ROepfFFlc{R2G*GNRe10P{QuGXGr;>_ zl)zO{32~uNRmHYAi?*r3W`;C>XJEc-r0xkC#kwl~St<8l@i}$$2IEf#&2OcudOAJs z-K)BX2#KnD=tlw(3__%Ip8hzcVF>`a^itxt7^*>n?s*5__JC{f;-WBe2Y=v&Yh5OT z0e{!R^Rs7%>D}1Pa*%6^%;)F8)7?zX;x6{?Pri5#P{Qf&$&+tGAV+Mf&a8bFO{c)vcZUitQZ28Gdy3;>`{;uim-C?++h8e0b~8TfNdn zD*?3~3=08~;RtUYZg=td58#hZIPk-Szt>kLz%T&93B2R@C!grf$HkXne~?4t!Etb^ zsj;zXsu9*+?Yyn2_01YKI9SlSk8jB)+1pgqu9QIC`dA9bj&+6$+9B){AQG=J1quKs zk$p<^8wV3uF?V3)XqoYS*{OeF`*jeO z#y(DaLHK7xPuzfLN+? z>Ux{TJ`7=@5LSC?Z4G38K)gbN;rF!+yaF{$J_LwXqG*Q$pn+5TuVjcW!ea*TA5pN^YcF3g z=C#M@ck0--Gmjqeiy2>+$jMu{c#*Bs5BUS|rw63=mzRmD7!==s|J=E4kG5`We>3_F z=VB}H_lCeQ0j>tXC=OL5umH+Q2H0~k^P!~uAnSo?dTT5^@pUgs#JBC&%mq)DyLGWO@boOk%G1lM|kLxxbR@s3}LH> z&{fIjSGhhSlyf#hh=s{VqUb0(Ms%_PuqfY_#n1uBa09y(BOpVZMD=3FjsgTjnluNo zd_E4=kH)e*qVRbc#K=eSAf98##V}ZJ01yr+{W#-fGz--oy8wo@06<1p zX&jv9Xvd`&00=*H$Fv$VYh8s5tqir+pe*nSzLWNTxW#Rxla6N1Z zL6LeLYg#b>B{=4lviI2efgh!Ncr5`qOz$Koq+`I9QOF9 z#OPQfLvu&x(90q9>WFq=hX963bxU5Bg7VpW@e(IOzDivp$5Jl9lUmQ$X!M))1UMOT zu_mK3q+t7y??XC3fS=sL3Iq&Wt<^9izV}6W_zp%rG!iA+hnnE1{|yMXeLiw~q*Mnt zAFxu&7?L4`LL@3SB|VArAEcOF<|lMimf};>#8H#Kv6O{w;^r|Q5}PTnAqf(;-ek1z zhA6F=DhX>cCd+&<)(OU1rPgJk1q{MP30X4L`5C99hSWdz7lBf#u8T)UKF|AgrqCz^ zP_V?V52Ye-UQ~><<~=n@k{mHhnk~{d(&}hc+UAf@pH&_T;W#(joZ#l$1rwo6d3)>0Y5WJF&kZQ4WL3(sTU#-_R-WB8P{UlB97kE* z0kie)YC3>~m@1|L!b?o28{tooXQgDWGFMML{NJT}@WoW>=kBQ))1^p@r?~?=@QT$S z_X%wm&PGMR58fln$@}K@_CCvl9V4y2OngW5f%YbTDV`nQp?oZm!LZ1k{FTUGP#&BB zg?|5q;Sb*gdiv)5H@xDLUl6w}OW?A6``EFMj{E_-G=BMB94(h|5qS7;W#;=(@b@8q z@P&tWmbO|G{k|w-PJp}xA`(Gv;IRLG4+Vn==G?cNRsitx*az~>1MB|edYiJy1(AIa zRbbu1sfGwxY);DDi$nQ(U|+te5$OgbMHrlqfcuCZo{b)TFumd3xB?lO8ca3|h^ zHaw)^@Dj)h&{5`vbvYJ6p;-Oyf&&NA?>rcNA0Cd>E)u-NB_T9@XcUBDWSIJyAqO0g z2MI1W@4=S8K>M;b2wezsnhf2+zO*D~ipk%lHO#19V+1t#>FMYiKGP9!RVBKlFMz_y zkpPQ42>^LOhQG!-z!l&N&*L^Y3IrF*kt#Ygh-`3s$aYJcLmq;6Tpb33M}#@h>WbrE ziWpjL&2hLiauF65HYhW23=s)rgUtYoMF9YAR~*91SeK8Vg`446;DsfY>4~>tO@s2! zJ&l||9|7~2?b5~2y2<7W;6!URb77SGmtlw}(_bLuOQ)mV+0$b_-O6`lDDhLbMus)$ zAWcYgP!`B-SH($0jZAAOCJ(8n`mFjmy%_+gB6X^&a|a~TW1&EZoQ?dD^*2+;s5@pf8q?N$9Y5}{2xZ*YXk%bEC^iG?t7mvTv!ZI2TaUT zHKzJM7$10+8fi|5J_2%b zae?Frbs|qTu5WBykEIwB;*^wt8u?rl+}9UZWhw=gv!r^K6qj#{F-z~dS%NZ36htnf z0~4c6ENcP16B7kNhiDZ(5=s4rqxb_yB>)14gF%G&2mquOkVilR;1M4KhXVZ}owFp* zbhe$Psco% z{U%DiLTaG%@U;yyJj)`%o}T%*LK70cg?ahflJkM-KwEGy$;tkPycxhNh$nu8bjt3A zi+V=*i!UtvW&xSh0K&2Z1UUzi24=KhY_D^sLcH)=0PR@)bh_Dt;aJ4*bX;nsc{U$G&5Uvb zGm6y;r@#$Fq)P>8Of0=XAZ28bZ!-7F+UD>t8znc!^5P?r!{SRM6sI`lvV z9wH)e*h3mVnuf6fOM_frR4Jz_+aZ*mCY<@9Ond?$SXkf|a+)&*DQ`%NpjM<7%&vCZ zQusOe;{f9gWj06_R>(nljW;0>i$%oXIp(s#=?v2zi$ijfg;!P8l!SiBzYmU&D_3S_ zX0QqSBKUu<{1eAQ%44$s7Zc#=pnoRmYx)9Vf7h>_mHH)~0nZZu0E#6z<{iH$TG;{Ak+>0QMe!@yv-+Vvdyxvv1#z z7=g6{uLz+HfS-RH5HJAXaq9e-1S4a|#fwZDPL;h7Q6bR?HYADb;6eC%x&1QobhbNe zy#&7Q74++li$wa+7NWwCDFWaN-J#|E1-jzY3%Z#TAu-T!Bn)g(b4t+e#Zbp7FG|Iy z6xwf(UXAS_FS`Lmq8OkcG4jZei>QX2`xoZCAyd$r`(CmUIQW4*^hpuuC3rTP0xgD# zmSFkf$b;AmH{yD@=S>UG$B(EO{m^{SyI3eavU2eg=Ns%G0HvPb?+s?*vdWTz={Fh8 zf+GOH`4Rk0%qQ1NL(QoCdEEv_cqt_QF)I+jxZpG3d|JPXq67)7NlkiV%+4PRxCa2# z-b>erHHMj$^MjZ?WOM|GZAp|l<WWm z?U^cIBD#Tt;Uy3XZ7jdC#(nk~(5G7RK-Es^|Zw!H!2C5NB#pvz>hUBG7QWx|f0Rb1$ z0%G`b0+!wdD+m_e3-k#yG?1}@d>7pyNKH69j94pvX{y7c1?%rG-cvHdZUEqOUjzlr z=fb}mM8CTM{=R%$T<=};yS=?%0{VJ^eSi4RKfH0|B^>03Flt=nvG3BQJEA%s-+BBv zK;WI|>?a5W{{2ns@STTePQ~bVc;D^)06@#2dwXvv4RBQo79Rh_AA-O3;Diesuy26h z#1kN>j)SS@N@$6&xLKkIth_14x=<5y5VDx{>zVw*bZCMfzjsgR9Jpl^c~?=RFa^~L zN`RBtMRA+}w-Ekzys(9s$32+Pw}UNu$b*p_aENty{9~3h2H&Y|iOe1W3QhlB_Wh5B zV82l+Km`E4{Kk=}14Kx81R1tnYs~?#S&BAbWxp&1&I3hth=X3U6hg2_daw>t1U%z? zvbD`8^J6**ru5Oo!7}DL91L+1Y+}kR;}4{+VNU*buEzk)`33xv3%?{Pvee6ru8jQRuT0QC= zsY2o*n*-$4WO5yCt;L)^d$CpV$t+0AktU9qm8GGQ3Ugfz=0A{1?U_HOX8u=L+ghMrF&Oo{2<`z9LPuJyq4qh zlmcG)iX@0)P6>3d`a=oH%-%O;MUTS(2M6%S76JYa`|sOtzNzb9;CzG5Pca2Y58u9hYU9Se zot@6-oSa-(xVdoi;jQUAmm-$;@tp_&iGYtOeBnB5`12Bc=fj29Hm=Nn%UAdBzuNAB zkXDm#H~kM2pz@$sO@OPMzy!coUj?-x4?F+Qwmpg(XZm~d$;M{oT0tL(0Z|Dr40Y}s z9GUH#jVX{Ru)HKrJo*jVREN{zD-7B40!(CN_d5o`9V9}a2t>Ea4)4HW3Fc!-&pEU0 zRyM+s&gcy2x=RKh1S)vAGn66m#h2ZE4gefd@du|r2m*(JeJyLp*LE#A_vIxj{G$9n zV&57)CZlJLzn@(3flP)%;ECuF<-&xgPDGUgP|lD;w#3;Q5}H5c5^>0p!2B) z!K`e;^^U7ooU;;PS{<^V(dW)6XbbBwWBBnakVq}Cc2{y3y7Q`eqPryktgW?7rdlQq zhErkpCH&P6KnSRw%3Nq4QJB7@$qBF3Id`0>1G&M3b58QbTn9r=Y3QwG$}>r0dfi~G zD=9^+0YVxUm2mp2X4t->vNN7uaRKlj3;w|P=RqHFjg!946A(-1t8!l{{7-T}>0kK5 zJ;h>0LKp!cS6gOXA)8)T!24`O7rb#GyxxWQzpiWIdYNu-mEd(iAU$#yv^IC4C+?-| zz&`e)593ze&%WLkF2eK%ucHU}FMsg}`0b51wg3K$hCltdd(@N%Y{1*L?!CN!FTP~) zg|slcaP#8DOE)hG`haqe4S%a4kTW2_kN?lkgbny_T8byP1rAs}zbDQB0Amr%x!3_!Spu%Ep^Fk~dmW{-l7M2IFp z{3!$fNCpqNDAO3o7qJ*?DAXoQJoIEJq*M;{8$&BrILw9D@fWwYYpn$@YwhyTcY&bQ zf0L6T5P$L|ufc8v(X;2*s17OYzK58FU{#>v@DGXj4NkZbS%b9}!}vBbfkkz}i!OX4 zn9!sd9GN;azj{gLz}K9zkfofQU%x#SVV+ffGzFXU5PE3@T;K+sokllsPfrE%!!#G+u`!rIJ*(KQ`TvU_)-MASpCkLZC-fX?cU5 z5wd9JxD~QeGb%X3Pi$Z@B};+%u39+SO1K=x4R#E#4{aiBKn|6bM#2mQe#A%;A~hka zbwFeYWiXy62c~DHxq~A!rvdg4tiMQ>ZlKn1po6OJia#GJG8_0`ooAp!MV>z}%=NOm zU75oLP`UT_0DIEDKo!G4)cU#e0RXQ=IzT!<*m${kmVV#+7u5MdE67=XXI~uq;KqFm zWJ-*T!qZ}w&O)i?Fv>kBlIZV$30OEZ+=YZcodTbF?F@1- z`IomX_G8ownBLpBZ+E`-TT0X}!_G#2?&i$JOStzvyh-$XD4C09z3?6Ff`}BV{%jCE zk!SY*v}GZ_0{)E)F?=BH?}z-qeVbl9vv*?@g}_qu*FXQ!D1>wS_O&}I>w9_7z5)LJ z;3v=S+V$+Nwr6*J_8G6-bhl|nNYdce zG^!}c^I!17Q2@9_HerRrAP@`T2m(OOe=d_38V&_PAfFvkKB@o^x4oh0`uEyO4h+TP z9RG}a+<*fMa-@IhrIwcjeQTpqdKG^d@z$(a3PYdAJukr?1)p~m%w)X#it2C_3{#;4 z)(QUf5^!gJr5_l=m<_u0xigOUIqLJWdEZUUyXmf4klc|UMI(fsN1?g^CklNxyh)8<(V7+Lk=r|3|3pVH&0J{Tl%}Rw$b|_| zO`kqAN~|a|UYeT2YQ`-vTx+1lOYQV6{U_l)sAR_>l2=I?Q3^AX1F9Sfipr`q|H()z za<;mGkvCaq9em}@_sSKJz&SG>|JOmN;qg^?c7*`wwzn>^zxS!{1MZzZO)BI*G7!{( z$uv~m0>>?WxgU$A&uVf+VK5Mo00^bVT0F&95L$yhCV*W7|5Xy*jVlxegt6K zxOMOTtv^j(;_CaiJAVsT!6C>1-5i3QchifH9*G2QrxzGmSU<7?f6GRY8|QAE(**c~ zK>TmQ3jFM@S9kIIu2%58O`tpE@nyhiqpE-d05*{)#yN0{Hs8q+Qy|?q0^&G`_u^wY z0`@Tt#{M|~rbU1<2}2_dk4Sf@oP$}IkCy)K7hIl4N?6}5iuMF3K3Kv)5xqkqg@?s_ z1p4EM&w}jxVEzkX@8#7txS>FPtn~tnxO<-hLniB*5P8K4xCr_t*Ss`o(F?a+#z9YV z%ROZEi&+qje;Zthw82_v%v;fxt8WU70Vo;}7rg$`HWJ!1=N;laMvx)^`g4o~azw-~ z7!rYDITFTD4#>S0e;Ww0^8Sjytw#QZX+TVs-OCQmv}%*|nj4hZ$1LwQe**FjjDe}N zK(U;%s8G(f;P>V3E8&Z>XL#QOBNpbpu@xI|#F6OTX!B`ZPZJx@fOMZ7$Y?q zZaOZhnlN#ItaeCNO}+dd)*?4xsLF7o^!!KCBBP82qFI4m=0Zlc7UgnL%aLNSm?%?7 zghn|vRMPGdx;;zQDLS<(>#Je|og6tA3S$Pu5E6YQA4>KM0@XxkBI`LNf`!Ol9a^w4f6L_D$ zt%L#M@!wDWTL8HD$*yN#efHH|uOiLr)%DnNdFKNT!fCK`5bH0&kCCUzWFN7RIEO*6 zZ(>&0KeuEW0GWOd2%HUy7)NXERMviz>yX$7XQ~*dz%7i3feNsT5iz3}{YEwXaRvnZ zNvaoN-zoqEH#~eKT>XZ_Nl^3Okm`X`d7=`29IfF}d}!CT)UWgplVV)4s}QH&GeNYoa*ft;<%GX2VkoO2%c zxEzHj$ekM`*M~a+{b9Zom+eXa2b=q1WyLi~$vfXb#Ficf*A79Ngb?~Qj#f7Sv#>f0Y) zoCNm^)iYyXq6?q^P!l14rz3sOI|fieFq4`EV>NWN6pxGqC_H4?3l-^Jj^k}uPY>aR z4VnM}W+P=C_}p*q4`>`Au>oEe(w1hn!O;WPYz-lq;PSjY*g!zhzhLMkR8l4n9UTO{ zc@1)9UocV&n)(*XezLGY5Vg38S&og(-d)9cDF8neNM08mk@t9-mqA?rnuGCIM?=dA z@wKVftQ-(n78A`NGg{~LDB*wm8E%t0fkymAn5tT!hYr8z zgrKpWI_VB%9}t_x0M}LuL4ru*V6HV+su+b?Fh4U>Rdw^GQvnkhNCZo)LApnpmnT2G zaNq#_z*UNkMR)_b-}7I6^%bll7y`8dBke!}nCt9=QwaW9@*rsX=)xPWvjrIM4FGu7 zEXZP5h-nbv7Q8qPs-#Offlr|w7>+p3EZBnK1nJsAJq)HO4&>97I6EA>K7T)9~5o(B(&u9x*ri#jRWajEawCwtTenfOz=! zvDfZc1`}4`i(A>4&L9Nj!5ltydGCo+@6#5neEq{e$^i!e3>yL)OP@EZ|UF4GMl;#iZZ_Z3$_$j;9j|9)# zQ0P4ma5y>{&w$pqkQ81cD=@KeV$wk{_P>RxFABxiGOV|bI27x7FT#rS^C@s7Sb_z5 zuIUK)=gCknr*x&Wb2p`ZxJ*?Gv9S^8Hm^`F-r$oiY0>tjwlaZwa-qPf)pfdDzg0JgSTOpPK8%A*s6N$t7HJjF)= z#U!vpiEa(#FD%r|C9>vDik>v9tF_HyC2r8_%zSD2D#AB*CKZaVImdAhSq3%J&YzYD zMHNg2z=C@)Ydb!pgO0kt0!dx4$BDwqZY=d)i8XEYQD#1+I$3s_a6`s=pYR0OwhPX; zfn6PbC~HRQLoMI3c7IZ%aPEvuL=jIv6;C*{jHEQDd@4wMv}T~hb@ z`I3b&WJMA%`U(KAsSvme7|3JEfg=%6A;!CL6U5i*N#vpa{M0$M8uecNPw1NujVxTOuD*2hrnlXPk0tOE-}^O( zzYp(Ry7llaBBHckzBW zfiFMW_LgE1m<4lVHOsLI0SSH_0Ye<>_np8z0W!#R5RuM^#23{8q64MAuON?; zAOrJx1mquUR|_WXQS0@j2t+uHa$;cl^~gv3>kqLB5=;~MhTKyy>;#ylsPl*pxFKHv zrTn8AgmL$yp7wMITqAZEhF_At1UYqoV7HBOu{;=ZMr1zL2;FZaK_V55WPSna2Ky9} z5Jjf)t%tM)FNh>5>j{ys9L{>!iKp;%VhXUBTn}1<_r!%@7Uuaczui$;c}3sn^YH5c z|MHChpr*#Cyd$LwBLZNGP4wZex3FN=qr8&dXr+y!U-YwNDqe8}M^j(~Yaad7yhIal zCz=!)F29J>mUSHbR=Zxv(f>j_{fO)0NfRo2`Jx) zv?WxuREmKY&L-@GgQz&`@?QkZ&ru^NhJb;A#k2ypus91*imkS}amkGGVzNw3Wx72- z2^%zP8DxMLYU@MS2R}@09`=ODj7Gh(q=F_vfP@?cVc!7Ec2Mb;rF6!LSZ(S+uU9r9 zJR+{VV}}zyc-O94=mSAF5?%`|DK3-(ic(aVW5$1un}0%V4)_qHJvS7K{2fF8XN^m} zt1xi`l(LeVLG%stzpw@qprWEd4dYn?)kbIE;}rNn9LROXp1KO;EEy268}}DKjbzWv zz8YsRKJahc4eG%!*G2H-kD${40fJ|{-C-u>+VHw{k505ZRGpu~< z0|N5)_cajk()9GD>cPR$-TeTs6K77G*m`2))nlM`G1wvdo^#*PP!}QqoR0udPT+?_ z+fMbu`zsc>{jGgx_AV<6>s+q@@PAan2m-%90X_*6-~|96>yVyhq&<~>jXwF6Q}`My zGv1y-fz&h;0DT0UQVnL4AyD|&WC+CT>#(*K-o>I!ef@VBISd#!QRaP)#(xKcq1?G)#;zBgR zGd+gCpR#smj)X}=rSi=f_Uv5z)B?BQWIWuhg#W?jaUku+I?sOwKJUS{_a1;_9Ou8* zymJC!3+4m}WGc>l&1gXOUH}5q)=5W*menMf$U3>1iTA=sr^n<9*m8Guw2|47>42svxkml{wsN2iAeH%*ZPYCqB}+2(B2TE*)Je#As^bse@|NX>Av zv`wU~SmR3~BmVg(kW$3H5Zl=?oqZ9 z`n)uP2}EEa2$k8-yzO28bM_YBRg^$gfF6@k#peCEIa1H z{)=rlC^a|(h7xbgB=9hN@WC^`wlL+(kN)r*41Sm3=oPc!{FXZpzkc}j*B@d9et7HF zXQM4=ww~AuhIiwMt1s@oz07Zc*Hz)=QH4bF>0P!UjeQu8fOkGb6v9SR9-I&lFS8Lz zuh9lfq4VpX|L6p`4>IUYngBmvm4#pyczlrnxRc-5ge0ejsNWQ?QGCzfPSyYR5gGAC zMizJ~*%Xa{RKH9$Hbsx}pmtr}2Jv>q=_6EsC#hhb3poV>`8e)**YyNQ{R;@DA>|>k zD-%rcW~b(pCZ-=dScEAk>KyX0H{>>T;+^G!LtzJwZN5uE_p%hcAETZC+0-=ZkuFSu z{4PDrq_h4GJs89E-m2L>%nSrM?k)V?`sL0{j#$h%klVg-gd-3NpUI>Bdkj#5cJ&I8B#Z zww0V{ZsroFoD2c5t*wYW$=11SF#<7=ytJ$()au4S{45q^!(0}*c&+#;cp&G6Iykk% zaUn+LNk;9KmsXgWo6n>gJx}wZh!ie1FjVo!%<*|a6#oL`ZLh# zOOr@j8w2<&R0S2C?XRn%T2%PQ%t^B<=VJBq_3nM+uYk#y6D$A^Z@7X#C&V{gDHYFS z<3>W36)_kBzXAXP0YU02{1msp{w}usLJ=rg43^+exgApzb6wZK`$&#qAlCgrf9S*Y zeFxDGkDyg!dWrhWVB%GI&j-((*wov5cMraQbVO^f6wQI%<^0D`zm6AXN6$Rkdv)X0 z6DLk=Jays(%7M{ozP!9D4YfBa31KJ5QF`e9bLPW4k7ERUc) zFeJqRp-YqIK}DhR4j927?uJ`NbGG5Hj0@ThiQ(H|}G1jsQ>$Z(~U-{ ze=z|v8B3ny8em=kXO#*arNZ?2CrSG3{_{h&0R!g-_0IsWc}+U*IW}6F7{MSOfOLhif~k-3_yPZ}^W_VI!TV-^)fd-~ECj5- z;6WsO9^c$A-5S1g<6?W+@X4q8FQ54(?{cWRy!(fXt8=XG-1(Xic(_!R0s#>@(0K!Gb<|Nz$|M2k6$`SC+!<&zK+usb+B9>gns>n{@cE+JkQ^N&sKR=V-^wYD5L=az4Ad2a__G`YWP8&PM>q7#QjP9+1|!Ki=Om zPG7LZE{mToekySwJ3@R5#H-i%l)kwx?!L~1R$nG-(Qygv8kZ-S>75)_mNv69_^Hd6 zuL8I30swEX!RgQNhsW1nKfHN!V(HA@t!Kb=oY=eVmshW1-zDg^hb^`@O306X1p9EW z`$3lf{PIk^0`s$uod~{P$LQ}r69BMR8}R>d14Ix4R^WX!!mS6?o8T%7!vhc(p{W1|i^$FLV+&wqjXSQ3r0 z0)azDK<(9dO86U%@XR4tnhQyUDE&UnfSL^ZLNva9MxTPB`z8r|^O8rq5jYy-8hOr} z*FA5-;B0Bj8xdk`^0)aeUj(E1($P_z<1nZ=7{L=h zvZB?sQY1za&48B}00DsfNhN_BttKRdnI6z8mPDEw$11dX4#dwDSF9{P)>>_V`_L`J{{asKDUKa@NP-7-PL3fMl;x;?GZujPvr!JppZ#R(r z=fur$`$Lw&huC`;I#0ZagWro=Hy+!xZTS@UUH*tl;FOnew|Au$-T0>wkPGmhk47*_ zK8}@uasvAV2pP=sencTC8>^khV25G--3|-@L?cK$)AEB8_{sN-Ad8E~KQa1g-`zPl zO8{(AC@LR=$({TX66Y~R;e{Y@i|&33j@CCK9{?~(j~s9gFq)Jr7$JjG5gQUzFltA_ zxYcFuSF12yz}`zOG@)rTYp5s%#4=18Bs$@>`1z=&J(3*p;5QVC&xeNMG0^~M3{>Jv zI0CASbE#{#3%>;ma|n5T6a?bKyaul^0CEWAy-%v>C>U!^gn<|VXAOOU2KK}LHVu5# z``HKAq!EyJ!KMkPMQ>LCOprW}=z}on6q3t(7*T?+zv&VBxMERBNA38!zB>OgJVu8L?#S#66!=_AQhZa zXSBtwPio~wR}8g#fVEu4_bUM)hcpZ|CB{SJt6!XNksJx*U@F8%lEKZbQbp%7$^eu> zq?uD9(UIAp*;=&k0@9i}pXC@LW7ltMvqBYuj!>RlM@92z1+fehO4|mq3|?-_=G0J< z3#t>9UpCb7NrQfVfzFWWf%n9@M8!kPg+6lwx=IS2;HEsTbtC75?WcBxNM1ViK#1ZvwHmHLI_ zpOOKc2t$6Nf3r__EuP;<-s0J2UI2C28+A|&p>OxlaD;i0?``eMx22H(GBg_TAHqT* z;HWa6!(nfhsJ1Hn&zC?!8$V!;)1fCqJoK!aLMCRN4}&XUB#E9-(949qXu`cP#)Tah zKYS5nRS0D>+c!8fpU<2oJ>eOWQfWa~pe<5K)gCd+Dpj73`ae>E=tzkvPTSWJr#9PW-Jfj}i3}-|3YQeIVU2cVA+kNC(bfy!izH ztXI!cJ>%-h<_=7|SZP2pg8o6sbafIwPBUOFt3mLVf~t@x8AQ9f#L%4c^b5%w%m%ms zfQ7ocTqat;3yE8br%6Kq2rKqKALwaLNZTX6D52JmdsPS0_t>c(839?O4o4g(Kd#6; z6lSvs%7PG@0Qd_4AjAI7It+Te>;76;dtbt```xFXasa$0y|X?>a=>e}jBo+A^m&|w z$L`_r@$1@#-+S)`<-_nai1+pDNRKbs-RriZmrX$S=M6VG|9u$zy*DR2x1G3sN*phx zeZ2wodj0InFFow-`2ipX2*i8P`rC0Q8URJATy9tTshHry?N_&Mz1r?pB~E}h;y$GB zPk^t30og>6;Oo%@_$1E4A_?;QPyR}x_qdS^w?M$4&UtuXDBSs10wC95(ZiJA((x-{ zARm?jYUPDakY3+51i#>fe4YL%3~Vuf8-_Nd z!dMX~PFFzIzqH$&2e)7;rH9r2b|ffY!tF1D!Id>w5vc0?5C9U0#c1FHI7;sa9o#jFV6x=d1VLvas%ymtFm><4BtOmsh#2Toahby1BHo=S(J z9yI2{%nYDhp&0UAD4!-k;!zQgLUWq#h}2Neg-fAkKw{UkyTVR9rvTLoD|M@7LV;rp z@)Sao#4tP>V&iP1$gehw*$;B*EUPzwe|#e&k2-QMt^Z)93y5T^U={Ou|L5uVEO5t^ zhKt?`#(nwsBj5Mmc2^__e&(qq1mxfOFb>4O`KTSXw>?(Ev@c`1J{INS_wH*K%ljiF z$iBBQ9KLnqhm9bf0ilD26>gA#B|AqSUOKK7*orpIg*$l{Bt61-n4M0D!DD?=Ghm}B z;VC~fOm6W^sbmC6f6@Sk1XP>fwA#`W3@#*qpKg7CJxpp;`$f@! ztNKA^pAR}gLDq=UP$$WVxEIrz2a({p%qV-MnZ~MU$OGq9tIp6sb%-EMHM|UN8UJpK zG+Dx@)Y4Fb8Ic;Mjmy#Jj<(&^WC&+JzBTXjpPwZIvPtik3}lDr%b57hn+4H_<#_9ntec70@8 zosz2BI2`l9`f}pK%-1%zYmQ0xx&rPZbu6-&gI|JeN)4DJfr9C3k7X<>BH|JG0CpVy zcmvFO6V5V?Px#lN-~n&KL8Hf^Evsk*MxfHbA-+|C&SHt#Vvebi843J>k|V|N(?cvd zjP~GCi3OQVlOdSrybEjk1JKPhH1IdB5fm56X}}?$;6@05&WdmTtm8ADDj^t0a1Ppj z(IbNPI7o+h5>?kRE8Ur|sFEh06RUCxgeC}K1#C!3w@p<01Abc z0e~3NKIHw6&bNmbLD}{m?d|xp9;pl9dzS!lQHVzppDH zlrV=+ZPWzlekHOT0Jt9|K_CQtYu}C60gz@uK95P@kH5LV`EPKLc3|aQHSHuNJSb+P zjERo$_gA8y2;%U}$uA5_ApSK@h1ZpuKstE~r89$?0dW)LXlMZp8k9f+0|42P?tYLL zI03%EVEh+W?tuV5{%FxDZ?opU(NQBGh!JbhElZEI&_hFO41jCnqK~DB4Ou<@g&}Y> z+J$GCXd_QB=E6}=c%1Pt7mkD<8u!-3{UC%tr{g0IIxdLggB3|56IT2w8DU}yAQi$) zgC&j_NmuUn4bsAB06gUQ=!p%2NC2RSC2~s1;q5b&L}TO{wWvt$54LLBc+~n4vQX*y1(XR06%E7nw*r9-5wNYfSr@>$ zW{g3=KdD`G?`x&pxjLQ49*G={P zM_Lt}b!rM0AJ#@)Am+Dvh0tef!j?&H*A*m6QI$`aKflQ6s*pA#H8K>{N>?DdA}0Y< z1-pE6GX%h@0z$3$-f0H|G7FFZ*q}@=hGo@vFr{B%)d0W)7g2*LK_Ny!@WEt^>XneF zKvu;@p!^eA2tYopy^IKSAZkw4n7MoP0Kf|mJ|)|W?+*xp*B0;dqDQUYV%K*_iC**y zj2?89o;w}d8Tq&Y@*^q1fHeef?}s#+A<+Er7VW;8{x-Ml03Fh~)gkq_m*2Sg@S$sr z0Duo~E}iQA9{PP5gWO&I*mLwtrsl6|P0~9}rEen)eq_NMGa1caW4GlH*&Yf@dO6T&zilW&^K}>p@D(xvrIr>ULg4O^g zP3|V+M~J;Qu$3_B^eQ}yv@TKs)?qb{9l~kHU2$j&dcl-IQ=)14LaM8s z8$*jjj&-;=@v9|nI#lv%jIr$_Z(0SjAE1em(XHBbiG32mgwx+H0wC{<#bU> zu!6`~Va#eJ(zNH8dykH^tGVn_L8`1#Vwm6nH|&gi+%Ti@QBdo!lc6P)DF6Zoa(b)U zLMXby@ANb7!MG5j*uAQ{x>S#_E@lhn^#@+B@;b87l<%~{28=L-EOy^|-Tf*9mBgn(bVqevMQl1%JRrj)!M) z3v7`Vx@%NlaKONBu$J9BK!S8W(;M$1Zth=&f6)tHdf+1h0s_Ch`@`vQ zRfYPV-rIY}?l>Dd+yH-nqFp1PNQFd*nk|8W(dI1pLkHrWaMMBl;%kQg|A z{1r@ppBz8z;Afb@V$gJ_tSqVWDh#&Yf-%XMPaOmOB8T$O| zKwn>rTHi4JtvwPZKQGO({*N}`A@&~0{N@fMN8m?Fn2G3VwCeU9!a9n%F5LZsYj`r0 zBT*^yydwhX33mD)bS$KPz3hG`N_gH97a`ywsQxxfp#fa{SprL*^nhV~j+AXO z6K@Qpoi`52BJ>&Z_zRTF?u+9d%!Uv#!6`SUCz+Jh7!WXz>#gQLilP^yIOx!aWc*77 zhzw80oO>EPaRSL|rMa}`>mpBFDj)fSLyDFXq8V|YsfgPJ7-$KeE`*ThI+)@BqJY4( z^@Octk;!d{@#Mj;StmeiS`u@7DXR-%Wf!A+cVUg(C6ioM+%a^7)x4^qh@5IeCM^%N zId9;z4&L147tXd;6siS$3HbwwkanL_w{SKgQ=Mef*e%cJK&;Y)#`%wzxU4UO4Ai0; zkpPHdr2(+nR2AYw-Eui_Yle9KxIGvhK5BimB zxxIsiNf)YS;A3v!f1esLad|zjrebZtNMohkTfFeSITeM3`~#PQa2mu@THzK2fuR07;xi6i{P51o0{r;v zM;mzqWcCX=kYfNqw*x~6EgAIR!5_Ms-uiaa4T@l7gnJSuz&HyAX;_-p@IV@%UpQ!M zoE|_jzP^*FHmHnzGLG7?xC49W^R6@Q{C?z+q|Z$gjdt~J_zuUx z?;>RkH{B7(B`nC+!Q|7j3qqg)oM=))ATNLVQ&ZD2VXlv%6eA0s0Tpuv_Z$D!Q8rmp zT0T?7jr075RuLd%1Y;frY4}jqx0HeD@SLy5wdXPZrQDU|pcs35c@OlIX!3#p7#8M~ zvhnfm?SUl;X@W(0ych;`fWuH-19M?+H8|cLpR~D|10DSi`gB}_sRg8ojXaAiBlL`@ zW=YmckD0#awoK@f;kRuF-L~Ov9_ulRRen5f0b#%cSH$SBDO?U+W96h!i z^})gKd+he@A5y+w?s+@fi3Njkm1dNM(7tqY1poo6mmY1y1lSt@aCz(gm;+(p{f_~l zop5LbIrrA4m9%IYLB5GpFyjn^A<_Zis9mxweo0zbw>6aApYq2lHX1NwSh+8(B16f*$K3Iw*&R#C7OfpNt@VlTlbIj)JojO2=Xl43iL^CxJ09RstH9ChAxi?5CME0x>Jw3&64qY&NCc7%ikF_&k_?SZwiek{j4Y)j z56Lk(sbJ{gAabcAU6#18Fq0UWmMkWUG4#BsJkuNrk6Q!uif|DIRZ&$XCK$2UnA#+k zu9;JMRcWS{t1wN$C{BV1l14xA$!rG3pG%=o*9wB9W)2lAjGiV&)-xEEVPE)f;qQ)v z{ZG4i3cN3%R8|ZxfEW!a znPw{pTb0g|_rTfD*LNYH4}rM9ckbUvA29nrHYnd-^B?`ckCvTiwfyHl|KX$kZ=BiI z`~Ip+pw{6pLt*+4SYYa$MFI~!e5@+C(1>}db0ec)umm4v`pb*^Rf)+r0RQ&=5CES< zSul_Ro@?g~@VAi+S^yXV@pl|Y3e2lv+&ick=P>^%<%;;HDG<~LUj+u@$et1aLKs*M z0N4~{GrAu3kp}^nq9xd+A!I`gdiY1AyAQ$mm;#li%5D&GBRmX_x+;lJNR0%$2%!(; zNJ|J$Sn~9@#HoC#B{ZtHnC3MA%3Iu}Jeei_ZAD#}yaB@f!KrW3rN9{etN;wQIAYC+ z=RU}su>ea47=Uk$j+jou?wfEF^oIYRuJ?b6!amoA7Z(;b8(tE!%VyOhXer$_4XFiG zvWIBx(XL5@0kc}7cG47^DKuM<&UqQljvBY7#APtUQ8II!bSAHg%{vwAJaf`V6@M{K z$LI{d_1}4}>$>mHLfSs42(TbEsyhj2;(nG3atc$$pe$)h2kV|ZF0P*5%9o@ za$^oC0s(DF)Iq-=3$ZXo+Gs31frb%PcJME5vQ{x-r5-cRW8g2}0FV*fDP(5}t91PX z0;W0KrDC;|17|>t?+CenrZKFX<5(E?w7+o1i+O5-od_X@G0bZUGh)2`Up)C>=Tl=n zm(i;69Qzadt6DUtfPmB4dV63K$qykLOOz}gPzt}C_!0VwxdVg!1;+8MTK?jKO?(`t zKx~Vr&!6`Ru%SerHj?A~hXIhCluTUdh45PQA9+)(uJm9?j+~`*MW?}5wN(=0@`&f> z7-z9qb_JBqMI#{bj|V_XUI>?zE)xXJADpa8@`9(S>=M#qvP1Pt>`2N^o8X#qLscU+ zv~t%4!ZtR#R=c;9%_kY1->mtv!AqaA*<6CzH8>+iz;#Hh!)qmd%<`&~tR+dON`Rk+ zJ|JN8yk$numm;?Her)+KB18Cu)1UM(EQGtqeVFv{0#q`yh=F$DvqoZ!9cdM_sf5C->xE0=jI-u59!#KSH8UR=I3v|dGg@J zEj?>_VBjG4+@Evy`?<}2Ki3LOUx*pqj=pqhIV2%STfOw)Eb$H#;A?LkK6_->gX4@w zP!<*^z`uO+F9*Q0XJv%ju%;32v9h2AfghehDW-9|J4Z=+PzTM;H#OM-T4a#n_$lqj zh|9+dZG6fwg*~l%l>=bG?H~fcj;QDp-V41TeNu_2-UXr#b(VwRE=cH8N(_k+TnT}E zXb(0*cxy;Y4Z4_-E-OviB$u2fKqrJR5${~pUF0sXwJG1T8{b2(}3iL?7{xBzk z%eDhggc4xV7{&vSO9(?+cY=DDqIpFY29)zfs)DS?i!zH?M`qgWzvIBH@9E>lSH{Oz z)Qnklk)Kr4=O~2cV3rQdi1afAOvYi6>0tJDMVcCh9*9Sou}VuLH|+EfZDVC~o1}s% z8sD({wnZiLi?PLs?~6L&%MCVaa+bKQ#`tVlUZd@`$xT~sQ!I@MKTsqd2^fp7F3I{` z<6u(=O2u<+uhO!hn}YzzcxMZDR^LV>q7iV(+C4~yXr(0p@^K2%YEn0QQ@f!Yl4DMT z{@4K$6c1ITYP+t5_=UMI1R?NAI_XxXAT%mwrBT|v)+$Svs&;21pX;^h7&3>L1lY=x z92j4&m#UD9V^Tu^t9g7GBh4^`W)Hk4O~Fs@5i+d}Dt$)=VKy%LN)`n15{lM`=$Zp5 zJ)}mrEPjdyfm(5hrN$v3f%$_|;AxmE$hj_=W3UXv^zl11;%pyg1Wp2Hg8g+Zs2qST zIC)3JvNFB+CBSCf+Q4*ZD?_LHg?GWb6a< z@Hci}O!1f`G53&~&~JgL)+*8u8Fbf}U7Gkk*FW$&zq8<4efuCd;IEE;g%YGU4=mdT z%z5q6^3N^f=&30Zh#yBNrad%n!j&!-!M)Qn>JnYqo4rrU>N*N;HMY+ z!;miD8-7?8D#?(3xqexL8Klrc2Alf%WP=g{lchV!d27m~S>%q=P*1m>w;Lc55s-y&pNTLlocP!W$1NBjNFHQX zt~WU2Bp4iH96m#!Uq|z0|Co2h0VMGlhQTONlQJ}M#Qj{{F1@{d!->P-EHDBdpa_N( z2)9;@fLmGJg9h| z;jw{75AQvDV%LMsM=;)o&PX0=2?=!vtv=J_G9w}IK%kt*H3FN+677^i8|NP5-*MC5}_J$)dH^GL=zP z%~5vvQTk^NUM#`%1IGk_CWVQG&Lk84wJX(`pUQ?lx4oeY*i0Z?q?vQjzUJf?k9jV1 zQy3O;bd0~>zD7JF6*F^K^0szX6;g_@QyuwQ>2!-sp&F;fs&u*NMlAk5Oo9}&h;l)w zDVjx?8!dHp71JTU_}U+xuaXnCBp4YYA`R{uCW3Iagy;{z*3ivADU%BT$oDedlp+%5 z^eK-;{k`0CsSD%^%X=lNli=c2$X3E*WB66G`K`)YtIFt!hG z43`U)ncvT_7-Z>2@9<`&{b}I)=wF%NB$@uo+``1ay~o~}zWtefM$MJW6I+OW>iw8bNySg8=xK57ss!Y5r3ul1+e7O&tU;PJj?b?*#l!O3;GJ zBq1SHFkphYWNG}M4URJCRImfPCs=VzqCi58oXvoR0pEx%8p|+nq#y5KO&qXJ*tfMy zr$2BY16v1-E(VOTLfwQfq(yWT9FZ!TZ_^0)dIF)a~u{Yiz}WB!`CO31t=w-hq;&;hmw`3k-ve!(90?7X--G2zbd79&E~>YT3EUG z(hjCv1Ze7*m?NVZKNN5EEViRFJD4(1Bb^8IG zU!F&MK!~xoEc%T!PCaBgs$!_fqKf^^tU2_wpuhdDf>d<6ssqn?M@9HM9i z3&wA-B*8|nipw^_<`Ln?@_$IH6^%3}s@^7-t>+?)A{6xs1M=#a>)b*jgi;;+AwxC= z62Kx9c6%TKo8LT18Z#aYZ*r>KftV(~pFX%dY=Fb>)jOm>S}k>-wzp$tA0zy1|!U#Nsx&;gLk@q#hL90w_R*{BHOt8ZVu`pyFGeK3f; z3^VYDT|5u6sAuEIf*FF9RQ&q0TlR>tIQA09wMVu1`bUp&@tB*tF}JjY;rHZIdif;>h8bc@<=uS6F9y8HMqA376u8sbCLoA1!ZiLN6ygA&VO>k#RBlzENGG#40F`!TAn@jT@yN!AV7z2 zYed+m!yP~adgzjkfCMHy%UP%@wbk;2h&hovI9D}s3?Gw^TlprwA}H_R9aG#NR$-Ni z zt&~dKYO~2km-!I@E$o>O#Ba#35X)3<%f@! z9`uAD7?^pPXRwNZ%D#F{xW*Tch81|iL@@f40KmBiAx992(0h)ofAHY=Sv}z(2omI* zf4l)c)&RJH^WTvk-2fj48O#^q1jrSbS3os-@LR`ME7HPbM>zZ$LyY7Dh+v|9f<8R; zkrYYUvCuR$XqHoM%rM}zEHs@|r2b?&WG1L3Nu}zz_fZui3WUeO!hoE?Ov_h1!iaow zijI*}j;BFV!-u?=K*;C)Nt?9e_OnQCM44LsP6Chg`vI_DSHKa=L8!?9N9_D(3$RDu ztLu(mU|P|9cD>Unkas#-Gzxl*t+w_{2q{%yxgagH?X>DeD*Ad%0GuFLxGoJKH?hd~XE-woyzXppI9GWKTP|3p||o6T`f zLj)BzJViX~l$Ss@;Pf0zLdc9T(#qt3RaJ!;0AgB%i!7gEM+lc-VkCay@|@$J0|vNT zJMK_3%pyvVjwJ91QMN$BYR*PLpxTfiDoKoCKtUwI9A~AeDtkE+ffjFwZRI=286!1j zsF5}dJf?(OV6vpe8Qd|};rb?G6ewCTAlXI>xRNkNM?&kxq#K!QEyHG*oHaCLjE`~$ zS(M)50LbjsX0F+ZhBr~z|A`UJU$#7Owt<^_Xwy7O`LBnM2|qhzN) zz~37`dPDOc0q}g}IwD^%_ett*Vps>|Uz@SPeAbpR05rRY1E9SYwcrG*IPmRh`3Pi!RV(ZOD4Uld;6PfN@Q8GR zR9F%MdHv(juS{$t0B&TD=GG4BV^(`a!~xScjFC{K!UVjs-vG_3V{*-Jhrt-@t6rpo z<_hMSub^w6_FjH{MShJWev7ok9T5BtpQNWqexOG0qjLBVH>|(m!}+;v|{X|shaiBb?MQRcOB`0`Zp}} zW?BupP|vV0Sp@&q8Pr(q+lqB3^aMy}+C(z~_+ zAJ)oC6-(xD z^Mlr^lzQT%fNsN-XJDuq5MbEWSF?*qOE}0=;i$4?3Oo+FN?NwA6pA)^3Y3OU_2?Y^ zB#7Z2T(Gd{egYsvp@CEbqK9d@;S9L-3}!&+qb)+PYf}&fDovUZ(?qy35bdCJfcO*y zS;KlH1S+cp&No z!A|GA@uDV07F~vPeEyaa!cq8g&RoOpmBSQB^|ZrZ+F4+pBs|;M6JJtkvhddEp;_Ho z5DkT~5S|q^j@UM2!^e~WFxDPIRJ}ZDW+qzelsl(Xz&KvbF#EY(Q=x8fKgNmh9QI?% zRCKn(V8(R7oGrIlQS(x((7&szp0fQ&QAjgamBtyKu>_gmI&1#Xx|>S~Ky43hcN<+q zd0UJgBm~0_Vq9=6=5NlQ?j{CiTtJ;q_*GHq2bA{>d6bkKA}r?R0!&d1P!Isv%RAqW zZc!z;`L#+o)6E5(ay#stR1#zS(( zP1E(P3YGjCd$3p)Jw$&HXTK)CyG^r1faibo1`*Ih@gto75PK!~yFRPTQ|!GO{ARnl2!Vt!r6EY^ zr#%@lSsd=}Jp-okWn>4w3%NjXnFq@gr~jT*U1wb8Ff=o(law z(+IfCiZ~?096xsW#O2GEH}5+6;KBCY7muGfyC(d_4RCv{63OzSFJGElRuqh{z>kIn zfRb0E1nyk{ppnAr1KIG+U;Y&fj3}7HJ&R(2brPyuU5lq0zhhow9a}}#aW5OaJ>qH42VfQ*|GPR_KSq{&^aSEk}OH8 zQ#dG$YYMc-v`FDi%m9#D>b%>76V=Y0v7C|tGjx1poHU_H4qLBzg+T}BEFo2nHWUx( z3df#GxpZj-mLBSD3Q) zH-O(%wjn!2+{6D242!}tMndC?ST9$c&U>u>MYap555gPh-+JMyqC&Mn{N-b*;V)#!k$|XZrTd`$ad${V`wgaL`=@u(GiJ(Fpgr7KVka z)Sf+y9){&7z||2D8}PMjPx`Jon&F%mD^{06Nln656|0k?G^9R@GE4$zEo{>n&)iv#-^fseg+L=wRu6Z8^~t`2t& zgAK73O`7O7tzz0p$ow-;TzE@AL-6}m=7$r8WQRID_FFsBfal_u%a#DR&eKlI6CwE2 z2SUB2P_*ACCfJ&OKnwEt!~rw)VoA1ldnzD0r|$c}S0k1&^D&4Q>A zIj3p?chz|Jviq&|cj@Dt04^0Z5|~`O;LQNgg@Q^&P1)oZbv+Dzy{`fis1T!8nLgtH z7;A4cRW-55s^VhIebMTvFcQ=HWi;tQip)M=e;YZBSjO&n3iqqVB`eg&RIN7-sFe^K zTz&YE8z#ID060!{xDUp-ASZJ1Ces@7&*nWb!RUh>hIhCEW^z7!GBlO3`NU@?C#XFr zAwCt6`;iFzWuP_)bD9ke0O{R;M}&a`X6TR%u#s4!$Y=}DAF^i32w<&bl}4;#ijX5w zn;RF~#;hW-a4L-GW+(t8{|nZa0+%GUF+<@AwmhxNNlKx!Lq@>>|4Jd7Kbu5i!w?UF zx&$UDX{^nj&5TP;>KKV|25PgLRsPW&VK{yr4uf;^b(#PPfp5&+RWv>U@Gd97l@;sz zp!@~9?E+>%D??hKwPTk2E;141^MLNTi;|cHW=0z{p1OLEkGaY~=>D#S1#8JPqli?t zV`H!WV9SxCZ=t>oHjvxPYwFtoSaXlqf?gjR+4%a!%_lEjJb3aVYb-|2oEe@e-xl40~rCWBcOWW5Fvf*%E4vRLE8enJautBuYXd=V5U31i%wvJz@EKq{P-r&zxMR^ zumkTQ0PflFfh-_l1r8J7ELPyrGuOgF&rlF10;*ed1LQYGCjoBfj?T`V*uLP9%fzS) zpo@a+$Cz^Se_CfgK$JKvP09AwlW*_?;b_0|m1QgBHdn(pi$#|cL0&nj1{OeEEM<7;+4m-N*1t{sT^GPKCvy9j3FCQtD7{SCgP0TT z_g$u`z8^bhTweFn46WZH#@WqBLZQ!}~s7l|YLnf6gIu?kCjZ~Q}m`w6E{NZ`b z_z!{>k&vgnrgpup>KLhZ3p_l+iV!H_v;kN7R@<6U1;WRAs~o35G90-bJD3o2`n2h6 zYGjKNqjUT!1cVvp4CYiS-Xfn{wpC?&j*`(}KKwvK>!n?q{Dh3!M9Cu+Z#49R+gB6bW)^FE5BSM&l0Il@Pvo9kT zhG_^39Sh=n5r!I|k82g9i#MVX?ztCEyrsqU*5|+HwDvT(HXeP3!SBhTk&C-e?mKxL zYcE1dFfF`)Vdlb(rMaaGOBWunNa>?hDU2&)YzI~n!mSr?uP)U@)8jpCK(Y&9&*J)h zo44%ksTG3k`Ili>Dg}lLW)T#K`#>JAR>BzoVgek-7QAyOxLp-2w+wN>t5dPBGb6W$n$AfkhbeYFG_M?hCbOAT#&aKBB1*nHOwm;#Ft(7*EY)0Su|E^nXrmhv8)9AQ07%<#TNHp8VI@-oJLwR7%J|Y;!X8EAM{A=|DrAIF z8Zym4WeI{gHsVEc(`3Lo=fU6Wg~zS(uqg4MSuO0`+hI^iGN}P0BGB(HIzXBwec>~Z zB$ft4v;zR52wk3D-ur-kx(JFC7DsaRV`ic<8DWfi8MG$>7J-VOKlq!1u`nO95K{}V z;Bbs_Fl0kseeTysA%gkp@ZK*!zj@niAoesj_vF(*{q?V#H$VUU`eW2J z^Y_REnwz_MbMC@}k2vZX4MI_jQ17)`OD5B`W*h(?;R*-T$$gSxF{`wFmKnPv{fQ&`Gb`74lPRL)PJ52$tCy4#H z=yrAk|2iptajh8yfDA`~?Z8ly=}b5x5*2kM)CxRFUw@hnnY4wl9m&LiN`e_d6ao}5 zjEa^g#NrVEGsvbI(5OcE+eGTN-*coD8BILYaZoKvmsqmIsJ@X)wL-X!t6jjB0Ifvn zOLD+52C!_+zz_kd4g|lKWl8ZgR4u^(I-K*kw8G5`tSgu{5I|QLXDjdlGq;VK2_$U` zuA7L9f%;I|70!STbH$43#Y1ZTIsQdfn1RoK8&XXFGiSAk+{q3@J!J$sF;YmY11aSz zu?~H0l4fFTZ}aR^!#@EVfwXo(R4*on!tc-rClw;w&SMqZoJ|>+$@ut=1vPKL#)Fw0V;M9%C1rsD(or$|-4p@dYrg4sAs5+ujCX{J|YBl)3j zfghAFoCD>*MXeE7VH$duD52&h4)|2pvY)86qf=v__TQl;`bK)0Ysz5LDJJ^KtAS;- zo}HOE<1wwCU(?W(d?8cpq08H{3;PPvsfS7p?4n~TS5vmGKBDy*UoUlyr<45G1%q9K zAzy1r_3sjK>-@*C>XL<3gPv9b4Cg(d9vd<5aQB^OAOgEFBT~Gu>TS$Io@okU8wm68 zuZ!{^Eqr}8qy-uP67o0~UhOyLm$9j1lM9xOkHaCSz}JxqJp!s2jldfYA6BpBmEWic zE{tn)Tc7*EfBaxG`Y^A2c?@|lCy?xS^X3wIGMDu8!x z$;=vB<$r0u{NR5G!+QKJ7I=?j&>JiZ#v74{et!=uu!gp4!)JyG zfIAiE+-IxoHKt(E1V^f4XD1DDJ2G0USf7q>(KZk#F|AIMVoEZ6OHDMBibef|HOY3k zNw&%H{>RbJt#D}299B@OnuE}l3zrFAW06b!T5J*MCj#RM_vZv zmbk$Et}01=n6nr z`{}=cg365i@YJjzpI%kTSZ%N^y_y0EE1Upl%=a4$Mq};NVf-_i0q(S%6@LIukh4e4 z3KN;z!-fmc|Dka}TF^0>e=-SKp)=(QO_CzzEGF890Ig za~UqVf>-<6%yfr0oNl8T7ywA!orE$uepLj&8@(!UW5RUOlKvvrJj{sdh-D>&Ckdn( zRp03GfymV-XIqD~d0KSiO^P_cn^i0fZL>9p5CK7nDE&SOy~_0T&6b-jF6hHlIGt=< z0t7+}NGEU|``-wFaHoKJZmuTD`${25iFGLph;3~xS?mlbj!3g)g0i|b(CO?@*UY-8 zW^53+So^P5kVuTYgG4AEbGoFW+9aC@fL7*{)yw;SVn% z0uVjui;IU5TYnHt@I$Bqmz9(?H+S&eqn0B0k=ETF4tI=!aUO&d;42rTtFamI_VV(f zEob+h4Fw>3kFDRl<;Y(3!<}U#TmZnw|B#2uG(dTQ;S_niY6ST@tiam1V> zx%eX?271KYAZ$94FwlZgP58o)XbJ&&;TtzF^HX1;EPn?%Vg=Wm0x&#)8klh-lo66J z{ykR%T0Edu*Fq(b8x^6V_g|_+Q-=ZwVbc6*dh|(7ZDh{@j!_GpkhQJi90?v{3MEUY z-~d?b0ttzL28bzhepo@0B}+3%AB=C4s1VP<_r@eVv-uCWLkv<(J&t!dpW+}z-mydF zm(uO!w8-K;LMVekkr_>_8#W6^lP-dyNw7L2ANnD95FnJzdU2P(nDtJRCC`buHl7x3 zx2`=|JSud8SkHL?WJhF%OF2$_>J+*Wx3C%J0g6;$i~4EH7DS=00U$FFIK?4&B`N8N z5U_EHW1d8NNFQJ}LVFXNM_AUuhj8knr-ND;J2E00Fq@o)wwuIpOTGP(nE9p?)(!&1 zY*852{ub!Jxo~sDQyO)>420B2XU!MFE|Pgks+&u7@DVcf6e-duXKGOIIqE+0B1l>( z15|BsC;`^*clFyZ%?r#GnDhrVFm!hy<)v#uiC9X>zvl)KOoP?|qIccXLr+l|gB_Tz zI1~RdKt@J5UIiH)P0oadgtuQmxq;)@S4Y1*aC3D41OZ(6kC%{zwRrgOBJq!XAs{rC zO&Mq-;Kd_7v~&>pP8>OM{P?jG<^c|}=*7iPUcBu|fC@uhUOvbP@HHC(7g>q9aq*Lq4i=z|-b6!$whI@n>!SRH1AJHr=;Cnbros&e94 z!B}7=BS;tnggim{4UU=RArT0Zf8J4S^LCI`c&6V92)w<%`3XWgJN9XMPVN zU{q~M0KZ_uNh!Dh)uT8YbSO&EUD~<_3Pfc%#A633UBboAPJn}LHO|8pMw4@3ilU?Z9#pI>Ey$<6NQr4mq!YdoL#qI65ol1T(Y z>L!@!e6nk@nj}IX>y#J|J+1T=L7v%trJt_a8!|>MySgT0*G;@CR#?ItKSyGs#E7K8 z{A#4Pp3Q1NAq8>)i>R!_6>z9AVnP_qf>Qix@}q4|G5BJ6)pn_LghZm=t4r(|P$~|e z9Hi6CmnNLivnBx4ga*3?mtd2*fP%3&1eTPr21?5=V-fZ^Z0d_3# z+Y$Gti|dc<6@kk_U^i_5jPQ1H* z^Th`zcWpjlvt&2{F7EyO#oM>T2*^(K<%=hR5tuQnR~|qG6Iy}~?=b*;{7)G84RQeY z1OPO9u%!Vy3H;&g=rzWm_Mr&r2>_5_$Pj4S;CK`C;ZL;4PLUuxW1JGBc6x$H&=fGt z2&6kCHb{YB+S0PzUPnP8=D&^=Oo7`b^=oid2D1%bybjBlQaYe6e?A6k{!@Jt(-O9I zZR7fj`Xnm*2HfhQV_?}jghxCSmB|Mq6K44^?ej?JMrS0nqG0q(uqVMaBk^gxix}r&=`4V?kQQqkcMM!bEB{iQBw6{?yrK#*mmki$$NN90JqPRrw4j z!~Hhj?Rp9Gkh0!a|?pO zRE0sWm(992;&BVsiVKPO_DCd1Vc@k;j)EQ55X#)GO#39~zXtZGqgk_Bt@lr04vu=R zuj(9**MD9sBbY4Z6VMB%;tq^yz?a^>;Oio zlGidJBzg`~mj+TDiAa0<{wAFl)zMjM)WNS*SBLF3Nr^OaVzd(*_!0f?-c=InFC~XT zLJR^?Ulst82|*!}+A$sYRF*_r99a(T$Cee%HJ4m5;}1Z9FdJ)ZVf2&*q>eFIdTWB?@1qTjxF@!~rtkDm~h?G5cAi;LSY-1d%PL%^GxU+b}zS2mHCPCh_1g1w3r z7(S4HQUN|D{y_)0XAwf^4F-_jiMeV7!3zAOGd9erqOb3U5g))nL;#8n1_X9$`6Vyh zsXbV|ARH)66R2yU-3j$P=+)A?|EWR~uL1K?gTT3M9*jC^q=(Ic9n#5QA1?a}Yydbg z-~*uq(Tb^EAf3xtX#$|>nhAmZ1D7n_@6u`w+(;<=u(i1C(;yozM>PN8(av`0&oGCc z!d^Ivj*M_{tGPpb$(<;At%m?`_<$oHfe|Xe3G0BusgN~oMMeEpBnY&0m$bV)NCQ_Y z)@o^UU|NA!lc+PN2*%R;5B@#&3a+yERrS7^8E?{ z0e=9^ss2XdcdA25(^IOHLSEm=+z&*b(TZh|LlFz`CbbdemmyIBxK>qw^!rxDS`oRZ=e_xmmdd&^+2@?yjr4C1Lm<|S5*MY67 zZ>J_c-+?>(!c@S2hnWq{Z<0)#Q^i6*42f2qE|vtrf>AXJ<6Na=>B*FWp(kYpq5G}i z%kZ!|fEb%!HuA$>a5N;z%b9y&+qMO@CNV5a@)#>p+DJ-%L~uy4-zIx&*%Z}eJ&1v2 z$3zdmSKGPjK#UTRD$#9vX{K693(ePx)COwPRqkKG_uWF-W(=ocvn7x7UbgUg!n zO!_Q+G=AX?M&w#^o7&!NLw3(@z%_6m22`ZgJLsw=yX+d6iapMJzLSGe8vz1So#08M z7Sf%vB^a;~8qrh14Px6}N1xxb=YeHYxxly~Y2wWcX8(DYLCIULT4>I2oeT zO_Z$yV^G{!8N!w>=RJajHoQwW3>Yn=Sn z6V_-zUp+w#e+VYc29}IC6xI#(PI2Kqolpb}PJIosha^hV4ZH;^YnllP$w*zDBBaH7 zG&C^yl+;o3PNHOV$?5YBehS2ANfJgu+CXT9;~~#RKp@~O$G+>9k8s^aK^6nwn^iBm zh2>voM)cJ&=FMHb%8MVNk?*rJAm@*cj@0C+qTYwk96I#E5B9u82ISV2b;j3v6yWm6 ziI0wkhPSV1Y}++{VfyBU-~8K)pFpIs@0C~HS-0+)S6+VRm38P-ym_JiLS=Y+=nxJa zn_upmGfXvO$@1;($WK5goaIILEbcq`5?12FCJXH8`R1qJ{Bt1mV_AVWa0J}2;e!t} z{XJ$F;2Hp&J)^!~ep`7HCeMGk)5Qig`MKEx?5}Q3Z7B_eKt>xsVlfaRMj7`F8&e|i zV{l-UEpo$p+2W%MJZL%kY4&6Hk4zvTC?U8q3XVt8D;ETXijg*394a*FZ!5b-5cDt* z?`7{plGv}GYc1wD;vSh^8wZW~We%VbAtNSR2HR1t`9avnTORSjZ`@L?IR8l_&2TIQ zJ#+b0Okh!*v2qR|bmnSY!NZDl?y3{mkATAloAy7G>CXkP15qM$frd9Pm!CB912Z#0 z4h(R6fg@x=w^T63X0E}HHtl^n}e1c$3SGt&f1inHESqjD{00RFK`>D#~ z-ifFre6P3WB(ZL3k`7S#YZ$9|nkrwS7bK^6e>{WCJExgcb6{?$mwzai;O=hVUoZGo zx{S5|ws_Er8Z1d&XJOSCLYB->tJKgeO5dUG%z8OEnC~o=3pm+Cgdy}KLOjO+ZNex< zN7kQWT~KeX;3_C#S`>2H(gGl>Dr}XX3B8!fDnXRF&dEq`FojSygNtD!3y2%0Aj2uy z>93(=OK?_+3k~>K{o(v;Ylf&Alt+o;=w$1>Ou)(gxFpi+3`Eofc*lxBGz{MHPLT5v zF0TYY%YwOXjyNIUeZI~oMm~q)4~&4g{9Sz;WtiYMUgah%_IPY|1!8D?_aWnip4HSS z*28UhI5Q{*!g@eE!M4D_>sz z(?j}g#nS&hWjw%*fOYp5*1XZs@XCcz^!4oI;GW?V`Kg@zB zPi{HVLt_YyZin~O(w^5oR~8HuF!=ewPe1tWV}DxRfN=xd1^_%$5C9HGZG0mSvTYE{ zZKvcfor4+!d8HyV$XBR@j{0L6ub5 zi7aD_v1cEcpDm`LQGM#Baj{@jks-j!iuI&NYqh_%#v|bkaK~7bj93seV^~ad)Q~T* z81>;};T37i1?%{lCsGG_TT(u%WI32zK4Uma;@yL0) z;4&VCZN%u_9yD<@b{NIUuuQBO_~>6{V0CM zA+yxVLZqa3V2TYsZ_Ds6@0v0uLO(BP;QtTEclDm)V7LU&5()2#0G2usS${~nViF*W zL9T{_pQ--Fx<)~PwDDjiF@o+@h{c0s1h@DXHXl2z=)S|R{NA|=-T;>$)vsrLxv1Q| zi??oF-go))eY-huZ@1Mc^wE#hJ65h zDg>M(M85TrvmT3=ccUY?N5dcB5CHhWw>RLw+ZYHAFj+i3j9 zh#Vif`&r>fd8DR=7SA!_!yq7)fF%93zMz^dcwoHjVFwfTWro7^GI@}38&!+tT3v`{ zG(}#O3q~SOXu`vI$25C^->`xPLy0KHL&T<92x`+U(3!X`y8`GnP^Sw;_3P-%?#l9ttZa=)E63i zOxGFiQgIaodnU9I8{Uc3WG^z!Szb7Gyj8vJBX1GUIYqH3rV9737Fgn@8_2q1P~-$? zopkp3G~VS+Ll_qTX4Yr{Nt3ik6K$OcaG}c>>JR}SPmDw(#cEN{Y`+lOg?9pTa3!oC zawQ+laNWwz>TZSpWr$Ll=4Os*WP+QS3Ihn-&jdeJe&F+GCA0<;oCIgfWEch`AmLtY z2gNJQIJGbt3(~hXI_|HHRw#@=l8%+Eg*9k}28uRdVx%wzAB4>op9IQ5PKt@-blv_$ zf}Riw0qF+e0^giG&&X#uf{g{H{rB$qfPnM?OAZ|wld^@g-^W*xf*{aaxo#7o>7hmb zg6x3p4XO9cgFZ$3+f@{SQ1=4TF_jt}ZENe`Kgg3zGNFVm1vN|uL$jXSec~{NJPdd* z6QQ2^{P*xt8S8A%;%g_iY`Jy(_~zZ1)i%F`b~s?)m$z<78+hwCnEQx)B6`txIkT(B z#nAkTp^@=g9R2`hK$^dvhC-wp5YBvL@%OqA?mNCk0vm-x@7eRMJp8|h5%8ODKKS6> zch|#<_lN)ZU;p*RAHVots>58xzpoFCZXE{ppcF(2oG~j1?j-V23S+bfS>H};*a6qu z#&Qs@!+1T8(y|KCQ=zJMn2-6ry-xwsL_@$~j2U%SI?@rakIx{3mh%G{0BfGSDoI@I zaKXI6WuYIXGk6XSU>8H9-72RAcT=quGiYB%%7FvH-YdxSQ=b7~|A0`&u73Ix$`b|q zx{BjL48uQG%!uVBObF)$fEI~A!RQx198&D8>5-9HMbAEU?F*+p@Eg`T5Ojd&co2+M zWc{cZuZv^pBr^_t(={<*I&`dbD!9)^rWlZE8JA7(|83{Ao9)^78m!m)Bc&g~c2k=f0N z{jk$t)%M>iJ-d+4%}vQlMn4ETFJqy9lj9yGG5M<3kQnz;tEQv31Xv_W1RlK%t$Fmh zSxq@s(NYN(y$G~;OTE0safhWuu-DYgL%m*|qy#KI-RQ;F2yE%i4!J;@K!$A<0M-T7h#6prNBzp1L6=YuWEp zYEp;znP3S31Um#ScR!Nv>!^D{`ZFg#D}MtHa`bDxLuLe1XM?5x*&&dBI8T7GhEN9x z6Y#zJlmgzTD_HIizXEdpvu7-V1LR5TydVV(pb(Sawl3Pk+D5l+gL-3Sa$!M6F05}0 z_^B*~P0ww43k>g95Uh;XU_4IVtQTXSuSQ(_-~Swf5nV-$*Snb3M(7*HSkCtorBlwmM4%7EeQ7YzVt9U>}WsaU({ zq|+gj3i(SZ5Fs$WDT_8RZBaD5anjsyZVIuu1gi}Z(IF(Xei2i;@U14Zsd#m|#bOcm ze7lX>oF(BMr@%IUT)Wq#yKqkmz@|{}W*0>71h4PL{hyA5vuCP=B4iVjQ;ESQxG z49R=HzO4SX#amZ?=7K$f*`wv9OBatn0Ql`bi8kOj4<6i(=&K&W-d+#$+q-z>XUnV6 zsdRZvT(Nia>DEgSIlp;<6?3miQ{%K=IDz|Ij8(`Ey^V7!F{eJW?@v zPGdT}5|K)GiAy<|<9BYyFt;TLW~ z)BY}p?D1jRfD4Y^Tutqr=?X=F#fsiam5Zc<6^7$e?jlo&vQ5*$4MLxA%Ci4L9gCv4 z(|wwl%|B?2h{>7T%%J8L>vYOOpHuu7#}(GKJ7LULVD)7Z08`w5$&6ToNL2Y(W{PXq z11uunl+Y^2jM*9*%cNo!PVkQ_a;*%h$?Mvj4Q79Nl7U$HxU!e|4rP{N2qgEKOW0-_ zrvzkrF5BW2nfryPlsG3<1OiwDcvcfZBI6Tm_&VYYna*h2PN?IE&)L?-xiRM$n8FFUpOJ}xM9@~a z;KE^WPFc00Ky4;!c~EX7i$yX!w_pv`U%>Kjr>$0~R;JqhF;%5wip;uq09WKWehT(5h!c zpY=+m1b~wsc^{&<8L$%-Y;u1!ii3V)$3V`PQIpH0YVzl3I`~0SK^JXVSkah2+Kh8i zE6xmsz$Or^wPUu2B9T}qOb3kZm+quJz9s;MQ{VrCDbFgEki#r&A`#1q;3g@B+xeVl zKo*jl1}4r%U`$M>ku;bffx(ZV<2WAb?7ZDrK*@lsDo=}4+3>E&C{d17y^RdDqOuP& zU2g#XZh${&JqHWdw;&~k*l9g@|+1qT3 zW*=oUn}HQ&fKwoXT>yr9g~2gdWPpM>X~|Uyfbgv~qi5JUFY$4TMa2goLK+(9Midl7 zn1dlt*@KDw`}6zj>fWgP5zwy=M?i%BMUo1>;*!h{x1j}s!0a6Vb` z0g!os_eFfL8WV~a>i#5lS+IP->u!LvdN@H}3c%OahG*Lt9Sumt0*t;4^oQW1*qPLC z;V=u3$b9(ma|l9^)bI1}edbZ9LbKbCW-xN@o7_uu430f**~ zV)Tf_`4WjmV;;(GHMOy56m*FydXzpA3)slvX41$`(H?0-5o96Y$hWneHb_ZJM>66{ z7#|AL1FP4&kdX=uWF<)dCIR0jMm$?$jGQ612lF?uzZ3EauOkxr=McqgvtWllu{Kwt zpTSxfO}Ts*0@^VSP(xr@RdN9U3%33$3Z`7N$b*V0on`tc@+~Uko|i^ zYfkFiInM-qUv2221l?xBc8!e=dC>rX20fg_OoN=U4qpIZy{YCn$Pvr9?y?(>0_gqH zbFkTrN)(1eClb8(!2rS;kcU86D0n~=Qp#6M0L*!ERxM{s;u?62fq+e3zeHIL0g%IA zPRt5Js_;V?MZn7?td59ZS}uoGMerFfhG*bTE>z3HDVufJXpiU;5h zNMQ@}u_B;BR65rv_I8@HUy|!9m|FoL0a4AEc*N3F?^F`TH-=l8&ZT5wehq>-e8zMHp|JxnuvylW1{aCI6Ci#c9F$tOgOlN?ePkB_5cr3jEYu43 zcRjmt&s%>60{+jfb>p9{odCfDFU`y#_38qGua=RBzx3(Z*M3f$+gEJ86nxECeDu@L z+~{@_L*s5teuzyycyM@T_{NP3bB}J=BFfs+Fp*-BrYnSP=<~HQbje}PLo(>&-(3PA z{U7%i)Plqt-^zj_Urw;zkU3HYy8xDPWb!# zJ>kz`He6oQ1PJKcp=X`7FqlpQ zLVi<8sG6~v!PECmym`ybJ-YZBA*kMdafkL-QeY+3K2-ne3Ufqf% zIT}!fuqg(&I&PUfMnrIczJ5bL7X+F;Zj*1nBVp?u@nfJzLI>ZQui1WwOs9iBC!GHb zB|-ES#TFMF)9ftBSIg=`$20WCY5Fr1vs6FBJ2U^P;K-m+X@CfiR?xoVUBye~)3uLI zg}(Wehxr9Aq(G;eV)d1%;L$Gc6Qk_pr=wm)q=`ZjVzn7u#d7#0Y#E^q&o|+yyFv`` zD(%K)we!q@IX@RRU>*5ln#I(|p*tWDu1b+J;VD6t3-??wvaq=+@TrNzAc*0JNn()O zS2cZ{DsPh{QQZy~S8~2${xTdR6VgcMRWc&sbEqh(s$(P);g>`pOe9aAR)QWfUVwch zHhOoc=NwPiauJ{k?;Fg#aNyh0XV1=2C zLRe5L>WAnr9Q{O0$*0e@E0Eq|uitJ@@nAI=@>`KZU6JOEfH78iFFXJ{O* zK_GrEU6?6U>Jd9OwFKyVc>9qj!F(1zSNlwLB~V07EF@2%DUeYiRSUgNe>aXh=crGsq(kqJS)Ep@o1MW`uA9 z#wY-87~d?N70!Lsyl~>6xZJv?!sb^}3|~Z{ z9KN99Fg`&cSmdN*PNyd<@1Ej6P$G;$m>91V(}B;frMGCJ)40bpzk)C(%-<`lamxr)f$IN=|2Y2RChA=Xcw%iObxBadB0n0| zUs=<5;Nx0ZCA~qO!ur6Qfk;`YNcbp)NqfqD&h}`dkM$<21TlwjwQ5tR#VC*}$tzBj z$uNwaS2>)@F&Shfv0tMy6V$J!L{}Ioz`R0yXVUC!m1u~sx30-d7%kRar1Cecz;U`g z>TUT2stu{HBf_Yc77MdNmv6RZTBW}>6&e*hg`ys2Md}c*rN$4Ae0ShO2Ing_8AcHJg-b|=IbF(IRT8d+8U^P|xB(g^ za#!I95wXAbx$~Y1nOA=9!=+EZQiG$j_b>;7=v~pT*?t}ROd`$K5GM^)%!+nqq#H&i@_~G&yk1T*C7;>1)x89tXS-Ndi zM^8=XOd|N^5*;B7OjVy;4IJGEvV99y-NRx$$Q9o@cKO)9-}?7ki^sOCU;k@7{nZYC z0>8h9z`y%lNO=bS!MF0^dtZG0?Wd2Gh0rxh!sCer{B;t?I-*2BbN$9t5kcP9Vozmq zis|k6f20;8eACTDW2*(+(U8MwX>_S*+!`z(A7>gup&)Swc4ba?=}DixCTqvR+LMYh zg@76XsaYv24u4>vwh`;-Mv8zt zqJtZcexf@HR(h%NkO0WiOy_b7KG22Fmv)lZcl)%`5{lAJS3F|h=@2&QDJ_+6cu|1L zYhT(e#3|7o#v`Fl-Df@YjR*+O#XZl!Vz2n8lJ5O1*Wp@gP%Rgt(jFH0#@sv!yw46^pMxm!~-P*ra&(v6XA5GxmAV3 z`Z(5LlH*|2QA4*{G8x2zPp%^0W=dLGvI+Jnp$!;+8m2A)An_06gA!M=7*Qo{Zc&3} zlKq$jz!KcM%`An>+WWFN3C?jPrr9HsttM~~#Q&x#iDsrs=Jse&V9XGS->C)~lJR9t zaYzK9B3}lz=%6}S{R_~eBnA^8(qEJalVlbuO(3V)i=@_%W<;Q#PYMFv3JgYsoNx)) z$4U?b!28O8xz5h>S(3T4g1;5DV`9Ob>;Sw$=`y;&Nsv<_AP=GVkV1#4*4{ zlxZ>>p8)vb_rJgS=SP2z4fxAXe!nVcQ66eI?Rhrf5){nHy}Gq{`S|+F`}XbHeQEoJ z<+UHeM>8W;nOB?}*K`5fYK?rElh}9(elmYRD7b#}`t>g%YJc;t2Phf-^{*fQRp@8r z$K$`-um^Y>q@EA0N1y)bi!c5O{=WWrR+Vs_mS4c2Q_Or;qL|SF#7wwYPB|ZDn2+&2 zmKA4_!)zAAnLi3KU?mEHv~9%RNbBYU0U&)_YlLm+io^H20}n?+d4z{2bsl7DYC$3u zn-ncM3w22&o2(~u(`px-+CDA`0ojo`5Z*K4w?NYZj$n;t*AY|hS65(8b>juwY_-2u zf(FMoV@-a_rT6*InGF*|%cNT@*kQ0{SF5EOq+Q;~kK^r5DXRLMMUzI`B&tulI`7$% zZ3$bpAM4$f$+S;(gtJU6W~?s`f$zs`9t;cyPk>e??D^3Z&2*{NP(ZsIat-DjXaHzp zyEx;bog~IIFZXRIO7hr1Bo(w<1inaMu^kar1bcRVg7aIGrHbevdx$b~jzMVNLFI+9pX*Q|IK4tLnSSpZjM z3_dqeh9oe&53^rh72|o0fOx7#q;sJ#o8|4~B@lI>FWRH12w#muNhKu!=hR?MK{Kk& zONucN3!I%sY$@<-8cq=&{>UCrw=gw<0131Nz|r1;>dR@`ks&8!m>}K2+^6w=4t4xm zT4isOrv#t5j-r+%iDQVKA^+2k?=%WYVTq&fMD`N{o6Ql7GNh7Rad!xSvqA7I0~{}U zdRhqZcb!|ViJE!lbF&CXJW2)c_0L+O{;c{l@n(2K5D93}&|PB>-bHmKPk>imRBFpp z@56j52=r=nJS{&O{_B?Yn~xvgw{PFc&HJ{$@(ySY6a}vWpssw6%<+4BH3CqQLUb$5 zO<%ZC89BMWM-yPrp2HiEBzWxdOS|;6Z!-e59z6KL5B~bsFaD|}*Pl56o*AV_4Kv`U z&#onZ@8hR_U1u1~&K-S5cQENWdPCEo8gUfy+}1`Pri}6A0`Z-|jzS%l^nC{S69l^1 zO0rsh|5#En?}YrO1^B_Xz{+$9e{Cu7 z2*|6RGR7!GcQi|j|Ha4_m8~OP2_9`l!dMuf=2DtHlr!kWyiJ7_=F*(AGIfuya)k^v zfzl3UbV!sX#M(V#HDxpri1J|?z9O6e0XnL_bl)(;Re0&c59|DGVosjYqp6BcF!mT* zsImdGH1f6z#ZD7P*}D|UG)X0Bw?if%w8c0I;+$CJr;3qyX_sUr$>p~>pDYp2@|prU z18V+jY{0KlWBxQnf6&|I*)xRwTSdYNBV==2$>koFeNJx!FFXY17|B&32n%aEi_0y# z6qh`F{wW42M3f87)prVPah6J&dh~tZ(#Vq_NfJ3g>RN<}jDKnHQYPSOYa??SzzIiG z_{&Z>Vym7JW=ql#3jMIf^JNV#c>{_L~hT$k)k@ z*v}PCdCWvrXYeUBf}C17MQhyHsjDgn0q=_)*lvhj$k%^x0?Ix-Eq?MFj&o0IQ1-1^ zko6!-7cM;@`fcBS65_yv#gUl{HRme8exnutwvi&u z$Bc9^FH8~u@kG~f$aONt)XrwnNpZnv7>p%?MBDIyYU9Wk4>$nIzZR0PR!NUd_L~oe zWye0x0=%?NR50xzWeb4@vs(;-t7&I-IRg%l^EdpB4-f#IkXY3x>h}q2_O%n{4&EEm)oF^`MI*5o`YC5ZDUojtCL_A+-Dw0A;6xL}s4ghhKbK1O93n zFb8Ib)DsLEhbFkBxL`^E=b)5nz7w3lJOV}*YB+ZdKdvum@VkC}8{P_5;QHuwlS7jj z=9P~{!S)(353yKRVfIjUCIg{Qjdjg-DIM$nHnPF5|B4CDFam#d>y>5sfN{%v`nRwF zKMlA>SX&xCxceZhdL|BBxPU^qshe}lw^vEv8VIhP0Bk}MO^1vH{#5gy zfgjSbN7agc?HbJ;DQi1#vs`tIZrFT~!L~y>7$!h>Dn(OKNni#M8V9kM+3IB}t(e)$ zzoYm)h>1ky-Bbv+2?S|0vF}Y|H(di#ApmxW3?A0cv_yFwL_RLZijTG$Uqrwt(7?zK zk;3NSxU@R<3GeKMOY5Y5F*DtW#MDg58gY|}fGaH*uxVfbX~RXI_yV9&9%GN(D@q}sL zY)$!GiTX29%_;eQqyDc?+8$u?7|nlLBKhALBKBC6fz+{chHIuXRDFla?#SRu4B6t-mD@liUj z`Le;X0ZX!ZH1Gh30kFibq!QU9948Y<4k;J?@xd|T=~BE>sqVF$M??w z05JoO4sZJKJq>>!3;wSE{mk_<_%{GD@0Dw#3bYU4$Dh$ur~b8<5N5{?3xmOG9QtE5 z0jA=%0mrzi{&0p>0nu^&<8&wFFkWh17#X?dw8_M3T!$-=5 z(;jyw8&69A>{;GvF22SQm(XxmWxhd91c&I5IB$7kd=t&2h4T)89M6&xEyq3ik5EQS zoW)1+V~zC%Z;J%Vh!_<L}Q(T%fOw?%Dn7!@nRo1o@BR-sR+ zrMzCOOhnmN)rj^=C8W|wj2DJl2|LXZy_t1NXqv;s#-=xwd$gF<7~Wo7?$D1u!~#xK zzmdq8B3l9#i&kYW!H78E_{WO$DaIBw8>E#Y3SY$(mk(Dx{c&tLl2ZCSV-A=MZOID6 zKkEoSf4;TUaGJ(CGlV4P=gAe%Qw2RA9KeQtzZ3v2knFYHH|)T2aV%Ix2qvIyB#2Lq zDGd-OzpDs_W<2WHsn>~qV+McHQPT$}f_O!H@-KdJ>@Wdv@zyK;A6cE7p%`Olx<4FCjp z0t95Z!uE@AzxwLiuWmfFNzxDKh;z3|?9T!D1}{NhhFr`!EmOn6T)0`?6b`uIP; z{@w3R`RWV!12k^q{HMC}Yh-;>^1U$wx)QxX_`0E2Iu%6D=h1fe#M=y!Z}W}HY9x&7 zRgf_?e`1wEDo;+v+RehH()6921UYPCB~FF1be3g8ij5i2elTP}bs=^XREMSs?*=G# z83-$`KMfcItfHiidUtuinGY`)CK?V{c;JX`dTu)@8^MtZ0SywP$cN(7U%)e`DhP)B zN(xqfZf}zySxykrAj3wY49gPd)lgJK2f1ItCbghDEY|X|DyH(A40phBt6O64IvUf9 z{A<#1ju-UR@n0G@5?9;^X95e{{#Xr z)6{YXSDb`Rz9OVz27poBLPXDMv;+E8NsCZ)jF&RGcpfnV@c!~3Ck?bnURpM)q)VK1 zmW+j#IBkfAFX}_0qix5I2sO?mg;5Z!l3)sAGI33Q+=1hYy^l9B_&^m$qEM>U);!n6 zhE_wCMkrx+G}QN+EU@i3x_*Uzl5Zg{p?PH6gn$pByGaZOE#Kwek?`gg-bSr2Fh!qL@+D? z5W9M_ZiA({M#=}l=$7oJ2ki4KthUoa%p^y`NMt`e!^FM2Yht0nf83E1B=Ei0?Dj{3 zgM6;_VzL|QWBerI-8U=YVHN}kzPw=3(5GJg$y=)DU0i(S z=F>HVE*Ig|6QErIiGUQc_;t^eEj0ktET}}l3*`bltgk$Sp#1IIpMU<7=bs1m@fV&w z|NKd$YF*sE{q5HQd|NkeVl@!e%Rr5Rt%sidoy8n{T|58PPJk*qzjkfwr=R}r!?6zy z|3*j8Tt^Jx=r-v8a3loo?bvDA_kDwMz}>i^39i#>J~#yK)B@~^S$rSmD2-{$)I3zN zU^>MlILUo?(D1I0-*hO9o8f#IuIz5-1ct&@T`^s-X1KJ;Xo!53+T<6QVpl<9eT{jCG9F%0%mV3Y zj)0X~0|NeQ7f_<1X^wIjX39|AzS+}cd_Vj@7IA5st?j)BkxT}dC` zA5$u{UH@1X%yCd7pVev3j=lc&#?X!V%n`zv-_1dKS5Op!SDH9Lclli^OJr1o_}-u zc6`4d0`hIz+EHeS(7-?+Q(QU*N4q|C@H6zQod6H<1SkmHy7kal*N0v31fRiL%*7b^ z_eAGEYdh~VtDBXd_p$b>giD zcemoOFmZ9|EFp?2f$@&KN7k21%Ax^)B#R|aVLoa$N#RVkB<*vgWc?lhz^SafZ`gJ5 zKO)I>d0I;|R%2%EyI(FVhJ?+TP|Q$7L!iYk{7+-PvsjTvSW3<#Yv#P55afrz4b30T zb@K*^q<+N}>oQoEWKGq^B?{Y?|^m&;u!`UJ2v#~ z?9lYb8F28-nL{7i*1I<8nOw*0wh(M^=FHYZhYp?TI)iFSm_zuJ^5<(rD#jjk%Kdh& z+xv|=JBJx$s_8BhHem9=?V&mhda)E*TDh1gHYp4XKtSPKU*D+p3-j%mUT8}lwEj44 zT7!u8WHvxry+3J1Qi};5Eg*ReKer8A@+majG{jAE^<;mD7UB`+0@4pM;)^Y^vOoZP zwb95xnAQfoS#H1$z*>Yyg4e_qejS#ERql{IkGDOh{wXioPkv6-)-=)u%TO&3SZnX3 zqOAmj41yUa28PubKe@)HO=c(wP}Cz|h9}qD1%-ij478!G=&s?4WoUWM4iT!|wanJK z=aDb8{>qIVQ*lcyqx&AiUDOK~^(tYL#sv5?epe6ECLFa(9~>wr-*cf zIgX1tTZ$1z%|I>Se*s+!F*By~#m?FMhQYrUCN@4YeIJNzD(-|jUaHH}88}%-P z=`$0$QPK1cdC7cIE3g{g8he4AoDNHQRB2WfuVv;r(jiH~m~6qY{aUa-9l^LXW*bd6 z&Aito?7;lF)F@D#hBgKW*xN8=R0jV{2wPNh-ij%aeot?FH@M9*T&YDwX_8u`3 zG>BP8uB#7e>}tPdWdQ#+2CgqQZQOmetmwC@@L@Qa{)sUN`fpX|n%8D<|2DhV=2Pm<;x_<9aP7MF`2LL8w(ol==hz|C7e3phlev73PbnNv# zc1cP}`pn@Z#`0SxN{?DB*RTzO!`_^(B*q1+QJSP4n$JdD7K3zD$zl5K!H#%=+t7fh zyJ5{)!WxoV=ZJtU9a0GefQkkzTGD}DW{nf+jE=O}Xbq#Ham%Y7KEpnmb4?6gEV%2< z0I*nGF)S8j1{J4&m4%h*`{sYGx+1D#os(9>rBSS zxVCed%(;w}3B_!)HJXDFr|m*QQ5@~Y7~J>}=&xwOrADIQloT@j z9EbvBQ~DBFk|mXb@OD@ShY8kY5H_;IHDivHBni5I=V9v!h*@M!$2egp8Q zbU?}hMT6{Q=ODg|U?Ih~TKkO~7Lm}o!%x$Ax?w)LJ{$kSbI51<+BtYk4(=T6GpdE( zNv!hmcE_06UBQWaIjlG7Y5f%dvZ=DnaYtLnmt ztDmdUDiO+^Yb^y`sUh7h!HNyIhAmPX6$O;V`ikbuV&uq#V!BZE+aegN;Oy^;tlxBm z)YQsWvm`#~%g6Zic z?zsM7JiT<7K0dO=IZaZSCHK-Xd(|I`39z(j%;k<-Cht+wHVyzpB+UH&*h)U&8{gr` z07$=>Z*xfG9LS>|HPY@0p-S+Wv`GEI;|HH^fAZb$G79kD|Msiz{0r57|JTj& z@7r?dgn>`L`InbpLlnLK`A@&|;d^gE7X3>A;E(b2>?7{IKYH!0_uhN$nF-&w-g*Nf z7=R!99>0%uEhWXvRK@5j#RhW)Mwp*A;Qu3S!Fu}Fi--Su_r->MzKzkqfVU9`L8G6Z z_t;s~Vf#53UmzcY52X2{9J&EABobgcHF`p47o~dv02cXSoB?-tTRahVy(VWyz1XDL z3!D+*3WJFAREe3scq>_y+eZ7vq(7K&3M94TTVR|7$&XA7Y(b3N$gbD9&h_fSZ;<7! z=C{Al&bVL6*tg~xa4p1sF)QK?6J^xYJwM8@yJPF`PEwvEmc$m1on-hB02=$yaH$ti zdx>mRHE1IEej=-#`ahiP*Wj@1iiPTps&gIdsyAMv^POT9!#p!l)9UscKpLsb$(iaOepbv}h zZG@|?9<&$|y}6_?e5hwQX|h}$*$QJ9%<&I4=4N~(XpW@oPAZ$EwEM7X+F&KAT!m1qh+-6NTdQxRF-sjtg;Z2A&(V`D*QWq{P^&} z$TS#msgHm2x0nDy0{@rS{~fanBKzR?-=6yNO7o{rzuA1c zIQ#cIAH2_2V9*>OIsOjI?jQf~%^&~h$Isp*`f(0?_M<1y@ZyK>efR+`eh~S655afd z_f(yMuUp^!*w!KZ;}(qbo&oSi(ESBtV6@=!&IfWAaMvAx@VL~gbntrt&LeVOUTE#5 z2u9Qe``j9=^x!j2dOd}LREoBJ00RMmPRauAb-8XxEORQwpvo{umH{$&smKGCkr9KT zRWL=~@C%fL@T*;a6~HvVVX*BuA5ee0dPE`AcjCGix4acy_10YSmWLxmq595Rj(u{p z?Px-rq}O-^Oy-T)fbZX*=$-0O6SCgF33v$rcM^xuPiH~vSPCw>{CKjivZQLk{KmQ; z2n-2ZG}m2fnK>g{-Z%%JW>(8!2J4FenWRRzs_TJe&Zs;p7(TP&KqFb6lj=Mxijx&m zk%FUzTHJXnnVSr>{_?zMDmV*khZD_GUbNptidTd$fR-0t(6YwBVloFAz7&=~WeR>? zwLus>NULqh%5ErEbPwc9nAYG6W*WX6!T^%RM3^8jl!iFK-xR}L@V!>1s1U71x-;&I z115YjZw3qrb`lUJWHSVXxby)Jr&K*M#cq$b!vEC%TjI^HEjhI2Eqv6=MuQ*8Nz%Dh zGebrFm2{mW1#-ZqHrU#x$@%iixS*~#jDHA=ASItJ&kvt(OA>v&{a6#>#Wqq8 zbP5#m0Sk$LFvT5y3IP1%e=rC9+b{k^<>i0)L!O59`;_1Edv(5H=Y{_H^#1#w|KR;! z{*p`Wdq2Xs2LP0+8D2K990Wij;FBlsz47F|w?2IT19|v&6#XRL<00?>{b@)K*{hFs z>WvQK3y2OQYGLku`sug8@4sIB>&3;t0st?u(&EP@g8l~DZM(!jUi}(A{G~;>5%rgy zPOAau+(3so)fpAoh6GTPF|H;b=_!W>ExTBqyX@Q5fQ}F_^NT8 zp@D;%roQ_TS%OC+079^hAX*+b*}}}9^lamyUBRM&#a@UG_7o^*T(pF&g)c-n8Hc@} zdcGs7J4EM{bCYSwKcH2L0ElKnxsR*^Anfpme?(4ahag_wXcUhn{bl;o*l zlL*`8zq!J|q4wCA2OAZo;6oG0)s~8v7L%V_Vnc>)ksj;A%Mk~;*^Q6o5EEWToOrV6cNn~1ic=A#-)SyQi~&} zs9p|yjDc}#R%?^KH^u_eF^nspoFH2upAQxe5K4pS7vdja4q&)HKFXtCl>Q=~c>mTb z#sG={G5WC@4gjb!VDB++$r z&aOmZ@TU(R|N3vgD**iGuReVGFTcMY`0Qi*-za*4q2ue%zW)3F^)LVOk3Rm+2fuvp z2k%kc^5jR)&<~7u;AdX|1rZGM+FNfvd-J0=-z3-Z!3Q6{AH?6>*a`gMxi!}d{=0(tzDlUbA{FU>b`K;$HxFH7E zk*D}J=xF;buqG2R`C5TbPu-WJ$l!>3kvqgRApZf@8jOwkGo(tBq3JMLkg@C$j4GA1 zMoZAXavFpPPIIA0KxqIq{;k#R2zF(M08ycT9Ns8<77ngNo*&`uzRHcPbk=B?)PBmp ziUF~n(w-v_Fqt;iQU}~x!nZ{F_Lb7Gm;4&h5mF5wTewK7x#z4OzPSkU_xl6Vo^F1W>h%ZX}9v<})tp6PHIjjBPJVf-C)) z-<_B6Px@#2))F%cJ-7H*c=^&x@upnBGfIyx(*#^zZ8`nG z8CbwSZQCV(Y)LX`PJ<$a0dNaS<=O%%&Fz;k$50rT|Gr9N;Jn*_g^;@Z9a#uS031ge zjIV%-dU+1GaKRVr=NcM zKY#Zx{t*<&U;X=!|3ukU&hPub|6py)@6mVu_ka1*kH7Q!pSw20r>2U`VV&=KHRy_RS?tOTA_i^ zfIUn^;um0N#tRQ2aM}0|k0aeVbk2ymC)In&C+hrwJCo`lLnzD(iJjg0@j|s9T}^Sl z77uwnc7F^84UKOj#9N^#9r;%1^mQ4;q7tzROiZ_X)boJ>kpBXoo}Ts^rw|PCcqk0i z8W*Icq7XVd>KD=%ej(tpLzi%e?R)skZO{Yf#`LvVf$LF%zGKOs?HwM_+zxDdgp}}( z2EMvyKAry7*I1^x#`x8009rt$zdi-_bC*Z;Iv@I4^nCrY+;J*0@=0*-TE7M^Ca6*rdyh!Ca~FT3+DuT{F(K^tzp+` zQjQfZExqJCNaEPzV@njS8412bJDl`@Q&VV&!?&eraV_-kE)2`9l3l*su=P><2G@vz z9?p2L*MHc#^Nu$Ix@@=0MA5` z2>s?=g6_Jw{m=lK|Jc`yQzx&p`%(yZa&^H4mx%Y^d^?H$7FCF;_v_C-TmR|%?|oqczuwtomUYZ6<5{G= zr_11I5aK~xD>sCN8(c%{PRcjI(N{gDUR>D;G!#s&h0dj4cXb>|5eH}i^`vLnS-TOl zDqVFQ|1BpGM_r9z{D^_xNgW|O{p;1YpGsS;?we)x zNtVub5COTUCE*rm?^z+D!ThxwK@zq7Fk>;A|8>+v+FK+>W%)8=AcTUopD z)Kt0oZCT_FoD+SUZaKm#uY{^6Ctk78XcO0Rxq?~tOM9JWy@v0AX4;6AT4md5^~I~& z(znb|YAsI)*J6DT9-W8@Nj3czAb3~Z8`t*v4-eCg7YKlaEwCL*=^Jix2Bg+mIWRP@ z!D%Cdg2!_9Wd>3sVDypo!jrcc|!3J*Q+1pqQeVHg7@+2*As)dK6I8HnWI{uU&B-aq~ z0>60u>)(Gv==bUPMYoZdUX#Fhy1dlr_d>7LI2c>0;_=1z+7E>!5s0GoWhVes z3Jm)p*e1uT3_jl|kSUyEja9fRsSrk_7Ioc%qLACQq&xEI7vusNMI9$|Vk&eB6W|fw zAh?<+4mIk4V-&0#@Yd3f%Z?;jd>xgb_l0E@uZ&h z>(1>@`)So5g)3eLu}hZpE{t>DigBAX-*e{EE<4g zAD)B;#(J4z49kUd6ns=8CG7Q;Xr(n6iGXl|sFI2v;H0)p5UBJ(@yQiYAhv5eF|b;2 z+?jS`Q67~W=v9jxdN0BUdZ$VNprm@MN^ETe(sb38k^rd-6ZIsI}Thg?|Y^|*pAflKeDY@WXTQVv6y#{H5%XX2sKES z=ejWvay90ji|x0?d_gF3uwUCSM-Xl4AXrjYaLEuvG#ZW>Utm|sk|2=YHRd&skwQNn z#*jE{4L2!eDeHqUzEX9A0(Q@UrBXt>lGb59!onN{hsdGk$hX8BVTt3e8aDYH;rRG9 z%pQ2LY>+#8m*tnM@_wAn%NL9Vm&2bzV8Z?O*Q=|qau>*c^uj>~!{N^Wh!K!nh(HfN zpCkZ`r{{8jY%}QPgp3K4fZl{@g_Ab$0f}Jr!NDQ?7&ef9{O(_A1bp&y@*IEoW_a2K zyNR~ACr_Td_T)Xtn4js=XUzLb6W|wsz#o3`#cOPSgY=nv@aNxmH?13j>iwvo?dt?z zM>ia$e`t(E-~pzRwZ3&P9T6CVWn~%2(splIlEw|2JlOBC!PyQ$r+`0K8VPyiO&fH& zWPbTt1|g{FO`!*{0b_~9FVif>^|a#*%MvI>12Cl?4|NYb2}+07r=fRy0D@B53OX{h!6dTwvNt#6#C(PSY@ma$t>IOv&mi zJ-_~NIYFSHh!3fdRSKCSWWhV|jUM)Xo>`i69n~mui#=GAA0;i1$oYQUS4cr*U)j2W zak83Xu680L1{kS|^O~HzPCdvX6fA1vDYX{*^@A00%1g265ikp(p4u*}j|$PmER*k^ z9c_<_CPXT}5t8;Dgl_}&n7+cw#F0eLTEsa)f-jMM*n9^NZkInyaSQpHgEp*V9lH^*r>REM0pduf8hGrSc}TLNm!a8_|K;_cKYe;@c41{@@{>0|c!x_b7T#yS`Qq6x68iD!k0Zzmli!oS zdmm#TzM;7L{hj;w!0x)7yPjA_wo8l{4PS4Z0su#QymfKh;TKgJm8fLa6v$_T7Y~>3 z9#Z7IVP^+9)n3$@6W+Q2J_`DZ`T|hZTgT21F2oJp?g)+pz#qtsP7sHb>~W7`4U(_l z#VE(bP}plQ5ypx!0${8tE&2dDF+*|$v?2z(n>fynzV@_%cUTg_;}%6B9Rna5Lk1N- zuc{!opJ%}k^7{4AJ8J^en%mFoJ%oVFOF$RMO5eP2=m_2Vq2xZ!(cY^$3o>iJTFpbQ zAT{?=OcmVB$b;uK6NdRRoK}{U2uCI?3A>U`MZ)5`_*eP zbmo%0e#ig|ris1e>TH@--8PWvj9O6XsK^tX29?6?iu&TBj)8(r1E8Ax^CJ=6bfSVE!-{!lOYr9HFMXF5GpJZk-TEx8>04WenOEI1Z zao~!nat6#XE|t0YL?zCG2>^HDHxuq@3>2G;7dNSs)&fcZn<;M!3^$d^M})F&nMur? z>1Kw)VC~Ff9{en=S;8pE5Pd%4xI_!`CJZ8ShcHCn(f@bs2OgKVC~G;2&?}mQ`I`X& zorLPD^P^iy@Up+FL*QAN>+L>mbn~(H9`Oaf{BB5O{0x!!=TiQidk`cUa(q$-gj(K^toaaFz=BD=8I~D1O6Q{9P8Jz!Ts}J{nJ+;|M!3LXnh4HUKrXw zdX0K!Ui_Z@;@K~L@$A_%?!RAr^{0RO$FKeIfBYdG9)I@($Xn1c_WAce|6Ju3YB@umgAs32Bk3aW)w{>Vw9&zltbtRRI&r}xXXh8HT#P$=#KvBy;^-&t#uJ$M9m4%du(hL|z{>iXSP=YIt=IE#X^wUgsy_*eIox(>&~xK2H8bWp zw9rms8mp%KzP;=6O6{=(J^ABQ_1WJ^DK9(Kn|H&=?o%KOkAQ+92!T@PrIpV~C{%TZ zUwWfLS{_L<^N4ewuXc}g!c*(=B0mOGX!eL*zSTnN<16w|SWu&ImgPCOPBXCTubNae zf>lrFHUDp})WYJpD;V76v5rM>m7;;JqMCGVx=n=y7QG^?w+%C3lR42%s-7*AMoJ)n z3Q(wkRK+52G&BHeH)UcK;E(37t*76(C2pE#;F=~kK5O&H(o&~6;R_hI3ok8WURs_2 zOJ!FhVa>!*Z8&{L50U_|B;yEfgEIv7Vl(6^{NlGQcOI zK~9{IFH^_`gSc1RY4!ao}MmW6fMq~Memb$HO)!3X!Hupi3k>UDg6^kVW>s0IM41qVhz!XE>&Cs|U#h!L?E z(Ebh&g#f$aqYC2)9?@&^Nb&c0MIqCotWtCRmtC(E9z_dZxPvtW7G&q}g^%DSJ8*#~ zTy>?BI36UuOf4!9G&6FY#qe*JubduOL!pOmHdz!`j9A<#%MvQa{){I#wyDpOu&B05 z8A60*Y(8JG(Zj|$TmlsaN`4jqu*4-8!~^_mEl?$Jxs`XpkWkc2gKw)8T0OpqTs(6q zTzRn&(`v$pVWhxP$q80GCz282DB1R4=`&5A#i^7i{Cus`1cEBxlr-^gvw?(K;Ufq{PXYaTtX>=f{usxM)mI@ z*a{&n4;_T3L_CfnA0uUH4`24!Uze?R(bsE7+=0x$y^&*8_=Wt?Z>o2+4g>r~BmO|M z(J94(Jn2nCXcZ~-Q{jUQ}|n}~tH*JeMuK@5Kc zGj6~4?%`jC-{B(|lR$=@@!nf||4tOnx4t`fc zydWjAkn8PLzjYflOOaGDRn3sm36g#?rCW8uhoTUO#HM5MS40eBhgk^xuM%29-35t= zK;WVXVEAYVY{Hws$D$3rT&W}CR8yQ~HHF2(buJ@U;aViQa7LqBj{m`nPQS`C0P`Pu zKX(CA0*$>_DKFIE=@(5!LRUof7TgwCOk4>+kn>*Dne!AP0F(`QRmse|)Ipb7O{AcE zW$RNV$TyD1-_2eNgl%s>c3kyifHhR$bcG`x2j`D8&buj;J{ru~nBN+ML{@b^KfN<4~XN-9O zSQK3HW#Hj1(Qw}47J%)Rw%{q^+}U3r?dMjIBmOyFQ6@u$Ab$M$*{ie@Z@rr)KpgBy zeQ*s9QQ$@XBmg9^om_0w3L@LwIZeX20d6xq&?V@O3Uqf8#>4G@^WVMsT>;>4fBQdu z@$4&}{Qgu3_|X$gfv?_uWu~9U>ACFzBNpL;QmxxtPUz2vL6`riV<>DqkXE{={o#b5Z877OIHG!t{c&< zb8$XuFXqG3(*QswC=_Se;=nJ1E+JGSpm~r{C$k5l5VhTeK*S$R+-^p=shf9|8)Rd7 z0C01SQdO6@HC2NsoCN@Q_wGFqK14l~DNVvE#}h)ICJ`zIe=2O75CA8>`ib)G`-KS+ zhMc=+zr2~vO&-;J{=J^V-Nm3MRr199^b)ujauJp9s5^aKHJQSCN@xcb>8@H7RFg+mg# z956&?j-{KJ-b(X&#QFJFQZ-u=BR9x&Tj}?}Deb{3|793HvR_K+@qmHdGVhKp{HY|l zF3(%jCoJ5gJ;PQG0w&jJ>H(LQ=Hp3am{{be*mUlDpA8^DWL*=v?S{UuL;yr6AgVAo zx9%`0`sZIG8vf6}CKTR6EP^NydGEpmCpH+dU=%+q@!*Ic_sYeWBs~7weMhfeZM|ZQ zG`3*)Lsny1e%C^nv!`cI{{_!zh0}(6B0tEXXPBT3{70NilGGFMn< zmJVV%e5loMa0BtQzk#65NNW;n5o51aC~H>0%tHS zto>Ag-p|D^kSn7NY1EHnU$D0-DGE_?H73M$8GAp@f3=?L11Ii)BG__w_7DmEa{rN{ z5Y}^u1-f;lna zlc;4eN-?9+xp3VCQ*+FWL@xAvTlXjG!<9xZ=LHZF{ch6{6ar}d39Jt^^>N_pk5$9p zs$%C?nJy}82TgKi$)@=@k_b{GhbnPVtwf|HU;w+;$Wsv4SbfRgiPAnsqZ-)C3=-XK zl?{OH_H8CQud+F4-VfyF$i;AGvA~@e+0W`^Z1T_7cWFon%C$iYHVOnaID2y@8h(w(;nflqJU zVmZdGThm)&LN?EWWTE|+nKRtBaoPhGLioHe-go3P1<~w366bsLJFdD6@ERYX6t28r zcKDT8kXM`le|Plmzc3K>LgE)v8~W+|a8w&W9iV(fc31^SPqx z)Le!xGko$tY@kBQ!N(8p$?1Eqey^@0pM=lrlGdFH4otve{JP{^Q13M429Y1G>%*LCf;rVe1Xgu4uoy+6pX|a| z5p?#!zxeufS$2^w%_2Qt1Y1T&!DH|u925zGr@~IhLKjlkFypmOc?OK_tgvW?lc9iv zf|%ftM2plR^w&ign2qI(7iKl!*!}wQ%H3s&W{ehVJ2!RCjzoyQx3#sZw`c;7xfDRC z=Cbvu{qP8A=^hbEnFWc(kUY;7;&kUQ=w%}IS1~UWhTZS6LQY9o>va*bk#$G{IRW6h zbFm)rBfVdPQs)1tN#4RybX;G>)?lZk>M~ex&0dyg#JJczOWF06Ft{n4%4t`QdLczp z3^Pd0F$T?Ixv}~e-;o*HXU*oX0{-Y zrRJ=6mf5oF68r~dzzP;e+2fcT?In1Ytwwj)wL$eCf&mX!7qA4YZjxTJ10|vA&wvaV zg4Yxtf{nsu&X}C=N|5@M8H-AmcSaXL5Ft?pM+6*(--FNQSUx8|$c*}kJSK9Iqg9uG z3Vb-mI>a`pzKw(omvAyQ{Nrie&+xPV71^%Rec4D79~Bj)JOsr^XEIunHO(H6p4k@(Dc@0N5fmcuv*;pi2!{Hb

EXh6#e)KB>;BWr|^WRtSb$t0u6CiT^KKSqh#29?=&iB6m4lhyn-%)-vZc#eT z-^bMthdD^adF>-_dC%&OwK`@QaKZQcVIJ6l3k32BQkiV1* z`#17#=H?)7}<>$xhtq2ri4CCxSrAVSwv( zavWNS34kL-!srI5#42Vp@?>ZlM6a?i(8oS`Mnch7ui6gMzg}|zfIHHqSfG;ne3OGC z??TdBt!;@2gFR1r)sNTza)M__`I|WJ3QvDY2qf8C4cA4#A98B~pr^z_YQxO5nu-UB zgi-$#c&44362LwE*Wn1Le7n&k^GL9puF1C4_2G!IvA=$v)f%XIvM##tieC;%q2 zQd6b^rGeE#N_{Rm@WucC1%kQYuVRvetFHXVg|G{21}qBxW>?={RWUGLT~<}EVxd6+ zgZTj8!P;NaAoH|^Gy?&Z5k2L^751nvEMWxHFxH-1_4_dPp5!g^UJ!#{TV+%V%a*ub z^9+c3%Q;nSXo==xOK}RRSZ>MuI0;@LUzt~-B%thIfnDhEXAs0-7Umfcv88CnqyUCK z5S1Xo2sce*Feg;@`l^(dzXklt_zOF`pvS&c6UoIp>|9gfotuN3y#epBoC*igdzX!!L69{P_yRF%-h!S1U{e z+*Um5$;ry|U;pa6fAJUJ{j>k{Uu0|}{yl&5qYplKPQ3g4{yNlX8buhzP|eIa|+z)e}+wL4==%sHe#wAcR);21KD?93|_Fm zqtMG-G@f!tJB*nc5de8}qyM)+(^}&c*w?`sP;~I66Q98dkHp4MC&RCZh6_NFpQFom zuh~V~KAV+ZtD7SoX=4u@a^vGmM^0kfiGhG#uJ{G1@TH0tc5Un?5Jlq6L8Fd+SNm%r`@p7eoi8 zf11kbx&r122h}tL-snKu0SF;_2dgapczn<>|L&OHQ10^;*ItOBs~!v=rBX`M8L5&I z$G-`6gH>l8xZYClMEK&kCFD^Cfx$3RpyB(D!23#wWIO{}v_c6{ngFv(a4e&++>Vv1H3oE35toezNufC*6`UtUdq4{M>-gDPy*sK{ARNvNw%14IV& zuEsxg^OEdcphPcEIoNfyDdo|#%!Qdnu{aP32`H-^vZil6UD|w!KHe$j|0zEo>oVj2 z+QTV!jj+|1MV21rnBP*KQ(GJBfENUSiv6>sS<2~_B!sOJOM$U+BUf78z(}0NxH#rf zklZcjJBy!{dJlkXPN~QfBcJ+10A+0QU{oKxAyb^#c)C=}Io4qfle}FzobcuJo!KP` z|2XDuZM}^eb27jbT!SLUt`Fox;=vZB(Fi^mvm9?r<-p?>j3;P4BK}eE%-L`L)tN&8 z@w&2u5yn{olB9y{MH~Ac8Q0lm?SX<_LzE#<6MKH zX$eE|Y39VJfl7E_HWpDIcG!ep6>&Bg@Ant>4SSPKC3L>K^AyZ*_GvSJWumBgnFUJ31q z9Uv4@4@-{2BHWdgbfs`Wg#>aKBnUPSRJ9>IBGe!)fl3svz{5L24&_JRK4>ENlo8N# zlu08Te?j!fJoU|Za8&{?tcpxV!|#k78zqqwWs)GO;M^*Ylu)oNs1ki@ENk3?&WwyW;0tIHnVL~leOWOF(kU*HMV>|v$SnJj zSci1`4iqpL_b~r0jR|~DRU>yqq8D#rCCb8Blit2Eo?Bv@7o2Y|?aQlu%c6DcJLe5VTpkedHaCjUxxx?ct;2!{w#IQzZLT#i5@|Ii z3C^EoFzNnr*= zlaX9;i4LYF{JzA>qBGJE=;^gC{=~$p`aLoeyVqjlpgI(X@NJ#To`8$+ zS&taM6m4MMHQt*mu1-% zRbrYO+Pov0`czll4NOkJeD56y{1MIR_uOPem9qVlR}X@F>s zn&_=hWl2 zFz3Ub#Vy=yUpgCxD5w~NF6a+OI^TvqkN~J)KH%ToDU`2nMcg)JnPG;V}XBUX{f4TU?6iH5T!+53*^sBtWAgD`PHp4JMhK= z!K0@O^ILcYE0)Go06nDyaLj5DsR=P=rkp>c-M$boGNJV<1po>Fe|Pq~qklN^ub>2+ zIuG*q!op``pag(c1(GGkOnBu|V04F^vo*y2Una*qKYot=SFm`jC+K6&w?FyWuYdD@ z{^r*|`||mhU;fdDE3eanRi!!uJFh~SI00S>|CZP6^Z?+kV8z=23bap)Bh7wwrH;tP zFrw$TPhY)OVAl4C7v>dEUvpweN7`?#1Y|@@qf>>-gQ^j+2NNa4aO9E|_Y}h&KArbq ziYr`>h<~Ttf7OBM6c}1Wv={e?f5pbB0uzXFi@Nr;;RZN35IB1KjXij_uv(;{P7H9T z=i^|{KYIX_@k(Mc1?&%kzXszuiP#6ar8pTB-Hi&?vf|y{S%EJ10J zVE(gXg!e%9luWCtqdi?>P+*Go0~StC&rMOf3;<-8rO04b{E`jP1X!M884~Kyr-w@_ zhg1Bi`idmxo@Z)w1f32eOyM>%^tlFOj>O#$`!0T9<((PlPb`EQF9{AA1gMZJ8{*mCr@+In<-E2+|2n=rcv}_c5j=a(jWg%#6L;oAVkZP8MZ=z2k;MDEWT}7N~ zJQVlK4H(x!e%50W&`_vse$E`A2`f$c0U8}cCGEpbU$7je*NJ|L{0oj>&rxS#0E}i} z<{nP+q)>)J^Y1E3qUr*4b@q~F4dYyO5`DfqqKvQVSJJyg<56lfit$Z0;6kEktA)KJ zAb&Q+{clTRx#yj7anKopCU0~uhi;~mq> z0{)!usEVVSJ#88k|HiSVV2tGo=|~2uxU_~GAqv_TJF;j6PWV8YoMI6vcsm-8W*uls zpKiO&h=c z^io`cm1fw^Dc%|Aw`2|pBbroK!6605GVf!u40BN*r6I8D!(GM{Y5iJgvr`?hw0Flz zFkz*wdl}Zqw$rbtu!A)PvxwC&u;rDLS)2jA|8hXviA^|8d^Z|H*cvRSFQE&%>znAu z6J6x#OSPg=FNQ(AEk-{@cG#k zGk!<`?0bs|GUa9I!NKb$i^n3E9Rr8u=HYq7N%Nqjqoe}K2F zNjs=1JE33>Tzq6Tn(yqSr56?sJiwY*i)tQxF957pJp($_G%ik*?7%5? zg0ZghNPTdRNG7LQHnO0pE5x@)S~#siT2wWq{b@YTX+X?EkgfOksh}p!vdelod^w{h zWu7_*Rs4t++fFZYE;LSdS*|uc+}fmC znAbPL4f`+4KKNm2-d!b%5d#(RGDYgwtTUB;FnKsLOZ{(i>dvHb&N3C2CAF!?V08#R z9GjA^;5*$FGwJ}=);$fdTfGeg#PD`|x2*6}ymf90%$oODxDH66Ae5E0i{57~?7<<1t0vU1(5V-G9XJp~eoBlZRB5WVr z7Nvo-{w8*KKM>GQzawD28vv*Um`{gs06hOvf|po^H54A7m;*l6ONWn-w>2(a2?1BG z4v&)}ngEDwz)wF#I2JJPiceIy5bjcK-0_5T?=jGC8GePk_qqSxS1EV3x;Wkb8~8i` zfIIhiEkvbJr-QFG%yOv*4X3|L8hjr1$#<} zu@9HZJA7ePBmLQ>y|%RJO4lF&cIk;@saIAD9;1udq3F-$Zqxa@r*^%G2d+T8P%QGF z=-EYiO9+4!03f>|q?~QmI5RXHf(q2POk3TyG~}A_}BSRm_B}D!HYa5)f?hL z6?{|)b(8Dv@=UMe2fDVyg}&}c;tVJ-EnIh8W^BWZv;uS-6_Ns3wI2nemPwH4^0hyN zc`(RAD8$7OnJv~BRce8K#4X}bnNnk5F&@{y zi@n5}Bbz3F69AF}(Jq~c;Z;dx^qb6*2JS+|=fnd5p=vFm{hQkL9?QaD5Fj=6hCnJ) z#@i1_l3=UFx{RfH3Rf{u16*il)k4XMZ`hW@MEx2(-|?}iMpk(_#d#uQcXus)p*yYH zno@T#Ghs?@Q<6@lJ&g1|CR&wT@0OmR##=xNKISb*Z}8R~)nvY8l8n6}dWqi^uS&*bpE(F)k-(4aK$%@;!X`@P$$i9*PGU?WiK6BRDDO+U^l> z@ifkBFwa6YCnLe2;)PeEVs#N;iX@MPis5CG<^_u>@DFjR{&cQ1OC??q<4cAy_sy2` zty-o(%7VcRpO?j1D=93E;bVK{O1@%8CvcT2R;_H&pHYKo)9%%%^>zgGVo`>XUi5+J zs2S%uai~;Hi*ThXCME4v^AWHf=?QqQ`(7A-&Bk(XtQ&!dM#YrYQjp0vyKePR+KXg| z6sHX8M!>p$KaPHN3A3Z5CEY zN{e}1m1z*l?_#Q}*egxEw11c5VKJ02wfr4xTzBOg%tR9xufegX;~sMDb(k}6E6pE% zsVo4DL1hJ-_&|KJNb za7Y%WP=E<=FpO+v#y6KGWM*QZ0;d^MI>+P#Xk4ZUfLm0YjAyuSP6@<@WHic>^tD?O z8_SL1^B?0{$i(8YJ^$f-Nb_RGS~$=OtS|+hxHaM7VArNpT7mYw2aW^(SZt2)0?c!S zUU3>r4$YruX$OrWFnic(LJGvmrYwTPjJMRr%tsB+=2FSf7p7sHHs@%1F0Cn(H^ z(0j>+*GlH33B2H&zVsk?%qyU-dKwF_4yBaA&mup7Zj{If*iH_w4mUXTJ1E{m?ecaZ$JG z*?9^5fI!0@rOb{j04ZM0OMbPp?(GFPvZu&Xd|YHSn=J-2ES8rs`FeD&z=c8@^O8Jz zZ%0nwN&dL~ezwOye53&q$*gPi)EiA8`Zs{hlb*1W5>WG4t!TeTL;@B9`{FvcnEHxh zV#KsJh~^JrmJHr8OzNK-fDi9#iD2QQC9_8y2IHVu@NDRJvx|;r3)}0Ol1J+!czDd2 zV5a_6Vmx$2D*qM^f^Ks4jXy49@!9qvZwQ6Sygrw07*4x%&EYT9^dUSIi7Cv-U$`SX zn$irE?APd)62uWscKMRl*T~Z&0H&B0*Zr~-lc|6+Ku`9hPpy(xS(pRp?RIBUgNFdH zBmkU22|ByamtIZ}BQbwIs9wH2Or=K3Ox@HBDAGoGf_S0bT4Dj*(x$(?B0 zjL)Pa1RcB-s%oWM2>>CBAv&H}=uElGysOU3Wr_%Ixh-VD+UI@Gf4CH;8{qy??7>qh z<NN`B4-F&B@|r3qwe0?^DmvnD~j`uGYfv4aqpnSZ4?z`Mt>=}PP}QDZQX z5KHfdW18@OL^r_TvEFY2h7f>2 zK7}r1M8yoTpwnPa2fxnP)`npZnaWQ3#XW6f!a#wV1S)`&LLA&}2jB+V3FV#*1KLx2 zq$2$JUMTRBI?GjQySwD?y7tDk$P+pu5Y;z@Stj8ZWdII>m|qMXPo9m?bm)r{Tlv5( zNCk;(ShK!JZHKa+F2t%%?%>y3Cxw)Soy%rJ6FN zC$`9?nhhmhO>C}B97f;j<}BFRnB@8)6})D6X&Djn@tykEl?kn@e8p@) z7zaVSIpeya@1=m`P7+#1i#jBrlo)wJQ7yyDMlI0ueLTR zU@o;||K%hI6y^DG`nFO|+ls1I`ZFJ#0Jx--1FyD_{B3fTRjZK-kAQ#?D+nRs5@$i! zfrnA81i|ynJb-Op6X3$Fw`q8z_8I&z)?lz9bc&46HeCQ$W=hPy6H<|iz`i)}$dMOg zY0SPb?_J#ikNhIX!6}Y?C+B(CDF#9iz$YL$&abXK1d<1N9_^T9gS8xs`XJbm9wG1v zHc!M0AL~k}Z5Y400yknAOr7Y6j5@?L0sjUBz`KA$cv_*!m>d%?@l~mx-l`htQO4k%iHbZ)}4pjF34 zz&&1<67}mG8U4_ekYucctb2QkQJ-DRxZ~`yu8UFQpnsi*%B+KM3RCzG$`_L*;ja}K z*oY8SFU0ARWfe?8{cuW0P{WAA+^=tAND#o=dz$~0R+wRgg$P>SkG|6KtaiqNI$&!^ zX!ZKlexAE0%6Q_!591H_R(^2iXextYp}LpmGIcU>Sev8+9jDCeB*4kU2IRW5)Ph5W zyi9Hkh(U(1@|@9F>(TG4(=}uP&A0U4@Nr485%uudMv6z6*#t)w6 zw1{dz%k3isK;V}~Zl|4cX^o?t9KgjWECPG)sImhNa+S!u($M9iBOC;a=FPIO6=&Xx zt(MlGytbM&fI>_H;HtMWuie? z#5Puf3twWCJ*;;NildjF8Lk?b$3grN|mPlaGOC40!cra=5j zH6Ak1!4<%p;F2kehH`L@*@AcwPOM`J0;voHge}m}E1%r0{RIgF$J&1-@S`f4?ZCIt z6ukO2-67-gezanG>eJ=#AND;1S{8^r!1KUArQXv7@;rVB@{%Z!(fAU>SS2H63^w1G z0S^Q9u>6AY@U;+Z34V2wRaUMBWIa}V^?Qh$-tpn`MtJq1g29cCZHRaud^u%^>^Y^= zV?v|I#`2^hDzczkI{08|XPJM%o-31(1kP7sV_(@sQUN!I08;WHbdntxM#1O@A!kg(V!Iftql`#%(o&`QxSDfPMI zv=B&PdM(Al7#u~h^qixOomQ{#73guE;HtvyLw3F&95fpsW1YX@|dDX z=~;5pi&FR1W{ctQ2Hfoi{P7X+a)kj`&cnYh1`!70^2gC`b@yN@XkFz4BB2?UG(r&L zTJX81P(dugyTK!~D+Eig7?IsBu4+$hid!Q7l_J==tjDm+mm^zRcs={c8M5lyx3U1R zCFYkE>X9Q@QkOaTkMg`934pdV<@=wDK%C4ViF8}>t19iC2>{etuuX|HKy3>Gmpgp# zsRdmBUQ)fNu3s8ihQz=n22B&mm&S8U*k{=YZ+DpYwo%>kS6xR8xrX=&wxn|h#TPcd0?Cq5FT$w0f;J+%#cX_cka@p?c|(8 zFf?J15*LEo@s&_<ox}XQ8*3Cx4|zR-j-lanB6NnDdhAN0<8n(Vs)K! z)p8PQ3dxUlR=eL$Wgm$*_b&A_zcie_6(NK)11tWC09uHWO$7n~1n6mDRQ^ES=$-=k zm&^va7J6d+NhLxCoC#x>n>@mqqwd`;C8X*bw$j`ejB-%Bisial$f4)X7)1_iHQDa! ze2d~3_$OslAC-#$OF*>06WM&FddZxt09%PdpR*7zYHoGZ%ucvTCIQEx0M}n1A19Rx zyP*R7Y7Qx_MOOtT$OLtTa9`AFH~b*iPp(X_!BU}3HGFgGhch~1H%#?ct z6YzN@VVe()vzi>a`jSSeC99rZXs-IW2vZx^)}|FQE&y=?J_fLuEz9M(IbH7fFKJo1 zdr?VA+~F$ARC?z8f#T>gU)-ss7#ksc?y4p3>E=+SlbrwD1}9m5^jb#Ir4UM`=NR@l z8jA8@d59tdT`Vjod#k+3k9#?z+FqBu&A_)iy|iHb^BW*<#v~dZ5ug{7{*;)dVUVN- z)?B1sQQ}Mhq%(wBHYMp_O16XWgYiDp6SlAuFGv)Kb|mPaNpvi50$d>G0RYEmSora> zB+~n0LH5n*E|B=8{)O|Q3*e#%ox|V0-f>?iz~7zScp?Cj@eR1cSoh^N_FXBM!DUb& zb1q#p(*QmB5hgDz6V#y)qaG;|;GmLXcn8FJ@K_=lJq0&>!si=TsA}U85MO-9Btps!*p_kjIv^)RW}Ey17_}~ZrQMS6|;P_sib~eQlY*Nb{TZTMY&@Z zSjz6fWRiSn`Anw|OX%m$B4S`Q(L**6OBy{OV;ovycjDF~+Bxck(irD@Hpc!<)J$0~ zR4qqRmTESbRIVdycsQJByUueICQ%ocG4EwvzTu#-dAEgi#9MRT1Q(lYAtLZGp%o^T ziNc+m$`)-#$%e3OQF7#F?OOd@OZ^*72iK?jp_PC9_rcx_QV*;AUz^Sm_=`yKXBOA2 zt5TbpOaLGh0D2QQIoIa!85E%UwG8WA@+4k8y2@3+MJBiCc3UoG%Ns3DMC@4^&@ zI<|l;AR305sasD)fs8c)68|8Cb{>{%((x{D=jfN7unPZ!S&)D5K~MmAahUqxJmEcO z^_#2EkFT~ZlRi0lj9h4j=L-%mt`wB23n5Ly$5$4+a1(|GP{l}h?VaOWrGq{k@cwrN z{5w{BGj3VODEV=kJ#K$M!#aPiAP9yfmunly^F-2J$}`3n%UWON5GA27;GWu%OGo98 zY-F>eEJVS*NH(3w9*WP&K~YXxUG|(q$`>`4NfSta2fsd=Ad5MJso#6 zTua(#03IV$3z2y38E|8gtB3PR(A~I1pGj^+6TfT7(tmnEr;6tEy6fD7dR{}BMW$Yw zFI`WrsSoew2|QR7t>JE@%<|ixLt4{ls#$WK!oRdYJA9@eP3iS|WY5?^T;RV396$%r zQVHpe^7m zSD|@X*ak3bLz*(LKp4E6yc>j1o%pz{inm1&DvcLgl+{6SOfLyIWr9~EyL6-4$gRFC zSu0!O+-{}P^T>quJC`|kwv>~w8D$<6LGwL?ZCHZsqoX`|h)C2sca$3_lOC1UWwpae z4>;rOQym=<#DKI0801(6HB0aCl9uO9ie-p{j^&yGluH3^ge!5=ev0&GKp(AdU`Gyc z5X7sHsBm^R4npHdQfJqIyv-rdcX?@q03#t zArF1Ws;__w@Uzbljet`jZh$brg)mpTKKdU<92sHgAkl%ZLfM3)=xs1y&}l(F365FB z6ei01OQ2F?7ceI?@~L(55wg}IH|w&aCL|VA)+U@0nB45#D&Z4RO4#H!H(P;EPt)7! zD27PJnSc1|L#E8>B@5vwrbgISSIDMAU?l2SPVLp z({I$W_XfJMWp2dnr|cGwg{CS5PkYukn38Ab@qH z<8e;Y;%>6~@|ZUZY?}>i#cu*g&f@IHdtGhS*;p0VUe^5F(Wi84a4u9zE&=CjL6$@#Tg_>G|W#Lt^ zQ7a_Rc%s6t)H*c)wxTd|sOC4-27?tQc3Pec^mT;=A{x6jEx>@Y z+oGZG0HWw@TZqe`_FIT>lm)mnWP0@U*VEH)zr9HPG|~-+OFUhY7#=5mO-WioWuBU9 z*=Hpj-^@+;6?%>qn308;e8Si`zv@Zq_v#26va3b5ly=3p$tJf?%=C-zFOCWSl6V- z&39vkNyT{4JTRs`kR&SzJ?IygZhr=^@6Puhe*Z41UKxK?iNwjy_TG`Tz&HisReC3A zqFHv%SqUBx@EVvD8DA>g*yzXuY_nUBaM_XRO-{K>q6^=oKxm*`jd)q%+@=5+KZ|5% zmHE$p==807moui*%&tydJ5=fDaV=uE?ArfgKnS{fCV9HpTzK6kq1F5j%R78uA% zbj*KqWPp{e(dA~^RVckLV+TxQKA`b!N+oi%tKmgpAWwW^I#BI9Efq1o?%AKQz`WH1 zuA?a7O;$IP$CCp6#%zbc% zz-?0)Bsh2*E69jmQS{4$&_Gk#qT!ErI2r|% zgC#V)!pMiCAF1Kx6-J{nCjtMK-#$gl`Tg%94i#a5aUH5g1PWn|P3R-eER6jqtli@V z{E#{Lm%>Nf$=E5$_Z)NtZTj*aDB$V^mflN+JR|J6q01aAlIXHTao$3y#Us@kSqkQKEIg*N%_y)br+qn2?enA8P zGP*y|P$7mAOxxDnQ_~&Lr;voyIRJVxjLveW3}D{UnmTcG{)Aiw{~e*+NRQZYl{ob` znR8ejF)CSQCbLF$QY%U*Q_bV6d^1Gu?1Y!KSd>}n(O1k>)TI|vR*dY71<90RLiLHG zAGq3A1t!aSD^+#_vlzKj(Q2BiJrWs`Imn*ANA_SU!Nu_ghBK@9m}!r@?ru&`RAY!N zW~-_%T2(S>)4sS$Y{QioJpvtpQ}9RH-Y9U2mIhM4KKQunv47bb=H=!wxq^^rm@NoX7N1 z33@$*N7b1o{BtpPc3nXf!Kgku# z`4TK+h>Mi^XcB>{rjtLpM@oUO+y~wQWsMx?^18(@xDwWUzvd4%Z z=tH21B|(&Ac$LU)ZW16LRrEdMfTsk&X4+PBeR{8A0^g3*n5bw487i1`pVD7Y~*I8eGW4Zui>QRd5S zkT-a@1qJ=7loHbxM!+Q|s$lgb7hJNOx-3nM`Y>CF_`mIIi~s<;E{q*$JV$Q0Xgn@ zM8t9&;RgYJ(!MA%=Jz+RfK%FTWd@E+ESJHF<~=;m(-8!aSHb;~?cLxJ@Iqc+40kla zZ3D;{0JE|(sb4R}6#VHK&2Wf2*^0$E3UEukAU~S&#XW$T}W9eK^Kj6#hvkT{SRV4X$v+%Q)_7hU1V( zr!p7h%=6mB%kYSKDM^oK=0Td7sxq__{0&Beq|6(&G~y9#8Y%Pf+TI5L86bOCqe&&5zUbdwPw{7zRRu$$43?Sz*kXP(^Ae;hPP2fT9)-j^G^upq48+LA(_!{;x1%E9~C-XJ|}9jd@3? z)w>kf;m!qr0RW|UIZ_iaAhE$EOKuEB;G1yhu_Eb`+i#JGj1-rwld|m_Vu(*+^I)A) zUWU{V|DlDa!L18#lrNPAeIaHc9>Aj@zNv3asaL%K)rJey8&n83^0MJxL=>6@;eUt; z?refNIt444f?mad^RL_U)WmUZV?zSy=t&E#apA8P<*Ix=dgP+xOovX;!Y%ibImpDvCD-xQCvz1q>{R#w|e?3GnJ*;bQxv4 zq@r|esWWC>+nkSBmPDWc_AM$iblM?*N`~f(xC;)4qz1lWlpe-H#w8G)6mW|94@)%x zu*7V>VOziHe3!Jd9Vd9+5CDo#kEafUuWFVi)P%YyGh$G-_ zw)&#WV-67rnE!xZls6+ppS$ynC}j$Jn2maeAvVmenVVC?2~wj;g8&4T9t{Tw=36;C z=8ru6N%l9x@seyXgI>@IGP63fuNf~YKlUU1bZh~Pac}?Z+j^L9rDENj01brc8K6$F z&)bj%o|qqbe$I%~6X)jZJroV29azFYocL`7mS2le!_ch?Ja645x$dTR+ z1nl(EU6Kky`sN1WY&p8B7%3xuIZ#zv8bPDqCF($8Hgi3Q<$3))mtc^y!2@QmlEo0d zA$vJKNJZk2K7||FB%j@+U6yATI5>%LnnDb7EV`73k2VvdVt*1YV$F~Ft{$>#rP@ew zSXH5JR>(`+YPk_Og%S|JB11dox>WwgKOogEhz%7qH7!>0yhg!vX4$j^hDAkDDWpZy zqB8F333ia_t~)*eVlf|j2INi+kELj3>YzlV~8;bukEnNtA%N21b ztqS>H1n2<(sb|LOi_aT1f#B;J6_(bZ!0y|eQV|lskL7R*zgIgFqobLfQg)aDi2)|3 zfOMV5bx;xZqDkltZc%3K*5A@l6>(g;OEU_-DzzHrmNkJ`LLpn`=(p4^xx0vu-yX(d z&6$ts(4i;9pRLwurAj|E1Vmc}M>nHdPMi@=2vUBx6RIR0@HM)d0p5pZd4 z3wSPZjqiPEQYwyBgbwh+Pf9xAUv9?bmai6Gkr`f{w_9XC0`851V=cW$N&R>B-*Ug- z2EdDa^Yto>XWJJ5zw>RRKA*D|_%O^N=T->n`Jn>@X?}}(bg{q!z!gVit>Dh5EL1!n zTmkep5CZt1u0(vx12=$+hoph;q9gA3eo=&h0B{)@btqKak**fJA+B~9_U>WH-5cpT zsO&eIxHc5^+>oq!)NpEihmt|1{{gP3M(Gg%wJ7mW)&pxia`lne1x$zyo&`Sxb$e+K zux2q1Zp9JDKt=@?Gy$?~q`*rgtx&ZJ?>i1V;Hjt8h+<%TF%%hvSqtKqL`SL&iSLyd zTQ~t)SzSCe6Wn#WdTvYx*}>7%(ie!u6Cpr}55TKKLYyRz_!9wOb)euU*1=6e%xBHC z*552L{!(B8phRRtRuP3^;2{8V3C0MnexR)2Y<{*jWuaM4;={BpN9HqaZ<&hKnX!;n zmA>lDd&j>u$2=wk?&a+vew@8(44_#tdNhhRdXPe-61Tmqkp5kW*)&9cH@tHZQ5vzO z*A16mhl>@Pb+H1kHr?Bs#>3R{D?qAgwyTK}X~t!*sNvmm!HNi!UZoP!cEex19HZba zGKF@1AY8444lqj5G4dg)Z|a~dQ=EE1c8AI-fF-1@Vefz-A@IYT)z%8UaDaRO=E0!o zoM1VGY?uW?N)Ju-ZGg5mnFwZX#bwV5zp_}5lF*Dc6a78s?H9J0P7$R`yd!cbqYH$O zw@S_Ps)DvCcP_Djoipj3+d%0p5+TgHSA4X%T8?>`_7syPvoK^hWQt)1L3$0|G=+V4 z$ennLJFkKiK=u;v4~l8-+h@wbyh8t&`tnLari&L$z_BL2qp_#G6d8D? z6hJ@w77KiG;oILu-2RkwaI&q)=jWUOFWi1~{G1?nqO;)fp_8FiCvr^JFMEO&dTLuR zGZ93LU;xA_JYXgQUPs5<{S_9204kYD0(KbUXpDhO#R4uCPce8m2!C+9-QS^4bd3`T zzAT*s|4>=?J4{Dq@F@i#;xi$A;1R30(Nod565{K!P*jW21>0c}B8HKy(=j6~xCq+! zlAMSOkS?VZ>=>mux3OGK0jVZzfsLnpJm4ZnHtZP!wM)9QH1l>g1NRu$MLr7^O=k({Aw5y>7iyYqQ* zIWhzhXR6dcZl(0@E)Cr($Gw|tGW{I~1i(8g1zu`Sc~-@~i;WghS)BE5@!p5ap;BKc z=bPt!aG|^~O#mDcT{mY?h6w=VhXDX#f#YScB_GHUi{zAh1sL2ftKQcUFM>-E!e`F< zbJd$Ge}n1WKbvP`()hof0rB*Q8#lo8r0^?BTY!9kKZ;@mfDXT6+{^Z1?7%0M1fnEZ z!`}l;e^=r?4nydoF_5b-RWgK4oa|W~abL0c9RJLZF!TlBxy;nR+qVmgm~kY{APtOM zXnz$c-me#`Kt7>9t|y^el{c`BN<#w@V_rNK6bhsdi%bZnXVei_oKq%=Tz&CE+)21b zUg+pYNsBV^0f48R^>~xCm<5MFJTxX$tjVG8J54PR9@BVA5svkGP0oK6LtQR)(IaaB z*_C92lt`FGExZ1-d*YglT5;9vVJ#oQkkdDL6X9RTS!5>8;+uz0 zsb>m%j+;R?0uo}@rIwLiW_=P46#SWsQXv+dK2{3?H-arH?j};+PfE7!1ytt6ah&;N zzd(~m8YGkHuzCGXdFzJ(utRdn>Gr{E2mrgah;>PZUt_3qWuoQ^|I@?;C%bScpV{c9 zo8W3W=D{Yz7Rq!N?|S29*a3f&Rw?+1nJ{RyT21NxKmi}He0-If=`#0I0?r(%VZ8m| zpl!+*;*oEjQZ=_ZBa=ueihRZBzLbHk#Zj*3GWC#-g$Bau5 zU;O`v!2jpw1eoYwYhk$Y`q)Q5h-31h`@2vOj9znfVymx%qWO;7hbtDrC=i-S`Byp$ z9)}e~SqN7?b+6s$sEBBU4Q|1eE9U+o7Z67HD&wF}HyD+=k!|dd0a>?yVInWStPnW> z4w(K@MBE?dzX5MxFMJ21`mZ-4Cs1k5f)C~{Wd=cKr7EW;y|em%JD@{0SOVN33yc<| zOT|`^=Rg9VCcsAA?|i81U3O(N>9Pf+6TvaWuggmcsk-qi-VGZLN>CtCOIV1nXMe#I z9bU|y>`Jqd&xO5fH(kSS6vsEIdXf5$4bFpxKmT0G-3gA=$S8-41(z0S zN7#Zx_f;)UDCF!H=g5NIN~>IIcq;@77o(G{60ru!?}4}jHCGlWpv29h5mK4hkX?V& zbd+~7Jqv0#9TY`(6bp{UvOt|~pqiC7f>V=PG(#lg(XGBs1 z^B}^GID2_|F^zICg@hUC3mHy(i1JMaxM1i5)6_-w59bD`UOd0(hE&nw|rM?Y`DM!#1_sUBn; z&yS9h4df3w6Y`CEfp47uH~|vj$ZTA=^5Z0M?!u*U>WxG0L5zU$oVUR%^1pDr9UeOw zOUVaUmOx(-0CfvIrWSe!(N`;1^#`hpgO~$+2^VL0Lne!NW~s8EIuE;BmD52|oI%%D zRfU@1&%)h7N0G{416(S^Rt@C4d{)@&go&cCNc{z_MW%M^{92KYc*894B@vIcmz2r4 z5dBgkTgP~ZiSX2|a1KDws3&gOaWe$J%Z9=_aQ@>pIeCLQFi`%?!=S6w`O!{1Kx$nI zvMZv7r`e4T^+3N!j#2Yj>LFvG`yc}SnFh%9c2Erf^hr>}2g*iyS&VoWMGTN67WeDG zKp@a!;va-O;DHBjBvy!w0$E~>RQQYXuIf7cF%dz3?8Nl$QC{5-CS%XvqKS?<_lohd z#W%}C1FLylet!Q8MkLGfG}ers6R{!sx1v$3<;3s65|@Z(W?>RdjyXvk)t8k-{pRoo zM@a2Py@wuy%FV^a$b8mGRsa~@j_Z5{j&+K3-fbES6<+GW)YG8<-Qu{3%mjHwcD*~( zZbI7Rz~EahSD?Z>kg$2G8Ma_#EvzzfD$Rf#(y+kJ$qF*HP|Cf$d_O+T0Eph6dRrC| zOn^Gj(Y#B4?B_R-S7*SM0%uwYZV7<+wfg7|0Dqe^t!s-gm3c6C zK+_^>7Bd{%lyG@uBK3lXLFBqj54i##EKtfP7q7QyF3ta6U02WA$i1%>WQ`My2nfxX zscg8zJyr_Ag3Zh#w%>4IzzZqT3j+6mK)7)ebYK@<7B+Va75)Sg3n@~ZZk_G+p2~%~ ze4YEe{Qe_t$dzr`mi1;^dh~mFUZC^62AP^Xm|NF?xQBv3DmupZu(Jkm_ISsowHu%w zeSdY!%s4m)%0Ja5py=CbcZGB&_icoJYaa{iHsHbt1wYyg=215J3#)|JM+E4_BFzJP zyFa4-GXQqeJ(>UQy%gD}BGD1TJ6XW|5})aN<=_wbKoiz*qMBdxU~H1G=Mn_s51c@Y z=>1X#sm}m`&vhy}(gjqHrQDWsP^3dBp9G?B@~9-_;ir!qtpi#|i_7_dksxp1eh?={ zF_%ubDQ?uUaxz%iE1&fqrj6tS68Vfi%D}|eeU2C5iqD={wcisT-coolD@k*`*7z6G zKR;~oc&kDuN8*?=k_e8K0Fv!=5oUCGKbd*LQfX2rhE15oxN@9CI-?EiiYW59u<$CF zW>~rM9hZ5RpcF3hqUuTY!5uLcqc3xBVeOPnT%&~$=PjNPzA(h**l-hgDC0Sy0wRcV%sUPdP2eqRPr+C)JEr2v+prh1JE zcLfmu$!D3crS^m`Q{&53RiWbCL>tukwGeL=*jI$!*m-X-Kbj#IbZGE|9T3zrxhStWVxae_mmdLFSI0XB@uaO^Xd);ZG}AWNsGBuX00Tr zKPxYm&$-xWP!acn1_gD~#x6j@H@3*MO$ZKgS`R|kmc$M*_}jAAMe{2g82}%9Sny(= z8j+uA_$$tH<+yZnpiO(07{qcBZFj5M02hUx9MvlAgL#>$SyrREK4{;f_yY(qQs;BNH7!Et!mOLgngRUxDbXJK8%6M>OO!DRbbz_mN+%Ebi90Qf`bc< z)k$BHH}VSea26y<#>QHZ3b!=oD`@?f3bogHkZW)cEd=f}Vo5If=SfZ{LW}!f-!JW^ z`iY#Ab|vS@-p`}Qa0AO|d0IH?QiX6HO>iE$M~N$wh4-JK%T=9p9_mFq8g%S0{7qk- zbT&y9Ah#fyL~Sw0D{T4_M3tP58z0mF$v;xz|>;7gp-5pG>jC0Qq|lb|dEG7W(gNEKI>@2R9_>!hwW(!kCe_Y=(Bt!whD^-K^j0Olo;z9D@Gyxz>z@eK|DS&l-gAt$! zY!)Umi6=(VloXL#HNDGECd6-{`3zYkan~G>v9L(rD(I@svssn!;cSGlIt; zD2?NVWWXBkEnM~y0w2Bqcuai1bvn=pi|4#&acJR4@2iagGF6R4KY1eHMFNVrgA`7t z(8&;?OTzq}DEG;kz`I?i7`DqFp-<;UHqu_cSJs4}w$sYQ{xB*6Wrjr}^yPnv{1=#b z3DO`gg+~(Y;U1n-N>$&nPe8-9Cok~jkBE0<6gs>@UA+1Y zVO~A;#g?v8OKdTK6~8EHbiYp*Lg zXxSTqIHwv=ev)>SM9l}@{ZyCIT+o+7H8_>pSFWn4T&%f^t4!e6O#zvFMjihow+1Yp z_OPt0WL`j+;xln6!zlL3sH4LF&>6tza=WKz>AA8+xEgLP8qw~+#;L?SO#us8xx8Ek zi_krHOVcbel`lPklZ5y@Rx9V>y(%`M8*g5D-oEV8frFJ2{#<#u%tRK;K?}0f-2~nh zowzLPyb#LdR+<&b;Pl{{>N9r0mqq`3&>6-qqpTrdtIOK)AcetG5pX0OPP&3m(M7T9 zNUgH?OuUkroJ?(sRYd^0_aPIlI_k6l)?ucgO`0v7A@qDAI|W)>O(qHfp*5Bg-^!I( zc|^e5QCPF+hCn$%zdTFHMeq{{A~FDwTZAjVM|pTV1F0C&vG;g-FYeqEQ-Lu67h37Q z*J%d~L>wR?b4GW3+?}c7;c%t!M};FPi@_-^VSH0ei#t=d%S|)8TScPxbmQ;JEALwF z_%i?=CxndjAgr+<9EtxTXRY7tetPH35cp=H!No5jVTmG>pt2jt=o(jWAMi&32+KZp zupg7Zy=l+vVmA!OPU^9Wg z{)kVpOWMRdym$ef2UyQklmY-Vy1%_q24vyb#3eVu5i>+C$PL-jZ?d;pH)D@5Ax{lUauDeMH6}l0pkyPQ3nhX-cFGlB>#sI63k4ctW|BAsFoss$5$}Bcd zjcVZ>wSElmTnLhPQaDzl@X|zf_&PbKw2uQs3=MPJSn)fjddP)JD;EBPIIP%TMp|28 z(sbSyaihyn%C-KGUm^L4VK5!J#_EGFWB2R^+67*esvKBevbfEX$~P-hQ?HFgX15j4 zhgfvcxW+zzNBPO&`WHL%)ByvH8diWcKVyqTnBw0v7v)(b_kK7!r+~Qfuy;?34+g_1 z9gsFxrbHLrvbQM9FPvCq`An2ttr)a9p@o&=&*kf<&kQb~mEm%_GFe&$AT=A;nkJqB z`CtZ!B5-AI7UB^hGC|XT(MBVo$cVYSTGd7kcz4GY1N%_vadmiiJ+lcQj!?iMCmkQ} zC<_q-dI6amyazaJOV+7AqA-O6zjyBjDm4LCr_khL4?+qfJM2;FYKL+H9P(b-7N1*P zCH|6@gG=4YP*o&p6}J?O+>UUClEGo5iPo3DxeV`xek$^``f%*!qlnHZ>ktmSj-M|U zT^VR4+?v+;*egpgy!nFoygB;3u_Lry5O%+(2;hkQIPQVB2L!a&y|{ro6Fn3592lz1 z`-RJ2Z8r#!r2n}F+&|>|hcqYz0p?OcaPR}%lkt)(ukgIYjG?AJ7Udy)Vjvhfmme1P zg+HS&dh_OW_V)Fg*91WJK@>WuRm<|CNd@4mS6G4cE$`Zz6)dEZtFm2AaVGY#O*F!R zXJ)`?`%qJS`yuucBD=tbJo!T#;OoqmDBY7I~`nvd&s6 zq#a8adt%tBnVky_Wpa;7b2(?thyNB~(YNWVE#kxT$8G@;lSp;12kstZG4xr@!&||7 zk$x7eo23@W%RYTv=-rnkJjoNF7g?IoS?BA8Z*CuGm4GoU&AbDS(6`Bj_U8;YEw+W& z%FQZT;PTu?ewjV9CY?Puu(Ap^U&Q|=shfQM7h#VaPE2}g&Yd8QKXZz5Ol=R zSew#szG#iezv5hn& zClq7&IJq4p0Mu;nlu(CDYpl0E)za9J!K1-2?jU+`u5makM7ORmI3nYCb3f!dSqtLn zB7Cr}q-+KV0=Y&Y!r)qmQ38tkve;<(`^XwECW2Or2nkUV1`?v~lc~N}BuA*4} zp?U_$;!kl%yDk|d#(-VZo9q%IAKgr72}DSZc4=n=RrbFWhj>?P4V-tuEvvt0@I=M? zKEEV9!V+sqEgYzTeBw;-*RGWehG$>F!sGI1)PM{E!3+?U-P^Z6y?On*pQCoM14(gi zCIb3GPxdeX#LO^zV}~cq>nhRX8v4@Tgp-sUrKlSL1qS37ai3*t<(woETu6gqGd%a6 zLrS*B`-v)e$^^zb(tU+mwiTjDJ_m}S_aLu@PY1_T;|YR2F{?&2=iv}tA6S0|)aZy^ zGZyxy>xh6vG0ym-@V)W;Kg&V~vQ2jK0H(F*i6@n5O*n+XTLyJh+Y6HZ8f+&GtLu9)9?ZHpS)@_RSFNM;Dy>V$`>JY3Jsn z1~e6S0oYM_(!nBcUGY_dJo_RPSrBF<^AHb4|DPrZH1-25jI`>Zi_Bj2>T1h+rJOd> zs2yM*jkSY_X%M5_A}l(Df7*9g@DWR|rYLJcpcWp+OKvh~zYov>22$J$H+(0;J^LFG0Kvu?qzv^d5?;XdgHsK9bKFb79!Sy-6uGAr0*b)99(@kj0%OlY0N*HJ zZkP%@wZ9{^yMjF$B@Bk93eq!Gb)R|Aj|dC7zZ%?&HJuvZFU7z|nIHna|NU>H-S4~3 z9{)%f=i}4_3*+Pnqw)_!KvsVb&yjc0*A2WDg@*pC&8QSbl`1K}B%~ z=q@ZPoDp1qkg-u!83nZvj?^t1f?(fKdF!(E%&(%FRL|7RT4P5I`@Bu)RrqvUE*)@D zl=kl;0CJg}3nbC*gIFhi6=KF14;&0xn>}$9dscs|^ zmQg_hKfZyv1QMq3PqV;fZUY)+YS6KzHOr?C4yxGDWC6e79!t zCSb*Xwn}5Yr~!#llW3Nu6j^ET$IDd?OsEU%JJ@vFI~v0_(3oxK_fFE|iK0MoGhs>U z_;Xg9C>Lver}A;e3Trr2BvCjK$Y2UkAqE`-!(qI~%5N+H91#Quo5%MH?Se_XJLOOf zQahBL zDVTg^b>_nb9bFWH?pP0DAv1m#U=LpL-Yz&rlxfW!$k07D(Ifm$3*1Ryp3Xm1f*j*5 zu>u}wBRozsKLr4L2~2YYJO0Hwm>b`rUIASCtsnm+2L3Yu3h{P_)$i}SKaB!+jsZCw zROs!(9a_fG&c^(t(_H@%|IjLn>bzA6_*~9_u@>0}N197vj`Zi}`2{rC^%HFiTB&>I zw2@i9cu9{tuQbsE|8M~hz*a@dxjo{{3A?zE2?8dB_{j1(xgy-Q%I027S?@lvAW^$q z$>EPKG5>s~1*{CApPDMjeaZVk1)s%i-SCglqegdIP3u*eB%jXi>VzCm#!T@WPE+KU zyq>`$d{XcIq%}65jC7M@M0#3-ghWg7SM}>nNV(Mc!Mq_YGWzE1(UMDz9{zHg&)Exs zFt~4H92lw&6keP;G`S1FA{4f4o$U_2m3_8@r8GBm$Oq6f*{A9tE}}Nfd17G~ZA#uf z*B004S}B#Q!0a!6quD$=H8(xommGmyABf}n+6YKVZeR{{Dm&#bdUg05x^$` zKx2gM1MtrM1FD~UARuYNcU-S743-d-jL{7D(3Hy@fthj|N6to04CcBc4ri3Oy^HmW z_9%l0dc(3}8Xhs}aLrP1VAdd8-yx!sf|*E>hYd`XrMXxz2pt+Z`oQ!YBV!la)?#1KY; zA2Q1#s>F7qZdU8fk`8~MLCb}iJ!p&rYtQ<^z|`tANO`Aq$Te<)?1u}hcS+_)Mn7y& z8k^nQ0SVI`v#>;oi5-Zw$T&&mUF8IeaDHLe+@$24%+G4IVxs9fLUZ2OI6CJgRJ%D4 zh-_%KhxzegseV}ARidV_{p=#b+rU5mJ#tP?iErE;;Ybkzt!h4vTjihcGvFLI-kdD$ zKqVZKD%TaL)Ev1?U)!S7sTcxFlX>D^0tU8n}`I55rpF@Q7F4d-(Q`-CrK|^1j+9M)Y2!Xu_dGGPMWM$Ib&l zR)B$k(uV{Q#wVgeQGD1BZvlYVHC)Q`g>@io0{@d938*Am&G03xLY;I|&q;w+6P!;# ziKTavNrET<$rnU3NsmA=Un)Ptcx>$S^!paa92qn#~Q>=Gf{X}Y3X6BI|#Bk z)C&236)q^={D^3$a!v>+Fbd~{r6H>GG|g!&aoEik0!vzn@nxrx%QUf#A2P~TB?xOW zE}NE-NbCx*VIp0dE|Z*gZyX>!~~Efh{J{2Ti~ zWZm#BSNLOWzQjL4;IID<08GvA@4LRw+|BwR%FE8^q7jQ!O`U8ybzx(dz zR}CEz+GpR*zk9fR^M>0=&%Lq59CTLI&PJ{NrPJNqRM& zY_dS$+^(eXy$Q4f3T?xAWg8w;TNYE2V1XPy-hln3;#1TZZSW)r1LlK zG@+HRj^aAe&6{PP(=J7M!2_TQ1jNyhe)qU%90ksFvh0;>r(-%bb6Q&<44UvrmIVMO zQu=PWeW=avqXhx0C`!i0J&yzR#$|}&b06PRi+d{K@%@5P;p2})OIUx+u8n_qXJLuh zjSt(l~U~R}{Aaz%aL4kZ(PR{5Y?F(Y*4jvBbrAt&m5; z*`(Iqn8pZ5M`r_!n{j{=pzey!He+tdX^4e8O$fwx1g-qnFqsCNePjmuK#LDR*DwSi z3d2N998=P*dHZ}SRout*$7Bcnm`KxyIpF6`4?;CauhW1W4FbOy0q)%x@AkV;fcTpS zeO>IMK^E}^L78Z0nF{g(D_>0Tp6%xQ9qPZW#(^vy(-1JV#{b|V1Zg4gu}AgRe@o)u z3yF0Z7XrrMk9huOOKwHfYGLvd{_Rq~-6$sMTo8DX*{Fp4it0w8=WsJ!v?Ne$Z67$@1T2`gkn7{t6E>8N3NEDQfW)Lntt zHenx=uGu~@Jk8jn23rm$mUQJFa7loYF6d8!t~TmHp+*@S*%oO}t-hu^V6MRQTrU%y z7S|z{O)F=xZKJV+i@-*%0BHep(?;!wFX!9FL7Moch|W01dqvUtRuP5~o@AyUF{%tu zW2@gSMgWR=n()bn^cy)bXZneE5MtaNxAVbsaYRz?2DugXQdM(MdZam@7<&?zgr-Ka zHjES+2~7I>gOw2yyo&rv&+Vw=SWU`geih3QE;nkU*~P_A*?*8nm|4T<&_5Jzs}um7 z%F2T~%y2}diD!;8L13*oHnhiRkQo!gaiFZCDR-MuwOh;Z^z@EfVCHdL+v)U{i5fN& z0IUH3ZzUo_QN=#^{{83A5}w^DUhN(^ksnzmo;hPqlofsqwYkNfnYVN%YRtC^9-($` zFm*sM9HnnhqYuWmmaQ+FS_ODOGBVJL=1ykLJw}XQXewjK%DT&Y%9O=-V3x|DqRuNT(*Th`7(s|BHsFAdsOqp5te8Lf{@y z=;a47Z=WFWZ~K3|UW)LtEc1nVk6ZlaU2l`c%fR+_Ycjl;)bO@bYL+nu#&cP;)_;WPYeA;u$ z#XB0i4?Wjp_<)A^CJ@nSK;Hkxej)~dBtYl6rNHvURt?B~EDn&y2>>CdnLBE38!r<4 zbmJP)izzLd=SmnQ0E%pwryjUCrUEKKlbhXhFpg029vk|l7!)F?FlnM$9KeDZ0uyO6 zR7!T71{lO3VHpp^X1qtHP$jmSZVyXn#lWEFsOa7ibn&WE{N|MK4vIX z8_533DZ=KLNRP`k$Zzm%K4J2j4-CRQy*26pa<13|YX>VZN-GjU5*N|EA;c&IK#lCc zibgG{t!{6O&ids0ufO>oM4ah>Zh<4B7zG_t>@KL+rD46fdm0e}0vT-{>AoCPN`azy zU^l?r{VEL!zNe~OIM@r&GY^zgFuew zczFKf&#VIHSa0keKF#Ml@LYI4LEw@I_&53`Bpk$|5|qG}1kf4@mq`AYbH*nc%q6T6 z*#5q{k%fIcCACA?!pUGOVH-@VA_39fe-RxnlzU3MTjHY$aoZ-02b$!~%p>_7V3n#> z2)TU1Mka}PB1l+ZZMcmAUmaCj{ek$Ur$J4&-^%46IyiDUO!Z@zb1iO+%xB;^-T%-R zp(eH1im$5!$V#!DT{PhYV}||kwK@)C>J*M{Ohnt82OuadSdP%G>egL^xsCYr6QR3X0A%aC(j>&?sA?uJ8=2E3qRk&Dd3$L6dcUxwPvy-c# zo83v7Tih1Sa+8OBm9dFN^koOARUDOO)QH?Si7GQo;YE#a+w#b?2;t))nMZfbpn%gV zdeUQ?)l$LdhC=>V$bV64WkS0S_Kpr0Wvoxi#HlGQmvf(t1+PHvPyzy0p}qL}guS7! ziko3d&xnn~9-}U=r&Ig(O@(~SMly+yT;yTe1lOlMRdTStr^o%RT>nm0N?p-{Z#=$x zPYAS`DPfB%62=cPNd$lgwu!aC>k%0;@6MCrTPUOB{rk>{ZbA?X>F`XK zzPbk{4v2rM0M|zaAmc*tS-WolAhsrJxnWa7x9QvuHk)XJJ38R6o5%^-9JIh;cNI|g z>DUF~%fr76bIB9ITVPEBx7z&%06xD|Ixwbyzpy9-&2PW6FP7xN#=U$m)cl*?XhXzZ z>8tHO8Pm;1YaSWGkR~v)@=5l6%JvN}zq#D}AnO1C(iQ1K%a1H=d*z}0lo&1bDoABs zc-Y#RS~vlptPq}rdo+M~68`xhM;AeX4FuW#_WK0Q8;7IQi(j5{jXd#TSOluXN-B;O zxq$>g=|D_1G_tZcRLZ6#DOIdjTx}MedXJiqH|3Rbk1CGmEGN0SiBBD1NZ%&X zpO6pHNbFSScEVy49E)I8Z|7nP$v{?Kt1JMEeS?=SetnY~U?ZTuyYVDY>O+yO+fd}W zB11pgT2?}e@ws?N0niDyx=;=^?d=ig*%nmCz;tAWugfKwuK7UTQt(?F!)O{B0H~2+ z8xq1OPfJN^fPd90ZgCX?xRhX&>N)%^X=Pf@I=>b-wJXQ5m8Y?;RqB$Vy)9KZX+iURx{kr%z_$4^K?S_g7VByuYBnQ!QOB`FWeLa`Am}^jenBR@3&SlS z=5S%@2y}lRKMqyMaij+;R&%M>R@!y=_ZVD2)1>*kjgba0uocXyR>WPAw@JB}{P-Vy z_jlvrquDV%L){;rzJR>$Yo(y4lJ8%KX7`uW`GOGmY?r7qafnRJIrqIg7Jz!|wjoDN za7+R5kvEb7p{|<;4MUP(nx&eN_GAovqL1^|?tMPI;^tJcc1&ZK+~MlT)_zZpx@;^8 zu&yE|fI4Qg>tS9p#D60CB>=4L5@QH_N3W$vAb%jVzV6+kM=YWWkyMrp(Q} zi|KWN=N8wKOTI@Uir#@R;96YHb1B#=v{e|?!|m039d#m++_4*ma|BL5;2 zq*jDmC*oa25D0i92QM59Y$I}2mpbApYH^KKG4$s zDs6*BsvBqmh!%O+Q*@?->3A*tX>SxZTcmO8>+ty#o(=>x>u`(-WlCZO`Uc1JvKfCB z2smaC5;M_Jok~HH*2^MKvr~ue4ewfDpsQu<$9kOZ`+{$a_3#S-3>yS{CIlf+x{<}* sdi__V=f__kfBp6Eo4@1pCb{DOA9z+dNAAEWkpKVy07*qoM6N<$g1T?2;s5{u literal 0 HcmV?d00001 From 69ed7ab7829e470c089806955e59d0cb2697d7df Mon Sep 17 00:00:00 2001 From: Prashanth Ramadoss Date: Sun, 29 Nov 2020 15:35:41 +0100 Subject: [PATCH 3/8] Update README and CHANGELOG --- CHANGELOG.md | 1 + README.md | 1 + 2 files changed, 2 insertions(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index 0c8ecc2a29..5024b1d6c1 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -18,6 +18,7 @@ All notable changes to this project are documented in this file. - Implement LinearizedFrictionCone class (https://github.com/dic-iit/bipedal-locomotion-framework/pull/244) - Added a check on whether the installed public headers have the correct folder structure (https://github.com/dic-iit/bipedal-locomotion-framework/pull/247) - Implement python bindings for VariablesHandler class (https://github.com/dic-iit/bipedal-locomotion-framework/pull/234) +- Implement `PerceptionFeatures` library and implement `ArucoDetector`. (https://github.com/dic-iit/bipedal-locomotion-framework/pull/159) ### Changed - Move all the Contacts related classes in Contacts component (https://github.com/dic-iit/bipedal-locomotion-framework/pull/204) diff --git a/README.md b/README.md index 2edb40d632..fc29154094 100644 --- a/README.md +++ b/README.md @@ -64,6 +64,7 @@ The **bipedal-locomotion-framework** project consists of several components. The | [YarpUtilities](./src/YarpUtilities) | Utilities library for retrieving data and from YARP structures | [`YARP`](https://www.yarp.it/git-master/) | | [PerceptionInterface](./src/RobotInterface) | Generic interface classes to adapt to perception data formats like images and point clouds | [`OpenCV`](https://github.com/opencv/opencv) [`PCL`](https://github.com/PointCloudLibrary/pcl) | | [PerceptionCapture](./src/Perception) | Library containing driver classes for perception devices | [`OpenCV`](https://github.com/opencv/opencv) [`PCL`](https://github.com/PointCloudLibrary/pcl) [`realsense2`](https://github.com/IntelRealSense/librealsense) | +| [PerceptionFeatures](./src/Perception) | Library containing perception algorithms useful for locomotion | [`OpenCV`](https://github.com/opencv/opencv) | # :hammer: Build the suite From 71b4d6bb2afcb55c12d4d185497c13b4867782c2 Mon Sep 17 00:00:00 2001 From: Prashanth Ramadoss Date: Sun, 29 Nov 2020 16:04:11 +0100 Subject: [PATCH 4/8] [Perception] remove support for AprilTag to fix ci compilation --- .../Perception/Features/ArucoDetector.h | 3 +-- src/Perception/src/ArucoDetector.cpp | 9 ++------- 2 files changed, 3 insertions(+), 9 deletions(-) diff --git a/src/Perception/include/BipedalLocomotion/Perception/Features/ArucoDetector.h b/src/Perception/include/BipedalLocomotion/Perception/Features/ArucoDetector.h index 112a807bb1..7083fe6861 100644 --- a/src/Perception/include/BipedalLocomotion/Perception/Features/ArucoDetector.h +++ b/src/Perception/include/BipedalLocomotion/Perception/Features/ArucoDetector.h @@ -73,8 +73,7 @@ class ArucoDetector : public System::Advanceable * "5X5_50", "5X5_100", "5X5_250", "5X5_1000", * "6X6_50", "6X6_100", "6X6_250", "6X6_1000", * "7X7_50", "7X7_100", "7X7_250", "7X7_1000", - * "ARUCO_ORIGINAL", - * "APRILTAG_16h5", "APRILTAG_25h9", "APRILTAG_36h10","APRILTAG_36h11") + * "ARUCO_ORIGINAL") * options coherent with https://docs.opencv.org/master/d9/d6a/group__aruco.html#gac84398a9ed9dd01306592dd616c2c975 * - "marker_length" marker length in m * - "camera_matrix" 9d vector representing the camera calbration matrix in row major order diff --git a/src/Perception/src/ArucoDetector.cpp b/src/Perception/src/ArucoDetector.cpp index 78fb7d2a7d..3dd6a093ff 100644 --- a/src/Perception/src/ArucoDetector.cpp +++ b/src/Perception/src/ArucoDetector.cpp @@ -66,11 +66,7 @@ class ArucoDetector::Impl {"7X7_100", cv::aruco::PREDEFINED_DICTIONARY_NAME::DICT_7X7_100}, {"7X7_250", cv::aruco::PREDEFINED_DICTIONARY_NAME::DICT_7X7_250}, {"7X7_1000",cv::aruco::PREDEFINED_DICTIONARY_NAME::DICT_7X7_1000}, - {"ARUCO_ORIGINAL",cv::aruco::PREDEFINED_DICTIONARY_NAME::DICT_ARUCO_ORIGINAL}, - {"APRILTAG_16h5", cv::aruco::PREDEFINED_DICTIONARY_NAME::DICT_APRILTAG_16h5}, - {"APRILTAG_25h9", cv::aruco::PREDEFINED_DICTIONARY_NAME::DICT_APRILTAG_25h9}, - {"APRILTAG_36h10",cv::aruco::PREDEFINED_DICTIONARY_NAME::DICT_APRILTAG_36h10}, - {"APRILTAG_36h11", cv::aruco::PREDEFINED_DICTIONARY_NAME::DICT_APRILTAG_36h11} }; + {"ARUCO_ORIGINAL",cv::aruco::PREDEFINED_DICTIONARY_NAME::DICT_ARUCO_ORIGINAL} }; }; ArucoDetector::ArucoDetector() : @@ -109,8 +105,7 @@ bool ArucoDetector::initialize(std::weak_ptr handler) << "\"6X6_50\", \"6X6_100\", \"6X6_250\", \"6X6_1000\", \n" << "\"7X7_50\", \"7X7_100\", \"7X7_250\", \"7X7_1000\", \n" << " \"ARUCO_ORIGINAL\", \n" - << " \"APRILTAG_16h5\", \"APRILTAG_25h9\", \"APRILTAG_36h10\",\"APRILTAG_36h11\". \n" - << "options coherent with https://docs.opencv.org/master/d9/d6a/group__aruco.html#gac84398a9ed9dd01306592dd616c2c975" + << "options coherent with v3.4.0 in https://docs.opencv.org/3.4.1/d9/d6a/group__aruco.html" << std::endl; return false; } From c34bf0ae807fe512a51392d1864d7ff13ef3bd57 Mon Sep 17 00:00:00 2001 From: Prashanth Date: Fri, 12 Mar 2021 16:26:31 +0100 Subject: [PATCH 5/8] Add valgrind suppression opencv ubuntu20.04 --- cmake/valgrind-linux.supp | 48 +++++++++++++++++++++++++++++++++++++++ 1 file changed, 48 insertions(+) diff --git a/cmake/valgrind-linux.supp b/cmake/valgrind-linux.supp index 5bc9dd2890..4f68d7e7af 100644 --- a/cmake/valgrind-linux.supp +++ b/cmake/valgrind-linux.supp @@ -37,3 +37,51 @@ fun:_dl_open fun:dlopen_doit } + +{ + + Memcheck:Leak + fun:malloc + fun:_ZN3tbb8internal23allocate_via_handler_v3Em +} + +{ + + Memcheck:Leak + match-leak-kinds: possible + fun:calloc + fun:allocate_dtv + fun:_dl_allocate_tls + fun:allocate_stack + fun:pthread_create@@GLIBC_2.2.5 + fun:_ZN2cv12WorkerThreadC1ERNS_10ThreadPoolEj + fun:_ZN2cv10ThreadPool12reconfigure_Ej + fun:_ZN2cv21parallel_for_pthreadsERKNS_5RangeERKNS_16ParallelLoopBodyEd + fun:_ZN2cv13parallel_for_ERKNS_5RangeERKNS_16ParallelLoopBodyEd + fun:_ZN2cv3hal8opt_AVX212cvtBGRtoGrayEPKhmPhmiiiib + fun:_ZN2cv3hal12cvtBGRtoGrayEPKhmPhmiiiib + fun:_ZN2cv16cvtColorBGR2GrayERKNS_11_InputArrayERKNS_12_OutputArrayEb + fun:_ZN2cv8cvtColorERKNS_11_InputArrayERKNS_12_OutputArrayEii + fun:_ZN2cv5arucoL14_convertToGreyERKNS_11_InputArrayERKNS_12_OutputArrayE +} + +{ + + Memcheck:Leak + match-leak-kinds: possible + fun:calloc + fun:allocate_dtv + fun:_dl_allocate_tls + fun:allocate_stack + fun:pthread_create@@GLIBC_2.2.5 + obj:/usr/lib/x86_64-linux-gnu/libtbb.so.2 + obj:/usr/lib/x86_64-linux-gnu/libtbb.so.2 + obj:/usr/lib/x86_64-linux-gnu/libopencv_core.so.4.2.0 + obj:/usr/lib/x86_64-linux-gnu/libtbb.so.2 + obj:/usr/lib/x86_64-linux-gnu/libtbb.so.2 + obj:/usr/lib/x86_64-linux-gnu/libtbb.so.2 + obj:/usr/lib/x86_64-linux-gnu/libopencv_core.so.4.2.0 + obj:/usr/lib/x86_64-linux-gnu/libopencv_core.so.4.2.0 + fun:_ZNK3tbb10interface78internal15task_arena_base16internal_executeERNS1_13delegate_baseE +} + From 482ceed3a04e496244ec078f26ba56f1d5ba9928 Mon Sep 17 00:00:00 2001 From: Prashanth Date: Tue, 23 Mar 2021 12:27:08 +0100 Subject: [PATCH 6/8] [cmake] add gen-suppressions to unit test valgrind command --- cmake/AddBipedalLocomotionUnitTest.cmake | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cmake/AddBipedalLocomotionUnitTest.cmake b/cmake/AddBipedalLocomotionUnitTest.cmake index 5e4fc2e937..7f21c678fe 100644 --- a/cmake/AddBipedalLocomotionUnitTest.cmake +++ b/cmake/AddBipedalLocomotionUnitTest.cmake @@ -15,7 +15,7 @@ if (FRAMEWORK_RUN_Valgrind_tests) else () set(MEMORYCHECK_SUPPRESSIONS "") endif () - set(MEMORYCHECK_COMMAND_OPTIONS "--leak-check=full --error-exitcode=1 ${MEMORYCHECK_SUPPRESSIONS}" CACHE STRING "Options to pass to the memory checker") + set(MEMORYCHECK_COMMAND_OPTIONS "--leak-check=full --gen-suppressions=all --error-exitcode=1 ${MEMORYCHECK_SUPPRESSIONS}" CACHE STRING "Options to pass to the memory checker") mark_as_advanced(MEMORYCHECK_COMMAND_OPTIONS) set(MEMCHECK_COMMAND_COMPLETE "${MEMORYCHECK_COMMAND} ${MEMORYCHECK_COMMAND_OPTIONS}") separate_arguments(MEMCHECK_COMMAND_COMPLETE) From c552e59fba02dc750bb50d05ccb51e7c083bed33 Mon Sep 17 00:00:00 2001 From: Prashanth Date: Tue, 23 Mar 2021 11:00:03 +0100 Subject: [PATCH 7/8] [Perception] avoid memcpy in ArucoDetector and fix docs --- .../Perception/Features/ArucoDetector.h | 10 +++++---- src/Perception/src/ArucoDetector.cpp | 21 +++++++++---------- .../Perception/Features/ArucoDetectorTest.cpp | 9 +++++--- 3 files changed, 22 insertions(+), 18 deletions(-) diff --git a/src/Perception/include/BipedalLocomotion/Perception/Features/ArucoDetector.h b/src/Perception/include/BipedalLocomotion/Perception/Features/ArucoDetector.h index 7083fe6861..d2e479f7f4 100644 --- a/src/Perception/include/BipedalLocomotion/Perception/Features/ArucoDetector.h +++ b/src/Perception/include/BipedalLocomotion/Perception/Features/ArucoDetector.h @@ -85,9 +85,11 @@ class ArucoDetector : public System::Advanceable bool initialize(std::weak_ptr handler); /** - * Set image for which markers need to be detecte + * Set image for which markers need to be detected * @param[in] inputImg image as OpenCV mat * @param[in] timeNow current time in chosen time units + * it is useful for bookkeeping + * or time delay synchronization * @return True in case of success, false otherwise */ bool setImage(const cv::Mat& inputImg, double timeNow); @@ -119,9 +121,9 @@ class ArucoDetector : public System::Advanceable * @param[in] axisLengthForDrawing axis length for drawing the frame axes, 0.1 by default * @return True in case of success, false if no marker was detected */ - bool getImgWithDetectedMarkers(cv::Mat& outputImg, - const bool& drawFrames = false, - const double& axisLengthForDrawing = 0.1); + bool getImageWithDetectedMarkers(cv::Mat& outputImg, + const bool& drawFrames = false, + const double& axisLengthForDrawing = 0.1); /** * Determines the validity of the object retrieved with get() diff --git a/src/Perception/src/ArucoDetector.cpp b/src/Perception/src/ArucoDetector.cpp index 3dd6a093ff..0760994b21 100644 --- a/src/Perception/src/ArucoDetector.cpp +++ b/src/Perception/src/ArucoDetector.cpp @@ -120,9 +120,8 @@ bool ArucoDetector::initialize(std::weak_ptr handler) return false; } - std::vector calibVec; - if (!handle->getParameter("camera_matrix", - GenericContainer::make_vector(calibVec, GenericContainer::VectorResizeMode::Resizable))) + Eigen::Matrix calibVec; + if (!handle->getParameter("camera_matrix", calibVec)) { log()->error("{} " "The parameter handler could not find \" camera_matrix \" in the configuration file.", @@ -130,12 +129,12 @@ bool ArucoDetector::initialize(std::weak_ptr handler) return false; } + Eigen::Matrix3d calibMat = Eigen::Map< Eigen::Matrix >(calibVec.data()); m_pimpl->cameraMatrix = cv::Mat(3, 3, CV_64F); - std::memcpy(m_pimpl->cameraMatrix.data, calibVec.data(), calibVec.size()*sizeof(double)); + cv::eigen2cv(calibMat, m_pimpl->cameraMatrix); - std::vector distCoeffVec; - if (!handle->getParameter("distortion_coefficients", - GenericContainer::make_vector(distCoeffVec, GenericContainer::VectorResizeMode::Resizable))) + Eigen::Matrix distCoeffVec; + if (!handle->getParameter("distortion_coefficients", distCoeffVec)) { log()->error("{} " "The parameter handler could not find \" distortion_coefficients \" in the configuration file.", @@ -144,7 +143,7 @@ bool ArucoDetector::initialize(std::weak_ptr handler) } m_pimpl->distCoeff = cv::Mat(5, 1, CV_64F); - std::memcpy(m_pimpl->distCoeff.data, distCoeffVec.data(), distCoeffVec.size()*sizeof(double)); + cv::eigen2cv(distCoeffVec, m_pimpl->distCoeff); m_pimpl->initialized = true; return true; @@ -250,9 +249,9 @@ bool ArucoDetector::getDetectedMarkerData(const int& id, ArucoMarkerData& marker } -bool ArucoDetector::getImgWithDetectedMarkers(cv::Mat& outputImg, - const bool& drawFrames, - const double& axisLengthForDrawing) +bool ArucoDetector::getImageWithDetectedMarkers(cv::Mat& outputImg, + const bool& drawFrames, + const double& axisLengthForDrawing) { std::size_t nrDetectedMarkers = m_pimpl->currentDetectedMarkerIds.size(); if (m_pimpl->currentImg.empty() || nrDetectedMarkers <= 0) diff --git a/src/Perception/tests/Perception/Features/ArucoDetectorTest.cpp b/src/Perception/tests/Perception/Features/ArucoDetectorTest.cpp index dd463e7739..ab93ad6fb0 100644 --- a/src/Perception/tests/Perception/Features/ArucoDetectorTest.cpp +++ b/src/Perception/tests/Perception/Features/ArucoDetectorTest.cpp @@ -36,15 +36,18 @@ TEST_CASE("Aruco Detector") REQUIRE(detector.advance()); cv::Mat outputImage; - REQUIRE(detector.getImgWithDetectedMarkers(outputImage, /*drawFrames=*/ true, /*axisLengthForDrawing=*/ 0.3)); + REQUIRE(detector.getImageWithDetectedMarkers(outputImage, + /*drawFrames=*/ true, + /*axisLengthForDrawing=*/ 0.3)); // Marker 2 is detected in the sample image ArucoMarkerData marker2; REQUIRE(detector.getDetectedMarkerData(/*id=*/ 2, marker2)); REQUIRE(marker2.id == 2); - /* // uncomment this block to view the output image + /* // uncomment this block to view the output image cv::imshow("outputImage", outputImage); cv::waitKey(); - */ + */ + } From 81b92b54e3bfd045dc63b7679120089be2f59b7c Mon Sep 17 00:00:00 2001 From: Prashanth Date: Fri, 26 Mar 2021 17:06:26 +0100 Subject: [PATCH 8/8] [Perception][ArucoDetector] fix debug print --- src/Perception/src/ArucoDetector.cpp | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/src/Perception/src/ArucoDetector.cpp b/src/Perception/src/ArucoDetector.cpp index 0760994b21..7f791adf92 100644 --- a/src/Perception/src/ArucoDetector.cpp +++ b/src/Perception/src/ArucoDetector.cpp @@ -98,15 +98,15 @@ bool ArucoDetector::initialize(std::weak_ptr handler) if (m_pimpl->availableDict.find(dictName) == m_pimpl->availableDict.end()) { - std::cerr << printPrefix - << "Undefined value set to \" marker_dictionary \" in the configuration file. Please choose one among \n" - << "available options: \"4X4_50\", \"4X4_100\", \"4X4_250\", \"4X4_1000\", \n" - << "\"5X5_50\", \"5X5_100\", \"5X5_250\", \"5X5_1000\", \n" - << "\"6X6_50\", \"6X6_100\", \"6X6_250\", \"6X6_1000\", \n" - << "\"7X7_50\", \"7X7_100\", \"7X7_250\", \"7X7_1000\", \n" - << " \"ARUCO_ORIGINAL\", \n" - << "options coherent with v3.4.0 in https://docs.opencv.org/3.4.1/d9/d6a/group__aruco.html" - << std::endl; + log()->error( "{} " + "Undefined value set to \" marker_dictionary \" in the configuration file. Please choose one among \n" + "available options: \"4X4_50\", \"4X4_100\", \"4X4_250\", \"4X4_1000\", \n" + "\"5X5_50\", \"5X5_100\", \"5X5_250\", \"5X5_1000\", \n" + "\"6X6_50\", \"6X6_100\", \"6X6_250\", \"6X6_1000\", \n" + "\"7X7_50\", \"7X7_100\", \"7X7_250\", \"7X7_1000\", \n" + " \"ARUCO_ORIGINAL\", \n" + "options coherent with v3.4.0 in https://docs.opencv.org/3.4.1/d9/d6a/group__aruco.html", + printPrefix); return false; }