From ca37348c7fe6fb3e4fed7fd54c06027a335bac2d Mon Sep 17 00:00:00 2001 From: Mingyu1991 <115005477+Mingyu1991@users.noreply.github.com> Date: Fri, 7 Jul 2023 07:57:00 +0900 Subject: [PATCH] feat(traffic_light_occlusion_predictor): add traffic_light_occlusion_predictor (#4050) * add traffic_light_occlusion_predictor Signed-off-by: Mingyu Li * update README Signed-off-by: Mingyu Li * update occlusion package I/F Signed-off-by: Mingyu Li * revert wrong update of README.md Signed-off-by: Mingyu Li * update perception_utils Signed-off-by: Mingyu Li * add _deg to variables and update README Signed-off-by: Mingyu Li * fix Cmakelists Signed-off-by: Shunsuke Miura --------- Signed-off-by: Mingyu Li Signed-off-by: Shunsuke Miura Co-authored-by: Shunsuke Miura --- common/perception_utils/CMakeLists.txt | 1 + .../perception_utils/prime_synchronizer.hpp | 354 ++++++++++++++++++ .../perception_utils/traffic_light_utils.hpp | 52 +++ common/perception_utils/package.xml | 2 + .../src/traffic_light_utils.cpp | 79 ++++ .../ros/pcl_conversion.hpp | 72 ++++ common/tier4_autoware_utils/package.xml | 1 + .../CMakeLists.txt | 32 ++ .../README.md | 36 ++ ...affic_light_occlusion_predictor.param.yaml | 11 + .../images/occlusion.png | Bin 0 -> 281848 bytes .../nodelet.hpp | 102 +++++ .../occlusion_predictor.hpp | 95 +++++ ...affic_light_occlusion_predictor.launch.xml | 20 + .../package.xml | 36 ++ .../src/nodelet.cpp | 138 +++++++ .../src/occlusion_predictor.cpp | 250 +++++++++++++ 17 files changed, 1281 insertions(+) create mode 100644 common/perception_utils/include/perception_utils/prime_synchronizer.hpp create mode 100644 common/perception_utils/include/perception_utils/traffic_light_utils.hpp create mode 100644 common/perception_utils/src/traffic_light_utils.cpp create mode 100644 common/tier4_autoware_utils/include/tier4_autoware_utils/ros/pcl_conversion.hpp create mode 100644 perception/traffic_light_occlusion_predictor/CMakeLists.txt create mode 100644 perception/traffic_light_occlusion_predictor/README.md create mode 100644 perception/traffic_light_occlusion_predictor/config/traffic_light_occlusion_predictor.param.yaml create mode 100644 perception/traffic_light_occlusion_predictor/images/occlusion.png create mode 100644 perception/traffic_light_occlusion_predictor/include/traffic_light_occlusion_predictor/nodelet.hpp create mode 100644 perception/traffic_light_occlusion_predictor/include/traffic_light_occlusion_predictor/occlusion_predictor.hpp create mode 100644 perception/traffic_light_occlusion_predictor/launch/traffic_light_occlusion_predictor.launch.xml create mode 100644 perception/traffic_light_occlusion_predictor/package.xml create mode 100644 perception/traffic_light_occlusion_predictor/src/nodelet.cpp create mode 100644 perception/traffic_light_occlusion_predictor/src/occlusion_predictor.cpp diff --git a/common/perception_utils/CMakeLists.txt b/common/perception_utils/CMakeLists.txt index 338874a41a3f7..146591c865b5d 100644 --- a/common/perception_utils/CMakeLists.txt +++ b/common/perception_utils/CMakeLists.txt @@ -8,6 +8,7 @@ find_package(Boost REQUIRED) ament_auto_add_library(perception_utils SHARED src/predicted_path_utils.cpp + src/traffic_light_utils.cpp src/conversion.cpp ) diff --git a/common/perception_utils/include/perception_utils/prime_synchronizer.hpp b/common/perception_utils/include/perception_utils/prime_synchronizer.hpp new file mode 100644 index 0000000000000..5af44595b8fb2 --- /dev/null +++ b/common/perception_utils/include/perception_utils/prime_synchronizer.hpp @@ -0,0 +1,354 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +#ifndef PERCEPTION_UTILS__PRIME_SYNCHRONIZER_HPP_ +#define PERCEPTION_UTILS__PRIME_SYNCHRONIZER_HPP_ + +#include + +#include + +#include +#include +#include +#include +#include +#include +#include + +namespace perception_utils +{ + +/** + * @brief This class implemented a multi-topic approximate time synchronizer. + * Different from message_filters::sync::ApproximateTime, this class assumes there's a primary topic + * and more than one secondary topics and the registered callback function will always been called + * for every primary topic message, while for message_filters::sync::ApproximateTime, the callback + * function will be called only when all topics are synchronized. + * + * For every primary topic message M1, when this class receives it, the class would check whether it + * could gather one message of every secondary topic whose timestamp is similar to that of M1. If + * yes, the registered callback function would be called at once with M1 and the gathered messages. + * Otherwise, it would wait for some time. After that, the class would collect secondary messages + * again. For secondary topics that can't find any message with similar timestamp to M1, nullptr + * would be used instead and the registered function would be called. + * + * This class assumes the message types of the primary topic and secondary topics are defined during + * compile-time. It should be noted that the registered callback function is too slow, it would + * block the thread and the primary message couldn't be received. + * + * @tparam PrimeMsgT Primary topic message type + * @tparam SecondaryMsgT Secondary topic message types + */ +template +class PrimeSynchronizer +{ + typedef double StampT; + +public: + /** + * @brief Construct a new Prime Synchronizer object + * + * @param node_ptr node handler pointer + * @param topics topic vector. topics[0] corresponds to primary topic and the others + * correspond to secondary topics + * @param qos qos vector. configured for every topic + * @param callback registered callback function, would be called when the messages are + * synchronized + * @param max_delay_t maximum timestamp different (seconds) between primary topic message and + * any other secondary topic message + * @param max_wait_t maximum wait time (seconds) before the messages are synchronized + */ + PrimeSynchronizer( + rclcpp::Node * node_ptr, const std::vector & topics, + const std::vector & qos, + std::function + callback, + StampT max_delay_t = 0.2, StampT max_wait_t = 0.1) + : node_ptr_(node_ptr), callback_(callback), max_delay_t_(max_delay_t), max_wait_t_(max_wait_t) + { + assert((topics.size() == sizeof...(SecondaryMsgT) + 1) && "Incorrect topic number"); + assert(topics.size() == qos.size() && "topic size not equal to qos size!"); + prime_subscriber_ = node_ptr_->create_subscription( + topics[0], qos[0], std::bind(&PrimeSynchronizer::primeCallback, this, std::placeholders::_1)); + initSecondaryListener( + std::vector(topics.begin() + 1, topics.end()), + std::vector(qos.begin() + 1, qos.end())); + std::chrono::nanoseconds wait_duration(static_cast(1e9 * max_wait_t)); + timer_ = rclcpp::create_timer( + node_ptr_, node_ptr_->get_clock(), wait_duration, + std::bind(&PrimeSynchronizer::timerCallback, this)); + timer_->cancel(); + } + +private: + /** + * @brief initialize the secondary topic subscribers. + * Have to use template recursion method to indexing the subscriber tuple + * + * @tparam Idx secondary subscriber tuple index + * @param topics topics vector + * @param qos qos vector + */ + template + void initSecondaryListener( + const std::vector & topics, const std::vector & qos) + { + if constexpr (Idx < sizeof...(SecondaryMsgT)) { + typedef std::tuple_element_t> type; + std::get(sec_subscriber_) = node_ptr_->create_subscription( + topics[Idx], qos[Idx], + std::bind(&PrimeSynchronizer::secondaryCallback, this, std::placeholders::_1)); + initSecondaryListener(topics, qos); + } + } + + /** + * @brief Collect the Idx-th secondary messages with similar timestamp to prime message, + * which is stored in argv[0] and write to argv[Idx + 1] + * + * @tparam Idx secondary subscriber tuple index + * @param argv output tuple + */ + template + void collectSecondaryMsg( + std::tuple & + argv) + { + if constexpr (Idx < sizeof...(SecondaryMsgT)) { + /* + if can't find any message for this topic, write nullptr + */ + if (std::get(sec_messages_).empty()) { + std::get(argv) = nullptr; + } else { + StampT prime_stamp = convertStampFormat(std::get<0>(argv)->header.stamp); + StampT min_delay = std::numeric_limits::max(); + auto best_sec_msg = std::get(sec_messages_).begin()->second; + /* + find the message with closest timestamp to primary message + */ + for (const auto & sec_msg_p : std::get(sec_messages_)) { + StampT delay = std::abs(prime_stamp - sec_msg_p.first); + if (delay < min_delay) { + min_delay = delay; + best_sec_msg = sec_msg_p.second; + } + } + std::get(argv) = min_delay < max_delay_t_ ? best_sec_msg : nullptr; + } + collectSecondaryMsg(argv); + } + } + + /** + * @brief check if all messages in argv are valid (not equal to nullptr) + * + * @tparam Idx + * @param argv + * @return true All messages are not nullptr + * @return false At least one message in the tuplc is nullptr + */ + template + bool isArgvValid( + const std::tuple< + typename PrimeMsgT::ConstSharedPtr, typename SecondaryMsgT::ConstSharedPtr...> & argv) + { + if constexpr (Idx < sizeof...(SecondaryMsgT) + 1) { + return (std::get(argv) != nullptr) && isArgvValid(argv); + } + return true; + } + + inline StampT convertStampFormat(const std_msgs::msg::Header::_stamp_type & stamp) + { + return rclcpp::Time(stamp).seconds(); + } + + /** + * @brief callback function when primary message is received + * + * @param msg + */ + void primeCallback(const typename PrimeMsgT::ConstSharedPtr msg) + { + prime_cnt++; + timer_->cancel(); + assert(prime_messages_.size() <= 1); + /* + if there are old prime messages waiting for synchronization with secondary messages, + stop waiting and call the registered callback function with prime message and synchronized + secondary messages. For secondary topics that are not synchronized, use nullptr. + */ + for (auto & p : prime_messages_) { + tryCallback(p.first, true); + } + prime_messages_.clear(); + /* + update the prime messages + */ + StampT stamp = convertStampFormat(msg->header.stamp); + prime_messages_.insert(std::make_pair(stamp, msg)); + /* + check if secondary messages are all ready to synchronize with prime message. + If yes, process it immediately + */ + if (tryCallback(stamp, false)) { + prime_messages_.clear(); + } else { + timer_->reset(); + } + // RCLCPP_INFO_STREAM(node_ptr_->get_logger(), "primary message count = " << prime_cnt); + } + + /** + * @brief callback function when secondary message is received. + * + * @tparam M Type of the secondary message + * @tparam Idx Idx of the type + * @param msg + */ + template + void secondaryCallback(const typename M::ConstSharedPtr msg) + { + /* + insert the new secondary message + */ + StampT stamp = convertStampFormat(msg->header.stamp); + auto & msg_map = std::get(sec_messages_); + msg_map.insert(std::make_pair(stamp, msg)); + assert(prime_messages_.size() <= 1); + /* + check if any prime message can gather all secondary messages. + */ + for (auto it = prime_messages_.begin(); it != prime_messages_.end();) { + /* + Try to synchronize. If succeeds, remove the handled primary message + */ + if (tryCallback(it->first, false)) { + timer_->cancel(); + it = prime_messages_.erase(it); + } else { + it++; + } + } + + /* + this should not happen. Just in case. + */ + if (prime_messages_.empty() && msg_map.empty()) { + RCLCPP_ERROR_STREAM(node_ptr_->get_logger(), "Empty prime_messages and secondary_messages"); + return; + } + /* + remove old secondary messages. + */ + StampT stamp_thres = + prime_messages_.empty() ? msg_map.rbegin()->first : prime_messages_.begin()->first; + for (auto it = msg_map.begin(); it != msg_map.end();) { + if (stamp_thres - it->first > max_delay_t_) { + it = msg_map.erase(it); + } else { + it++; + } + } + } + + /** + * @brief Timer callback. The maximum wait time exceeds. Handle all stored primary messages. + * + */ + void timerCallback() + { + timer_->cancel(); + assert(prime_messages_.size() <= 1); + for (auto & p : prime_messages_) { + tryCallback(p.first, true); + } + prime_messages_.clear(); + } + + /** + * @brief Try to synchronize. If ignoreInvalidSecMsg is set to true, + * the registered function would be called with the primary message with given timestamp and + * collected secondary messages even if not all secondary messages are collected. Otherwise, the + * registered function would not be called except all secondary messages are collected. + * + * @param stamp + * @param ignoreInvalidSecMsg + * @return true + * @return false + */ + bool tryCallback(StampT stamp, bool ignoreInvalidSecMsg = true) + { + if (prime_messages_.count(stamp) == 0) { + return true; + } + std::tuple argv; + std::get<0>(argv) = prime_messages_[stamp]; + collectSecondaryMsg(argv); + if (ignoreInvalidSecMsg || isArgvValid(argv)) { + std::apply(callback_, argv); + return true; + } + return false; + } + /** + * @brief node pointer + * + */ + rclcpp::Node * node_ptr_; + /** + * @brief The registered callback function that would be called when the prime message and sub + * messages are synchronized or timeout + * + */ + std::function + callback_; + /** + * @brief the prime message subscriber + * + */ + typename rclcpp::Subscription::SharedPtr prime_subscriber_; + /** + * @brief the secondary message subscriber tuple + * + */ + std::tuple::SharedPtr...> sec_subscriber_; + /** + * @brief map to store the prime messages using timestamp of the messages as key. + * + */ + std::map prime_messages_; + rclcpp::TimerBase::SharedPtr timer_; + /** + * @brief tuple of maps to store the secondary messages using timestamp of the messages as key + * + */ + std::tuple...> sec_messages_; + /* + maximum wait time (seconds) before the secondary messages are collected + */ + double max_wait_t_; + /* + maximum delay time (seconds) between a secondary message and the primary message + */ + double max_delay_t_; + int prime_cnt = 0; +}; + +} // namespace perception_utils + +#endif // PERCEPTION_UTILS__PRIME_SYNCHRONIZER_HPP_ diff --git a/common/perception_utils/include/perception_utils/traffic_light_utils.hpp b/common/perception_utils/include/perception_utils/traffic_light_utils.hpp new file mode 100644 index 0000000000000..be21536953ce7 --- /dev/null +++ b/common/perception_utils/include/perception_utils/traffic_light_utils.hpp @@ -0,0 +1,52 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef PERCEPTION_UTILS__TRAFFIC_LIGHT_UTILS_HPP_ +#define PERCEPTION_UTILS__TRAFFIC_LIGHT_UTILS_HPP_ + +#include "tier4_perception_msgs/msg/traffic_light_element.hpp" +#include "tier4_perception_msgs/msg/traffic_light_roi.hpp" +#include "tier4_perception_msgs/msg/traffic_signal.hpp" + +#include +#include +#include +#include + +namespace perception_utils +{ + +namespace traffic_light +{ + +bool isRoiValid( + const tier4_perception_msgs::msg::TrafficLightRoi & roi, uint32_t width, uint32_t height); + +void setRoiInvalid(tier4_perception_msgs::msg::TrafficLightRoi & roi); + +bool isSignalUnknown(const tier4_perception_msgs::msg::TrafficSignal & signal); + +void setSignalUnknown(tier4_perception_msgs::msg::TrafficSignal & signal, float confidence = -1); + +tf2::Vector3 getTrafficLightTopLeft(const lanelet::ConstLineString3d & traffic_light); + +tf2::Vector3 getTrafficLightBottomRight(const lanelet::ConstLineString3d & traffic_light); + +tf2::Vector3 getTrafficLightCenter(const lanelet::ConstLineString3d & traffic_light); + +} // namespace traffic_light + +} // namespace perception_utils + +#endif // PERCEPTION_UTILS__TRAFFIC_LIGHT_UTILS_HPP_ diff --git a/common/perception_utils/package.xml b/common/perception_utils/package.xml index bc1d1b8b6bece..2fa9ccfbb430c 100644 --- a/common/perception_utils/package.xml +++ b/common/perception_utils/package.xml @@ -16,9 +16,11 @@ autoware_auto_perception_msgs geometry_msgs interpolation + lanelet2_extension libboost-dev rclcpp tier4_autoware_utils + tier4_perception_msgs ament_cmake_ros ament_lint_auto diff --git a/common/perception_utils/src/traffic_light_utils.cpp b/common/perception_utils/src/traffic_light_utils.cpp new file mode 100644 index 0000000000000..5ff3b3d422945 --- /dev/null +++ b/common/perception_utils/src/traffic_light_utils.cpp @@ -0,0 +1,79 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "perception_utils/traffic_light_utils.hpp" + +namespace perception_utils +{ + +namespace traffic_light +{ + +bool isRoiValid( + const tier4_perception_msgs::msg::TrafficLightRoi & roi, uint32_t width, uint32_t height) +{ + uint32_t x1 = roi.roi.x_offset; + uint32_t x2 = roi.roi.x_offset + roi.roi.width; + uint32_t y1 = roi.roi.y_offset; + uint32_t y2 = roi.roi.y_offset + roi.roi.height; + return roi.roi.width > 0 && roi.roi.height > 0 && x1 < width && y1 < height && x2 < width && + y2 < height; +} + +void setRoiInvalid(tier4_perception_msgs::msg::TrafficLightRoi & roi) +{ + roi.roi.height = roi.roi.width = 0; +} + +bool isSignalUnknown(const tier4_perception_msgs::msg::TrafficSignal & signal) +{ + return signal.elements.size() == 1 && + signal.elements[0].shape == tier4_perception_msgs::msg::TrafficLightElement::UNKNOWN && + signal.elements[0].color == tier4_perception_msgs::msg::TrafficLightElement::UNKNOWN; +} + +void setSignalUnknown(tier4_perception_msgs::msg::TrafficSignal & signal, float confidence) +{ + signal.elements.resize(1); + signal.elements[0].shape = tier4_perception_msgs::msg::TrafficLightElement::UNKNOWN; + signal.elements[0].color = tier4_perception_msgs::msg::TrafficLightElement::UNKNOWN; + // the default value is -1, which means to not set confidence + if (confidence >= 0) { + signal.elements[0].confidence = confidence; + } +} + +tf2::Vector3 getTrafficLightTopLeft(const lanelet::ConstLineString3d & traffic_light) +{ + const auto & tl_bl = traffic_light.front(); + const double tl_height = traffic_light.attributeOr("height", 0.0); + return tf2::Vector3(tl_bl.x(), tl_bl.y(), tl_bl.z() + tl_height); +} + +tf2::Vector3 getTrafficLightBottomRight(const lanelet::ConstLineString3d & traffic_light) +{ + const auto & tl_bl = traffic_light.back(); + return tf2::Vector3(tl_bl.x(), tl_bl.y(), tl_bl.z()); +} + +tf2::Vector3 getTrafficLightCenter(const lanelet::ConstLineString3d & traffic_light) +{ + tf2::Vector3 top_left = getTrafficLightTopLeft(traffic_light); + tf2::Vector3 bottom_right = getTrafficLightBottomRight(traffic_light); + return (top_left + bottom_right) / 2; +} + +} // namespace traffic_light + +} // namespace perception_utils diff --git a/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/pcl_conversion.hpp b/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/pcl_conversion.hpp new file mode 100644 index 0000000000000..c66a63eb1ac51 --- /dev/null +++ b/common/tier4_autoware_utils/include/tier4_autoware_utils/ros/pcl_conversion.hpp @@ -0,0 +1,72 @@ +// Copyright 2023 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef TIER4_AUTOWARE_UTILS__ROS__PCL_CONVERSION_HPP_ +#define TIER4_AUTOWARE_UTILS__ROS__PCL_CONVERSION_HPP_ + +#include +#include + +#include + +namespace tier4_autoware_utils +{ +/** + * @brief a faster implementation of converting sensor_msgs::msg::PointCloud2 to + * pcl::PointCloud and transform the cloud + * + * @tparam Scalar + * @param cloud input PointCloud2 message + * @param pcl_cloud output transformed pcl cloud + * @param transform eigen transformation matrix + */ +template +void transformPointCloudFromROSMsg( + const sensor_msgs::msg::PointCloud2 & cloud, pcl::PointCloud & pcl_cloud, + const Eigen::Matrix & transform) +{ + // Copy info fields + pcl_conversions::toPCL(cloud.header, pcl_cloud.header); + pcl_cloud.width = cloud.width; + pcl_cloud.height = cloud.height; + pcl_cloud.is_dense = cloud.is_dense == 1; + + pcl::MsgFieldMap field_map; + std::vector msg_fields; + pcl_conversions::toPCL(cloud.fields, msg_fields); + pcl::createMapping(msg_fields, field_map); + + // transform point data + std::uint32_t num_points = cloud.width * cloud.height; + pcl_cloud.points.resize(num_points); + std::uint8_t * cloud_data = reinterpret_cast(&pcl_cloud.points[0]); + pcl::detail::Transformer tf(transform); + + for (std::uint32_t row = 0; row < cloud.height; ++row) { + const std::uint8_t * row_data = &cloud.data[row * cloud.row_step]; + for (std::uint32_t col = 0; col < cloud.width; ++col) { + const std::uint8_t * msg_data = row_data + col * cloud.point_step; + for (const pcl::detail::FieldMapping & mapping : field_map) { + const float * msg_ptr = reinterpret_cast(msg_data); + float * pcl_ptr = reinterpret_cast(cloud_data + mapping.struct_offset); + tf.se3(msg_ptr, pcl_ptr); + } + cloud_data += sizeof(pcl::PointXYZ); + } + } +} + +} // namespace tier4_autoware_utils + +#endif // TIER4_AUTOWARE_UTILS__ROS__PCL_CONVERSION_HPP_ diff --git a/common/tier4_autoware_utils/package.xml b/common/tier4_autoware_utils/package.xml index ff3fa65f034b3..fd9b315f8e4d5 100644 --- a/common/tier4_autoware_utils/package.xml +++ b/common/tier4_autoware_utils/package.xml @@ -19,6 +19,7 @@ diagnostic_msgs geometry_msgs libboost-dev + pcl_conversions pcl_ros rclcpp tf2 diff --git a/perception/traffic_light_occlusion_predictor/CMakeLists.txt b/perception/traffic_light_occlusion_predictor/CMakeLists.txt new file mode 100644 index 0000000000000..481561ed92be8 --- /dev/null +++ b/perception/traffic_light_occlusion_predictor/CMakeLists.txt @@ -0,0 +1,32 @@ +cmake_minimum_required(VERSION 3.14) +project(traffic_light_occlusion_predictor) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +find_package(Eigen3 REQUIRED) +find_package(PCL 1.8 REQUIRED) + +include_directories( + SYSTEM + ${EIGEN3_INCLUDE_DIR} + ${PCL_INCLUDE_DIRS} +) + +ament_auto_add_library(traffic_light_occlusion_predictor SHARED + src/nodelet.cpp + src/occlusion_predictor.cpp +) + +rclcpp_components_register_node(traffic_light_occlusion_predictor + PLUGIN "traffic_light::TrafficLightOcclusionPredictorNodelet" + EXECUTABLE traffic_light_occlusion_predictor_node +) + +link_directories(${PCL_LIBRARY_DIRS}) +target_link_libraries(traffic_light_occlusion_predictor ${PCL_LIBRARIES}) + +ament_auto_package(INSTALL_TO_SHARE + config + launch +) diff --git a/perception/traffic_light_occlusion_predictor/README.md b/perception/traffic_light_occlusion_predictor/README.md new file mode 100644 index 0000000000000..312f9abccc464 --- /dev/null +++ b/perception/traffic_light_occlusion_predictor/README.md @@ -0,0 +1,36 @@ +# The `traffic_light_occlusion_predictor` Package + +## Overview + +`traffic_light_occlusion_predictor` receives the detected traffic lights rois and calculates the occlusion ratios of each roi with point cloud. + +For each traffic light roi, hundreds of pixels would be selected and projected into the 3D space. Then from the camera point of view, the number of projected pixels that are occluded by the point cloud is counted and used for calculating the occlusion ratio for the roi. As shown in follow image, the red pixels are occluded and the occlusion ratio is the number of red pixels divided by the total pixel numbers. + +![image](images/occlusion.png) + +If no point cloud is received or all point clouds have very large stamp difference with the camera image, the occlusion ratio of each roi would be set as 0. + +## Input topics + +| Name | Type | Description | +| -------------------- | --------------------------------------------------- | ------------------------ | +| `~input/vector_map` | autoware_auto_mapping_msgs::HADMapBin | vector map | +| `~/input/rois` | autoware_auto_perception_msgs::TrafficLightRoiArray | traffic light detections | +| `~input/camera_info` | sensor_msgs::CameraInfo | target camera parameter | +| `~/input/cloud` | sensor_msgs::PointCloud2 | LiDAR point cloud | + +## Output topics + +| Name | Type | Description | +| -------------------- | --------------------------------------------------------- | ---------------------------- | +| `~/output/occlusion` | autoware_auto_perception_msgs::TrafficLightOcclusionArray | occlusion ratios of each roi | + +## Node parameters + +| Parameter | Type | Description | +| ------------------------------------ | ------ | ------------------------------------------------------------- | +| `azimuth_occlusion_resolution_deg` | double | azimuth resolution of LiDAR point cloud (degree) | +| `elevation_occlusion_resolution_deg` | double | elevation resolution of LiDAR point cloud (degree) | +| `max_valid_pt_dist` | double | The points within this distance would be used for calculation | +| `max_image_cloud_delay` | double | The maximum delay between LiDAR point cloud and camera image | +| `max_wait_t` | double | The maximum time waiting for the LiDAR point cloud | diff --git a/perception/traffic_light_occlusion_predictor/config/traffic_light_occlusion_predictor.param.yaml b/perception/traffic_light_occlusion_predictor/config/traffic_light_occlusion_predictor.param.yaml new file mode 100644 index 0000000000000..d0230e2b12c42 --- /dev/null +++ b/perception/traffic_light_occlusion_predictor/config/traffic_light_occlusion_predictor.param.yaml @@ -0,0 +1,11 @@ +/**: + ros__parameters: + azimuth_occlusion_resolution_deg: 0.15 # degree + elevation_occlusion_resolution_deg: 0.08 # degree + max_valid_pt_dist: 50.0 + # the node would wait at most max_wait_t seconds for cloud whose timestamp different with the image is less than max_image_cloud_delay. + # If no cloud with timestamp difference smaller than max_image_cloud_delay is found, the node would publish occlusion ratio of all + # traffic lights as 0 + max_image_cloud_delay: 0.5 + max_wait_t: 0.05 + max_occlusion_ratio: 50 diff --git a/perception/traffic_light_occlusion_predictor/images/occlusion.png b/perception/traffic_light_occlusion_predictor/images/occlusion.png new file mode 100644 index 0000000000000000000000000000000000000000..94e2dc4469f3553b4854e8c281962573462f8be3 GIT binary patch literal 281848 zcmV)OK(@b$P)ZgXgFbngSdJ^%m!Gig*P; z8w3bR4+2d8&;R>>n3*9zXdwAZaDnD?I*FeiYw_$(*sd6ozdbuUM`bvWbc59IzT{99!Ci~jgO zfrfX}_>;PBfnW0aUy+Tk8%%ukp9udA2JL?$oc06)_z(I8Tfb!=_jx$8WqCo-7;}~1(ojchPwryR(j81? zm0O-aJy57ecOFOvNbE=y^jro^*d>iR&?7l8a~+8BaU$gXpwI_3U)!CH%$H$IomP~+mqL&DmhMfMwD9@XbE=!l`>7(l#XU6PR__<;8UOkx+DBa9UfxZo2r#s4x zpM@3w(g|~Zl2<=C(o$ZgOTf7sU^RH*pVh$+A`r0x2=lHIA`wCm@DM^k2mz4-Cayq0Zt%eDK5opm(C{#+jQ>3vGYYo=H|um(Y^ zL4&iAxpxCQdDsDWYOx&<>u5CIyGXx2`ge@7m0TZX#rOudNB`Txr|_@up&B>U@1GIG zFZi&_?`8XV-moOs@4Ux5|J~v5=;bTk`A-euy=vEUdf%h?^MO)YDzvp#OG}!md$PZ} z%61H?zw5`O#xQ^g@{KKua-~qm%Bjz=H#lfn26nFh&MUE?i%Ave%f_(#CnD$vMrBR+ zJsE!*Ry6!%q-3SE-=oL1@ej-4RLmH8V#HliGT3;luJ#Ag>c?$8jwpVXhOdWrsb6#L z`kB+ar|n8TJ+5%q{bEk3_Ub?F3sZjQV{GSxA?s)Ry7chG%OT$vR^aIDzWfao1Uv*e z1_C5Xz(foYDF(z45o1IO5wTte06-}MBuXhLML={X%Y9+@F(WNC;T@{CGuy~^UM2k=^_w1o@;%K2HqS=>nzYoh%9M1<=@Z4 zDBIryhkpmiyiWZCxjnqw4D_Gz+_@}&gAWHjnyGA2=XYm5oge&no8LT?t-JH5DFgWT zmFToxUlK#FANe?(r835kz=12Hd+gt6JG1=XqdGO0z6n%T!~G)73L@MTC9=wOhJ7X0 z39?14o(Tgh8abVrk?2Qq-Y}9TdM=`_Q|N`mdugos+QLNjq8Q}+(2FcipK&(R_{<6b z65ccxtgm+hir=GYNynhnPiR;^`$7ivMxihDkcltTvM>1ib8B({hyoB86bKXufr1=E zz!oD?jM!4b786oEMx>MghJpoFpiq#r97`_9CF96hj|V6NM+P_-6s4A#!8A<&eA%8q zSM%(E*nbX07%?Bn;-w6uF-G)a$5f36raYW3Tm_%U2weI&yS1p3K~^twoN>}0IVpPi z{y#8W&~|Mq{Y0*>(;V%$rT(fHvwmAq*TuZBCEwzmvphcHjaLt^%l3Bw?azVVPs7q9 zF^h>QENzCL6VYdAZSIUdQAyIw}1Ld3QF zIJ#Uzt=xD91V8IYj^DbME&gor=~XWDQ9bG#-PILHJ5OW9*Q-QanFpM72_xPW)~>B) zAaSO!uHm1xY*#M}-g&3(`<$-%e);T0Zdc`9yPlolz3dDAK2LEJ00aPm#1j#L5ZW}R zv_;&~hTE3pm^N(NhTA4_%!HD~^Kj&hoQpda9Qi;z4jji0$^abzQ$Zn{A8pg1bc)kr zVCOviOy!w^`qUWv{Dn6{^-#Z2noAkxKm=$lcTE3H3hTVTS{@xAuLjJnEcZ#YFZ$c6 z`%W_T{qWA(ng2+5)97EvFYcUx(6ywQb!=Dv^9%F+4@O#E*)wnP&gwBsUJS zvl`<;gfki{kTCF|aqg+^IMdS#yAYw3o`swoFV@eyB;UpYOC$U`sz)t+dh0aL%je#t zVI--SCYRJqvE3-jiP_;Bv)X*K5g}!}YJe9NYJ!)>cy0>(?A@z;-c&q1#k~K%JT?lF zix)kk(+QyeKn%BOgp2GuyJv0u4HKTGFan%WIi8H+zesB&6w9W&uG80bM2$#)wN7Kz z7rX=>JQ4%~2Li_cL>8|^RIfw~h*5yVc1yTzH{5SGJhlz@+YNWUW`=km6hIt@{&L1~ z6zoUDegx1Cz(527G5{0^fT#J5bjZ3hx)fTD6?(?@Jl^|5}K-H8~at5Eo6}%R_g^8aWy?G^bK9`_nD|%0GHl#GTp8^e2hO07bINY_z#6EnZaZH zb>W!&v#&C{=v@P^cShXX`s4znEQ@i)J13cb)RsRRl=uKQy;0|%-20QT)OJ(OS3u_@ zoVFBTXDcp7FhMOh8}0929>|6&r z-1$)WHd@_;Xcf%0%nk*z6?YX@f_!u$5>mOdV&^bt*7h=1XCh`Zdw-TuL&6IKzgH~d4oTs;} zqR~b3Des*(`Z|pTUDs`NE=S$skdMOr_*DX*+e5G49?JB#u=!iz+}`N8CUG@9Ivc4nR`2B56F=GzCnoNdrhc685+p8@IFbL_ooT#aHlP zKqA?Khm%zsJ!BW#3t3)t=v+dbm`*l@q!@O8g|nUK}{kkV1XLyQ^m$Ow^C<`!fe zI1msDfeHXykj?h%fy4+Rr1*n!d{_TZb`*__vZ%p}q)vqB@>@hxIG1tli5JhvR$EVB;ok-(R1GlM7VA)xO6}i-}NKiBX znG{5zI56SPgYFhW9zwJQf8+Ef4sqE;GWq3t6606zZ=h+D@jqE%Lfz zPY+W1eBTXxk^P%#jq3EGy|3ltCoQvjafSy2J?fC5f7Dvs!#3j<9Wku;kgo+y~;dYyV7Kt<0>1rjBc1(29Q zMVs~nH3G;^+W8nvO4d#`fQwJVAW6>5hgVUrfyC=O?}t|-RactowIRvx-}IT*`;G5t zqUW5vW=SsVaw1~}5zF{I@6%;0zyIcM(`m!I~C6QYlA&TX`9clLr0TL^;XS0MxSy6&G#>> z*sB;UUdC+v{gokuPJXQVY2&R^>B}oFzo7C=t*r8Rv(DP(VEw<6+pDy$%JY)OtDb%p z{uZEE!##^Q9St6gxaHRAQ?Wm2t1h8F(K9pVQXgx6XMpZAb>(>dk2=)~Ft1V3JJVf1 ztKTz0bIlJ|;S`uJ?2B$q!5d_scA16j8>C>1;nrTJzpCef1w_bFg&+Vz?}>xJ(&0G= z>;D9u{={{sy3^X!^%IF8172lP%8fZpxOgvwfCo7iD&U}T4qz}CrH+I(4~3;EhJ;qc zC6MsvSB&^hZ}_CgoEs{y`|4j&cbB=2LSs4c<&4mEKc8bxi{Z@3iX=u6K&ykhy(VrJ zupFXAp(D?u-H>L?E$9Ya*Z^VpmT@lq`UQ!7-!6j1qU*8kRHahOmSt!#lcHpuyta zH1vEWeQKX{V8SQnuK3NgJ`98TjlOUzfHA!H>Vt({QtU5!gV5*jN;GtJF`J#EaoiCx zD~&F}^ACUyG)~F?1W24&_iw&_^5U5>eFY|(NOXGbB~2f+nT6WbXsWW8x_Hcs7TFGQ z@3jQg3iw&o^MVlWPDgpu_k=muj*^!|`MSIS6PJi$p=*{GJ&33&EonTTirjDZv7%|x za_z@x?NyHsM4;%A!3rdZL-kfL>)K>y0VO&e%A5%VcWGs-9i-J$8^~iMdoh3%=!n`8 zdd={!@TY--3L>(&(Sx|tW%m$2<*9V<^zA)@h!;R&sOq&bd?78CVHN+TVewXIfb8dC z)zKDLlj43OQ)jF%1=+INXgFR|Hw(O#1YD5x&YkKqeMgb~>CV$17`-N2$@8^$FS_*R z>Kc+AjXKBpm9KqTeY$6OY#CpZUcn-N&g*rC$}?xJ(PoUS%RUh{q($z}q#WK|Jm^NQ zI{VJWt_-GL?Nn(#wF?2VCL&~T$Y6>n$Y7m{R5)VefLjST3`mrOgEwT}k@-MCP{SVr zBp5)HGKLUP5Ri)eLLtz>Kq}&mhzD{waL|EV1W2?EF(89G|(Qsz;o(3LIuMpO1n%1H$4orByW}gNep`G~F zXJ?`HenC#2f2&#+71)e>7eDdYI_pcSs6V-~OILN)HPso2n3{8-;!Mo1?dO)l1&_3c zJ_izA-m8kOqDA$hM=G!pzh!VTfE?bg|9W%H5Qho-`mliYju{I*p|l%*^DUn zVLH>cb!R5^MpO_Xzf4&?6MCPC<=g{{YGL^*>y53cS}(xF()eA5Rs1^wuczt!&P7^( zX1%^lj4%rF4>DYWu_5MC*}lq)rblMkPbV~-&@;qO9ez1V*y2VJ@_slkYe&OiInVs< zN3zyw_A=QSbnNpOjF!%2aKV`?+oKcsD|VJ-erS}Z><*6L|CJg?1)DUFq^KJ9DG z8(Kf;N*6#vw+XgN9((?(zgmsV(}7+aS?}JzteaDN?8G2`0VaG8{*)N%|G2n8+pM~s zKkpm&ng(iFjy8CE`%OJQObdG3f}p9`bMDN_UuZ{XlzRDHd&DaOy0Wb7k%f*OY>rtf z4dCZv5HVKp87H09?@0S#Gqex5)gP&SObQYR0YSk8I95<0N7SiKYzwk2m&$}qcvrhp z#Tr-220%d-NT3NdMIN3(35+82IuPN&1Z8A88mOrEbln88j*68*fmKmARNB}bR|5Bi za+=v=@$BN=Q@J)beWzO9?s*?R`y!F^T6i;)WqJAKGppJ1%P>f|mB8~6Yx(dFI9y2O z<#VfNUW19VuHUCJYI;-RgFvX~*6pqY9m{kBqq#HohIjl2t*8lOZ*QIHDH|!O*>n%{ zB#Y~jx{|kd=PU-g$SEPO(E5eUOEBRLg-(&pJUN4eu~O`OGyq&0eb!250}`Wmf&g%c zV2WT0;)Os&K|th)h={!ih%isYfg29qt4BiEhCmcR0D@iz*%1SUig+Y4AtnMP1|``c zs>B01N;*f$;te76yX!UWp~uluU-YN5{8(@Pxyhkk9?46!?;9w&>TgRU?@Zoa z$<+%UdL8}p;c5Mp%WjehysYW98QArkA=^>@dP;}}5YhAR8elBy&x+-`$D~t@#w8!w z<-q$cZe?w)!nkwPB!V3{Wz}6Hk9GCrl#J)NcTAMAJibk)wRqH*v(r~Yqb%$1gj-tf z>+?0ObDXz_yV*LU7or0c%@e`ujbMg&B{+yjn;9qp{aOi2S9f`;WpR0RvmU(B(K=45 z#CB*uSJ?a_BUVBCRs2#7!ITP3~3449Mn#X=-O}}XM zMGX$;W1YIrN;L4X7n?a5DLm`PxY8M&m81%3F@4vk~eg@$k*q zpT9_99ntD({VYvUzHB~?Dc&233%S$!So=YNX?u;EN5YL7_eA+RJrm5=#?^TZ@};bQ zTSE@|WJ#~jY9MW-bX9_xo`LpZMBVHvqp0I2yQsXpqG$Nqi}y}!nZZ(n^D?Ii!x{_~<9URKjZyN(j;ZK1FtVO?hKPS(6F zylcSRomtDG4v#57co2mN6`fPcxUBSO!jXa;8ORe?O z$y%IgeR+QJ?vU-^_1olcqo=XHfm6?4Dm^`~lB*{Vyu7&fvS?uUzJI&- z?b>WeUrE%S@%_ik@wp#58m9AhBu&$fb2v4IT#3Bx0MxY&%>DGFdSo-tD{!zQm=FrY ztz7_w04|zaC_wQ$IxULU?daNS*gu%K$gUtDt_i8CcW?R1l4tAU>0qEj)<>`{xIO_B zehWgAP6TuNc_!%3t6;oh@=@`1SLZ^l>#Q#%*YdVg8fVmbqvRr`zZaI8bEO29FL#G2 zjb-;3tiiKa$EV%^5+e)udAv|uUJ6}lksr1PFD_;^Z2U|r!@Wns3FS`Ek&>)^j+K5l zrKSoy>JpG!ZWOk1Ws8_gu74VcXhus@4r}Gv_n@J-d5xoVnLsxquTQg|OFO!nYuQ|x zO_`lA*c>-Ldjck;fLF4Fm*>`0#p0L&6o3^_a6rc1zyoAKbkQA_#P}D`VRD%O1X9lg z5dsrplrLz9`ke{}qG%8frnuc^7r`HeQs?&p@lYP$cP0?w^@CNHSkQ)7iZj@s5RNy?q_lfN_?6XJkwqzKCyCFw4T)Q$7FE z%wOZ|)U|rz>8~ZzczV?b`xN}na$P^D{jI&&O^sWIQC0)vpn-2U>8~n(9FUNKZ+LB_KLR4@sM2tl?E9|`m7uamw0La0nKYDK*cSQT}c z+62EVQ?Tt{W%s6f?H6C$w58c57Yf|phX!vPIw($$2v=cYaH-a+SFfEA^EDeoz~y$c3n?Ied9g6U$TY#?^0+y ztD=G22-W0GuuTq3s=4U~9#ojbSQ&CPk4A@=hn*c^(e45E8dUSJ*R0KGk;Yqnt11mv z8rPcL1BiakHdiIkjXqMN&UEZKxbX4%9=G%EFO6mN3Gw1wQ(*xD)sW|aLe_=`8q@>9 z=85niLS!r|nBZDYr&9P?V&#F$&WZ$e1d%_mt!*^GVt&YCV#>9q4uWt+)lRF=C7^XY5 zex-WT7)Pfz)m~iX2zn6Vr;Pb>uKLqdMt4qU&z#54a^*dpCH%7B$;v@<`>nF*SZmSu zTRqHldAV-#w;8OiU`@2wI8WQU>_fkCG@QvO89?w?c1nx3^ogu0Y3@VbGi)|{PrCsJ zHfkD8br8()re3#tG(F_XQR~ThHO9pnFn&1GvE#W<-wn==N39p_cNcX4y!TBk5mq*Zzsu z!5ctty;r5#1rsciIoA(#egCh9t6V;yfM_WH*}EU6IlQ@^axlL3P9CFCaHYV2u`XakRFt%v*-+l)*{)&Vo}QV~y4FsAl3JA1y)a zi)7a=jOAt?wu$v+KkqR8RZpBNhO6CCF`lqMyXpI+qlHiMcQwWZ001BWNklZF>YocwCgyz?mifQ#jcWfJCXzD}=ZZ3TFUg(&V$>Kn=Ghg+CL)(fKgiLkjc<)se zP*bO?`_0%l0|7N{FWpC3KlaLw%`GWy|D~NU@W#Rfe4}uftKqc28I}I{B8Q35R=smL zW#3=Dh9}n_8cz_>f}i!nQ$9~>>7Ns9;p`z^RMx5<`uG)n?}YVJZ}jECfcNsm?8u4g zTDRT|^s>AqbXuHIak%8D|5G3D%b*74XiwF<5bKXw$Oc3c|cN1_Lk2N1DrgGJq1 zL3~|{?QC8IKN_#;vz5vUXpxKZ&`7VBVdHsw&g@?5D*LPtF5>OVr*X>nYujpQb}g6H zE={E+KxDg96?K-8ItfsUU{tT6tFLfj~$(%g2vGU^O0w z^0{wF)N6k<&=6VnIX5ujM#kh?E0`QH9;bAe#n2bEa|q*(?znpF+SM0#G!R!P(4Bb$ z^U{Fz&-HgsU4s*Yzm@vy@LE2banjM(KEc+2~~IB3%)ZjaZ2Bc+L^wp*DNWfCQw1>M`gSK^C?X5!6`m! zRl6W)>?^E)>xdpZs6x)*Ay>PD;O)yhgswr2u)ZxW-|r~(%BzcFeT-^Z@O#MA>8ea*4fly>XCIOFuBD z>v*W6X5AONQ{OrIwj1m0v_sm{6VJ}vb80%WFUc&=?6(>`?dqQWHMyxt+`dc%yEW#8tXy_x~hZ>8Y15{*8A&NQc%U@xM)TSklI9S1ypQ zS!bX~{$kFd6EF*NuUiK+zT1T7Xh5h(qH29wbf9%n#$x!Weom$n5I%p_d{+W_C`qr* zXjzA+EIJvmF10~nEc2zM8L-ZRU0oZkofh{BX0kRX8b^6w4L2s)CByv#sEx~*4DHfv zGMJ!>z>TtuUo~&ia2$13Fj4;n1Y((5MM^X^uwwk=&*$133pzj3s;|{emsICkGP`w_ z=QdzOUF@7UbC+FrkNQ9DosnusL)XN<9Pnb}-0+t~d>Oqik&2zzXhnBNgL|Ow7T5Iv zzz<4zAkjZF#fYx%7o@Zz)x!&g7y0=bnD4JT3awaf z%t|jDZ=F7Kkr)rq!Q{%Kb=DqXm#7C9)1ul&$1Hc(qz zbJ2AX(CJJCg#(C7o$@3eh)|z1VB!HpS7IA*)O)Fvj8cjuH2O$tQp3+Q7y-@m0QF3u z0*VSA2n|$Jce*7f3Qs_UC9l^mBd=O|W_R4oE%wU5dMTtTfuE-^%jLBQ>h2Gqwq_Vq)bB=}DJN@M*X*_X7mdgG}RFS}`ddhYJV-zUTnhBroOC49=O`+&}I^ad?C z`P~F+RWK{}Z1t{?(qjsL6?jpcQPfo_J{N`ic)3}(J*W?j>ac&qDCd?9`xwAaovP&e zDK|q}D|j&DP7fVF--*odKk)kxkEQt?&0Lq&LvoIi1&+%c~7` z47F41?DYcDR+hOuJzFev6P;J>NXyj&<0DHM@iLqZPQ0g6m)>W)u1U;k%(lKyNBXMZ zJe99?`l#~+`x>AwvHsk3B)?X6)oyct;5my?PMNwI$nk4Q{5MYOxK-^7ZU3W|kjv_- zITs>m)po}6SF)g8It{-}e>|U1RG05EPfts&hgNyDF3nc9INi}nKm^qdHv}9wFky?c zO8|$`?C??qRM@^C3MM*dWvwt*6-=^5f@AI%=GCVLWk&87bRL%XNK_Dk`XhpZ36`}I zzQT+TU9#0HQPG$?){1K#@wHc?7JoQ@6+U^kf2&suje`?od$`j+%H_?} zp)N*2Rmqh+|vD^|&Hl z%XE$43MN`DwQZ+n9+>j>yg@GBXQRpSa4z?J9@O4n%Hp;-TauBfg_7PZS6(e39g4GV zyG42G?JoK!dU5LUXKZot{(RcVIg>Z8o@>;=N0Ze`Sg=6P7XuA#1{!w;UOx-f%k&j5 zpGneLs!sekJW;1co&;jsq0a*yqtVGN>-SYY*VH?$%6R~<=iNVF~v}7qPf4n&7KEBfK7>-eeRZ|$DKlf`S z*i|4e)eB~R=HY5(=zJom-g~y@Q6>Dv{Y4JsZ~hctoWA#&NL{}-cCAM7GWD^qjL-fN zhT^HtdcoWbFSzF_XIY=rdwx#w7+MEkD-b_*$&3fX=WOTtoPGSs&s(kQgM7bGdErND z8m$Xb{EjPi$0wg}f8N(5T*Ek}NG(6=&QFBi6l!g#jmpEhf2y^CJiq4GIl~L3RPyASY-1S5LO=-s&dSo*Lnx}mccNA zN&d3`#a8!mi!4KahZvQ2U2g&Q!rwqoK9!bl25sYj4}dMXq~g-WH4p^{fQf z2WZY<2>yd=Y;8E~K-Bn$WU#9$<<^S5!9BM!jnO?3wTy*JE3fX})iGNa$eo!?&};7Q z_{`ptqZPb5W1xA`Oa>04o-WNv#GI9(tC;oxJ7Hrx_qdJ*2KPzynXL=f>68XMtvvpG zuD5k&bata=*~;C{$LVT~pK4EC3^>jC`17H>-wu&p}teosWQRs`sC}vN0~mS zGmdb5le(IPw>SJ0Alv@dyp^+8&Kg_!w_5SOPN;zg?%%dZ)_ZlJgyhRc6ae|swRj@z zdlNQ80!)e_M4td?prYC(uF~`><$OSXNw$j$EW1gCg2M6vIS&j-y$tAndVk!(X#^Cm zwC5ngO?A>Os0c%a@=)o%K}}jtfrkosH=I2?#?P$wPR#s7-$_29bbet?<7kR~7S4p< z8>2qfSuZ-~J7F|kdOwJZuYBGwJ_ES!a8sv(5Fx0+(%h}=-ti}1N!qoJoH*qoYn?=Z z78Rt`oG`=Gbqu1$+olKup!A`m*{=IyJ4NROuO3SgI!b}kf?k+TL4_!5-k@&kOsg-Y zxa;4JG;c&yBdaY4WA<(8>fg0TOMm9xs?1h>#$B{J>FcE#xG?oxg@03oCj3A< z21k$VkWKxO(SeKk2h^Q17|w&y3(p=*xPMFn9uN=^5ttFUevtwOAY>|R0}BBn*8|y4 z+g97LHx~4qRtDyH^vb(PUtmTlqFY42XqiY9SD=7M0U_v-g7Vslap$Ze&sTP=|7?y? z9rNiQQ#1q0Y_HX ztv~x@n=yMuNHYMfUATg((gDdCl<@MjGuXZHq*Ej71_O2+%Csc$stCi4R+d&KaN}|7 zu-@>lvTTrD=f_#MRl~b_p6z~04YpOR$XxY1xN-)RP(+6S00$H* z2o!25t1Vw&YWb$)*bzcR2vOYM(J>gg&Ta+LUmeMv_1ro*p;(P2U66>XNbM8f1Y0{{ zO4e80nMcA;8#tHLXKeE-tezbt{pyP5`)}tp_LUD`?=N~oYIS9F1oCua z!4gf52$(4q*!0Rp#bRhiUNs2N>SaM@U;dhFe_{$r3_LBr)ejV8b%qYA0&1gblAsw3 zl{W@srGkY5oeA2XhZ1G|LJ^sV(qtc1FyW1n1{ep+x-&kcbc$bg}gj z1-g5awrwCJQ01{02q^~jPEgl}S|KNsXK7Mcedbb7az-v0nKLrvSlf~bF-Am0q!5u} z)P5N&&#!_9e5D9~`=fm5uj#OW2ny2ggYqv?sBtp`n;|yFuY;{Q%sC@dMxor!OBV3N zuJ*p01#i~&CD*!<@28mT zDJrgJPU^d}8M;GGDnBEl$RvtVCgq#j#+UVW4I+#fKM>-728eC&rvqsnm{|dc)}zM( zjD8e&xc2q+0t;W>nzAXrQ~6tFPY?oSCOkk|fLnc4=4`MS3cx|tjDUi?QNHSk5i;x2m86!s*%yz3_t~d)~2m( zQR}JiL_Gk6 zJVC8^X+L&=#F?Eq1Bqm&vV#F+)ePl3c)8ZFz!>1j-NYe|L^+ka$r8zZ;6{~3%pY3p}W8y>qX z(nkb(@oH`EL4}WRhH(r5DI{!^8%1m}VM`HPip|&zqmbgM zz)O>Y#jwt5SnsssICkviz`;BAvRB1QAZ%g7jS{x7VT&7X+g1TZigC%GRXH;&pC9cA zHR9En01*-;0mCsNCOrl@h6+|XB>j;%6297T9EZ?w95~9315)P7@0}sxY$EfVoQ7)I zuA^Pebm!gx4+a<`lGb;kge`5-r?oDEDSU3}47U9uf0ei<8w=ye2eQ=(bOwa>wVaFA zgEJPj9z4M4^EDwyRbFgcLc)eEB&4t*rA_5zLQJXC1FO*E#Dy$T&|`xS?Yxb4+lab1 zz&rT`GYY*fZs!c|Q7bi%YJhvaX1W5+LtTN4){Q+^OGxMjN3tJGsYZUQ523%w;6OHL zJCU!K0+15l0mg}iU+H}FRkE5L`N$$ONqn$t&@lB+z()+bFi@PX_HvdmlHc+Rn! zOM5oGS8fQrKP)$P&A~Cerl7}a3^YcaVlD@6~>LYjUb|VB~+o>C|w62s7(WK zRXd)WC24w|3VN>Hc#pu#onMqIsB{$<(1*HLo0~trj$aG*w#=#=gC>P+! zG78`Xa~p}#YZl{bL&A*`ZgInwHrzH*`rDSODq6ND134df?g#c`#}hlA{KT{Dh`i&w z1W*>k*?T6sCLthkLPEk867IO+7PeYn_ifV=KtG~8l2NKrkyWtgB0m`+a*Bn9(NQ&c z{FbJzT^ICX-EYhr!pzu@U4C?6=L5SLdN^=+nrgk20aOebF6fc569W*aF5^0lse*_o zM+YdV1R$7qLggUIdE3@ifdtn- z{fV7+Jn_U{^qijv9FU7_Y{I2^y(-9MOw2p;GIjM{>FS7E$SZDgGK3%l5h(HwmY_MQ<=W?b+xLeMg93GGl;W!Rm}6`jAQTViqvFR1!d0g zYCP4Xw;za-baNd!FC|yN4YKKn%_AJlduw3A0f=S8pG)bg#5{tXXV6bW zs;OF?nb*VtEv>WcJax5=Awa^we5ml2s;CEo zxU}_pFaV)tC-Go_p{@(1$v`R_HCZrw1N%$0OYFNDn-2_o{fdlxljmGm<%< zO$eBP%xV}PB_o$Z4do(6YB;ddfq(;n4^TOPoPkWpg?sQ29H0o&?{0j<9UJas2G$Mt z?S|X!hWqV?pp4fU*xageKMs6{C!X}gZ~n&b{EbLY5Wc~MfPA2o0@A5gV|x%063Iy4 zoo{&1L+UHuao_HE-0$M82oWKkOh0j>Qb)a>=G7*idQHWxTey}Xrm z#T`|YyD3%QPpOY5p7<_i-0mRWfwEU4p^m5(as6^>fZ`Pa!MqQ4jvh>eECzoC5heo* z0YwIIKvcm5RWPCag3?cEDuY)dM}*Ack>K{>xe6x0GJ;E+fC$|1MR$C~JHEC%9`_rz znCcX^zO3UO=quAz@;nY1m4DI`zsqm@&c6}&sMEPrftP|ng!^{K7d`M59(be&zP1N$ zn*i2Z+6LYB0Q<4y zo4)bHH@^8B-{l+M$G7OvLOAjPzh0z`5ThE?Q+91Dj_dAk#X(+s*UFI6HX(TyksSm4*{H^PEBKER_a;W{%KxGHmxi`0bU6>6LQ^Hp6 zxZ{C4J@AOaKlkm9`~8mFc5nKC#?s8CTdlbh!&~K*8wfG^U${79IH>$;U?PSHG3p62 zVbJQWNp6#oG7xo$$Jph?uuT!jr5oz6PSdOTpaKtTBlDIQ^;FBiPBZrFS|XtGfIk|z z6wu=9kL%C8&jL==>#KDqbtTV$sColq5KmYPN$W68K%ySFmQ3RoHj_Sh90#7^Tl?e_ z-{l+6{4GF5*OavZBd#F7_&(Wj!Z>ntZqtnrr%9~gc-FxdK!V5B)h=E!Ld&UJkJ`>nBV}JJjvcujgk24nG1C@4a(YB_~hLc`OvkDGgU7 zO_tR;;Cep{+%c!Hy7;aB{^*Y<_G8tAue z>(a1uh8f&k-K05ZnXX}OQ#!Ec1A95}%sV0-2rxr60QmqP1j zJMMJHmm2S1>5j)Hpy%;;)H&?^NIg}1Vn25Lrr-D%zLCmr#3O+yf?0qJXOd}FC3`P2 zOuz-54sr`O+{*(GeBoDk;46ON*Y<_4+e1ckqtvSp*1T<=YR0a0WJd!N7GxSr(w~kL z$5a>Kk{cm?$v)hk;_AjP_)XvVjom=GXA3MN7h2-&=_PR5lmfC)1cde5z_iwKA%AZC%<;Yf()kzmqA{;E*) z7-^H~MCFbLKk$pBAN-RZ_;q{e)S}?Lb5rGZeR%W*7G~`Gjw9~)jo;Yv4RIIa6ii}F z>%wHBfCoSDMZfS*_`*nH~+@Jit>7h2=tAe6~t4( z0}tGT7@PO>z+-#hcDvURY#*9_JKNTHHesI6Cw}8!_!s|1%A3+4h9fhBN-MWFR=7Ar zMvLdimMR4ukm$Dn?uqnMgG^@0G@=+HA|>h9<*t4DSFQ7}+m}wE+z>*j?KxDvuc@hK zWVBoQxAe7tA?6K12L%Y~Z7U?8-Axf%0*R?UP^VKSB;2+;?)-%>Qr=0w@VI^9aev@( ze_-U!xggxt>-bDj<38H}NR?d&j?jRF8OCieBqHgNbU%Fi*Gp^Cb!=jMi+tR1#G~d{ zr%w^p!JDX4T%)ZE@zbct>w3AiHDNa8b@x*N^WjQPRSs`X9-F5sQh*H?w0e@CO~=Z0 zV6DmdL+wplSCZl;03vQk!SXNIF4J?2Lkl^DgMsVPPT)Jfaioj}Hv#wPp z`|bn-L>U|i%=)Ffz>S^)z>T;N>(r(ags~zQln_xuLP`u2=mNojx>xY(H~^`+P?6$J>0z2CS0k43o&fAazo0$5n_}ro&jVq_L5ODgK|MG)Rec? zBC{y!xFO{mHooDGyV41J>nRcRz zOVVu$EG(FY#xwtj^1ZEN$)#Z9e<77kluC@c$S=rH3lk1L>U08ohZIB@kZ4BQEb0IQ z3<@H&HUeY-#DIi&B%G|P9*HLB`oWWCgw*Lx`rhc3h&iHUM#vCD9gG4yiUA;NU2eFQ z8y@%)BR>AZf2CjeuiGz~LZ@qTn$qt3+XZwNAOZ3Aq`ZMb&~YS|bvku)Ui!g}?|9&$ z!2TEhEBzy$!tI9p?LM`;wX2PO|HgM~*Q2#-q+NhKA|CW5qwnzxU-1i%^o4tR;C>Up za?V@sE8tz3xqJE>zmZBp%(4a}?BZzzS-l50Z=B(GvhoJB^~3Qv5+`y^FIPYUmKZ}_ zK!_<~D;sWn!-MW3Q{pfDlm5YfZU5lw_Ju9Uw6YL_=KV@@_7!6W_i-FZ)*dlvUFaJu zJISzTtq_mPX!SMAsMjAWW`OxScvZHk+K7nQ}fZFJMIHeJtvgda4L zy34Um1qKIJgTvBd3t*&P? z_aMS9x)M+Y60*3E03A^aMMl>|p~l{=U-w-PwR3b^W!Cna|60ZV97F(EzH6xPr(^t` z#nYcn+0FU;=bB(V&x?lZlVmT#nD{EQH*2DAnm5CHLjO$p69ExPyly2Sl?_|j)L6ga zhP$}N>4AH=HBql40g{#j5+tCZf(J4XAwVLQCn!W91pSh*%^e1g%s|eXO*+P>lXd)tP`~)2llmbd%WRkTTJ7+w3S0h=bT6rL0qwYi` zqueDS$scW88W-9-bP^V0V3M6!D6Nd^S7%T>k@jq_3(;W}3En1yCZ;L7*5AOF}FWL=lhhkRPdMB7ET<8Xq^_8F|YOPRtLOzKJo&n!*TC z?vdr&9r{Zl>Y9y$LIoLalZNcQ6jraj@$3n#Aff__YN0n-)zQuXF%m^Q=#G1E?H#}H zPx^&_wtw)Ieqqxoo}^Qo{M0McJ6CeMkZkU7ghRHJ5567>5TF|>P~G65koe7P7omF9 z0W33CQDtVLgqSxZ7GBnTirAu=~UVA8wov_ARI-!*#{li`H81`IQH@cLFBW^`VliQJkASAXpTnF=HzvhoORfb9qZ zEUeEnfD{a9nI}Szlyo|n5kJcHK6Fv_oRK(zB0v$+CnLA(0K`aAC%Qdz*7bZ%-j|-| zX^;jy<~f|ZxYZC$@7?C%%v}>#FhR`foluZq{XDcz*=DFIh_JRXp~(y`s65ClTYk$P zNm-{f`t+Tl$@4MEXdnZnAfSLVgENCN>yp^k%H-hRY zoFA2|%GFJ83eH1O7i!}SM9fy|&kTJZ)`{x$rQ^MMxTepj{Sv>c5bq z7_3BK5>LRvz)=`67jPE74#7NcdL+9Z0nb)xy{T~($#28jcGa-+@A3pCF`9EII4EPM z15X^-$`eN^Kp}7;onE2br%K!AAWMBEY(*5dcuAzrHnQDPQUx%6caOHKRc>I5c0B3X zfCMDJIyJz}nN1;Sd19wTW-ipf&bl(iU095nQc436Q9uOC$2t^D05Qm%`V868DIkM5 zqi_~ixbAdiMqVB7sdAhrAVK6k6VQPZlXKB+|Ehy2w#XWeH~c^Ep)e4t>n#jSgu;j! zu*G$3AVQ6_l(Y{N2cp#*@K5?L+_$an;$(}@{hsXo)`?R8?V3Y6;iMo+-Gq>)NQ*n$AXgxbb2$2y(i5g!dqgfHB~qyDzA zEkQ#sSIioq=1Z^r0H{9Y)JUiQlE#12Ha2`O^I?GNrmWWss7?`mKw!PYLqYbxk z!!5RrFSfedmKfk|R-4Il=x#*?I~_tl3`FeG)~?u_f`|Sn?Cb zn}G`3juk)y4(=BeNJu#v1CKj(HokU`4Pg3Np3?UcfCIxhSN_XI296F$pA1Sr(X?l?g}op z3KawoA{^Kri%A3|RMby`Pzs?G!jTE6KdE@$bqg=#`mZ31a9H?WNh{yJ_R0+BvUj6v zra%p_n3Cm6KN`Vx*|reij@l zV~>Xp1P~}w-M5{!zHE-QjjMA2z&a|#K#T#I+D;w>s^3FE76Zn1`Y0$?@e5X=YS{UY zjoCbEQwAn)BBCxdzJoUwT0lsMct%xxhq(I>WCYd)yEq_bkCa1;MsN>496gAyGmo!qWu>2OnZw46?%m3&7^( z55M~LJ^)3hPm+unmv{#@X@dm9Gj7=T1II3)`k;(MdF#-f-D)2+s?aev^~;}`z9{lc%?7ar*@JHv%dMuZ_#+BmE6o{MZ5nr$)d zxel`LM&z8qhpY`rkhNAw1(Bs)o?(+`b6e|DvY%p7kUO5!QR7mo4G>DGGKvpI*%|qn zMV_niDqDKX4rHvJkPzkDDYk~?Oqa+Y6lC!*OWzWkh`~FHU6cg`acVjtL|NyS5V28g z9*LTt2NaTzOnb{Rox4E##G!ex>3dMLU+wObd!)n ze&vuIoV?d5U>V4l?`DPN|DAjCgacd7H3( zBd?951$IYs&re>6P#L0))G45-ZRbsj_Sfp~rIA0?^LrL{?JTE{`<&Mgb+lC`9hKRe z_Z?H$(X-R+hg$gvRGio7=XH&K3C9UQ@i)m|Q-4pQ#ty`4WCl_I#V2~m{Xt)QeLi~jUG7l=Txt)sPqq`qW#9Ew6)39;K>pO{2R!#pRO1SI>^?XqJEwF*vl#*=DB>13G4w!)L8b{j_Z@rO@qF$`wBw0GJx2$2B2g}Y ztEUDcOzF`0<904Y_Y0<}8UeN#)#f^1fCy0YI{U$y(td#nT!OZ&)t8({j_w!gFK|F) z9dIeCP>v$|upc(}J=du?^7VG#LxsM=vL)+r?D&3uWBe1Z`{Kv7}ohmraa1VnPTJx47dOcQ8ZN+r$kK0%FQD;sk-&shw&$N^i}z^NcG5JSK%ChWWL)idtcpSmS;i3nw{ zx!Clk;*2^5)$_LPqSK~?YD7gf?xem#lV5tiZJTT=alhm1@rAFiF98zU9k;Y01sw%f z4`n&Bw7dOs4%WnGq3i3md}5NHHSk8}jYY%^vjII<_5YZr|I z50re!K*~+L6E<>85d!Kt)IlTPa=zYd4VBNM>{)cww@eA*C?DR-h%yx{6dC;*)n!K7i`=JOL9co5_O<7uTSImdDmO)V~f?PmxFYLXV6R zN(B;Zj!4QV!A*A>kb~64sQlf2>INpv3!!MAN&^w$%;nF%BcgMA&E_Yqy%5X5s{~F1 zS=mnCc?~3-{p;T1_wRS{+MsG!Roa%1uh9M*;mv2?dQ1iQY5SbiYp3Y#U2^ALr{Q|r zw%G-;{{pq`Q};1d0J1ZJan%V(N$PWOG9#ir@s~Sa1XZ z5gWUaD7TD~Ht@z`5N|r7KtVT3X!GcU z(iSV2NJuse3#xmV+h}8*@9z|7*$Z;8=~1Gn%f={20dK5;hJg*BL|~4xU0mHR(3FY- z911epNPe-K8~L`;P*Xa7_}ewV7*lFUxosCi)SrE=oCr{*n}PtZK!g-zk@t}{JmZe< z@I=BB--saI1$-7#aaP5x177Ir%y^XaX%8XRu z0mQ5xiGt=SXv!~m009FK25Iyg7`iQRIWqE|ai}4@@3PyAjULx=Dqla$^}}r6&nKSW z0wl^_P!5Qfi(B94gHfIZM-ZU;%~3(W_Q!2Q*%G!*4JQPoBwt}A3e`~HBpxQ4Oa6=p zZfTd%S*>Rv0GUzpfwC7tDxL8NS7VLY>i11z+kP{|P`{>J)Zh#V*g^s&Ad!HGBi*p4 zXWfqZ8&COuQhrMRQlo&ty3e~aSU~lh$m!4O=~5Gw^dpv04CZZ<-))Q7Hkqb&yKT7L zWD9B8)##4<{UO^*$Am<&>g|#lWzRTv`9{aSi@{Y5{?d;cldHpKILSQo05RTD2x3E& zwk>o63=TjXa(x`R0@59adTb~E=Ba4fxleRO9^F**ir$d2;!*QMGHTQ3mQ7DIEWo-vL39SD3$kFy-(SBQ=9?rReh~9^~gj! z>UoIj8E0Ns4;%u7?=NF&?X7TV;FBF$*R|9PT>(Uk@hPg}{b+b33O=nfvMiVrmB}3^dfm*AX5_kn1pg zesDNo0Vm$EY`a>2&tj%wy2bmU2Mg;YTI|}BTx(YUQZ0k%^aX9NXnpJcYqa&UO0GEE zMv$lbUdj8D0Yuc^J%9lOklkPw&aUV?y#%)lWd#kiF^ zg(X7_2?X^Ba5Gb*O}kU0fiX$ z{cQ?C!JK&_%+(!HbYXKYGQFeZf^vuvk#+PtXEoGqgvyL8c6As?w-dB2X%k{9;+b&D zB`_gTM2J8M@IJ$8&UqwY<~uhqVJzFe zkuxl=t{}pDC8+fWOT)2s&10J4r2JXXjC|Kk1VlKGL9v(;}=_j0|A5lj0YMbyW21GLQe&Bd25HtYcfW&dMZD9Sv_M$eQ80&3t#y;43 z+cxkmgUcrCu|Q&SCst3Y^g|*UFtP#XQpASLDA;ob7isTu6dZfTaTINT`|7#z|1b}O zy_YgnFG;F>Q@?${3Ir)4Cc?%M1)Hqn$Qi%s8;LeV);?)77D#qC3}`yhd!6gRmdQMJ zw2fHQK?D!6tz4ZThnGWkrrTtYZI>Z@Ux@Y752eb4Itajx&&Ub?-lS?d)n}Y$tLNUH z;u#?&>nw&i3hO9TW^fJyBB&rx)~_?Fb_wzfvI@{Tfm6_ppF>{9DOiP|{p;3A^j?V3 zBOxF{7bjK_;YJc%?Tod3!|9Wr-z zKuQ}@%sK_8Af*j4vAEw8DtJp21#po$Z^gU1g{K1%1U__%Spc%`$*p6mJ%~X2kdglg zq6y$;I(@$+uQ$r2oP=DT3G`ZPW+xmF7?#!)~pu(E|py<%1Huat=0TfZY6q%wt ziWnr{JD$Iv`2PKk=kusQfosX&00r8|8V?!CKK6{f>pF?-JSil`blX*I7bijGuL6{| zmZeYx$5O#^g4R`3Peq8>a>5a_tmQF-X_p_07%*jT@j2^Oj{|sUwZ_6*DIsm*tt?5l zO6RD&uj?gbOJ`kA1=(Q*1RQBc!Z#wzm&|dHOkLD+A1q(IM+K$Sjf*h1K@6FeqtmNE zx~_(FTi*@$wBfPc@O8W4@wnshxZ&}*RZt-w3jOe7-9l70HaM7(tsfpmJQCkKp1;5G z{rjoLsMeVq)u}vg)2jj@Z3){Z3*NUN9+H^aG!y|6(!Y<~j{7coJi~#6Z+x@PrPsA% zgafQooN&lmv_i5Y5tSXby9MtI&cZ*zWMqu8sZ7z$52}}7Yohy^(+H2O=Ue zC6t)KN!RFP=vLmYoe(;%vQVcs6`_|8M&1kZGb1aIpd>VukWmr?>YWpl%niO}IFClg z@zkkwyMF0;KiV`W_iNuX0dmN?IK55fiy>5ADfbM{H=W8SBmJ?0dN_O0gw_8?-Ir}S zj^o;Hkd*AG{{K%sm0?RH?gIvblw>=Hs_v^?PAN2U1h6qt7MN=!R_2|BZd7KVip%5v z-0^(wI!|{U`y-f$Th7_%;!@1TH;bEZk$6Fm8=?$K79`=i(>|0URp|;S_!lkz?YD$`_;~SfFTcF* zMbYy3_>0Hyw)vi`XD-Y5i<>p}X=PrNW5yor|AiCmgvgFbrFGuBU|d-Q7t=OjZ=$_Y zp*XA1SyM(y49;+CShD_4aPVyAzdbjsX+ud}!)+kKRwcH&lPkXhI3^(gO=AUibvvZe zq>Nh)WlX3kp{62COocA9NO;On6BfAxismh6+6<)utoW>v2-JX7pe* zL>9GdmP%T)A|(Vxgi&&0FeU7&OlW8l%-Ga7`zZp#_8XNmtUj}H6Lr7}(o9>P5Lw5h2{Z7zFmu;xJ{3s(c;fNg z)OD#2774&yzLTDvB+?M;Fzb=7SrZ@Sh(<%+G6fIiJ4h}zT@P8Rs8rKupO;~YtZ zb#`LK_Jad&U{~3j&)53@larmk7>Rq`K5-IDk{N~Kv>_g{R{_0N|!{%M@`+tJXX%)4awz( zl#(o$#`voOPB)_gRky;n5XlNXS)+1?{88J%7Qus&v_|K;p6E`FN<{64~oWWSB&Q*^EXk@Hixcfl2!@C8ZrX=~^7(g0ZJvlo$#k zwjypj?n>uy+s07<5|B3Sncn0ZNnJ-QvA~)o_2{jvxGy){S6Qk2uex07*naRP4edqNN~le}~0L9A-B6XVBQ)ll(hP z);eG`r)g+LU%L#ZYHJC$Hg_TGLyd9Swmk%3cbBpVBs``p(2txF+EUR<@o`sjMlBh2 zFJdLhk?#c1tMt`?geaGGSb%xk8}?^)!1{P>aBGAEi6Hzku?9&Z6JabL^M4XK&>EFK}5?!e_E?m^u%o;P`Cmeyj0_Q4uP? zjAHqf4GF z;;nrw#LNSM8|%fMgT5*u6X8Y$l-eX{F-d@6E0Q9w6%$Bx47+Bq6H04`C0AJwAr+sH zwm?@>zxbgJ7h}X$*xVb7rZ6{fBD5^=5S#jf*Jam?HQgf7_1hFc#0V$EM5=BS=pX_L zFsPY;0T=Y3Oug+2!W68OT(FdiTB-_r3@+MUB4)v|WhRn9SpyPitimkZN7!8|o=$}HC?09|~qkpQeb#?8zlVk(yK`@bYpgpKQn8LidYHBJ3sn%IDFmYup zxnNrs8RvUdZL&OTu01jrdzO{V;+~LN16N>66$zWThnTSZ6kzmxZW9gT!x2~0Vzcu3 zDAY?P9q1U!P*u>NP1e$#4aP+jRyMT!Oxre^jc6vPBf>Wz0 zLjvzt&2?KcS}j;h0k7-|4O?Tu;xt+lz*n=zO62Ck+?Hg~&bEsMrxgjt-^tc^k$4VM zbX0EOrfyD|(KO3bP6e)3sLw8+Uj{H3-C9st%A*M=>~|FKX|PDx z|8cXiC2|ouh)}@VEMB6iKnUYe7(fImt>K3L>>gqy9s(e?r(|jx0^1c(#5H0ZSXsN6 z#kV%pQWcy@yVg?BmKx>(m-3}=9!9*nB1`2#q!EKR*1AtlvH^#nb#;;sa(k^bux|Rj0XN`dgqv?&==V#xd z3}e8wk199D2apB|i%1$lSKdO@fkcaz2m=QxcMy@X#f&*d3NAfcGwTgyoXpn?kdfCkaoz$745f~`nxrt?115(XaV1W^A@f$2qb z7Jl9p0g#Qy)WI7rwqFJjpKoWYD~>mu{2j`5kc9^qu+tB|2ODS4{OWcluwMxAvVB^% z2_YN~15y8pO+~rkTyHWGw+D^giLX|7WUvazsgY<;TT-EiF{C=2gha26oxUjd+&ZsY zE4;)%Ck&ziAT$lkW7qOpj&)lwY#u9SF>w*pwN0j})?d($cWai+PJ68do}mgQvUH7B zhMvkbv{}${owpB%zF^UW*Qmu7KYIZZ9W?h9xEZZUV5j-3GHYOM)g0>FurxEDG^E6$ zv8l4|1yUNtbtUoybZe})6JV+Dv~?nc4FjQz2{V}Bc*g*YLR<79&_~5d6MFx;rAJ-3 zG^3HFyBx`(E+={R9Bdr1Sm#ba#Wz0wO)jO0dij5SK%8S3k|p zGiL@fa4&qpg!3jmCN-p%kae-P%9_!OSr-jCs>L*LucXaSjiWINJ@rc{|{R*yOGyJRfOsw*8! zJV#ddj=mV0ww0w_Z56fd+NTmT@_cT1Yyup9d_VC0fuOz#+}F#W?jv=j2IdO=oJdPaG0{7e;z)X-yUQ1L*Mz(d{S@1RHOC z&aukMpRvi`ziIcsd*Vt#VHRtO3{NSzz;f zo|UZ$`1Em&Kx;G(il~8zWzEr?kXv?se&9zz@VC_42Vr%n!`U{?1?YHEMU}Z$*)b*Z z#01vHCh!`#7+jl%y#fStX>!-5I{e-54Pb2OGj*9{X`fsRN|Oa~b1kxOMHWdkAc5{F zR18F97Tr}N35Ib3rv%@$LINTfP|JY~f&^B7XO~u{b~i8)`y~R1&~_a-K+TEayjylY}01thSK3?>==b#?TYuZ182A#8khzMvR_?j8OSuerI5i6}R#@EzO zdv`F=1AB+DN5T}$)NCNa8EC6m6r2FUSh5K$C406Xviirib6VAzywf_CUb5CAKm>+^ zh;Tkf97KeEX01T~H{Kt~UKgllFu}Swln6P?Qe=f)-It29%1|?bD++zipec>tt z5)adAMwbZ9+T@-U?*DrP56eiVcR!vlWp7Z&?E$k_!a_zV3AuFPi+pj=XsziWBBkVD!rp7yiT14nh;5O0 zfl_2mpST_YYoIvL)9&{9ra;aTBBUS~rVb)(ALKTr51})stt%}?z>*C}7+BH0y(oGl zbU@YV@MwJq0OCvmr0)Q@^E0wzb_==9<9T699||+ci<4Zh8-MV!)>zhHeYRJGz5rxC z8r|!3CZpCJwPsn)fFN#7IU(=jZYN1Qq(Db8Ym`hqYhH{}CIFGnPvwf|4HR0SdS0>v zeAy=ljS)!Laa`598KA%jD4K!^RuEAYJQ$deXGS0)U996L#MLDQ5JiE591DPOAYmW^ zV#O{wCp1p(S1Ra-97LF(Y-N^$)FcZCwWL1S3DLMi5loznA=1XC_?!E{E2bUczJ+$} zx1q!7cE#@h2#EObgM*>$TK;%bhCkRk@5*pY0r2`=zIAH)zO*kW?@Dxne~hlP<`D7L)TJl2`tj>mrWGY~=jUMnNiB4Jtz0NgO-U+31X5rYXh3c@&X zp$UwuYto%M_c9uj0R(tSz=;$74!mNpXk<*+n+gBy+GGV0u0h*Xo7loLz3m9HxL*V> zB2=>Ur7wCVj3pg)>^2JQzlRq-|SkGjFVwev{9fP+;VmDWsMXe zf?Fg+gKGj;n2anki#2jY&?-2D{~*ZeW=gGEAmd5;wY5W+$rbzI88?zFZ8O@pUEYpb8%qWvqEM-TsJqLZk2kYGXp#MA7MEqoxUEG} zf8KAB3iNh!w+U%8c2K=n#>Se_Wz*EH&n*a+rsX$)#$ik-&9(92^)PTb&L@*R4(-GW zQd@GcQkz;M*ye2jwve({?e~3e3LpgdY}?*ln>-Ds)+Gp6FE=9f$F|?-(lj3*T$?WY zKmIXGVsWl?LDpCD9V`;dXpJa~=hU~XOmTiROUwI|biO~nzw!O!fo}~wx1ikJvMAZw z4hl3!*QT*DM1)pJvf>46#2(yMYHnz`iFQ3amk65f(tw0nBsBZg1nL0{ii+s6Vq>rd zi{`#n>_tFPu^6br;Fh6bBOuKJCdnZBm!eg2bZttfLVhgep=U2xNOZ3<%Lk<_g4^WU zsbAz!4xY~SevK53 zVC$#|=wH_b>utsDzDfqQb@8lHq*e*5wz;YbuZ3rEboo5~Z9sw|kZ5R7*CrLHM>$iD z4MfOZ(!x7{ur%QcBFwGHgXuxtwW;cI=8V?c(@-r{NrKhXceQ0*0Lzv!Co7Et1rE%9 z8U`-Y(D54107C#55k%;&*yb(^=)b;jnf{3vBb3QKLfC&IyWBe~~gx~(|NM8TE zKt8^e2EnxtnNIO!K^LHrnB`NjM8p^grmai?Q;E5R^b5p95RRU4$W*10W<8F!Ym6**E z5y6nTHtjB0y#^A}?k$^w!CWx{onRi^wr0!3>&-yb>1T&y*M?^rgrp84)}uutnLCUM z*eX2kYI*qne&EO7-}w9QANcY8P_VUO+pAa<6f}uu+qB(%?v4Voj8h4&Wfx*&b|6W~ zEAL9oAwB_a1(3N+p2E|tDrS)|+Ge2MXiW#k?7{2NBC+iiWv?h|ktn5x<`==OYCEUY zwe5&>z+x0E#?(PX-w#~QWEg9#6S-xe8{sLLcyV7(kC&{^sZU|4XY(TD5-;F zud)SOtJ1_R5z`(`!9qhdK!LE=xWHbv$lDc2XcD7@Gyn)&b1H}6>g3Nrfke)z++;GK zA+eZ)s&zDiCW)%2d~IwdE(y5qx}o0TLz9o=-TTYV8N;^9#h4TC4uNF7JGpl&Os4)F zne;b7#IJ52$)oQjlHcDx{sy1k`%^_6+U%bJ6XUl=0nB!+9Ebr4UM2+;K{((^C_bf* zztlG;Qo?jB<yV|bjg;C7_8NAIRi0JJ%yvNGozTM;kR~Ild*0tb%TX4Ux`1)D}O#J6A$u(4i z{{%GfRe;3vF@gsRQtiLymM2T+=>FBjp=MpskATwa;(SKdIBnLhYT+;oS2my!erCN< zk3%$;tUd1D6c(V{RABb{=t6X!tUv{;^WL+95>Ay11D(J~D{v;TAiQ(Bhr_wy`$Ly^ z-~7}A=$EDFLUW5Q(q#+H<;j0v=a~uh+BT2x2Y&qc#@|1_-D0-Fo@{w55vC{e6?cU?1=nAXT+V*Fc4z|2g% zqqg7XkOwkbJX@rU445cu@rYZkf2<#OgMUfSY&A+vVwIfJ7BWdB(rxCpYA}Q<$w*!ay*zWbet*{ZJ1n}TMgGN#GhzBn^ z{C8#7H_!jF-2bW~hjV{e0DtwmnQNTf`|G8#4t{^zt9HH0!Z5zum?^@`*a=b_1oX+Z zDL&$bITrdL^hJU9aQ_L22xA}$Tz!>I&1+qITtd`@_EOAS2M)$CC*6CORsx6sFupf} zugPb8023#|@T+YE6J6`uV?nByI|7IfE+Ww<5J^l#tr@LJklnVGurlw&SiHyBd>+m$%H7ju`>g5hNmHRM_Gnww5Qkz z53&x;XsmD?;t)2jh*pqVHY6KD8LNbF1qc2_gFph_lk?+4g z3gBaEEEc)nd}I@+9s}-;XDL{P@O?zkhh&*Q%vZIwvDO z9cmJ3gA7&iS9hz;plKE`QL?01mT{bv{+cCG7gHpNTT`?|M7jAwabjS?;w!r)WXHZ2 zY!@Vg6>QBJvDwRDm z7uDn$x^m7En_-{@9b7Tc=Sqlya7#qAM%Y{m3W0&=sIabbyaeqA@X>(>hq?HYLnF>B zyWi)I$8<=!;q_8WlRj!7LjJJXBEqRH^71qO+xcPyg$7cFI`BLP z!Z@@qPt@f^84QyC~t+lO`wt8$BApnW^e?>zT>jbLaZFbxdNZ65C zBrH9=uQbJ3!G)!b?-GL@7el>`vlO9;RU$R=Pmqr)r;M&`VKhjPVrLx@=?wkD@od-p zx$F{d9>uKyZ0t;=@328WeCqY~hvn~oZTqNl|J3$h`|!sl82w|%F*Lrx8nTaN8`lS| zrw#jy^32TsvsR*Me|2nxJr+Vi4=i}~=q_@q8#$;g_BlA^L+*&TGm?8T2+l@4;Y=H-U0rd0*zi6bEF)m z>BWHH>0)o%(C2=Sa`Hf3ojK*1IW1sj*G}JVtN!}&{kEv@yJTESSt=#k+cvC#`+RP& zG@&jKx{J{XkYEmJ#3Ps-g}#2I!h#R0-h!hQqK}g(xY&0Z#<9|cM{|ptf_-DQ8Wm#R zZE>E(l+euVYfJR`a^3fb3vrMQZE)P8=6V)PmPG?7SP5riMVD;03 zt7|oSngDgzaY0J=z0Z38F{8(g*xa4KglovjTtDPl69A=Y6+lEFF-ZrZbH#3HiecQ3;jBVSIQtr*KbE+mn&XJ~eg@U^qrR;(}Gp2S1~{~W*HvO9SkfPQu3Ba> zjc`J38HpvIx35wd8$sV{gMwfTu?t}EbHK=Wc_>s5GU^j*XjsAlK%DfR-^UmC{jNCt z$@BlH$o&>f^hWx$9G~E-S=;|w^YG`lPro*R2|Z?vsaoT91RL>hoo;m2MnS5)C?6lr z_ZN-rd3AhJB$u=L#Q5ynQMt#wyLS){E0WGvD}$ByFP`=0DVyts2! zw@hqXMoLduyb~n>Fcy1a*@^nA$X$sHKuG$|1wc~kPeIDr)3chi(^y^i*z7s}${-fY zyB!#=i=x7VZOf*hZ0GU&TpOE{ef^E-9y*Vfv@R z!nvW4xB+CUXf2^aKaje>-^YPV9bkrQ3}+C*3|(~SM7+{5Bdgv9z@qPSm!<$FUNUM5 zMWgZ3?`)q4NB_!p#dL>_@#&=d{LWB>Aguq>+s}UC048wiB;fBR&j~#-`pDG><~oXv z^YRgg5pI0Z2k{w!{n;Mq-+J};%jY6s;3!m%KNAMxoQv(ynGp?w-zVicWne~Ll+JVo zMiBlZ)0zdd8FA2b|8V_P$$9|uAjya4DD16_rkOp^sK~W{P9hqLOORkf&qi`vRf8u0 zW7{_OkzdyZ_xnv3o-6L=;-4Ob4%1Y205N0)i{r!o`GB~n1WjOKxE6`?6mOz~VQTfE zxn6+?aIaewz+XM*1)lzPE=L79SCq1VNY@A`U9gXI$K3rBv+@dS&oBgng|U>3r7cc#Er2{F z37lUwg{aMENj7MhpyFyyo$<~2UT16J_^0?<;ESGx>HtV)I)5nvo^0&@ zUxBFC0Al`o{&xR+e28r)#+n-$D2Is&&0^zR>Q`-G81{~-Dp3aJ7Rbq zZ*XZVXqy9wQ1R@t#4o>n@#}Sr(hLoa)H5=XT9>X$FiAwy@t>Xr$M*%Xi{RSlv8Se1 z`b98-$s%EEoS3WXzOU{}ZN9jxy1aDFSEm>wfNcKj@gv<*!SQ}@fBvKz(qD4cEfQ}? zlJHJrniy_=CGZRzk8SQ+-B8Zo+I|MrTwa_|Nf7F1DOjeZwV$PjG{IA|b6F5)024VS zS%bj>Ig`38M9=~o3nTBf&Wb(+6WM%O@saLyi-g6bh(#hJ=KxllCU0Tj+I{3FdQq#v zh~KZM0KGs$zkBE9&&dD)AOJ~3K~%y{yU&5X)&L2Js1>%dwo^SaVZXeMLyrU0O+c^Fdpq5dS8IBol)Fb#6LS5-+lbX`C_AIZySW(03Vwmky|4|`qu~~4s%&M-PUds@Q^!@Xd{>)Th%%M zijoyMQ!^lu(ON-9(_o7#0T+;k>y9o*NAZAlId$f+GVW0NS&SG#ge;P6!UNnKYeLxE z^D)8exp?*a+bbdIzq*C7?vtJ8vc1nNGtJVUE5dI)8@JcY;nlSl-yi35fDOl|rj-F+ zeD8e;{rDgl1foea-*kM@beg8We|Ze@{6`Q8mFq;;6@Z<&TRHfXarHCBu+5vLg9le6 zn6}E&PAkLV!^8bJGN-eQFF#k>bB5t`3P$@z7BjG$Pdo0MRLb`tprPahE=A}g1q(&3 zsx|Fkqbvnw$*RHZ^n387juwd47m*udhPsb&bRW{U4gDwkY2;GBMwgoB(KYT}lg&cw zeBR6U6YuPW4f{_goW6Wer15xd_(~j?-c%~=1t0rP+buH<`3l#T>UUW)mLjfA*{=I) z(CBl?za94z{X4Oo${6lcV62DU7hRKV+(bWp&BP{dPG*hh3!Qa(^QMhq{Y?`ti~qyN zcWn)+R_rMVsoWQ++-n{dYm33wBJ+eGYmHZ^rGTIo30+0pV&JR=L97} zM)olr7ae3~RpO2T_HF@*HRcW;d@P1$HSkamgc*s!F;#A zeMLBXNhtXF<#*He9c`Hv;)i>#c((Sv1BuPXoo1M;70(jrF=6DnaUVbgl7I-?dsqT- zUx<#X0E@7Wgv2z5GIJk;qSq%-3)YA>?bY3B01}+UA^~#)VW3e_vxq?mOZSwKP)Eid zTDlifCx}iM)LFM7Zg+A<~_gq}6VVmWuKGv1sr6@K}>stOd?$ zW|oNFg?xPM{cDaTI}tn+kw=l6b)wdSWs#u5WbP~}tDn4Od+C9oUGA{HRx^0CK*V$N zKkl>US`lEvz_EgJoWv-f9$L`IgSzo2?0n1OGN66((&Nl)CY!_pCL<0F{uS2%f4k~`vg*%02k-~m$%Oy5stNEM4xOvz4P!?SgWLOCj|3AOgqzv z2WO@4cmG~*7|~-2mcKxNr`h#V{_*3{53$ePQ1(-|gFt^d{vFQsUw4;y)w^!_wD%cd zP}dA8?+Y$X4*tS=q!@KeJ+Z$he;e-~P z(}nIbJPsP+&1`L>*GV-x%uDHk)+vAjPhv8Bv+qri8{?2BdJxOc<4dl_y8%2N z;%=&@ht0#<9OGIzG>oUS*8P|}n8mGWmZ-4!ATz5qr(oar03vLy0R}uRZJ$G86|n3= zN!RO;AA(zxWf1GpR_b4#L>@vANbMU?MM265Mcc+&S;(NsVrHR8q;VMbjR+Q8VC*W~ z5xn!*ub~HLUU@l&4}*#(!Wcl+;jwV9(RizCeAo2tIL=Pxv|pU;JpE!x58Ekmr(^pz zM%DNP8HWO(({6D(fVnYs@Et6_Mu%+yhX5jwAnr}nz)68bQUKxB2~qT$MWV;ebgLUN z0ZoC#1SSra31pBP8Pp=d(7t0rp8wgx6p+=gDPaT?q4`}S#N8|%H4I>cMNFo}vuqI& zBX(x`_P>w)XPrI{fzP&IWhh6%>la`2hqrl{&&9eFoPXydKfC>8Tb+T3*RN3EFz~*S z+nu!oPgfZxq(`ANJneKYj{YthdO1%xUlfYxF+Iuf!>3NSh2{ry>P-AP2NCDb z#B(?~KU{PAsJZrYLMbLJVJrc`g~P7=u>nZOws#O=e{&en{eKRFYmQ|Y%N;?)C$Qn zBU1zm$8ykc?^I~-n@%gIu0Lst?%KqjwJGjl?}Ax;GI?+-k~w z90%q=5lkNVT^uhRL_~`SIP{Ha&BF`{Bh3Gv>D_4`P&kOk^H@23^hgEYxieWg4>B2s zZa+Npif){h?D~9o3x$5*u|y0);|9`dAYG2jr!LSXYT8&bp#1#7xpMTB{B!7`?%|Vnn;%$J&XQ6*Q!S+r;n44F4Z( z?*PKN;QTLdZ=|X}!R#$V)Act#sQbW##=Bn&FIVs8lcTFUj(4BF*Ih!63%AnM7&S-B8RtPEZx-G+y8I z=S+y=;TsPBa=cn|QD`d~-DRDf%!;YYB41F=Nk|=p_0Yck!Yhh&{@v>~^+7V!Em0Rt zj3>v;T(g+g1uHK@Xa#saqi=T`>}X25@d8 zkVqAct5_sh)4!UFlg+u-#{(EZBVBAdBekk~4!?}VtZq&$Rten~o3TVVBu(+Yc9W|7rjc+W5RL3~V93-#glmA^ zjcarn9kb{FKH7pdwOJONT3z68t-%65E$@BGS<`@uU#@hi#84Dn$n4gtW{V+R3~NJq zX6(8G^0x254)CTzi?@x{lDh;l4r09|gWYNPC6U1Pj`ERNkzBr}7KNF%jQ?);2SEaKW4-9gFlW(x&)7 zaQcxskUrjaLR;tZ{n0HH#T81#y?((8F|T1B7i;Uj>7kU`XDP|5*PIiWB|eD=NVTB@ zp{9Yf7~WEHUzu9wmhM@Uwv>{(pJ9?~>DZBQQsncdHTlURo_ZVrMAvdhDjl~V5MPX^ z`R^ko#Bel^!Wq2sw2v44Nk?->iRF)tqCr-iCn#OcTjPn{Iv&b7Rci29P#Q_YefmDO zm&rwQ1Mb_%!;SCR`aaG7535~M1QW`mD2{WXClbI-;hWrLjYOc;SPjT;IVaF&ruAn?LKY2d;@Mli8h!E|u7=8M17+E8~5a%w$4GkFxoF6c>{z$_5# z%aOxDgnh#`4xwX*0Xhh9lc4pJ+aD)*|KN5))-SJL-}~+@zrX!a5OMMTw_t)!jtA~P z-qR@lkdpl!tX>_iRC`i3@^bH`cvN4*)udh+x7mpS=HguJ`P~>NuPWpy3QS9P4fMBj0zQ_z6S| z|Hd}*xy$gt)qNKMf8S*#>V4mZ*1A7;2|4ZyN`cUMWe_QeK(np|%qsw~P)P8uWO{l& zH>6CUC%|Z^O?|ReyVm0xCaHHmWkS#(G0c)tXzHo{$N4xnkb;Qe*H;>*aDCin!RHO7 z3{%}d>(+Vr+%c=jK^Q#Q*qb7bHJ^~ZR0blbpN~y5&vcs3%{O%G0LH!Fa2C(Rff#gJ zds@X$>iznb&$nUdv9Axr1h>{9C7_K^BF03RzzrTKpUjmks|9B}tKeeaoBF+rY-4gy zci(EBWyx0|uM660x?Ga@(Uc@89-&p~$je4+gV6(kBbaFH;KEjh_r)Y_h+PQA?;3e_ zk;27(I1WQ*xHgl|fhR_GI*z%2V)OY6o7eNmCb1^iq(2ZTaz3OZ4~IsMik5*c*t_)N zc?S(#wMz%qudJY9h7uNt-DT`SX}|^+lEg4mf-CSXhNCH%;NFcvdEJ^{(Q?#Lc~9~U6tL&mScUFP$q&s z3oSI$yAD_Sw~oT($SC`nsOcNX!Ym0uji>sdSq6&MkE{9~%0gCyP}eTA$h!^#SFhzU z$9t^7+1EeYuHJg&F@1aj7=Rt=-v%b+`uNtfY#TF(2@qu5A2=YC?g1mPh#&4k0b*+F z2p%Z9-%J2wE};rVW+`}XPduL+wr#`nxygcC8vL1yyFwG)=m3>QpD!t>7+3;w%(p5!AC@>-!xkYhU6ex?<1IqWr{*V z0Htx7cC?49_s@ex39QCr1dikJksK`zkYL@$DB>tIEl}aj2uo; zA9rs)IMPCGqfxkZULCh#rkbS*Vu^@3ni>TF@d`)~Ku92N!V^@UcaH-S&m$;+00dN+ zuwBH`pympFS*8R=_T{%t&`OlhN&}aQmIX|-+`tKF$+!y3L~T_OdY?@DwhNHZN~Tnh z(}J3I_3LWBYM*hHA;^Tn5E~}hC|<-)0j#dC7~SW?@sm4Wx=y?ykRQ9`yeq?-&qlT| z$ykBuT?vQ(|7=J0hmqGrt(p;x>4DjOM@FHM+SoepS@ySCY@u8^?qX`QpVIwdplSp0t21fc;Z}r_;V*ck%P}1 zGiosPH?z$_{4>6!lI8#+T-XgRO*C~T!?mlmR&4u@=X1m3@xuXdqYcUc~ zce$1%!%a&~R_0cBCP1tZ+xFBs`NZ@2#Ih~|BG%P|Xx;TNXL!SDU#1|p#3t>oS`&b1 zYNc#E00;pQaUB?K5w#*pQw@Y3F%iPMHlM-6OjaYmB#fhK+>ciB!9De|B>&Jx(?KM` zPWU3z==?`+?_lC;W1y#WM{Jkl_&r!+Y>_liwMJoxdRJ2?{8E9Dw)~FLBZff4! zckH`p%C_gGKtk>-c|pw^YL<5~OJzkEfGO?}1)u>D4z)bG5I=dzr`u0ZgMYW1@hO0iBV#k>aMa1&Rl^<6MT-P*B*+tK z3AaYy=qS0&=s}5@%}bi=fbiF0I=R4Ntj&Q~o>&W#faVEI z#CaLteVN5}5N6L=V{~uw_j(_`TGgWGjX!{h>7P9xF|K{4DUIE?9ouum4+kU5GYc50?dJbmV%*ckd{t}wz2!<%Q)Gd~mWoA0;gK6&0WuDx8J zY)3lG@dYM)wdS34h>_s%U9SRZ>SVc|5=nxCoRD^4uL`(XEfSl|$sa#{;QRZ5Wm~bX zEB0EYJY=h6i_23Vr|cLfrS2jlZl>_IaCat#x-rua8^5YZSx0Oj83H1(w)MA|ox zifAc5N?-4~$aOMj&sbLt%AmKe{4-k^mz|}?NzKRc%Q*bu7V$^};?O)57wBZ5_dc@a z6wY|LDdSJ1X{$n%LZ_8q}7e z3sq^e(Q!51E6p&Uoco#K_Q{=}6SwKb{|1+PQa5!a#srYl_= zJP1K2By(ajhqqk{5Jt#P1<;FUqJX3${wN^Xhp8992sItv80yjqUwofy;x5Y-OFRpI zvruElgCz2cTklOHp!T<2oxy}ZdCIk3%R%-a>F-pVYZeLPkS7d+LOVN%u&WV7M61L^ z3Hm%_jYE?d3A0Fie}Ci0j~{qEHjRr|u&$EBUO+@f$`!dZN!*u{t}|gPmG*us&y1v* z`C6;kYZc+>sqRiYA+=Fb9x=o$kVA*R35IiLL`oj${7;dC(XGf1B8ceN`*c#Ad~g=1 zln+ghcP!t5K26u>b0;Hdnw8V@{-J(i(4e#ZI>05&L$(X%hwsOB3%j8}^ME`VpaZ}H zg}?hVy{*PZi2{<%@z?b6xShE!+6zPxuL5c!a3f#ef;nVuvbhW^C(B+5Dl;P|<<|t{ zZF7Z7t2?&+iO2IBKfZt9@4tUw-FI~fY--)mh3(3Mr8ZD%K}eHW3AXa0D?_Y(3>3uJ zh}IZYe`cBB2~6~{K{$)Q=pA{)pw>7XK!gPWZg@VQpq9K4%d%p}j!G3Z zRdA}k8HmB^uVoWh3OE^zI5uwYj5E0Lrw8IMfe3#XpMi-uzJ6y5Lgm?K-?h%4Z@sJU z{BA|xz5mmCT(y$y`&4{y!tBp<%|RC!oSK{x*ny|JAVOUr89)U2JaK}p&z!aDtCn_B zN}Z8+tHkuQuQ~8Z-*tj$Lh?DAIAc5gd7l23qj+y8>VEa2cqeku^!>3cLWYc69I&b>V6t~iZZtppDNDFe= zk*f+b8ITop#nZ!9Ku!rLr2~n*Ry?;2%X7i9WM5U6QoUC0&#fAS+wNi(EfM`M8phMu zaq~RsW1W29dgi2qRRRt);O+lz_C_Yo(|`%!+lt`x)XIX;?{PoXi?3>o!^?(@P2Lbu zP>gf+WM<9s$nj&|oE%T{;kLuEYb$Y9=?;>8J`BZE+NgqV$D)%I{bDx#iqW1~Lyy1pU{*y4rOB7S#LCB@#^`OGrqT)hV$c z)x_$~q&%w;h`J1K?NcnC0ab2nu^1Fhe4~c!Xo8QX_-Uer!6AcKkWsA_l`3}Hv0=lL zH>CPhw%YuF!n1g<^FM>L1E>6OQPW%0TbDIdT9sh2DKYho)ff!zX{JM}f zPd|Il@pxwFz6HTAlEYbOQRy#eJHtzVsp0yE2cbF$I+-NjcuGJf8jkPxJ8ri-*7YXA ze5G_DkLYDv9fg^*n@2(UlOZ&`(cFK6a4^65)z_~|-S2QfQAoFutkryQ4OiK>eIi_tpb=wND$zVv@fr0yc@y(FO9B#p45( zb^OirN-`cb0M#r0cx-rXJGM;(abNF&FPiIsey-?#ml3*<9R#w;RVXT)WJD9LG9-nfG6PHb}vs0WgPxUb{L5;zQz+&RiOlMj`2Pigc zl#b|YiZ7f35!4+F~$N%Rf7HzMajh;llsY_JKh7 zt}|a;po^XzGVbshm>3D}NQ~{W6mBLx;VZs(ucs(!ryU(6suF$E zPW#RCIO}x6M_8~*bs^L=hoP`j(~*M@9>7Fx4Xm*dAeumg2r&})DeFhbYRDN}3V~(tYM+TO>L-Xnj*F{-VPwFovcEA?_!FzEjpMm z03XGeVKfYayS6E_kGoU)Of>F)VspJ-v_V#={dqy(L{@5Dp`c}Ya^Z$q>&ICHwbG0kPsKg z$K!!bGq^QPOKW8x`Z`W9&TG6ox@}^a-|$pfoZ0MQ&2y zl@tH~AOJ~3K~zd8ad8%6@*oQa6i7hK8-V%<%d>%R2BL1}`LQ-}m_}dXRx2thcHXhI z4Y@wVY?1^>ES@a^NE$C;19upfJqKa8Dh-X*2hpnzywY~Rd+w*Ux6JBuX7*ET@3Inq zw08gA_EE9VKtwnm=u{Xn>~m-W5q8vxun9S@`;{;Dz-T#R#Q6d;KiVW3#*+P4bpQ2r z$Nhf8db?p+S1eJ(hghyFG3Kffqx64v|49c-Ou9cl8NfMOO0K?t5D{_g&+|4vIs$$2 z)X(2L^I;ncJ!{jOcbK&%jJK!~ogv_HymrAgGCFZ>XetyLEf=z1Yjanq^|oN!SFHPj z+q!_;0&o-er%WnvQnyIdRrBOa<#Q=`JT@%Lrt4RzU_%waF4b#{stb*FRv6bN>5`ep zkZ9u)IM8}K7vzNAkO+{>&zY7v{yjW0H14m^sq@2kA$3`$hk;=s!PtcH-IX5 zw=|+s9?LZ~Qk4hG_qCldPY}U4w^}RS*`^dAqX2X0u zHawrZ{2rTUZF@YPcs`zZD)_3ciG>hjnT82wq64nl% z@Yd;JkNt>z`~Bwh!i4CkT%35KD}?@l_|&P?IH08Em1dGyTG%Vo>(_f|D(jr}l%{(4 zGa~y_cqZB|qBSDc+1j+U)_MS;r2{iW(iogf_>a||J7)w7aR5!OR9b9Fv(~7g@{XN0 zQPX!VrKZ2~Xmoidn;1sfQ=vTV=#Txt#SeX9i3D(WTW?*;x!TTeHdAXfjA863$ z;?7$h7%Opg;jLiz?`)sdnugu!b}?R0@ADLRuOy8ys^g&k1uf?By-F;VfyCwQk_mFI z*%QVr8oh%1?S}jPhTCn$x~yW6D8)5|AC-=s&7IUcoS()~FXh!&I1uI&*CwMm{ltqx zPEz{^*MGlf-fxl44K&ZL&!iLZrZmAq&IM2qNw~F97$P?8IdW(GazUJPG>IYH-q*ueN9ecW@m0>;NYEcX*yWKQlVV zCQ{2&)!0LESwhruZ#%Ya#lBap>mu2S80yMIs+6cWrd*Koj_0<6 zwjHeC(A?O(T~g0Jl(X)A;k7IvVp$wOtm}%~T4YUyl68F8_+?4KYFQs^#p5aCYu8wU zS{tfcEY5pzl#OFscS;}UkIzXjN4HE={Urh@iBOlOanavw--|+CP_8o6WvV$C+_xQD z-h6J`>eiCvfWR!7bilzaYTxnHxYO@%O*8wwiS_28!0Y*R*Cq=fHz_m<{6}DWJbS3u z!8I!E_1b6+xZstSG6}~HI=k`w@!?7k$en18#B+RJ#|8(1Sr~jgoz09?*1GtVfe#z` zyI#pJL)T8)#`DKMVGw5%>SqL?aPOy|JFR4>ogcog-G6`kkO2>~>(#~%Cgd-hIG?n@ zJR{D&$J72rIh^sRP(>Im63c@1w&JGl0k?I*{kGzETXDNBSk@J#EWzja&F8|r9?zKo zds2;yp?f6A{o$z5aV^f(%l^xNc$5E@cq+eHW$*JW0PL;{x# zpB(B2fiN<{P^*}*aCGdCTT&iYmd38s8{Y0dP`E0k0 zmd0WKW;@&xr?*zE*FKyiv*4;V!i!Dbg&jl$S&lj&h#-QKRh1>%Dg$a_mT$WYRAfTB zB!km3b^u{jDY5_y`i!uF@2l8Z`Dkj5?#kq6Xg*_g3TJFGwT8+~UnJPFn!)Nl1q+c4!WEI4i%xMA}^Y#u*{QAwOFF5{9*H>Rnnd1a`F}()C9dL#QlB~OT_Jl+geo1 zSKM8oI@E1!#V_;ttnBQ+a zG|Z4$8d{Dg0dyDFpZ~acmbfM49ff9g0k-$YP+MgrkR?=60xfm+x*=VCFc>8 zGIFU{mMV+ZJvNl`M9vu&fY*YiwM`0=*izmGdZovf*s;b-Sa+LS$;pt8P1>7A+s2wY zw9|1wo|W>X;r%lXAx02kefrTh5q_%}PuJ`Q6FAx!kZkLTY|kB~WZZ5$>R!=m1(=aY z;vveCQCqN9l4Ry;ZBf>rK$I0kY)DzaAwl}THO5{WQrbQE7=T+O3`AsgX(|CkjPVh2 zT#CeQ)K;-G)E%#3-AH! zKuEjxHFl0ghyt@5n^(D66$}uhw1*fIi;E-FoRG7{i(s%gS|-fL;~^=Z|Nh30AK%!X zdv|A2AQ{_BXg?jrxyvmQRTFNzl-J3t#fe$Hr$(6?Dc*6o{gSPo%WtPeK78f)?ZXux z13JG4df`MGGr#<~Ie)&fXAK(VF}F*Qxi*onuQrg0VQ+#44}c&p^c?HJ3F4L1bTBKJ z5YHsFW;3g?!IUxqOt88(`D?8nM819mWnB&RV3X;aG1T$gao~8Pc>q(z&K1N0B3M_; zLska1WE3iBw9CrbI%`Pkq?EhH zdaL5*loP0?0d#lD6FSU+fyG4hV{d7i`%~XX{Y>Wr9fWcCd+d{OZWG3SJ>4jly9*Gp z{oC+&CnG$)=k(>DY|7MO8s^qeQ^mHC1H^4xQB{z%VEIx?4^oD?=_F(ZmPIO`$bi7o zK?G$m6RKJwvVu{mrMOJ>*oYKpRl!o0ZjD$2n7FN2mx5fx+Df~mU&S6k(YC8g)7D*e zT+3d&U_1bX*qk(-9wZP%N^EC(fAtJxLyUyhniKhb7JGEPje>P!b4?QqVNxLB>vg3b z7nf^At65yV+>&7cB&;3t;~Rhf_!~d|{uWEbbJLiJxB%VUPTikl9C~N9kvork*Z3ff ze@8-Tyb|*q4n^rj>Pmuv&R&#{PR<>GkJa_4BnAdfvN^@4?S0TtWTt)x$A3DOEd9B)v<6#uqGzexWSMFLny!;= z!3a7aX&}nS7zsNYuMAUJCq?6my;Y#@vT`00s7dO%jDkXotbE-nnyCuHV4KI4H^?Bg zcvHRj`=8j}0fyJ#|Cu<6ckeSIc$B(~lb(Tz|HAgB%J17GNERp6{A}X`V=-;7`S7;Z zVEOm^eS=ifOHAmCI;Nx=Ct(&7DIGS`5HH2zB34bodBgpF$Jf`F23{u(Y$Q+PN$T3v zv)u%fIZ@C|EAyfxxucc(I4v;He8r@x3liDhM+t*j`HWfzpHJ(YzIatEpDmh}kW)rW zj3JkL5Fy1vX~B>k==u9{c&EB!#I%(|@uHi7T1aD=B3Cg2E8poEUI6&{IJST;Fr@gM zQJTHnyh&*~R>mF8`9^0Wh%@2Z-qXPntQg=NW#!qPXp>qze(t8uB6<~A?0*Na@b1BcplGf9}N|gXwq8jF@3gz0k z=00RrfqmbF?&OTjN|$m*0YR)04JlPG7eF19R*TChvZz`W0mp)>7qvnZb7@-TXYpKq zZdp*)>@+aW7jvBwf!KnHB}T#mzpJ_M#q3do_J3+?-(E8T8=D5;Itt%T)_~A?{6&Z?Q~ln^*Y3hmz^(J`r{ruc<`p7ac})0 zeXR=hiC$kRt6wRSPOn^%{Q;zfZ=H#ehjWT@2)&=p=RfrOm_3pmM06O@>(l{-isE{) z96KT$F#wj;7Fi>(StF3ROHVL!kjtc)I?4YfB(!h`1ymQz`Xt&8P7SSAv|ZMlsJh++ zCkAImqTIDT);`n$QLK_#q+Q5&WPm(?d7qYZzO5H zI6jo=A4V82@!f|Y;^oWFj>prTk;sCIW}e)pj2r7YsUlngK!aqKQvo#~Cf(6`%yT5p=oM*?fb z-*)%l#=SN-z1P-y$(+DO;*Sn+ZY#dNzVP*R!~Nd#sY$tY0+^YtA$C!_==( zK~xsClGvFW?%OU4UNM7mavy2a;Fa6foeBE>ik0NH|pQ_?-TwQXIs-@fj+-&U+~%@hR%OzeVKDG9A* zSWKG%LJ7SS*OBb=BIEfiKGsg@gVwoc9g_W`W8cp$=3TJe$91|^vZ(jyO#TK(s9!}qtko{5GH+jA55qg()08W?Edxr}SYT322584m7j z3<;ntx{7+y0Q?Xe;VzfjUmAA<6~s+Q-z%$2QytuzHg{>--Brh87XnejNI$z|^^%>$ z!3S;E@M{hxnga^}5kOBxyB=det!c%Igq0UymX)FwA zH3Ao&&c_iF#ODxI=5|_T)ZN-27^OuzKcEfF5JhNd0FeN9Y zGYjrY@1cBpuT3p{ZTL0YPva(9fO>Fph~EwEf7nh0Odi1AET{J#<&&$QZvNQ-4(4l} z1082nky=d!J)0B_nm@Xm(4$Xp@7)d#h@(k~T-d=}82<)4kZ91rtE8PsJ9gTUu>l$2 z1|-#>8q+q$JY?GhF~oOY_!%I@FaLb|J{p1R`D?-yGpkyBMQnE+&rJjVw&#XNmNiVk$^_~@1QWI< z0uPXpkU^Q8P%dgsxGT{SLYZX|qLcdBQA$ZOoZQ0Cgs6<1^03g+6oc{<`6QU$NenF=ejSQJ$5wnCAW| zWz1OD-P>o|&8OS4u!ztR^XexTVoi&k@O5ADb-&^3e#8As8Szq37R!8NZDp3FATQ~0 z(scmD=7XR{XAM)?-`wr9!jx=u4sE+eWzZ=NADdDU>;ue)~TMJrUz^#J7 z$cgZL6g-!V?YW0C=uf3A6HtBKfnva~gNSu0`1xV zt(uT)?k;g}nX+Pf*iF}IAZ_c0=eoJTFXJ@31%grnB_L%&K}O@n1GWW3$lNgZ8~_f+ zvSw?tbis>$V^zUZR!TRQ%MK)JZMwi(#imM)O~7YBMLiql z`(z&U)u1INfgN~LivWUE!HS@O3cvVq?tI4rts7PB&T@J{yk$f)nqtZcE4ElbNZas4 zo{II43WB*koRyDjyCfn|CX|rIw`UGi>(aVt#=rn1!k9O@mmHWt$A4FfB&Ac!QgB;W z4+s~*K4V>$;F_g%Z^2u@S|KqK8GwK)x&%n9>w>@j`oh=Om!wJe6zNKrAq%^fESCS< zTG84HFguMEo+xtYzIRX&<8>Tx1`Dve-<=?bC}|!}4x(`!NH%8K$1m$WXQ1Mf?F!VK zLDQ4s`Bwa8!%Be4W(F|9KqF7h#-_%we|tqS zz%GLNw!4OiQ~(oUA+Ca))DK$SuWkZ-*4r91vmJPJFoD2SdU-6(tq^D#(*}Z;WpOtL z`w@09@3JbV_FpO4Q{>vBYZBTlTbE2*ZPp8Q ziSpE7TOh8aP`vJ@Ax0l1>T+}v`?YVigVbjzND^L+pl9YmZ3TF)H!J?C=_VM30T1uC@KUKhP8}IQhBg(d5Go4Yd-0+C?j7w}j@Lr~0zfLe1nGED~1dGm-CIL-bosV@|MD(37To zR`)csF3o9tZ>uY~BrZl>o{|dmAeaNM&j42*DSuoFZnx%|d$Hn+!p7oNOi?rjo=XNT z3kOVzRZ-A?%d$+#No1b-f~|qC2@PBRA9?S(CON7r3Q9O4tJmK1{;#?!BWyH3&>dkr zvZ~L_H$!(;*qDnDLKhIA<5A?1-lei1uq&^Z_c7TvRw(!xQE7CnzOjB?TD0qashsmA zHX06ds;f}xskOo2|D6pC2@gF|RZEpt@JtcGV9K&0!GC^r!XFchTo$_X#Jt-@SUt!n z2&)}^3^+WX!#<1&7{&w;0Ca@M#?~nNwqn~rX3>=MkAm${r`9S&3VI##3cEsHrEOLu zX+Fvct;9KC_1!;H_|dwi29V;tuzl`@6>UzPB^+oyI%d__7kNhT1?0bU z*9=FS)!X@?j^WbO`>uY%|NQfdXHmMFv2U<7nPs)hyne9}(OMhtUk})i?f{s_1M-T& z_!~;5{XXVB362$*Cq;DCkqZ6n|8OH1KFROL5a5sZ4zISsu^+k-P)>gFv&N6-rk7ql zA7fLcC{_rD-`{W8wimSa1^_;i@*p^H?DYZw zcx*%9{rY;suYbP65xKv9*%6e#^z;}}-cctd0vzDn!=6uvuLE9>9UhMZUaw>Lmbc-; zGYl?MR)^6g%GJj3nX)V=Z~0m5hT@M8X{8m^^+0CyI(-c_pz(!Z&j&oepYZ$p1>55r zet!=hIgYa&!Z4S)8c&#CcpS;*(8tz*o*NK70Ab9miUIw4zTowI!1wnC-`i`<%o6~y z>)hD(#(5r%??z#x!5LY@b%Nc8^!QL-kw7s3nO+D09%$|pymHnyGv>^Y7@Lrv&z%hk zfE5El1h)!V|LINAj|R39XB*BDO<{a~J%;k8M#KZYzTT>^=&D;@^*Rn{#{tLD;5c@L z(<{SAKLB=8qunmC+u`f$Z5yEZSk~tksc|afP876kM2yJ@tIr$A{!+TlDaP{Gn(e)i z8Rmmsn+|bpdizz0VNBS}ubpBf^ypnAU2o}|8V;#fRkSBJ6mxAFyq$Qa8F^nE;n0bO z0fFj*R;@?_U0|3><8?-Ke^40Sx#w4jRfoS=yJamorE~5@X0XdGgQ!>@jnz#gloEs}@xnQfR43qGV=kuvXp*LXO??a8KLssO}xEr*C z4PX<)VH>|2uc!?};xV}+3g6I`5w~J58k|nPF&uh(_+z){ZSeeKKj3Hw?5zPF2jFqQ zp6DsyJatQ{!Z@OpeF@fC1ZGh9xa*K9W0k80b9QW!_Xj$V9E@g7%Tj~&!Bg)xzh6#}#BwUh1`5t{jovM?G$i)Woxz#keDX9n)7F!gnaaGx0w z=i!DCq44~H5s_*`|BX9Oj@bjU{Sy1W@lC#)o_GV`eX}>{eb6NGQuXuk0Q5|9f5QIj zOI-uJ#hP2RwQ(HdhBn*R+Jk>>v##H?>susB!L|_)4WH-%M}z0rV3P0m4$s#Pug9DH zs>f})t!=Px2gs(<$3s>IHm5voI?Vyu@EQN-z=1QhEz@;`t@tL4vjqG)~(+#QOZuRx#**A_;*QVwS8;rCr7ks^+u>bl6|FF^`Z~y?iV>Q?a zb#>|a+~7DKyaH>oN7{=rsnN`!813_`r(#He(&Lehh<#U=Jh@O!R$}Cyl&~V<u>tB{DFEz4mm$@Y;-6Re#i$^eodtVuy#pT2CMzCCxgxM~@!a8SKgNWS7`Lw-UXNq&j`t1?57^rd`)>Lz=!AG5Bl3>MUUe10v_Hbu-7RH| zyABmN;Y8R3TGmXmF#+IRn?kf%@@hnM8n@p0RS6w%6%aW6A~Znso2^}auB@@V*ma+T ztVL|F!$BKhcP>#<61GXn7a=_Oq_^G7=Pn>k5^F*H%s+9?I2-A_dCvdmW3}zNJ@KmB+;DE z4;W(vFqSHXAshhvj_`iV4Ed&pfUZ0|#!OP@ei0WL05dX<{@_ighZ%vDL8S0B0AK+O zCWz%Zx(XFD2FOYpY--pX$54D^X8Qfw;rZO*`FOzhYuqv~Lcg_x8FMoQJ>39&K!d+s z@o+QkdJJTw??ZXX8#97+Sv zZLEm=^Xm)#^PgYvKmWtW<^E^5Gd#^CavHHx)3XbBA`^{}Wf4_HlJl^nl?67SQ zXzdM%Z)ms!;BW_%Tgc7r%Ql}rpHJSXKVW$9X8p(3;3=?#P1d0Ll2=Fvju?-kobqP* zuYJHKOZY_Noc{NIKznUED?E>a_1N&kT;4(Zb>o$Y#>@O;rhm9L4IGPce(VRl-`j9Q z;?l;7#KtQUU+|y*`~&~{zyBF~NZ1JUE;Q;&qY5l5R1E;JL2n4H4+B~@m_N3zZX?@v zu#swRX;+2>0H_<>)3402G5C0z8V!Z!@pZR0x! z-ogV|k)(0?pH3i=DPQCHfPLHH#VcLU*8_fi?ePBfr7klAj;Fd~h*AqU#&+kEy!=IQ z;sT<)C;T;)!9%faAPVkSNt798=i0=6=fik<>uQ7^TT2vu<}=*}MP}yncP7@tszhfu zYdxF*com}YiUjiJ>A2}yb&JWcV3m(RjiJu{CUwq0kv^BxJ|k>f9_d4oYz!fllKGleRHQ6%6=$w!LtJpgx?SP?C^LD8Tr)*EU)J=CfZ&* zym<0qv~>f-U1cS}Ta8263kir}4@wSaHiqbXcEhyvQ(YPXKv zc{4SC0|0m+1Bnc!*bdRE<_2{%LqZIQaHPb@Bknc9hzLxDK_CRbIa~Hzs1X5&{YS@G zk>KNKQSvgAYMlT!+ZflR6H(~aS>ditz7y2)5^3pt@4aG<4!v0o7A0O*rV71v4#|MP z0FWa!2ePi<@CWp+MsgdUAP71IQZ~%y5Vvx_Y4kcl=y^k59Z5tCCZQxY)Nc{T86jC!Le(`J>>aPfL zR2TpdHz018&Q7x5>-&AcxP2jDALshTz+|7eD;-|8jhJYjzf=|AcVDJ zO=%T(CbHXj_v27Sn*d-xI=uEB9kGt9QzkxSe+7WZ&;m&>FH(SeosQuVg){)nS$m&$q zuD<9|D*G%eV`4HQWIXYh8mkdl+f?E|2k~cMO$*R|*)Gujd2)VLtkQ{qO(Ss>DBE(P)N( z*E>=OhJ>RTgpCa-g8qEi9b=69WAAY6LLc+#cw#V&i5Y~)gWqLe-X<&d?nv?$`Nr6T zwlV(QMtk0y@qF&^e2#JW*ml_3J|^36T-F$jdKkBlx88Z*uIa#^8WW=1DM96n}CUM0HWQ?t*PVB zbvDTo(WtY-xNl;(H#I;S%7z#ytu^SaLGKM3bwFx-q?sQn=OG}AoDCt-ZW7y5o( z&(xW|nCdxasNT==-wmG_9IO0ZON8qAPs86SYmhsyi%dlhy6-~xX6eF#;(v*HUi$0x z)W7GqEcd>6HDU%Gol<=TWS8o}{6dGaV7ICwg8DNz|J;&spT~7GN^iSs`{xvZZe!Jps?yO4+jSy#P1xITqSlHe}pb zF&_(&`h8?6qsTOHeX`yI3TD}uxYqnGMr;|<%?Yh-|+Rd z!{fOt?ui|-n?m??tcQ7IcfE(8CjssI z?)Hhi$7IR#ttb77>svlG$j#-l!L`D}HI4xMnDwr+?x=BY5D~$#paxH>ls!O6$Fn3p!GgQV8P;gufXwyM1!4JsTw3{N_BS~3_`82Fq9)`Cv z)1pF^_Zd%%%p-|s{Ih1%XAa7tU4Pf)~p40Gt&)P(eI~ zp2f>%NMWvGOrUI(tPtYrJr1%N!1oR>z5wd`HJ;!5p{_RLTz(c@?5F+SpUxLN(fJu6 zoRE_lJSGI>M5*uJ<0jW{zU}tC?_ne6Xw#tz!04OdF4d{qakknAf|?m1a&53#y>Z_C z_v;Pc-~6W+XNfC@ooOy^5eFX`yzftVzaM%uVw1jW?m3dodLASHIYr{=9e)4!H~jba zZ}|P+Z}|Rx>k+JSgy`^5H>K(O^@iu~@8NEM2(Pys6S{>uOIX5~VWpqOodxgr8~*$I z1^@m1d#q5n`!2>`2k4FaZJaXo{Qic=W2|r-a%`>kRgH`Ii~25qcGRfb-0SWm(IYm? z5=W4k&W&e4Wn;V?C;)+8d{_?#f2kF9(tS&>*I{GvCGUJJs#Cf}*$ys01mI7vmxXEs zxvAOs*Kis9R@cN%1TWspvoSG71Hzh9s*fo3k6&*{dx_0 zku&?d(>+2@AVA`)5~A!C`HT+7`B%ywbf|kt-ea{=ZsdmTJdc-(6s|zd?FPoE7*0#rs50M#)@xG7Ey}y5d!}s?~jTbp8+cu&* zDn>Re&||TtM{jV;{X%vZNn`#uHQ?Ju4N1*+RJVX)yd@#CAS&dMFl-*@AnnY?`83wu}ux9VcVL&yutj-?61R zy8=h!CfQw;7d?@PH(l@hp&QAMV{=OJgO&R?$Ze#V?$%^jEVEaEac0Wo0pG8;3DKAM zPur$M0G{pSevxBc?G&z~psLwmjBPN324F0+2SLKmf;%~PUyKMjGI-w~yhQ#mqXEQt zAe+a*G$*h?s;5d3dh&iyA4b>rH~jbaH@sdiJw{V55)*^>=t9RY_^o#i0K8sff14g}@CaAqH7F zHXYA@{`TUD77`8HMov2oD!Mzaa57(xHuo{IqGp?{UrvefV^qeT%-oA19rq7_D$#08 zfbg%bGFJ3E?Sj6 zVz1Y`)-zm@D_TFxlMRZovQrxoVn~QFAO6^&&ZKNEGN6;q05UW7i~3UMbjIGIrENlg3~8k_Dw$ikD$e^>`2G$iP{bSuOt zt`x*);W{HiX8OrsG?ykm{iJQsTZgT6=vxQuwj$ABgGLYjmDLHpWD7TF-7TMWac=_M zXpIEA8i8#b#np}j@+cDVAao)Mcs|-!*-Xffwj>623Pj!c5Ie50{=E^QWde*MFjoC0x8SNvi?|!`2`c+>*eNtygJa*| z{d~atwdp2PbSDf6S})jA!mWSF+SPcMOMqVQ9e)4!HH7s`&Y15y3j_crh`(7Gpm96t z*L#Q8>k+ENi37xt1)$90t5DfZzzF`vip>H2*xBIP;PJAv^dIiT5Ck?N!1oz34jtbp za8el(5_eG74eH;oq1=R7QdXQgvTwS_7Yt)qZ;o~fauo`_9@LN!7m?Qvzkh$jZ&eoe zIBVBIH~#-_uR%*RR?Fn1m8!D2_fTzLH9XuH@W+6HO?*X#S z>;bL%T#wTb7!<#a(hLe>rEAdX_qQ`Lb(PU6dMkkvWVkmHVh5o6F0kjZEt4d2A{GJY zid{U7OI)_ieTInO^?HrJ@0S|xeu5)$WBzq|3dNOxw!H!6i0e+!u&L2FRzrDJ*41P8 zEX@5dheC%Ta&YYMesA#o{bGHSV1MuM{d^C;?~J%JMP-)cHLXy3CK`Mwk6FKWMJ~i_ z>S{JlYZ7B$*W?JMU&FqaTf$paQ3Shq^w3T4eq7omuFf4#j5>f?k@#WAs}kiZMXoN; z!b0Z(Rr{C4l<7G%p(sI3a7Qm}7<> zHmYJF^pW`a;_D4!WbVfSulF0io-Y>80)~U*VkXC42XU(50MUpTvuw^_D4tD?f{G~I za=Hl7&Wa4rrpbkLZ5*xnehj5pPd#FRqJ{+es^+mF&(T=V!56|xAiFy3`vEU@DSCbH zEJSTtAHWO=IcBo=p^(1#=4ge7qPjW5Is47a-ijzdx(bnsDCEQ+F&z9xT7Nge$mS|=eIh4B z$#3J!0`npUhG>v?q;n0%kepplm| zBE~HA8^Wb@fhK3zPZ*5iBK(27-I-^&{VmqE%HrGOl#)MKagRoX9px&@`o149c)6cs z+3lEN@xgC0VQMQ9V*-Zvd%WK8+RcT}d?G*4VBvAdY>>Kn9DGt1=$$cgPl722!&PJB%iavXg%ROau(%Nu z{mQxg2Os0B%kGS~aUAEaMByiC#zZnChG8SKW;^@T z+lquL3;=-dK~LkPlwD`3MR__4p=YxqaG0UG^Qw)&b9B3=7jdjQz0kq+-pv3LW5&^o z2|KU!3+*5aSjDU=uzHMWmlIm#?uAs0b%MqzS)lD{vGD;@rc`QSNJPb)fG=3=-6VP=dsLivc7Kx< z7P+e@?)g{;S4UFJPjhJ>`uw&cG3Z40D(uGZ(D+<@9w+$81kB;a+@Y>b46lMo3bPm) zqO9+50Kl&FsuLqDf27~!7V!NY@0+Oo7;Fp}nR;Bwv)oxhj*kwwJZ%I%>ceb*PtPlZ z({v%}6C0Z%r~I!>`ie238?K!pVdW5r+!6hiJVMaZvK#1t>hg9R>|U?@o=jf4gB-$2 ztLkv)G?^vQd6-kt`cq7_8Xi18?`U?u7{SsbGXX@1mtd$;ZI{p~f<)+AZje)#bk}_I zM<@;fH!d*3unMusY6NVofDC{0;nE?742#rC68v$DjY%@di46`r$65sT zfVzpm3;ke5gjedv`!%YCzz6Q8t=y^~p$I(5;J9sG7LyeVXCd)V8k8R!3toi%JAnep z-3gzh{h%ao#0eK+yr1>!WE`?&9H)uwgV`U)I1bd^^6HO%)BXm>tWpJ@83ah&k!q@D z%F)N#u6aMixgp``jAlmd{cQ)#W=wb`LuOImMOlVJQ7o$q1A{^ezD|n2f=>sG z=K%qFXGDnNrWbgLQrev_b(fQ#NG}%E{Rrt^jk6U{Uw`-&m=aCNEVL-gdLR%H><5@K z#WSBGNBq8}pag(X7Wi?cNM;`E@#JKY8MF+0!m$*UpXDSYH(?L)_`Ot!dyfh^h9^-T zm8R6l_p`C?YDD;p)QKT08Nzp~Oua6s!F4s3vJS3_Ysy$)nt8%|V-^nc=_#qEgP zE^2n8JETwEW1{LkEUu@~H!h)4|e51fG-l>qWQ3>I%t#e+4d ze2kQm^vp7qD<&Be*?C{SD%T;lNT5lVM-E727ugVYt@f{44Gg%Jqg&oh>4vP5DMiZAo~o; z9*G9jNLM5p0p9`9f=iPa5{-tDK^=KdHZ#ah&<_CGY1kNirrjZ{5!(*ivB7bS!GGw0 zhvEK2vYF8sBqG}7VJujn2i3wMf7Cb6pw>$Auno{z6%I#Ez^Rb-%A}LZGFYq}SC%&> zlwd0u?*vaB|3>hXcLm4a34xJiWk{P#r%fla#FAXZ0`Z9)M>_y^FK9r2y<#lFHX0HX z36ojxu?^(`OWay%xq1QK91YRdnPG+Hh(|nvtDnXB`Z#j$9A=Hk#Exa+3XZ zK91TppId!I2P?%L+ItU*ktw92Ic69c<}~=J&*5#1A$X;l#8j12iMy5uZ~%XsaGmYwQ@XM@`&OT6cp=AKVBnL zWF;!SdBQW-IZ;N(?DGNp?%}8uPgihmgQmk6uW_-TVjCPi0_iG|^syh;@i)gu1={oN zDX79|O&Y^t2>)Zw0m5@lUvm0|;w<)y=t#s`m2DD<~L|ex{Hn&T!I9)aZV6Mh6^>;PN;nP!&s_ zBnU8>k(3RI$kdrR%QFD@jbyz8Aa)=^7L4Ao<4jz4SS9gI!}RMKt;VEN0=RhzuR(=! zrObUIB?kc+86uhtsg8NW^=o8nTl-G{~B)b^Z z-yC2p-wX&K-&-DoQ3;rg373ziE+A7P9KZ?(I_1F0z)Go~TN?%ogAcka^UAn+(?#hz_8a)$zb* zqfdBSFdW?YH0~|`dfK42RJ?`@2Gen_H-CE)(6xJsrf^e zCPPB%@xSuo2{DkiVmW0}ULI$b#wkm-w?Q`}@;(XbgE)F8z&=jL!Hob9xmgm~6c`;T z{*1_{Er_*AM6gjGD;}Fu61L%9)k2E^Oo$63s(Z^D6cN1>))K~M6d4nri6sOCB|Jcn zeSc$OonH+XT&20su~#)1ko=_WDp~4WLQq=bpu4Bc#B!w{0|UK~OvVsgE(92UbUm>_ z3iu3yf=CrKOK!&qI~M2aodBtW-dui_*hA|i*p%MG;kiqssVw*<5&`1AL8(uKZct>1 z|M$N$Jm}gv1cbF&nm~L)0$Gl_RV0F$SXhVj1M=S>nLcsde-7-Ak6vH@2aDoagJr9?N z57Jt+PlKZ2!4fIw>C(gM+pLH%uH(n8A8zRTw7}bhpF}HuCfdGIO7BmZv9^ZU*{ClD zVH6a-)Yk%s@HuG@#m^32|L$Hew=K0CXPiW~GV@HIDzb!$c#AfrXabmK%(F5B24mpW zl8Y#$8PCGMM<>VuDsl%`fYhzh%vy&1`uk24Hl{gL-j(1dH_pkm2Yo3LH`l+?P{4l| zy3gZclG7nqS^h<@StVsu7_^Xe9dTb%{?2?WuJGAvtk(@gr}OX>gGt-zsuz5d*6aJy zGYxrCnqMBjz@;Bu& z2tH_MkjVG)t&TX2FwAX;Usm)5kf$e-zB`rcU4Z5~ot}b)5Cu>p0=&|iU_uZ9;>NKP zPSKFaaZy()bdZ3LdQ>@H=vH1r9iiAHdYJL}`7RP>#L~=j3~x->H|rN&-J$4m=Xrme zg+1d72-(mOI*3YeYNcmWnBoNzSFD_}7Pjnpg@W`c&rK_p1D>&ExAG= zGdyyn)fA5v^-Fln(^J*F2g1F{+zU17syi$3}RDe%nnBh{|P;}%n6(uMzwtWuO8RxK zoTi>&+`~3&9_tkZ$ItY)qKvt<%Yds?&N$GHF&g!=JRu#T>1b>NczJ^mRwQDzo)FaU zOp#J;P4z@jAOpdcoY3Dh(O{zn4_%SqWB$l?%fp6dOtc{>%!(RD1NH-82VJ4)^svoG z+GIN=r2!vb<{9xw5sZlyej@wySYHG;&IW--0W>}&XJt)m3?5ypx;7e>}a_RA6ffuFMjH{n%kEXO42gOSPwwA0*!~;*^fB{^=D>K-r1uBykA)y)`x^i^RaO7d3UgJ#! zyYKTfMk8>k&2y=1aTl=}dcCBvP*eGK9WwnO%pDcQSfNsA9L9g*_o-1ST~KU{W*pY_ zejoo#jvs2jOWr`9IPwG^3>7>M4qt$ir%s0D)~W71oeqRv9?$();NeWM%Jed-bhw`~ z;?x}(1V8?-IQPsSRt4A3uA5T15#~Ew>|T7F(hTV^yafQA4(UqbatMs4yWDx~>Kj>g z(Z-5A&Wl4YJ<4`r;$gl`j%JBmdDb8od%sM;4dGB4PR2(ReRHhpEz0m=>^j5C_ z6BNiQ#lsXK$W$;y4hwQ|DUt*wz8WSm@*h(Qc?zCXi^qr6crK0BAEf_26L%&xI9w0 z9aony$>{`+na#LvWNrPN%xHQGY;nb}ugWSOGmPFPpknl;-6f>xx$ZJt3um{GUk}{y zSg^q`J&u;j%_QXYIh~nJkd(wRDU9f%-BGWS%iULBDIFD)bRHFJJx5yOeNQMeNtl$D zvcO4^aq+}`BC~Co&?T8FPv~IqZ8xDB6~%}j#YvDkUI=AjWWdlwpasLPHdVz^a!#jg z`MU+ccrL)Aqh`cjiE4TrrI+V!zI0}CsU!z4`qnxAi}pN0K~Ykw5#ev)q z+n**LT!o?WS#L6jqdb-;)M zrbfk>UDx|ZByA`#vr)&|DQ^M?2n^C?%l@>pK#M|XZo5yt3ZB8t)NFclp$J^P131Hh zaVP>qtHMx+U!4Gra}@*-XTcIyV@hd;>0^L4y@k#&6ckxYrd-gQlSiN%{5~9=mB@*u zJ4Hl|t~J00rytwW3qktEUlvkxnB#I+jI2Wj=`(=2wmF^|SE48)(YJFlB0Q|VAFbdk zUUSv1Pd=}Mhr-%36_**nkAl&Er62;xn2-G)T>-3yiWux>Gx-|OZ&gBgQ0xU5${6Ctu&Z=V3e} z=wvj{u9N%bb&hh61dRSFT$@}6G6O-Nz?aLW(W230?0x*j)ri&_n-B8eL!s=CK2{_S z92*=q7^@P{p#vYm1>*n4*@yu92CWTaLMld-3rl#THy&eCH-96L-TL5UkD3e6!5LB{ zbc&&!!jqKvD$cLz@~}$FX!D~h#j$`i=zJ*0nse9q2@8ra()2NwJKom3&JQI0C&jsx zQ!}e}&og8)6z&em8V)%Pg7jH@$;IGArp1v*q-$hHK}T}~QOl@|2N12}-5rbEs z`AcBpNjHgs0%s6`?*&&Z3uEL8eN!L$h6BXitd_x#ui5NP6$IKz-!jji23aLebK3Ee z1p|_!?I4>XQxBZgk%v|rX2VA0Qn)XOICEbchnW7P{Kbwbf?6q@aO|0slah%nD7?)u zhjilCEYARDc;-w5HW{Hf#el;=8<;TaX)cj~jnOlX;pD+d8_&bJawacUMPU@rV4Z?} zMN5?0Gmn0pb+BAUX4X^sPjHol;bOl?#F=;ZvQ9Odf#s6;%un#xq|p4Os@=n9!vF(~ z#yq)%Nat>r8!A=~G*?5GI44fc2t#0A-4Z&6y^lksrQ3RmUcsO3^Rx^!3LrxK3W z5S-MB_9IMNbrf5M)Dt#PHZM{n2oQ!U&!nSphRrKLCI|cmCr?H}19C1wRolZ1{Um)7 zot9LL%7?>BN~zSuyd%yvNQ$5OHIK%s5_IqRcLh)t7U_aeG9b-(bG$*&ug~a;ApPdJ z>I{MFx9TX#;I4f#211>nM_uS2I$TXfd0JJ0X%!E}D3z0^ri-?f>z|cE=%%)V0^wG# zrY#Cm2}A`TuIgdzBu{$^WTySIU4WuIRx-BD5jnuHqJXl+7yy75@F>ibF;} z{ZaOLJEt#ERibeL8$7E9AuD4Nf*yj9h4Kg zy8Wb*?*m$nw^^C+F5OovMo~u8!7Kezyvoy0pJ4x zp#fqC%YramLo8^Iu`3GNn;zgN*oxhJ*!<@T=XI&bG{kj~~~z$AI*=g;(zl(~lb z+p6v|Z6LIi2JKmyxH5T9iwx7$XQ`#hMGIGgD}m_oGckO|l^!SPVb98sYfr4`CehHk zXQxu8x(Bz6zN8oRW`#le2vfJ|cj=!r17;S<1X~a-1z{?$Ch4zO4hawU%7zmNm7tXf zzo$&op0l-pvrAq>f(xf&rML)Efp9+t&^i;I+SdF1kW!}ke>PXzg>REC$BB=AF zamP5K6?=n&I$$4)Jh4Hcw`hwT!?9{X?2aTxMDHDt9gT*fgd-~ubi%N)m-L$Y1CG|9 z?QdH_pm8(g);nz52CxwTJXpw%fhS@!pJn1ZU?vbuam6q=(Z~K4f%$Ny0x7IlV{ZYR z7=bZ+T#_sq|KE@)C1^EExsTh(`j!lxf9HdcV^3B~=buyD!>?zspF-0*TR!W3`+hizKW2+$x;Jx ztXiS))>V5r`Mi@dRHohK>hpT9Um3~eWY?2YK`-iza7L*r)lo{HLoMiH4s#Q<__(5S1UgJNDu zS=U{Cna#*bTF!JX#zZ|+?Fj0YERu9HRpImi6CIwGTjgKnD`{UMD3VqHC%gSdCN&ou z2V5l!Fy%0&X(Eb>REvTld>BW^dc>?wgs7DXySp zTRwDF(IuSgmL#G3%KY-||EfrU&!GsWm1*&>f zX-FZ8QXY#_WO~G=@HYu8gLaEo{|Y69E$0;yJ?w3r3bW@RUF0tZ%J;TZX6$`9X@(m03J0P&P{(VOIc7Q-|P zr5c7s%CI!OfI%1~IQ0bQvO`Fhb!u+{<|SV0a4B`D6a*e>{1(P&rf zXCbvmvF(nvF8j#g*WzkrwX(@3q3FxF>qqthSGnF~Y~QDSQn%}}&w`UJfrnLmZpPVa++9%Yk9EEKc{~sI ze-TPskIH*(Ob_uSAiUFK=aI$6Y(UuImPwzPegS|t>&a?_84<^Ez`h^DwTahE4(f2g zSefX+?oDpfHX@(0)DUPRXao#PgJDPGR6dpg?fU;i}&Ho9q`w}okD-gtmc|9yq(qY=f=d9@RV9V zMk}T003%DR%DAY?{FuOep}FbVj04_u6RjN zslNG>QY3cr(4k;P_}s8;A3#_EIcvuH5-oU~p9&!Tb6%0#_$}2PyRq>Tod8@vdrHzp{l}e4V z5!c5HCAb{oRoW%uGXJ6UWj)R;$4P>zFH(e#1&2RXlzrU5TsqgNgfWPK#QKGgE~Py2 zm@ZE!O2P4H0_&peEMDfjJjv?(yY6+#@ga?mb?~HomF|&oTyWod45#N)ES`S!KxT%G za7mPzq^MYt@I_hL*_f!xRKU2Ewkpx#IEFESUTLBkGBeT;c8#zxSnK^LK+do;$XMW+s}H#mBSt#7bx2iHezv@~dagVqVC&0KM` z)k(IAJDc*7JE$@u^39VPd%D-GbY8tam(FF&t$CAaRwvk1zxVwC9?1fC2u zMR__#8g)*Q8zT!L8V}(?G{Z#<q6^E%G@KGuknwnRG)4!^yBdjW7A`cxH){Ipi{~sD2cRDM237 zcj}8oTk5TD%m)XJYFFt+SheSLJUT5+IMR>86;eG-l#?ZAy|EICrS`FSDY8wg5es>J z8gNal%ZdZqi!?Wj3n|Y4&hjM5DYOmjzN8Ez=5i`9P9YSY9gT^KbbQ=A@l&mZ%Qsw; z%M$SU`^h%7xWCMxoF09NXVjZCgfi_do>gTE`zYnlm*kOn;$h$^ZMKfZVt9`m z53B8OrX!gFA)BoG(cw6Dz@rTTOAQV@%$PtiCWcf&7z_t>bzmr6ga92nAT~h2aSSZk z-_hE*PeKL;@4q;R0DFf60ot)a-^L#T=&`Wdu|eO4s})d#x!WQdwbLi=B?68~z7QOF z_1Z7Ho)3gi!e1%myoMW9T(P-7hT&$KTQFdqI(l-D;9w%gCFERzbrtDYaYML zOgBKm@q9V9t0}Z6bzEG|&5E)Atu(|DF)5lf_l?lH`0!`t<=j2X)$PjmwGvbcV2rzh z!E?QG8=}5aQicHhDMyyZw=Y5_|4esOXjxf6NxvsW69KXXfB=wr^wcjaWoC*u-d_o| zpr1I<35vw&c^V-L@{4#*3{=aTxxtxWJ`G_g{22$!25(*3Jho!m&pGL(Q6Gw}_>Uww ztE5U*jr`SbZWqN*^Ghmsjh7PgK)9J-7+)x>DhfkKgGTQwoLM`(rf>%0j91eyqMSLS zjl_@2Nv~9r=Qn}(Sk`#p1L=6ix-hHbu4;mg^Wb@FDdn4+_Ome@`l6)u1W_e21XuYx zKYyn3QSoH&BW^X8{dmc;%I=LAWi5^fhq;N5+yGH$$UP%UCk{(88x=De{E1C&MPio~ ziD5`|JjNe%Anef5j?)AHH6(^BlbqIsaA1dqW5aa^tLJEKY|!SF3{)4Z)W&u|=L_rf zPK!2HC?0&dot!ZpM})izBM>QAk#sTGj(Vf-&cb^M+u`sfb70Pk;bwBRz-DE(wLS-c2B}1Rjton zfwkiZW@93WL3D-?)4x`6v3cB&iLA_0_$Mm|5%lW{f1RGL7BriWh_M zr%(b6)h|Lg@gpZE@??^FgQ1j~6c(JzGalv;;M%LSm6{hvL5ha?li#0vl6z6uop6!X zvAk+r$rtnjB^6&86CzHg?Ov87Nz}R3wEW^no)`&Ke)sRuoi1Huw?KSwZDLWN!=0QY z@SW(ZrSPv+l8=6sKR6JO4(QOJV}}FBY6M>~2f8ZZ5YUj1g2e`MG^?m)589yjK2Bfi z9k#8F5=hRx9V-1nPr}b~{o5g69X|oYP)F`?RNN6iTOMTy0}cz^XAIgCD`KAozO1 za6+4;z%bbW%nAlS7)>UtYuc1mg-}z9clm!hEdF9B`>?zf{al`2txVhsH&ANoYPF@l z8aGjnWGQxasqjNj770bWP9z9Q!g&WpRY_JCgYx`!(TX!?*= z8~g=cL8Hp*a)J(hs=3-}*z3#(mfz=)OC7MTeWIz@^J_qci@~@&ze-7G^qf%BfyBPS@aMa@jro96hKGzFqeO0;QLW;Rk%7Dc#+GxGW?@cTgpAs#Xgi3 zwTH+*62dwEUH%Qz@XIgNcvEom>O)myB7un%oH)ByRX#urYNXi`)A3!|e&)^Y^%UKXi;8hh>%lwMf?lZ)ZISQ@iA&Xs8+kI|4Xw!( zArra4$~%HnN3wQkK-7m3LCpz8W_b;u(YWuSwFYf#u+cCg2sXpS0pr9b zfN^1+2vYBM#hbvznArJ(Iw_*#aDM{clQEu0tHljuv}s16o*s}!X4&VY*>s7KeEgp> zFJI3Jh7W@u_m}C;wE8>1oYXPl?2{^VjGX|nDp=JqPJoseLq>U9C@4vw-RFZCtG=CA zU_8sk1uMvCte{9OqMp=9rB4=hTpe-mus+2XR& zS(z0pW8$Y&I4cgHm6z4O3brzCld+}EDxqA3=k9``(}w{x0xs2RLYjLiyACk16k`dlDkLxp<{cNnpeSsD?txT*6xRB406Gn&qO70p@ zt~eCu5k_)~movEL5rcg5HA3XcnEqlZ(fP@_Hu+=!W`p4z7!fcl5r^S}GbPlGsmpy5 zI94SN-C*5e7!iG}PH+hbz?-ofw2fec2DTa@ivBPngkduuFC!|U1ST|7Tuyi#ex<(DYXldsbTfyo!mY4~8 z8mFo?u`jQbS1ZqnXL4_@$h>9d8wN^jOf5oI9F5`C<)_Tol7v20 z`USx!X^Jr4pge=9(BD+Xh2Bkk<)=pg03ZNKL_t*PiWry_<l#lN0r9O4W&Qs`w+fKhL2=Kd^%cCikD_?f5t>r1vyD0PJjDkVZ&ndp2F>_G=KXtpZBe@zv3LpI_#x^*K2f(Kt4Tw$mOMuobD-tT;I>CeYPiz|jJy-xe5U4dJc&UR3*;Oj{OJP|$s~~RHQEmjD z^-natkZVhl2#%t4zB>US()qn1dcW)dUqGP0pM0;3nyV1e;GeRfPj#IsE2;FD-NsFI znb8WDWxJNfOqH}2Qc?U=h0Qewx4lLEHuj^yIfv27WRX=x+`2A%K>(+`PYh>@KYRL& zz9XK=8BW2#!6~&0%nYZ8*x+{1Vbyyl_!i_8D-ljLaFCpLvRA|-ECT77A>j+dgzW2F zAE_zmALN)$H)#_(!|`GCA1?_15=6#K&aPxqQJNv;k`AxNn)^J_5&zs(xIPIherfJw zVn8hLvo2Zl2I)xvZd%S&==6nPL^!(D!64oW-k3;@P;zie`QJz1C|AqBV`W_+Fc=Yw zwoO?~X34YV_4-N#_`}fx0I^q{nXlgez+=8zE9hf7}aD^I$@fP2){DHXFBnH z5o9I=a?6k*ZsTBBf(8$kuh^s8kyNPrGWf(MwqyW!uLK?k?3_+cnA(mG&nFokaJV+H z#R3S!<*5%10ve8Ur?jK|j#POK_zP-N`CKYBca4dhG3ERDVCUybqbu^9mx*fhsXs9L%zeE=F^CLX{T-+p1n<}S*a=&54({<%{2+&%;cyMNB5ku*YIdxB6bm&$Sz%|L*7wd|O$Z%Vk&u zwjx4NVwzFw&92YYBgKFiTaM7>#4c4bDrM;8Ek>PT)At6J{RRl9%4*GXlDd<4V_Asy z{k%UbbEK6#@O>GdDzFkC#8|BA3EB&13Y{;f=&!qi>Si!jex3i)2)i&M>}hUwtwxMX%DD;p4GM#KRf5XWkSTv)denGY)y zG~zh5NuFD4>e6J^GyqWt>J55pT&LAfy~9BO)P@n!jt+ere}adG8?p^|7o%)R9$aJ?eoXGQ$5CYc>`pak6C5nM}Tn9B^pVr9(73p-fr z(q$b!L%_AqL#b^{oA+mjFs_D5FKC6?Yd;mVB%Zt%U}aboP4d7y*uy1lvVS43;N+r% zQGwdt(-C|!2&_0%Ugon2?$^S2t~Z)&^YaYenTmj?uMyfgM(Eo8z!-Z;SqQmg6QXnX z(%W}G=aku%NV>~hx`Y;p`Ka5jFS4;{>#|F9a9X{QKS*z2fCIpt=p`^v+=`p|%v3BG zJ}-?4umKP>33fTs{f&V^*F|_{qCAow^x)~-Deg`eE7ydM)#J5jm^$bF z3QNjfD)>df`8TwXD8N3s@Ga{&=WR%l3p$dG^?w{p){IJjYD6qFtOA*F0%Fp>mbywD z0|k_2$C-W*O;%uIVwrIfCMqr-eVQ!e>q8)_T)Eh)U&77SI_^YUB8Y#h_7v~xFKZ8j z(U?4p425VY`|b=U-bDerp8`8H-Y1~~iphG6 zgK$~YPg`-)}=iu?!2Ja5itZSi_P0ECHf0sQNLE6E+-*Hc%@vEPYr3ih^M8b@_9~>f#?K(>&TD8Nw2x!@lY8M_I&Qv_6bzi z;ojIT%r6IHaAUfsNrj*I$(Uw@tti+bd%)vT=T$O<;NEAe3Bg*j->MzXQ1J$YKRz>) z;VonE4)gp>A2~1XL@v$rOYYyZLhmH{vtY-CBI`D@>jq{fl#MWLxakOLXf2xXiTwK; zXef^{AaIJ53qPK1aQyWni0>E?<5$d-KgY?RlpwsO80Rije0$ByQ=%!cgV%f*SV`Fqf05&eNpN?$C z25&@AhmHWl!KsD%Q~+>&)EczbVQUR&YXCG{oJN`h5beGQ>atN9)U^qq4_79>wC>ms z*xL@+npWC-2feV4XSD2hq!ElMvqE>o*wt>*Q>Cq?Z669Ez|O*bf=tuIDl5JSs~V;tis+j(@yq- zQp*iA{KyOXVj!ClL&=z!GZ_o>`yt|zn+oc9joqD!(+2;$h`Lj)FT|4eter&rZbaJ4M)%|*?lCiAjv0G(jsV;1U7o_pFzUX7pxZ>GO$ zOjE*P8Y%$!z0eQV!=ie-X&3~?w7|v5r?ar)gb%Z}Mes@mpQ;OP0D1yK7)C=Im&XwS zAT>26h7o}fa6}#ub8Z^9Npxt$NJZY~fR2#GeX1ceXlz6f5RH2#gkbO(c{+ADI3Malvzi-RRb9h0jQj^$@k2W~ zOJFKWusQ<0X9z1OQYnGX>eYx+2`OD^0ti8-RiH>akzd9HCu#w;WI2)H2w~ryJD(@y z3AD3P6JnOR>QF}!h;9(xy-?#`fKd*<=HI$P6)|yb04(4s%2Jh;>(%qYz>9` z7en;OtMn!OdhS^Cd27hi$jUGz2xs=a$eXjQRdRq#14%*6WiLsx>Zy1W(D`8=vwrMf zX?io*=JOQK0s;Hl-%9$a=yDuRpLj*WGko^+Cs;|~0+JcBu@?fs?~53#5aaF#By>l$ zN?NIt0xY^;f;tc&bVLBYs1DJrW?PW}XiVV5o3OWSvpz*on2tk)T8GBF=S7L^M1aVb z)wKiKzQf)c;67F)#2u=&4Tv^qZJgvJn3h$Tp3x(-%7sGp3AxyRJ1^0EHrsCyH;>W}`@UeSZp@|HuXBy&3>)G>aHA54XU3GV(B z_k4?uXBgoehxz2M)37M$s*ffEH8CG#*-k3s&P*t8i`+3Hd~6}tif~N=23I)Vv@jyd z6~i@X9u51g}R>;|uC=DE!jG#thaGq!7utJFdY-)-cpR1OVCNK+t$bN6CTf@6_Sw z2eiJ!aWuevANV5BzilJfHf{rrdo8q0Y{=yMC5R0mugo~KEiiu34_71MwsLeGeyUUg z)PwjsWKnif{_+i1iE2Sl@pr!QlwBf3@GLl8(EDX3at(exOG@z}Ol~OYV~mp@rVD?` zk`?D55hWs^%wFPtg!5jAqJ+}ZD!4IHX~?dPt2zVk_B10}L#nQ#WA*Q!#>-zCJXK)c zq18k!AEq~lDpr@cn=1kYpJINNl`F6CugWSxw^aw3gz?6NR~${y@{=l-80&`lIg`T5 zmd#7Q)6O$G=+%k=4UY?bTxt+h)YxBQG`wdib@zlYs0N+M4|h&8?QSNwAP__zn_7P ziGD!uZ5R=_N8OH$u_7Y0jzGbWrluLK zR>6)hC1rq?f8Fz5lweBxDZMZN0?;}A3XDmp&Tb?&YZO%~NpGwo_Qk))_0b_%o}+K~ z+#XTJh5}gt50UQPFf)ssMyr^Z$$9u-*qs>=74NfW!8d?IESQ@zsL>EEuFL&;lYW=*FN}!k zZX-%Zhq5j-RhUEK4^{`x^6pe7iX*0+EiQW&u z1L1(NM~HF^oOL=93^viNly!l^$xmP0U&Lpdrtxt$aG z{R3U`vMl&UTt&wPB}{6RBsfOGPjs!S1beS5{j}_955V0LO67e~2dA7@ zgK~XINaT0|s9G3$z0!7kC@dGs@l_iNSDLeZ5_7c}eoG(&Y+~pnEw5yGRb;KMsqFcL z|E%JtOOI-#UsA~(rK^H>9;n=(C%k{bhqLM$(EkBwd1S77`-(i5Y_QA}73sQ;qC^Bp zOA;kKXCb#S=r*@p|2`O~`i7csT6;^z#1ih08Re)ln(kK_?uF~pOfI47=V$eKK05c# zMKu~8a{-brGwK!N_5?A1D+7ifeMZ;qUR(hpX zu+z9_qPGTH>(JX+Sx_sSKR1>Ns1oV~DiL^oh7th6alcbW z8_P(s{t3*Wbwwq5dM?Xa;nK4_SU$}lt<_fw4+|Izk?ZT7j)-)%R$Nk3p`XpV7!a2v z=LKP<6P*cEPn9Ra@f<>zqELPp3jPFj;bxN+AHP2@k07c+0F^VLpFJJUtqY^lpE>U7 z^+ExiE`Tq`71PTHhQlX;eBGIqtlrB~?u=81TjeD)Kf>aztn0#<_(+W0WwV;z)8rrY zL)NV&dcimRTSYoQH6n7kUeEsntQIAgHT|$m&!bOdNCsoo1~2!x@x}ooR=um;9j^$b z{GT?J(!=Rk3>lW;Gt6iF`oF5~6@X_oS{`$43S4MzTox5W1bl|&SQ@#Gg*1AwXm2(q z_!9vT@$ytBphl^vQBdO(qDYQzRlZ1i<8^Nh8lS*KfZ)xJv2xJ?`r+y|cA&@Hw&4OL z#*06-$*V2M?X-yx(r(bPafx5|{m0|`4l$kO{&V4YUB}-p%@NN}g32VDsjiHPxl57= zNgEO>-%Zaf!>Uu&-vpY->+z4#n&fB(0d4iV-XjUr|(C8!1!$qy3 zj>>Jx_xn}(C6ZUc>z<)AJPk^6jk5#rH5aui%MTeN2?A zO1)>&<4^vxIEc@x5XU_FOPxOr!t|HJA%H30L^LZWq z=%WmY!-mjkTw2#!gSKtZIzgijTW^UmplLbc;zR(l8GC}gnuQu4&A*k)M4)j=pTbOG zg84iY2{3=VWEJV{FEWd>umWqrM}8jW;Wnak{3+XY+0k4KQKPCFLftAhl>^90DCmrb znA?0}2SJ$MFO=OYs;`5WX47PRdrs#+j#ODDf7Pz zKvM-&e2-msZ!ud-OLynUQ=Z^7WuXFC(i9((Qi;HubAtd0HS?oWh_kTq;L5AY?eTz< z-+Up^%RLvMlRuTdo-3Ys)(STZHClhw2$+NRc?E}MUhv`-Q{)HUBY%5`o&hJi6KBt`{iWcMZ6CjkHr%*N;g<{?nqTt2d}?G0e- z065&5T5GUv4SFB9U^jx$Vyk|vhKwU;rCnTKaBV`5W6=90oa>VSRBhx`_km@9-tFkM z5c_1{{?%|cXi}U1K7=2Z$n+<0C0=c5Zq>;`3q=GOt!HDx{|^3c`J_vW{e4s+VmPgO02@*LvN$GB4|^p{TPcFIfuacR)= z>OhQ8q9jkSh8+?6;*Z{sv5 zfW`_xhS4S~0<8f64MStw8g$+#A6gC;r)%^hRPd~y^k zct&@4g73ex2Ia>YI-LHUaxa5zD0Hp>3uS+9c^w61!0~G z|7c7Hh08zF1qcpXOCthj9mvsoo*6$KX$8-my1Rro_HsOA!M)w)6^Sp=g)uSfXyX}I zRC!+eY1ssjEZ%8lc-FFW$v+iLi{2}Ay6_oiocR?MjUz~xR*p8%Lri9D#i*j>jyoG?X4|2v zM4)G@c5tUZfh|?~qw~=BeH(it`nG|d;1mYZhyx;XY0~H zcc#qBh3TXIL@zNS>{K8O%zcd*uj_b-g3t_7J7q2zR@Kr<=;mx$aNkujb6J&^B&#uN z<)jiPv)c^uA5`Jv!{<#M`~2)u7sE1L5!Y5IN;8g+CpHH|p8)47Sgcx9_4>Z2#QUmH z?rk{hmzeGpqnID;H@bU@Y_#V}w5{QoAC>)JEMt=_7ap@5u&) zQ>r1-EQJSfv&(BB!Ws6OjQ3AurX09r0e8X3X8noQi35y_?;nMNITN_qE${d2k`^u# zRX|9x(QTv+q8|;PLD3f@g8Yf|9KSU9vap^NS|>tRxo6sdWK2L!vp#;MLQ;`Js5H+m z=gAabAWi~zrX&pUE8&-(2}*6W@N}3;h=P}E#|52ami=R6A{!An;U+3IH5V%tc)sF)(J^ae`lb|r zBdpRbMVgFRPoSpH`TL6I!cI^*eOcfZecwenU+;hN@XTd;$Z#rk6(Y4gd{iK;OqF4y z2D$Gvrwt%_syYV`o$BTlHxJT4mKzE@SY#gtbiS~z$rW(pXjol_kjuxb?WNJjqeNoEsBo<8h^M zT!cSa-Ol`V)_`vz{hn|A-{M6V?LA@GSJF3{`Rg(a4&w#4cn)2`aG~T*k(raxN!qHs znr~Z4Y48?lA@Jr8LY5KNBF%-L%Fq>lg?`WE*hySn=;Fg2p89hg;W6dShTz@Zz{>_h_BMpp0c4qih@3HDMhYTAr*UE3Mq)(R{*T=0y*mR( z+_azr_3_t_1CHUZWGvYm5wc>@`I0;m_pEbVR0hR8V?u#FO*vKg|Msweb8hKsfX?ci zr!Vz=Puaba>_q=xFw=g9c)7fhyg%sV?u56BKTC2Y1n=d#R=Cf6SXE`1`Y@#mn%_M| zKl|ceyVPU_FqLsns^}5G*3wrR?T@I)s{*-2mIxbRHqp?a=wcxZn z#E4iL6QZBoH6kJ;;aKkF%>EUAP`lev_B#2W>AdINwfy#HM#M@lS@w8EvQxW-pVA53 zD}I{8mF%sgmF0Q(Pox?)IYr*y0a&J?Pk%22`^5S8RVgMt!3iW?wFvyocgI+j=&kF* z#Mt5>Zb*Y^j{^CwYaBOFx7J{*Dh2=`0&)u#9ms?!z*w!|l?gZ;WZBIC5s=-nuyts? z53_}Gn?$ zf7t4)^3S30U2*n22R}v^=lZW0w7$kpz)+@BKDqqawWx;If4>f~9kn@<`OVLIYKdQT zsK`KHy`R)khck?=3k|7%Ap1jqx+0WzR`@-2Tg#wiE6VeBfA5gd;cW1EnjSSo*lktC zH_n@ory=o&`;>H{3XAObsH>}mKi3$qLuR+r^S>rxKX2Fn&EA(TNRHy%9${zI-1mRm z$uPP3o(xt|y0_r)_{8>WWpkFEA6QR;2_+wd(cvIY<#v zN^yO!WzhF(=%($XmxQVu0V|3R2$-mZidSRWwOw`xxU>oxa3La8Dy|5T@moix{ykhV zmGq~%Rql44U(2v>J3DFOeR|fy+FTb;a*6!%gb7cbGa1Upp~zOiXIX?o%#>Ebu=kf> zw$x$I1umcOx(HCI2rqw7=t zYEQ&%H`J*Iiv2_Hd!59gAdX*5Sp+bsASLn@eG0&0B2rxbsgLvv6}C8?xQ!!gO! zE9q+3*AazDnNMY~nE(oekeN`=t`gTg_fBh1%+)vSBB?Ch2V(KiA3}@s**xW6rkacb zv`N>4S)9p3y&v^w*Bvh0>X>ViLKr>LpM$2&?HlkeFLP%ip2ts4i!1q0t&xq(hc4&U zJ`1M_TrS*P^_}F|ItVAPa8v>v z?Q*&nwwX}Xde|KkwN?~4hSqMrrhnICtdX5x(}t#R)D zSg*|8bj#wy=osr^u9ZirujZPoz-J*CZof`!%dpa+AFh(MN#3mzwZyW=+aMwWhqDmR z-8-PekCI?re3@7mL}meN2$^h{TTU={GPI=r=ALo zkZ=cN==dGML`K=rh?Ir-isQxKDr|T8W^0ja+m8zHtY-eu8+ke5lH~sET{RlwqjxRX z?Wf%9WCjzR={ViMP$o9PjKN?kAgZk+6E!m;G`d@s#RPG(-)7nbW)vbE)bDx-C31uk z0II>7RsaNpYP;}`YV82X0f<9>t6Wsq!Gu;w0wR?0$OQEWO#DR{;kNq{n7FfdVP-e9 z@aOPtNZ6~C&vKMRBD0@^wKjFkapW;mBv(=gCdP882}J*QDCcQaM>w&n+b6AcWzKX( ziKd~)wWjVw;Gys~d_4E){@nN=*{Yxub{E1#R*WHHve;}DJ#}t* zm3-Zed6UUK6GdZQo;R4*6p^)GQZ>ALFyXn9`d@+x>fznj*hA;|nfa(M&iK4?EAc)i zo~M$THjQSm?P>T<&YuCl+Q8u0mduHqo%f+LvH#kg)Rs?pQDO1;*U@>6gp7P!eK(;* zI!jUnk~B<2CO;gS@Z2U~f``U~=-!7E0d~w8H&D>IuWy1X(slz9476XC4cVo4d6~(!B*H?$(37>16)ToPdcz_+1L!#=qnry6Qdym~aB&ScY*0 zQZ=z-;xxRZrm7SlyEfunG9CqhQz0!$Du@$9)KMt99@`56_(nW0jCtRwJfWWY9Cnuo zHET@scV=^AUMpww4#)cUdnRriJSzFkH5`jF^T?Fop)Z*%VR^K4GNH2{R`RSK)}x#4 zhvEAENaK_A16>1%FmE+Yq%fWWF%r(l@mzac0B>C4vJBT;9qP zjB=-?$o8d8e39ll)4GhncM!5M0_Xhsj}#sc~Mm zyXAHn+zU27%WtyTItuaqy8s9cZ~-EGx}=~%1r{|^a$)@MIM?`etg})VuKZ2et>g8w zaBWAna;;zxD%EhJ698v&B_$<7p>`2nr-=blyayCpWhjcmzCxP zLn2peNS{-;5E3$YblHy|3>|OgaLM-4@3Frqz42D*Zx{n<)=42nfCUiee(LkNp6EsH zc_ohBAY$Q1w?DsCHz8sahyg5D=U0XEg7!H*y|S*hdvG>qaX#i(&SWwN0^>lAym0Ij zp&k}s#z|vH7flAgagO|D{d?&$5RrX%&w*eEEG!gbN-q@b>0JCxHIihzNB_&qT{ETRvq=gb{sg41IO_~d9@>8>7}=07f@joDj)?p1lR>)ZqN^x zIod#ttukn!`sofo{t8l(QCaaz2 zU?Qv6hwijfUT~`?63}V5p@i&-dIL<5rZn!ic(Q=CVn{R9iP)8=_^6#O#^T9mKZd^2 zHKM?c$k5NJTewb8c9EeUtMk`vhBfFtxwVB)>5ONq9)#Km-pOiNM;vE;Qep zTkiJMCvHrKhxs`H7`L6wNnh^A(e0w|A~S=}}Bx(6ci6dz6d!QB?phAdJ6E2H-oX|q80q-$KxRdpd!lqGv%7PYx&|kdg_>7 zCWCQOzz4vB0Kbp#I~-v=wP_@a`(Im}&yL$#C7%D6g@b{uL5f+GRfKnN6zWEmGgZ#-luzRmA@ z);(FC*!lM2B-O*w^W37(k?3ng(pbi18H~#rQcetTy{Y9PiPs9I0yR6T3L@Cu1EIIq zxrs^tE4p#J6l`u#2LWyC&lQXVRr-X~XsxKntKC<}5L2s)y6>oa#a?%7(00siGjX!| zbT=4!^DP4w{!Du-fu922bLnL38C|+7(lNSB*jc`4+^6(j4cafdkrQViVnMRU9eEPh zqEhCb)KZlF+&H--bf0E&znv~aCL}G_I$hx}1&?=VNy49}z7WSEI}vXcyL_Un)Gr!i z(Tsga=JEZV6mcmWcM3bCI2LmF9r%H{r74D|be=eK()?UPv0g?z;pD$l!RI8GW%XvM zT_ik$iIK3Yt&}ZC@4cohf3V z>pa9+8gAkp$?_e`fr+zYp~PhZmCP-7YK?8_Yf>9S+$);+?C$N>t*U#CF{ zDP3x3Rccw#K(T7O_ZQ*AMfCW2NnQAU{!P#c3oK z#Yx_k86@Ai|8-n5Xe6W~N6gbv4;WFq&0{9|A!C#I3~1&~-1bTkD~Mo}(u989dQBjp zu+d6r*Gn`IK>$;Wi=mPoGvtjy)HY#MF+Cz?fDdp5j+f9I3pr8za)$?G>5XrzD!J>LfY_-rFhMhzSW#~5l-pZB z=_&ycSMD45l6P5BOSo}0W`saWn$=CV=g`F+q( z44pV*#2Fcsgdw4uSOG<>A-e}p9m|9)8=yU4G3rSfS&RoOOOrfE!Gw&Y!i}Z1dnQ;e zQ-M*X8VOMG2P?sjqHV-M_fLQs2LNyd)y~Gb$^~|{f@=Yl1LY_UM4+WtN&#kRru zg=d`CqeI!}~J zU*@0FGsMtAi4G|?sBB-9iB%FGN8sETRjN;j`sU4 zoCtuLqi(XkebnN2xqObeD%I&%&n{;+)8*DIB_B3p)LQi#JC)U3{E%4xqrqnk1>Dj| z2$+zuV4W(H--2)-GwRQ>p?N5UlAIRP5yxWUG|O@Mz;5J5yURAe6NrkNJDTYdn80## zw%$5S1QZZZ074OvLpaa?05h6dlYj}{bhP047`o@W7O(%5%Ny#`p`JIT7^xf;RQ~yD<@{AQeq7RM=YchS8faly?-!(sEu; zz1g|fr-WR&L72S|u_Q2szH=wbyFvx0Z~bzjQ{K!MKxB0NuBbK zvv{|{`a=qMIo)2kn}haNIv2?@aC#I@h%+QGj=@AYThcQ4uf&dYNI$NcRRq_9BbazN z9>4C+K}1H!8)Ennf3>$EgE&r5nfi54Pw5)@-;~#PZEzo`Jgt=zex~w&CoxNF1}yXV z_raZ{80O9!lxJpuOE&|Sxc_2NGv@C>ME=}qB$4?VpIZ*coASX}1j%_yD;Ge2r8|?Y z&fVo4;sJzv&gbd`OlVvawkh;44RcK;!B+Sa2|Isl@4L@XZ5KHdM5yqI!*Oiwu8Hjc*JD-108u;`#&hgdoZzl!VII;- z1>)1=92T^!1d@cLXA}1~aFwJUyFqJZ)5Aj-@q`nj8bM19 z(Gmn`y!NaXA*p!yR`uP8kc+5qx+V1w;@|Om5`PYpjkhLlXSFc$zwepje4M?bmM*#r zRG*Qb(R9XaGsrN8@_CVDFJ>~-SL*xTiTvcJKE69+(zKMkabVbqOLCGzyI-RHfeZAg zSKA9W!vNgrww)6P>&7u zINaS~9%%}j7V|1IITBcFCwzI?=wv?4WarHJVdj&~w@jW~XG#IW)%QEj-L$DK;FC_nCM1Ml z%O1a?!GSgKxqSHMj5tky!V6B_GzK&OEZ!ZYF^u_T==<&3@6SC$yngJEYxkQKyCmmp zg5)}PN*?c&ZKj4Y-;rUTxU>BYJ-JT9RohY0PnM=ln2T@W&UPv*F((wy|0Z(8%7vt} zK9JKezn$cHdOYd?u}_NH!~-{YFS=38;{rqs8Jp~pfWsy1NQcn(&+5K1h?C>k5X`KdpptT*oMD?qAQvTvZ$C@ksm+aJUJeV+x;;<-*A~s5dg(# z4)pe1n}LbQsQwq+Y6Wi*_-hzxihnP$OB1gto3FOd1zlgQhas`+b83Etb71034*n*0 zA)7>ZV}ALo+;YB27#-t&WnWgnY&0)Ar!2JEBM=cX%%5k%Tw{4%>$+_%|6k00^P+!8 z#>r@-70}H<#KNTnKVjaF5>Aq!DVfXM9e~i^`o{aTYo|46W;*53Io+)4_1JpAVw%^cTF6qP_2X$ zriNdV0#Jh-s6;4Ku$881*yPf>&6n4JeXFYqcQa$HIF19a*GulUXl3MDQTE+#yrxpx z<#lBPQISpHu0F0LlvLgyD)WIYqirI+d+G+A330=^fGf(RA|LHFM;`o75{j zEyV9HXKXbC5ntLL@eMru?mnC}yGdUA8bPZS)oZHW%kACxx9TiN9(Ow09XjqJlhwU9 zi^&9c1ot3z|ZF#rvko)&m(38;TP~$=SI%OK)BfnV3E>wItb zyrC^b1Rm0m(LsoEbw-g2*5KhcX4KLq$&~dRpB`V@j&)&u+#BPuaN>5NB8iJ>Q30q_ zx#f8P6;xp>B0|6G6Uav>UKny%DIL#mtP#6}28Xju+@t&6OCn zR&2)$W!szSQ`x}Vh5}&QWTFbIbFCprI$=Fo8Hk;qZ#1A5ql1SfgV#Q8!niX!w=q*iY1CJ$_HqmG0Y50vtnizQaD<(Y{OpAT!!wLu~zGxlj;5 z3q&I!dlFCp(@2nj2M;O=0i_AdDnPS$!lvWXz860dTO%PYm00O~lBT5P?vVs|M zov{%>RN97cErHXlxB?1*atDa<*fAe4Q@?3+01>fW7Q^Y0 zt;G}PR!I~_eF<&-p5F6Ji2Hi|$C6!?^IMzS^Opy8dqKnB z+9j6)^E%L@6t6;FEVWpONBu7x7Leq_=RIqc(-RQ!%*|BL;`z@xH!f_ojNI3&vEpa& z_-qD7OsC_7Js^BzUcOb2ChR_lGbQki^t|Ps(U66vp$=9lnw*b5K2*}2PN}3$o66c? zOVw6V001BWNklEcfHHoT3Mcey=(9%bm8Jtwa9kl2Xx+#LYj(nw*P4{F zK#l^Wm{6;`CEL)b?wdGp9578p-42xFh5h)zUTYBAYuQj(F1zz9HICso9O^2?4Qe~> z39-Xul^DbTXYR$r^Ay{S9P9G~;2D8*%5YA{!q?WM{wa?9!*_y-)cfz4YM;9I=pI+~ zzE<}4WB>X(j~ctLRI>I!oDYtkNEHlQ5@aCL19@VM>Cxv;I+;5f~ zo5n6KL;8nqZqsR=C+<-ztlvUEPbT*OdO(H0OsZQDJG`&rKXug`wp)_p+HOO+YrLuCMWx9U+gANolwq_7Pl)(AR?ehW~Px4K;bkJL9sBf{RX4r&cGz=gDGmr>iKJ@E;JGHM)#%z<@>(kqYk!ec+pcECpyPshR z!1gL|(Nfsj_?w<-G-go~?J>|qXUiJ0T z{`xw53L^A9=Vv*+QElHBHq!k;r_{y}tFULF;h*0NIs80#3lO27czT@P@-)8(Is@MT zB4T36d<__t%L#A|BGgZXM2eFCf{ZRi_Tmj=fzgB?QlVX$Ni=Jo>c^EK6eoGPH{Yiv zh`i#ja2@X61rt`y@}c`XSTYq;EM2Gr!6?{vNwk58QCrcUnPmY$W#DA5L|)GJeRo}E z`kehOlM;&OeAx)q%jC?=M?Q>EviGD8q1guHW{-L2BI~ql2#YA19%%;5qGhOUTQq|~ zMZ&m2>Tk*}XnRUD4Fc?biDvrLOp^4(rebOdHcbSWLA9b%0m@;5dnpCSCU;EK1C{GQ zGeQFpbeQ$Z^42VB8h4i$hoFfO<~Tso7O+Ilrq$?Dd(Rv3(xTnqIltqSs7Y1140rM& ziGIeAuX6hehY!@}LVM z7a{(1Z~JaH9qoPQ(n>r55f?ds)!pUwcX;*LkZgDM!5?L;%+waih1eGT_-_Q3>YG30)m+_P7Ae%pz6D?7E9ey)cS5HMWEna3=w=Cm zEkxR-zjFz3rva|I>L}!90rDiqap(u|0Dga|CSEJby*nCITcBaay}fFZuZQ{^D&zy^ zuVBIeL@Sj2wH)rrT9CLsHjH)~t%_2_YG*&V_P`b3q8FxBR2-+i=Z{!UeUq94brt+~0`_RNDzi!~j(WRoRqX(SQV#yLW~Bk5xqbp9b3U z*O3|YNkh>OLK*aCYu`b=DzOv*0w}hP!2%{Km-Z}q@YaEqYG?Z9bmb!j$9CY@UO4t0 z$8n$@hy7MLd5c{o_;m#%OZw^^8UBh{U3WSR4@%m>brzz3*!@5i1rgIp!N4LsH164_Y!XOnDi@0P_KgkV^jkH zT_6^)NA3y$(%9XfWiJiOiK%+c01CtQHIsmi@aKR9*0LPA##Nx=|Js!c1%>6>0WR$V z~%G`|Eh2o$VuNs8rO#^4tE@uWq%O<&+BEs@&A9e^MFluL_8$20SXjz`+%$ z2M(@y;lRc(ym-Tgt*!bWj9M9`7SKWcucG}zK!t6J?j2dt*;zkPh~qb2w>qdvM^*v2 z|5q!63Q+t_5FT`j{-=oHS>X+3YrmVKcSV(j8mQuK?!=YbehIiuP~5Z+^{A+F-^8|U zc$G~iS3!w_7Q=D1Cv~CU!%D}n!azgdGgcA(+&T!m0i(ZxBd{ksRh35UY85jI$irP_seOkhgKxtjr+EvqXJ(=gPR++#TLm+KX(%CDyBuXU%5=HKvXq&UelnC0P$O)YplWyiw z9Sv&tC@8uILMz>?m{`YR1uCJI(gb7`;B{bGKW<>6T~4>f35W=wcHC>N6-Vv+BPuGW zvY2&suvRO#Iy(-O*9$MXl#ZF(Wr6-uKLrz|VBGk8reRRVBK>*@J21Bs=W5Lo`HJ9n zz94gV%Kq2gcjv1%-?pan3!CkX#y<@rrhxQ~b$Uk2Z&}X%;&@!p=;fe0ML4IR)A%;E z7wvYZs^0+-a~{74MDz@9x|=om#r}6@N;H$p)0gb&Zq9f8&lbo%fXKl_OY^E-$vF`Liz2_jp-gOLI95ox_2jb&Pmc~g{N}N2zN;6L5(*STL%a%F#@cq2cchJz~ zV)G~e>|nKqC4`ewJCNugqFu{?c34tjpj0^(bZq~QD6DPug*}jPU_wCz2VWE_D7F1k zE!aPgm*ml)nSzH7C`1#%?H31tgWF$)fe0%+!&Q|0i4fdY+tGkTRUpy-UVH%cg{^Mj z3eZsvOq8P?ok|B#P*71&2q+@V+YQfJNvfF`Rw8WAMcX_e;bq0b4esbVg7s%FQx()F zgQ;sroWM;j-Hid>Vw%mat>QRp`y~>P#jO)CP-P=Y6`)a%isN;llmoBVXS)~>j6z$# z^;&?1J_lo8qYJW4@s}~F&Z@Bfq{;K=sQq=#D`^8}5H%Rjtjeix0 zNaFqS9{P^}6MQ=G$CS_8ctytyCeDE8S(Uv5CcX+HzQdh@h__tU?z1rV+_C%jI%Ee5 z`ImFQMXE{BQc!ax`QjQ(tbopHRGrO{chXv(RHj0<`##Cp>;hl7T;})k(u)3d>a(Q+ zC4MK(5`Y8^WYHqrn9@bhBo80rb4x5{Jy7_C!W&SjX*()|jsmK+frvxwu?|8ZMsXFd7o%}| zftvR8`xWFzWonLnM9qi#k)}z9XHBNU?wN3ZBu6!A8XnjL{9rUTZA1ej2aZGYX0QPO z?tUzLRGdb_E(K(u6h_(F{tE%84VALo(7hOjS`WI(+lGbqF z@RC(jLJ7@sgFX)9#g1p?JIgf#3I54N^wWHv-rT!rh#$!J_VZJs3jv$+AR#6t0R~}y z4!gQDgp%}PxkihOInQ5#%bvKhYUvmA@%$nLC6Qhc(S5@8=5OEZt zy=*O>EFd!xDh))twy_hJNWh5KGC0$wBA{XOrcI)SD3Co91|&qYz(CvkP}u$yNN|yY zzW~}`U_v)PlLPEpJ^HKrBMvidYJa6REkqG8LHtU91fd+x#HltQu@Q9Bxb2tFGT8nA z5v0@6;+Ep)%Ud*Pi%TvpyKnv?x^CjsQKHhpk}U(+^*abehnQ;hG&coarcn{PxN9V8 zkvk?_`lVECya%mE-#0Or4d|e1eAYh9?sw&u44gAh=k;h)?gMvsf$0~zUskriz%7C0 zU*v{Sj5CV=G>Fjee^s4c67=^_`&5X2C^lZ^P3g5j^kq^c4mDWmPYW z?A~(M(a)$jk9Ahp?7_s_WmthNyh0(AKu)_qIMur zh`^=v2nuwL) za0AT$c3K{}x1`7AvcgH&@9Chc=&8UmlJH&m8pvJ=oHx=~e9uXpePh^F0p}be&vrQo zLm&3x-gbB5cJEq+K$o_YM>e#hcmkFvQf+R;AC zmKdwlx`@Wo_#=9hw51Qxn6b5&lYJLs*+54q+x0#h0_WBj zBG3*L5%5bTK<`8_l0Ar!BVKD2(12uyhDN*yeu zJl4_YSBEArF)_vyj(yktIXQB2+W&r=#=>{yuei$z{BL)^pUS7z9%24p;KHmse**3Z zURSm7l@5AMMVAkLPn|yPWxoPws@So1v0YXmLf=i+I?XlD<;=}sKY8{z^Rlw|tjm58 zM8vp#PK|VV8N!>~1mHo`h1@VD_pz`ns<)6B=FKKECNaq`mJXl7LzD}q!s+XbEMi)L zw(B0=fy+JE8I4R7K6Y{42S`)(Y$J5=6`07z(|R-fJWk``&SCUrENmd!?^xB_Ai5?2 z6Nn%zYLd|p7#dIL8giS`pebN@-9JA+?bIMOVX9jb^m$`Ie)(Wv2WTUdolsr{+reNF z{+r-g!k!3LQ=Hd<<8|Qm`2xQfpknB-{HPPj{euJ-CrX1{*So7tTso}P|PCV*TKYB-9H1$ew+J-MTltD z+6B$N0=jVDSk+H@#xkt?5KLJT8sqo(fy63ew>cM2a(*rxbDwh!_;4)WN(^u5L;w+J zcke-1T@-GJJvfzdh7rG5T@0(`S(4V_7TGQOHHAD^Y0&g<7J`QN-gYtn&~6LbCv(oCC<bzR0K`1XKt#pydC1=j^|P5Qm7|JTl-ge%c**?|TZQbA5Fqga=paD$ zNVF51q#{MrQTM%RR<_!KM7tF(HtfK3#(fQQzv-jjv>du>VC}7&p$YBqR*lKf<5`>8 zQWwMtXqt*zu@wPD+h!(Amba=1)KrNyKL*#sI-_6(=tU$QNGNk_JMv8vqKMYA@CTY^YY`e)t^LMO zvkA^uEBJmI*9*No6qUkC+Dc9tC*jUZhH#X4KQ4Yw#g)u`rWt&EAIdLsSK7{2F z0C8!@${sKvfdily$+4-AQt=fK@wd2N1tNTuzEDhkWptItZ*{FlWGnXW zb9-E9BgO^8@!2Q!4sH6V0=>?;N{Ct!_-L#kf^@+yno6FI-}VDs57hl=GP0fmB?l&{#zD6l^uvuv z4ma9y90y*<(SXEpU^`w7NYq`nBy0vEN-fy`t3cxQia?^EX(Be!PRNza`)5V{*uXEA zlbZ;oR@6#hE^c#my!YVvJn;JO3;fBbN6VbJppYIabzq|dRe^-uVvR!q1b|ojJ@jy@ zqWdo-ugW-T#bz3b))GWrDA!KYk51(XJd`WY+_`)w_9jjWBx`?{J3=`h9Hi%7bJ^+gpB)}oHt$gQaay2%kOo62Z)F;-HjprPGd;_{310`2r;;Uqj(%bm?7lMd0Ic=f?>tbG|@ih?9a~{FOmn!~A;X|aA>x)_* z<5)KRpKelwUL6^LI0qGLTCU)Sf(Qc@G}EP&ce7<6T05YFIa$zSO(WFpIWWpfWBU@_ zF;UjqzM-mIzdIwxb1(;RpWMTr`Tb`Vkr6m1b*{JFM2a%N4kxX&bu{8bL^dFdfY)nx5* zG%Ka1nNUEnW2-w}$BvCR0TX&*-PSY`pPvU_uNRJbh!z6TtVw}H1?s+I|ER!=!%0dT zmtH}3=RqU3zM5In@!uEfXGJ+SR5`EqMXv@XXv0A}h}&Hg?czGJ3-H(h3Dsp(Dh43h zK97pMZXHNCz+jtGMz?%2`=CRkB9F9z01I zf~w(s^0Bf9gzurn0n+=qxcX5lG$ z&ZM%j&d<^s7Xa3@WhtlW4q##yr7lzGc`b@Y_!`(36kGs&g5(U%4Nm8>LKyN z8$yr!Vy3aq-}CzAm`@A20+*bGJ)!T^lAT&sV!-0Uq=JSjlls-)C$}0>3*T%FP?$1E8UB0=0EJ; z`&jKjL!x>SZ9*4Gz?J*P>21_LOxg&$J3>kuG!qQ~z!v%CUN^g{p@MgAa`Ij+M@Sr0 zNkj895OFjm!siS1RZYe&$A;r*`ymd|M!b#>Yyu`W)ktt@pn^B-|NVU7_4$d<&juuT zLnFw51iE=s1^9!3PX@ivOq6QDR%L&Mb+{&!@-b*6K3}N+ttfJ|>q`MdIdD+Liw+P9 zY6VIK=tWKQ@q+tRAVD~&U{}CWH*Cj-x;Y>bz(jv8r2!D#@JuSyQ)jB}Pc{`3h0f|b zhdna@w0#m5*J}tWHw}g5<$hhKRiT~^Jqx&%?{ysD|gh7&NtFu<$iCQ zpNZ-BLac;=EZ#8wZs&VVCkx(Gp3tG!YF{^h@hD0S{)<=cFm zW88PvN9@0OHCzeu=PQb9FmX;#9{;{XepVLp0f-#G07fIm6-!u1KF2c;Sl zIfp+34gw;o_scXBtOD}jAM)eyY~Kc;5d6^rjmD1v!=>%ZVn1x@bkLzPoF`7hVxn>7 z?(?JwAVxUR8Z&Am>`Tx_%s_$*w}oo%vSld*+DWcw&_N@4ie*ccEe)^FPaK~I>SslL zG0JOeGPP(W`rnSNw(A-;Zns}IAhCBK@!$V`HjRW33b{W5wV@Pj+)R!B3*ZwdFTy4& zkgA<5AlQa_yhfrCd!Qa0N@cvthEiTQ%8sKPc$EW$qg_T<*)$RQr|)``_Calj`Mzza z$A+yOI7B1iwG#SF0wT6;!zLZ%sI{G*#1&22Z%!BOZNszOTQT%4W_L-p4pV9>N$RKm z7BEPGi10TR`cc@uR}=Ot5vm}JR;LX(k#=xVQ89o+F6}$ybSAHz069%XEp`)kE2w9# zee&Ru+i2i0glH|NuRw&YqGSTpiJ)@>M4WtG5P1^(JKUQX=6N=2f|r;6eW$xGpZ;O@ zYd}O_ddRBbOpw0<5m_2{=y^iJ?5=XU?$-A^eyY?WpxbeDdcUKaoq>qOFCp|X z!n+Bzw_giA?D7YD5Yx0ZTq`;!Qs^Vdmf%ht4z)21l7ans=H^rdjZw-Z zq>O%ypD^4AY}U?YHPA2>V3EL$Fi+fX0u!esd>5El)y+QwM0_`>nmbos4ZL{H(^%*A zgr2i_ZlWB%CnGU+G(FsL>&~+V6Z6YG7-ZW@jmXya!XNA_$Le=!bb54dd(z3X!aQ|X z7hZi2W1-~>0=UYv{RmkBR`^O|+_MQ84*9Oc4#aS&G7rs;S+*gLGK*uo( zUbOxev@YJeVC;m?spyXSsQMoR1{dncuhP4fe|@hkr~1f#O#M}1oJ||xgmQNDhxTw4 zFueCPvUno9xbHn`>o0B>i7WsB-rU;0s-{O#6uEj2ZRGmGw}XjM7vVvJ)Q8(Iq2KM) zCcQAaa671{RMTLXNs}%bi+mNWJ)()9YA>3+$pF=6xg!hCg=O)XsI00Ct-UP9IvL0;G-WQmCln4+ceDw%nl0&gGfww=s>fTYCwWy z?}Y-1ai2s-U#${0GgoS+OC3CH?RVR-ZyUC~mBk$CiBok#+B|e<-w3VqkedJpmd|}U zX6bAVn0PP&fD2Ij$j~%OX@h~dNPHdGoj(6e%yQH%X<%?YaKOjwQ!GixsR|<8U{Il* z7;*wt+mjN;@6g2a#OCVFCLtG6j-6FT5md`p63mTpYb!rt>E~YDU*f()uJ}s6)EVBj z3BsFs{6idv&hZYmbd{Pu-%BO>-|3)N>7UUMrt#DC#vwC(oF7m9)_Fz0(Y!JwC_L7L z!(~1`?LmOUAy!)0J!=?SJRC}q)~#i=XgBux_h%ELeZn-R zd=E^7x*J#jH9rFrqos+;NE&AZ5^#0p%Mt#;^kmhX#0^@67+#Ogo!Ib#iFMgV1RTv{ zJPvH2Fn`RyXO11g4nDZA+(C`}+Fc`H+icx|1ohLJ2&hyi5YbAjV4{_tL0V}JY`8td zrM5$Xs>sqDp9|!-G%ZJg>^o+{{`vXBaWsvDH*I2eJHkaPfhs`avtWPiT_eH1BS~wS zHiFy@dFVjm)h^OF=m3=$AeW_8X1gtK)JWik_Q&X23DP|f?U|fLV%s+C`;L9v+i6p# zDuGpIkxSvC+O7|#%w;PuGca|d$b|bUotZ=n0LP2t>QAuE-4H-d<=7poY7}(UzqU*9 zNXk@>!`i=(5(nzPhOM0%x+%rlabdrmVy*bUjeCPUL zNyiHx-L%B>@fH7n(&-1`?!}pb& zR{R}pCd6yLDtCZ`3=(OKX$HO%%Ddo4gXV{)XP)xN*B!#@K({E7`e~91DcbCqb*O{s zW%YUeVQ^i;!2aF+f-q<#BtZoqrGW_r5NbJ83m~@~7-+BqdmNzXQriF`N(T{@+C|Up zqU6%$W4XoJYa|Lae-ePPzh3=9x^^dnA{_@Ll=uqlqK&A>tL=f%)qH4&cfujVOq=u= z*J>tCjDso&hk%IBhOU@Fa`mj()4ju)V;bDS+q_j0HQ8560Hm> z?0QjI1^v$cG*}#99S4SuLd-y|ZL_lnHoC&#R~kxR@u_0oH0?!U;6OC1VCHr%aEpmU z;A-10(Lh!`wzj`w-)z7VA}jz}CuKpiaV1EI4vd4`;6V2atKnLwv3}FD?P4nP1asj6 zA9*tW{|dL3@qUjpp6J`+|FCnKiFH%tU*afmec3w-KS_FD?GSTXmlNU`euuWia8~C2n7C1P=r28MKVBn! zalA=S8OFAb>uzGM97M;!Fz8)+qrzv%d{Gkj{j}OUkm&Kbe<8<{JlJq1PI|E%i8cZS zX3|vkzA_R~T0sJI{A$_AYQX>pn#|llga8vWYw`f1*tH8yGeLHGs+cytaL7?mRWGq9 zwF3!xuT+5@cztfzUmK3s(F9Quzyrq@jYLBR5N$-$M6^?w&^Aruz|n4P14AsJxVEdh zD;baoAmV@=a|KsX)PIR=Kg7Om0uZ`_Q%`8J<6&!U$JY*EBC1#r;sbrat6DtONN69E zG{bMLQ<`lM6cPGG_?Ixv+H6=AaGIcoPdcNk?!r1dhE@>fv2ED2?JD;bIibbI6iHjU zNo5@8*+2UAjC+(>U7*jobL=$O`NjVmBYRKHpvBB&t%oi>llT?S6 zc5|Z!oHy&n`E&iPT6_;EbWftC&2zpTcyRybg>Lx1;p?~in;2;_6=pEv>tE|LBEiXJ zENXOS8m)1RO>}+{=ov&gM+N)q^>QaK$#vUx02J~EW*nb8j#s-vyPe9!B8+Mskqt5gZ3Ntg>jow&w~tI> zj}J!S+B6dWR_hT^aR2l5)Sk(-5y!UKfV9eUr#F?dVcQf$%$kD+0(^JSPN}V=1FEg% z1M`J-7RJ(U7w$nd5>@Qd(Cyj$oe*mL)-(})({x6$>#L! zg}Ut>2+GM-YC70Us>K|26*Ci=hmW5==I3TkMZ>q1TZt1FV8ROve}mxsOTfgU{5(AW ziy0ocD-fY!=v-KhAs6{PZJ0d$_;NNGKbz{WsmsgoBV2(MB z0*g;$5Mn|ac}*?rFMJqzYZhq5i}O7E{5IadpvSA~ywGEe!fwxQrj7=Z+{9xfM?euj z&4PTNyS;Ef&XvRbF7szM-Kj~Knx;MF<>zBdF9MP-@V5H(ziN%(SLIXFp`q@(RwJOn zRG?MyEXH&1gB(7|^ixBA1wd%qc8b?wS1&##eWmrctW#|r@cc;LD=UYSooLR; zgN%IRwP+%!wr~n0ROls1SDtOJg#G99B9WJ)c~hZc`!J}=RS9}?wVE;&r-k6QH$p+i z{`!2$t1szYzytvlEiDZjwFlZEZ12jp1xBWMwT;ykQ~{uY!sF03;?@Z^(bOETW|~%a z)GA;?7!;Rrl98!#+~?rS?75ETRvCc6FxFicKX=(=X_>F1g>gUL;QFiFNhVe$Pg(DY zyOUHB##YJx&w-4gz}j~+T+jl{VNd&=lTL*>g*m4Us5$N1ZZUy}mq#LXi*d6bj3Vk; zt=&oTQefsq7_H_3JUs&w>0?W05N>0-e(Vh3V&Z}AJ&H~}jNQGlsED&VT-X07<;=Wz z2_lj_M-$>M(9Tqb)#|AYY1vY?xWs+7u%;dUA`sBO0WA1=eFO$IGZU`qa{wMmnn?2* z(t}&bauyU;w?mBwO~%|YJ0zI^-Tau21&UxIYMKzhN*d>ho06FiPMCOw%Zu$Dp<71{ zM9}s0=b;>FxfWh)#|gpuWd$UBUL%lkVcZ=O9!w~RP)!1;n>3NFK=bCmP+2ah0E2M|aEO4SQj_41S36p?9<`gs=!s2C z{TFf!tZF6n7+ATNf?w^UT*e1N8`#vgp#w(;69H5>)20quoD|QnBWamAoZfWE=I~&~ zG%|sX0z$vhrf`Rs-gFH3%j}o|R4~hha3;jJ?|LbX_KSA=cC}+|nHgM)0~DK(+wR_| zZvR2M_^;i|Q4iS%BfsMxGs}G%tdLg5pkpxlO@3`ka6bYudausF1an|ouP%iAF3cNn$oxhSQAfWVNL&IIA68ps)bfaw?0bq2KhA~Gv}}?{TO8N4 zL0WP7T8x1n?>{|1SamWjN7gM9FB>t`3J@0ltgpGWE&SryOV&Q?FVDUAxQh>OV^|58 z#=HWDCMz}*bCE}>nH+)igr+9^tDMH<)6+|qd)m3gs_of1oRQ`LMmK$GS_(ZawQD?D z%)Ji|8N`Z)bYR1EL=}YnssLPEWoNQN;D!C@*O`T)4P}bNrGbb_=zA^Nq^lQhOzr5= zs8o8Zh<>|s`Ukl8j^cn}z=#GynRRD|ktvcV!ZGJC_9PBhQBzUd08?FWR%dT#>e(NC@KyKRBy%`Nmv>Oczl?GV04W+bO!M*uc>%S#*Of7R~Gj1X} zoBJ)|IKk1xEJL|s)ujnPT~)sd{&g6`LmrFz`36Vhcvw>Z>uC5c_r2|MRu4}EP+kPM zre@tQ3H}Je=dLd}gojy9o3fp~hRExnZ@F=3kAm?`YeLVmf3Lz^(0{vd<2cR)`!QqX zhkY@oXBmYaTOpO-I9F(XkphEIZ3Rx|P6YAX30?9dGB zHc<(e<3Gmd`>z8SCbR>Szz$A9M-S`wJoxzTghtIn_j`K5C05fk2ljgEv6{$ICcpt# zZ@wNgnPZ+0P0S8dROk3lj+{!L5a^K|D_ejI*?m`g_pw_jA~CUQMRD@nI8QI_u4PecFkr zhN_*d6&Ew8LEz8ZYE94jUiHPH}b)OiLvYCok_omAWX#} zsti0h5TU4?<~&Sx@ceNE6TZ?3Xg6E;Z{)&u-*!12Kn5Nd)BptQz7aS^)Y_)qGeO~0 zCr_8|r_hV)nBCfwXenN=7l`_;+1tLg)2_D7Kn1X&0N~9rJ69v)`RkDo`5A+dejLF> z`?vxN-T!ULE0SYmdH`Dt^!A`Z*0cNh)cVJB3X?U6(T>VntYQQxnh-`CB)w z=<|;GtH6Glovz+14{acVz&7>TdZzFM|2qm(LB}$6^+6c4*AYmJb6ZCDz@n1*)YHZ) zP9Rc})npAejW7 z40M&jtxv08XQ%qAa zfe6PbyRF~=BF46WmUpOh4dsQZSk?$~yAjIK;|9QVh`i?1kG4XkDyp*ngeZ)ICcRPQbz zWbSu}(P{yu-xy6ZxBT+s)*SpWn`j9?;g z+C=!#qffhFtbjs_K~5NULUUh{N1w+Hh-lhQ$gpbRxr0< zb$PjkRk-)4K^v1^6PCcC`DYQ`rpJ+oE(U7~GJMdK!DO9r@on;rbF1$+S^ZjMN}k6I zh*MI6MxruMx?FCjJ0*0h^xCE@iKp-{?Eo@I;EC1RMk=a>fej>4tWSM*!-^ddS5 zJgsI}JoLdb{rPykrfi^A67V3l^R+-Olz^y2+6~XFOuCh%3C2z}=LVzNb_M$`VcyM@ z$D211RK3`3zDAjs;~%WhR_?%GbwC<(rI;2pp4h_;VG77_MUnKhzDT}P>3a>7aWx>( z_Fr%ZS5 zvyrU;LIF+l%Y}gvOw21AlzhvXLku0=7$YXNPH&V@*6j8yjc;(56VNZt|E^1Bl{3=Q zcH!06G2T^~$DEx2v5e0yfO4Oc{?csVDUmpj{HOq>t|ex|bA^G7Yiv za?KTC?J@`?%T-X{v1H88q|D|{J%R@jn9PB~+@t0sPAl%I?v!|X&_Mz8kHZblD|`LM z%4J@6bFi-Fds81jw|N1>&;Juk9GLVe%S@Y?$D*2FPpbo=g1*{=f< zAzjE+hc>zS3`-=r(9~$dArG3BAXCGpD}}ttF{bzaleqxF9tx(?!5V3&-U6$ zIz!wrxGrU!6*gn+O0O}Pq8bHFJfiPM+qtES+)X!-hCD zlc-vYY?$x2bGHrU)U*;-F+U0b+*@!kUR!gz?bA9+xqUn=`wXQ;5 z*6E|luR^WBgZU(Vn>lABcPw|#f^^|={E*Iko+2Rh#edz>1x|mj&eC=n7in!YetJ^Z&vU+x5?f*c1>BRXAMIzZ z?*%a79>d}XYdu~~+#J&HAVQx)KY=^vLK~H5A z4s`bZ7C7F@ROito5(5WQ=5cDh(ny3dbq zzQ?^Q3!Xq-#yJHOgTLtr6x>UGtO6%HO@xidE9Wy|%cX^EC0 zgHbI+W$3{|Iw;zLGxs#Kw$xi!>2(}>BE6q*Kmk~d8&>L|p#p`Q$xmStX1D3_xv*88 z4hO5eRs7ff>OOxlOKTGTOnw(bF~=IT-?=nZQ#lG0YX zCZ+vw0|AxoUWi%>jBLei1J&Jl4Z`v9VUvlPPL*xL#=C1czhcq*M(ZHT z0V0?HFkM?kt6Gi6&TTlEixU1rCcT@G;ud}pWPNn75#bH_E zs}OvW1zY!z$GOtLbl3DvA+Bd^7xyCG+ItR{w9DCR?zxz-&)kFYosG)1=&cW4E8&Hx z)!g3AKmnLNvd#i`da3~k!gO3}NQm;@a58e_mFF+x!fq0k zy@$zu>wax>!U<)$Q@KzDei?_56IH`;!aaQNO)O8{vZj|HFPi}iFRc6UZurc-LY~=g zwq^_4K0`h64c)T3>pZz zTtfi`y2ZZ-5!(8unLr;L9!!LdUs?x~O3*n)r(oM$?pJtZE&ve0gI86PU07G30K$&r zB0?=PG1Q7$H`IFIINEWss#T~~*VWQyX*Xt=CIf(-2vv{WZs2b9!8R#2bQ}Q$x#tl~ zzy+NI0(-qJ_6^~qAQb1~InA?St!=stbIB9hFuS7}`PZqtuCvxh7VScs$~hRgL&d7^ ztuIVcPAg?NNn?z+4Et{1Nhj-jWna2GMOm!U-5tkaF1hKlNv-uEcF#S;{4Aly%8`E7 z_*E0gm3L)*V2rNwMsZ-G|E<78pQA<~q5a^t^t!_OZ-@I(JTKJeqm59}Ww*!R8t$w@_9DS^4qm5-Up$h*IsZUhmbu{}o|(+R6R zRaTl@@X}xgk#2(4i$w?p?IfoL90;{+*f*UZy6U=362N#7Ppyoj9N3Nn$Lob-+i<*I zcx|7pZaz1={kq+NIEp~RW~lWR8$@mP?G-SLv6&A(WE8jEec>jWVZG=6#SqWkRh_M; zu{&YzwdHvp*J&)vkjx{$qmSIFvoGf%Ld&o;@E`@geF|kFEQN~lyOp>$e&QT`o-eh(1lzeAr7HE|l^ zdLZF66b2yDXQ`!Ofp2_%3?m4(qTXb(1iop*v3s`Gl1YZBr{hR7K*_FS+$8c2k2+fo zNhE~xkfGDwh-U6eaMkn^&5chYJa8lyQkO~R<)!5qoG2Xfy*0|J|^rtk9i@$rF={R1B#J3a(JG`|KUK1MJxshBzZwC4=cV(uid zZQVlzV7)GV`YPmC=pnCKPvFvQVoOA)h14XeV5=KG+_yHNknN*5ni>eTDkxDkce|kO z_4#QhLjl0H?Pl)OHwnsjDh@P}b>P5@2pw4PTwTF%zypw2dnc~9$rSwokbuDGG1y%; z)+Z|9Uq}&MCb)HXR%gQ`wu*|?>iZpW+T}sB|9QNaYf8fuYzECwddp>b_@d6f$*t@C z-iYaw;nif{Tvi@(JO^+`+ zKY34m#LG2070HEZx=3Wt^4m?As_}dCQ>{Xci%ijEiER#QZQB`YVStJ3B)%|YIeEU| zqw{#vwxsp<5VVKaxfJqCQy3T3Co`HgKI(s?Pp^cDY!fsSH&!G$%|cR-XU+#-YTQ6j ztAZ{Vr$otQu684bhnE(JF07*naRGvAMkDXr- z-pAZ2#E_pZKTb#C8_7KUp|8XCPHcZFkDIupX^_*%4i%7hq25o6j%i6h{9*nrs#OJn zxM1J6T~6+)U{o*_R3o;w4qcki*lx`$^4xRsgSeXpkpmIqAKAtLViJ%7xuK6hC@8d{ z(1yM2_$WI*$`5>$4}8!^0|`X{#kMyPux;4o25WoY8c5jp4g220+3&Vv-!}(3_I@Fo zGNGWhH7?$Nohgs+Ke3s7yOE`(r#&#-1Sje0grsI&waO)R5`iijz>~}RtdCLGOz>6! zvm?w80j`XF-{qc(y=f-o;<~bJW-_J?PLN4f z%WLNz&zrH^qfOWFk7uhpSFWYK0uY?|ErOnV21mv`?#KDxb~HcDa`)gK)|um*XWEGK zxi}FdPWDXn9OrMRisiKIqriW!&#%ji-`efgCSTp1g`h0NNn@Q&;C{{>e}f&keRGRn zj@PjAD$kjW?F;W7z(g~L5W|E)2nh)!`E@Wei(t`etmhd|>6`a2^g}mPyWmZghVTH) zKr_EC&7L9K+%nd+!V7>+J3Rph!lJ(~Mv$wIetK2@J$m=B6Npe5BuRp%2gHxbVqreE zvqCO5@~`?e`vvJXzcT@&Pd@&V~hp61?ro$gGWgbYDlpG>MDj2kDi zdF|pgJ!>A+bX_8-4|!PdsS7BrgA6pJ9m_U@2`jKHzMBZ??t4rBQV<~{mt0U?*iZqI zRCZUHUU_C;U@z1xe{BD8A?zRfhFUAO?Lg%Ml-kgVY9(aFnM(x?eiK5_GC25RpHvGm zXd}WiTDom7KtU-xwr$5=KJc-9;K%j@KeiwE*mmsOhy3o&Ov#%o?On^THI2nqw&Z!k zww3nhLB!Mmh#+F@GlSl0?(fnG6NV6&VNbQ49W0=WYZp1Va9c&-+Q5WXtu*Xb2-r4D z&o-7HhZFb@nJa|Znu`2DJqix`l(LBi<2YKK?(Mg18@64w6J2xBtAP4o(xYKLn2@k` zqSQm-CtYb722lTy{bpgk*DkfL@dU_C75`SymRxh2r*FJhAUw_ zo3zHhqhs$ufs&wf6=31g@_q?KT=(!f_;rToR=X#NA^9|=M7{oX44R#=O-o)20GLKX zCrP+(tio|KZfZqr{7XT?xG%sC&v3$c7tS5X7|ejuk|%SEhVJG>==q_iyWSWbfr7mc zX)+?cgkDyP|EzIB5Pq`)DhSEqx}HLqL#5+}G%BJtO^zV&%-8B zS7`<5+yy)X6)xOz&PqP4P9ySuL2w>Iny@{5pHh6F{Ye8&^Rphao8^3_iS}t;^Po^= zBHJj4iXeE*#`PtN9m@7%*mIwA+)#rK1|n|ShXN-*I|4`YgFrd7Z_qvrIt!mgdC#4s8$Nw=-DvMgv*+HoW}zaVH2qJ`jE7`G z+>4%aM?hY9^6+$nw407E(wHhErD}FdapoeQMONlLikUNj&~IU#YSc`SGkpT`BfA|P zRrjtjqh0W-8zXBM?yEN!ikblf6i{Ivo!{#}D%`v3@ZWjyizz(?2L0L3EmJz730UN5 zFG*3D+*D)TzYmR+HTzNs?rmp3Cj#>*I9eMH+MP)t^H1a88Ric)Me(s_4V-88lN34S zn|_{1;FzpsC7xm4%-mQzKAR{RhfT)5!zIMBl5oN*mQ$aRzKH4Ue)3w(`E;y(-|42E z1!??|?&+)hKt76A#1tUOOM=;=srhw202<0E9kl((9<8wW&Q88|ar|Feb~f_edViPE zNl%)K-_yTB?V5%nK;rd!VJihkQL`rQdnClX2~-*YC~mJqggkIYPVOlwpfGSYDzzXI zSB`Eix@r3313v^n{QUTdpZibz`1paJA3yN%(Kk{5_-LD|)m*6*J>@92bIYzzC`~=% zo}=`SC9dV(Y1_ZCV}+V=EAl2}kL|5#Qcs&1O(Vf*N92OQRL!i(n2OYCLx^qDUL``Q zgsQe$?9blw%tZpf0q&-ImB@3*A!bTYZ&EZsPz{Oan+<(Aln za~O8?o=-Hn>(f`P&}a2GbBuNTWjVjKK9i$ zvN?!KPsPi{fMf3iWn3GG2nRD5h|s+W`CbKYRs^R}@S20rZ$lpOInp)qD|X)Gyu7&5 zrNXlwWFnIaH?lt>e1rw)d99i~@CWBLfP(X|t7M(ru?p|2BXy2vQSS%2=5ZYNZ*aO5 z>zT4rLS~M0*NvJ3&CL3`ExHVhGbh0Us8(R5ZQ@>uW7flizjk;fd--0kZRIWiv@mBp z>rI|Xu0#0FpEQJDU*bW?6+f*c^$!+NJC75m?a79)0}-CBTT*`22#ivtj<}un(M|-B zXJ)JWA`QR=Xr^HRb36LgIumpAtL=m*wN%sdikVv(YN?{dXzhF)yV>0~)Y>++^VU}4 zLfyGCw>))(#J)TUbz{77bY5~zKf87dX9|O8^}C|wP4^8+e2;VWXg}hY()hlZYRzL~ zi-r%s*3Ec;rzc9jHBwLdL5Mu3G{5C8%OMIp=b}NH^AdzVpl5yv?w;6^eLtJXpSe8c zmZ!}-^47Ht{hi!AfpVHeJ8mZoxK z;W6|~9p6^%PChsV3qfKWC&4k7`;JHYdLDtAWN~e^-sUZB>|d2RoaWY>*<2$Qf5KT( zuj=Um%bY|EI;61z6nz;-X&AwT%i!TWv<#lfI4kGpmJv7zO+i!9n3x-X4Y;$)%x2ca z!>`l*8yBO)i5kb2NBvSI-<;(o&9QGbK%TOo7E-` zuWFVFrofI9?7)bOZm*Rn3Nu~0)dXo#yVr`t?$%HNMvsLB06l)zS`yoF*vc6dLMd(I zdb?+$=Wk5c29G|I(V5LHGpHE2*d-I-<#V^8JOdOn75_V~x5Zkab1tM@)y%~_^O%Xh zd4Sx2`ha<@Rr93$Do~h35l)>iFHegl&IF;W$CFeX5wY#jP(>6W|-STUAal{yeH)4c;cRpCjdFm z5aBM4w`5M55)!`@Ogwkf$mD?<$wLa7; z2Q37ef7qG<*>H^}NA9{&`QzgQ3`V8e{z?T?MJ?Q(O9eKxy$B!u$kbAFUqP=@rA|Qu z6@WHse|tfx|DU~g>9uWH(u2OpG3H$RJZ|~oTduOXvZ<2G4{V@RHsC^TAc1+b=^`FI zIv^yw#eaZb0UhWd(E)@JLUgcr2!jz45>{cW%A)Grdmj6ov-e(ejtm-^5%EQ4j=9#k zb;_<1jJ@X?uN;|?k&zMcuwH1U#cgeD+b;#x}nRzLak?oKqYpSx$bQKaoi^X8x=jBjU+}lJh+0hcaESVp`!H;?qMwhjLSfx7VTi70SVpECpgpUNQHVQSVlUyKRXCO(6X(z2L#)ryhlYp z(X-qFEyKCz$Df5wFn!E?aK~$iC-owTeY960Xn-Zqp)-#)m-%5oy$1x+BsYDQDpHAKRn z0Ol50KGyn=<4J(@ArEHFH*-@S7uKYI$9PsWq>}kvs-{;039>_}2Z8_u4`2_UdHvI( zP*Gn!we~&UYUz_2eArXOwB87I0DC5= zm%&%YI4Tr^+NGt|+Mbcp*90Vt#atnIXw&TU+lA=djV2Vw`7uf|8whG#uyn)}hIG(W zo6uBk<8@0{2+4TH%1!pJNWoSV+QCG`FDNvo_o%fkPXa&>Lr@x%2)##Q^Zg`Lwa>NL zAhI<8X-oOqH4?V+d#`7t$dc2$s`&o#%)e3u+rHtlZ@64G2c#DRrCXDy-!DMo_Y#OK zB(vSUQklNC)q0i8I?m20$k82pB*NKQfeClA%=n(lkJ6;+VG_0Sz1bQ~0Kztds{|VIkAVc|w_UIt zXCRQTM~8m`5j_ISI*4D!qcP5uCNVy7>IFctDzgV6g0@w(-{sJW(sdwYU2*z_zgQco z<27@vgEwmhYScFYR>%NUz6lPQFiNf96X(c%6@zZHIE@?PV3c5Y4&sVeE`_ zPk)Lk+Q9^%1wikSfJoo_t@f~zzoj(Y@3Mw}$v+7ClmpPS025573@qKZtvOn%in6t3 zIUPh$Z$uS^Zi?&m+IEP(G)KSf$sjQSV?b99A~r$U+YeeGs*tilYMba?jt#PH4M@l( zfr;pm5RcmD4_McqbsyK-3kqFn=N2U1-IM1zWC0qQ>NNH}NJ>N&Cy+H~#%k#d&R;enb^d*1~$Wejg=*d;5#f_b} zwjH?NZ*4MuM?bYzY_+!4ptcRAG%#7TAa_?;eg#6$6-X-`7#{})4@}GVwsO_B6Ucu=o1yP(6!ks?lEI~kb4{ER$Lx#lz1)KZF3S&h4q0n z$jNgG@Y)8C(<7OO7iyHw+4yc?VtBn0&_%>1U$@&G&(F_ze!k)T`w!UO7nJvHUgU8c zs9I4}haHk%YOstZyUDK*0Jil037zwd1q$i)iOV?4)%u$`tqF{bGM<9V6xR|=&^M2Y z;$hfV9RVCBpU-_Z1@}nU-vAlFI1eI*Dk(&4bWriVB(#qrueSG_Xy3YFj%&>N+#}KT zX1^YLD)N2g&GNAC`vw!Tt!|B29^TZuQ);OlNVFb_-FqbR90{gaY`NGDB4ihoi$GLR zRUJT-+BT3Yb;G6`F0y0C-ho8SkBBj!M!&{TB?A-3(G-R%R7(tP;tAJU9Y~lAO#bVM zur$8f&ZeeF7nS*}DVMzjS-(0ztkp!@I7V0a+Q3=qTS(Lry%arW0}Z-u*kQsVecr@| z`~B$4?%qAMHoPg)wuywtQ6S~sdWdelOjJ?!y>D))P2p`DHuMSgy_+Fg{d#_>1qIqF z&ubkKL)y&HChRRw`(?+|(*r{Lak;c1bK6$_fw;K;K#reTL9UONOxGWr z<8`ij_zV&Lv5fxy=R)>Fz9Wd>kc+^hqxroYuPCaqbw0pEJR6E+?FKhOXYA zl|X_IS<*CQDQ{c{AM?)7mfkF)6`Ckt_6#laMt{@Y^q!b_qKEmLnZDI=UQ=EI39q#S zuRDUTXEDCq)_nHxWias?zyJC98SmeJz=!uAuy3WU!q`E?{eHtyrSZ7}kLO=%I_J%D zL4Lt-J>{c)cQVlH1t7r{>I@J*?opd48t9&>9^yO8)*Qu2fY(1x!<48V2aHhUI|CLy ztX z_kG(S=nka;2^-p!dL$Z`L!>W#%GL( z$1R1|oQ^piRzxIx+I33m%4|b>93&a9MH7a+(KFBWafDBkjUH*q4dleL{~sU zU4~i%KYY@)jXbGh8v`4d=o=oJJXp^J$gl0JOT7%XGqFAEtE$dD7Zed4yKUUI)vZme z#69=!+JUNh>8fHjsK<3Yp^xUeeV#oR=4A*eYfvMXIm+^ z%_%wR0o;2v=W^I9Dpe4hml0iH0|S+wh&aYN!B=NRk?vdG1l!(##MAYHk3MQZ;?s{m z!qd|gPj9ZcIFNYxc*&G~AI|3Y>7+l3>-#m!zqe`p|Htpm@qLutP@8||c)siL7)*4% zIXck(Y;bJT?TX@s`$WS_HCjA6prCKaP6g39e9F%&P}13C>(w#8odLkY%})nWgk@u4hVe;2*}?%jJ_uhz(=sJ$nm^;8t!1WbmQ zmH)T_wfwsK*nP9^dkmu$V52>fdDadl(C;Mhik%#&5Ajo=e4Q>9;m09(@h;V2{$_Z0 z-Y~#n$A`a7jb z3z2#w5ZBUW0n(QBSDGK;yFD<^?8e2a>9l>{cb7pG%=04{Ol*qnx?#Vzapt@P?9>G! z$h{GJLAexcRXqoL-LM;o=;ys&8jvtRAv<<7AkqE_9QpEi)7mFgAAM4^&gcR9Jzeq9M{n@)CvVy?r#DZy?0bCqI!m-pa#ZNA`sO_JZ0>OK z_DNZkO%4-xoBlv6At% zLrB*vqF+&7uK^OPeIKsZ9oyFIZJTi2hB{p?F;BE|Yyap|kaN+7^#z#Vdf<(|5<^?u zc2YR&kuW~!D0)_(2!xn#wwkx|y6a5GdUdkM{ObV3%YOe;VK0;6_eY(Oabbb>P-sjd$3%^`;kZTPzm9L&iF(>z2!(lQz$ z2Z0Wd1hwx_UaMrucVH40m3u2}iP*MZhwb4}QTM%#0rtv7K(1CC9)07cPv9;Er5q?* z+eur5@=G~c)qkJH?x5$4@j6|TN+M<1z|H^u_5X!``LF+5cy#>LKl!iYul>n?GiVzq z^D7$H%wwKoth0LgfS==m(K`{o&z`@)U;6L=)rWNdE5G>9<3IQ_e{Hd9NLGS#5a0?cdLFoNM&&?HF66Bi$x1KmM=&%ERw}{N@+%KmD`+ z@$@`FOP1dx%b@$8f%g0-9l!L~|3%#Nn4a5lDHr_4U->WR_~_~p`)4d{dDB_e{SoEd zua#MWKmKR`6v`K0oYD;dzwukYooShf8RiMl1?OyZRF*CLmZ$kK$BaMrPyHJ9zw>t< z(*2u%=Qp8GPZYr-<`Z=HTIo-pp9mJm^$Y*PKZncT`rjVL`SC9 zAb_r^M?wLgyKEzd4ymYebU*!|xmdOJR1|G{zt!%CXhmDh-&U9F`+?otuih*44(I`t z`_|_hS8Vr+&CYdeBUS2#QcL^khNB+Xuh(mLv|`Ma1Bk-C6AfIHr-E`7Y?rntgdycT z)4Ro2Yz_a*j?1y*I4)4BkgYTz(E-H8&h>f}_PziBAOJ~3K~&nnh3?pN$EF)LY}mB4 zYXcKy!&dA}8`LE@otv;SB7=)P%g7^HOz&Q>{$7Dn)xr!W_|XZNFhG=PCo;%s#Q-Mk zwXgIs@+h@TwBb&+>EE`M)=RW&%rh}uHUNp(lfr;R2N31Ju^lK!fs_r!7L@8MCbj(Z z(VM-eM1pzk5YbK5 z(jfzYf9#WA!INI`_U&8xEV+EIP5za~oL{Sd#(M*wn-m;cSCQbCKl(AA$`$WFJOfzB zCztck&Ak}ul8^D>8DN{rwFNA)HH)w~e)0MvY*O&<-TNuVDNagjMP~v9gUo}k{eAl? zcoMu&Rs49{P!{O`!13v)fC#?)@~f=ci3THfJ+>N2x6TgL!a>os))@=rj~;6ov7>(a zDZc*fbJQRFV0feFGBBnjIn^@|GE%(o4gJ~AfB5i_?)xwNBEJ2dpWt?R!dzj7Xh&y} zuc=HX2QicXs^jOr{r2Je+b{hx-v9J-+DS*p zr2GCC{v!6bZ?SL1f8JQS73|vv-DCAHFYRyyrrd>2U6>-qI}Ir2v@0gA~c=B2Vm4$)}@6YY<|i1wh5-Vl0cz@a}+;6l__Q*GyC zn0|1yJ=AQteg_iR(C+)>du%MBm54kYfHfJD95xIT82%0Oa6sRv4x1|)0~ zv9{3#t<)p~nAj@hNl>l=xdP?V072RM9uEkI%_h8V`-c6p;W&0&>jhf0Z9KOZ>~+UQ zuh_MLh)ccTQZF4ebRba+N(T}}JE)MhlG7%eZ;EF?f~y07ws~7GA`=eP*6pW#*G(TP zC1HZj6wmS?$6y95;VgUDg?1OKjr97|m=CQ2P2jq*?h~TzRa*&G+v-_TlF|r+8p@;; z=|Ez`PAiVshIKK~unW0HYrKfy5J4$-l%x2smV#s>77=1gVB< zt`Xk|pdK7Yt+?H8`1+f{SS`}`wc-2T8#a-DwOg$(Rm=_-^P_tTJf4&#;Pd0lhjicX zcYM%i{N(e`Ez{wAxLnaQy7%kxShDP8g*=!%27=Q9`%>Y z>SrYPyv)m-*0s#1Uv-`UK&|I=TbQ5x^b6uKy?0G(d5N5{^W?k|$>nVh?xH}FpO!e* zE^B=ZBvgT~zWf?T#V9C4dzX5gsU$eLW%26p>>Qo2RM+FY*9vH|^5vIbELiwv6NAf^Lt4&W?C#h@tt@r6?TZ5S0zdQgkxCC zcTVL6j*K+F@QJ7OLd<8jZEb!tNT9#@GM5Q|$3P}V6HVY#m0Y}3B9i*1b!{fu`>Fo+lKAd&+82_6H9+wG1I_Ye5& zv!B3)i5+q|IeXfXRyqc!W<1V%P$XXB5!a97z^&f!)1Q7$w6z#g++*E7zj^U6W9?~J z0|bHTQnrV}VtdrELmn;Iyo$Z zO+=47m(}b{9xnn3#TTD{iTm?mF~|W2BzE#F&J{|XsXt!oNvRcI zeDNjTU7ym|4{O`#kEgmtWiUDC$>SU?HCQNbx0iv$*I$2wZ@>I%(i=%8R>Tj*o5IOl z_T1Cr09CSly%tDx^XRK!mLhG5{N5YkJrYVA$|gWD#7EC&ezPrDb0f!LfI?IGOnuFR zZ1&*&n%*oF;FEIDc}3i-TX=MX#$g~A3G+(?c$gst1G5!?P}_T=PdA7& zt*Bb6my0M`L;fahW4S6Q4kY?wINJP^yY)!iZn!_+QE!TRt0?z2glRhtY<>9Cb{yF1 z)_gkh%f*4j<$`VB`>w>Lqnud&^(aSVV5`7Yp;ra23S1P}v~{7Bj)s7~pFwNc-uD8n z8&vlufCUW{99shrdc{?*xYTyuYaiC+-6zt9#`J5crA@q+{wsEt)GM(P7?0T>Xmm)Y9pnHw;|Ve( zuyzIG!p^y}kD&Q<)viE3<%Jae}= zx7>YR-U1(=(|y0+@u5EBv#)<@A1&ggRzXX{LNIuq%3}1}7tdc2c1`zz8}9h&=U=3{ zmmK{842_AbYy9~!_QLVC&Fv~>duWDgZM%(r^X<2jY$)J8QsGDksBBI(uyXiTZ46T$ zy?D4>CFSSrP;Db+O}=x3#YzvJ#V4s}A;5I+GB+@-S?*)?yj};W$Ko|T5}$qcQ@=mc zsUvu1Ua^i#XXD-I6?yt|{5|4_bQ`UofBsbfiG@Qog3GxscyfzY-mE7lg6ZJWyuZ{V z(SgJ_+x5HEH*&z8=NQYt@*|1fQ~gYQxW5KSy!{$)zx)cUQ{^NNOJ_0{@pQvOfjoW! zsD(xVn2fyyBrI7GkRIaUO&h9K?9{90$HG3nu2p_6OZGET0xoMBVn3GN*qCe|ELV9nf2wFq% zz3<&t1<=yLU!NmkK1v4>x91z~&o|WPih8piiNpQ2&3}6v%G7%##2WT%!T$7gZM#SB zdjk?g@M>t2UMlpe?Y#G2QE2aau}QmzrnkC5FCAnEfE^tqY`FGbh^v7KeZr+S5Me+< z4uKpUL>!GVf`X#`+*_DzQ@p6&;e6WNI5t!1{Wv$_#p4t`)4m9V*T?iU2^@x+foP3F z3Xu2|AwO+9aJ&}V@YTxl%`ch>{sr8J`EPezcR!6S3uQ`sR;)6cpt3{85 z^#ED<-tYGYB<^?IkE4w>yk~Gx30%}#TMxz&j-^=37CX-5=r^tizS_Ti2qd0wH@v@p zz;FNbvvr(*3~|IY9H)OqYq zL;sudW93X|1B$kyoH=U^NaTHSQh}srBR}NDAwmsEe2LrpJG|6&aZXCz$|Hjc*8XZT zw1{gUcv)Lsa%^j@`26!P@fQ1ct9NFH2LRy>eP!rHn_Aa(ijQ^UOFa_DQStWe*ZA^_ zue?rBG$|k1m!6$S=Q)4JwD@!9;A;#Fb9|u4^>9893WyfZ;-)6rdJ=(%64cDyPA{r>O%(k&dwUC zgxrXc%V73P@?SnPh+yzAgA4Pq13)PCN@#01Mw7*DE70DMTWX0FH+%d(w5j_n_uDgW z&o>;;74^9S9Z0la^*3K6 zk;Kp@=;n@a5dmu3L3`63*J>c*shx4{OTli9;G=^F`n54%1}Mx?VujUZfCbxSLb{Kt zYxXCPfW-Zd z+tG$LvBSqeV%0jH=^SWza0m=E3_!w%6Z96qeFNT{$792JW*`A~if!0iJ?3ls!0YT} ztX9qsLT@D=va6C%(;RRjyf@52213+K4Ztf+Bkdqs$XE1+248YCxx--dn zwK^jI!2SMs!Hm`;@eRKC@~hNvViARQBf<$x$QZz7C}hd&rR&!$Qvp_s`$EU@7yt!{ zp^I$jwyjcWLsZf{D|TvGmyoj_=j0uyBRk|~f~;QB&q2&c1IeVHdHCXLF%qLy7j(ZK z^sM7K^BHD0VDvp$^F=;0e>0#MX&KU#xVQS-)O_6W&?Zgq14w9J^hg;{6m|bvM4+U8Ak2b7hbZ;nw)+kXNDzy_((R%NO?E;|0&Qm|XK)tIDB5-y=s zaiBTCBHdAMr8FytkeDV60^1RiyHg(nh*?NTTpotZ0Ac|qIKJ?~Jq-UiWqv-{yHToD zeWJ1mP!TPbsZ~QG_O``(-$-ujO4EQvS6;Q&ZV-rUQxsKV7jYZraI~RLDMLWlR0bv# z<4$xu{?Y+d%J`@a@Ze}+uceLm{fj^RbK%(c$>n>oV5n`ySj#g#6? zzz05*Y_!Gq)ze3KzFzU$zxcd% zlLw-FZDG0&(*XHt0TK2cJURmQOCUjuwG2O|cf5c3V7Zy|o!<{%DwVSxs|FN`W9H)t zm^h^CfNz1H|Lsq4xfK$gIBr+q zN5AzkzWL@G7YcK}8BEx71{Cn*Wibd)t6s6PZN*; zg7?I)Op>^+@dX!#c@Wim94ZZKGT9F>!FBAv{_}qk|LAZ22EO&ly$E}wivQu4{&X82 zLJkb;JE3x(WZmkS0w~D(uxfX5*$L0-F9gc3{@Y*ub^L|@^MA!RPamgpvg6$^{TX~) zHt5|ZTZ0_I*>PgW8BTlXWp?;1j`7(m209xBHd9Cr2fA8P(xacaYx>gB-E?+-MmsTs^ZyrXxc9QOlK1)J`^^y?F7Xp=tS zQZFdAE&J+2n(pn418I1Zd50@#u`0(ioXAH8C&v2_@UarU?pRfr_&z%|)XG?*1tS2&J$|DXeRZAgc;9X}JogrOJ0C}dxHHz|Y1`XG zew%~Czn#zhz1T9uA`WUB&&<(6C;xH=8 z@2=#HKleM&lc)qH!ojLlU4eNo1Qrf^lFO{*+{sSP9<{QOBQiQx{M{7iBDK_mA#>Q% zo`MK)9+u+emjCg371?(I6sNs2CBVeqT#u7lGMT| zL!9n;26KEPBFWz|P#NoUkz5uWe(hAwG_7<&04})hTj`JGaRMe*g+A)oksj~m>b((L z0umcO{^TQk^6|&`q1`1I3H@M*VAx7!Wx-o3}WZ{Oj|FTaZ47w!D+-8%;o zZ8#l+1L9+U7!Exs?5t}>zO!7qk3ryq-@6RM_WeoS z;<_@5I_u1=H8WiguV12<=0DiGc}P>g7Xuh=0)!1?!lvF6Vdru!C{KdzsbK$P!~XG( z%f~zR{*zt%rgjHDy!(Ln-@fa=CU4L0KH&c0=tG+X+p%LiF6mtA=0EF^utkve+wJCS zqL*5r8yfPd0JdJh8$6q})V|tArHMBPh20%{u7?SID!gmOciA&^q!zD0DSp0?zk5NnN|G?_8)gjjnOqk#I>>OC$6()I3(sVSmoS`LbtY-_14R9?+$T8d5t=EGP*N$N85shK~UnLNT2i4c11@K z(*sV?+|n2PYk3yRXSN7z;5Fn%v9;95wH=dR3sT1GEGvzlKbfLI7J_!;R26V;s&cc!42^OWaO#C~jN{;S= z&f)av7D_pQwvyX?61^KO86+aRS(`y-gsY%Or}FUx=%T>>F)+njNn!6*a2 zBS$#^qxie{bl?y>+!JrJq)p}R;Yp?}PMWaHa&g`oY47`a(5cx$qGEIq(=NT{QvG2- z<=~lUOaPknWn$CG^XY-EZklcq>2x~rbKaUgKo39ik6Q2Td16Lbk)9%}g(Z++jHyf7 z^O38l&^3R#0uu2}21Q7+qn$wlS}34r${jxGLzLMGHd0b`k(58aUpl5EfRf?yz>`Tg zl0J>$a&vD)DQ%bP%f91!yWoDm;yCWE7uXiF-D!<=&-n2C0UthmXbpGI&jc74ND^;` zcV0?LPIq$p+0l;1NsG^Q6e4W8cK?nVHtD&?@1O+nO^Ta*gGWF@;*!CH>yX5k6T0l9 z(bkY|%c;78resI0bwV%4A$-@~RRQnRZ5@EUM>}=;nUYz zA$@py+_xX9_^-6jTF-#aogQ^1#;aw3!o9hg4|S=B~l zTicevgB}hjEKJW|TfWMF&bPjTj&zw~$5gz4yKH3I9(WyRLz-rRVByb3b9JwYo(_VN z#O)Pma$t?g}56o4&JYo#HP>s+_nbJb2G?+L;|vN+OpSeqCIA?XwCEy%Zf zTO#fG`PnBXIfzKT5PiaRe-`sZV!2BO5y@!s1v`uVo=RmFlPS|VPUhR}5ZWs)_c?)Z z(E7bQZR6K*u-vD(WOcouX>_W_dPW34syg{2@qJTxNDvQg+P4k+r7b{l+4l}4E^Wf& z-g+c_M{^rD?E8dJIWJaiibfQ;eslxq*CWUJUv?15Q)5tJfFi=?y3ITr-sZGCSS|xk zgMKkCoO(U`*=S_&5Mtl;mWXFMG?r_gls@0PSh#G?JrL%gmJw{xdppQCT^>enI_Q>r z6Zkr`cBVh2EAu;cZXz#8WvBg*>)a5FnNKp*w;{80Z`e$ir5tj^w%0B2@O`GipASXN zycLDd@5{R>Yx*XAmB`nW?x>4WR{5PMy<>`oG8}j(B7Jp38s0SYNL(%(F4qfg&zD&7 zuj>Su4yif-iDx`NKjXuP4|xCKeX~K&H(xZt{jwoLew*}(nh)t=a<3{o_?E{3uzUbu+E2VndcXl^IZz;Ig66!sqU{+ad*(9Eb#zE;{QKyb!!<<{&|m-! ztA9H12tc&jx4cLn&g6VgKO!apMsC3GvPkn>rN6IQTLXS=zp8D=2d#oy(Rw6GIdB|p zLptoz9QGYeK{*|b*;;BF<}^A(e0U+7VDz66sS<`Z^++60-JH0#HHCBrMU-717bn z<~Z2O9B@a$EK=#$MHSno(7Lsix~lDdt$-XIEHaNO>R}4{pfV30+va$s9En$vSs)wy zkz3kr4LLv4RY=89t-={IM}*3+YAAG5<{v(M!1MDnod*5ki|6u+Fj(?>ky`vE zz2+%(r`!O9t#RL0|J(h%bza#n;jP^%c{ZV;WO$bJr22Dqkb|yvot776a6tfqd6If1 z%wC-EhF$3FRP;;te!4y~PuZ09gF4Q@8W@H)C3;t1w?C>F%6Z_Cn7&=fMYav`K8JJL zu*i-k4V%B`Z!L`3vEdVn4+x_lfwHrx6b|mRt|DCyMWL`>9~Zosz~h2e5hNfn_C{=5 z!S%Z1_I$zZcE$aEi{+lM$ASO=AOJ~3K~%w$gUdY*MHXpLy^)#skndgOl!{A!jRvKOd?6Qu2tWq|2{XUdJa*AHnu5-%{(OU=Xe3vxK@c~i976uK+( z_jv!l&7b)2{(TH%y4`3QSR2-K571yk04GH@Q8p-RGUh8mSm$o3+Qw%uI^G=C92$4X zhU+0ArHfh7T5m>NGes+75p_C0&(89TxybopFd=zAfoYD!r2z^95)hey!?Z_&I|bwJ z&RlOm2Ds(afyD{^GB8NS_Y>=z^*Cmy(`CT)eA%$?TL)ejT&`DKFIQZz2Wq|I za=Ek~3X}i`;ax0q(YcU3Wbd))x`BHdMxYQtVkl<<91FI-aEyUie?R6SB!4}Y-|4gd zf`J5|CkhwE9(hMPpT{%jgY^&dJt#eMsupn#A;on>`_&VtOgkS_9YM%Za#Y=s8lT6v z$${knxIjn0dT4Z~XW4%D(IzD@9Ob?&7yi~9SMre@9E`Rgl}ol65k#>P zQyD9jCA0{v?qqA|U-n5sbEClW@vXuzHRzut##&5YM-}| z1;+T5d6tE=)(TXhROzeM97C^!8DHr;@&Tm=cxaxf0g7&9x>9FnqY2>btb@XsLbNY= zK9EGtV;0X$OfvJ9uD8L|HUWuK_$T4SGv$4%KnyFP$N*jJuibYex zU`St1tTbueOhD__g|6*?*Wwo(M}_tl7AyPXXyd}I{A=A?{w3t9t+CxU6jTvZDPEFu ztF!b>F{9LJa3d!qHpt~UKC>29H@^M3^+??AcRWA07NIs7`yJlD>p+6$MEG@IQq3mB z%?2=JV%1U>x_7-Y+FD_u5i`{LXu$~)0|pa&+;@Fl$F!90vBh; z*g~ILq)it4MBIJfTTg_637T}h?K=dZ3B!CIRwAMXl=GEKFc@Q;I0TElDnDKDZ`t~c z1+TN*O)+v=({<^+5SM+&_2~&uPj7HM<<-bK?gFIbJde2(Y8>DUvYuqHFoK8SmzEkO z`Hd{E>&t?&ksFyV&Wt%T(PETh$whEdHkQ%?L`>J|BlAi$HHuhIn-r?Mi!^iIW?F;( z0ROW1F7tIVnDj=W+U;&_&kDrBM3RxtQU(fBi#S$wi)c!~z0*KW^B6BUUgUbo`px4J z0}?h@V#`arZW}&4UGaRo;&yw}dL-@#H9CZI8=HmQXlPSw#IoLrIgca1b0d#Xow9sK zFL|81;c*|z>pX$dmYytl&WlJ;Jx{dFwQX&d$gfY@>AdQN-YxNn)y%JpSvn1Ha} z&~)lKToHh^F>1=1zi|l?mNOmtBjV1Y7HO_9g9&51y7xE!C?6U>UY<9GHem)4Hg~zN z@(H!62WUVdb`x#jL8P`WI%)erl+po2LGP^qQ5_EBBXu03=X+L6UKJsDNf0%~&BIol z86LBGB{61u>sNBPTjp&n{maJ;Cz4an50OpYXa?QpoTSlgzG-KP--4V3oCKhOq)xBz zoFTo!CmX2#9;i@l(pXjc&ex6aG9V{w&1%CLYVWRXb0!%5njfG5?f7bCD_uznHeUhh zj{Cj%UKOf+QG!w+MPmut6MhWE;1$h+@Q*+BpTxPCqBNG7V)teE?zla-IT9Z}d`KYT zxaZ!8`~98`n3bAFDXp*J-?UOqnrk}7Z^rBC*&x6RwVv+6shL}(v!ac-(@>ou_O7m- z$4dt{eKf>ij*!!pD4k?|P8}2dc5OS;9``$r4jk^sfy@0)D~xRrk-n5`^hWSeTpB&2PL2|Y{It$6OZJS9Pf#{le2Drg}&`N*Y$F@L|vH#$YHuM%j}?@ zbGmjhT9v7&@+bha59a%frc5l~sj}qnIeW@LBKRZ2w*dr$27jRTBy>a?Qj=PXW8P5; zlRyAF(rXaG!#wOe^m^yI(C9LKMe%{s=KT2`(PBMe(F@TQui3V?x{YeZ(ZPc+0Zt<_ zI#WV#(4^~TPiQfZzCca_5`*3l`je$O)1CHqsG9ON*C`SL6QP0EBWQcgF$Y`K$?>@i z@Ay8Pff+!|4Ld6!k*^1OjDHVvHTo+gYaUJK_9>7c5MkRdNCObkhZdP%UR6=NEP2`i zdmp)uvm>7BliR9R52e~jAzD(lhijjg3?u+)yGa*q&RZ>jRur4WK`SUFV_+54&yU$V z!vdwKveM{-OwumQ99LBSs4|W5UUn{6UDZzonXTvS^-ng(5XEV$4(Dyfgh(S%G&#$& zLDR^T3v_TIgkH=A72{nt8kQHEA5l;nxGmy>)$$xJN?@FVQnZf&RVX$hQvAE3ZBmYH zv<)iXSiATRF(5%QP__+QTP_R*+Q-utcl=lUU15z=00DC-Wj<3L7)Ttx+1w5H+w%k> z4qNi|-gdJNLzXxnyx=FJBcKtUY_kW9_iFgn3?WIWu14K z)sO5aw08kkXD~suxD1ZZvXiagbh)mCZRGq}4}|YPy%ngodkB14{21y;!^0z1vXR`= z$qjG!==Ja4WnItZwDM7ckKCwXjk-oh>WwgcJpgj%|ET+amP4ap{4jTGt=!l)VYuc+ z9!3yht4%7}{MGj3>-PPbw~_1PiY^&Gr4o*_kj&A)SjDM^{B}7-1+>726=`X^S63AR z6Pn@-nyDUgGzd`mN*Bw69CASx76uWn)h*t2wY7JA z2GYLGXN0)%$rXtVz(AJ_s$C$^RQFf;s(lu|v}J&Od0idKxW!kb?RH+a4cj7b3Psg| zqT1%d5VCjYyer7&c+4BtZK`ecuwK}r1u|N2;~cRgKmxG_qB!yo6K3-w*^LM|Ej_$k;GVB9aVFt<`(aw(cYVpy2@HWa@6H z$RRL#5@=YyBjrA4ed6Ne+~lgd%5}cXqG4D5oI!(>f=!z~-AWAqy6kOY`la{QY#n?A z7;i=iDoGx>e1atHI+UFP=0T5}_I+4^2a}JLoO;7Z*EbfuYZjI*cTz^)HTz+aTPh08 z^+RHz3LaK;dbj~uI4n+6yUVI#F7z-_3?R%ITqNwGG^fqMSJ!K;l0k#VKRD(IL=29L zIWM645^}zX17lpd4thQZy=m8H;33ChvODYFO$)Sxh^>PNY~4Z%S}(-W#-W=tJJJ`r zftQUA5aD*F>lo%~V!xHqAakRwa2rLo%Hm=M)9XJl68RvWaKU&y-uHuca@r zd8yTg=BScx4><|YP)3~8?@z4esj@X+XYe`uIROdP>77Dj9;+?&YOB}?8i?>7i3TE? z+}O~gQT8=x@(M82Q~I$C#<}$@SJl4aDlIXqiaqMMhV!k%PRO98MOEX>9H)0&Z+kI& zA=|z5mK`rQg|86h(T|nF<9b0Mca{lkB_rOKfQ2jr2F^~T=-PcsVcC||ZH)0Ni6FDg z619gN{kPVo?B=?X5Q~$=VSKM1j(vr}-wT7@%iBt(^f;>sq}H~NM6I4T%cc!|Qxxo; zfK|xY)K1HW+V>;r19dwuTBW`phtpvz-0WIWb@x2(5ESX7XNxUWU^xk<@({Y_JSej@ z0S6oLReD+VZM|H^T*@pTwa@?Ppu&E79BCneQEo>GVTVA+FoUz0d_6C(&MjB`!&w7B zjNgtlJbE%_KwX}ifHxkJ{1Sbu*1Hs;Ibzalk&*_@;>ne2Qfm?~F z-+t9WF1HLGwe}rr`-X}2(Xgcl2G;7Y>q;swzn+UBj2Z=S)@KiuGq(l6LH+Ha$j&|cMqXDypdD%XY4k#E4^0f<<%O1iVF^Xhmx zt#;v}xBw9%)0Y95%&s)l(De;F@VVhCNoeAK6yPdM)b|{VKXH5VC_gDRk3W@!mkSdY z*OIAQ&=dA$EO&oq_d`8`=6aOs3&qC{eQJgExFY-{9jVnV*!3G?lV{HNEQwU}EJ|r&&IY2blOYkwm;) z$0Ze7=;Q`P$oyaM2jex}4a1!Ht)KW;6(~Th ztv4bK2_%19tX!D?CWllh5~u~$%`|LEz;#Wa*fY`wyyXbZ(N;=NF)+^w>CaRt3^UdY zf793uD4NsI-L^4$v`OjG=^A3pj+R|_dIZ!X0kjFm-GgKhvG6@oDiO1rq#idBI)*nM zF2TtldLk+7_GqM~%`Ml6_iXJv0}&GCHAOcVZ-w^ZN3Q+agm?lIT>3t=pv11aIK;A! z1`4_prrKI+ih4d832k^2jz&*gtwK?EQnpa*z)LK!F14joE zW>J;+9nMjYQHei;k&N>kK6sX8x;+{4*~2EI0Rj_4*yXW!ZY<(C5nBfmPft(y=*=6v zdGiL>r>8zC{eo@V`n;ws_LXquT46&3GCyWpk@80lIRIbq!+RzeQ1tNYJO)Rn_=yEB zP6hxR1Q2}`0bz`|AU(q2x#tb&;_eg;&H~9ux>n{{mZ|ZYub9qph*Wa)F_eot(v-e= zCPNytAkBGEt}`tE?huC#o$n(K&TEP@=|ifMqaDmFq_{EgJ<~q(JD$1Tveg6G?PG5G!c$~9a{ly~l5Z6~ z1Yzb2t{#F~8>Yd7ON~^iy2^s!K=nRTOX#A%hUC4)&=tz{`JDPW*A^w&NcUut)#2uzS=ZPb=Fbjjyn zh>&RHl^|+S6x*56#6Rl%PcF!nIai)(le4dd);MP z0Boi0%KLP^;?0{k_~he{@$}}6?;GI_MMGRs4r}>{r%6jo@qN;VR3+ z!O~Kw60&@`c)Cm)Eqsp1a@gqQ4Gcj}1$Dkn=cT4|aGGUcC7i7*g@O%$;!YsD4eUL&wx2P5%!tN=LDIH`QGVemxmvmFUn8xJmCCW39NY3rRGY%g- zNUk@4W>d|%OY^2uC79WkdSPe?rSCyw_QvQVUANM4EnLqrgB<(YeKOa@_B<35b3dgq zYAXL)0BbzRPP(NrI{QkrX4&CX=H7v57>*%IG+fDKDa}t?$Z_INzEApjplggHYus^{=MFqTUNBonD(8feXJ9Gr=(<2EZ3O|Ul4o(lz&=j^gF;?*O-Dnw{ z7-Weu0F<+`Xo=|LFlk+68j%Ai#4COXnxR*^RTO}gMzwcey~ z{w$>;*89?1YCAZ~W5^3?>8-miBY+-l{n#oM5TMqb_L*ocIor0i@#))!QYsk2MgB-8 ziJx4WvU=8aXX&yzPL6bLT79r#P5m6hnrQWnULSHPk}N8#(I~5S4v)mjt)lkjdV}ty z2)!Kbp02;gLs?wAPDodVb?Z`XTT7~WqP}H3_*uEwN6a;{{fuLt&?*!od$n=v! zrq{aorVWX+jT+B~(AZy6YvFK?_I$WW29)?Y8csh*{}}5OAq!PWE*v2 zaClNUa%8NW+}2aPqrTB_ILP1*2iZN+N6ASBQu=uC+|%;Av-}R<({~Bzak(&^_U(el z{@3-f)m?ZasmVww(w4C|@as-k)c0_n7eD890EY=o4197OLW(!UKQuARyEOpB;*Rby z%yKf?8mbp(*2VyZ^%R(GA6xeym3w|R)@fUH3Edy)`GM&IohI=#N3yQcHy zBRS@D?fjJl{gL;~SJYDNRje2t=9#RYm%InN}#=JzqrnkSDa2 zPf93SL$0+}lx;()ZSwR{YZv-Kd33IDkA(F7D{R-?B$J7^3@R+ga0elNlJ1e7_nwHs zaq*H@1*j#+=ScXZIgK6(GT26!rNw-9DOfo&g`J^`0Jw2T6W3XGrdPbm4pihg&AX9&@4nLTY;_*zW%Lgc zcTM(^;T{glLvlJ)0pjJT%hUDX@MVCIuP2*8@5lWOR$&&|9CNa;H!SO;+>h^bTs=fw zzZh3LCmoB>gA78kpb=yrSLya3Bp>Z(AflAsn_esCIaF-VD4(Ru;};W#4NN$16VKMV z#IBouioBP;?0V?Cv3Ditsf%6^1Husr=%&@~GcYm6HOkd|Kj+Qrz1KfMYbaJh-n(Yu z08`x2Q$i)7W*SETGS@x#vM6t%-PRx?>O}_J^aaM}SaQ89lHeXhNKBA>Z#Sw5k1->^$X&cFjmi9wG z55}TJ+P;lM`n$B0DGTSBGDCI@NSUM$$bri>qF08Voop`OXkbN+Om|SvXFK{ z?lkx=fGIt4*2c0;m!#-i&poOFJ86rz@`43$B;;yU?B*HUVAH*3H+_WVAU@I@LXA$BH+LI(rTxhN9Oz zXjF(V_C75R0JO5Q1x65SMm4&7P;)d*Kb!#xbI_co6FE>&8CjiX<4pQy=}bmlpFsfp zoyUPWK41>7R*y#~CpjmkqqF0&)*LL$>@<tp8mt;^LIR^f>=W#Y(`RlW~Gd{LCE+N-h);Jvj8la-cqt2bB)tL$dYiw)~m6Pfy z*O{hJt$bt-V-9CZGx$8MLWSVgbk_AuDn88d$;Lj)KV)MlGfUW5Qd*5DQXCYNK5@DM zh%271*S<>A#g}~Dx2^9T(ZEF8gQnGwT1s1`Mq00>IqWBb)!A|eAUX?0mUWbWtyI;x zgAh_KtISyDJ%@4iZJ&1?>wX8(X*xXQ@x1)TG8=mtW^h3|*d592cxA_Cd}rUyAc7qu zb{;K!9nw#rqGzVpqz7e7a%zsEV!Dpfz)+7@j?r+Z_G|_ae2iei8V-fx$qu?wKGy|m z={3KmPpZ~7oVS$f_al&7)Du{LIcTK(d(4T*>Ea}RCy(dq_b?_vdyfP?@}Wnr$h!k*Jqn_2g9#C!k8O7V z=wqMh`yvoS>7_Bkdm^-;XkUp#3#OKMbFdkd*e<7Ls&y6wvXd!aZq)gM2~BA>2w`{!PA?q zN#yB)Q3bI%4SnhKIFUi}+L-io-Gq?5xuIkkq-Ucwut&1lkiO!eVBdCZ`-W}b(+W*b z*DEd^Ncaj(qwN6IA*+ibfQ0T}^Qrxrdn6?3q_f_QCIg^qH`c*1ZFheuj6^Wu=SZ?= zpvJBxGCa_h%Zh1T0ta`}^(0IN1gL=m_hMUk49%Z4R4mXbxr3SesQ8+FQ$`tEg=tCel~z zQH5;U-}K&y2~0%qM3EAJMl-kxsR@=_>jG4B7L)NF9Bw~@K+C`+)-sl+!k6RI zZQoF~&9hsux%?ITm6ms(OpO2vB=UZi;l2~+zj2&vwdMR=xgg!M1YnS@@O!#Za3gQ! z1WJdO|082g*2caySy>9&cnl)zhIJ5sr7H)+Nl`L4C4GBZ7ZXqDnj8qz-8SacCP8x} zg9FH3|Cd#4$X8q96-{sTp)F?YX0;sOfXj4{CmBDYDri7EIWkrUQ);FwsG%a2FV|ay zL!ms`8hwZpJVS0q2e}Y!ORDZ=!)0sxL0qnvcD`J2eR^sj;^_%*-aO%Yy|jAQc~NT( zM}aqZLO9uN$yQqamCDySp2xtws_v%(x4HBR3gh0#Y`J4}NPCmKzM zceI)v+MZ}Unn40I*Y_8}1nUfvlLQnj-7!AWF;35z^TqeB>lQ<6&PMaORG_S<%z_AL%^HTWSn&K2oXmQyxYn zNw@pZ%}yz~K|^Yw%J4YP%k~pWlfi=3Gk!h;sqjU{^2p&L(=9H*n>CX?8|W9rLMKia z+c0(yNf!_Lg7X}@xuq9&eqABNm?p+Q@&%G366qV^{3HU-Pfw587+bdTc@<1pR=Pzq zou}>DEFEjA%LV(kg-)tRUYgjKK<-vR3beExQF*yx)lr+x`j;CtT$Qom z>}#f)zV*_gI_afmJYnvVOd-E1ioZE$L^Id=hI4|40h&s`o>geK7bH)~VV7gXcKB93Mc5*xyA$0~5KY0jL)~^8*9uDRouX-flHOyt3 zqfCj+<>P@D{usYzqDOv=V1hG}!LF`lLt?+OC74LM!fq@~5AS8s{YT+u@&QZ;D4p+c zB&TPz`l)yUw~UdVxuy}QJ=>%8IUDEJl2jZ_l(Ip#(f~yNp`iClv@!IpSHh@_9tmri zR&6bd4LocaMA$Dm)Ghr+eIWtw{+%aRLK&t!5ReGxiH%P`V^Eq-n8bar*rg9|lCBh42?+ox z#VeEbbeZE*t71DgZ1;N~B8ToQxA_u<96WQ9s~k9vpo1N2bb+pgR+Z}cmJ-WD25%o1 zgQV-8r^ztbwQU)1N{;ROH;+*=2~*@yY0YqYZX6RFQfkUT0{BAW4bPGt*(6 zR_2QvfDud#X(kZC0A)-wf0b!Zb}btYi&F=H=)Dsz{~!w%ba;0MR#WB}cDQJsEqG?*{z0vf;AtxLz)J^Ynx_ zZ$83DAGHnV3|!bm>wVuEaPM_gadeu(3GljD0MX)rGaQsWypv_j3=M*Tj6U6is)k`arYfjSvkYbLD^O{9% zzFyFp=|J#Shi{z^Q6||Dj(HxFqv{d9=13(UdSmi#k)2l!5Mgr${2QZ5=XhU5(Xwo3 z{&AgtDXy^$9v&xqQux@<>eikGtPIw3jr zL}T~Q&3`%rS2-i0i&<8^JYaMCH0gjSgBC~dNiZ+Sk!^oz_x}zaF0sMJ4j3Kb=WqvF8^Rd+gX=aZ!+Eny(?YE zhx3;dxnFyaL>>4^1{)+dq$gelB4}kRcO1xp2nWL@Y1Zhc`a)*SZ$1$z`cNL>Tm!Mf zO_&CcAMkg%cd38FtUSjfXdoW&FO^CDaym{cnfi&HUw_+a#@ai1|Trl>p?6@moMG}Zl_It5-?iOHqtpB6W84z;75ycNMHi+y4T}i zH6}_9uj^HS#%PBedmdST&ER24l2aZwBzlK~>P{5$qCBS&(tD-5S&#bWs+Oix!;+Tk znt=pAmdzeHQb0qgDo}g;Jzz`D=6Jw`&SgX*jr(z6+iay6@r~_5 z`Bof9+`D7lwM;33qZDl0fqHDHdkm}K{6wDnJP&53a(V_-Z1@ySa^~e3(^9Oa{tyP! zlP4J(^@D*4rz0C3OSjfgtn4JDYl~IhpyAtNG}7&CXmr&oY%kgN5(wulw+#d_RGPA=?Z_ z#@6IIq?PM2IZX?P)c7zpSWFJr0+0|-m}iOKW`8Ha4mmpo5sM?7XX0xD5tRSe9H%CE zK@VTPg3hJ`#<=Eqn^V_inskNfhzuNZ*~PoD4Cm}{`VkMwmeEG^@UhahX(*9>NBq~6 zUZ&^lcxYi%7l+Pn!X zJaTh}+^^ZU^kt}plb)qxs92h=mE?TB&f+;69st?N>1Z$YNVxJv+TdwyEoGqRJxoJh zQdR~f$;xir;{hTlRZ&YtQANRqqHUu&-L&;2)i$xx!9>YGB5zJ*M%IYZpwFCislK_E z_+rM5sb#aJDjOI%wu1Y%;ke&%96OHtfqGQbgPni4GhxQf_Jla@ciiuH+-`T=o^QC_ zZn)oW?YVEX6#yfKH4R)pM5^ql+%0uB^L zP51XUD63np|H7Q`I8&kX+VQ4@)s&^Utl6fQCJ+3baoyFbIe7i2#hg|JY$yA{P>f*0 z(qI~_d`HE7b}(o#MmTuj=X{LiY4xMlR8Ne)P*ld0Uj$M!(sUjqCdT#wQ4IIo}497i(&3X3G7x z(u>XiXv^uzJ2LF96kGp(-!|NCw@xMw9DV2Mn#1h+yH-Z+`&Ha-ZFQ*IYao2YV-5b** znM5hq5weoXG=N%>jhe`}T3t3BqeoT3W?(1!M1K3WH6kIaG+kuhh(7W9da<3W6WC&K zYZMX`>T=@Lh`K!1!4Wec154ZR&^?%fWSAZf_fq}_J*xV&8kvBv>kRe`&4uLeaJK<7 zGU0n9z!s-jJjdr&*fYH|e6QJ(zqjmbyn!QD!3c_{ami(}aM@OkBqx2pAlp+%@nIkd z9PinXBLrsm@^^7bkNm?SloLgqd{;QM!pc_3Z4qvq6{@Whj$T zXR^QQ40MG3e>_Vw+0MrDL6_&p^8FBpTLT? z5=jBD0XP^W-Rck}3P&I+ZnC-9aR4`<90m1OP!E6)3PhzIz*Y;&(RNCuqqrlXRO*6D zVeUedk409^Zu{@uwYq30%y{tdsGlVB;!eW*9;6KB#g8kdOZ%@4(Ww>!KY83@bTj(eEj$kAHV*HPai+w<+ow(h! zmqUk@Bux`4F{OLVTItc#q{OYVjYFR4(S>65LlK7VTFP}IMr{1ApAGuWf7z;B(|BSJ z2HmJ(JCly&*?%{X2^XBe z;=$jPPqR{;h8Xm(3zK<{duHVp)}(HY+404n`*QeIgvS4G(HVh+ZAY zKXlh2nRG#aWpe9hYCqjT@*s)rHV<@ax zY%XkHwqd+;st1FFQ;sQj|K$BSNRVE>F#bJd16&tvu1~WxdB5iw+m)xUFEP0Bb(s8e z>6uP|p7gZJ9u?xL7^9)yCqP6%SU!@}z}WDErIYd%g5cz!_8rrQrGFKDN}sQ@nLXQd z=!RZ*60!9mfPEM0vTfM5(pF;tF^WAA zj_ znSto3PMW+Xw>^Pi(;d_78gya=qxvVf00L5D;Fh=4dSBEBL?Lit1~NX4%i^BiXC&0C z?+kjs_gus!!(IKBD7q+(Byf@8h~+tNw8D`7;D&V0WmP4O@)LLFO>8R9nQNm9Q`#m= zt21n&llFy`aVSn>v!t9W{gZ=e(Gi4_LRtzJGZU$F6crP6!maU-dgzX^k(MU!? zX(U2^N+u4x-fpk~eCITMF#(9OB3@jW%Sw9b^5CELw9DNc3;NO&0Lu##U$zh=Lh(;b{ zbG@keqZ>ehtMtK8hzw{wh5~?jUON!$f4)aT!Z+j@!|p)Qmz015bU-O?R)}de35|w(4FbTW;Avc~1}LJX{#gl)o{rJ@7^X($M(u*{RqS&yk9JtM9iL_c*5xwa`Iq;a>u9nlfmu*h^slIILzX95|*_4 z3r4aLj~_sw9M zfJDPi&JWi!AwbEK3+a&{+m8e!L_&tUbrNwqv=ufJiJ|oleUcm3KqO?Y1GDu=JUw0U z`tquTr4I8YsuGFU*H^rJvLQ`hfBkhB+VtWGNgUc_nM<(z)w1aM#`*^%A?$am=D1UJ zKtDm003QxJ86hiYFE<%nsFKM&UdhNz6}D3@M4IB{y2{mx@c?k}_AXkR@GvNJeeV3| zulH;Tbyb!VwmCaVEr_9==!y*XebhoLr~K6LKbCIWm!$QY={zOX8Fr?jd91^d-spWB z(nQu9vCEu@9s6a&_309ZH|>3&h`kdDArqw(fGa8y+-4P~Gu&LBM_^)jPsM%IKM1l&U+J>@pG9g5QZghu8Y}k(4 zChi_&B%&YV90|*qJn5R^$$1`e6mF~U-bhT|4K4u`C(qeW7nFNH0)G`PR}u4~8eY|n z(Xq@CpH<+<37b<)88FF&YafbD;-ugwWipX^F9bZx{t>zgQd{RW{6<0}ljNFQh|qGa z-LFQ7WhvR0rzgC;ytJWB#|_6}6DM_f)uZarrk9tOMkItxd}U(nMz+vfQAOeT@g;T`v@=Va~UFX*T&-H^AcU}1+*SAh~r$IwhA31{&>%l-I(DGl( zpWMAnRtP!GJ$_jh`jER?ZG|9C06;`bfn+Z-8R_EnNvo!S(bIa_z$#Q<-7To7_DT z5qim^#*-MFQ*%+4!yu7`o4t`E=JWENkF>}dlO<2sRKI(D5<*F~R{pw9(GB%_5K%OI z4tz#=g->XHe|X3Aa||)dk}0Zree%9e@;vLpvloVVVyGTdH+}AH>Fj-{gynYfCzq`^ z)~!r?972r226i3y>WqV}+X`E?i2xJ=-=O4y zYDHl}<$|Jh!?pIX8{*XGO4NfJIk-_@2DUUJapPzp|dtZAJ#D4+*1O@q;)<7!ExP=OU z*v;z6MeeN-GU5F@a_egXX(^}M9erL=D|DZU%@GZ0QI$Cux0@R}{?$ z&v3=iAsC_&my1-88p=N|2rvd<9%hK+SMQLlX!9dlkA(C@T(1{gp8686&rf}xL|>uF zkqAE|s|6eDW(M{eU#A=&f-nk#^8Bp$tChRaibO)=@<>n$ULr||{x~Ax?@ftBhD;I; zhdVQ}lj9ukJH4xNA}__t=m~->IuXI&4E@dXi#dkxopjg%3xIdx#@6N$DA}{QeuzDl zGdKEr{%(%s;`|}xxp3@$dT-&^1a!J~z@e97{e3QDn!L02W|>rXf7CtR!@RWfJpUfl z4$;x{bo#;@C3Jc^^>+r$#J+@YBY9uNM|awOD4xE)xT6k9Aot#RxTC)l9Q z$WVheZn4l!hcd~$2p!VY_e)U#A@bNhO<;KS(^C4k-&G7+IwBn+Ic^~mnpozHw8aiZzc@E+%L|6P;~Q3eth(Vd!m zB+pB%O2gz=N%J~9Q#zL3?3hi5FnC^lC+5e4zypbI&NKlhirx?q@j}tPbOrAD0qd&=m2)2 zA(T+KM?sJBa6Wq;tE)M`dJqKwG=>)yxc6k@ageMm#HSw)P6&g<*OpA}-DW+KVv}k(P0DRzTBG6=_tXHKcA!A zxsG_u5_$zS)j47OL^N^3dqa$z(IErF+}9|dj?Hj}Ye-HvWMae^=%b$)1qEEVuLj%Y zA{#WV?Cio_xp=Ne#X<&Q{OkD^+;U$WNaDEgdXQFe2xG=#3hji7k3W#+&fAp<|zqb@hs%1Q)kY^%z=3?4-lCa%>a-tN7mW! ztU8?7x}`mG@2c*G->Ep;q4RLXCHUj+&-K;0JGXt0SVo>+Oum#z{{wcxu6zS*Ms(ua z-IxJUB}ZGtY#aBrr;9xr7Wo?OSFY2e^o(bAXVob4XrATxWP1!)dPPS`xlJwLTV!c4 zJ;4&RV`yYt$;yIE43&6R81slVeb6GdU#?eslh6!o;kI+N{}l%BjP0`N#Jy&8tQ)-H zCqWn#ets1Z`GKj8TV?`eH)Q{Qp|)dkX)8hz7nBZP$W6AkVCioDQOg5&pJ5XZ>^v+( z)(s8iPu0^5^x{ieg>T__oxL= zWOE_>JedH{p;Z!=B|QwU_$GR(&lA#l5!b!%R{ezMch7kD?j7E}e~0Vkg3I-a>*b=m zT({M&T2GxP|BaBR4H+SXI)VDx(aE=^p=XUF3unC&=zv~6)S~p7lHIuy1TWum&hzt3 zG~D%Ak21iS$eoXCiqq7w&l^iG$#r+K>~IKs;cw(Mj*MleRj^YPuXo&8wr?vpXO?TbwfW&)Za;E9I?|z*8yW?_i`e`g&y6W|W$!CCZ5ztAp=`x%Iwpx%6x8mQ z_6sDU2pRC>>C0I8WQXKNCE7dMBS9K!4sR0gFVpOL=eKv1|=?QW>0cQNJ4DXMh?tp2zNII4P#Q{p)FGA+-R910mTcQ{=)mC8gag6z{ zRk)vPZ$ux~bbY$w`S}U&o}cml{X2a4@E-eadq>F5^rffAdir{f3F*o8!To`O8IjOu zhKw3a4>s}lnXW184F@Ya&q0o+Hrb+ zK_Idxob>8EJSW%w`(E8h3|8_Z!jbqar!9P!0OK5Ay%7YiNYLHy7GAsslzSUCb>1$? zZ$c{62Hz8%1&aUH|~i!}6xhh3N?ePyQZ>^w=BmKw?s3zn+_gyXy}D*e_34jRpvv zM07H-Rd-#%8>8%{{d$+VY*?f#yM%BJ=;a@%Oo;En;v_SsYlELjBwtp|ft>G|Ni zK*q$j`sWm~KJbd!e-H)M+9KzLLDO>=M2JY2rzPUB%07X}=_JNud@okgR5bd}hL50E z_Fiepja!dN7z~OEw6?nBbC(ys!ilF67g09u*-&!i{E^tG5*(G}5cv-3h8~AN8fLu` zZgnN~s)PR?Z{LzD0LcJT{8^Gx3f0hb(5mGGt7|?#dIrvvj%G&!c{z_(jSmW50*P>Q z8G?0vgHcZKq{&-5_g%#+;H1VZ=xjF^p`%qEKka2@z!fFFlT(z9oDcuhZcp-@0SCw( zaGp%GZsEHjC5ZCjBhYGEs~DwFSgENEYkI=FcS0mS*xnLl8%k~3BUhXJw|Q^lb0Z5< zC)nk`1Ltf&-|B|dMa_pQfINba)&3;jkKm_^hXQ7m^`P`Mj_l7JsmSGOC3;fci+7_u zB@NqcgJH;og2~B)=pXeb%G&H=AZ8HRX}X{C2l9O4LIcGeN2#uUW9~s5sqgCfy?CEL zA1t7+i;gtJUJ1L--$|HaJM7vKCU50tuOr-HZD^0WITPBt@zQ*3>-Hf zHc6_J2-hPq2DLKfu6M%;bZ9kh1)%}!4$8@>KGI?}i`l75x>5j&2Ot7uWX}sB6mww-O17l7uveS26D=}1r z7Lt$>cF&2?a0W!`lqVGVn`DF~T@|iu`y&8gqP7YUSP2EO*AFTbK4q4!1OjF*w8$rL z$$+i^7G=#yMGUu{Ia6(^cQWI9fRspFHta$qp090a)BAUL|KUBhVkKiEk_i!uksPeZLnM)Y zxFF{BW#YG;rv$j;83dUT3a<+Y-E^x>UFWjbSrRHq!OX(T-w(=V7S6;6Z%6%OS8W{t zc*wu;(IV!Pa?0n<;>9b)J!9HwaxcUt)w7XAm>r7W&6BYTqxlpIkRZ!xI}NA}N96Kk zp_lDVl{IacObvkEzDYPF=_j($2_fRsAm8M?uPdVbR+sI?tSGeZ^%qWSub1z9Q}BV3 z0WW*m0}9{8BgG%w{grd^*)P|t1M{s%LdZlT6ctA~^qlqr+6lDvr3IBt_=s2}{MbMu z0v90>#pXxUP8#|~bD;jLx?YJYL#S+MlN5X~>SszY=;VYd2}!`sJ2U1pfHlS;`(a=! z#>HaE;a&52E`lq!ii1rK8ltVI#`aB7$bJB%iY9+flgc~`geLF!m3>@gPH5UI7VkVj z=82LSKz%4~-@fPxL~dn`8`$Mui58Cd(LsWXr#%~gI<(0pkJ*R=$SYWrF&TPdb&3rD zD+m`HY{o`xkt#4T%AB*76jbDWT2cmU*-4n~z9;u%@7%&S6a3s<<rk{JUjT7iEr_x`=g0P6C)cnwD+ z`oa*d07meX!u55wm!-;TY7I7GVQ6(o%Y-mQ-94U9355ooT6{x#av1sAMLH0bb2kOz zUfNtee#C{|2#1l)aBP7P?~YU&vZI$-P|PusZj6V8lP76Aeww zfS-?Gzfyh9PNvSVz$Bk$q4;_n;4e&1ikwRQSmBJEjxL|x&PYA>4RO}9YYj93Ly14) zkseZfy&OE?a(&cvegn=+TdoTpt+0DZ8(n(O1c$V)!D*}uZ=_UjF90qG=8 z-wHS8ERTnzK(kF)m01|v6VQ;VtdD{_ogkc42KPLbyv*N&VH1)~6RH}JWPhvR2Y>Nr zCi!aa>3{eUp8w15TP~~a5K;(Twv=6PB0Hkg{ZZs88Voxds@}xN{LZg@`#j!%{S$uT zKmNXI)xaOHk~u_q>1p6lKb+9Y?NkmPxQd=@uQ7i6-~Z#lwvPAy>o@$=U;O*ygCUH` zPdA`5-KO!J7)0O5q32pojbO_8-~Ik?;R7@H`}25z|64zSfA8P=x2*w*+fb%Lgaeiz z)%8x8yn7?)KuFF{B@0fE_@5^ewY~G7{iXj7Uw-`h1b_nn^1t}6slGM9)8pd+zmbT( z>~q&RR=Xkykvsl-El2tDb=#f)=YQ?5;un7O2dDA=^Z(p03lK_{@FS1^t)4RdU~t|N8&*KjN4F#$O+o zv3Bu!{crwT{NOu3-!IL6j0SkA6+_&Hw?aP5GDWT*1m|bZPh^4gpIjS`%MHVXIJ|nm znajY<@6&HSquc?jyF;Vp=QtmSko_EvfO{_-jTF3*2RKjsN3J{|_12z~`vZWTlQ5a0 z?-NfUtIJd{Dr%n~UAUlf1#tmuL5o66hDF!x@B2vf&F7Azg8D{vI0(2=Gb$C>I+0*z zl-f5Pli?*G6dn^iX50k*@He69!@oF5e2Xx2deHLkq7`7U){bA-)Hv^|NaMj z+;2Dz(!D5T2W}bW6p(2LVhw1dSSBK-NBwauJ7D<9W4@fr*Y^oXMw>&=%YYmJfq7DK&uRzL!`MbLn&&EH+O z1C?xeQ@ItC8?~N=qwfw|(Flbq-&S}+9O_X~Zx!`+px!EQYowu(2eh564}fost#_p# zwPLFUh1>6_1sj*PmxTOrO4)))#D)h>Psaa^RfqfZoGvD zf%dNXe@Y~J7!v+m_s!G3%GcSgS*0_j>=cX3XS1uZ6?Cf=x2@o|ZMun^jzt&re#e!g zpdNMDj4t;`Xb(yU88#`*r7Zx~#V;tDi86$8l~YFtT2G#Q6_yHXE1T*l`_vt+t=ff9 z`urs!6(wsApNE`eG}p%moa`y1*JMFFqWnYdk)8YJQ63%mVumz=7!cMMrv?)4G1Xa_ z^?O=x7)DlX^`qPxuleWF5%hZwhM;A(^@T6wcbaEJIQk+PAxnTD+cP2|=?fyzWQPd_;s8NOb&#C~&-EsTqQKzED#xQ+Qu*$X+J`8!v|OBav< z#S zMkeZ3vGIlt1zXv$?`@-_?bth+pw_~c$iwk^;CQ*=_VE?RO9fs5+<@bDpd1^vo%1X7Y`C0i39h39{GGQ;_LAG~%_bwGc_U$5>hvH}5a@PZyNIdEmy2nVkfO8J}Mhq28Z9?== z)8UK)p_R|R?R`h;9hbeGKjL0{t1i$Qd{oZsFqaii!E?Y1D zh|}&DuJ+i;Qscg1bm0RFL%Zv%kEuJS_}%Cv^XbNsS&xRSX8gG_021R;2YOq>PVBRSk(fv}LEq{PYc zBP>nn&nK~HLN*~TEQ%n#tf$^b_ux)?SNEc#PKr6@bIgWzAuG@nBD{Qh!Rzabn?QQN zPm*4_Hq4{q(&9ZPy^oe&oiJ_y*j5y=8x4C?PK626z-plbxAAW1W>zv zjzw8J;2UYtkVc7ePN&|R`ah<@`;%RiiG_~}&B)~+y3L+j$(FLwzNtU%d?0-;Cgi@D zW6Jm-qdL+s(vR(YAQF`-m@1CmGjUKG(j-LUQZBfZ9hdzAzSd3%q}M=(uhSZ?b;IvM=08`Cen$clKQo}vy2*xECE&^ z0q+cCtq5l%Vp&jU??^?hTC!AxZQ9ZH=DRUiG5RPt{gcj zPCe%!araUt-#%`Gx(V;vvVqP{B1&n*p%ADa3mI|n!(%qLPfP&Bwdxpuzig@PiQq`a z1H^4`PUhI_y7_4rD9o?$)2{W`@@Y7~6sqnAZV6 zH1W)1=}FqQ4VTMBcdmYVdb$(CR+hKhP4lgEIGo;OA)|MY7~l=Nu9>3JUFBts0N zKN)14#GWe{Z6R=gZSGGm+tB|&0&-lP4GlCd-dTW#chhq^gK?wtJrX<%YZ65Na{V6G zB;vk%yk4HiAV0UO`FD5Xcux-As!wLlMNCd-Btmbg{+M{Rs;geVd?N%R+7Htpk9i)y z>Gu+u7@?5^tHv}Upn~|37t~7yo*48>D7S*WZpm2o9*Nt5&HnD{b;8Y2Qf_vahp{PIO^5yzb>x)+4G=60e;E9NJQT<|;Q(_44Uc z8|Kj$133ERZRyo8JCR`tK-|{f4&W=Lo`x@JIFcH#`^G|YUs{z!5&O9hHf+iFKsfTS zZ`k{B+gh*Vw#nS52I6$w{Nav5B;;8q8pM>w*FWw8iSU(34n%HQ;z%g7v6LK?T$O6A z#LpK_<$0xfdkO{;QQa@LPk6(Sby@H+q)Um!-u8)jetyF9^YcToyWL&`h(B~r(V=xE z0{yWUDh_G$=8sK(2nj(VAnc&QLp>7B$=cFLlKpNh7C@M1jvEvBq z?e`W->5&M%60fK)74?O|2LVDPZe)a_mbMXHJs}bh0dh(!WSpyNUf?H%p@kCsa#`t( zz0(ZAuSu`MQUrK*I=vYUoEG+|T<39L5s6jo7I9b*mSq5wXo|j@=1Jy#a&u}!Jm`}1 zcD!6JeYf6C=QrGLw+@b)T<+AykpJ0te;Ti^uXufZ#Y;cFzP{qq^9>uf9truzZ`PH2 zBxW+uVo87~!v4vak7jh1x!9GYv|{gn_jUf-PM}MY0p>REfoxK)AG)-8647@#-uDgL z-p1VTGI`gvTubY9m4<>6C*>aX098VzYLmYSxc*jcAl>OM$*=kznpe>v`Rl0s&F0J@ z4#2UMExo5=%MH|rRy8qD1=xP;272Y8fanGsKegF6DQvi+m$LVSBFb-G&ei$j&U}>N z%5=Z%xbz;0=XdYGMEI?5{RBQ;uE9Sd!cjK-sqg(xAFgL0Uh2qkIC*E2_edfddE{!( zV(LA>==X_U14dfLxB0m#F! zGLi8OujFqspgTXiJpH)s_`Rnm{6E)uZ_qFP@CTj1_TdE`Y$zd-$*1Kt001BWNklmFSZ5H-$YZWYd|h2b!%^wCDAtR{{X`PoF;Ni-7HH zJrD_ML;_cUo(S8m;JEELZmku|hBP3|liY^?pIino1iYnvO9R$Thd^{4Uk&p(4dwtv8<;}bq{ z!FB-UwE~}R`1o9L`Fn?Jv5gzmDLNdmqiHG@zybkP8Pwd-5$-47ls~B0e&ZGNqr<&z zuKq;9{p95Vc&?sPF~=G(6Z{p`EuEDxnA&ez2blV&Od@b^#?z| zr|VS>i>B!~@PB^i7j$Tok()>e<2;655Bhl{5orZ8A4!)3*-+*A7CvA8@}KxQ{FA@; zyZB)z5}s6U%=kb4*gq7?CuB%}*J_y&1uLHzz4i_(IPqXZ^V{hbBNHKs`0sz_XYnum zz2DS$XZN?i_yQld4LY<=Y>1cPs2=n@(+6PIk}J>VjzD9+0r=HF@iX{0zWeKOp9ts8 zufP9*AFlS07`&6XJr2tB-TMeMxWDw}xAEtG_=DyC7QgxY4!^(mMF%p1%wY>=yMv_P z0<`@%+oke8}7duMbBTh z>|KR8Uh0J1@P-tIuMqC%3NAo2BFk@bE%ZPq{@z}QShVZ*#AIZef>DID2Vw??A`!*p z1+&QMo47)lb^xfI_b{-dv5uMUSf7GdZY z=R)__{=_4>wI$Sic10Atb4JAjI_aJL@E?B9dJ5p=&9}yoeWxTsL2ajzJt^ET)c9!2 zla!-BpOvUDTh}A8w>fLq%N5tBEB=dL{_}YM?!A^}i<1$9wz8fL)3ep2T={Su!W76v zH8KG>BH=-{cs^))m?Ea)c zxGxLKZ2pQwk=AKDpLJLKSKs*s{MSGKrwtfPfU(^3pkDVr2|9f|j}kDG2O7?D3}$5F zSAY6v@vA@mvq6vFoe+L%8=~!*>dO4Z33yw%zw(n`;;;PVm+d>(#H^Ou5TupcBn%o( z7IC~AqjRe--~X*Y`6uxo{F{FPKlzhCi7&tW5`X;5FY)DLcN_%Od&)t6qiz*D)#W|l1v`+xMfUC5k*hocabddJ z*}WES^UpxPw;4`82JGbRgPQml6W2gz_v{!6g@53ZlF}-@84R}hUqg0Cn#I-vxlqrG z)#+?!YQr-)T#_q`+QoLg-)=W(EU33kQCzu6i3D>SZ+`4HTtwDI4~VfBayJI(6AbIY zwlwTf9f3eQzY$OgbW~6+z16Fr)C$z1>#v9T5iV^*_Du?YreH;a2S(??+E6Ss_~$Fp zTAfVXl1OAAHF?Pi`7ES0iI|6&!gk=VOtKEx{GFwy=)l z2uEMGKJVK2ei;IDSZ`0*NnGyPuE_H9U^RovAaiaHjJVMp1>s%QC{_6Gdv63n@rAr? zPjjoW>{rA3G<}kMR8bogG|bRR{8#E_nKqOEK>YSLx8<^5+V64+WvS)E=yHApvfwAn z%djPrlUQz{rvj<$T*d@7wIUIr{1=K&>nk-~K&<3&lKtV+_M8zqe~@HKfrOPwXw^%V zX{eHVy3ll?A?PiT`4LBxv(=kF-mSt#aJpfHCa{qzo zPwjaEvD11nS9%XSB7l2cQLhMXJ|Ox%noHx9sOrICu4&rZ(Tdl?6J@H6ziK;EWAJCl z`ijg@AKEzHkBZzA8Thn05-}s~4C|3@^RZlhsVvD)Fp#}q`Dt;{^cZ}Y6NkB2&#%?X zW-E77;(hs7VsKx%38n2eC%am=cV*?92DGThN*jdSai}nAFBECnJ=ri=Hx7313W6C<9dck-gW zb!re~XutxzrLwYjY0!g1JgJwPRuB(JVr_X$m3V>ac~4fJJ{IY&mWiKM6}^(D@(cJEWtOPaeW#`%6R;5gU;t zj*<`le4bZJr@a8sUg(*V7Cd(&1vCT2!Hr+SsbvnUrm4n9s}B;);H-zKgp zo>Mo^ktjEr+}!VRxNo~wt=>6CaR`_9VDxio;T?gnp(J-mg?joq0CMJ{PM_WH4_(*@ z0Ix;I8o$;pf8i7T&Oe-%AwluVnoMLp@V5MsxQ8nKfEU*IfgXS7W7d5sZOzOlxgx8p zk{?74L?<#~^3!d~U<`V`!Do+M#oiuTh*eDE^j;|EdHIJ1EF!dJ1grHp^q-0lk-t56 z><(|Oj6jSEcZ`z(62lx6n}qD`9tYXKfT@CO(fLrN797VBmVx!h?n!8&W;Z-ZdT`os zM(Krc_lEKGj!5|YNiOs(tl&z{BqH4rcO^TIIrG6S9IK#FJoiT116rR}iL{n)p&?B} z$X-VU0MccpP~U-kvKm(}H!-HQR&BBKabq6K$a*F+d2m0ci+veJj-VFFu(|&OF|a3^6)&6Mg3|7$T~3 zTktt?@S^lEaR?r~4J1F}RwTl7nAV684c~gKM>(H?%=9hXyX%H_@uLaiNG4nz^~U2Z zWI|iY&EH7kef|iDj$qoSC%dVgcXfOg=h@I*xj%+M`u(tS6VK9+;}X+0`aS(BemslP z0$BsTYF4C>BvM#%rASrn-LZ!8|`t3pOFXK6D0H=t;mGiOb$WbeI81FOhA_dUmkvSGjHz` zyWtaaz!eA_PNkyfyX6IeTwYTE$J1|Dr}7gi1-9dl>xRY} zf4a8L?NbNr<@zDK=7B!->(rY8zcSLANX%tNq=CcbX|2jpYB3YpTZ!~}P>(B^=>ICS!**`6I^2hEqj# z%1MTfuqwaUW6%^{_jXVoqV!q-HilGsW60u?EV;CV0*h7~nPdiwpD0WJTIuUT`;F?T z$i{V+_X7zSz-1&CGUlFB-eflnzeraPH!j`*fv0X32D7f(qd-wx$dbrP*qS#fVgyj@ zrEWbEKG=X)L|K!2=v&;NWhK8YO^$D5V$-lIa%*Ppk;ucFCgi~lcY>dH1cY*pc|QkS zc0MTd;DR*Igupc^hT#i%K!$o9mT-cR=MzgXs0vPxX7YWWIDr|l)OO!SV+e$9N}Qt{kn_-|*Qr+SaE86jdQ+8(h}ZDA zMSiFBx_~Pp_G!{zBSeHE=M>V_ugTr-e-wX(NO=Yk!2Mdll#F>R=mxWv25$PQO#_3& zT$uGO3RemW<}Mb9*c|H}36*sLXHy7Vq>p!*A*r?We?JP_xTyVVwWc=L3c_1kepr?BHI)4pg$erL>iCTuqNA; z+z)T+*F(<(hkIJa&VtTc@q7H?|@0K&$`%04QN-Zp%N=%7%?`-XDO|Z z-+jvqfAlVs2q5L}1NKDR=hVR2JPH5IT?G4ZW{J+?u*A+`jzN~;F$_8Ldfi>j!&pY@ zfp_5Y=gk?tLQjvyiID9>wr5uV#O_JBVaRBRkMm8vH(LnBS;#H zi_(v>hXj|t-0Rktf!*{RAh&Xp0J*iBcZr|1bjCdl^xy#^=P(zj=Ml0Jt(BgnYU#jb ztc)~(ywuGef_hxL1mOE7LpjZec_2K4Ao1Oh8n1*L$Rz;#e(9U4?QWyBV&lbCMiKt2 zvT*MdTEIQ2_(P?Y!zV>^I42w%*ceuiy5cT%cbXI9?kM& zMJP09R0KNc*Ni&}p|=V%V8fIaj)Gs4de#fyWT7Q)HSFOG0G+!>fm_mdcfNjW3;s%m z*D-kWEiCP_tvmx5VOgPnUpQFJv5cCd#~f&xEh;Z$45M=xV(*-S5L?xR5yc)8j0wtuoubaQ(b; z1#tm!1##P^Vc$xz#DhQu-~yD=NJSyEV*#+C?RM*1!-$kj#2$yz4B%#CdAGe_-#5?! z(B3O0p{?I5<#C5d5N`$uCk9Eel{m*5r*Pz?P6i_%$}x!Y{Nrhjxu*aoMoPbO-J*dJ zJ7u{vXm2$vv-5L5*0$>nN-u=uwe93|(rk2*9hvvGN!O-?*IL@Wp%EZ2Aig9Sj+NIA z2?q8v5L&Eorfd=Fypxd2=@quS1^;k0kZL!G@3b?^LZch$pcqE+$)Gq zCIzaGUED*!)6>y)#qJGUEW!I^;(jd|&FYXo|15Nu%9`@sNKFX1>3T5_UG;a@)32z@B$jUi^@TN-bhHHcZpXawP)~+%w4nj*WpGc>3ZAPamG}^zIqY zPfvKdUU9kfRxu)MM5v{pZUvXi1-I)JPwx)!?Eos{vcKYZs;DpAdL<5k+-7vL5gql- z=Zs7Ukto_5L2jtR{VHy3Rj$+Hp@c&r^WCm<<0Hr%)TsAYY8VoQLx%8uT#U6-ZIP+SNrkCas;DEp(UBn zz!A${Lk&j7895H0>i1K<8FZ-gKcM&)(9n-T?%m;LJ73|!$DoS~pW7GIK_Cn1;S|^8 zayWkU;v>+n#oHN^d=ISA$nWa?PS{E**tcDYL;LM`db;B2=?T~C6_?9JNd(YV=Q{d^ zij~S>~j^>%sVa@)ai+AXMFlts+EB%AC3PI&{AdZhO7m7`QQTRNy$kwQm?*349dP z$|!xGH`yqfYQg@+hY!%!N@DPaw#?Mlhy*t1Ib8^sFRr+Lal!S&71wu9czSxmWxrtW zM1ngQ<9)~Fx}!c{fm%V#C{%DX;feq|*PVL#P#XP$ZjbhYBE$hP;0$wTi-ij>!589Ew!>2f<{e% zMvo|QRHPEcc0GZg-6+3_L_jbwnNbhD12OMpOfLsXS{Tv?@V@VrPy&*a#W^@7V~$K`Ut^?JqA({m>hO}42UiCWuUAVMVSap1VwZtpWfk$b5;kwCak zMt)`}7ddnayi?uD#Y2=ii8S$yTJMuX&?_$EDx7Ga+-$mp5#UJ-}&fuNg@$)RO=vf81&e`ENCR+0I;Ji z+QCpl!P^Et7&sV5C2X~z@}@eRT%O5~E5HYXZ~j-ouhe=R4gwzsxB~THl)8bAwp_g8 z^xo*NM52nJ+ZosZ+IocLxC3+{?C*E%A9h^cUvPQ8V1H`6s5T-|z@^Qj;C;j8asfZL zacqSM+qR*;RPc>~SAdST^d$9PISQy!8^+|w1nJNwxt1P@C<5cz%;onopqaiJFM0Wj za|?x)6xn0^gXaGSIrdU)=bYcC=+it7lawv;d;a#1Pb7Gj&k4*bks!jp?|Ap_8PD&Y z@vU!tf%os<?8 zH;2MfX~s#;?vaSWpcC0z_mkG0k*ws*^9Hv4trTbQ)hRsR3pN6dq-=%n$jxYY?f0R^TpE?c(6aSPWHMoh=u8hjfR-k& zSRDYw{)OI%zyT9^e2a@!cv==2g#7>2#kzjC62+@GX6ww4?AaZ28%=X+)sAxxDAYCi zFS?Rln0I5@fm_tpu)Rjmb+v$I*DE1IXk!Bp47g47ak&4WTa(#y85KRu9nrQrG|_oJ zo=U8s%P@y{40?-E`zNujXpXbOuu11n9!?pPr%P>+IIx6mV@t5fxzH+4_x+Ik{9 zp{O?o4uFpqPCXcOFiNcrt9LB!M-A;?eE483Qa~dNJAj=)J3u=Dmv*EJVSBe>d$*yy z->^Mz*sdG4%Z|OY9tltZ%GL*xDNQdMuGd)Gf`ED7`0w z++^#aIAggEMb7C?25X^oM?V+Ajly!DNYL56S$yPdVl!h4A%}|1y;2M4mXEE){2qhi z^`qI%W!hKI$M?1J`)l{TDh{Va_I=0m^D~~GpYW~TBk}I}*@3Oi4FQp%O??F%SrA}1 zLUB0c%G~FuNNT$hjV&?`FMDjGQRm4S0(sE)-F2Q1l1%)Vch3LlC$L&ZZ{-GK5cta+ z5XcRdxbu(^L1KpQoqUIUO79Gn{RW27s-Rv7~cb7 zGUc%`^%T|HM7EW45<%|W)IgH_ zSVeTz*cNTkeh|+*PDS>dMduw2y4&bQ8Hi~8Ik$4$Mm1|AA-^JrTFdj?3$%v8r1e#4rs-0mGqXIS>bz zZ_|X0`8r9>;#L^>8hsR{lH((QPI?u3>kk$5vEyyH-4|bcfe#;AkHoVM|7gRQMB$XK z{7WC&wC@}C&3Yy1uo!XWKE__M#VcB#r*_KEfxr-4001BWNklzX4 zu_eyF6Bsj7lq>(T%gWOmq}Um*4}3N38%XLz{qF zZ3t87kvQUH>((OyBNHx;eu$GN6FIHR@?QZ-MKkA4dXkh>_PkN!IOnM@Geai@ ziI|PA4snZjoL|$*|3~5?!0$(2iH63dNu55iN2YgZ;{W*lTn>71a{>Lh&{ zNUS%e1H3J?-i4INLC^Z{M?byaD`KJLp!SF+WWxJ1`VmqUWOPCTCwhM7hDQqm5xybI zH~Fhnl}t!)gb;}~b%HFWH-HYH9E5sQ)%}{kStW%Y3D~fvTSa~4*5lDh1|8g{AcP@J z8wyvHx?$sj{r&ShMvvzZK za3Ve@&wYiSf$PxjxsHPmE7%4z`eyLXiNwg_b5eY(!aDKumaZ6o|3+4@a!&3&QE;5j zy|*$JRSioaZ2N|%>lN3hr#{j8U0)2~+9s@)tu3b+43X=NkYOZ!9C{ln(!(#TL!C73 z9`L*P`*W93YbQX7C&QUS-jNyDz@TfU@{3;KpC}-0%hLL<#N#p*3Zw4 zNQlh(Ww@Eq4GFs*3Evwrk_aIRoIEUo%>mp^2G4Z;`M+TsM%24E`s&Y3NN|C3BWe>k`**atCI3 zH|cHPGod?fxq8>;LqP;)3_srqV(a6}CU0KP64^dAL%zt-z;LY@9G~}eF}zI9eilaj zD(PYEk@fL&fI44Ch7x@C&j*0-^oJ)3A#SSktj?{5F3pI8=_;3ZDhEa;;B?KLNZ38A z!ec|PFLy0zDf3kJ0fnvvYoaa;nOaW-_f4NGxUq)-eL#Z0zCSbR$Os`#{ntrEImnR+ z+c=s{aYBKWPPXPaU*cf!QGtVjqx2(zDg(96k!X3h^>W{^zkhzlQQNp#CPuk*@^C3A z*MjZZj&yDJ_{!i5gRcNzE9!;88>5z<3B8qU>1Ztgr*5tgRL+y1GvMU`_L58l;A1Exf`B#SHt@Ob z9`<2bnkI-xpPXny(D;;6g#)w#OEGzcmBF6+kz1$w#MEmaKmP9ByRfR*zPDwI(OZiM z(8<=NxFJpZuKQ7V1zS3anB)904+e0P&Kb@C6T*&|r(^=Y9L-2bOWE3zds(|9*KAVi zbhVy%`OWYtdXtqZJAY$$tM&GHBW8zI-#JAf`|2Y@(YxN_BP+eBjP-Y|d)=bkLTj1J zlTe0S_C_zgDK$}KDn5z+Nt{S}%C;SsT_#u?k&t~OT6{^7hjeFq(qQu=j=|6b zmC}rNY`7R@WB}e$WZcQ0z35*#cb*&Sxd(b7y9YO^f|IzOlZZ!%ery>|Qm|B&@xk5t zIehWhllHXNg9+HYcRq8OG%`3OJ=Pmve;>20InT8hT2diIf}yRtGUTK6NMO3E;+U@U ze0z(_;J1-_4)rbK5?}M>Tlqx*tUJ%wGx?NU7sG&o^h^Qzf=J|?xz|gO{f~Ze@&_(2 z#_tC51Z&Vxd*_LSk_hWP@_7i1WGwbzq+U6-4FXIYiQo}IMw>XpldSi=3ghWt)gub& z@XoMIeQy|TJrPHrA5nFgcQ`Vkf%ad2+~!Lh+|VpB4~mqs4yUU6J%J8lQ4R2-<9cU+p_VkC1WpMi0Q~u zgTkDq$W_CMQh=)D@7s-7^{MX^r(NlZgD? z__I8;9;s1gY4ZKd&)A?k9&;MF>+$%#g*%>`jS8)24j&11kh7{JqFw1&5^B9{RH!$~ zH!@LcTk=)pgV~V@(b=BBh*D-&GNBvK>5qDk1%WF-we;Q#`4-whwChrU+#|lVS=!jR zO^PlI6b6?KRBG>a=;OBvx1mgZ7d+}TM@Dw#%Eb&6rp9zC+>)<7Lyq=rs|?hw?V?u; z3fDHNqfhJrBTcqGa|RNkqQGd;^o_SG@t}D8X(FW>=LBf7jvVJLc#z}5R7o5a8(cZ$ zVKKHOo1QAp&Q#h1Q7!EvOEkpLvm*jfJpS_Ml>3s=8qTaUgm?$ zoqz+EFi%T{@BJrJzXl58-k11KlXdE1xNrM5I%%=-GS=h70GIYoCTI3F0_w4+Q7Wc& zOXKe+ghQ*D$gtnhdfQ6aM`GXi?msE0IQSSg9L&qRss;FloTP!`%`yEG&>fyX;6{1R z7jN=x`AE~GWOoe~Jm9eBGw(k)&qEEo^WNO$Mypv`GMH-jPC^^Npo2v0k3N3X@B6yM zdSJcu4Q2wK2*ee&lInXx1badnSZ!AX>md{7sS4+Vy%iP=b&Fs(ml-x8<8}w;NtxUsImP^2lV+%9e(AXFxmT2#>aDO&I*W8A0H1J<7@K z+{H<;RF?sHIrT>LH$on)T_z4={`vY~yJye$cpA@R-7}fe#m!ac_qD)4s2~(aB&ao< zZv9v~k?22}>uE!_eP&7cQMOxrxV=_5`O6Ks_DS8SjC2l)ds9$b>v2=bfwcrPf}lfZOf0Dd5{JfTEeSTS5(<}8x zB4jLj5C1Gzyuoor5tL82tsdz6v5zI^k@x--2#LaT_a19-b8lyzj7Xi6c}>i_YawRbZm(g{gIGtQakWN(wlG3lzWGoh zA$!E!>pjRsV&=vkg}ICJ9&y1)9wNzz-}o{g&*$~UmVq|XAWtdUPd#~NR#&x`1`g#b7b(Z~n4iPi;5C$P@sI5OcP z%)N_6y4@=?s8ZiJV*}OJ3sL$}dL&S{-pf&3PXxC)7VL<`d`oFxZn+$%z(jP1!+v)> zow*1Q^=iOxz2oc{&0mW8o%rnDSge%Sm(Z?7&7r2G3MnI3Gnqg)X zj7T^IJ}JfHV4l9di}m9;&!`X+X`+a#`i1(0{KZ~Nb7TP z`mqcZzmD{IB)5iwF3KAsz)H$J!#D(f|1IH#20FM zhyavW-~%CeAmm_>{P$8V^n$ygD7s-{k;MQy>6Hx=Ws^kawqJyti{72}NW8H+tMlK@ zhKFPlF_hIKqNstLhaW&l`s`dy-|^Tv>IKI6o?W^7XMxTD(p$+y{{C(t>S9Z+J72V* z=CsVpdVW2ETeb>y>W8o6OS=<*e{>nl&PdIfW3ROHJ&9|Im+xgJqOf3xV5)tu+T+kj zgzt?=6JmqC%L^sk0+EnjNS}|hUWs@<%G?fYSe z zm93JotWoaA^&Qk`?$_Nb8H?D@n1wH4qAU)d6*(p=euq|5$X1$Y(qqx z4T#JEAGfih(mUbmiyEgp!49ojKB_rOdil5Bh}I*qZ>29w+)3|#X+WcIl4$Z0hep^h z)}gn!l`cG$lfj0ra)+0f^A^njJEkK7MZ3Qm?&8mL&+$ko?w6gHOFd@~)>#*2V)vffi+*E0)aJ~ka53s{ zdu@y(U__$zL{!weW8W)UuSAQBCjzzvGY|RD>aR3nS&xMDWOyR+Xs?93GtYr6LtPH$ z!=!RP^ci&~5pG2C`6|ihv#p zT|b*$`Lf{Neb97P1j|Mupe?HMJoHRR6v5cGP9%s@>rW@NV$`}pZDY@E%z5sS5T$*) zwRQTpKH-|Y5KRikl!hn{sSPsW$%n^VQMY%n98Nz0TAD`T_sncO9^EWXo*BFQV z{^;wx2O{=HWV;cl; zkoj%W8)12tCtF8Cp5p_|<>HJ$tXnW=Njjxim=)q`2*m20*|WR#=T2paWwi2ZChLy{ z_fQ-^!v#5X)o#`}F`mcx`m!DY;p}`iyeOu927agKBD4LTf-t#u&lH2`_hZX=h`UeZ zEDlp5v5?80Py62HL)2P(PsHAPC0cy)&?X@hWAD3>2)}gmtVd#&*W&K?4lkY#*eN$` zxuj3ZRWk*-TroUoxW#TbW z@4npyLn|eFLU;g&(tCdO3PJ;a7G{d1er(6B8m93i)N7Og8v-_g+d71?>@jXs} zmx-oxk|lY9KGE9d@d$|!La}XI$U`L&z))ALRrsyiAOZs~e_0kkk3`%L_j5>uf5*$$ zBi{s<(Rd=XZy^!uyiaxaVgLHq52VS147s*&<^|_%U^=7B60+gR#Bm&m!xb^{ zN5Y*6(^|m1Y&4lEL2f>WOvLxzRtL!`PYU6Z)2~7(09(PZy<_#O|ZAsejk`bKj7UJTSSkq*}ugs_RIg;SyUOh^h*OHUi- z)XHVA$AM6h`$|c4FsPJ1H-cMBY$p+#A{QDqpNt6@)%oZlF?9Q3p)pQ(ACD3ON-BO94dpB zo>n1BvF_-L_DEa@BJr}n*v4OF9NIL+vH_q5P21vKSqW{6mwbd;Hv(FlU0bJZ{^^Ha#N*PL0Q0Ip-Mg?22b^N+vB9qk#N0dMkHG7mEgKOi7lPddMWw2&MWzT)e3F0 zxN6yxlsx9fxXek!n@PYMzte^^ipDn&$DH8)x5mhwd+na{GuJb$#A)zfT44jYkPwr; z&Ch+PrXwO)jReBW%bZZ;Vw^t z{NhL?&#AxK zShs9^GWj+VVFW|ok-8A=<>PUXh7wp zsIq^35)&jqLYOH?`~jFCW|k}@1~4!TfC&ODCYCHAF|owJ1KTsp zl0kA?hIadduC9AsANTBctzeKD5l=)$uJ!J7ZyV>Ep+b zbi=O)17NENo~nk;bri3gxrnZ<*@{3ArTRIGE7V<8kvR_E|3-L;+_+b9=Yaaqd;evq zOV=5FK@FX@K4)a&JPAyVbcGBhZoRz_iKK@|d=@RL@=20NE~+{-!moxoIVmFy_N^0K z-p@M>3~W)+J{|xW6Ua&@D*4az^y$Gc9e~10rf)k0yGLRlha{p%BJ}t|9E9Mt@zgk> ztu4y#k(_5T+Rx#%loY4HyFF^7B+9JzGK1TB!~y+geGjHv>EYQu2CBgy9OK=~>=Pgo zAYW^JF9}83ryRFG9PVZ2=zGM!9KV`ksAX40T(x8W7~Og_;=HY39wXRQz+M6OI*xcx zOm>#xQ`)fFPfaby5D5cK<%vGhPsjbUfaNjyo8r2m0$3i_2xgFR-Zxn=qvk}&JFZ59 zH5(}dXXN%uu}+rNBk`vMzL%5E{6S&aA~(Ggp_@#Fsm3h=ieZwxkg>pvbJcxS2t8N> z1Z%2{=idzAWyCcqHOL~c3Er!SrFv#%_~(<+=|-jRXHWq#rgRSOFNEt#Fo2fEDWHUv zoO5rL%N5G|0e~PUM|vii9tYi|HH3H9^})C!ao?vMCC+GD&$l|-2J_GD!*sXX_(0t@ zy&EwZS?&#si3ac$Q(9@%7Y{JO!7{d?pFyA3o8qsku zH5lSm-O){^Z(Cz}etxo#DdH%YuOil`@7;0wo|0#kq5ywh|Ec#k zh3qgL;OO<~kr1NJO;_f#C${|@*gPI8kTKf=(y>#>l+c zGM)}~fKwfF$Cg)V@@($7;j)B|soq}WZ|aD`&Hz$-KUtMT2=&*7-BSBEm-}M@NoLfY zYW7B14%2xkoN%t6KLhb|TH5L8b(BZ4Gm)6(%N@3FBNBOk+73sdZE=+sAqDt@4ASB4 zNdW|jFY3VqJ23hC5M$-0AiHK}%oJ+YiHdErON#$lc)a6G_TIDH`|r5-g^=hjB>ORD zA~jnGiN~iISj1jGxM4=Kvkb{+=bCVC+{OyBb21P?PDA6S*vLXndn%`!Ro zaKl;!DfVI<)f1>pzAX)^J$3zcL^F5Bu#&)KbYSrMUw z&UJ{#>3Kt-wIFN=J{mu3;Mo}Rcxc?;VA{xrBm$<8xMNu8o!0X}r=A;765TZFBXI?Z z2n8norSHm7PC@lpF%O}BrMUAWjAifp)%R#a9iIS22~pK;b|S7xM#}?pBxs^UB`T=y zAwZ~P)4C_=_0gyg!nP)4BNEBZ1^b7W*ewhmd!3<-aUXRLKRnl38((F=(e1WTYn$0C zB@)csr#Qfz=>vLcr<@mr!uMy;*NZ*MtL6R>PC3zy>2jgokEBsG$16f|)hnKRXjQxn z3-WWgA9}ix)S^>2J*w?~2HRoZfQy>4JhBzzLELoEFmdC}xnO>yE=E%ENPAng3%`B_;-k$}IV6anBx0xjsfS%i z?nJa7#5^5@@s>=vh(l>{D&azNPAVh(G5Bo>7Lb22rc0 z09q^aJ_%5!=)LvoC|$R&<&2kP&V1>10Dc7$fxYtDL!Fcsl+}8aMioVe1+pfb*X?9I z*RY0*5yU-)95BVRTLdgprmt91_*0o;qlg`aI2r--1TjN|_l;g)_~4h4hns!)YXfHh zq=d7Pa(U7jvgr#=`lseeh#FIa%E?Arv?Ov8t6m_i!vWfBAYJGQM_~T=(Dp3D>QG47F|p&>2BtO@_Rbx6@2T9vh?u^! z(}~2>(8)$b3aAd+_d7AsG-uk@q+b9%->-X$mt_SqyRJ;W>@t+MF2Lhea3Yz{uK>e| zTmafNPjQ+D+H|;Asx6t$l<6SEgs04|OwNcFw}OdCS59>~No z>s79|Gr};}@mYPvven+(AY1)l8D_i2U;`eg0b{vtpC2U>aYUkbIiJ~C?1YS?82UVl zJh$aDl9tmT;<7!}BV1S>t2FBU6|gU2Ho1_Tx|~(|m3(!2ZzU2r-OB1SRG8tBAZss& z{vv^xE*}Q;#fb!Naa2NIivzjU-0_`>_no$*#Sw{+MRw^GTJ8RmyY%0y__CcbbUY!&Kp-qRT*Lp_g#Z8`07*naR67{t#&be_?rxuZ@AJh&Y+&FZ zlLIeCkT~_yX8@+XUI6@)yQs2vae~veOduWzs(;~S*gj9tj4mbPOGMslM*!Z_dlCc0 z=`V~(==2gc?J8=SQA9GK^iG=-4Q*gj6RpcNVVQ#IujeI?* zggHV2aIF7x+r1zZ0W&~*vW}@Vl}S6Hydx@(NYs`CoRoSm^=-p$90!sKl!L6SQ07&( zf-Ws?s!p%SVQx<-TQ$md?%q!D*W%eV(OBu?BgkW|6G59QGBNHuK!1@8>v>(V$iMF( zt{zPNV{}49o9kb|-g{rTX!<@$=-m(}5eNKWT2ueYSP+TryKkZ&j6TL^8}tLehY-sc zk?;no&|@w*Q0WMCN%v!sUw!_nm$ML=5gg!7E5sU3j8{vs>P5%vL8AhI(_VP8{qUUW z`neJhuj9K07**O>j!0BI34}cUD2~E};qKD$I#BQ|jC=&(C{sEiZN<4D{Se@)wJ*Y| z%zAvjqEyzm{G9lYAx|Kr0o2fI1F@!T+dWO+k!Ut5v2C~1Lkzu1jbj-C$s#HYF21yB zaztJ9Q7GuaP!RCuVi&@xgBj#cpkGyHwB-y^qO4VFGVfQ_rvaKpuSz5nYeyEICz?nk zjc2_*K}%ezFDM6-bTT2-2~Dys)%ea-t#1r@M8dvf0x$dDZtHg>h-fTttjkIIGT!Q_ zs(>RBZyf=U)ZY63qUYTbEO*NbZ&CNPuB7*KDC&mYHT9aK4^;3~rJ?pHKL_pgN+GVu zP}SswCM}G9a)8z5qgQB0j6|fDfN?oeU0G3e$v>8sNklHcRd^IIVxEdv0wA6Jr(TUD zAx6l!&u+yL{82iG&s0;JR4%n$@m&Zc5qM5*J&s7!)`Y`-kubJ)OwZ&VaNTl|hmg-J zyX&!zcnG!$e}sJ;QHrA!7|&^nGRMDq-m_8Xr_xzGcU250TsfAd>KEwQL8`l%NDLXq zdyT|OCKO*P?x8*^0q|$sPDDg)XWI5g`@Ye!>xZDDZAQ%^ct=9?9f@6RR6;-RAUp1J zU(IO{36{};D@3VVh~BGgGCa$3W5XUO)uf5^;aqUt1aJ=04w7WKyDay$12ICQ zMktgS-X(PzfpEEO!f3=$Bxb!vNtf6^`o+F74)zZB-r$Yew!xPp7a}cB(7tHK7F{y(AHp(N;jpMAOJboHj#r;^36{kgu>~qZFnO2qZCW zKbIo3C0_j{_3Lu@CWOM@i|`L3_Lr=mr>RX22F8-cBKASLFd}g{ppDa06aZh5h4Q4HCMbPiXJyhwe zd#3;ipi@LUMpUNbh-D=rW2Ho)@UgRF_tCAxKj4Y)PxN|qA~BWQMSjjg_1xUEjP|Au zYQqwWiJ%UA1Qpu~1ZFa!<-j6@-z317spAMl3+I$f5Ur*+A@EWW;`F9IVSWvMD@?E+ zaX7E9ND^?HM;&B(W+tN7ZF3zDrdfyB5q2GaJYSxjuNk(&bU}}j4q?mfQ<-#HVMaPK zmUY#AazY{0zibV;Gc952qY=kJ+i17`t{i%5c0q*3i`LvfFufCzz9*p{o!(`PM$j0! zU?&nXL_5ewB(!iNkbvY-a;iwgT=4aw#0CoS8+ou^7BbMw*x)MMc^c3WoIQMXPNx5! zB{wuPnV93QK-e_Z2!7soUm-w`N0mD?*i1=>{@Zk{{G~@OcL^Od0*aMD+4y6OI3ncF ztm~#ss?bG3L#rgh$OBuNw#W0-rt+s#n=Fl0-cgiz({S%3tkcp|hT0iqLlxqb7=O^G zm61G?HPm!=!wcCSOn0)tgVZVTRKRaplez5jaqq#QNE~$9-=&`72jak{BzZ`QN!X7q zFqy?S1=Umgj>*%Fp5d$N{<8J0liAjVRN^4wD>a4bO=)UVEH}3eS5uiLqD5-oT$jA8 z5NcQHK5VQ@!xD+ZYTwi9BM?+bB=F1UEBj4!<~stY27u#wcVb%&w-z4M;>ln@hV8^D zst7XMcnP;Z-^NPrnm5v3(DM5P@Wth0=-1&dTvtRwWkn*eA`_K9#q%q>%Asyok=8zV zZletMMqp0nKk|JmBGJDE5!@e^@ytOwI_M-q zltd_jppMkL3P>jrqaCVl8boBGV{dfqTbi0U<1i~3q5jV1nBHXMVN7k3u|gAW_4{#h z@c8t@7?n8k)FxFNnwR9XhIm>@Gw?=VZJ-W79tRHuMqZHyRKiR_>cCnN)BW=~ADTv~ zBh;_+SBG_@b%i-|x^D_-ajfVhUN@PDD#-H)D8{&^{dm)2AJ3iFqV+UG3|&XoFA)2) z{bp@kP92DR+0Z1LTse?n*q8UA%(X5DyKQYMft-;SSCiO_m-B*OtL`M?nO($(jDx!eEcMW!9+&a?Y@(}5$h1xBRTlL|7-)X<^bl>kzB5XPnylAZo z&fP!DK_t{V=;0x+y7~aB#zP#vG&;({iWTKjd$Or>;G~??;pwYs(Ozqr#gPEpSNRR% zIElbEfp|%y&*Zimd1$Sbiy|nXL>$!9IRY8Pk)!+l9*BhJW-g!7XGtuRRRm@W1@{3j zQmi#3Etal63)>KPDX+&olN1oSXjqkRSl#oM(ES|2yJ3llW|>y$Gx;*{LPp{Q?FRSq z37uqt;10xuNev9a*kTrTN8@xrSo}u3!oxnQZPcG=W_pUZ5&JMCI()B8X;~H{j-uxt z9x?*K)aP&t_c`GbhZG|Sa>K}_Gt^wHjdU!-;2tTLZZHZbj=zZbGQ`miG`5)w2HOrwV3i7-%TA{a+2;RNMmxSj!S;vP4YfdBI6M8X<04=p36Xzl52oeYc z?KJCOO#khp5t{Z@SoLB%*gNTUm7ryQpZM8jheT@Ut9zA5^cBKx_JZ}hcQ5q*{d?NB z&F(?q(}~1bwJ8w^TfQ?9BPGF3hKoGI5tj#7VYX;JpQTCr7RiLisplULSwo?*V!Gt- z;)JJ1K4yKK+i4Y)2vp}MNsUBk{KFOwn|K_DwMn&K{W~K&-S0cy$M;5bdq^an6aX#v z_3I4}fG3t@h zS286X$zgBf`>4NOr}e1OR1yQL$$X*6SGXKNu9P=pRLjmp#6SpQE1AP-S)O|&tbEF+ zkO&I{z#CK}AEgXw0q9>wq;1Urc_a)9esocqVfDtP(fK&iQVijy0iVHuK!F^8g)O^z z!AO|G&4#sx{I>vtNMaTpSt1F&=^GfFCeHmGJRqtGB0v!TVIAFOn53;xEy5^%we zSAd>PiX`rAEhpHT?D6bHVjMZ{N?j+1y0|aPM){YKK>}{UJ*svs04u|Bmr?B6s?k+o z>YFss2>6SsO_=VuFcTqY5u+hs%*`A>2oXjAW})UtM~FSm(J^D59u1H5CJStRANAVf!g%Kx z+*xM5t-?Ga@kGzhFJo%cyYzxJ5?R+*oX)hI+VmE6H3tc@XM;kqe1b2;>4)%)tH!0p zyB2Xt5LH-$V}B-xnSg6n!4{JF^XdH?e=d#ALHbcuYi)SkoWveTZ>zEMiQN%MXs@plH5u#d1 z#V#{ApMVq8H=B+}dv!G;5k?Q8ZHG3lFTL;c`z%LVktgTNa7%1H<$*ZkmLR0>G$5@B}Ird*a6;D^FNNw;$)=;=wDqJ` zVn90A4Z-S}-8iGH)BWm|DiBzZ2@_`ltgeRtv#h$Kj$CE!*%uNlgQ0%tQLWiRV^cof znR{??BM)x0QSXjGB6LLJvB2B%&e|F^zb9I>cL?o4|U~b%;2& zK15_$cS=b=Jv=h)Ytq*@)|r4!@TO<(F*#t28!e{)U-|KxNc49k-o1OFZQEQgp(nE+ z>$DVswf|@PIafg8uA_;c!P^65Bmg^W$kBd9GEvL2ls4(|OeX3)JyQ2*Co3BnO>!My zCJ-9$c~}FvOhD>m&3}&zWm6(yBM^f`-0yd~-}`$J;d>+Od0^Q0=FhQAZBDk`wi5n2 z*!)|<3a4THdz2}mvR%o_4~@1cu#eK0Rhs=&Txh{YXW;pBBEi%ee(z;oUN>aKd=k9p z0x!qk@B2g~>W(CeCVVR6@tnlGcm&$+piByX5Mv~W5YjE~TI?2rjA$}`xacIhy7rcE z+JW_m%0mJBJ1MNq4pa<%OXR06-%<~mJr=K zK21HY5|zSMiGa*w;h75+qWnIAX3Ca46P}mSWRFSX!Cq+&G-${)99AqYzq<_BO=QL( zO$5*icdOwH5o8S{4a*CSOf3XusWlGIo(xb1<}`GL6hPsDUbpBl+`=$q2z!Me37<47 zVS1GL^N0t|=&fEB+3CAp1_g)wp-%jtKmS|wC;rlZNH^ZBaa(#%MEmy-`ZwjDr9b-9 zA51UC#db1czG$yn2Q~0n5r}zTK5O*%|J0AEe<7*}jp@Vx_7#2h=e~;1vAHO`c$7dv>0+>0(azI&9`?9k{U;S7A z7|CrRw-9ZA?HBa?U;G_HyCD?KjHZ{R(q77K+l)kXBJqyizkg5Kv)t#o--G_`d!OoH zL_#EtMEv)E{?F0puODl%nd!Ga|APMGfAL>VZ5L#&O;jB!9Eb<7pE&1avi`fj_%m^l$%5zd7X1qY>%;;$%GMf(2PH>F9EbGU+G&>%a1s=#PH+CG88{ zdu@&WjX&|P&^;7zEw`SBzLK$>oTbI(WTKzhu?PFE1maHj*S_74zJUDy@b~@>{pK%! z0dmc``xpN3AEB>WOGE-wPZGU}NC4K*h#(#8fU(4g=uiFb|4aYw&%Rp9eG{QS{=*;B z@3f5+l=nC_8ruo`G3QZCl?lv7AQsm|qS1fw*ZwN~TYvulqP;b;>A3x&zP;b+um3Oq zE7AAAZ$zV9Ve7t+IwZ3?GTNZSbQJ*ay9MKxTn@7)WQ-i9;zKb;H&MCre>=1=>S{Rs5Hi26b3UIrpKSnN;vrSb1 zB^8xB6=VkKcyBPmXmB!|#rbd)gW)K#ZS5o2E7Cx6+J>a1SE%@OFE3iN0H-1LEh=^WVe`Z@a&;RF6`>#Ju1mfWl2{?~B zGv~(dvupr5Gys6lEMz7k+Wz*P_V3@8*JsgZM{?#=%5qq>PiVhHL~>(Yu6>r{@89Y8 z;nUpa5uEfp&2j~M#cdjq(9wu@@7@tJTaPl4e~3;;DDGolY>GrrTtw)@{gv9H@%-M? zGyU)vKTqvd;J=@G*jFbX2-dCeAzI8F+658OcV1t+iWjo~V%zA~zWzGYr|-vm-)4%? zk>_BUvAUhxDABKe{7AHrn}}%JcY4`(y5C&SV{dX*Ml<+hMHBFhcK+drslJ@sr!(#J zYGmS-Uhnt*Qnm>Fc<9z`A@|qJ^c@lU2iyq1LjSD=o$5KZZd*N%R^C<*Lcg(}%l&(; z(f5v>{x;}H)jqw`bOy94pY3Wq7KdFJZQDr$23EY&n7;pupA!+$b{tfN`#=7N==pbk zo82ZX5_)4&?LJ*5BSIMRGF0^2xq}g zn8P}{da7-gC$@>-@9-#zDcd!yJkYSikC0eYbk&1$8 zU|^{5ltVF0E%`>7w$>=2JX~k6@;O`!Bm_za70IV?K|CB4#3BPg2Hhy5XtL3JtnpMN zB7@maZHS-rTvl8HJi`8BVFd0R_F2zOJwOo{`?GXeT!uk27b zW&_U``}x^Rd;Rr6yk~uTFgzl|**Q*Anj|f8JheTDVy*JOf1{TwH02{ZjH0P*t?iRt-d*VhtP50je@$)jG^ZS!ZhTX<$o zA{?x9vJpxmtbH+qZSqATP(O@JjNj}1PWRVW)0yK!@}Js@VMt&uGW&+m?L=D2l5*Xu zqUh#YA%D^uS?8#h(GXtScpw;)PfhvM%h<*e7S1HXMu4R-}{~#p&@_#0=cca zb?;00ieVOg#^W-uX=Gvs;yUV~xFU-eI^|erm5|5zKnQN{fo4|6QLTt}cHcjoa5ef} z$rDjvdLE~x;HZRxd5FbEv=r}z`YzanK%7~ii9qzNjPzN*whdS-RuUO0#_WbAbql-(>7?xT@`YvcIB zK0u12fe~avbCQ)l1{_NsCf+Xkr%r8% zBN;diFY3^^o1z^ZyUE->62M%ZNjK!eWB*~6gFf4eb3!8iqV@bjFUI*;=p$PTmYxM(Pqn%qP-&I`{Bw{wGeogHFkpen`HeZia zT!r9i)OR-rdEAKbqoyJ=PK@|TWsGvPrq9+32@vE(pJ%4WYy$cH9_PjFiw==T)BF@$ z@<^OjSm|LToCs`Zm16=N!w%Q_7Dfc%e)Wz3Ry8&F4-eq>fe@SbV}*HBMQ@GAOV}{~ ziXn$Z-~r>2$uKeL0))qL^p7U#$8e6FcxP(6P}{doB94O^ELj+O%t;%LH--)z%B;gK z01;H;=`meFM`CqY8rq!M?qe088sgRGR+={f(Fh>wItRdBINz>_Y|C%<<-$g8AX6OT z1H}t(Ge>X|Nkj!!F35z$yC%5A^S!4bw41&YroDw;CU+cC7wkG29wb70lhhz<6pQ+u z>vA>4tpfUIt7Hj@Y?pF79-iY7)#tPhc6_>DQJ}7;Io+{Nf4<|o$Q8-!J}iw(Y#kGJ z8-gkFX%QHm_U0`KMIsXGTDlHs9+S^7yMd#DYEm0I=g>wa76<+aWJMAIdQWs+PnOsl zK=8xB!QxGYQ3#gp*+bD^*w#l-L?#m&LPrN_d7`bPP}dKa$rW&&C0rcwY$sITkJxFq z7vC09`5y&aLPYyrXqO#2YP{XNt;H8M3G+Y@r}`beY`UI~Pb5E%gJi4{89OAT5M`mD zEu<%HD{P9A( zxpJ@>nR#?#mW6o$v~eHV@CTW3(-DasUKY|3iFOF_!PJh{Kdu4=ABJtj)2~4HR3Ns) z({9|4g=Ce9m7Rb~Oh=&R#U9ba%Hd&(Q+ci~6v2DvIW|Cn5h9B95eyN6MgZd8J4B=; z!tz=Y2qKmR43m84I5y-!P)@6Y9=ZuWyh_W4`iVf!c&8m*SSB5f>+ARXhrslFAQY9< z>#WSOq&yVDyuo>D%(YYK*>>T=h+QQ!w1Wq-^o_tc5!Ruv*`JLuPLr{F3SfY}v^9zF z5w`IBCwQOOt4*%g1|-0i4QJd4kJ$hN=Cv*)$ls9HK-Zh}M1`kN&u8IHz&Xc#a!z~S zzLENT0@|pj9eCSV-Sdsf#7HR?d;!PVye|=KRZiDqiK}<*^#=+ukKyB27c%erK|8@T zs>3^JN=#nn<}?X^!W2Q`HFHDjG^cn6xgr`RT=aCG>fI;mW0+o>es7Fv0z82jG3~7ODdM>`*Ww{|DR;yO(9{S$#$H81;d|X zYqzUUR3OAeX=NVr&ftp-KVaj%ZOB7WYPfY-y|TG2=2_tum4f{RY{P`z%-M39IA4=? zqU{ipW21I7+GOj75POKg@zNj@+8RxX5%kx^a(Wu7!3=Y+M4pzL3%k~06=6jqt>rjH zKx^M>l5mu&3Y-8|?A1#SD&(VzuPY(4SdSYWh7U8RmQu=?+(WoM6D*%flb!k+n)=-U zjK$@&5ed=rD%ArPX&6fUnlQ7I2}@S+{wP~M4n+n>A%8_?wQOuU&jSHRBoOFW*=sNB zWX;nK$HO<-8RL}pgLZNqI8eTSVmkK%<|^H2Lv2r05U8bhxfN zk3DU14AoF@uOkxsF}_+oeXpPr^{VXpQp0y5C+12d5<&4N&W|ti81%sHSZJ?TN-oqF zA>dZXaQ*Bd7Ly+E&)vH!vFvv07*naRJPYq5)siY&f_1-3S@#+n^E|x5Lk!S*gLb~Wg%V1 zn)ZHuJ7|!Iu~vVUq5A3dM|1Z;P}A-cf@DU2CFp|t0>Qy1z*AJ`!=wm7vRT0E86c*J zFdA@(Q+&aCz+6-VCOv`ZFs_iLOqZP`CK=hUS77RKGNEV40pmiJM*T~{zw!J7(p8!4 zT^>2;m3E>=@P0%~I#^q@D+1BwNQOrDWiHd4bG@hi?!GW4MAS0jkh!-sTU4Lwq7m;Joum6?9>@Q)Ng(0S5Ur-G-cX(FqC$%m~Ux#xw-IE4p)^` zi&r1`Nr#Uvq}?iF%j@fuTI@LcHkDZ<0QAO2wz{Y`8si$+a2!Z`&B=}J}#EwJ3 zBVH7Xx8H(_2q1VVdjb5@%|=$3%J)fTQzllnN}2+GV&9!Wbc}_Fi2m^V-yjj98*e1i z=-^Hun24G%{f*n-rGIY!Lwz)&buytpmG99P=R#hjD!)YDK+s&0{MDWKE=0S`x=KW^ zf9Q$c|MjmamtIeA^?ijZrVH~C9x1$d5!zRKujcz4_x%q((aT@{#UyWbC{cvf$HPWB z8gcMnza&w2fJ{u;A)@v>A4xvni1t~A(ng9z`V)6`Ak`SqKwO zp)RG-HzNA0zw)c}PyO_#^vlLmwS4#ENBTQsRjA*;@K#jT!(aZj@6&Jo&hLcPnKZoY zJN@qSi=SAv!AH=-Nl@E8Pq8Sx#5nv5KlpX}cmCGjqp+e&Ja8Ci zx>L&LKE=j}wG$-0BhkqOe)KG+&CK*?-+iF}{2%<3enR!~%TFTodm^;ocN_H(_#&+3kt`_4`NqdpU)1_$wmxyV6(Qi{NPnaMwU$ z)_^GkM4^qx&H?}Zg&+Tz{1 z`|cuQAqTRsZ^fa$j`X_?Lsm^AnekjxXW_9T8#r%OE|HIv5#O|SyfL#mKyTgSS$kMwswtZ7@yIraZf}-hz{C1kRze+^*l2wahjDj)G3qaC+Y$!0BpaNr<4Br&$vew zhN-{g3>tv|LJgwP0aU0FBkG=~JUf|qou(J8t32!I%4+>87bgN*a8n6z)guJ8fu(|! zK(X6|KxGGoaE~;2(|;d{h|`&(px=A?f`0O^{_k`g2YvO`m-OYAU(r`z_1~9YeMMh= z`6Yez^RMX3_T_ltI=&hnFqd`YdGf}y!x{op_SyD_yq1Z?}D>o}z;i=E0RpO3^L9ut(Y%Tp)w#eeqO zDUa}+0(c@)Ho@dxD!f-?HZ=hbqVU5q6H6ljL6qMW-kqBW{U?9?pHH0tF|gIwx8Rwl zP(ZB*lljyC%papa{ZId~xjno!6lmd5@*m&fN|j!emk7~+^H2N{`fvZqKQf(9cV;0^ z;;m#&{#c@ZeF zhs>c}(CB&htU9>VH2-J0(f{=H-B8Ge5!z^LLd1upyou#s0oq#FMcb*4a^uzZt!;he z@2`CS2lVg%dw-IC@asRIAOGk_^rIjBh<^B^AJLC~_(S^9kA6hI_{A^im%sOWL_hh7 z#g)qfM^?)wf`d-0+n(YN=Mel?L;z-iSiDU5%@XUsPTOx1%D&f& zc+KA!6hfJ6U2$77I-3a#&F!x?NyLf-kO+$Klf&{+DYlnCN*2wHhCUkC> z_m)H>w;y|W*}6A!rk#&YB>14CjZukmq8>QC-1xIS{#54!QBL26A_K0W{TXNu1T zsFh^vzJT0i@k&;_Bq!qw)>TI0^}MxF2?4B8F}-9#uNtl=?>eR=6$Cd>h_dHj20Z;# zai2-0`N%c$ZIcNt=WiCvH|;h2HX^~PO>3>K%kJ@H&#c>QZER{~`cN7YiGAN~ghCFV zx@p8xFn$0>!EQQO)Vi7y9l@~~r zSLQ@GLT>nCUqwSb_S8uz$!mXo-^MhfLnE*;g%g%+EU;w79HJUHn^$=pM8{YbRu0;E zr=52?c&Aivkb>t$PK z3g4oLeB$kZLoq@p5RKZ_mlEE#W-swSJ>6&NyX@Nu#FCGyARviDDd zew{@ygNqd76#x3(B6b6I(T99v5`nT@=rXq7OWmm=c#ACal{dwUJ+owx5p4fv5GwKB*a23@i^rKbYVZ}K=C-#U zMbE;;-Fp572K2=+sp}%Gx!pwl5A8hr5YTmE>fZ!0^zQfDw@=bOH6q%iZyWXRi164p z>7Ag^VFj$*%Nu1HGI$(Bw2ino&<)a2BPKe=8E({$Ml6k*Y{b(1W$OqUhwxZ%G#6Yh zOnpvhHgZ0{l4w5;BI)l(1Tw*Qy3=O%iiD^gL?ld28i{zetWwIxo|GBnT?Vbl05~mU zb$mte;lSQV>;5)C^eoL3VVJJM`Hc|O%ZNIw;eJ}2v824nrW~&6*M<0RaAKGDYIV=2ru~yd!u=8) z_~ZIrou8%yO=*MsSTvBy8I{pV*jnwIQE#0rY>l?9?<;w@-JSxGAfiAdM8v*G?7htS z17nip0Qo_Oa@kyW)@$AuEk75{0)U@Z0oL=%8K1;+)_YjSl^c{KJ5|I{Pvpc%^1j7z zEss7uAvWFSeIz_Xx?#^kr=4wQeaWL*28gmB9}x$#0@u;@t?J=T_Q`;_?x%>rq#Bt> zN{j&8MmXLs2@zn5-Y1z11OoV~x-cF+9bDx#p)fxKzQ*#T&)Y}~(^5@G$Q}r78=YD32 zZ|LVpaB}E@JTMRn1N%rObbpY{7WHK*leRM;5%&DX#Jf(#0uo^laQ|!rH)^6}qWOq~ zxg_ztnF3a53kx%Pf>7x8vpJhYd>q8W{blPh3UTK<-RMR;-G|t$jD$$q=rJrvL}=ed z=~ZZF2}tm<3i_>;Mn(j2PP)cTX$Utg-uFI?kjL?8tUhOEvaK$78i{k+6tWUzgZt%w^gLTZ9$O0E6ifr43>_L1wt zan3bRe?&IZlevFe3KdA5z{T|w3_w`60B90<=)W`_GF5_1J28#$B#sss@nNrvOr8do z!PT`Mfd_GV6UML6GR$bt_NB5nmC+806U5HXP0bBD2wl!tXBpEX{#}L&CjchLd&IUg zk)S~&WQ;!82!as_>7(Dw{*F*46r2=-Jzj21v=OoWTsRh{{!S52WMXQvQ4=K-TYuTQ zHgd@!6ZG;08!h3UQQE<1^`$k(2V#b?%t_25 zAE>lo9PHGT_l2W;1KRK@1h5i8DUgc8)3cRqj{v9Yd{;*9Fa2_9hU2}LAvRhb`yt;% z_CmN27?EX=uxk!1$uxZ2GAiqdnv41EAsL(XHJ7df0|v)C=V3|)0H5iL8EuX?F5~#- zgkgDY^7=gpm8Y-MO2^(TA14!MJ-uho%{HUR`$=V0z33hhb&sG%97ZL!?M6>eH@e;W z@9C+JNGLE+J9)p~jY#O|L^ZYPLd=!)*LR3!|yk-W~o`kG0|Y;A0Q_O)p!+y_!A}iAWkE zp@?Kd4OB0;K3BYh`>ZW*vP29!h0WIf6d7&HUc@yb;~!*=pq1+QN)d{)mMMwHx;xcT z^lwNgs`@-FBk!`dUw&s#L-&Q=j<7hh@2Omtk_an9&tP2_@N}GgfhqZYUMI1BOpl0Q z{TYF{Er)R*lJRM7kfT8Sa-~Vgm!}5hI^>$mdC`UfvWq1ar;H_$R30rqJMLv7BvcX! z7MspQjg3ffYd#{;JTIQpo~9BNVzMbxtmH&V#HQs6`q$}$lUeE0o0L#Y>%Ix0I!M~a zQ^v^90GXo|3WVYiI;6iNK}TPk{TP2c-)X0fcG~FPS6ny#qh)?bqt@w6sIb|P7oloN z3&8SCNCYN>pgIZ)>RS++6@dEGQ44Q_V%~p6Cf)>0Dv&+mUyV%YgX~Yh{Y6peatzcK%ots=k-&s2mLH^@@XYpq(jhl z9v~AdVD@ku!35uMUGkCC_Yo1XjYjy0gc69Srzabk=pz#II}##d=c`eON%BA+N`I;PSwKzzb_U-jPEOj4!ND>7-< zxfU+uF-5VOA~Q|v@e6Sa_bd2rFm0u^W+c&J#lq*vY|b)?&;u<#qW5{ zD{>+cF2?f~ve1*f09kl`$XLlcTZuqFP zv^_D!7p%_&B5yyi8M4mD?))3Iw$W`&WqP`G67l@}Y$Fo=9f=-?j!5WqCnXU0o`fv) z^wEG|zs$CQgOKx8Y~kK6mt3Z?NI6HFrk~F($iw`s0_50Bt|RYSZYojO6aQj7Q<~NpRPQK9-92}10koMu1(2FxSu96++l?8g;( zz+;OO<>7eF@{_*Y-no$Y5tE&>x@96!;$ZJc$apzgh{j9SEf7wv*FwLvXd3)rT2tFJ z7j4?=Pv4PfhmJ@T;MWUkl>N9q0SF`%5(^qfA~KnvgNS$TqY>0sY`Tx}h(5Wg3(A8~ z9NZg({&^*_>xh=o(uy%O05VWLjT{u^Fjc}TEhxv(v)WHsW6Sbh^}s$PS2}NXm}Kq7 zgx-WkJytIE@QfOF4&{r@y zvychJdAJ%~cng6jdqrvSF}N$eeL&y%BAzP}aoGz#k>165jf-Jl&#&T6KD4E2O}E<< z-JX0zLPsU45ec2zG%x9yr#6WT6q{aYOB`I!Wrgp;2$1m)1#S0__H;c(CZN4!VW8uFfu_|MQeE}0r_BS zP@hxTwsdYa5~0Tyzu{31<%wAnFxYwagOUuJ<^<=c35gL03WP$o)zl`AMax9}+Y1s% zL?4YHdq;w9I3m%BLtibm5p$o8+ov@-p(sCTIXl*(QJ`T+fNJ$94w-fRb0su+En--#vEHpe)ub7RB-VT}(NhTt}Hi zTmr36ls5zRf0RNsB7tE7dIf>1dq|0hBpheJ)9<&v@ePQ65}zT94YQjY0`w*l5sITlq2OXmCP8`&Dr=2>PXxvGL zFgdVec1cI=&W+S9)Z}K=Sn;T0TOEqlz=u~QP^CB*5)=8#52c}pcmSjbeC;=YYCT&3 zi&{9ZTP-)k`YK!Q&0OSdZWzUfoI+#d`3E4qM_kks>@V~7X57F*kKCvs(E&XRzed!* z$zBKN=7Mh<#3Pp>z|uS`gAIta^Nk#8+a) zq(7B_Eivh+HOLayMQco3Ykf-7(~X{l^(_Or&ayP9owqKjWDP-(GeU zIq)2cv&bv9v30v)?xabfnv3UH#_QTkC!3j|Mv&J^w$Mo{547uCDWBSz!SjB`0AlCa z$`(1)1lhl}j+Hr{8=hxOo#*2j8KnrVoTI|)GKg(!Bu6I_eCRS}-0{0eU)f2-raU!n zw9`S2`}ZdLbf?{95pL9y2AuVHEpb84(;4V_(Eo;}0a5nGKn0;lG9b+4JWT-&gv7_s z0yHvg+{D~Jwx>)O47xd(Ro>EmmT%g3t4K&_LM-euXzot)2SR*$Q(-R)jxwq9bhbZw zg@|osG5pfB)~^t#W;m$SDAlpW8#O}jeG~_tfsixM*LC&Wz&}hPG(u1KRNjZe?2cQaVjt zO15iBB2=&?naBZv3*`M%@(|^!%48-JM6tarWt^TlRezN3G_5?^u#^BugpWG-w%e%_ zU#IS0L0|yoHOO7%;k>A1E@CKli&t?8f+)NB4PjzC9xspUhRIad7is9UAtVpE(<%55 z%H;&^@KS8VRxtxAr5@u{z1sX{QWMkAd#2~iH}QD)bKF-b_e?r-K&(^TWROhXvqYsp z`Q~!v>Kxo&l|umP)`6S-(uMP3yl-8pGtxVYi^&%^5YtnI+p4o`vW7B!3*<(RM^raa z0hCOz4p(r(cmVboGm?tI@E8p9HD6EtP$IE$U+VRU#_>1~I;g)|jUbz$8$-Rm1A%bZ)fIvb&bW_EJML zvN)FW(|1rTxkW?B*$KDVb2y*}_n@W+9V4<4p`cbHF8Smpa1my>IT42;WN;8x7vRpU zFa`xO+sfy51#A=IBGZIPB_8lPK_<^vbzZMIV8MCZ3lbr)pYyQ_))*|&Lf|-_wT=9|BRpkB1>?$OK|F zA~6aGWL4dpLB8&fN9ZkU!ed-H-qjZGe*|ozEj}&!97PHKtNl6;l?ZcuRhui$C%ug$ z1an$v0kK&ar4v7QPAG7ylW#koDB2W&5;a@6Ha!ZC=lt5)=)@wkD|Y3Wn5^?l)8fi% z=gd5Mg#rNc-hSwnU##$jBNDnwTQwRH_r3Sn;=c$;G?4UCkaLbJPi>1;s6H*mtNV2u zAZu?-gG`K4V8D?ck>@d1aYk8HBkm0`_`nGp#cjklDgZ(cC_5}aJ2@l*8#IsX#bY9v znkV|f#DR?w>xKXEZHZVeuy0u{oFbvm!`8s$8k|BdVu2stpn0XS%(GyARW{$h1+B<+ zlf>!`*ehKao<$)Pd^MQXv~ASd*4L;N>SSX4TrPiK!k30Uh{>llG4DN@#w1KeAV`E7 z(U3{S9CF6YxTq7EpkXt_<3TVij{yrTz~0mEXPsR5(4(h>kMs15=2OKtf0A4L)R=T{ z{LCt`8Bmi2i~*{?hTQzag_Ckvp98r}mwLS@rn697FB;D{8iB+?9gL6W z_!mD@FR-}WRIw#nF6QR&{Ki`N%Ii#_Q z6MWF8PGb^EX*}H4N4fxV3{>1Udb&N)^YatEj44g;-@m8NKKsnR4dK7OG7}L2!Kewu zaU51gE_())v+Q%voH{`~x7Mc$d{;Vy=O2k<9C^A(CM+vvIO{wbzQ_jSsvIH!i6SK1 zr(hw-+|wu>_Jit!Ah8O$Iz)97(x~dpMu@ zq40RBQ0az)^3_NL!XvB@^}l##kuaRDWgGU#_H{EO3=U5*`N#xMcT8jg>d|U9xPH|j zjej7%K?-K#K;fKy+eFZYb{UOKV1C#;eP(o}yI}vkky90rHk|rDEwU@yG!~#*>>t8Tt@}7T9 zlY?g{b1(n^AOJ~3K~!`xCTOh>fW@G9WxZ$(10XiTud;$Pmer{Av%Jd$=k(1f>5u$J z4CxJ{1!)JH1_9d#p3C>3%u|EQ;361$I0h$Bse(5%JVUXFaLGG4bAo8hy@(zG%QdhN z&mWwt$%GonoR&=Sy@^0f4xU32)%32@eGOO5@{tgdmigSO=QooG9xqyNaaz;6ckk%K zhY$4O!w36n_5J=zudjED|B^t2-ffgMx6XB#fde|q>#!P;z%t6D^^8E|xKzd&3_faS z@^fq1=X22BKpx|=02WGl9xcS;`4ym>AL~TGMx?4FvB-=-kbPT%lH>uns*N!-o%YAm z2qJ^6By9`hJ^*a7A@z4xYv);DQYzjRBKUxqPz&ON8^2LuIE=(zW#2mBk#rzHF^4HUW{)5s8l# zNBa1&%il>u9FfS=oF)R1db$FAU9`&y7y)s-wr1-%=V?>(h{T#qs4UU``px042PAsr z9&N{SB5s%Kc)NcG%ag%u01Icb%{H+vml&56=UjHMrQ-H*o?_+Y?HvaMJ^|umzYot5 zBM_}YJ_1$Wi)9^(C1-!wx^pl-e^fS)&PDaklSzcw+V3h4^OK>ofvK3*_hE?jjfFdt3T=O*N8LJ8eT%?(Eo%-*hh=>&yf|v+m2K;rRk`t` zPgd@lPb{y27vg)4BkyorWk+>KM`>7eMJ@N~;enBcDDIr{FKI8P%vlb^D)~a%JM-q2 zX24ELAcSaiTCiES*xr2kS0T3~0eI@D1X*S3oUBPXKx*rqYd&}I*ji_62la1BG;g#d zM285G9JC)ybTBa;BXu2_7$XuweR(Qkmv$HvE&Nrl?TisPY}7A!9^q!2r_^scpPSkv zMSb=uIac7Kto)khMW50U3wxemLHb(&p2FHxvm9GG(2Pt&5v8?y-6 zs9Wt|wBF*!s`T8Mepb&uHXEP_JLpRF z##nz5$gX;`l94P+jf^V zuG)lOs75k@N#x_HNJd!(dxKaiweKtYh39bkUg%I2Ek`97C<_!~3ZC`@FxK2bMrV$> zP@lX5q>L)$Yc6juE3HwV9WaybbFrbvo}E}Q=RAwuV?w46)On0?i+5BgLYr6UNVpcf zJQkt;620&s5W_~8F^L$1iHh$?m^}d?)f70jo^j@}?Mq-1jXF?ZpwBTA;b*m5vkz)W z>&qnChcuMIAB}XC17#*Ex{g?I(-DiIAksfn!iNyEP-~>$!7c)a%~X((e=9KdQ2{na zNvg>se{*p zsK3~L^vZ(jg@_mV9p#kIBQS4mlFRNHjgVU-eTDuw`qr!(lo1*5*U!YqPsMvVvRi4h zgjhagXkhsG_Vm{X9nw{Xm7VMMGwUmo8KkhFY!KSt%H`9|cKlM416K{f7=G@0j~ z$IU^+)6)}u_Spw||NcF_dwHSf=V$x)91=bUJ-A&vu$e@>HN#L^VQEO8`jQK{8d*3y zuh%Z6NzboI=^N{{Oe^l231N-De#hg1m`TfYJtYr7(HS}{;+_C;>LfVi2wVG2tpTPp znF!ix1wgA&w|#00fgqdw>A3E}pU-2MI{CP=Gqj8|#1B5t>JV(0`ep^c*x?YYAYbJt z)^YB*Sjp$a!Eud(y{TMMA>{WgaDPs-C4d~ua24hbhS(0(Hu&fS4O=n4FSHKXR^_&( zZK#&dp#j6OpI?#*p>#hF*un68w#Q=mdz46+1_n%0lsl3J2JOKzPambTkJD{rU!bOq zh;Br@iS2K0=(Z2Jb|&5%@y*0Ae($I;78Lifcw?=J;6`u4{ z+|mq$iFC@+$c^QZ2n3T@Luf2?Gyv0>ui2DEKWnG-K0sJPwo*Zt3$5T3fuF4igdNU? zF&JSb3)0hXhmZ^s(FC0YPwDA?Y3Q1Q;ZBr#K85HIq9)YjphMb7n~Ja5uZToHmVC98 z0gWq}hiB^fJQ|aZOm)IE@@wTYVn=XijYr9fZj*#o*4dHxQ1m=h-GVVc=pa7Wr~H+m zHxURT%I`)5;E#Hj3e>us{NG2(E$(e26ipPruR`RSQH`|LCN@Zkf!d;dNV2@x4z zs@~J|rNerQ*CP;%a(Xx@Xht2V2}De5O(xFHOJt$4nwD&pfU@m-erBKZ9=g9xg#Pf_*0CKK^~Jhy%>>OdwEQRX5=bbHpu za#?vCee|~`5i47O=|8ehN(fSRZFB;z%UBgv&kKHudZYeT>p>v&czfE+4{f)tFK)Co z$5)L_-SlIrok(o7J#Tb-y^$P5ba4OH+r1f)U?dVpGa|v#w;O)hTH8c4iy823-2t@@ zG?|Z)QKrbYl5*>aMr*|FAZknmBNEojtNYYhjx}tUK5{5=Xig%Cl}sFCIoUq)!7}=X z0k}JRyl!lu66%5>pAt5+hWMfL44&^)FsnWElp2gaH%P;w?++ZuIF2iZPBg+G zg+=O!eMl1>GTd(4H=tT;7b+{1$2e^*3=8EX2|l@@Jd4rR#pJ{;l%)#aiG;pL{rvJw z&(C8YrZK&H_nzLpdq>aD{Y%!W+x;bLU$F_vgve0{l*AL1XC2UyIrsK*kD$L_J0lf7 z?QI72X9S{pKFgP%t>SwtnOLPij>xBJ%w*y$A9dua!}Um!m)j$9s(hYr{22kwBN0Fz zRvO~z_Z=q>WH!0Agb{7$IMX1gkDXh&*8 zQI{;*{Cq3+^VF<5BmNvNE9*VYL{gLs(^;|S`0IkiGC?At8J%rr)~Oh>jmhUL;9U`k z2>w_4HOp2L2_%Sf2M(3*q*Wy0F+wqAtK-=~ESx+Tk-+Dgkl3h%5Z#Dm6C)SflYY0z zM{9_!uR{wsi&{0h*3LIFSJIur+E2cj5H!81GaFlloVoK5dB)7=btr+L`+b zP^3enOwWUk~Q*bCQ)bSOH8pv2I)PKkudm;o&sQSm8E2JF=_ohdt{ zdr2fT1NP%VCi=0>S_^qu7h1=n(O8#qv2dQRXPr8V>(>`8BmA1ZEY~|JaRCc z;nV?y21ZFOBa3fNDv<1MeenQy_+V6wC{WN7+bghmU3y-08Gt!Alkkib>BYd|n%5@> z!36$sq8nLw1g9}Wg&~CmQflW!;(|oH0q%Kp>7mee#YaNChnXxR%sfUPp2rK+@95q8 z_qP8srZYV~J&)}ZZCmd}-1psHw0?bkwbh%HP^?EF^7%!s!Rb!2Q+{2CW4q+WIuqH!nNDRY z=kU)U%;nD@f5aD#F(a|fSFSSpfZ8t$i7go~1S>64dHcwySe)8HFcDfN$g7u+;~I*C z9HVZS#>=(vjDmVEpG+cJx<8A|c3*3awx%Rvv#pX+BoJ$IkcuOofxOP)n~{h*z9<6% z@>!NlB>dj9G*G@-uW_FSDLfku#<=qSTL=YlY>)HSuLm;0G)5$(&oaLW(bkECw7%b- z8*R_6k4ik<=yn^VbAwj}8j-D{x^1*QZL~ez=;`IDe<*rP<(3;!+c#=TAnuzJiM>%f zB8h0S(M@AmTo{(1ALS?=HZP<4@!0&oj|R#%{L2beu>qF|mw~ z)-fA9?lhslC!q>)D6#01`-yZ)&Zq-32A01JUa`VKDM|d93BVKuitL;|+VJJs+ZEv zora1`;B(qD)!TvJtPXqIw*H~Hckk)LXCG`TlfE0#%=tSAAR^lLokWCQUtj6<^&{Qy zuP{2{)0?hBF4JJX7Jl{$2v_CrbvTbkRPmwnJ)0Kr2q?cQ2k!vU&12=(pLG)9U^F4c zMS8W2>(QL5Z94#2%UO*?gb|72Wqdm>WtaY1qa_S40W(|ArF}3hOmVs*6Ezs@sYap| z76VCTd$v#d3CYBva9ypyEMy(z%ICA(F%Gve>vnZoS1HVXsi&X>rZC^$rzE)(Fhs)?YTLbxZP;8QHjx>VQQ1UAJJ|b z-JUnv_oqIyMc-q7W!mmrACb6sLechdd~7x%vCShAqrZLlOdT3T@M+UIMrMvCjwfwR zO146o8c{olk3PJ@Fd|{#Y|{}4eM4dpiK7MJs=oag#)C!roPH7-i@=iD2S55S4iQru zfL>IA6kLbe9I{7M49bupkb#-f2T4gJdR$TQN-{C7i6t%p*axRQNjs-^_M=gjtKKa% z)Lu|LrPuAX0|_;}o@YpR5C{eP8ZXm$|ATb&MM#dBG@-tAr|4|EZThYRmTRgDDC;nt z$)+;RgaTLOIBa^|;a&&IA$8_B0Z7I#INlRr5uVlfQD3WPg~%E1N;@RU2*AqpT1nTq zuG!TFfKHm+NoO*FqYT)VJUQ1LneNNYtY}vh@Atga*)Dd2Q&EE>LIZ>`5jEPj+aMC} z=);H4=!-ADpfA4ofhB zGJ*G9k$}}G#UnDE2GGH(PGekJrv2t&RxP6SN@a71_4Am#GvLTzL*VD-dbWDkarE~k zX1^d7uY*FiwyG{WuP8LVE5S3FK=5Z~7<@^{vzZaI4hHPWgwNYBeU&e+&CClj&rZ~`sMvh(u5 z40CaAa%rb=Uy+FVc}+Xvf-@lQXYAaWsX*c|FT>l@U9~H;X=eoDN@pV(B68A@j>AuU zzx89$QHenwr1`eJG-^*w?WvDS^!FrMBuyhO-a3ico^P}r2i^KgHng{$_U$0PF|~c` zWMUACz8xgu@E5JO@zV88SB51@rf`5R1$=$(`PN4x8c|=4HG(u}0RKsBBtaMZ}2DLLr&Ybs_%fUW0UScHF5%k-1U9Bp%tB8Auc)RN3=TeJ(W<7iHkTjD44$|D>_DFhr=^jD z#Sq-gtw=;ngVb6Q$xzY(ro#2H4f)V9YXgN^%IIRDrC?sICE-~Gz7Mc%TX){WVK*5s!?!kG{Ad5Jo~j~g*_e`oJPbwB zU-S!tS`TG^P}`anH?z;-ogBt|kcxpkR)U5+(hvbHf(IZ59+A49jpLP#hhhK^O{8sD zbfE;zx)UT!)k=?(SSj7mEc9MDmoP>dbOn{IZS-_|vX`nq8zU0m{qA?^d*A!s_~6{v z^!3*t>Ep+b^!3+Y6A>9%$i(6}b_0uKr2 zf1T&G3{2iBHpxV|XuzCqJU6G2_bWTAryd3v2FQHdua9;hK4N0c13WY&ZS7At_yRdx z8foc|X7a#oNhBJ_W6a;GJY(lq257-JmF1S>ogO2%nN^wVH62})5s8rNWgruoJi$x3 zI?971KDw`EI8TN3_ZoDXqx+{8@~sw)iEX4lj7GpObT&+-9?Qndx2mV>HdzDvnM};j zMOnOk;Jvj@WgUqA5A%0zvvA4wS>NAIB=UYmGRm^^Y6by)%S;CNaVk>(T!Ij_!wAHo zL}HwyCnA1g;v3O+gIO5^6JcETp66|&?KtQ-`oyH8_4iVF8!uujnYi7IRBZdL6AB{{ z;~j~<`h(EG;>%duY|tJ(mw9n_nl;y zu{JH!wo8ABdMA>dXgi4HpuXhP(eJU3*B!7g-6b3(w2idd_^v|ZMn`MZj)V4Xqph_* zO{O*4r1v1VHr~ll@Lug|?wi8}~In&5Jr2G_n@GH;mv2O>g==qIt*XObjLv z!2lxWNnmGchf?mw^H?4u4RuKG-@m8teD^zjD$^IA)90UmZtqBZ`0$?Izke5cy*$p* zdwf6-(7w~Y_wDVLS8+OXZZ!d5Efh%eY@7F2;Smy%M^aYtUd6Q<$*}!NsrA7^2957J zixJR)AHaPl4Asa{w392q<>#>+{J#F44Eoox)ay77BU-O_dc8k^{khL8&ZsRIX=kwJ z#9>S|wUOe2NTl~Bh;#d!E2bn9sbM0hv}1@n#Hardn-u`h?5jO9lL@S{vP{fpQD}R4 zpNMSfO`W5DyFHC%q5BGNA3l6GR&#qtFJq-Q{JxCUL2Ld&%iE2fpL{hq)iODbAb&}q zLo>-XaxT{;DFpq|{W2cAZ{66G6zj7~0>QcFYa($KlpJS#rSewy#}uvPqJAg4p6xv1 zHY2hZL5RkOn#pj6e$z|44)yP#!;f^e(nI?4tqC)UkasewjXe7A*pL3ZA9URNG2eyg zPDDEq-HGJRhS6#7vNah?5X(kQs1u1@#;QO>#Ns4^cKz)m!oiI8K_<4e{y7xBP$v=k zHO>7vXdgqdyi+F$yL90Of#_T5)1Zt*@E{VfFTL-H`z-q28$6bPZB3{hoh-EDpkv$m z%0JuINrZThfPL5{YEoUxi_>RBqP|{4oq&DCa#tjxOvA`T1YZQ{WI_?*3l6v-5?wGj zqcQ?m#^(td7v?dMiI7GB&gifqS6C-ZbjW7Y@b3En^tN9A3~ZR9EVi1#cC)D~-GINN z`)haJGRmv9Mz60<9x|CwK&Xu(5DBQ7OeDH2S46@MgjYud3+9B??!}Dzedbu5K$t2> zdIUjgCKRNOI|9W_Bup=08_u~1q@z7qzfFh7euK!n(T22;R#%NtvUDNGw$(b{+SZB0 zcfLd4`ObIfi_gEH&wxlMP*7lm`BM^c9EXtz-THKunn++AaTI~3ecf6cKG~*%D9h=r zr!6}8sH0UnOR(}_2=F413$D4J^j3l6g$sXxUCcGRnpw8L!cEQkIysau} z5YbM!JrRkW_I-3(Jl*L@N4V}g-FGDtWHN>Jsp;EG*2NN~YL_#x>DMWTo8%yYYfjJfpA@CrZH-LvyLby6gPT$ zy3uE!eMax!e;7pKg`S?CY;-%5812w{dU~R#=cm5J^dJ(dBbE2BY~@=*CJ+`!*uQ9p zCp|Tj&noav0Q|v6)bU)|E+na{XD)MWr@d}tUJ1`Ih>lHY`zT~Dfixl6$L}UV?qd|*0de;pl%3>$5Z{^T zPITNi+U`QfU1+;+bli#BU8vm;8@1?L8v8_a@E{VMOdP_UMDWpH&{j~WJz(xyp(AmVPD?QxefrT>zbwp5VC(K(6A4yv2P_x9l)^15?p<9`(z?jlTP^(vSIF8`$6P z17v#R^|UB;o+L5>qiEIWga62FCv$3lNWNmZPa_eoWL_5I*gGcFNToQvX3XA2+sPr{ z$Xie*jm-T)0=PJ}iQK1AYMVsVJD_el{pe;SK}p5upS!JidH0TZg=rAqUM#Z1} zTQ$!w^z!m*avfC24AOJ~3 zK~#~~MHElg^#|9S3{Z@Vd)M=nc?9X;SM5&_`wy+NlR{!03^MYAd5h_ov_+-F9SM@Y8XNCSvbT$rSBXult{-4EJ#e?J1>Y1ZjYH=TB*BNClJFv)$VW9xIVHWu3Wphmm4`9A!z zkxe(k3N{iUeH21_hwt}0$?MUX&MQ;9A9UO|YIhgd)~;0&aq#%M9_$ktndnBxm!UPo zXe;jQv>h95?Vxt-wCx+=Jh>@6=-qd9E1K0+l-^!)K7ebkk4luW22 zv+@{afb&|njc&vEKfgTpQMA#!(6+7j4n4on%e!A1dC)0NI2xf2JvcA{V+cMJL3lp) zkqifhS|`CCB56Pex(WcmgKZDMYkp>W-cdx*A!Z&k00#V+0790* z0?BjuBM?R{Axl;R5@1uZ+TC5RySlnw*Sq&-<~e7_Vi2*``qqlrC-b$vQz!TDh!qhl z*80AP*byWG6K@jB@+`$OON$E=64b)vp0dRjB-9TbA08k2EKOh8(54R`o^1Vy1^^-< zfXZ45)^#CZC`KN<=PbVGj!{Bh4GCc#NcqMj!uRvAa$c1|pWNxs!Vk7%N&}Csyu_dhYC#?5AHS}#WH6@S3v z<0G!uTenFogcsJDY=f7a7{E*>x_WX3fx4Z|6>RT^M*BgK*wbAeP zJRzE5{}xKG7D{Z!PBw{4cdTy59KSI7F4H}QcA)HNJruP->SB7U!OeDl7 zN-`p0-7giWJ5cxDOHc%RsaVS1TKxN*v}Fa#t)OhB4Lj0R@p_qQZ^W*KueX}iTLrEF zZoqO|uy^vXUK>MNZfnZ`U7ov^zBG67pU&n4xbdL^W#hQ6?SqnKQ4+C-k8i?u$B*U0 zk4Nv=fhbvQVwHsOi?!`Nc!vJdxcXm7lEW+1G7JF|b5*qDci)3o;iOy$~C%2%^ z$wbpvz4q|%fNSqD2t!9idnBTsltqU%weIQD>16eyEh+Eh;^Fav%jGHdL|o~(J9;G& zA#Xj4ExCpEo=5PO4k2(Xe(h)r4)m=pB5%q7xZq#g}#O@W@L!%0Q4I7YHR#&;lOy86c_6SH#fC-h9NfazIe zeTug7DBM|khn^7%Cx5s+5Q+X>L>%_kdR6y*@52!yq1fwgM8f6AU}O0_4`<3f58Ob< z@8)o3=Wpj3++IxM$UgBvOA={tVuJL3ltH*@n2B9ZO9Fu0OK)TXFyi30!#}cK*A*YX z`iPGoKiUwdMkLNy^*af*4~wo+%)JqhxZd{u5$!tED@{qzYDe#}K@Y>>{W411?Af`0 zR^T7^`FStivEC_;Fc4oH(EGLGWI|eI%raq3-dL*Q?okkw^tF#`8y|&(ny7UDw+OVWjmp%rpKuJrd zaf#Za_eXCM>q-PU?|(lSs?}>^nC}3PfPos8BL|4wz=LWV1R^Z^DOB(aAv$ z7AUnO3aC;#5eR{WI6YmV^70$py0whX$Ktghh0Y}zK>xq4tBG^DTyVKwyq92DsL5rB zt5!E6v2CXoPw@}m&gU~8`jDyXH4ka(WMcPT38_>78PJLo2+tSFQFUJWu7qH?5rzT) z3TwwqpGW24h{ga(FY^E4=|F-afq2j6c0RV8r&8CsoUe)Qkz)P^Hu;OImm&bpGxL>|hNQgxJb!~diA!tlV!^D}bcq+tYU^KfUq zDIvszblkr`gOR~mr{}ZYj5;wobb!;V?;g~piG12ZtpG^vz7j11=hX5YKL+hX4`^u9 zo_ZzPnj^c9ZLWPniQVm-r^QJNQrrb2ff%PL;U=k)1dum8H$}7t3NLVaRYN6(5 z$54p)z~t8Jhp`KtPl$vPl!9Wj$2k~|t=A|{0v4T}sZaKzvo3vjdcxC(Cm#m+_<+;- zgl%2nYZv)F94we6PWNO1lKHT~~caE+76z-1~ne z5Pm%NNT985y`vF|+9qjPuM1>b8;RHp>b{`X#cYq3N3DX|hcw+TH(Xz@xV~I)du^lw zSG2}^B@nj-g%+eMok*;@?whRG_MN)X3xK_%mV&Yf%C(~CUkC42QMRSE@K=Gffm_h^ z76ttS@+#Q(ire0XH(jsogD_kHxdO|zk%%^=sbaq^jYxD7Ve3lNrOnDD1+^~i3v^vK zf)PSLG-IIMguMbTYwxZxgZWM(!7WSdl+$C`IOg}GqWW=oKN(>EFCpw9F0p@exDoBn zi9*wy;@5GkP3{>%ThsKq4ray+`+_t&#DaqquX+^Hh@DviC-q zlUUMze)rxpM~|4gnO;Otz{Ah-%cDI$ibIEDh&gTlc^nSb7w?%MK+oSuG=eaaiFS>L zJo$Yt(&M!tXnmbPFjS6M<}C{%=#Rt%LmUq1^}U!^YO9AHjZ9oLqYJ&83cv`A#zTJe zO>L5qNFW^p$&RE}cNAD7t4;B$#G+%5$Hxb2aCmxp#KS{tcxXKmC6I}&_eh+2kHq7{ zgH6t`ZQI=LdV)yb$ex7y3DQ+e>cyR7PJbZFDQ>C<5Vmm$as;_^N+kIKX~4RTeqj$L z{(i7+#owi?fV3g`p1c@8*$0c)oabt$y4UM!%ELRumoLq+f(fpS4N$*7dSfVC~aOwO=c% zMZdw2rL80^dLDr$)#+vkq|fc&_p7v7oyyY2j=j63G$_`Q!^WY}a-B<+2zDb719oBa z29*({aae=w`NAE-G<{LhOF^g@*db`sW&x6)Tj6G95yY8-pjZ}FKdfKZP9o?V2L2$i z)?NqQuzAl!?~&*q<=0xVZyV0ygPw{>SsxOL0}?UUm)uj3>)xD9fbxAtBK$oH`;HC5B#a#YEbT|SZ9NjD_y^O& zni31nXK#SmI(ZOj>&sj(H*5G(f5Jn~t)XkFsB83FmMvVdX-KfmOjbRigH`}Y^sa(NR&<{7Fn^C(iV>^U19B)@>~qS zO9%6wsUvuFaI1E$Wr>nN&rDk}SK}$5#q9b8J(m(Ij@~BQnE^I$)#M)w`)CWGgp?-u zTs2yQLvjzsY?Oh~7-3$ST3bcZHBV^EraMl1jN>@&<7X(bObQ5?4Ha_;Q>;u&L0GkX z>bZkXv4Nb&QA+VH{yv=UdcERux#IQp6)&%^HpX;a)^4<$bJlQ|rBJI+bJ*LqPUm*l z=@xAU75mV-?Wxc;=cZc#a5I3HF1-mW-_nH?)r>%}`xSbDjky|fep$g*1PpO|3m7}l zQzzp2kcmVN&mA1qU3MH@NQQ$EL}+Uu69xVGyzu-nB`;E_Q#mrIZa^z8a5%Qi#XXn$ zF@R5?A-dyv-p(2u-XIvBHwD4=+zJ1^B*MZ!Jo|@4COq~4qT1mo&@qu1W#VTufEz&# z_X?CWv}i#oKwiB%5{liXR9AcCQ?UDYIp!q~dL$yDK)1u*gYaG=q5J8yut8r&o8b4~ zM#_kTs8w*i-XH?pZaXfQ z3!b-UyuQ5R^OrC9{P{D!{q|dY`t%uJzI?&+^9x>HUU9j+TH{#69>tR*2>NXR*oXq# zZUwds)G@CYgjr$(h==d?mdN^~4mhdKcp=)e5JyN$lKY~-Wwrdph6>G?N@KorhUCu z?AO*yQ7?kB3$WKtCZtbzv;eh@6e>2Xsr7tpWmy~;7KCZ27(k#iztUM>Ywhp1EVGC} zP!@8FOy~-;XW0cRK`0PmL*j&@aOLj>T~M0rR-$GFf;?LIHGtv!n=6tlM7TK(CNgeU z+*DZ)-sBs>F_O&y8Omd~{f_O(>9Y)Msd~P+t}qQfFmbSy(Q1o?Jr zC9x0uYXkXLBNG?AzFq?OYetz`e&8*~N+hBI_Md+AXusPY&-Fv?kcX4x9ayusxWF+f zx&Pu@_wThft6=k%^zr?p<2U2d_{fOsb$u_Bh#b~o>*4gh2(EPg_Bol@{3C4p#d9Vz z9=`WT?E5;E?=3)koL^+&LKyGY1({W@QJS&kcN$g<<9&@B?;{Tx4&Du~%$}M61G+bh zEoXZMrhFQEn&z`_MdFYaKf|0zFrf%*H;IIJY!OWIkqq=Bz@L?8?5Th2c-A8k)5rk* zevbq<60%?5Fml=G^SK;CqsUBduw4AYSmu#P066e*Oxp4yb4DCdAhqIlZ6DHKE=nkY zmzP(3`SJx{zI?&A-+sd9&!6%6%QK#zU-0_+ir3eRHCTzrG+jdfB7n!ixjxH4o{$cw z*<1h<1qv7OJcIr5JjM~R!^Fo3J)1CPCM&gr<(QtMw9Wi&O#3Jg6QZ{^rwxn)^$!TE zLWDniu74ka9l+K}MDLX-6_8DUzL4Cei_DpgXz3G$Z56(BgMJTv?PTJz_Z|rWZl(2r z>@^UHvKJJgo(Wm7t?TN}y0ae9ufcV%OLP|i>BBHU8S%`p_hatnVQbTIlv{XAY{+%yp)llAV@rNGCk0 zU1X@Qv5_If!F?7}67f!gWHqHkSz@FfQzkHcFTWCxg<6>?yxV{O zY%FOv-QFG6cf3CXNZ}m<_D2B8!uk$`Vu(xQ;C+_!jj#vu5InxOdS()#<Z?jM0NGqLo}?0vDP^XcJp^z=#nIN<0!CfCPi7b>=KOYf zj>4Hp@%HuEr0e%WOvZRrx8%r=>cS-2Qs(uN=Zj}>!8XIsk@PJNIReI&t>f?}o!M(n zBs@K_v4%;*ac_YGdrw=;h@&0~4%_dK;oH7vsQCqY-aJj2>3lxc=O@lz?^$q>L}VG0 zi5NCd^NdL3-XG1EhF1!TEy!zSt368n`<9oN7kqhs#+NV8`26V;K7IOxPoF>I)2C1P z{OL1ZUti5%vG>b)7no`xp526B;WT=I~&u*dFThhy|V=Bc~QfwjUHq;4DE^Y$ZE3hwZLF!xS%P$DZUK^R{YgE+Q7o<~% zr`e(N(>4YKU-+UghS9)yUwU^&AOc|s7rdomY4;W-4r`l2YF(8;tXK-oQ(JrijHN8T zhC~qDcLUHUrHkap0T|y?05fc^GMx`ta^KvF$E8EDEPTo~C3E41-JC`EJ|PZo9}ogP zEJ=>+q~n7CrAF&96d)0DmUTK#%d`>D zlc;4qQgv{~Qx9Yvyc3+h5y0?Ke5|tu zpF&w3hfSeS-e(~rL5tT~SVz4BO;%n{WZx^+btDq=me`!{_j?OCZ)UdrUi})0gvaM$ zrak)#t$#gowmVE#r~YPo<-SePhR>o{#N_34#CJrF%00ish@#N_65iWywaxf(cz%Ay^Yb&leEEXUU%ueW=P%Yvak*Tq$D30>(^)691mr{G41w{f z-dad0T=A=_do_Z7dyc~nB*Md{&|0=*4NNrZhbyaDA3lyh+s!G61MZP|nZ6Gw+eRSDlL zw?&{U(ARI1TH5y#wX~s5Rg6qX6>RIac_tPo5!y2$OPdC^eGT2g+Tu<)^hOkPgiRHx zOpIAU3rojXDVe~E6^%r!N+imHA}dxS6boQ0TbDxz6aC0&jNU~6G)du@{{sU`KHS9O zjix?6aTsJ74vwQ`gZIyqC=c-ZY3>l}KFi z`g+03%L}$`!|&{WfdAn4{%bsxZ5q^CR{V#5;xFP~{rJxyfDUU#fLBmiA*(ZgYhjW; zowB&l?+n7RtXT1Hoc?+I>)Ss&hI<_Gc&&``&br2rh(rq_ z0)l^M|IY#F>Y6d|RTliq>tDdXyZ$RJjxLv({LozWw%H!Y1mB}HMgSLoI<)Pd`?voh z)|Y31R$Vs`zpnWCzwj^OxBsL6c$#LGr~N8K7VLW^B9SHhZfP5VYuo?Rf9c=C`44{z zStq)(Ecp4a|2qD!|KvaQP(l_*LJ{MRJrZw&x4XB)`vt(S|NDO#AAj^C$TrqZDGQ!| z?bq;||LtFUE6_u5C}d!RW1s5qEL?up!OWlkD}Mz)_|4x$J)NfVTz>Hv@wfi^e{bdS z7N~EH8?{d!5r;V`h|J{SsCRHA${x>O_%Htp{K{|q#+HXf9^o5U;j7%62AWM0WU8vc<#jF<>du0 z&o6xj!ZvJ{3)f~m?Mo=gjy~K8)+^D71p3gX(w?D3p;4VopbEBST`lPXbmHJkaM!iX zbW|7g6fhxR5|JmeES{(ItPzRQ$88FIw1GaXskFshbjZ_ES0fQRw5gGZdDrLE-LkU` ziu%5-pndf|Cl=prE6pPfGEPawu|OQ)aXjw~VrH<*QJ!X^Qq%$J?Uuv($x2S!UGh*y zIVhszbdaNH#=AO^xV&O}X+u(eul^LTa>1)yreXbX`$hcS>+j%S(;g)4|s(4?@wQefaSeJ zLXSUvdQJiQ;SZNTiT@jaACHd@5U!R?q=G}hSfTI4pKc7gazrH7b;ZLU{Nyl>+b{nz zzW=}eFW9!#M4ZK|Jr`|0?}}y7Jj?R?xz{5LWtz4OM0Ef3yT5}HS}jTL@BaXQ@;811 zr_(vcE;2pN@n$eO5{mrp4Af`K)3y)4^;=lKe3{B!A0P4k|Km4tKA)%e=d$J)QXST7 zNuMSrDQr34zxsQB59{+Y*5{<>eLMa9=Xk0W`-cxnzOh`{uFQrt>D0ox%q>~T+UDK@ z2Dv}@(T}jcykLEKnalm{w|IJa!OQo*e<*L>j_QEMng4U0w5#E`ze;NL)sOx^ESFa- zm)EHb`1#Lq{^lE8|Ku-*aB>fj%ErCeV}ydRaNPjhyU(%Y#IkiCAo%ci{|?sISFEpd zx$DCNmLL5HzxT_3s(%ylYTrh@zP{piy~W;cl4Hmw^}XCOKiR8{u1mQFOODFSZ|><( zu+JogUo?w8I>8iMJWzAVat0zq;W)?-7Ihl<%oUEQrL<@oxG`Z2B5i~inM~vb=n5aB zV{Q2LRnP}X1QJp7!|PkY?Y49xQBikVpGYN;5*4KnZ88#JWCEQ)h!cn%Ky7>3i}hsa z2jAPeZXR||P+1n#rJ^o^rSFT5&+5aPW@9^nP9_x3L5T*Dj?%{x_8y6{tZmp5{I@PE zk%zulBGJbjE}{kjWO#ZU6Q{_G*&K;he){h(>dwi7?F)TOd89u>V8`A`M9hG4xPzk4 zBAXD3;j!8EOa|d*HBC7pt^2Os=+G2{qTg-q!s!enaHi^ zZ4b4`9T))o6#U%g2r-Uhp|XVI>8U^0>s8~_KzQN zKA%w^yaj!f&Chv-^VlP?8;E?fj#HRUCL+MatjCJB*I)W2oK73|t}FM3I=xqxcH|@? zUkf@l!E^74_xaEMs;%k3@#kKdu}7k`MzF!`O9;cBW`Z=3S582=Yb$m8-KUTE=9{14 z>m9gWFSuN;xL*5uNSCXxaxUqE`V@}PKX)hbIHoTVi%AMNZ9|w6!M(SWB;t_wgV3|< zVnNO0;2q|;ZGo_ zeF2OWrPjVkUHjO=%e8nRch&<#J@Dix%bp-ziw1KRYK8_rZQU zROduF6qxX=!hIKc>8wPVIDSB|@9lWKF1W0(Z5UpcZLby2cm{qj2xD8VZSlmHS8Aop zhGa%m`8ucffZS;sq=ORHRgjMAw%6;i&^`Vtg6sAEbMMyIWOUz4BnqeZ9Y8~BYrME# zuTw^FrJ0M?~Ym5zmIo(A^Nh$S?ju0BGE9w_BI%Yj@LqlKy8NyKj>bnofW_m0BT_B%e;H{a9XaJjS@@ACWKeVY)8;J^wW z;xJ7jHZjK0CL(Qujpt^=N8%8NTWf=t16INaA&*%1sb?ywaY<=%SWV|Yp|hOL0?@L?9r-IEa(gffcH zjQDJJI=h%W*s*W{6i#EChhn6m%WcHM?X`ubcz+^e5kSOCMX%|J<&n0KTNI@~Ok^Sm zm(EM+JL#)06#w3pI|S_61)CaX4a-Qx(hbJssM#qJUQ1?upCYr&iF$%E*Z; z$d#O_M;key;np2TlI~4yOczz+ffI>)5|(^AL*{g++<&&jJ5w?do}E|(7oYO~Nd7~4 zU6%3Dk-+G2DWyAKH`rDBN{)RR*iYrlT_SPYZ@6AA`1FaJ(dQ(Bw+#Fbax9*j0VV@a z`NrFGoew|Itu3^7!I`rr z!APz^9X(*gvzT!#efriF%eu7Q&sC>zU9rky_Tt_q(!PUvd3kvkahL;s6?l61X8ig1 zJ+0JQcCW9O5ML_&VH*j=d~9}%>HgM+i_#l+^2W-plYzBp7tP+#k3tgj<+IWc_T}>%Lw* zLwi8?<4{0sVl$6n0b0*T>llcru%Mtvjuk*65&}Uj0$D0* z>C;;(iCFrWt5b#CR{I!ZsilE^S%}4VCF8HbZx!{nquzGN6~GOtTctl&1xs&vv00n? zaj7d7=_Eqj2t?;LBNBo(8>f#MbA^9KL>Av}X@aX3>@LVlcyVi|h{N z;8`;9p(@SfowcgXKtVRf2N6%VnVfGCiGAPOY)ZWaZ|}zVdcETGdcpJR&Skdkw;iwh zD}G*oo)Sfdk;`Y2565O|l4sP^5?bPu?tH=LyK>ik#|_uuJUy_xuWE$68?H&JPYkMf zn|A%rzlk)tce&xymrq0vCa_kH>){cR(Bq=}ZY0|bOui<>x^39jie;^BSddgK_5N@b zO}i3_quF%$Stem{3BkK`Xz$PB59t>=ey7|yuBoXp5Sq(%qUAGkGYfTQ-rgi{?cSF! zU#2AL{aY%RflPQ@v1-rBp$HE(Io>{f`h;5sfS7~6dnBR`bK}o@31WF+cvkQ>k*Fg0 z_S0v4dH6PqjnOZ>pGeG(GjEujSZ3XBZvpa(&!0Zw=Ra4ug>XU~#;A=89tG=GPDLaT zGu$yB+SCHO-R}1m*IIGCT<}^p`>>vev>gs>BP`o)&HRkZG!ln#G87Nj^>nId5IEgX zK}aCRpA#&?&&;c`f^L|K^$sL&V7Dg))`<09b$sK2!V%}R4J0C1bQcyN(g4SAyfQM8 zg(-$hUh3AN~9Oxmt_Ig1va0HXnHsdSi~9+_66JX^RpKuqeQPX z>DL%z7F0pW6z zUhwrFea!+7hlc`b^!XSr8J2i)VT>Lel0qCV{F= z=sMnrM4#4oS#Ua?a6X@KI-PMkotlnxJ!$Ji+$Rx0Up;i+@y#Fo5roFHXP{Z-m|!#+ zqs)4Z^P2U8_2g)~2d>*fO%>mK^UY!Wekp^aGSoYY)OCVvuIUKrl!WKKWbXl6>3aE- zpZtW(`8lKT(;@DK5m z^8>Wp^xKF-GLa)qNLSMuNd(~!&Err%*kcKi+-B3zJDN84hD=nI;<)7pW zoaLC*%!tyIm{2kXJ7DjTUDEn2IXt$}B^UW*i+)RN-%sQ~ZpIpK*~nu>3+EA22{?v9 zR(-d`5E8IL$PXq8dM^`*g7$4PcL1zFS*0CsKv{w9ykR??u%1p>*Ufs}^_ymti7aaY z)`GGXlx@LsYCoW~nVD?5*QM{&7HrQpV}sbo*0qQch<({nOKta7!D-!4 z*AwJi+q|{6f^}a|>*kJMgjUU~sMj6)<%a$BhTH26auw98VA&Vk_D&e~1X319#Ik0*&5 zQ}Fi3o&0(>;xS_)NQ`m){PY6+Dd1tBe~@~)T=3=k1wa1rk2%Is-a#mmMURzCFxWbH zUuL~yIUjzt;Gw1uJNs+<<%XC21wa1XukGSMv_N`P(w&3qABT3d78hN4`r+ZherMgE z&qgemNL-&j&|;Ln-L@6wa=|y>d;=Zc!epX~PYIk!My)k~^W(f5do}df-!4O)5dhc6 zN7RYjmuxx%qYa+rl>;%>?M&`u@(zIXEE9^W2(G6S_5%WXx?b`1*T09Chlh}tGt=Ta;`>>T z1Ow!wEs%%_0er1HuG@y&!AIBY<$~Y;{oltoFE8-&?_pceC7fH__r2R2=Xc&L1<%(T zZtIHM!N>W_%L{(`)1Tt^N-GZ$S^&2T8i+&>*V4m;LGKxX&}WwLuGhmd+MX`g%WcQL zuDEPl#3fyi9z<-ShqeyQxNeB1hx2VL+qZpE)V)#PP3m$-#{#i-5VW7J%40p+8Ccbi8(wvGn7$5r{@C z1ly@&oYM(w?{QauSFpf_k?PE=I^ogUNJKdml+%LcyrLALRjm836Np7gMJEuY_LZ%l zU$})B*FZzFc=p^#OuZzt5PLLLOmwFSJ@&AN9*U_+YfUfYnS-Xn2)z2Ww9L%mkW zrLCN|>`g!uc#o@Dx2a*hhoZ;|odC8?|N7mCgejpXd7>b8%R?TTVmOYO62A*JGd`wE zBb<-zu}8;zIJEVSq4%!89E@f`ER;#$EnfsXDwaAv@VnppBmC;`eh)@U=yk#4<0GD)p78kih{vZVJUu?*;qejYb0Za{w66Zk(-Th5 z&$vB24!QY*-}){5!LR-r{%F!8!K>EhYtn(?j1W&h4mQ9I0^>v^N*VTl@Qc5MAAbE~ zy!841dHdc^e~Ql^zrr`)d}APo$BT0rmxH{FLqS-s2zUdrsM2QN`v%{Bes%&uVAy4?Tx z^Jo0*)MtV-{j7m(wDhDLicWo6SBE+qjuS32o)W`OZ5+ua!PCS*UuPwnmK1NtK2frq zmKBq_>Vmz4NKjb~*ARUh`$3Ka;^hyRez;C}eEKbp69tkb4}I$QMTa@*f^0BQzTetP!q=BqeEIeZp1=K!=WjpT z@%8zNda06tC2`} zxc#`yL-slv(@?@SQh-tDDD#ob3Y~#L{e!P^We^<4nxFeAW!kZfI4Hui<^@{7IP4T){ zwI?;Ci3vop9^h!rV>w0r1IZXR1;=^cqqMvVhB#TVeZ%Wy1M~$! zs*4~yGD#1}=Y^y=-m-Id9CLZ>zv@^FBkCH}x$LvTxzM@9XN*h;&=-kj5+N(FKCIZD zR%}lj9=>-Dzw`IcSWXM1uV(lB=^4-8e(9LJ{a!x3;P!IG_2mj&OCKe)+P+l(?4Z=X zo||-H5ql(>@QpmAUndo^3gj%nS+HCdtk(^v{f52n-Xj4tkWc~HE9$Lczt%Ri>81Bb zTv`u>Ep(xaUfhaxq1ZxomDZW)Jrp{$$x1;6?Fd^?r}<$rKyjM^#6(uX1Y*`zIE6$E zenVWTbx>0=HYJ2`4;gsAKFO+JmRO#HAdj{q$24;i_o42%9f8%O7MO($zRv4^@25jr z^juryo3L|u&fqP_@4$nM9FB>^VY=_!3%Yi2y@f$}qBsXwu0-*5g8Z(Jwn*`NQF$vT0IEY;~PmwtaA*eGq_78CA{mh zd)VG1q5Dt-hjtMpLm(A)KRi5CxVc>&k27h?{w&HH%Q|mIc54RY`M$n8`rZU33G5rb zQ<<05hl7;Z$duz>Y-m%iH|jsL+%TJ>voP)Zj@z#Gz-4G3$=>sKF^6~`WH`vPkUvZS zazhS-U<8<-`Pq0q7U5h5)Ek$?=kz{)=QshBshj+8+jO+!Qku^~nY zm}AFy{2n49{OlqVBGE_$7Qu2}u%1?I+uDaV^&W}EKe|TgLs1KSh9>QiIF&XUXm7(D zm%6s$QFX(*Z~pCa-TKI&#b;8L1)I-1-;JscYqFnyaNWSgc3ZLCR-4y&->W+~YPD&O zumAeguWhK)?z1=DU?f6z0JmaO!TOMm-3vTy@4?6KETV~EcW$#GXcsJB z&9E1QYq8SPG0VziBFWCqQuiE2(~I`6o40l>EhG*00De!?HawLqaSM9Xx-uNo6$LGQ zNFsXOtx`>l=8x3bb=_1l!3uLEqh=$;1&uQhD@uBHnD>Z8a0LF29@`MN{xS8sZEdzD z`q+Bu-_rmEwKm(f*S$?2tN?khsIrF^_&B7efo6SvuN9TZ#EeJ;z3aLf>?yV8X9pRG z@B~C0kqB;0Jth$ZL{k}&yUvoz{Fvl5{X=IFgvz5 zm}HgEyX1sgWo_hy7az`eHXe@_U3IMVf*{{H)FYuJLi!LV zJ@*k6tIgchba8Q?q5*2TF2#OjT^gxa3m~O`Zm?o0D+=0vDO=z7(LswZ%dp+9S9sP; zh(!O`x)uSd;CkJ#>Ac4KZjQqoK{m?Wv5I~#ajV#G75jDfmGf?}W9)^7Hq}1es}hPv zDj+?B1_L-znuBdlB!)XPhIi8++}9oy7^4PhKR zvY9Qox4oNCydxPIY)4Ztg3Q7vd{g3Nc3=ZLX+9Z9M3TioOb^8YlLTiugc}h28(Ve) z_vED`OK0vSFtFeD?hN5w{o10jln`(xHY$wU2PP48ObHl?NjAnM7}~73?DRDIY?@d7 z0KXH6)A@|^`P^r1+HkpCQA!D|hT%so?s+(q5eg*`y22;{Z0(`QEnuOAwM4LNc2r^u zzP<|}^uC2K6QSmNv-86iOe^N7k1W?72t-S}?2$-R9S+9Bb_nE?$|SowClYsm)T*z5 zClU$;Bav9hKyW0zM_|H0Otkb~p8bCSVu>^*vu-QWhVM#Xy%KM2T&{*2h(NL|{2#+{ z-lEoG9aaSS|wV<@2Ts@eAMG8DvK^xlS z3gWstGlK5}(-U>0d-shu8~1R0@4doGI1-5hK-igU-u7dQfh+$ziNtX_4NLdu$|Ma3 zK=ClG@6Z3~TV-2}haIWdIHxw84f?ar~Cb!g)#n2tXhanknRL?H#&= z($>0BXLH+czFI8xtnRzd)vi6Rx4jK}vSV#P>3}oL%0#X1Mj#{(_i1tLBj85{9g#$E zk3?&g&i1315nTgco7@{^n9DNTf{dEhozhL$!Z#B%n^o+Q09=E!E=|A!=MN<2S0)hx zdalJVk^v6$m`E_;G4Q1Cn&icGj~3!`rInOO$8Z9W%ox)klIq(G6sZhM{*i#CJ($P@ zg%<#u=1&vUza=QxwiUIu9zSf2)IwL_?f<+Lney54Fc!LNfoN_zplYF+zM7591SRQ| zS-{|TJr70NY?TY?PgQ_c7Sv@SB0)ou7(9ZHlMT}=!LfnT5$jqvvoL!|?}hNW%z9iy zV?c>^Mzcc-P)Hq?0h+ zBD({+S4!)VpyQ%F6j-1Q_U$u+0{&KLK^ro)Ed3h^scsBKnt-B(AbF2)Z!qAkgsCvS zJiG0W*N4I)184VVIX-(Um(cvFqs^+wMjjj}jxC(s;1q;!BmjhW z^QP5W^PnsRQhWHlzGuM0M8W|OC5VX(9kT&1g?c2`&F0x|vpBV`;3c=9lI?A+<}}Vf zd^ntjHHr65L=fn*@V7X+&&Sp>4xlazmfBmR8VdtJd7J@XDq<>}R32q=eAN0l*~s=Y zkqG%zi3myc7IwX+PFaCK2%oMo@XWv(47iU7M2FQL9L{e z&I&DLL<43H4&s(CX*)mkpsrSxu3V?|PVZ!0%M^n@~!lrlbOxQV8_3EtAQKi>1 zo_RUM^v@z6E9Kk0D1%AVa=BxWhdaku>N~_v4^NG!S8#TO_tnN+g2%wEac@fH?-vm# z=vr>7KBhVps#e2^mCW6=0oaofGa^!`bzfpQBArA8J#Ozhxc3h^gY%v_2$RdhVVSiD zV%s*Xo3AUfESXR!0V+LN+$yUdOpn8v92`{x&a4mF$>g4v-1{OT=!^ji8hBgK7O4_h zEdDH`4S(WmiD1k?Tn4;;IJq_@5@JL`W(0zWgaHq@?-=8a@iQ6lW4f+>ho1592;`8P z;l0%x0p*RP@Uw7qo~xz1M)G?tyrB-?F$QYiB>|?G4)+xWpq>X`&3)LQRqzBY33vy|iR!x9*`R$$8G*c)+7Bur<`7Ds&(p>)tA-K5)nEv+%1 znFJ8&vbv=`VHC*p-Pzt>a&XV?d8{yre)U%X03ZNKL_t&|@zI3(x#BT?HmZf@F{jq! zdK<1CrI#ae9pa|D5LZFcG}epa_{ria2)aYQne!s_wCVd~Ym(bZ>Fs*Qx?AXn__I2s z7+>voCl6KnP{1nKm?SjkRl$ryOv-ew&lq7KfWoN>DU7LeC8usWO`P;qIFwlMeLLgp zdRXX62|1aSD3Ayu5`~rFpj3hr4CPN2J;#SA8&?1Z8eNFaZd%9U8Gu01j6mtSbe73w2UZ7h9AADEAUMq0hyMCbowEq1=K^rUG2>J=9(-{xv2RuGLwINP@ zwO#%IUx|eET8YnKrv7@a26A{x8X3r2)&;#7Oo-`sw|!(c>{{^LelN%kva?iYAV>tG z=iFrKWtNeGC7mH;puwv+{0_MT`wjw)6a+X!7%kSHoU;^Y$U3oij(R#;`H5zn8H^cjgrmXt|?_w4j10yshke%#{Qr{$ikfstE;E0t61!O$`#04-5(GLeu< z$06TTOp-dFpX`64{f+UZW7Y48Ue9VFH^7ym!|cX~xvn$?cf}2!hE7yBIccV=oOj}( z%+$EaN#IC-C>9S$xBb+8nUV2j>8sq%)KH7Nz8GHrs2Gd(PP8FT{%i|lUD}-U zr|pDOUmgB@KKJh>Hk)8T_jzp*%FRKqeHTvp;b?y;ivtOc2%6(animRVFfe^rrq6g! zrT`Kku^k=tMucHXX5$o~3I_e`0mp9yI@VMXLfn&V;Cg*fhhhlP2ZzRiU>n9fHMva2 znbv##@~|lWUI#MdX{&Qq~1P|vk z&Zl#md)*ek=pQA)9php~Y-vLYP8+uK39<_ow3!g(2A~$mUfNm`D}cR!AzpPsI$ckq zO*7TjmuPJvo;j>c^GX1_Kt#VDo-KTQP@zrfg~t0(HjUiF3d)B@$slUnkLP-p#+bY@1TTQMKbQo%!8 z2JlN;L9rePUV+*_h^7^13w5~$DJ-{)5OAI5btE1h9y`!!Hq57ajG$l`x+D3Qiu#RW zkLnUZkTs5!_)H)wJnK;+4K*x)x7!R<_kI?>5eE9{dIh8_LWzjv0}~R_-(lxg4)*Cd z*w2(_s&6Jr0zvldB>%lJOMeQ?C#|FzRP}g*i(y>J<<>qUG~Ka}3OD3gW1zZa(y#2H;iWsLoiLW<3$f!rS|kd;MRilW$bSf$&V8lazMV z$?@3JJvSy}J_nPM>qsE**gf-9}yVgpr834vau3EU`$-# z-KIlAqMTCv5Ir7vd~K$${!D*pJ8c`aN>#|ZgoQ3-^?f-3=X3j*N?RMYwapu?M4}H! zYOR1v!P<$$wyoGs8{{S^*xPvD1(8VXrOjts7bg;F1wCHb+FNB?h8RFjK$-{{g6T*x0e(*FRo@YL`hsdJFRyy5RDm`usG@vm$f`u zU61u_AQFP!)!naERXX*RROiX|g=5fpQjy>&#ls!#&_rRAKTz=P`T?{5IljSOB#cs6 zZmo{Jm)*#f=E*XK7fc`lKqeDy*#eT&;&cBI{6WLkz1C z2urMy2>sTm4IA9nK7&&y6dLEgSCq0~$Bt4K)KZN|yhS1cM4em{(lysr4%dBFNO6jc zpARy<0m8C*8zJF6pHM6;AqX47mKZ{TtPYPknZ9IF%u_5kbGaiUKIZdusuFL+Bjc8fK7lEzy_4Q$0qIkRPgZC z8Rw4=I6pn$@$nH4=LeilC#=ibhAVZ$wXVGv;^Bnz^^E#v3idLv`2zqu@!<640cc@7+P~HOeFN3+$tDWp-khW33OQa7B{S*EV$wY zY4VntV=LDBs_(YK^PULl+Qn)cE5amxPkE?wb9IWF#D4}Vyn>J%A>K&vIKsnTiRl)r zsf#1S_4q)DGTpyt+z*3_Qd#`(2sc^#oOjb0GqE&XF2pfq&*7urh5V z)hwGCFwx;Lah-$)Zre)E0i05rEdEjgiO`;cldd}5SEJTxQ@JJGrxB$rTNL2*v@E6B zr*4<@gV3|uu60G}Ve9t}!>Y?r;u0kHmSIV&QL}xpGKeI^G)El?#%F!HRJzt>i$ucn zJr5z74Q=9?r$Vn$NCSe-=AjD?Al%tSke||4*cOOup5~$IHrd2na|2+su#pQUlo5mN zQa~RgBhGF#(e(jJIOYp#%zj#iAAy01u!SzUUjq3fA{CTZh7T;S+VMjAzbvcwMD#_g z+{cw(=43OZ^}ZD=pB}%Jjmi@n^2T0$f3B@IP&_~2bvX8%diF$n+W!S-Si)`nsCf!% zWm=M<3|kakFH__~@f~{%27nn1#-vy>gs-x^UcbDhe+&mQess(;!N=Z&18GuS`YxM$ z{2ou}BALlck0Z-A6quJKU*j8q$LaH`Q#iBooTnlOJ1fIbTw@_d852%okwSrS*pkle zg4^QIFd?&dG+@G^X)7pNY2wTD^E%p-%lAa}t5~htK7ROM;8=>FYz1XQ+n)-SQ$aZa zf;XVt*>_}XxFX+xilhC zluX=ukHlV3YFm1{^wsm0y0+m^N+wWx&jcAnGkR)d`#C!bGKTytJFlGckx1+TWY}D~ z9gX|v1IC@V!P1byo;gJe zK2ix!Fh7%C%qIs%K)9;iArmDZvvHaRJf$RdZ;YUXdmbNI3`w$uIAqLTl5j?VS%*yz z%=nUSXuLgwY?$31QXL_^8^Bc=-v?kb8P&SucH6P{1>g34$L)6WX(MYI8Ujz74wF2c zPS#s+?yF9p&u1eV8XwP~A1o5AEQ9PdsVyqCz!VIWEdc3po=JA-b{>KKm)?`?Ud zTe?u!BOo?AT}B`p0JPfG1bPmt3_`7^_?;-{=}{?uaD5}d&b~pzBxUAm5_)L>0s#kt zOM&SgH#)4qYls2D#qnF)oSmt#2SFxKnuWHvP9y$0g;-^jVKd`q$@;SI|v&c9b?w;aE4L+0(T0O|7+ed^@L)ZJ1_d@c^?1nLcZ{ zp>=|vRqduLYO}~_mC19XqV}+3rQ}_}Q5v=piGAOJB3MofmaSkp7cA#x_^lr{tWPVp z4;$8}4cp_2_1qVES~}=mS758C=MA!-QAAJ{U|ARJ4>!nFP%qL*1poF06NVHxTumhoBwN%NN14hXnMqPGGXkzgqXlA?wydca&6h7U|Tnb5r! zaBR_pgPfx+={~1Z9ech%dq1CWoJT~0<8mdA56wX8u?%d)V!ZJ<9t3%E(38A-?={}a zBp*vRv}VVs`5+9-8U!Cs4#{sD!%QvQf^;sitb)Ch5Pm^PE%{zwIE}Ns-uE4QZwL|+`xKIokB@e&!<$Mev=a4haT_oO)u&-dhkjVS+PM;pww{I9 zHwNLGCFK%14MQ&kNFUz4ybs@(E#)j&htm#v*Al|Er)|CS!>jv48*2r zhs#j>f~|6kam29VPPV(j78}4HZM3zZi-w&7e$Up+YzahybY1t8I>xf*D5DQS%EJWK zxUx^PH`Ylb5|f6mBipGy$MUihY5VZH6A7*Vsy91!pieUl>_-_0FGy&Cn&gH*Oh=te zDB%xef{29SI61P3l;+^O3%wWZt2LxR%d-JY)+fzZZM|0#VdYn&4K*;`$rB?~YbB=5 z5kjvU9pIJ@cxME}(l8+q{#;z=N4Ph@2*gY`DUADWEn@GG-{RM%WCBCkNqDo#E<@Tz zUnO*M^eh8(OS+a3Jwl8l^NKgOxBPS@KF8(8^0ELzy(bwR2$)2;u8+ZMeM~7UWmY5{ zIsGgV6dz1?nN+kqZE1ElptEbD@8Td`j&pj;b)DA&cvM7b3#bw#NQRwWZyJE_nfiG|1n zEc3jD%lAG@h3^LkHO<^!fK?2raIb_KNV@GdbQ&Q_IZYus17<0{kCm*czD3m(-R&aA8r5m_-I4}0B*O|({bB(?6(_k z`z=htYO^sNkcpIfOGnGD2+DaFV;0_8XRVbMM($cZxA%%UStkKTfco$+BQX2kSBIYU zP9U5s>2T68uDqRlG=>l0#dXp3q+Kh)`#NdTo}EM{BKVCz5QwK1bOpY5huCFM zKeVC8XM0>r8OcQKiJLb#9T5plSKg)sp7snp=&c}gF|bZ{d)D}KKqPcnpZmUI{zUbl zl%{(I5bRrk_LC5S=cAK}2&XEndvBJ#$%mOa{3dQ!v-vl%L zo`sobQ_B7<`<=P3wVJ`zBh;l?#!h@Sy=QW%DbldZ(N_@Ju+74ca?FTC@ViVN*mkBO z5=y^VxN5IK`w(l8+AYK#e5-MbMMU8jsz+$Uw;f8j$h0iO_VMY-TJ{8j?P10Guwi>x zu|00>_t1JCw#OAX7vKT?S0HBqC$tZ;3p$xtfU=^XIni}pu%1@z=MD8*fh*ca*Vh7E zm%eW#qTG6K#J(7Lm=g&d+N97;4MOaNu$IR(++psV$N=>{lZTy&MD?Lf(-yWAb{KLJ zJ&H|1X*1O<`eA67SKn7KFsz(Qr3{!NavZtkOyy+-M0oG$TJ(z91UhkG8etKFAAB#F zi0PTcUM3IpOLyzhfq{~2IHoNko$&bh zhz}n=gx}-iqY(`eSX|fJ71!Ghx8CcqccQ`{R%bF%N(q3QNyDBR3#z2)QFFQHA7VXI zuwUq0tc7;Rerp75-+dUEemFfFdNdFTCI?jlnbH+Uz2_mm>tH7miCDfe+6tQ&-f@uY z5`m(It^BE~$*JIB_ z>yhZc{EZIfhi6qWnMNP$3tuw0a(@d0k;?+qt}_cMtmh<`ji)6v1e(q>GUQ?;@6N@` zV6lfGKp*Nedaq0*LMe-ac1=UyOG2geR;a7Cm4m~0-9t@j1vejhFhY5o9Zp0Ke9P}} zy^-Pm=!au52=aFtqIRtJf*gT(Kap^lg~?56_hiiJY^tMca7AG_9QzaTAzD?B$$k%* zBo{K_W8MaZgOij#NkpOWwLWmK1f{5bY`yo^JrrrA;bFt+@r2XUhOO^Uk0+cSSJX2g zCxM&=^;A($eZN-JrS`&FT8y%p0bADv`)P&T1h@jYp^=AcLAfp{mww!PB$nESG_6nq z(f3%!IltUM!5nce^|suJB?@woEcLap{D z*C@gOemUwA%>H1k-y#vw-r@OnC7dwuOQFE#yb0J#sJv`AfsrGFc7I-T(J z^n?!|KH%fWk8S_qBc47ybs}*BfY#G-Z6u=YefX62NciG&J}Z;f`zG&ha^G&dl}8+I zG$HJX$OW)TL{II*vMhc2%wo=835E7VG+EkEu)WJP5{Ya_;&~;a5Ep{Gvk%N6dd^nf zy3T<9O4yr9Wc`|W&zX(nJev;hw4pi0K87!3EMh~*4CI&aPQ$<>fyn!zSA_O?%Va6! z#k5K@P>RRdz6EkLArT>93MYW>FjP#*kQjjm;A=$ax)Fz4mq*DB;S<9bT^D^=Qy$Jo zghIccP+O=#MsnWFNGRDss~`P62p#w9eTK+oY3PxCmJ~NejLn=(=p84}0JXpykazu; zp%TP$)1FF`L(&@)U&Lh)e6DagbU7!n=U_Aq7SVX3uTHDvYvaBq;TvquiQ=`4vJr|moiC*U|1`{^vUYTQJ_o~6c0~iNb#w{ zhaL}2Kh-N+z?SNy9~Ep5=QD20g0=TZoX#hl9yXjFPVM)2!ujch)6)s3$E^{Etzth_ z?AzXc>yCZtv6KQ?3Lp!xx&x|f!Ll!H7N`}#4Q;B|wYP-oZ(W>3+#wSB0|70A#neUa z3r?+l=9W0b$?{ZOK|%|!4sF_FuY|42De#tD>L%Bgvw}iB2tHH-6pv4N*~r7T`tiDM zO_zDRw#ima!OVC`Ob=^r^hxP_TGNkCvXLP0q2ZQrhOF4-;CPf_w#-X1)MYf>M{YOR zEx?UVCKGQF2_$ed{6L^>@^gAaL3|_BS1I#K6;hxqb(Lb=(ZzA*?iN~i$JUu>PJGJQ~0pPlAxSme9Uaz=p z8@AhKLnQ=oQoi}x5nMKx%N5IVg}2T&0Hw#Rg+H$TJosP*Y3X~WOeAWp4utK#w%+Q; zsJ(aMcEj!J-<8btM#FY8q2~_dRPRiUa@m_LU=Td2hS@M94+T9L)L5e7kTVUzxEKg-mCAJ47tKQ_<=-BH}=I7n_~8RUKkW{ z0xK4lzOVUSLIZ*R+ItnH?5I^xmKr`j*T@FY67o4dtL7{dUL8U;BNaZ83EAAik2&5` zLfbi|-vduN;npRR2_^Bx%0R)KP0>$v#p)C1gJ!*>Q^KEf>M*|Ko7QKpJtMfB`3OK~ z)l%Z14`}M7uy4#lvt=;?=|O**lt^j>!p62SSkvmED@vmpdDk-@ImOvyRp+ zL1;`FGJ<7`7=a^|lySoK*@9)d*LB_tBqjom6FU&Jy5`T$G1B{(1c&39rewT?`$4P_ z{&qf{ur3R3w;NEo6OphXPDez-44R*-L-5sWeaH~Ea;foZg`P+RfdT#q zGfxjWYuN(axinx$W3KJP(2+>!5Dq=o*3{{YE=D9U?2TozT5$^=6N>}=(s1TC=vu&* z3{DDNEkk67jch5Z8M~)CG|0f)5XHoqALW^d8?TU;YFra2S_(U3dM}k*oqZ&Kkk3;B zf#yvIB0-D6X*?Lk9&(3U*GEuQTvtj2bN%K1Vf7VPnx>WWWnEVrx|8!%q!9_8sfmfi z)8iAKo}O$PSOC~gCv4Yis~@Kg+trB#0IN^7??eL7biP{NwVo1PFT?9qnBF-%u2kmy zJrjS^q%y^!lxe+GZj$O!zG~?*z@U0bz%;a|XJV0n|6;Qn@t*A5 zpkFZ#Bc_RfD~Qd##;i*`v?%ZI9rLvqr++u6zQA;Uq3h||QQD5;oo#M!81&}cJId3z zAXn(|Y!_S>OYe+G>?j4OyI^11x(+SQ7_Y_U3K4v6)afV_lZpAS+OdH!%@fjV)id2{ zC2>5`p>DKv@U_y`H(C0z#!w+*Yl9adNRic;aO#(b`1F9Y!V2B^%9AM`t0#WJ-Zuk z5U?2E3nWepLBV_Y^J|Sfkdo%Cq3;#mw~=D&p5*c&Ox}<-;Y}9broh8rAj3opAW5a) z(w$(b&}BT`;VO{P5B+%7kP4~jQ@oded+ z0W7WII%KH;Zty7miwLAF{t*d)XoMn>uo)(3c#{LR9%d&cr7LYA@KpsJG-!8joE65V z-`zF>g7Wh8#n34!hAC()gm%>DXd*=#~2|cF7gtW)wxE(d}t zCZP!$hVN!T#}Xq|n-}u+oib7QS#K>rbk>>_vS&Gy7FRg6)cT$TlpjK}C)qY@epubg zWx)O;>9B=Mn6!n9cp>D}0qUhEbN={yv2MprFqX(s43ka#eR)I1qmA>9F-yMJq+pVv zsg9|SGUsP=Tzb!9oZAPB{U{AW^;5!i4Ocq0^8Z<af|Of001BWNklKZxluKj8tSbw!vNNMX% z$kG6@5el$Ti!+GSTKl4NXyX-YBN4TtftCu?y0j*T9gRSU69~;1TH;1M9+8P=I7NWP z%f9amu=WpKbPBcvEN4W*hc(e6TLk1)DFkTaElX5r^nBE?bPRN@ZHAU@T_NjAdAvfl zidt8!YwZp!DausI;SPZmlsET#L@Zdrz^{#Q#efEvKss2$wFKw+QT7XAJ2XVuW|oOV0&%7 z97ZHc@u^=s@lb=v<;`WL`RP?B<`d6kR4LyQ>Tz4s)9J%*{G;x5=qZ~2G_C8hH$tL- zUY)s!>yIX-*XyV{i3E^-=z1X5(^SS`JAqi(50h(7Ch~J{;TJZC?%W+j#xUcD!AB&5 zj}Ln$kggZ4v(!UW%0O6_GRu>({$)^E$WH4v2PXP_&MB=6?HPgCu$$8Dt?RJY8*8Ye znbFK9E!__;K*55gNU#~1Kn$Q-Fc=NfQ%Zn=5#jnQSQc^J4T>8rvlK5cJs;!r^0g+I z!Ju*8x})H_6<=!~hIcnTadiZssH|feJU|KG8vXIWeukZru9hPirs0?IF+zb!Tf^=j zWD9uqAiQHTF%yF8)|iK7n!XqpW0QN^k#8Q!gv)uDWx0|IfD&zZfbmv873?162jD6l zWl(=1;YxA-K))ES@QoM`r-z8T9&A#X2tLh}vLu|bg+QT57P*CEn_rVDXkBcmO zX;W423s8Y&7oaY!+fhZSXe6RGGQp|W{L@*X+Mr1_^wQU@Ah1UH*)qAkx5#4786d;j zk84lEp2>u!kBCHL#bu~9t(?VYYtgyy`%EqSzBdxFZ8U6Z>n)ZmwyioiI4E0a9G2Dy zhO=h4BOFOY4C|QOT3j@BK*I%?s5yTl8YS8 z!1Mtp4+P*CWSO(pII^=oNCIEvR$?Q}bSxwx$d5QjbJozYywxmY0!6DmNnoixbZIHwSU= z!*?=xPry3#8hBZ%o+Oo>oE&Wo`iPjo>kyL&)g#{DJx)YoAOy3YhH+4@x%}ru!V6IS zjM`#7=67aWsH;})3bLY)V&AGgdLW%xM4+>zFMzkl&FTOH3AQ7MI>*vm9uo+6B9f*X zwlpOhrr`;E@x38atR&y5TT#joRQ8D^x84^kQ-LmWHinx-l>E#QB0GegldWi})7d>a z1V`x}uaS%sGZ#E^68TNwu4?f{Qs-pi`02Ord${@XTLgl)C^zRrKq-@$S)5UZAyff; z!kS)B3f&*Vi`Z)*0=5^&w(2vAUyrPU8_zuWZsE`kegA3PkxXn-d1z8cKVj;?YQJH@ zqtXaPNBwQ=Avt#Mnede?v7-})(%$JLqV+}q3lRy)B%-!sClURd2(`}U1pj~H{&mff zT~!)JA?+ITz5jb%v%AYqv44nw04Z%(kF~y?^|#FvQH}F5H&P zGh%!N7bEuB==(^RjWjqzg@;bCK|@%?gOyp%bFP+^!ys)E0klQqMD5wMljhUxD+c@^T&7To)%|snoiBCt8!?^5~8rfAdP8C4W}%0dQ>sS-nWp)7=@K zYY>tOasl^3M!b={Q_cZ8Q0|I{>8ylGYhX1TduCxV=%m2I_NZi%0CO~M{5ZspV-63r z>BD1nC>6v+jmsjos*vBX`Y?)#0?I!Ew*{p7*=lp3kyD9>6K|JnEs7Ttd~5>!|@XPI!gY+(4rS$G+)>q$CaISVQO`*VhA zVHFlOP^pinH#e)ZK)VyMqn&}cc_l}qL54%vTxJ!$<;Xi6my{WeZu$iHExqDcG}Q;& z>-pc*w7r88dQVap89^12V=C1eb;rDHx7o_>BnV0_SRtXO?d-&DuB=C!b~@Jlu?baTBAn~r%sl=9jC zhu}&L(}-L0xpO9Z!;*UX+u3$@4&bG*r{H-*z!;e@w?hgcUpBex3 z&bZUWxndCgXmW`=~2wMC&6Pwof{vT-EX_|5b-X>Am#xFW4iUV^PKGM7fR=B74Ygf*n=PR&oh#x6mwDwyJ@0x6tN<$^naI4&1j%V>E&hkEw05YrG=@MHP!{*+U7il;d1y@* z63R*n5Q8t0Ak5|a@LmX-V{rH7qwiP=?tYis4U0M4<+vU0Sgdmscpkw)a$Q^XrOy|COF4O#{9el}^|3i?tCM3w4R^Ma z2k6co=R5n>ZEHR*&cr)AnGxm*PNBS${4GNKQF2rhT6*LpSaM^vCH0!+l+%}a5OFE{C8K@1wq#K@6|G0$YoF&WlBigT?47nPuJXAeAC!8DmF5fHX3&I4aB z0$cPgsFhL?hS~E|e(`je>4kHhE;K$%qNp#k?*n4QX2ysLd&>O^2K4mcFiV^KEjtV^Kwyk0sHOC4;I)Ip`&oO&-( z^icc$s^{YqAhGL}@QZXPf&#batzJzUsGFOSR3$d+TC4wHP3)=*(ITc*@O{x3(SCIW zB$&nNs1G0RTO5*h-<=ktXJANCJ!&k7{}>L4^+H0TaPUy<}L4-y4>wzCUX7>#)#8e{!a zh}A*x-#HWS9+Mshi2cZk;O9HwO!Bnl{e_KeV!+sAs~477t(<|%E5_03V1z7VQ4y0X z-dXwY&iDM60s603%p|~Zjf9`Co-EazIoVpGH$g(d2%G>1v%QxgS}+cPu{^KJk9#IW zbZE?nkcr9tnfcO-7~+Ip36W#W)sM1AVhXZgcoQ2p$;_7`(V3i@h#iXIm|lj=M52AL zBjt`&b0n~0)7pxualb14bS6|yc&{!IDZM#ZPaP8`2U;Fg#Rn~uR)F}BT(rEAjMOSp zjGvVIB3K+jd)9}RXbC8rkEIt>Gr&a8m4i5$<^Qm(kD#TtswT*R6HyyFNLLl$ zmmne`2^L>8O(e>Z5k+NKS#q;=6@K+0h_eilg>kM0OqKGdJzKm^~ZWb_)I*n z&Mlo`dm=j0r$wjcmqp7qxe7~=Gck?{WxOcy$j3Y#zIRM*)%9gh$4$m3rYrH@S_w z-0UVMCO5e+;M~k&r&#C>5eZNhOD_*!e!11zg^Q}b?D#B*GC6wVD3FG#IIRp1-2*?4 z>)7b+T;c(?htk)HkRPYNvS6&0GcN}|V z@cU7nNzz0%0nb7w>x~)_KFe#fD0eO^T#K#^N3(vV(-iIHq?^LQ^fInI%kL$4*XAm2 zWohBe<^2L2p(Fayn6w3Ktfu{!@m`PyK4g;*IV(H+S?kOMbGVKgvN*Qoa|XM>Xz2^J z&#E=6=f6Du4VL>+BCsI|cA0>so=KI3DhXtxoKe6xdw#8ytk2&t;sZ8c>7O2vZqn1J zv-LiD0y4`l$6<-@*?(BJ`s9FAP0kvHS zz^>AgC8b9y^;ysE`{&h2;NHYUu(YceP5`Mmr?x|DL*$?pzG}8WR)ta(ad(#R$6n>3 za~Q$>eh+-8G;AqaFcI%C8FGr)oZLFswH1+Lra4#Ss5^8oGJSc!ScL#z(Xvpvyd1i_ zUbPCz79#A5xyFO=Dfkx8>tXdWyc%1txyg#OXXKG(vB;&#vKC>{E~tVuL_!-wOQ5qsndI*k{sTGinQJ5?r)lanvh8w5_nD1bQL9x*si*X-vA9opM zqQ?>Aw3kiY&LO9q0myPQKc}sLZ%^}3k>Q}vpnxSnS8)Qg7RarBI5nau0DQr9fos)ISvSHLF~ zNIF5+V2N=>IX4^-7tTXypnc9eMG2C#Xp^2-wrdw#rJt?+JK3wYw1j4P+Qid)&E6f^ z`u&O~$3g|{H~PAbgZLRR6r~4zwUl-3MHP7sp08=PLe3KI1$Ne#qT40lDw32Xm+-yp zC|v}>n?^Nx&4+!QAmoR7ZkNn7#}X{2-W55pAAoWDJ`I8i&t*u1U{xS?%AJf`HI8E%X$NXZ z7K(mORJCv-j^`2OOLk7g=4M@bP9S7A8$eHBhh zxvFNU^M5Tna{?6a$(hhnLe*)|{ygM|2>?1~!Zg!~j8vmDNvY1nB2ByWiUVQkM8q?f zn@FGQht~WrhLyRE4G!CPmrh6{TcngDvm|;_M2Y7vG1MwkV{{oe@9i@JR~ukC6`2E% zLq+Y7+wG7sZqy(lvApXTIp+v+h;{LiZWzRfn}N2=@4&LW766%hgmUo&AFkM(iR2e) zVM}ft%9HFh_`>w^gz@k1Z~61*kNo-bN4~%38BWIB72H>XlhhNUb@^5d>B4>$N{tRn zz1CTtJcr~sjsOMOE93J=$XS4K5s^|BUZSB7BP<)zqI*bkT&}DASnUeRx%ZB}Z*5N* zt?dB?oiw_W-ZZl9JF9Wb>sjW-d1~ifURDPi;i>V6=&SXq@;oz?bWP_m=Ow}M#Kd{- zMJo+EOJ1%I4Q+uuppLg+Pl=T{NaDrwO@doCUGYv| z#+bp_K;mS;gs`9z5aS&^A3G5dRa*iVb0S_v^X`4bod5Z|(DyyQuG0Jf*1Ym_?i>_` zmU|rdoQ{B0rXp?dK&7_u3V-GmhaCtQ8YZ}qpA`VI0pJ%PQn)pPVwssDuopL+L&gxna>u3R zI$F|`((I8yD|rQvs@Qj7lnkKvU@p9H$l(ha;5}O8$C&d74%In4Q0x94&}IqtbIIl5 zyUQ1_8cD!Fig!wRelSTq8X2%4go*fG-Ouxs2Rjn(K>YsmTmJn19jmrsPZ@4mzPY1- z3DNiaU2eY8(!9Q<9td^kxuhPO3icCd4I5%-18P^gLQ^Mle1RFb4u9-OtRTAs?mXwW zQsS)d`||*D%}#}CWLh`XC>qf+k>W^Xxb@?p$zV4tjh<@N3uJr3N$fpCn|U`vWn16X zUZ%b>SntJqcZABE6?=7FD+ey)v2wlYIPe?#MqjniDnMA1w-Vnv@wYzF?RWcUJ6as{ z7~*QU$>=`JRPA|*iT6J|igoLzZbR>z*BP%Dwv{s8*is}+I)UF@9mT%e?)e2>|MLCy zhkL!%kFxptPm_?>)4U-Q^{J$~`4Q0KKwds>k5lj9r>?^@p}5vCEwQ4j_{n6Bc7}bw zXBX^RVL}mGp1Y$FWbZPkh|7O)9&BdHpzJRW(3Ai#l`;>%;NcjN6W~SvfJBoU6}0lgSOT;i5x;AuN$Z&DV2S7N=Tp8P5BdJ{Ex-T#mfydA%kSU6 zVnR7PG$u0hB}X_A_xqQ8edX`&=i_z@eHuLsH1{Lsmvv+9x_tPWc6gVd8{r#hh&n4F z$F;!%(kAUHt72~~Nhg5-S8)*XJ)hTb^bB^&UzRh`V%%A>Kp+YL zQDk3+(MtmZ)*XuDa0OYHtK{V-&-0AU>g1Fh(@m|kSWXklH`nkNUxCU24(*;Hs-l%$ zkrB-xnHSAo3FJ3b{u0IZIwRXMOVFZ~ge8P!9lIz%0@&Ll3RAj>WE@)41IQ>2gzS~W z$A_+9CG$;Zk+`1hV6ajF5Lz=}z{ReOK9P~xj_hxo2_YjW%pLxkvjSn4FpTPslB$Xv zCWqe0QIP;lSd4(F3~)1soM$fcdJZ@e!-wAtIb|+ITO5hoO>QF>J&4{2%buU=?2GSC zfBKTtZ6|9h)J6UfPvqB~BNW8^HtBdiFM1??|B_$7epNjoDRZhCyJX+LzT}^O{%ODe z$Up!5Bez>F?124g!Z|rlsT*hJP$m(HA!5;sO1hbU%#0O$uS#)+WssSar``)uorDHB z7f_aQbmwAi?8^7Z8{|I3Qi)z&(|YCLL^U9~iNp=v{G#)6KAUv7vv9+FqWO#EeSH%B z?KU4KP;x+dtvWm8ObA!Nau?H`s{&;*rDBF^ zQXk^HI~r1mJLuGm?D~MpetCpmW&!YAvi!KJjfFon^Z##-t+OK)tGzdAd$4V#Y+uPQ zU3W29FMnWT_e0#?^6V3q77^I!E`D$8b+K_TlXKvt zCLMHyBef|u74%315?0{~z)nOs0nNxTgS29js-Q2K(6#S{ zga(x0H29~XgxQ-A7#NDB8Q?kAn+!7ImTVz4@gYrKQBH~n>)wmVT;*!!K!%tcK6Jt) z_5_yME8$DS>X^$l9-a;TR86J0GYH*P1MSxxZ(3K|89K{hPgScr?f6{zRAk^qxQT~s z(nd{k=oM5WZ2#@TtPcs)%O+=0FIz0|w60@rX}7XdiULuJZhBxc0J|9hobUwuL114N zoj}E?6$fdlXgb6ua=%Noq@L#l;is?SG@xH%-DK6p_~#$_ z=Rg0E|NQfh{O3Rak$?X4AGsa3*qaB95a)Typ(>}UoTn6iGHu-R8GHP=Qvv77cs>dX zkB|{Bs&fxSLUM|u&|3P9>`0TZ2ou-jFd)9LPZIVCWo`5gh|3mrqIc0>%~@euz z$}e`H_DAdC@!ArOgF6v(m95;N-0qWya0YI-S*Pk=Cb_y)O;6kN7dpgj4Wr!fbMY;i z^2NE@v7#8Airn7<&TcTY2qi^L`TbZ)CrL%*-;mTbH{@hG5w-946CnCGM@fH6@U{Kr z8@7+@H%ffj^L1hn5VT^(x5qBd%U+MGV`ICw@wNbAa;cn*8mJ_5^qz)Hwp#UE3?zrV zQ5b;ge=8=?d4xeL75^@Qd)D@S4KEHwxw;mJ?nv#9s}$ocBbJ>5v7Kxk)=Jo!fNq+F z1gC=GBUKY6;TI_kr@G+D5MONfb0HK4AtJpTRg?^1t_+e63*HSG1G{GrIYcB}4v+gd zj#(~4=CZMH4qhlMb``=Sl?rkqJOspW`!u0o~;%hzQ#wnycmhGQ^yN%!5!pSfi3{eF{Z-PSpjDYB+YD|8*PQDX)3 zbx6`Bzl#%*nL^8Sn8)bV=#gwM+mi}+SwHU^oH_&p7|&;v&E>006R0)Zde|~@sW{HA zP&*zni{o(d001BWNklbSxyOAiS6{+54HNnT}PO}m8;EaVP_Iu@N_U+b}wo_H<7f+y@uC}X7z{iCDR z9o(AoJFVe$ef%yF=#hJfx+`~KB|^v<%KuUcw2YQ~C=!*NXu74>;y6-t7uzk{$Gz=D@rnc>QWg|&`#t!ug0y&|%rnu#wrDKdBII~)-XkwfGVA3o(E zt|-&8druky-Z8X#gDO9^kim}%AY$%D(6h=zrBzCvcip(!&LWaSZ6a|ArM9amyQ=yZ z)%W#bb{Xe3eX7*j!v4)sr*rLkpVs)pwi|z)LJmjS%;x?twAcXlZ^1kYn9dyD#}lIEw>;O*nIi6AQ(KA*QPxsI+noTSM0`j_8HJ8D-_q zxY0)F+BRi7RdMP(9#&b?in|0tC2pzL<8u(P=Unzqm>hDGA(%@Pf77T;=kuIPy4pQ^ zj!?H$tE?zF6AOi;PmALv$%8G)x(*S`;J^(0tbIOnvN!?wPN~lFaRrh~{JK)jPDydz zw&I+GXOUXiZiFbGvW*X*z9sK}=b#L-*j-{5*nPk5jR5bQtjmL(^4DSiS1oC60QldH z`o%#B{UF_1Cfv9??@be{@JfnT{Iq^$oW@Gjiq0tyTgL%dQ=?p?&q5^@RO00B;U6ri zho-L@p;Yb-iH*UjZ01XqTrRR8C6g)Wh|&`C8AV(72x(9##&6O`6oR14MN0~LFV+dv zJ1&(8at-K9$s^J1o-8Z>Sq3v~F862=H@*%YdQ#aU>Wn%>1U(iyH|Nu1$Uuwm1^uac z6G&}Q^+yMZImbzbxU__Dk}jw(E9&O^eqGKiIIK`xq(XjQxo`Ig7SS80lQ3s4Wd#H()_ht-*U;_Re-_H;ZR&*10z%-)D+EG0YB zKcDG5U`|LnP_;(}Lz>D^r$KzN1vYIDv`ChE)a+ZRgowLK+(u^OTT7!!#*^z5I~2YH z;TkCvjLtZUN>~Cz&P@_@vrdLm!}Gs6Di~v@CVQf%JfEk??YvDV`Zl5mrZ&z<_Bt5# zwW^h&$0f&$15r#d<%R-mu zYiT9EVQJhA@#{NYEP0gIb1>7cB;U0L+QeMHX_s3^Hb)rjqx|b3EjvCkUCV`B6xzQ( z`Y_X1N8qmB)8GnO>Dpfi1l%6S{{Ta>$V2IL3ePxR}|e3|YQ>TTxlTt=BQZ%&sO-(M1$Vrn?&&w0uj~ zc_wLM0eX`k&V7N>;e@_c!X6mB<67WVu*P_bb?w_-XH!%U822=6-0 z`~v`PK#{+z&&{sDQ9i7rRO{+c-ZL;A7;$i)6RLS$#Gl{4WABJR=#6;JiO@Do`T^B6)(a{0f zG`526X-$Uji!zs77LhtEZH%Hrv_)-PM=ilgHNX{^aGl`y8K+;6OrNj&2XG)!`9ajieJMwGb%_))6YMo9bH zJw5WSwcx7Kd*P4)t>bKW-@KwH-|d`;^3EADCrZ2XrYc8Fh8(eDwpg}mj^WF39U`*_ z!pm@YkA#ev;EH@lOG#q{%Ah#o;zQD)*go?5{Y*DA|5Gla!be@|%07*}c7iTwSe1H% z!b>Xy_w^L&_wnjpw|9xGwz(-9b|B?scJ%Hnq zX)tKS3P&@J3Y;QG{_UYTbr%i09*xjs$up9?u-M#Cv6g^HewCOFm>PceeZs|GU74+zp;$ zqTJMPWPCR!d@GXgYl=C1abunIjIT#dWduRM8OWk%{+0bq;v$!2ZIc;6*WLjY?7k*uupKjNk znZ?E}-|nEiBp;#?(W4;Q)143&`D^q>tPv5dRJ)+F_uuI9WJkA; z84?EP=|D_kdvAo8$UU8htK8@HR#leFld^)QahE1r2pvH7mW)?Ia+T z=HPPaF24{A%`YV-MCl2HF;#?GzpVxx8=zTCPCkIS_`gGy0Kcd7e&XihH_vuBLvclp{(_DIgPGKP#pMaTT&P!WmcUlZVC7iZ`P$op)aA9EPTfjtknSBEx$vu8LFa3pdAu33)~ zp=lk~W7w;LXxHla^dAo?d_GTkJRZKZ>u>q>>v!&4{d8dee9Ghb^kGnA*4JPmEn|DX z$KDaQTka1aGM8+Xb2t_R2?90w3>vg#|Zql~YihxxZzlVgVEck%iIq;r{<`5<}= z*bbQ$r-6s2ZCBS?60k+D7XU&!BI>{k``3GAc87(|r|%trt5{i0Fo&B+6xS+a^@c@n zp0wyjl@vxLV|R&kLLMqNG9Qz`7?}|=;r2cph|CN2z_{+I;Pl%He%vzNBB(YszXx4m z<0+mT>V`0uc1AZgX?L&_@dgL%%IYW8yr%oZ;6HRG+Q*aUcpv8w%zFJ1-^!^19=7SB za44NU)rFZxVXeGw3U`gAgh<-*S9&6p^^=N_d`FLjny)S-CghV4jM^Lpco{A8&$_#lbuSu8r917m2%uCsA?qTf8%R_E7woH*_0U% zYj|cnmb8sArDo_5wPP-0Ik4r>A>;7pa~UUhQqal*OA2^cEoN=}xBg(|U#n;-)ULFA zzmJt?`x0-MKaF;;`x{y=<)=79orX;$9caj_a+hG!5~Wq6$~|6}#FL_*kFRo7OmC!D z-|oM;O1eL-8$ODJC)(p-r)fA~Fp1@ed1Cc!<)|BH*)ShMbd%#a3A~FKdfO!DFtIbB zW6*qt;ZB6tqf|QHE3j#qM{Wp!M9+lJkH8SESzN5Zw!{|2quhw}MS87tP zZoorHK1Qt`BX(+^!|BqAC_QTNJsEv}ni97#fR2PDCak0O8Huz=N3p#~UxYPh+MAxV zLD??fQKE7oGE`2P$Ld^&BxKpe%o>x2GFN9v6ZUjb33HlG#gE4CbChJKxaHhhc$~YL zX8L0OCO@NL#-AL!;k9p%oqhQK==g~YW*0VYHD*imyO2O_r;r@vE(Ml8rQMJfnisIChS>n=GO|!FF3pZ)rsr!Ps)dG4E&m za4K|&?=Ugu?%6iG#C1$3;y8}jAa9t-fjpK9ci{uGJbS*E`O57mLQTqBOPFh$w)iaG z8Z=k>*eANiwRc-yIYX}^)$$+U=}LAf(_HQ^6wzW{S^w|Sp>in(rZ^GTdA;O4$3@Ac zXj9>Y(w!mDvIf}_F`tt&N8gzb-9w(x>JDQ$dn0&G!p(c;gh25;=6)?RZ5`%gH%;uA za;`_#Vbm>gXJz1L1fFffOhGRr4;K*!bZ7JkWRJw$aPIU~rOt7dp(tf&lk3DoX=szr zkpNF@X1q*>wlU;+p5FWLl*jkCe1B7~#P{q4sSO|%L>8dxCw3M}*S%3lwoa1oi(lz_ z9>bb=NPr{M8b>!LSCR>ENMX2ID9IvvKaq1D+EY~*8}^!37*gyzsE`$$-O1~=p~uC% zYXD+_1v^xe zEh>7FsMNSx^<|?=AulQH-fVsz$s3*@8xwHz}gZ;nkp=&^m`qBYSJ>w{LCjk(iJ7wtHt| zx3-)ygHm2Yrp?7SZOlS!f3%pa>-@HH5gB%cszo(HCvgMd#A8{v?g(6xzoG@TPp<-j zup}^AspuC9x+|lGUK=P0k%GSM`tP4Lp%2erIbTpFnT-P6z19~a zK#qxu$QWmYJr46R<0IpoSYrb1G4nBGNa>Ln!-qSW8~}MxoSW8;m7xqCMRF`u{g8#V zk1hP9>%ZH+#TYKax`|_XV%w)bKTsxr5f}5Q$v_&)WO>uO?}x7rHG3$Yk7sov&_b;>AB%i!)w=OXSgfLYio`C% z+g+o7sBT3%A>js$~IitGBYsEeo<+Z-t<)&hRE1>ET47Ix&4dyxt? z8!!bR@6AdSd0u1#Uwx-SfLUcD)VQ?r>r-!eSnfWLB7Lu_9KzLF%L@$}kGeC_*sxqD zU-OqeQx$Kq&fYl@yW=&;Uw{Ce?K;wrWvMut;SpsW2dWq@1C z<}P!SNE4BRTH+~1C_~F@F)j2ILxOW;l9XxTj1dLaz6OC-f0X~-v9#_ODFQ(hN(G)8 zA~}t-wtJD;B<8~^&{BIdxgpenHTR|DcMfwBF+1f(lSG4VcPy6XG-`z^rPo>3uBXiB zi^XWv=0mDuWK^sMTNT`EjdWE?@AVHW3VcJFoB+wy0Igk`w!K-QMfvW^iRfa|BIBU} zuaw*_>iyv|x&;)FWmaOX&BGZvr~S_}@4Ij~pg%|%2C&bnH)#cM3Gv2---Uw1yatV7 zPBHO1v|>e9FsKanpU*QuBj#)%9`r!WiPdxG>c@lTL5y?T5HUI*p`#9!TR2ZQx!-OP z#Hd1GwWZPbhVYe`qTWgBLGwQIL-Sc_RSGt;L?-})zLgS21%N(`4H-qm*R|M!F)z%> zau@1@=nnn`MO2QGAeioj!u0D%=TP4ma5@m$?lG)ro^wfEtOS=10tIx6gCD3KS zw?B4xh-|yBj@HZAqMC+!j(S>q9*hcw2TD|$_J#NkR0SH~)~_8LR`Dg$Thb-^G(2z~ zv*D?{mfiA7uk`Xo26p1OIYRlaq)OVuy!HTa_&|S2jOt~{XYJ`oHBoy%lCG8N*%Krr zSk0moS2|YArIg^_mslTO+Rp9!wUFOi$4$hGzN$MjbsA7;>l+O**~`+N zy2?EbC^_|g3;3@N){lA4cPr)h!_9as)kr_4OeGl?Af5yAx$&WNlS0YLhQ+NlB>+G; z5Y%E16Gs372ByYAMy}Uzl*CK1Y6cNnyJ)WY+bR0;43ksJqof(B7=;zh87s5(@+Nkh zTNQzpV_=eX_P#(#on~==1323mq(Yb#Fls%Z)$77WKkr(eO8LYiP)zw};YMpOpg`w14^juIs2l{Ml$M*- z*fE+Ao6NmzQsTm4D7^>S>wslnVW=OEhy3@~FZmtLgiow~o-vfE_hiP6{q zn8k>pUR&)w8AXm?Wa^->^K1bL4|Myb zNCyoCY-8*9-1E41QYp<4J)<`p8g>|m>kyuG&=4zmqPF(@Wf}K>U0HWl`beOoUelYvz)9wZ@Cb?5vJg-ax^-~^um`;) zRoj-P&bGK_t=^QiNH`Fs%$Q$|gR3)9E8aV2Vu#6VHppaBGfJ((ltJZfh&r`-%g#iJ z``z)W6Va_1mBqVm*Npa^No+?ls-6Kr2r!$U!OPS!bLi4+$(^!0bQGQsT7ERJ23dzG zI=mti^*E3N5xM|7{6_7!)F~}n*yK(G^DnAC0Uh6uhy42WOMd_UEq`Kp*9j)iG33Ou zOwEy~jw_6&(gg8a^h}6I^gw73NSpPY>+lv;?8JRgI+BhAO>AeU0?XyXaX^pG;k}>- zJ)8IZKAn*+PH8-Ma@3v+Y4rjs2nmzrO?2&G`#8Zzd_oY&Xf0rOlF}Mr%BlVHL zDr_jFN#Q!QXmM+em*Gf$$ziA<3AdGN4qKk#&{r7p@<1tM;|uFzqc9&v`9|eW^0K_s z#55x!s~lX(Mu~q{A=f|=nTA}D?JnkMAIHA0n(+hEP%Uexvo;h_e3o?8bnu_zh?m+j zVf24T&*oqo+%ZlUN&>Vy)4kAdopKRVTje=aMcEB2lT;B=+T;~22tPjDUNKc@cyZZK zs_M|Ca|Je$`=N8~_Uojx#R?fxUgN$fL&`jWUsD>D8Qn<0P~?)3;tDoFx(F9F_sURTLiYn(gC$)g2|`3e5-o+o9Z0WgdKVZ{cME6 z9B?uY6OmlAANf|DtKG!2QrBNswC&r>bmSp~oUfI++v22d69$s2(YR0|ne_5}pAjSg zgWu?Zj08}i){rIgHDAn<7Ts%tcNuE$K%aG*rQSnsgwGr0w$N4Nx1FPf-D@|4HxYLT zMD*~v5+ZX)ULB%Gf?`g_PT$jjoC)w0V4mj{OmKXQp-igTbC3=NQEnzfO(Yg9nB)&b zj|6}wEpUMIFfkkQ{dlG$5lg*3eYg=;ghGbqxx*}!13>+u>OB&(S7OeGs!PD4*W`?$ zH0ex;SU66{ZR%0h-PvNDPD2j=(&!OkzTS@MG~oH|cB62&pzUzoQKYE>r0w-mCz@PB ze?xbWBeb(i(0MU;fgFk4gJ%;4LZCV)`rkdT_d{-Xaw?8v_Co#sBfou4%%4A#&t@iP z^sb4B49V>uQl~_9f(?!Gk+=pcs=hOFB7!~TJ1q_bemwMt^eO{>@J+0RgVmmffi*49 zzj+ro7kG_6^#&gs6EYjvT5L^$x)4!(A(K}YU_Yt$-I1306TsGtD&3YhB zvVC8_&GR;t=CbbH{4>eB!y43SOl0?sbEEZMP;_a)dyAaZ&O; z5-vBTxHb;NVp+GD!K17*W^lf(e%IrQdhc`6SjR6qe}-Q%ft5N;FQk@Y#Y8~!9Xs5U zfJ!@HI}4#I4{fsgu2Ryjk_0@5hn2u9Tbp8;MWNQl00mB$p;fUe;m*)xI#G4m_t`vQ zCogz{in&O}=7=(~M2->9YXwxWTYfatJ`Ood#q!}pWL*gR}27xGGv=&w-@C0?q;)*bP$AO*Ab_B*t#$;>0 zkd~hE5<_8%_P#Fva5(xWkb9%bSZ&AVnJY=X2uq~ZEMCv$2oS?sMkQ!wHfJJ!4hKRC z7|5X{aAHMl%!!oHk3-=|jJTdke#Rav6B);u$wN2rs!jm7>Mi9(wu)#?MXh6m?(kW% zNpm>n$OAq1-{bj|-@kv$??1og&-Wkseti2-m(u}00jX|n!B^*f0(|O~a7SXCXY>+? z%ai#Wi4jZ5&PD@KnXS^IB67%pJ`{E!vRC3@2jZ5_!MwiB;Zes;?g#I>J?C%WI(V+E z6Sv}4h12p;6>~_dhRkP=H1t+oE;z#o$sIcj7r(*xURPA*c6T0p-RAY(^XksTuV26A z*Viw(-|x;-5wp2E*X=oblE&$xbqrr|tAVbz*(5*#=czNxLI(jj4zfDN5IyR5x)^ED?sCiS~Lqirj2K@rzFv09u@hCjaWj)2j@j zM^D3yc#y5~Bng$S=A8q7Hkh(rGv2V|*_uhxUy+9v#A@Bh+EVE<4OJmwq62>-a+Z0< zTzg^2n#eqqwC79cJmcFw!VnbP4?U)FWzUMx7s2%)*a~MG9;~lQg19D3MFs*!uNsOl z9v6QpeDK5&A2By**RF<>XdA&ZxA`BX8|d;tq^=p|qFpwYJEMh$c;EX(3sZKHUbmXAoP1Zxu1FUlkA0 z&&G_M3Eq4NhWyof9RUg={oV?)Vc;u0&(B_kzE_)c*v9XiO9tFl>~e*PQ-13`upuR(`&sECenH&)}c-5G~DuD z=lFgMNrJ-_P6V8UjniAIU1D%tAoPP<32SJV6SIyF$wFMwI5O}2L%_kKmHOejfSpIsmif6PuqPrmc;I;fBC zr~m*U07*naRBhhxf?uz7_Ub75cE`weIq9o7M5xg~n#`trHpxWPN;pYWs{g#&-EJRV zib?rg(gF@|3B_#xZ*t06MV3 zNUy-EDyOQb4&mVmY1O*%V)l4t1o4Hxc{8IT2cm}}P0=yx4vTT??yj!Yge%FB+=XuB zG3=#21^t$-g0bI7Iu)GcwF0;Dbn#c;9X)(&VOg!==37OL;RXULJN2SS+33f8FBp^P zi4X^F;Z&e^L3J(xdx+?nJrUzLMbCrEL}LPRZ8b)+&=COM(}}p^*auB;Sr#Zu>( z4H+_lWUq&CRxIkvbQn&WM9Uk?J)cjX8{uQ+V`x+M6m$Tvo3I+-PjzleM?gLti~!71 zdq&Q4_C^?1Ynp{O7h*$$L$**KvEp0KZMfgE#eH=e{Mr33U%un^*ZoWGUwMySiQ_m@ zj!HInm92*fZiH^l9?RFZ01Zs2@=I@o4@JvoBlZu0v%!<2MRn%=tNo~F;ug-G`COl; zJf08v^L>}w?GPJ~XV(|P)wT^GF1D8JmH;3^j#YT?9N4t9by6INV;SBQ>@0;5jWh%t zxXx!7==4Qvwz~rH=-jWlCt|fTU4LQ&RZ>EYKL1{+2ex~uB`JONDwB{J#Vf3HFPtYVgbOv3w_W*mwes*KjsY>LtjbIu)o;0f;idr@06!l9Qtwy*W1`=a>|c@CzQs zRC+$ZKXM@M_vw&*kt6X%PQ%yNmwbJF$v^k6xSmeW91_Jm705_`)_5OulRhlH5j#gB zu6e$MM1339oltiqVpBib4V`y5cUr#wnR&Z^-Q#?}-{tl-1mW*jc#KjKRR|a==ORISNXvX#m`br z41yz^M;Hgm`ZWVkSmE#9r=6+Re6lQuqo;G>f|=JW-)J0i0s>ma`-=V8FmAEy&c4cp z1aV^EO~W=jXQI>=2I+*_ZE@5qEl4d_MFXEKuwbVBE+ajDUFEHnvo6olCA-7$+U+JH znBZ3x_x!3FU37_7P$5~mEe}j+K>w}dkYk|L>dH;wbVw@VNJLk8;9uuweYVxM3&@K6 z6+PSotnu!YB$kiW>!c^2d}S5qn*ZnU-Kd|_DL7kCLd-#k{Ti}&;ymFn%GaRSFr-oOw zky?HPoPh+ZF_hG`O%G>TWqGN1-F5(QcmbIWF+FnG*yc#t{Wcwy+s%1)%2)7X$oR_P zUU%;ais5ABL}a&kZEHg|`Vp34=S(<%ba{Wko(l974`C`!B00G1SfnkR$MgA=$Je9w zOx*9$Bk@1~^FQ+IzrWlk+ceb?~w*T<*vY#bVP zO1L*Df#fcpzoPQ;D7+xWUStwsCBZQBwX&ewkTuWM@YQ#9=<$}~h5oDjEahBb!bOa) z55_bl0G0n~%Cq zex(&(*QAu7eJsOXU+XnzZYW8|!-TBGOH)Tw5f@M*od@Xo_D-joXF~$%%&yYPfOy?Nk zNStTRPl!B=*0}*zd15ND>eCpA$A1ot=eqyTIO82!`q_!V#O82pxcA{C@JJwk=MZ+C z&~?M^`A#ua=YgFGPYkjpl6uul?C{pTafs=Vfd(X6?QQ1&CgXOK^SF@{b%qlW!>Yc% zdy;33=Xbox#WOZY*xiUWbY{Mo+Sgr*<>d|bzWn9vjY+vbL&eJ zA98p2s!ftk#_T!3T!rDwQzJ9f^4xgCc^x)3^BkVxSUhQG=yN=BS4N}aqWZh)sZ9%fGm0oLXa+cBYp+CA%w^b&&x1R3_DHB#a61mqt2+_r zDZ__7ou@k!x14wmCjz^DWAb)74vj9zlq<5X=PExm%Q5VaByWOi(A(8oMtamR7J#@p zUhGhapuVWwA3o6lbP_p!; zwW9CdJpa_m_<=LB<79o2A>PJ%6(AA)Umcgu1d{anxi~(7P4Zd&u#%2A0!vZ8S-)Ln zw3_D)hSL{45}<1nS9$oOvifREIYj zSSK8bTR0N2oZnF^C5!+Yi#!W~5i4?2sJ?U}XcyJvkYmt2DPGdQg%_{xMfQ9SM@!c* zwOa6d6XASIud9?}1_uj8?Wp!Yo-MY4(t=T`f=|lyI7E+|=*!#gxZz~ZzYj_5&ayfiwR2d`P)Ex=%8VfAgIHE_v#xe6s z`$^ny_xbFG-kMYF{Gy>vb8`FC8CfPgnR)9-&^1Y`z*#H~1?m}E9cqbJ8FM=ne2`4P z@+}=vb|h3adLO1U!OOqieEHX3(IfHw=Z`$TzvcOWV_8?y>Wv4b^_*-2_qKQFfSe}Z zIKvAI%Cl%}6Un$Wd0Sc~1sa#AhQKN5YPLBq%-P4VYil_6N*KMY*`AU^ZE)|oB)fi% zvif(0f>(Mk>NkCVJUKJ**#5W4Iyk1(lQK$C*%k z4D;g5h6vt5Xo=JnVWV_{NH`Vu+YP&*-lqDB@${JJM^%wpdeU)VK$LKaX)h!>vGJ$g z1EESi66+5P6(>Ao=mo!a*Nc!W-=obW)uGb$dhDKGNXiF?+rqpr$|0Yrq(GVj+ZiZ_ zrX7cg*)6P4pCoPoc2i2_IF8tn^*Dx@`382e8IT4RudM*@as)VRR4+3#(J~(4|K@mO z-O~EJ1;^D$Y%;1DFfpTL+zkHWqB;{V6_SZWj|PBMA&!)1vNzF2!(4ss=SsO0epDsD zyRLPcZK`@5o%Pc~$w2)9=#7xo5wYb^6O$8j8)Aa2$YIbE>jc@I0UT!G1U#QlcP8e< z>6kxZ>XK#epd+6WekkcKB^LEO4-sEBp6bW)gdO2DpdKS|;;{BjG2pp;roFnUUzLSTSy%9anyBoIaZwezDOh50Hh-lq@h67O?3!y7{Pe?>=QYNXgAu52_ zZ-BGOfsknBBHYeIsnTR?SF%_^gaQ1dn_2;j(XuFT6HsT!yi7%CNO?v*l(>303gbDp1|2Z&2?|Rf6G!zddY?yiibE7OfWs8~-G3;l$+q9&`l_9N$hJ zgQiwG44lN~5IHm7FmV8HJLpgFkJXy6mqd;?zxj|m+I<=%hAv6E40}NMDofvw?^uB; z(u$=)F}58&5p8G_^=814FsB0!h4~Lo1PD=W*T#C8%Zi?kmn_h zOdHG8_C_46@^ri1K-Mjn7hrYA*pFe-(&o}lEnX5KEpAVl$;zOHAFS8TSd#BQ= zBPWlHnmO%N2I#8WT@JtK4Q;c>trhFLdht9;Sl#4S#;WLlSS57;has4cTTf8Nm&}Z|z zVn@YFyo-~oYuSI|OkBaVxc53>F*HL~p>4;fJs5kZ0h%xyTa7k?uKkv4%9Y=A+3G^- z9wp->dEK1{;sqk!I1;(eI9g4THdijBwAh*0qF>Gf5uAW`It+*AvV>}f9Ai$rmN|sF zC}CD63HD~%x~96XC^HVf>1h5i#bN!As zSxZD!Vhkm(N^2sqY7TEa*Byu$=43pEeg39=roIwofRlm=;ENTS9*;+iXU}0L-~nhE zd8Yj&p36Lmr;H(G)4lAG5D903>T3A9{pa+jFPw^ff6N4ORifGg&W=QsNpU8!+{(}= z*3B}VisDGn+=$7SFS*@l30C48FHKuo=8G;$J($mouT ziaQbPJfstG9EW`SlCR&7Innyz4(fS6=hD9;bt~j6D2Xzbus^VEX=_`pYW231FP!OW zHeMde!nd%99lzu=>Q`@Ny=-wU9^Vxqq#FX5q@Am!wd<|Au&tra*LUxniK{BNvp8rp z#4^7>cOLes{Of4wU?)Hkc?a1a#uGV4GTG(`EX=qCQwafoW-B!eU2qzxIl zJLXZ9P82UdvxO-puW{utLv^Jm(^$cXR;OZK%iN&Zoe8F;^KRzZC_D= zK)WP_F^JY=kGD$*!f-D`It9-tivUd`VwSr_W2K^HXjA;KM~0_02;en-XupT<4qbEw z#)yv>j>0EHoG7wTfw2pU>p*ri;M5G!vVv8De~aNuw-b(p1i!IbRv+fmt3yMJU<&Ea zRWmTS&7VYhhF;o%U1d&Gt-@ra(?E`duO@gLhwmHmh;t5eOPP@Fpm0LbAh6MWWHYX+ zq3plBJVMIIfbw679=t5hn(OPOxi*2?l~vpx&{0M$uq+B2v4|L>D3xqE6n`dr1;z`G z-k9O*bnD!VNJ#p#pB#Vv;m;2ye&bBMeBO^;gH(CFHavbzW+7+QUsvgMhl1bLurEpX zKkyGKoeM%1WSB`Sa5I;gFQ79gc24a$fpq6+ z^3>>FMb%_cxt_#KDxC;00y7rWuQM6aVgyL7I|LVpiM3^5Qwh@(fkR==!wIgB2sJ0h z>g0>5w;E7upoy5yAty56Tx6MGD1;oT)QjU(^oZp%G6dZmGJkWsw^~h%A_lwQTxt0( zpZ8-|^_R_zI)GP{=El$ixM-#y-vHEU#`}qSEOEpGr>8UzWSOo*ER-nTYrwIVFg#MblJZr{E!W9h_R^@Dqd8MNm$ZPrK5Oihq98nLdoi_<~*Zjk{qlG_oB_+pl8$-g7_CTQy zs&`2@hHr&9)B8hpny0YxA2=3%h8dfSVDy6wy-?4t3sG1r1tnEaKyxi~GvL&CqUyT8 z{3M@;uBSf{-TrmDn~};oPdf1uJF;4K_KMN6m@RI6U!$1HuB;@~U_(}8;5<=6EN}7buVQ^c4-a|T4JZ2K_^1b_hxtMLN&hS)eA=^B=eoE&EfvHs{mPf?<>6kT2P}Iua-%nLBKpuK>Bg2>MbAmrISgbYdm@@0BHI%m zH=V=s#WEU_YPq+>q-g}*7{-Qk?{imD6LV)m4#^)Gy6Ay`^3B*I0S!x!1X)qB8f2sT>RP=wLh_6Xd`QE6 zxM_x*1e%$sF~kRYN^3Nt!o3mkD;mm0uNcbtJdC&SM;b))|0-yFMc0?D2y`;$v>Ufj z?#?hc5h%BEMylD;3vG|3VdtiG$o-MKE>hX1)F%ArgG?Y9JAZenIKd~SJFb+g5-8`i zBUMUNW-ArR#tZp`3c~-ovy#6b#TsL&KYniwW*#TVUfrSj~ zq7x`=l)INsv#qep{MW>=-m@~r*UfR^ID@8KRivLB%Fg+JnVBV(6CDsZmx?9B25^pOqHZNAJcoOER03%4j0on6+4mX40o3b_6g%`KzS@o4i!d zLG}%V3t&;CTyW9)6LIu>WekybI0x)NlsMC5%rh5TDJ|FzEqi5b>`ER=4veDbC+V5r zc%=+}^mHjtNaB?th%)r^mavOYNe*K;o@X>9(W=T@<#6*qHr~sFTN<;jB>0BHGI}R? zdZqMA9kf*+6+qqUq64S|QW8M1FYEez`koVyhddv&8qe8U*t6PX9WI=y4iHIRU zlEP3Ni4bFrGlzlIDEtxTeKrh1jj5^(^OdM%_OvhHfSjXnlqBOie1kp_Zo5jlbLVQ- zH)xqZW<9eM26lGBpGKRGOa+Edgq)0&oLa8sHk<;;6wyL*0B$I916#Y(9oBw$#&KzN z8oC3)@M#V;E19DBwd5z>?G8=0ihsHpwYEmXFR4LKL*92Eu|+wy>;4xfm`;u4>w|4~ zyDF2={qcMM;4?eWk1|B5Ct{tlZ3O=!_0Nt9?5l1KeX=2<*siE=Y2DKP^zyVdvQid2 zzlZg_k~pM3vl3quT5V@smtjoRo{8{kO&Eu=me5irWFEQmqqH|;0ssIY07*naRL~T^ zv~g_bcsMDqxaLEfR0J(KDzT1jTnihRROHN&RECYIungkwZ0y>O?-%fE5Ale1TzNB_PT3%@dfaqQ=Ky*toExS7OFtG6y#fqfP64 znOMw?z}^5)AKt{R?6G8WRe{S5_dL|zfLac0C{kI!_>FoWEQ&bYh*9Ir(eGVei(on_ z3I5Yy4%Y$D>tZH@^vdE$pw~puf~79L0K6!gESu!jwQLtTDRxL=)4juot%kAJ%H`S^ zRv<<6NDMQPF}#-LFq)XBLQYunb@oa?4}qbEA*A>O(=WVX42GJ`L^vJsYd|D;g%WRi zVzIIFU3DU=1AzH*CGB8b*CK3Jw9-(n5syZkS$C|3d2v9$g97Uo^n<9lOo|n_I*_k7 z0XNUfqbn}}@)MV7gH%X{*e3m79<3F}Uc8Hg>egr0=7}-kTYaqypP%$|ZFB62!_Fq?qjoWnm#KKxHVxg>;RNUc( zLJQ|FSfu5rbE&uhzOifdb2<@oqV-dr&)HLf9gAal69HMML1sjdNutEX$IgV3pmjF6;0ZmfxX2%Xflhk=K|nX_9KQ}N-ZSjr;sDzaiT{;MdmWvV|bYzqFVPc>8-hN zCPYWr2iAdxp7bMZ_Ouz^GEY^l9jOajsRlobP6*+u+NFP+PDrLZ!2&rGSt73d;GjU? z?VO4JYZ+^5;=S5p*$0V58YMrCt4m59^32y9I#Sya7diuqEA&P~0W%w3Ywb-L24tvsVdqTL&ochy zb-7RbnD>?5?Ps4H-N5hO!~PHj$v-1J2WP^2B-E%4=P((EzjYv<^|-eFbtq8~5tNF1 zGNHh@#RSGAjLUpBH>8ukuCm+K&O=G4kjwe4Zx@mez@JR?>gjCXiIU zsg>3J!c|UV6qQ&hD~%M4fsf7ia?K}Ak-?yzr;& zI4n*C2i+*?`B4GL>8VHwgFHuRt9vLY;yP{pyb1^UPp;|BZ*hn zX^F|&2tY0*tquWYTQS3=DpR_CF<(OaZR(l&4QQl#z}U41m6U@F)UE99StU!?S9$Pr zw!{7B?_<;eAs{?gR}^=2d(Vk;!0N}npO3BDNW-Wz%SsAF&AEcXSaY=apf$=L& zx&V8j7QoEcp{O*NFvxr&<<*65N%-Q}3Umh!EoYv2$Vtx6gLAj3f$vDLeaKx&y?$T$ zzRf`|3)Xq`Dzfs4O(26qrM?)*<({K&toyvth+vE=+qO_JH7d|HWhO;vDy7)H+R(}_ zvH4tlO%89QR)oYtp$%$bsV(`wM+Hp+<{wsSLeB(Gt{!C=i-p0wW*HUs78DZPB2c%) z!p@fS7p>>w3Y~|9O|_y$Hj9Z>@iI_}?PNS?@#)xT#4@P!`JsoH3>k`5@3f>cm!!=J z>6mzpbkOSyhfbYlb})iNimMH89E_Hp@yMsn)_$n8GI_O?~;<)K`1pxKS3I9{uXKE*s>u1^?3;M>()_ zP|Ahvyw*@FtxTe3nROF63EF&lr5JV3*o{4jo@uvpyTeS1o>8r5R-hOc|FUW7Qzrt1 zT9y#L&)x`)!YsP*|KG>|6$uxP!#)VvC8;98K3Kh(M>-lB_Z5GlK73##Ux;ZY*rHPq zaaAE~bHx#7gjWzkTj(oNd)L54qJ>P3=U&FEdWBJUA_By1;#u3UxiD7<#PP+A3~ zw@hZMbOv7;R9m$ed`;CD@Fq?G*CvRws@PgEOgjq#;)A8ATu_nfAaK^ql?c;nn}9^) zM{-VtXA7Iq*y&LXOEza-J5t+pS@`MNdAq|`NZ0a1f8N`E0Bo|=VDQ+DZ{HR{^;JBFcECBESn`Ml@oqnC@)Cfm5@0_sAPUA9;&u^Pk7 zVv|R&DP`DQ0bSIBefq>)b4OxnnRZejj>HUbf%DH}^#={jv1nL~NG#!fWWE7q* zAOozdd=74_#4wRsepf0V@o_B8&a`B@jPk+;Sm;hf#D-5d!@AlI;JJsW44I0hWs_n% z%-5+HGR7f?3GHW--_!}=Nn8Tj4v0my3*%9C3h>E;%^u;NeiH zvvru6P+gRGz5;8>FfEUzm$0#7Ls00_s!3~oFE>peti&uNEq6<=R;lM*7kT~Cv`YE? zPEr5h*chism-OOVmLH}`S;#pBYW?RtpYV=*8~fk z09VB7grb-Bjv!CV+n$apJ6HCf-nWGqK0V$AO@vx0h~7u8Nmu6QBYHGXG0ag!RHq|> z@(f1;&?j}xKJOeaKjR6$FZc@eovMa~Ee%RMBb2X{b|k$JB9YN~<8g*ytCXfA&F9%7 zK}%+G7B8~3=7DPqFM%j!{+w=jtN?Bo!W`l8?OTaU#mK;HULW%pf_IQoKsk^=uyFKj zN*d-*oe9oQxMXN&S9Bp53xdW1xs&0HECFqOm(!p0VMrkXh!s*)8cdzWwR!0FS zaJ^|jG#rKmCA-xirn0w29G8brL=!3bWFI+pkl)n~s$y^$mWjENj>K$PJ|ey9+=34c zD0!Tsvh+S&?@$eAA~&3iP3Ia|1VgG5A<&d7&*5B!o{?6@Dzbx3G_u<#3*$X*AEQTVbgNNZ;QJU_Vj3IL9m=mo@;np4r;u{l4sskW>$`=4M4=bth z1GM$wYka5-G0lnO>gf#S+9*`6vc{#};|b?MQueAN;Wa0ml8iTYXs0x0)OCU;(srQ@ z-S^WY=*ZHDw7c_>&Nyru^IEcwv2iC`9=0ROs_Ws*R}L5I^tOYX2##-wmrbj-XCDC2 zqHZr82q|DP=SC)P*?~~yxLzso4~{Ef0lOz%KCY}N4qLA%jjp@an0SaOMbdc1;a`wY z4{m@#J%3k*pRm?tcPl#iZ}U<8)p>8Td6wp`f#HO$b3g> z2JF5xGpzoVIy3>G24MBYB24PACGTmdLzwV0LHC=AG zK(>h0#YAuf$i{6NK!{eP1Kteb&FMF0D0TnLqL#RMPK}@h+-3xy-RAyi2oJG2b)(YR zdA&FiS>I}8l68>d61G{aF+cDRYz}r$lwB zgK=NrS_{$dS1=LjS!Eh$e0R+9afO5-2j-K({avpPO23*;M}}!wkQR8QEli=71g50p zc}qj%@2HTB!v0K1suPhD1&{VDJ@Zu5D|f@7Aqb2c2@AJSZ7I^4Pj#aV7%`361WURW z2HjLNX652S?qI1wt8yp;1U2d`Jl#uOu>6@*c8%F}pQ5FOAVD^-4)WBr-YV9(Z)$4vwY}?9C2QeWB81iWrt7lJLf>{j! z*Z6KG9xd(IxtoS1iORD4_S{<{=gP!TCNAS9kCT_~@W9SQk1w9VC~CY16bfhA-28f; zQ&vsj0E834`YUq8js%_?l`k4nB(I$h1qfTF9!>-~COkZBe!tP3rQE8~RFbv4Uyq2w z#OJ`knW$v|O^Unt3BsYq53tf8aL*0h$CB$xy^0c^>kZm89jIa^j;@Xxrh35!ioSS_@y_=6iE_?!NF<&3O_9M*Zs z+uqvdGb-Ch+y?<)Xt>CpEbNP4RYP3j`O7e@d9#uuAJCDp z3MqoH@gjNE^33D17b>B&I8miJ4pAFEF1R`r5SC^UYmPVCv~vP?u`F+y=TKw)|IzlQ z3y!le+NeZo=Kinu>oPh&v^^3cN%wok-6>oeHX=+!T!_VCb-I)pPCDsZA~xSMu`V4E z6v8L`VQ{(8x^XW9I1+2o5;^Kl<2PLtf%3EwFw@azBI5pApP#!EaVk#~+EU3XJHYyj z$qh|5<0?LOSd)Ks$t~QJOBlq&godfgzZ~Na`t*_WPB)UkDw*4C(<0*SM!F;n;6Oy! z5d?G>gE>U8WYZ5%(9z4F>S|1K!bwK6X~g^Abd*w=QW_hc7C<5>C$UJB!+Sjr^W)#d zz0+mHk?Pm3a{?`9^m|@*0fL&N%d}>&g^wla&=ACV+v1G5GEn6Fm4-oar0hMR&Tu|N z{9xMz(A97fX<#5GQCtVG9PZ9&#lc6JG&mC708FFOXYoSgbR?705s~vUz?}`D?7WB^ z@$&TrbsVDG-xoLs&h;}$`Og0C|nrNBrGw=f6+7tSsDE}QIvgJ3R`t|!PtoE<#t$H3&Ivsnzv?`Unf~c&1q5^J{U?Y*Ebef} z{k|zAQ!75`lE)_0>lmWAsK~@j5L$0i8lW+zaceg4`6&R(2~xd|R#qn!7cplWOre_a zA)?&<=)iO050^9b@WElO;Cq!`?nLK|B<7BUIt>1Cxm*T-;b6^zUt&J1k@%yJVT_sb zH*q#GJ~oeFi3VYwu*B{()<9_C{vrtIkVn03-U5H2V7MZ5MZ#lqIv8W&9fk=`0wXox zF+*i=Ah5ECLw(RpF}wmC=;x*;3SDprkWAS>Zq;Fo{SkZXCRnlqZ5j4tlq#E(A}~WL zzO=*~6sa>1&+}{dCr)OH*@9$N*O_?a3Vr+cAAVMv@1v=qU-$Kf!N3|z%+RyuYirW%gD6zJ-dv~Wku1~5l%#T zS>9g#-=%gB;3LrRVH|OlyHlC=bZ{V+RmjWm1smqXoix`G3ukd!Taf&q5AlxaP5}e> z=8Cg$6gb~S{h^zy%qzX&^n`M%bJkW0Pd>|a&;(DYUAjCIA8*F2{?Q=GlAt}wdWEigFsS$Bafal0W*$r z$s@L^;yN6ppkq4jed*daOO)!2gqc-`UX}6`^5>v|dUso*zvxPMr7w-SKSF6?LD6HRlvVYLCn8wsNTID zJ~CB}7Ahl9IYb7Ej_B=Dk8p6C63FH$k{H%;eG~_U2IzeFAmeL~o+I}$vL)Vu(4Hnf z-*m}G82UshI;U<-9r?@{blhQH1d6i|I{3lbR?*az2J11Nl%t(mKPVJ{r_4qO%t~N0 z*3uamPyn~Cin2*Z{x|Km*?KtMHI_Eveu?TxR7DB6@}3+NaYiaVh}7ALzq*PT93>Hf zIX%EoiwYhhNQK5S}jL2N~A&)?8QCF^4@yFW}O+yKFf6r}SF`u3R&Wl?M3e zTbzy3XHVbgI_hSlW5C@AN6O^WnK;`&U8ie-228ylVureL548i2b~Et;$n|Q&$w3T1 z7{T$vN8pCa;)O)mKZYc}o>dCTs1V_*(8Nv^DVy^my)SRV4#|!|8C}OkPb>v77s5U8 zP!UfQ%b#%X1Y)?zH+s`4UOz)Cj>>4#|Cu-b4zmCqMPFUev4z?=6|u{9P%LFeqZi;r z8p;btpUpTkx?y75Q@e=$>)4G!b97V-O*XAfuK^H*fD^}gRB=_t?FDFJZb_pbK~S-H zS|-|V1f&i;s|A`xCo94RlX&4Bd=&dqej%R`cI(4f;?fyLD1_!W1m!%HDn4mrF_SDN z5nZaZ){BX(IIYuWup>-EySua`cr7cDptAZaq`Pj-HRcyEbi zOM1-fw*3-2oSE}0(Qmrr!&Q?gKk4#8ro~H_Zmo0qU>bqC)N2DgYPhrJeZA=Q^P<=O zq4jLqyuo0%TDzTwcURO@^W@9~#%KM+K0<4<;4s+Jfk>LaShAgu117^)C~#Dh4pQm~ zeMAl0gnk6Ou${1z&qp6d4K4>M|8yQYG<;Jq2(IC%*vLXQ#$$E)NBiu)7SsR!@Bh-z z&;QWt^+T`Mimi>6W?4XXmEEcMF z`ee}VjW%XOSujDRr)nCsCaWXk1{D5EUwl&Dkbin-Viw5nQ-S~GI`!0Cn|uy;9E2^C z8_I8$aEp8Ehxt1=lGWRRvq6Esqg+jIIcm{e4(0Sg$csZSVvdkyce+avlkzaD;f9B! zhT*~tQt^(UxB(Fk`@Ed*Js~sYrcXZP0$YPz_J(2Lqebk4gkT3s>Rw;c{4-R0%0jCQ zDB@^BmyZ!a|y$lgL(Vz5)`%kp0964bdf#X6mO3$$-Tp%wDl>ILtcx0}ko`{_p?L|NPJY(9h408S%?>hdIv6J{%G_B`OA6(eimk z_n|Z4eZot5^RHkmRT8p$QZ`^Wr=b(2>f|LW!Gj*1r&Sc!eg}0!0 zyIj-PAP>Z>%VGw#VNkwzf6mfUxpK+VA;?<4Ac5thudMJD7}=wZrc32FD(dmjikn$g z(xJRcz>S$Y!!i^3F@1h+c{H&;r?A(K-6ZsiCka8SvejoLJZlAp zv+6(*LeSliDWOZpTD+!w#*;Fz7$Ds2HV(#Mnm3Zw zs0vsZ?j$x%tUq@mXfZ7!dYLYNEz*yhEuyuAUdyqo?|la1FpY3ycmgHFI@Az3x9%VsF{c02j>a#7RIuqJWAOLHbyIY)bAhaO#n7@ zdD;+D!QGK90Af2(*TyUE1(!xh!!COqQ#zuaqUahZH+X59mALgSGI@s)+wN_^nM9Pu zsW(DK$6f|~Q)VQ12uB_5UD;R35+lmhtN|rWlxaBEZufs-J<7>3sdiBr=F0*z0UaRR z5w0EE`wul@ZF_0}Z^Lwr{2qkWNWcJ#8kq|5A~q3{`nK0~dsU&5NXG5wAUn3HQE3tZB&3E?_~h77#3lw0wHwf9{~6vXM!+SKiMexFP__SDBo*qm8UBlDvCxZ{h#nHsQJgIlGZM>dUK3hho$crGe<-e4XvSStK2i%~mRoL~$rI zG|5^i1=SW*yP(Of&>h|$nDsae6?krgDv1w=yJwpe6HyuU$8dq&@-C>8nSOqL=*Q^5 z9SN^^?+r3rXE2zSp7X&tvqOjRgtFUtf}!7?{$8&a{ovB3;vCl_#1kh~pB32`15%y( za)$Tp=d*9zfzY-<7;KQj7-6enAJ(gvnYg;^j*|vH=$S}z5Wt*Q{QYFv{N=@CuqEN+ zCAX)0|4s2*gxvD%uJgC+boZ#6vDqmIOSZ4j7P!N<#rB z*DD20!@txxZqHN=q&SVyc>S*~kn2%L7za6klY;^0S*?ur0_YoIEN~D8II|7Q)Q@48kJ>`36mm2rJ3+3`& zpo1ib%}t)1i*QWYquo}drB zd#i+m*p}|Bg`=K7Ia7f~OBgQtwKPX_7(!r_KU-iXqW;|YmfDERB_Seig9xahe2JIC zs_p6qm-S=JqS!1R;0F!4a3uEDZw3e)S?g^9Lkj!a`@a~{{+A2%ke5sk@Tu4jrH|!t zDKD^fF~V{`mfmsg@@*7ymX1|HM{I$WTi8X$Boni|>O6tcZFnFk_b85lpNv++?m=52 zky`MM2L0>jCuRX~7S1y#Dw-tVsXC5qo zyv@Es@OnAXr_k@cjxIC&DOdsC`z+k4qlC&VEe&l5x!c-bBVB`5#$Q?ZZ0sFFuSxXl@4NBYl!Vf^GOPhYc@JL$Eq7xrJV8(=wf}?fdwq|fT zdd91$j3E`09By!B!ttL>&TzD7nH3qJutNUHiTKJ8yy@&wVGQNI3*P}PP9E|GmM|)c zsV*b=lFZJ3fX-lt=D*vdNMZFQ0-gfuD`(+<|EMOBpoAkMkm9H%$ag)@}hJH%q`jRuJ7L z)JGh=FSIl}rj!%j>u7uMC&7$_P#*VM1-*aV(rIN&osrl=aR398*sMca&SWzbzDIzU zj*jNiCPzu0e&n0|_s;zh8}8%srq4==o`*vFkTj&FA&SU0M^*0G*E$_nSlmt+}C ztg}1o^`h6_^z-whxLoc??0Wj0Z@_k8Uz7qJBgU@CgUw4k_G$bX(sKKO@<)6*pB?0t z4k#)wH2f*6r=#GAYLSxxK{!Z4@Lch5C=@S0?%c`1WU)GpqX>dK*g3+Ty;zx zGXTARZyEdJT|c9G!}6vXiAm3w{^onSBmR?ZQ4Bz7jDxxFlQ#P14hfLyicMBp#*#Q=*^b4M++c!l&%o~lzev`OgT1cFk)_k!&(?$ zx{{0zD;R^tP;l6cxT2R0U9rqb+<+HaYw4yyVfzBG=;eFM(5oC7a}uO za#QD8Ke6eWU$CSJHY*24Vu=rh6H)d@?CL;FPQ+VP>$s9O%St_vI0$}$rA=kCwHtwy zFh4t&D|x5H(Xa8H3${ZHBxfb??le*yhHmVmL7H@y@f&0R(yneuI8VU4Y?Ub_;_O!k91U@j%&dfrKw3sx?l-bfle1atEK) zx{3oVSQZtEO{=BwbW{ck+xx~|M5Z=8tv`mDP?EkC-x z4Y1o@i%P&P4`+M<>y)4W01>?JZJz9acjbNy3&;R!wBPGs*rQOIJJ-txex~pUQ3)0M zLv%EsaUdvWm`{3-GRS2UXIg86b7L9w;N+J&Q^Td{r#0YqA`UVM#N;52K(^@F5lyW& z#&;E$$=5YaEfz51`hZd{;%tyVGcoyDwMNBr&IH}mbjSg@Gc*5j`kuT}G1Lus@ zL9h9(CpZbqN5I&o-bM7dOOY4oFbQSs#*^3w$%u40(tC>IpO2#`aP9QX0qB zNPxWbTvZ%2&J(=FAsY9H*L+`N55ZwIM!kPUE7hDWdJP5M)CQ4jJI`wpm(XHRB4YgN zaX32_rzSo55jZ*EFveky<0RSFXmf5X&AOFGciWQ_<=Zi@5>7-L!4KzykoBWAt$}4W zMk@LfCrZ4Bk-eDfcQ6h^s*a>-8F_T9ynZa2s}m8k5tiQ+V>J0ip2I0%2xq-m3Ab`fo=A_5n5R9=ty-71 zJmfdZo_Oc!eemTXkczaEjN?L>G}3sLjh@ccZmTR%V>G;M3DfHIo01Os!kw6Na)GmA zhdo#K-aTH&~;mN~qpv!WYPMo~CdNuFx^vRieUkb+E!ae;I z{%_YOA2XMve$r#jav91+LqETzbgek(^pi6j<(kYm2i^q43@*oZIfE-vq?BCg?5~W5 zuIB#pl`|6G(95OrLI36jZS2L4=_eN|aGh}n>5G8TJp;72?%6++ zwB97?N+T4vhXDtlF0R2KGpS{X;{#5~%0Hcj-b<18Lzjy6P|6kw!2BJy!>!{<0k4 zZA#-!){9=oO3Vws(ULy`qY;hVtDzqXE9GPI=ex_5ZmnZ6!Hk6Cq2{YjXW|Tc-{cMF zn|IDcNt^P~t@12NVO4LSogAnuvjN;Gb{QCud`EaQt9$>twJqI-McQ3c~+`GP!hKEj& zrA%1)z-VDK8etEqOvv0sXHU=c^|x2I8m||_eaLWZw*Id`+yE2obkv{2Rle~7ozxW) zQ60UAsVL8TsQ^c%uwWs9kB+%fv~A5X&Pw$1ZcRBTYK-nluubD=)Is17l9w7a=0vyx3>*g1Y>CNZX~H0}HF+xzFKmt=wA*hDS1I4# zD6nG0zGF^^OTIr+AZ3*^ryESz&r(VV^HFo7^!sq#M9SOTsQBrIst|8<;)%dv$YpHk zB;-foBxWRj_Y)t7OM|K!<7uqqcO#frQmRlGVKF-YOfwSplfF4Q9i8+HvUw;^(pfT` z0Vx-nL(+D>0H-LIWx>)WC<6DLI5qiky374>W?Hd~DQ6Qaj6yLw9z1nA6ZSfcvq;|v zN9vzS0pOUN&JxPuHiB5$w~5CTsySGZ@Z=-Jw}Bmpt;Li&>3DlL2(AXNkd0z;8Q@`` zbr|$Rk=QcC9e>Z9w;9)4OMsUd89@y$lTf5^4Y4 zxT;rbW7NwtT%UBvzg?%^yICDjG4cNw)@OLUEm_m-K=Q}EHLiFrioQDl@?mRpj_ACgQkxen{7qz1SjGL1U zX6H?J7}R-qiUUy`3WHIXJLN2+G}2N3B zZXD#WA&P5!HiAnyGoUQMZ@x^1JXR+qAvf9ES{EawW;hg^Aq^0LyYmj>7=g?BGk|^Z z>1q9iW&o$v#e=tySJ7+bB)1$qOkjo0k%fHT9fBTzk(1x|2el#p;j)7B3fStqk(k_CNHN#hvz9 z!s2yIGr;dIuP63U^mg$0VD>~br|8WyY*L8_I(Z8nB>E!Z+3VdZno{69!50vd@&D10 zsFi%j8hU-l9+|eLpNYH@lNmrbT@XqJgdr%eG^Swr0&IND{S#iKc%fC7&GM#&&o)FE zk`IiGN@T}$${{P6dgoVB+D(-r+l)s$e^}kcbw=hV0Xt=!QsFtULz2EqUB&$5dzhs%ZEKWbJ7>X11eb3*6L~I|n_k zuQz{tot`N1j9a34wvNjH#ys$eE!KbwAWKLk1w?Y@ncnTZyyV$he_2>TH; zk!>b+m}8$!a~jIC?V)g5b9f1rkPFE$%>4&+*4|z| zFQ)A{0f!6W?|mI~!)WZUST@-AX)q9XjIO&(EVwxhf~*6}hqe`1tMVUhoHyEaTGoW| z6|E`lomR;Wl3?%q>|w21orMlu4o>z?KzZV6(}755qS7Hj+Ue>}BjNqyW&9rUzPQl$ zY$5(#=Navo!{EGD`o%kO3IoOXa|(AK82vW%`Tt}>oK z4E&UG|LywTiMZsaa=y^pv~_Im*0wVa_0a5moX!K*cWYPb+GejDsXkw09~OduhZF>A zw=mifT3VqJu5n}Ke-jU{&m_sGmCNuwHp_W9^McX=9VqHZ^ak`QJ~j}hVs0ZO*{~S{ zbHfMmBk&90E`ks=Lfu%Wfnbg(3lNP)#m#Df5jXXK!J|(4EuspA+@SZfT=VKzCout; zNjR3$dMk`oIpFAcO5?5n5T+AEjK)ofVn#nNR>N&=S|YUfL%e;X?Nfxo-cO4IxsB6CrNsQ5s+_3XnDX5gR5GoIs|13Z;KT=44bT z*|p4JoFF)Ey5BMrdoHvS!=3XvT-b9Vj1{kaKpVK)p zpK1)7GnP^4&}cfG;Ip=H>}eP!)`CFuof@#`5CU8dWgW0$(I2nx3`vCMFsTO_E3R{6 zhWlzJS`m|>{I{?*NdMY#$i67_TT=LkS2gLO3L%b%_y2Nr=iFyI(su^=gcX(<32Jow zq0SHe<(Q~R&TpPfWmbEl)-??v4h8)S*`DFI0z>NKhr)%3e*TKz;C{fyaz}pXOFj_M zaWZ+n5i?1dP)Hz%*%%lO<7NEkiXDvJI#QPRSVs*~IE-_Xa_*9#QJu=$>z^+nijRR6 zDr4OAi!V$Iz!#g-kf^ajRsmGp-RZY8bc??)Ft-8 zAb|10*LRumM$}Dpypuj|SB-@fqUk-&Fnk`>Q{km4K0q_~;rhTBJ;X>zun2 zq5Eb?X`hilt21$Kw9Z+ua3YYu;a{SoIu6CLAfosHqd2Y*Z$)!a2!PHnU})neGBj5h z@^dDLs<2;!24jGuI}N83QAY!N7?iXdi0~`aVtLBUM58$z4HI(SwP%#!=qQ1qoFF#i z4dcq-PEE^{{l3Rpg_EzZBJpP64@OuWgLK*F?XHf*VE_*GeA3whKg`hOBRY5A6db+- z3Ozt$I%Rnbb1#5J;OpUETzu<$cSAnu1JL#ZV+;A6u18sfVp` zYvzA+9167mY{6$fkr}3-<4YCaIuj1#t=(sIg{_xUc-I{>7#*pzuHWJM=1{n-^1m*B zaCQaD&~&~`N}%LQRnv!&|D`9dt&?{zTRQ0x7?LCYSlZN+eBF?b2~)uLws3iSsEM(R zw_q3zA>N|HxkG@G28;~TLHUPgy7O?1%s~^2 zP%M3c@Lx0!4l#y=e1oEixT9E^<1bnK;UL)|Yo*HGj=8@<9!A8>_og`gy*YXzs{ud} ziW8Fdv+4KuX%^Ocs>jo$^zK6Cmx;$S2BKgp@nsb|k$x{^Cx9Bhkta*5Htzju2e3 zGC32+evE)K@u(kxG*v31VQ+BZ54f9Akg|3jYRbBRzgybMexJr1qqN~A%9@!_-s$W# z;7><_s2W9obB(!rWEp^I?+TsKK`Uk82u|h__~uQY+tKQn{KJ`f(%~0Y%~$r`m$>?m zcKSCqSaldD$?=Km{x7e0O6&7A%*DJ-{T)1)H(wa~pO$Ua!NH81%lcT|oDcGU0(rDY zp^Sg)ozoV*gYl_!=iy`CggmzD>H7ZXD;6?S?RpAPkF7pzm^^o>-#ETIKw|| zxWztLN9xtD$uVOLhK1EQoU>^q?mKoaoMH$RK7|AxJ0?U$(H<6Uzi>nqE9x*Db^sb8 zX9ZnYrZNY<_Hsx5=D7J+u-)m^JuOVM5l)GZzU9eH#qiBq2J%%SURUCt)=6znCTTWWI~J1Zt zdAyE~(z(HQ_EnS3oLtsMiqS$7u)NSkQIWR|mS{(nwnco! z`;0GiQN$fA1C@xX^$l9OebaG}Xg#jVNC03r#W=Vb5e2FDj%=E!A;Q@qw;8l=4R|10%3Tv7_d2`^v=+&T)c5Z z7#>QZbb4(Dp(9e+I?e2X)k}Dikd-r<6dK6%R78hj`u>Wt2VNQPJ?t@c?w&||MnX|G zW$Az)e0!_^gdSqJ5DvF4IB|K#Rnh@#d{SsoYIfu|oYET+pgoQcq> zyGfv^_B-j_VL;*SBY-!7Uic=h7hvHO#)s~6!tW#CTZlOiHgIDljD6VjOo$r}Ca_V? z{BpIA;D>?YAHQ;E-8WP}4?VxX^gOzZ>UnEJ7AalsPR> z%&Nt#;n-hw^dH;d_3IbAEq=9QV1-6ShlaiydP(ysP%7Q~XmTVn=OX-Yp%@_+pv#zz z@OYxZahSB8Jqy$6>vPZ<(q5%k=QH2CkTu~wt4}!=Wg>wOwqyAnu%qcPGWDZZ>}k66^)lh90pN; zz8NR)%KG+7Z9it6 zcRgOq$4=|B2;blmvDm{seGd=T#qdTx5SAow&r(}hF1u#HTm{lsAuY$!L&vhs!Kv~oHj&3AEd$#AyUk z5=I!(%z3c4!^(j`{xfmf9(F~ ztb}a)Ub@W;yk3ib_KVz-l(lF-JCQ8bM^*e$I!=^EcF@d;%jL$FeF1o_MeFsV^;+~= zFLfmRBYWXQ08WKSwre`j)Gm;tW>m4|?DC2H#^I^u?r-f3z4PTM?g_g#F*GYfOuY=rr$z?#$ zxWF2)2Br@W1& zJRzqBI`jNxh7avIh#xm}OS6l+l_E6Pt#LoGjK3x8U`{Mq1ZmFzy13g`y-enmNf0x zE59MJ0A_M$f@4OY_eb!L-vUKkm4r|@F6(fTUg}WT(k3=%N?}NznH3v{f$koIa2ly$ zCpbNl%Nq{*%zKlpF#319oF>8*PIeARqdq2xy_6xz6ImX%chorKwc^ZK0%B?&>AUn} z&Up5dg{tw6+ULZ?!81cRg`bx{0E1KBPWDW(F#2%I!#}fH(tvKa@<>7QHI+kS2hcgmU=`HC1_tc)2CJ-&Cx~i*y zt^{^P#@w%%=0^}1N&tfGARZ;hkQxxH710SXH=icKiaQLOZ8eihcG>7e_)-fBM}mlG zlVsmJq%itg5u4#8kbx)$mWUsx(#RQ-nm@*o%jn@Ikp&}r`6D4W$r7E2Yr`wWOu{Rb z5`J|UKPDy_=VdZ6y?h3TIgVsa!^~SLXTRYU&pfES{6=kg4XZ!p4$QEtTauQl()J6G5CIwKM5uhW@WFEG6Adj!kZ zXFH}u^0-$&87gKa{>0{MZ_i?NJYQ=Og)^~e^CH~D9k^&Zu#B2{yrf(RMP;2*mSg!+ zt#FofMgnOymp0)^P+buVB~80ip%MT;kXCq(GhfOdG>FjX$MAghnd+jefrYT%u7q;7 zq0VgFN13NlS1dC%-si2XE-6!{wc?J{GfMb?>u@6IT)%$|7+mmuD;Jkn5}92=lKdvw z{~v9}ZV`tPAluI8MjrAhUuPux%tY-^FueZ3nC;iUI}u;kK#lp|;uAO%ff!QG=G>>N zn$})Iv3M@|{_yY0% zZfZ+2TyV6_fzEsFfa++Roimq^%atM>V>&9rwgXv83rQ^TK@pGEPPVXj=+JJhXUFDK z(P3&LS>Y_GAx+^(#0aCm7q3rR!4-Ce8#{Lhb8TZ80q{1sx64Gh0j~CVa~|M%%eG@$ zvm!L&18S>#t)=-F6PshQ;zME&J&)Ea57}nj9g;wce5pesOg6WX25xNJwicoTFz`Xj zd}nvCicolQ!#wT_CbUW177K9oQWUEt0){^P~OuNBLKO1b7(Zl96(^M`)_{GmTKBk?@`k;AQZ*}k0D zYZ1}QHfe8geiBC^=KOd^P;@yf!9Xe!2AmUk-5#Jp@q;`Mq(x=0V5EpT{5&VuGq z)h>=pn3#NU!<9xJR#BH~hF&RhfU1H&0*z1_bp)Ant+(VZvjGJBKrzyOtL^?IH1o+D zLkkH1##>kqx948!7@mw-psV8=EbPOH2%Y14CCe?NtwZsl%RBEAfz0CI@1TvcvD$eN zzw6@9x8+ULD!O0u+tx=D{MTF`OvR3ao}RA{XKkMd>8o-q#We|9OsJpkReY}P^EJ`` zX9fUpK##we;HU!^`v0`?YAfq^I6U0rJnaDk!o`+GQhZ-qdXPfhT%UDAnh$tSc9ofc zL3Zoxy=hL#^yMVZPekWs!E>dZ0k{IpC2j9;_RZF2HzCV9xVcWt;$S5W2aVx}G}z-7gbmG2$liCe5@X#T-U)W~gx|3MX)h+> zXben~X~3IY;{WxkefSA09=bckJcR!30-IwZ`WAK(7Cx!lRh0A*kb%v{{k`eW zZ)PT#I?atuIKWO&p#MARP_?%T3~A~dSVq}-RxVf|xvi(H?RFp7V1n+khr!M(6@wCp zC9aeMo7{eHuNzJ!kaB!S;%liK@FaTQ<*e=O7SrU5erg>WEB^SYJ3n8=81%RztWlBF z1ZZ+5tq2kM2~KkUfKXVZ;HfwiQccku)uR}#BGC=q`NHcbHNu%`Z`}+k#I!flVxi5t zKOsNdF%+OkBFh!rrgfi(U`alwJYlK>y|J900Z!S18=ha={F?_WxXZ%8D6Nc2Ng%ZXz=83e&fmHFmE zQfVR~mwnYA9s_%mQD`s~{bosGpn{q~X$&W3{*a@gzl)F9)f8#_fM zXIv0+DofmtFfC~sX|`QM>Pwa{h#e8!Xz*H^^pdTO%s^|W0O`8(`m!EvZ6hgJfUCSDe|I= z-$6GEIX(heR{D6&7W8^d9{zm9j2lMqcuUS_@!*z z?p9ALCr9a1psT{Jb=6rLbRu+dM=Vz=PKAFwOP|rG3Nu(J45U1H#Pe&#Za6z2-rw7d zn?*u3rdu%vg3w}Bx=0=k% zAP?>>w3p3V_-i+VT=DyUmC{$P$ovH;YCcjn!R%is$yv3*Httx7!@Ni+oCrKBQ@)i# z$K_&a0^+cKEXN?2JsTK(S-d%_oHoEawVXJ;%M7Psk(M{JnmvG$$LZgf!s*8Ay&rn^ zWAC%1Y)=Z0q(y&%!HnYd0{l|tpBwb(fNOozozX5+~i0fr4$FjNxFyo>H%~9%QClYO^uMh zXj5&S_vB#&9*t6-j#C@Eq$w)hHB+tY->x$!zkmHjVkx(L`x(klo8bF(thVSd92Mm2 zl%}7Zh`)sk06IY^WfkT1DeI+-)7lve1JmJtW!`Vh?gRR;Kka^)x9=3vTt}CG9(ikq znoFnF&l!n8gd0ik0SM)GNpU0Weu5JcT`B+5g^FqH#8VXXk;egSpIM^P=|j1$G&)Xw z`q>Lp!?rF3B0J?Me?l>hRWz=ZWmZ;>!f)CzB41`C9CU#bT}X(`Y4GDy-GOjJ$ItoS zwoie4c}T;>c?~N4M2ez=$rMZOEg*s^@oiv=)TJ#xJK=b-P8YI|)rmS0@p}2#K8I6* zeV0A?<|sKxMLh*tp#ves2`0@rJ`RYoxWalJXlHxh)Yz{-n z^uL5F^uwLwPe9&+c%-^5^ZeQc5K0Gnto~dFK~z-^nzLo^0fQj9Dhv1!3~#oG--N!y#5Y1J-@vSTLV^`a$0 zON3sc-zsn%MLWpWwc9B@i#PGZ6dM7J6PQ*qN?}@G+TnET?gdw%39=!~P+m1SKbSnt z*mLq7bvLyaJVm~_&|<~jGmBB{uS%mk18mIbvuSx(nxyX3p3RJss}qsVE8dl^)1VE2 zgQarTL8z8j^Q4m!JYzpSV+?4|g(vhmB4kuzr&V;)J&e5F_VA2KTT+os>dTiCqPQy? zw~tDkE;U0c4WRE%>%D-BBj6;4qmPAAieqAYRw~Ipz8Non6Z_3|vtLhx^<5pKSrD=* zx~BDI4_z@1Dx}lMZHdTP1|QE!hlhrb`t)8+sNfNk`(-ww*F*36tk?O$aCb6qc&JW; z{;4#Gz?g2fFS*B(KDSRWOFTQ{&%O4cq5pn$WpljvD=*@|!SP1mmAiH2cIb9Q zyUy7V!G{^PDEfVS)24w;R59HLW9qTeBfymQGnCXG@zVoNlBMpj1K@b?i6L7CcuO9_CUvMik>fDZ~zBu`nM4CwnLq4iB5AO4t%&VB>NbF z-FpYT(brP@J=U7rD3X5&Ym++?b!1m!MnVb^rI&gdA9x9+Fz9^G#I!_WGdkBlO2{@F zA+J{+^$N$rdc8tsAeuAe?ewn(`)1$;n~YrPp)!&t2x^PmN`vPx4zmxDoG`0UH!O)t zL-|*1dRYJF#`y^74L%nsv{vl-=YA7eB;%HoXV1%X{6|=!{7v3NKE-V4gsx4 zWoDkqaCUp&`5Nh?8&PE$frlGU);uUUD<4Pf#M9t}bQsb&tM`D<47ilZrk~jOzCN3mpstH-7gb zb17#!6ZrOxfm5!7dm?UHSQN$|;Gxq6j(|_}pM7P^2x-`~D@3u#y&wXO&l;+_;rr{a zvLs1C#20)qbtKQN$jfDauWGLEMt|r?=#9_thbEl;)1+(Tze=btlgv3_+SFs-fToErzlcmiXNJ?w_`^Vkf+qx%AOj;!7`<>y*f6T)E#D-rD& z9hTxuj7$J|i$Vl?h?yEmV~?Q^d`Z_Kgh1i>+2r(kY5en$80-T5q#pppE>}n5wO%Ak zXxV8b%rET7s#FzGP z-Yg7hyZ~>=zbE2G<*}~@^Ki@RhUgakehQld>&8Ah6K}3y75^7`q|lwd+u`(VbRxh& z@ueC7X05BV;V$=X@*DZEroPEJ7(2@$;v;M4qw9=E2qvadugf(}_|d?r;?nsdM|uaT zpJ}WuPTPTRk;;$X8cJWlcq^xqS8ulrA?A1erKND|6Y=)`mF0*~C5_JS|FT4WGi&A7 zK<_AaQrw#<(t!Kx-ur-7H2TAtz*=I%5|r7Qz_8Ky2-m+|f0eK6oNrm= zpPUFN*v+cHsP`&|Le%iRJ<}yA1wYYK@mpe$rKEUU&ZHmx#YiUzCdyzm0AR1>tP^bg z1G~njalPeD*lG?3r3F#XS)Joim@L5Wnb@Xb&p}QeaKj(m$VY0rc z(vm2TS99UoL{oN9iSPCvG3kgbx0e)T3SzDbJYQ3e?l+vY^+w*lp z5zXY7S+hMmz8tR9dl;r^OcE(Q`_ejGdX$c6?UBL{;XG`(r;|{e3TgW(aK_DNBo^h2 z1laBAP!W-|o<=c+%ZxCA3+3`l+&W&maCJQ-rqoY+M=aZ^P3qLVgj~&;W8h!liICi_ z$lI(5o6yD?h+cm1jwHWp3a6=~iC(yVaxvL>JOXk!bV)!o}!1`;T{tNI;C%aTFQo6fBS}^sR@Ztx|CKtvsB_C%Pl#K1ga4<*Iue{A5m+dw^bgb@@D4&MiU%r~;p4fl1>=o`P~ef+Y9`LO*6?sp z06xoEaX^$tMl_m6LtI2?2@{d+e_%@GuLaq!ZLqeqvSCIdD@U-6m?gjVY_k#WOdO5` zGc9VcQZo1yS4a4V(cnwoCPJcj2+G;Oa52*m1|DwqggQjx`vJ_lw_`t#8l7IpqcbLZ zOPQG=A^pC@OUq=o?_03I@ujdSvN+RCGP9R)G?SvTDPMbg;!=+H)sS(qb5z)rcY=P? zDKqF!!%~DaD%na01`iA6Y=oUcw$o^LUR2ncWPP#@nregzou(5kK<7l5I6bBu#-JFS@&-H1FEms|eOB@liI=(a7tWV*~ z*7G|1gsZ!jn6@}oaGycx0$8H-bWkZ|!*w=dvK%hgH!~4)+7s%@m_vAbuCyQ2P*6KU z@;f?T!2j<0XT$Xv{5S{uP`BnREfplB!-?>uV|=UcudWX`>P|q_W6&n9DT={2@zh@e z^xvI`&v9~jI-+iZzobXWe}`czwijQkYBG*m|CityUu4R_^C?Sf-35j;(JBn-K}H%J zkdvDIY!6X;!yQU1ev${BZn{l@cy-y4%g6)on3f^eq|`^dgn zE_R$9%=#C!>%EorvvDxznMw0jTE0M-VH(ihSJ=TlfQbWOO8qN9QGE z7_NQuH&U!f0ItglKgs65y|g(3&)lA+CJx95!qVQut2aO<-G8#IZr8u&!}=$VOuXOn z{Z~ihel?nwF224*nEjAK{CpKZuygu`dzgxM#Rm)F01=Vy+*) zz!6ReyJ29Jn#7y>Qo6vpR6K(eVjhd=3ZS=fD zSeRBVoGqJ{5RiCH$X-WlbtoOPmPB$RUwk3k`^c!iJ2$;RADzj~MTSujpoeh;qpT>5 zQ%NO^5i2}^Q{p;s!uh5KS{W@r@?{7B=5WAp7VJjPeB6(POh^8snP7x?U&m~O z!KbrM9ABw^$%}lUXWHRXpZ(_sI~bD3h)*yxII(D;I}L{uQI|DITNW2p9$1@cACaKrDB+F!kqGk<@f9L|}CPkWJ!)!Gkr0i?arAA&$b zvo7tN+)5U$ZSsTTaqFgoQbLjTo%vpf|C1my#>OpoCN7`CVGx;@VvRQ zj~bwZLYVa@*Z2QGyR~<&i2xpu`K}w?1_GNW%eCxMv-jdl*!4pfECC0=(DD}gZz{~= zdNEnC(I)DXQaHpN0-ORTXfq)F@L0f9*?IL`=#mKaR0Mig*kGuE)Xdy(=@AG{UyzQYG%KY(PQ1 zP-hBz7)c5oS!q5;P(72xb_=@a#H@pz4er%j+H}1PKN~a zt8r}yE9Dv*FZBK+m(GLX1-c%&LSZX}lU%n#^ZJo5DWy0kjI8inlW}5cL;$I7G{vbRW}PJD@v4 ze_#Jt#M1#qrNZeuk}r*j2$RF%b0*T9NKmvFF+yFEJS^SGZzQ|7m_PYG@klF zlh;*s{iPvG#CbB2R~QB%`5)JX6oM(V2{7%2*_{BAC_9d4jQgmcZrbG{)Ew`b8Wf@# z5ZaClbsYLZJF~8%P611#_>%Z&S2I%kNDxSp=wdL|h14isX8bPu$5s!8QJjK)arRv` zWHLUSE#`3id@0a!!^*x9kRJZZ{87Hfp-f|Jm~Vu4LX|{=z LON)z5h^!c|ZwW1V zDagsp#KyPt|an%AZZ{s zvij?Pw^;iOx}4;QW%@p|bjA4@bqi0nitbtWD-olN%~N$&FyNiim9SPArT zfCqGvFVL_`=OKUG5L@XYjXfeX)&Yh|fz^_d^$tDLmv`JK@1zTd7C%Ne|p!MrX|bwR(M;N*r+sfNf#$l2gr0JFhiMu(Vj z#-z>!Iuz!zq@%%Ah?l;DcWThA;z)$yk6F5=)WVm2Ee)CKwlbc zr>@nw?2AwZMlie0mtFGs7|9*>36e@nlESmWzMp7>nNCo@N|Jf8bA(g zg$POc08Ns~Ir4W9+EBMUi(ZD)HR@+4%fvS|&O-Yq9N((9DaO z*3$1pJT?=ch}lHj^Kr7W2_-LD!jYv|x|dF%%|yIj;Y{dKznv|E840g{$HyJvl(H?w zfJi}qTDS=(r9w;AC~=)9*J4rHp-mi{9x3=t6$1qr!GA7W2tFitE_`chLTVQ_zvq)y#wUVUNPXcnEWA z=144qQ23HXL#DNdki!8301`|wS2BKVuHVahCuFL>s7rr0=iu%{V0z0_4mi49T0(qB z!vDCl;FU7OWz`aQ(0k-oVVOQ{1W^$FhR)xk0|^(n8#Q_B&{Ocjg$6=-*oHQm{%b9u+o1rRONLGIB zyDLwJiJ9qTaqIQ6lUB|{Rvq^82934A1N41lV-lXf#gPT|=dLjDZvD`($}KnEYf;6* zv0Gu_CHzF-@N!P@$5YC_#Peji2J_s z%QeXd51o<<Nb@{2A#At zZ+&TmyM$fy5XA>UIma zrtkIXLvv>f;QC=^Xdi6EFk^9Xx((flC@SBFGXk>yBeVfVzy>oS zVy1Uo{@4$U+&=0M7r+@^fnW|uMBCBVT27swb!V;8>I(; z0tR8WJp*-_L!$^LB3|lK5R)#oP-jeHxk{eSLqawJ?Z?CVw03@=&S!6M4@IAQEo&|P z3%*ooivvJ!%Oc`kXy6Ey=5-Sx4c6(3ff1w0L9`t82JyL~lniq-CgK=ND7W(ureE&i zIgM8YH zd=doYt}`kn#b8wKN~4f|2ym0NrN<+{!y67)4yrSEiTS|f$1hWpZ{ zQAg9zUe{}`(}Kq9bIJ zuj*Ylnp$}cUZlgmq>Een5l(Nc4@egK(w`v?ob6MNPi5C|(h$}5l?+HLh!5ALI6x;* zkYP`t;K{N0>SCLbD8%nZm7G=g3Z&lOAKBc)0ziWH&+;V9UUhyeXvh2>Yl@uOMLQ>b`^Y+_;& z8acFuWHHHRdLGWDPIky{j`Z5MKTHcSEjQy#aOJlxLYAT=0@xVa%`F^_<)Gzoo~}v{ z4d*J%{eyXZjeV1n75_5PHF6qqEQI~L1CCpEpo4qK8|U8?ED>AEYZzL{dP#dfzhOGPWvN>>-PNc~>D2xGjN4Xl#*?b8Z1eFc4ghpEn6QYh3kTp0{ z6tJ;79qI6Nv*TzN)SD_(&Uh%#pHB%%Gj80LDDpXZ&GlwzJH#DRvGdykN)yuZCh;%Kq7DV5 zMuUg-Hw)c;~GNv4CO#Cfl2C-vIH`Nc!32)nLVK`ny z6q`3!3iakhkU0=)bggte2FF52>34qJ8M-={2m6wt57{o&GR3#e_ps=4F8j_z3X*Oj*hjRC zrUM8JTbs5!l1}%)ALoTf)oFO~f-;FV?Tqt2G8j|PxsrjqQ=Zt&gXf9bfTvvndY=-e zWk{nq+9dj+K<-Al_VA{ycwpGr8T?L4Kkc_!X=C#?Tywl5CXz)&FCu;s@r(1fiRjVy z!kacLbXy+#B}_uw_{)FLT9m4t;SafEeZTyJC-z&U8+rWBb{A3joj`dTJ}L~+!C*!p zpA@A-F25O$fzDpTGE!zq9EqvrT51?ZLkgiVJh0qZ+sJ@B8A9{*>HU!6qHufkyOO6O zJ{_ty1>M1gP;Iu^fBce?UDBnV?Z&J_rS=-KQNY6;u6!C)k z!T3Q~Nb-F1D(?a(MawptMZ{P6n;++zud4f#FOCcN$UdDKQjp4D4!J`t#3ozfOmf2B zN;w*wa%^szAg*%1$QWw)t64zCdwWq2o%M>PccVPYE_RX=Q!Rrj2m3r+4A9nX#UU7J zfKsjZv_gQ(DtBC75rHGqZA7kRc|NS;q%vxKW%}D_+;Od_b6w%{9Gs0Il+%)Vnsy|x ztzGtqy$$!&Gc<%7{9K;k>crQc-;4BOd*N(o`HsXy=h4_8+S;YHeq%sB^LIih|H44s zB=H4eJ;Jk`p=$?raVs{j3(C&LI2*<6oOc&rp5FF<{&WOnUBD5b?r0d|CIax>f$jt z!VoxX?KyB)byAk?{Z?tibI`ODhdE?N zwBtLhk918b3ne2yl+){TzNrTc;H>ZTuSiz2KZw;%Nq$$Qn?`xcLoE5$-qx}La>yEg zK9UI*66p#(l=6`FKo7tG!3hJ%gce`JRlZ;wr|?lvds!?-w3~{phO*bog7^Yi4M)#n za_2|P8#=buA7KX{s!Z6RUas^Yj`s*B^@M%p;m|c!*{X5k5$_tc{kQ>O>|%Rh0Zr{Z57h3Di;;Zlt5Rx)kCu1Hw-i($i-) z2|YeyxHBaXCmB*ka{9#LV=p$Lf2Mc#U56 z+Cd|FGLMQj6v%rCt)(OO%sY&m-aqL%`e`D`ynauClXwm~MVb}SBW+ph=cTZ!W3^+S zO6gPJy>6!YM%x_W=UDa!s913Jz^&&*?Ti&9v8$;hs$Mw z{~p@>1ikO|C~d7x^4df%I%W~C*wqJeQ^=0@nI{r zu-_LGt%qc7B8PKrHLm=bx3)pHIqExq>mfWz$0-etx1hS_wNed39tj45b?$#myZS~K2aW}+o}{4qb2vv808meJpOh?m&u06XdVg|saC z%q!`7!OY&W<%5g^V>cvzMlK%Rk%1wtH2jj2o8{*|H{pySgp!~bda>?>;iu0rvrTTe zfl()E%pHB)TF(c}XkZW+7nlp0a0&p+!Z(ys*lo@JDRrQ%vGOGJ@X#*}+@r}i-jT## z;d8e~A_m^NZ8ySX*a2}|@6X*215cK}CK1xBl zX}>nCC4Xq|NBflt{5LJ{aVNst$Q%ymCO4uhD+>F5T%o;4X9AW}1&44$21moAqPL!> z9fmt?I42z(-)%~eh~yp&mIkRv$ zy_AiMa8rq_c<@1w;9q84mWjsIdcpw;M+j#}aNh>O+I6Qm8(~X>ahC95Pk@H(G0|I8jPalXgg;LAonhJ;(`^p zBMhxdgi9PY*H0`d7cH)wBpE9*IO4NtsY}eqiibEM@{dfFl)Yaf+-($SOPSp_dCHk5 z9RQ)?fc9B!ue1~NHQmQUb=)qlWkrw8=->e5ob=yk#y1}Jm^TIMXN1LCjyaxM&7ARofw1h zL$D_%()h~GKiEFNNCvN-?Wte{-f4J;U`mC-@!pAJ+Z3|Oc_v$Eeb&ph&F-zo(S6Ki z^j)4LG7%wp!Iyx2zkqwYOJ^aT7@5KDVA_sXPNOl~tjbPLg4)r?Ig!)aO&|A@|*J+$eUe(6^p`rQxxJ`er= z{_3p6W2Yn$)gP;K@t7!~M<)l#>K_LfYx*0XbT(g3`At>~fvP;k~56OeprvdoyAzDQv6L5<2mlZ~FUE zb}z9C9|a>xWL)d%i4joXkvHX}hcIHxjJorx_^@X@x}2zTIRJw)rVyc9EQ>KMBd zVZ60$?-ITP!;6`q|3sJ1%sI5o)5nc>on31STp==6e38hyJv;>fth;eC?P^^>3r3wgR zaUyur!;j5A5YZC-;F>LEdR8(o$Iv)7wkpVo<0RfbTi_!_)i^@$JdMsY@B{>m5LOqR zi*YSMVP*#0i#rU^+ZGmROTwnOcu}4(1ZXIzA!0j*(qRMv6wmoDPPbW`p7qeP9wH)I zMyNUy0r(Avf{9p-%?+amBFI3k-cW*rbirjNFk&Cg3n4||e}R+R!kfhQYgq5uNSe|v zm(7DIkQ~!6g=&;jbWr@MNn366X40a(3 z<$|%S!c20efwQc0J*v^4RZtxXTdu?p{mL)>kze|=f9cPozvp>qZ=q)kbXfKz`%%7& zVDw(;PMwKg@_jwJ9LZ+Qz==R-LPu_Vsf8Iz=1e^Nn?l?FIZcE#MX3sk=AchD!EHSe zACRQxK@P1;rC z53(=hX7YkYOUZTOZ+L&bn)`e9CO8Oc}}`UJ(T!`@`VUTD6ub# zw2Znd#7bu=qeAwY>{_f&1YtUJCi-l|ZoHxng&Z>yb(U=@&oSw7+skJrB$qWAZP!ld zSC6~(ObS~j?%1HxV~E?vA4oeTKgv$RFeY}=D&9&BuE}-%7t7HNjL*x7I5x$oPJuW<#nAaXp^M8 zya=nba}f4EK#j0xBO3nb;Q2ITi^-pIz5$A2&uid8jktio@1-lf;sQ057~EXtbAO3OXDLnC4_6dTcq8l!vV#ssVlXi4%t*qeM8`2QoOmaaSl~wF zUzW~ML~q|pe3j0ZeBewUKa0l+p6GX~-m+)UOn$x2d=gN|WbXs5Z_*jN1Q!C%Y3;NIdy^HsH zQbc#XVebg=UD6c=#)JuGBYbznB0nKw1P6YIC#VqxW{HmX`AyVLYM8TBb+XKLkNOQ z*XKMy0@G>V#%#oD`y`xZZLip!j+4KLS!b{PL!jnR`0Sco9SIOB1ub$$7rZ(-^|B;& zIRkCrU{tBG)x+(6&@5BzM>LqcATprca#92cv!#T7IyD`zCuTJ)@!{T4m^%D%9HhR0?sbXn6T z`q{dHev2OYi~A(Nc=wr!P{v4SO@W1J0(dC$*65}1mCKp3%mepGz)xbkdG1A$C-zMQ zaGdy#K?viq(&x@0(%=j};S9SnY)UbmV}`o1&imry&hF)Ipn0dc^%ay0nSn z@PqPu={^WvOuQcD$@SRY2$)S2bKYeK9tdzYU4@pR*$jUQ-cQWTv;k#dT!=Ce=o_nQ z$2t$axft4zy5LUhr9E8ZCZ3;Z_U|sNzE~KN_s%N?1~l%;d$5)fVUWkT zlwO}xHotcy)Y!y9;OSQYZdc*quqn;niUAid-*J-Vc0)Zd1om2yG7M#K<_dmf3cE{u zmC5pfT*+C8;aRe@Q!f60wSDP=<2cM*fwFrxdH;vaj4dKRa1}_pr+2?ZGj7SU!~tH5$8bgErS4R>3KIS(6tQ&ZoHZE>id51Y-W!2|fg3jl z1P)pS*;2_}R}iV*h^T`kS76izl3HR}lg-=ptt5X2f&GK)@7DNbxKW$^|=Y3Z&5iR3E7pKL9V0bIu0Lh%2 ziUPnSN5tQ#7GLz>VGkx&u+Zc!?}fRoKqhuEpP{UzuW0EN4Z|p>+$ufgdA498okQ_4 zlwY~BD!8v3x4v=f8}AXHm!0K>J6BH9lHu4u&I1V7!f0R&-G2*tOPwc6E9m3N$8AHf0&I=j z%I`tM9mAW@&m`$3+XVPazL18Z8b3&K62um$Y_`w@xP6aj+R=^UE?Xo^ji&pJ!`EHM zx8E}vU2pAWSbzUfj-1t}Gy>1c;W}t0dB4t`4@dejkZQRu^dng~1`;lq39di@C>ulH z1{ufz03ZNKL_t)1L4%xQM3bp~btaqVgX)R6CiJ?~kIT3r7XVQU8s@uXd%P=9_8y5o zbah8;XI>Uv)*hZpO7{1f`(R#@9JQ{erC8E=__sYP2vGEUN96T6g~s*PfZ1iTioF@< z%=eSdd$qa^|MAg%!d5=*vb&d|2Q`{$?K}#dD4W)SzmiT_}e92B762!G*)Q;4VrjMa#)kg*APS_mVIjbgbE_U>nk;YGYVM_#xrHs z>eCezK=eo`)g!x*qH+X(1bxhvXb&Q!3d<99=a?Bxa3N;7Q=1O~?~xE#ZwBP}FVYZh zDJ4TwdM!RNSh_-y@z2_%14a|p0Hz`2YcNs7(*?YfLW$Ida4e94Mj{Kr9#E*2)IisS zj0++@@pb^Q{Ad$IM%KY>^C%QpX`@R95;8N0Fdlj!p@2k>ga;3};L8L8dRZS^4Q;YA zl%Ot#bt_{xYMV1v5MPl%PQtMS4~%gpbGOTvOb;e}GcsC^HiIkFsyI2(I?`YNE#M&m z0$-*V5k`iAV247Qbq?5=0R*gkBY&whic|+sqCMTz;pM$9-$i;mla9q%#e#^- zCRpFs8}F+J6L*3NUvh(T8zOw=KyCQ=}$6=&gFD4lc} z6}AB^yPstG18tOqLVH2bu9o{h{ry8~N16P$WjN=?`EorEFEn0sedhoy=}q?&^JX0m z88!Vqmp1I(DTru6gPeJ;ZVxqkBW~z*1J`Xq#BKT_!$$}3FhPGOmRuH@nDcEtlGodN zCEn&kB9LHzyxDufW}_B*6uG5eGay^Zwb`)Ji=+H5WvoU&Ys5pL(>*<%pFD^vo& zTmuMO=wwnL@tHf)^(}00H0nqs!Q~>qzcz%j%r?B(sEedX+;2eytZoB{CC6*n`4U9< zzbTPo1s7-kwUp=6bG@i|#71Ptin$R=A`T~9Y&s*z0?#;8yV@MI_rw)r#Q}J$ppCzu zkTD_i2Bz4aTRvZ63<0Lt=J^9$yD;8)X7Ef7)6ZMCobq*@!QVjLDbN72&dj&0>&K|wKKHQJ`&+zQT5ZjJ``mzo zKpkSv#)p&yV6z>z9hidy2%vf>R!1NkzmV^2ma`pe+*nT9h-OO=dQZgkAYwZ3^gtrY zFc3z990}@s$Xos%e;2uGy9v@~H?+nIOVZln| z73<;qq;`QqZiT%4^91AtTUNqXxIBnc2JDTNp~A}d$hAf<4c(wH|H(Lm>0}T7v^N`Z5=3bQrVQWcTHJ0gj1R~qkJ>VbSNDBQ`p(5sd801`QWlDmCa6ZhazFhRa>-V^g- zHeMgK@|p6UEHSzB(puK_vS8u9UaqUwbMc-p-1Ck1d|4yHd^PEgLO1`^5Ea{~@~y{F zCnDSH%a?vMu~l;Ai{1dcP7nx(EG#14x$xdnT(xZI=CQnE$I(gngLTxzAam-@ERAxlG7VJlC6!8TB|`4PFaHU%apS~TrmF-o)h zRg1tLMG4()6K5tX#rXH-9YF>YHmp!`3jpl#MG$9?;Fa9S%j{Urwx5#i-hQ^<{JVk5aJ+T9~XAf-&f zj9l@mpkzZZ?6`a)>&ek%&j>5ru=V)^1m4=Or`k$4A`^2+IvpjjGzRrZfaXc0Q6NF2 z`j^0#ViJW9$F7vd>aNT=CqiOa(+%}~4Af^^M;t?=c**#pWK5H~`PbAV=xIT33lvB7 zNE}y@qE?GD;8H46=sI&gO7u4XM?kp0V7EBC14zl19{-iQd|NQF$Xgt@PsqQ;mRHpX zCSoYuZNZxba6Um33iwbm8)9)|UYD=Bgq#F#JbYt}3o$RKwcy9Hs@@s{sLhjj19$;= z!h(p0-IJ@6x!J@teDp&;D_9L^3)X=$#vVvyOKt`e2EyLg)rS)1&@VsxGTWQik&?s4 z!4-IAw|^D3w+f=1dZyl#X@h1gKZl!V(0)|mL%{LZ*E(2PZttlcW&P)evK$~8c29~iJ>3uU(pxZ`}Zl{<2-%1UCcGQ;Eja-X~FQsechN5 zNceCk2r77(Z~I&nNXRLWU^_ze*hT^@^*+$CNvrg`?Rse_WRR!n3kYjOnS5zZQ=gKPP4+mvnKX0d%oU0yxY}`s4 zcgA^aD^I--%pL6+(_8`?MXD3ciRy~@Lq@>NH~rgutj2WPTs5_ zg6B*G1`&X_Dp)@y|4EenIl?d^YCRGd!}n?62Psk74Ow!st!_OM=?G(z>xeP;wD6_W z?wcawJrXxC0Zc%r4c*B-2GUq&fyn9af(bSPVMNh^t1O0L41{53`-h< z^2SNnNy%~R@9giF&vo9yX}M0!B!XhWL;DwES_o` zP8TbU#d!ab6&%7^+@Ql7$5g)5TIlub;3s__aW0R!5K^_ zmE?TBJy@&F;;fgzS}YZMtIuJuO&0swZ2)9IuYob{Y@Dc-Vs1=%`dkT!Ltn`cTH}W!LjnLz^&Lz!QXG`Rl_~wE5#B3)5yZ{R>d?nbF$n%s5)XrKrlMhheaGH%Ram@aV7 zI^nvdd-_BjLroo{ZuM|oD0;-uCX?c2vaWx4+*uSpf72YQ5Du}mtgXEhK6cB7$V?x$ zbmN|tpAL90#jr;B8|4H=;3F8eK%z&JWf1mOnbE44frJCF7D(tq{K!$dL*xAcc)3r0 zSGFLcz7sq=o)xIooU%&}8ChGEt!@_haj%27mM74a1if=iA3`>~HQ9oQsXR=@f(oef zO{_=4y1i{J@#~s2^vWlX2W>eBa^95VqY3E2-^KENR<_>ajtJm_e=$~2L+*TK5;7=V z+z*Z`Dl#jluG<5b42*FlO~-X1<^g1AskF;?d?J_#`B-X7ZZ=hs)WjDEt5&w8$Eh`o zE4J8srDyw)KGuN~hz&kTPNvRY38_64Fnkj9tu;4AIZwFWUp{X_YjQL#18YH>tqi6< zxxeYdprK7KK)wL^qrg*vhgvZ4fDLo1iWdObaNEi0uJ%Bf3?;)kw5e9PvH1}f-eY)g zl`pBCbtD@)6=i!4w2ut4I1Fl(o?M*b3XV3O9%#WiQ2HmD{15QXAvL-~_0;XbgIlL^ zo{RJypgR2a5rE0JKc6Afr$d**p5Th}mKx#&^B6GX-Vxc51P?l5^}2U0RuDr~heEhV za9u{3=K1I~Fg%dRo{0IzJzn+pQ(}T)WLxRb>=dzp|CJ31t9!$6l6ow3amL-jaCR~7{onc=q+pko!k5pJl zl6VecLBzZYkH`~!6Ie~eMHUGD}m*^Ag9ra?GupQ)CgeiD_{BW5S^Nn zhNpyc;T4@YaEQsRk`q}Yco+fPE^Wh8a#$0OdDrSC!WceJ;&Ml0AkYhv%BBIl%Jt#b?J$f{slkC^GFx(vE@K*)haZzv3)N;D*1Gp*C6k}ed+rM-}%V4J?xd6Sp*#-eZJme#8Oe>#Hx zbiMjY!b7dMsg-Ll;JL`3?HcF1>p3-SGv7AZnkiQr!GzZ@18~wQmWL*X&Bv~Gx>rRA z%dGym?zPHP0;@?%OedHzx`cWpMg|caOprgJ)^~Mv3=D5P?ATW5I_tFJUeqA=$L)bc zEO$Ah)s`wKOcW-LC*D_X3MZ-A!(kiK*}FP53z_4$)Mk~7&$UQkc~j-?dao-}I7mxB z<;fpDEt8kZ4K`pP0jux9#5^xNHZoQKVTNiZp$&kSfm*xZOn?;;P}Fmw4Bo;&6?zlk zm^AMMfcWIpSQd78tL^ZiBE#3}|MZzx1PnC%CyXu}R1096wgGwp^O9V>X-EOiw9$Uf zo{8X*2N4*d#RIh*tBIS_2OHe@9(HC3u3wjb2FBNbe2IO0&IX(YP$Vs6 z+C5bqdjh)ctDEClD2C@ZBfo@PxbpkXta`1LHk#-52J40kO3B5L~|=xPDz2UjrlL z_X!I+9#KrqkBB#V3`MN9Q0gjK&L)h}(&Tb)CMfPN4*vt0*1D2eFgwBioHu}lxUQ8E z?zF953S{?b*jO){GNRzRwaY5&q5Pk!7FnGi+wsVH{I_9IOTf_1bWJNp7Vff(R&VW> z=kk93#Sl{Q?)bz9-xdI*xX|X`{aDROiEjsJ1u%%?VP$=_lr|?{jg;*Baj#dRJrS~5xPJ*6Da;V z1gW{g5lnD_-H=5kb-Izz!;J1M!QH>$W@?TKzLp zjq}3i`L`a4?R{!75pm-?oL_YvXI13b={eP}WA6u7Fb^b#pH(b)(91dylGd?fDeeED zgL;!RTJEFO-iaLmQzUyatmPOMR1gEw?u38v>!5w?Wf4QKB!;_Dkj1(cb{;4NtQPnJ z(%FLU;N5~$>V+8b`y`-Ug^b`N(#r9L989DvD=@C2Z#A&*t0Rp|pl|qU zYzj=VVLMZ7DcIw)Xnut4IMbP)FROev6ny3O;c9%tD80W#?M_i*Y3 zHiX!=DwtogxSR-c#3kQBnV%gyj94?0wE0c0ajwVTj}zEinOusp+Whs<)0YIEKQ79L zR2RNR(H5V?4KWDSkou(W%FcelxCh2taJ>igzM%6_Kt((t{_X)-JiwIJg1jj-I7 zi8Dw5$ORj9FvIUg{#BqfKk7iAf@rfn0`c>=e4^`8$WHoHjld$ILehdxCEo|z623e+pz9OT-jhgA z)}Dxwfy8(W8*y?8O~|&SQfwL91cv%R&5zexeXI_T`}U<3VXey9y&hnPq)5U-VQ0Op zS0P~e&-X!an!~vS7%i=-KI|fgHwC{h zWNS@)B%FAZKYKE?CgyPyDuJ{H*vO&TJ{De&A^AS4M(?U@1onF1Q{j634s^ zN$|XvHIdCg1+dc7)C=xVK`WeSE@$dRTVxB}2z{fojh1vB0Z&eA*Sy=Ue#lLx>5gyB zD`*2M*GiN1;P)f&AA&K(#%x|_K3Fo)AB zqdx~QhTwt)5RYFM?)Ss?51CIu;OUN{5uc9r{80ImJq6P7$PirrJS>>_=V7h7@%`6@ z>+1p!@fsdjsSaqY*tBK+cW1kolbu<=J|3Uw@t<4O|EI@J2R(fIdFejEnC`Q-=jHD} z20(8#Bfadlswe-qR8KW5!0e?b5ZC7eE}+`)>!b!jRbW2d_1F;S`&pv`uCEKv|NVu> zKMy?qiQb7TTRyD;aNru3`vX8O#k|EAxv05wd~UKyx)64|U3YG5?7>psXk@5{I<$0w zCGD2M9#F6;X59=stegnTN?d=k@%;5*kH430&f~+OgircyO5u>cR^94)FHO;@H!wFf zI_Yn-CqJ}nvVZx}n~J58Sd)iY$0$F#oNhy#mUj~$ryL&m9@uUzQ@_Z130=2)8AzN0 z3c>Zba6K@ zfS|)#N>wm4mj0}XrW;)XG{7hQVqoCHP`~zdurU|Y&46yjN3xJ#>R#`Si2I~{>UCRs zBm5`MxU&u z!<0nelt9Q=BDw}H^+DwtyLU%-nx)72M4ia)v|foaGF%RKG(1NFrIWEqTwEu`QwODt zLr`25!1NX*^;T#hC&C&8awx%f|2>v0RW-$%l@C;LjSJ(tj80d~lZg2zrVAqj8@0gH zjZoZgD#>^z@2ktZl}S|TJ|liVvy($hXwRT*O!Y>Pkt~|Xk`(b8Fc9Fq5_4J)!kA*K zDqXQ^mJjRlp-nl@M{Uo9FyJv^{qpm0y5_1_qk1Areg?*^m|~k+&R<_{Crm!C>%!~T z3-5p4c>j45xrjzbfBnIUuO6)7P^qC!UynSG`2Ka_`t{g)L3u?nogec3sng{*nr%D? z7=Kx_)zi%n&;CC@J_8`TUY+pYj_>P!x>|QMKGSb~uMFM_7EbZllErf9@mt~(3MLZt zwwClBRHR>=iustB&x!kb*otD$FTB6rxPQGdUw2OIyq*^x|LcjzKTi)P>{>2(AOXzx z1NZyJeZO(PZx7zphTl$2-Oloo50;<{1rtWA06ix=MjS~~R3NtOLp{?22ReuG`v3w% zr@_w$XUS&n{H*%*ma)^br$dkO!Y{8@Io@lj^=xB%-o0=V7XWc&(2$hKna`0mRe+nVKM$flOO^Drl>MF&%VqAmI@UcZX&W;n$fQ zVVnlOg6IU`E1>AkwF^l2fV$>9iq-6Fde{JP-5o3*ojKj}0Ahq)vxK@SE3Pfh6r?cm&U{L3_1vqQSrKrY|&IYP6y*r$+E?DELWR_Dr-?g zoP>KMB!gW9zW}|uA(c(@jk0l3(Az!jMs=yag2Iz&Y2&*3Lwum(K?<-(xrmbqN!X( z%WPqxmA*n(ASNd=Eogs!!8^JH*ER5XUikX+h4<^m{pU>;XRo#pwP_}<@u+#kjh&s&v zT%K?1f4H}5HT5?&LmkUs>;>n)YTK4@b<-ugxWqq>*M_J~wEoJ|Z+EEtC z7qmLlTNThQK}0k%waB5e-_u&k+sbv|b(5h}ed~Vnxg=MmkJ9+f0cZ;(IE}Rq0^+yO z_g&UM)mQTON-Y0MrOQJY#WADx9_YPzo#BgNw0tCvoA4TaC-!T$K$0Dmqs5Bso=pGrv0tdms<$;8# z&kyi1E)r#k;S)-UHh)P1yBbaskP>+RL&m}71ZlvUQhz>jvk&1XsYNOn-j42sT7;Kf zQvO|?hibh7I@HEdr!o*A&xn<-Gl-&=sYrV%QgojU6_~fMkw=lYM0x!=?%^n7Nb@8b z{n!Z5uH5bYZhe)mEtm-YcwnIlWuuj?2XPkvWg?=I_`Pvg*K2=fhLb}Yk?bWH!#8uR z)v$8hqSvj0ohWygj@^2)(8bcPVYzC8b-P}V6$G!&M*7z*i5tgLOWT$O$qs|!F^Bg& zSm4$J2yLY8t;!__wI7G~t_=<#C;;_$09z7v%;=Sn3?i<_1NYa{T1wv&_j`8Uw`-!t z=IPr*ABa*QVmybn5IqOR!-9wLsC!Jax%E!;JQ_gxHwW>(0gw~;I97`VkFJU_n#rpS@P#|LH%A4|UfFprN z2O&BY`m{h|J}2ha#C+YDuZj7-G4ELbNxJ54u*d z?3w}rr?@&MQ2@M7O@I%%r5AqL4`N=Ub9)6Y!f`Qz)X~KIV)aEYU^qK2N zvS*^OzVm@Fe;kkdwxvBUwF$QzO~p3cP*kFD2Im+m0cd!W=)iF5Dss*#!uh9cNIY9T z5my8fUT8zj&JT4Aq4nwfIXK@Gz{npJNaQgZQ&|vK#ZeNTJ+mc{;CUGvt`q)3cf5ra zAxwT>YeH8I!wLgT)~fBx5FUgSJf0)^SiPuCMJzZN!vcpPF_Bt#I@0H0J(^>$%1Y*w z<>v3C9Cg{#R>Zs)p|S^O!g+;b3V~S+!WukqDXBFvotoD7cqMj(50J}4$D(CsonE#Y zp-!x3rP9#muqOJwT`#2n*yFSsx}rqVugSRfQr6oGPYE>GXVem}89?m8-PQ*;001BW zNkl4coYvu|&%F^p zDNE_ZPiouLaCu%9JxbTlpo4-5?w$BoMP71mkIGsfwwFjhzJ5=AjitoznY|P9p3wKq z75W5XE5kgllH-TTF{H{64F?%OWFX;nmR8VK(K5knt1*ZPO!uls1N-qpHa2y#uB6vh z?-!d^?nvkvI&omj09 zgxUjpaJJ(rBp-6vQ!Eh+1N_+&5yP5pwa--Zo$Ju1xQugLTJM0M z3Nq`Hz&)cA%}8aa7vlFsy7QZK>?U!Sb)qKwj$Q~0vDF-aT2D=oeya*bcvp|9|O=#sKd zyyq4&E%vrvA2zBSynQ&raGIlAE$V8F@-f5)X3$nJna9{wIuauEovkI+(B0163M&t?RrO=0B-irBa7I5PIK=NS6a;oq* zL^%Bi!cRgXzmq=!IZ%NCUTeTps^j9%cAe0E^+~)oIqc=y(v53MbZ?93 z_1qeBzER(`3SCMTdv((1gPvI#$(FE9r<`Ri?~=%O@3a3e9<8>0p%>SQ{A!<5MCa%o`?z}1cJxBW4%FRN_3InLUwaxw+5X@v^x6w@G=GCPI#4L z#AhL{CS*~dvGhvh90?}m2VAsp13B>}o|Rg=H+mwZerTKo&+A>}|nIf~sP zQ(3n1d0jcMX!jZP77hD7ttAPCdMEOU_&wEbFRf@@^AB3*W-D4Nj9=@PLQ5=?lCAVk z8L9Hxty*3YYU{PH!2~;oPHHO0$*^IetCUgRUC;T*-k|&kTfK^ndKS}VHXKot?Una- zT^yknM;}6`MHZ*~z!0^S%6wsh)YKM92VbLs8O~^;1 zS4*+^q?HSsVd;hOixclYIjiqO;J+W-TAaoDTZ{a6L`4TO->1~vGTr)Fo!Gpu*WA*~ z^2_zDMI8Wa*Wc9O-;kW-q0PbjE{*hOq?>}Ym%IQ#dZZXKan;ZX8SHPozFIBdt^P}0 zbt%XOh+2b6uWZp+wmLTeisk!~)@RuvM8NVwI3UvF8gbm;O|CRM{5Q|IOUDO!5h^Fy z{7gfmT-1mYwuSSQUf%%bd~{we^jvg+3lj3P2G2!8x4BeSem>v`&++LWDz7?Li~0%a zn=nlrbFAcKnjY%VXnQ(VMzTNq##C3i_CSIg*}}KwdrIe}wI<8FM5swqQc&UounKXzml2_OePXn{j9DUluM9>hmvNzNt7XVNNgAHMc7I6$hEVv z*sRMTzcdpdV)?0A3)h>v4%EEbt)P3u*e}nHNHw)i@$bouf-2q zH#%CGapE}FScgHEM^P&A}EApWZ+P{2&SCzM{_4vL%{8bO4 zp!|nhUr{#DOqJwwZC+I*tX%p}N~P(sb9YZ-X%^=vvgHxed8E=CogbvQObs zG9|kH97v!7yX0-pR9aeV&K!vN9Rd%hh9I_8t>J>rk#UZT94v035IPmkVq4ycnn_-5Ml_fWiLEXcSOd;DmTKZ^e8m z<_q?D1IT$2Vw0=y;hUnys31885Zn_Hy%Y~t3d1H^ORQ2N!vTNnN{f410miV%CbqB~ zcFz=O!Zx|HphA54p)5xBM2HV*iV4?FLI(^X6NvH!gIp+!*!(SwAu(sU-XvkM42glf zJmCgTHuX~dHV8O_Hl|XOR=5r`4-Q!^)qy%7P^Sp9XmAGGBFJ9lZ;DeG|6x%D> zTk7_58!e+Oz1~%Q%J;jT6`}fo*{1oo9GcSo(8k{C%kpw6`KIJ?J~FiqHoA3LC<~K{3@W`T)11bMUndUz{IIt@*Df+Pyq{krY8&B7aoAtMy&=_*?#o?l%v7h$Ksd6w%UDJVn+k^sE}6_6=|6 zw9Rm*`X5(3q#}M4gGT@PG19xM@DxpaIscw1P@pA z82A#cwwV-cjMbYd>=hrrywVUrh6fk}0^95^ff6KFY#J&#v?-$=I0uP<(m-z~JPS$N z#Cri~$!j5nZU(H*nTnQ-^o`EJocH|tZ(%4tny@u*NErekf@&b>(VLp9G)w+{z620^ zQA7~I!YHZWowmJPZWCka*HCI+&)6U0((&JNBz5K<5^em6vI|;EhhRx(X&DNm$IcD2 zZ0ez2Af;W8Fk}RQ_a4jDc~P3(VTUob>qvWynwvC&wy~scS`0o{JwM6fCph}Iqx8w0 z_BYRDHBozHq|TD_N)EA67JpAz>|~P-Hk`cw#GH!hb1>}MKu}EX=84Pesz|Ny8=iOvdR`@|aI|@6>pnmgv zbD(AONUYyE>t6o{gGheG#;6EeQ5fm!8f1)o@cKOWt0@inhtQ?011I|S0g_T-)} zG)a0+%xNn&scHhM>$>oGKJ4>&;_(3FF>;@Y#H*9$`Yfw9RSR@K@8j3A@CSPLikFWF z@-dLCL?gd5&sjEvPM>t*bP(_rdXwFBlaZcoJbx6;wE&sK5=gkuWfvB{2E_js2vqSw zQcqxh{VXeSDL-F%W?E^#b+P4Z(4g&E(6datfHNWE$^Q&edilG_WRR9GJN<Ky z)M$G`twB+z(V1UL{N5hW!#%(5b7B40#bvei8k66pYwQDKucmv>T(xliQRr^~FM+%S z<9+#L>uGbJr(^(ec`#u^o%jQc>}VKxRNJ=DJP5%+^+H&J4)iA=ywh}6V$_}!BGzhw zY0EK+ZEhFK-Blb@!wiVydUh^{2YmJ>r>1>9rAEb$gElLfv`u zbq9&1lxb+Fepa8+>ef6dKn{ulKm`$+LBv38e3n&W2k(Ht-D992C9%~qLPQF_siq-N zIFa4Sa;smgu@0CK(`e-zPTSnnZgd8D-GXQxSh2u#DPzjUJEF_|MJyx8K08zG*(spD z07Fi+B!?qPV{hFuY6CuNFi0}ud1VkW757v#j8k(ZrhD#7P~HKQ?!GA=(`mn6E}x`&B~N3rbuJa$&e0l1fwOb1>E(w*K5*+)-P12W0Z!8Y{5Zc}?xhw> z-8BAg4s@^mnI4P%*^0UeJEfX!Mrg8oU3sy=Z`%VPV+543S`#bL9zh)Eoj^ETO-Ah2mO8KZM-c- zZ zJkP9a1K4R?oEKrZVyvtKU5n-&0QoaauX7;LjmspXR`l6hX{)y*7DQbPp=Y8fu&$|C zwoGBkmA|1C0OT#KbVTokX@LaNs0x;VBvwF~+FSlKc6CAnMd<2RpaZq3ALQr=OJ|_Igoo*-)Z$DODw|)b+~%s~nGAXE*Is z+-?x!PAB~uZi+)LF#wqpOulaRhEcMJ{5AtKf4)pqixfTI_% z=n@W%3%pyFGv~fL{`Q8ni|?QQ?pHlr@z+u*J^Z%I>{*I8sJ2$%TsGo;%RaAH-_z4# zz$r^M?Qvz>Md{}C3OZN6MnF;kkd2C7%m6*LrvvrYW$-X@zu(K}g*hj#%VhKU^#%P$ zfqw+!p9|MN59qD77|Uh(O(HjM<*Q#= zk4|B3>0fp0^HJ8d;nqyJgW>KM*E| zn6|$RRI}Hi0*Ly^q)|g^xeGFoFlI{o#E_)7DRXfuPM;m_8w3&auzrY zOrHePdL)GVA$lOuW;3foRUom;@WC#8Qp9c?3fwlHXn^H%)?4?|297I(0%;x0R!Ni? zA8cPhb{M=9m}M-ZROtodc+Aj;Ozxml5r0T6I z79_myiT69M@4ElK@qWK?zi-^{H{LCvxLX<4%8FN}bZ!B8i`UrfytkT+>tO*x1Qc=o zsOu|#fB0^s)9*cq$^{JTO!mQ_Vervm=g*Gz^jax7Jo8yVzB%-GnO_^-$)Ywo_cV4t z%iwcs%kQZitFYw9<@m`#c{ZLj@Ywmu;AySL256U{AscV}+Uyc4cu;P@aB!cx^2Yo9 z!uw^P+s_e5T-SxKUvJ=l1M(WU-WMM8Y3V;;!Gs8KOYV|8Zwn^wc^@~Y`^i$roz!x; zBnc09nErd$l~r37hUK|6#2oW}H8KG=mD>aFniBz|Hwk4^@;A$*<+R`_pn87| zaes^pUteE%em!wNZ#=&y^h<#!AYTG`E=zS&Z(Cfi*rk=FB%oij&)G1ZpLGeeQ)WsI zNSK0bjlLF0p!3N0lCX)^1LFTj>5=2=TC!9w{5{eqPrs(7CyWkuHi6}=Z0u?8K8c5)n2!YQ8J~Se9B$P(dFjn-B zM&o3T*H`Ix1I1G5$5MdPBi8G}m^LAgja$_`>KXvifp&~(SA|T_3IoN*420mRJBB zJbIw8XQ!Q(A;(I;x8FV;XIsC*kz?UM1v8)OvE|JEhh(e!`>b2F%2z#wQ)@ue{tPKF ziJYSbZ@hC&&)$a}2;O%D+7>vx{`|q~^#|`ifAIeE!hPR1#N)a!|Ct!C3)lOB$9&?6 z8;S{i43pJiz{COw*G=vroOjbi|Ml9i;J@{dd0)h>wsFAR8wmkg%Tr``3;8>&E=0&|k12e7^+a zbwR$aMziRdsbRGO%Xs02fVekql2EX3=D#T4XI%0iby=$TF3eD`UJ+3Fl;WAH4d?Y zh&Y$C=T?xSC!C2832NKsbWwgx4WyrAzJ${<=|xmF zrL&dAYV|SA-5RG#D#>g^a8ShHG7K0^xhFoz2|EY*hD78Mvp-kK~9v8qw%{tSFqWnzBtST^d zV9be`i!uxd4<{p;&s3t}!Rw8vL(C0eUU>a^;q`jq z?dSV-CxB{BH=Ong7SgZnPHRPxx_lQA3mP8Y)8IkFxZW99+|OwN#Pb1t0QwZ*DZpbu z9==p|%bH~^)qZ20(A`e}=;Oiikb2loz#wS1z z5b@{tAH4qjwt(XIZ_NA7@#6R`7C`71UU=h;8@Ei8(WlL&h}B>sh{ztm1f2z91GqBC z-I$@v_mxja!KMZlqGjjT={=H;#xwWRc>4aT5^^}_*9lWEp`e@ zRo28N@m1)(;(x3N7`Cl2XA2^tY@r|2*oSCXrAF77K+OTgz6`9t3sjE;0{o`YT6-j_ zXTngY*HtD41eaK_FueD{?z+Hu5MfYH5kW*o)Oq&h5mA#o4cI$V8rUm_SfdPqS64vN z*)jyHQ6Ty3!9)o_1rgB#Q1>FehyZJ-OffV=vM>t%k7=ET&jCY}Evcpf5({t@=GCll z*AW-6G>R^2Dw~ko-b5Ba#85AdUIGVomYyvYCXazJWg9=o&dsVzhSBS&Q12PAU`3`v z=CpCP#1|Q*_{@W#VJHdHEEGuGfm#3&!LL?8F}w0;%2v?C(yJf>zPXs>#8}>)xK?MH zo}N$cz6JA!Elv=-N_r46-{t_!u+KCesjNQKuVjmy0W^1wPAOrh+zfCkYcV`}2|_98 zIO~dT&lQ~{Cs10~;m8NT;$(M9bWMuGgJuX~N4V%%?)1 z0KUY6h^IiFreCGAARy4~gdFI2ua_~V!f_EDc*a^ zS)yKdIX-!;z-EKDA3;xS@9nL|DDc-F51lT%wepo~lDg_?%@}4$D}dPsjJ>g8-o9c> z%pICOq$%{}_X~f1|F+Nn`Hk1_-?-oJT%`&BYv7?@c*`McdZ3Vn zZ)aV;H+zi!D&MOBB7jj3CdT7}{-e-;0Q@61XW(ta_^$hb>%NI@=N`VU$Ch!c1_{PT zyVPtS*@Mj{P!KUDVsQ>O$Q49WFtN}j_lW>zU-8R3=B zmnA0Z3MMQNm}*Atg6}gS5kf>VLRAXIiGmRkNac$WWOTAXOqFFtm}YE*o;M{-v&EoB z)yoq%{j8CsGmm;|G9VxZ_o@oQ1WFV*&|WfeG~hLp_iY$n>(`Zs=|lS5<8#k04=yHTncittb%?G>#MB zJn)283sEpm=y9IV(#68-uD(RoQm!B!vpkau1(Pf%uV5DQc@TAvvj@~6|1u;4Zw%O& z;>hRna(Lhstu(jZ7*p`NOJ~-@#5D3PG05vOAN5WW1?AK>%PaL)m+w8H_WWSSph%-L zpqM(E?pHeHXiL^z?pzuzK(YYEgi>=U3cHX0x&)mM6)4X!Xp!IkKU6gEurs{L% z9b+wg-k3=Dy>cZAiypOi+Mnd#;iDMD#@_6Qry92Eez~JK{$aIgE%V2Za)3CZud{ngntRu$_9dX zZw*WXM{r;fSb}wn>@trA*a8afJ>UgFXc%txF6B_C>VeR$g`W5vwu<&9OS`)19%C3E5ij~(hxKS82&{dF~Y+7J|bQ?b6UgZ$>@L&36dgO zGE4JnHRrnhHKL2}LtRS2bI4KlJ#rRK z=yF% zCg?g>J<7G(*~Zi6&PqPR{}izFh7R&E0UE~~KJHoVI^44=hTbWElDaW~dD&*O@L=Kv zynj!;9&h})Uby5B2L6u^eR^YD!{SzG5? zmA#SzVQzz@`PefHg|32CnxeD=qP2y0Pw~5ZOIpWrEMG{M`OLi=tzj-~M$+44f&+;) z(AWYCo?Jb7c-*oNN%S)DlBj7j?US1e$32KQ+$ObmIXDFajV_@;4 zbsBz3gCffC7+mM|TGfY$sTR0m9gDI=Fag+PW@m@%Os_e&n!&oob!u)PsL?j8whu$n zVhYu}jFevGEW%O7*gdIgMv;jFWo-y5I3Mk7UG~ghVKf2j0dRT^O+#scOcdrMAItZ= zsfeBkmh(YD#3h$!AF@~s2{{dQN@L=^5V(=U{l+EEGw+d@xBYf2ZnX*7Ib;linlobe zD~Kp6uKJT*aUmyCGO*j^-P5+%J)JFmzHsUgh+g(_pq7gh3|gOi z*)eo*urZ28jlRs+m1T=xjXx1|O7;Rtmw9$talNF+)dec8d@k$WpD%i@g-tT&z1F}; z`n_0&?HkTd= z3L;|ILaxd(eKp2;Ww33HO4d_;55@g^;&t8lBQFg6f#~qX0&I!cxwdBW5EdU3A2e)1 zV34&Ftes6(6)Ak#v(Iw82s0$}6Osp``NB)3ch2nGzGWIsJQn7Clu!DNo;e1qr=$6C zvgL>{jMDS;TM&2n#Pb7L-$V9iGVxLe- z0YF?wK2E1tT?*>!@uI+P4r!2{1|paM*BK;?WeAYU=@4J1_e?AXjDiWo5U1fZ_P{Dy zwv&g^TO{hEqnuw715MP02-OnAxrV}w3H1%u()k4|vX~L5MQx+@npfHFnBxNA!9+17 zWhKFkrXf+M0fGi2*z3Q63nPZ$| zF#@PfPMolL1~DJQRy7mIP`f9ihBGZPQ+Y*^g6HgV`0rwnl^h${06QyvBVof%8r>WW6e#Q0n*n##f!B+NK!gk^_}%XOH|G~J zK)|h8Nu|5t+eqiLyoaL)4S6#qsoh`Ssp4;-@|@duKTsKU`QGxVW3z@*&*pCd*aIj0 zOdBZryf^LjS@K9dle(P&guv{_?EGDOB-+RCTkvq#+VBxX-1gBam;;!icwZCm@x~v# zAbJ6};Cj6Ah(KZkr!yN*PI7c&fwgI9)xodx>^fQ<>XI$7+#ZsY_C~>?V>JRKP*`|f z?`wCfVaW5OC7&&wey{0grWs({pVxSvH&js_xgKvoRgvPVMeBd}#NwQRyVhJEusZo_y=js!jV8nNP*_eg9*nj*NM z;9*^~Kx+<8((nU)dl?s77%C{mYvwxW)%c?&JpCYmoM47}CAuUXli&b$tj! zmiM@9yX*W^g7eMAqHYf#b)TNe-?e+!uzz8za$Gd$5&1~blUKeeOZJJpvIh2CoK1r&>VwK|dw zlkh(_yjZ3O7!Uj4A-2fO!;=+TWaxpX@h{$2^Ig{K82d{tbOHeCB}l{dja@IyWACOu zK(b*wj=AYW*^f>d!h+O57_V_4(d?2|3UU6w3kR%<@86=+00000NkvXXu0mjf&mr4V literal 0 HcmV?d00001 diff --git a/perception/traffic_light_occlusion_predictor/include/traffic_light_occlusion_predictor/nodelet.hpp b/perception/traffic_light_occlusion_predictor/include/traffic_light_occlusion_predictor/nodelet.hpp new file mode 100644 index 0000000000000..2117b650efc41 --- /dev/null +++ b/perception/traffic_light_occlusion_predictor/include/traffic_light_occlusion_predictor/nodelet.hpp @@ -0,0 +1,102 @@ +// Copyright 2023 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef TRAFFIC_LIGHT_OCCLUSION_PREDICTOR__NODELET_HPP_ +#define TRAFFIC_LIGHT_OCCLUSION_PREDICTOR__NODELET_HPP_ + +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +namespace traffic_light +{ +class TrafficLightOcclusionPredictorNodelet : public rclcpp::Node +{ +public: + explicit TrafficLightOcclusionPredictorNodelet(const rclcpp::NodeOptions & node_options); + +private: + struct Config + { + double azimuth_occlusion_resolution_deg; + double elevation_occlusion_resolution_deg; + double max_valid_pt_dist; + double max_image_cloud_delay; + double max_wait_t; + int max_occlusion_ratio; + }; + +private: + /** + * @brief receive the lanelet2 map + * + * @param input_msg + */ + void mapCallback(const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr input_msg); + /** + * @brief subscribers + * + */ + void syncCallback( + const tier4_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr in_signal_msg, + const tier4_perception_msgs::msg::TrafficLightRoiArray::ConstSharedPtr in_roi_msg, + const sensor_msgs::msg::CameraInfo::ConstSharedPtr in_cam_info_msg, + const sensor_msgs::msg::PointCloud2::ConstSharedPtr in_cloud_msg); + + rclcpp::Subscription::SharedPtr map_sub_; + /** + * @brief publishers + * + */ + rclcpp::Publisher::SharedPtr signal_pub_; + + tf2_ros::Buffer tf_buffer_; + tf2_ros::TransformListener tf_listener_; + std::map traffic_light_position_map_; + Config config_; + /** + * @brief main class for calculating the occlusion probability + * + */ + std::shared_ptr cloud_occlusion_predictor_; + + typedef perception_utils::PrimeSynchronizer< + tier4_perception_msgs::msg::TrafficSignalArray, + tier4_perception_msgs::msg::TrafficLightRoiArray, sensor_msgs::msg::CameraInfo, + sensor_msgs::msg::PointCloud2> + SynchronizerType; + + std::shared_ptr synchronizer_; +}; +} // namespace traffic_light +#endif // TRAFFIC_LIGHT_OCCLUSION_PREDICTOR__NODELET_HPP_ diff --git a/perception/traffic_light_occlusion_predictor/include/traffic_light_occlusion_predictor/occlusion_predictor.hpp b/perception/traffic_light_occlusion_predictor/include/traffic_light_occlusion_predictor/occlusion_predictor.hpp new file mode 100644 index 0000000000000..9c14cd992fac8 --- /dev/null +++ b/perception/traffic_light_occlusion_predictor/include/traffic_light_occlusion_predictor/occlusion_predictor.hpp @@ -0,0 +1,95 @@ +// Copyright 2023-2026 the Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// + +#ifndef TRAFFIC_LIGHT_OCCLUSION_PREDICTOR__OCCLUSION_PREDICTOR_HPP_ +#define TRAFFIC_LIGHT_OCCLUSION_PREDICTOR__OCCLUSION_PREDICTOR_HPP_ + +#include +#include +#include +#include + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +namespace traffic_light +{ + +struct Ray +{ + float azimuth; + float elevation; + float dist; +}; + +class CloudOcclusionPredictor +{ +public: + CloudOcclusionPredictor( + rclcpp::Node * node_ptr, float max_valid_pt_distance, float azimuth_occlusion_resolution_deg, + float elevation_occlusion_resolution_deg); + + void predict( + const sensor_msgs::msg::CameraInfo::ConstSharedPtr & camera_info_msg, + const tier4_perception_msgs::msg::TrafficLightRoiArray::ConstSharedPtr & rois_msg, + const sensor_msgs::msg::PointCloud2::ConstSharedPtr & cloud_msg, + const tf2_ros::Buffer & tf_buffer, + const std::map & traffic_light_position_map, + std::vector & occlusion_ratios); + +private: + uint32_t predict(const pcl::PointXYZ & roi_top_left, const pcl::PointXYZ & roi_bottom_right); + + void filterCloud( + const pcl::PointCloud & cloud_in, const std::vector & roi_tls, + const std::vector & roi_brs, pcl::PointCloud & cloud_out); + + void sampleTrafficLightRoi( + const pcl::PointXYZ & top_left, const pcl::PointXYZ & bottom_right, + uint32_t horizontal_sample_num, uint32_t vertical_sample_num, + pcl::PointCloud & cloud_out); + + void calcRoiVectex3D( + const tier4_perception_msgs::msg::TrafficLightRoi & roi, + const image_geometry::PinholeCameraModel & pinhole_model, + const std::map & traffic_light_position_map, + const tf2::Transform & tf_camera2map, pcl::PointXYZ & top_left, pcl::PointXYZ & bottom_right); + + std::map > > lidar_rays_; + rclcpp::Node * node_ptr_; + float max_valid_pt_distance_; + float azimuth_occlusion_resolution_deg_; + float elevation_occlusion_resolution_deg_; +}; + +} // namespace traffic_light + +#endif // TRAFFIC_LIGHT_OCCLUSION_PREDICTOR__OCCLUSION_PREDICTOR_HPP_ diff --git a/perception/traffic_light_occlusion_predictor/launch/traffic_light_occlusion_predictor.launch.xml b/perception/traffic_light_occlusion_predictor/launch/traffic_light_occlusion_predictor.launch.xml new file mode 100644 index 0000000000000..795267b920e24 --- /dev/null +++ b/perception/traffic_light_occlusion_predictor/launch/traffic_light_occlusion_predictor.launch.xml @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/perception/traffic_light_occlusion_predictor/package.xml b/perception/traffic_light_occlusion_predictor/package.xml new file mode 100644 index 0000000000000..813f2914b7c4b --- /dev/null +++ b/perception/traffic_light_occlusion_predictor/package.xml @@ -0,0 +1,36 @@ + + + + traffic_light_occlusion_predictor + 0.1.0 + The traffic_light_occlusion_predictor package + Mingyu Li + Apache License 2.0 + + ament_cmake_auto + + autoware_cmake + + autoware_auto_geometry + autoware_auto_mapping_msgs + geometry_msgs + image_geometry + lanelet2_extension + pcl_msgs + perception_utils + rclcpp + rclcpp_components + sensor_msgs + tf2 + tf2_eigen + tf2_ros + tier4_autoware_utils + tier4_perception_msgs + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/perception/traffic_light_occlusion_predictor/src/nodelet.cpp b/perception/traffic_light_occlusion_predictor/src/nodelet.cpp new file mode 100644 index 0000000000000..90d96b4c9cbfc --- /dev/null +++ b/perception/traffic_light_occlusion_predictor/src/nodelet.cpp @@ -0,0 +1,138 @@ +// Copyright 2023 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "traffic_light_occlusion_predictor/nodelet.hpp" + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#define EIGEN_MPL2_ONLY +#include +#include + +namespace traffic_light +{ + +TrafficLightOcclusionPredictorNodelet::TrafficLightOcclusionPredictorNodelet( + const rclcpp::NodeOptions & node_options) +: Node("traffic_light_occlusion_predictor_node", node_options), + tf_buffer_(this->get_clock()), + tf_listener_(tf_buffer_) +{ + using std::placeholders::_1; + using std::placeholders::_2; + using std::placeholders::_3; + using std::placeholders::_4; + + // subscribers + map_sub_ = create_subscription( + "~/input/vector_map", rclcpp::QoS{1}.transient_local(), + std::bind(&TrafficLightOcclusionPredictorNodelet::mapCallback, this, _1)); + + // publishers + signal_pub_ = + create_publisher("~/output/traffic_signals", 1); + // configuration parameters + config_.azimuth_occlusion_resolution_deg = + declare_parameter("azimuth_occlusion_resolution_deg", 0.15); + config_.elevation_occlusion_resolution_deg = + declare_parameter("elevation_occlusion_resolution_deg", 0.08); + config_.max_valid_pt_dist = declare_parameter("max_valid_pt_dist", 50.0); + config_.max_image_cloud_delay = declare_parameter("max_image_cloud_delay", 1.0); + config_.max_wait_t = declare_parameter("max_wait_t", 0.02); + config_.max_occlusion_ratio = declare_parameter("max_occlusion_ratio", 50); + + cloud_occlusion_predictor_ = std::make_shared( + this, config_.max_valid_pt_dist, config_.azimuth_occlusion_resolution_deg, + config_.elevation_occlusion_resolution_deg); + + const std::vector topics{ + "~/input/traffic_signals", "~/input/rois", "~/input/camera_info", "~/input/cloud"}; + const std::vector qos(topics.size(), rclcpp::SensorDataQoS()); + synchronizer_ = std::make_shared( + this, topics, qos, + std::bind(&TrafficLightOcclusionPredictorNodelet::syncCallback, this, _1, _2, _3, _4), + config_.max_image_cloud_delay, config_.max_wait_t); +} + +void TrafficLightOcclusionPredictorNodelet::mapCallback( + const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr input_msg) +{ + traffic_light_position_map_.clear(); + auto lanelet_map_ptr = std::make_shared(); + + lanelet::utils::conversion::fromBinMsg(*input_msg, lanelet_map_ptr); + lanelet::ConstLanelets all_lanelets = lanelet::utils::query::laneletLayer(lanelet_map_ptr); + std::vector all_lanelet_traffic_lights = + lanelet::utils::query::autowareTrafficLights(all_lanelets); + for (auto tl_itr = all_lanelet_traffic_lights.begin(); tl_itr != all_lanelet_traffic_lights.end(); + ++tl_itr) { + lanelet::AutowareTrafficLightConstPtr tl = *tl_itr; + + auto lights = tl->trafficLights(); + for (auto lsp : lights) { + if (!lsp.isLineString()) { // traffic lights must be linestrings + continue; + } + lanelet::ConstLineString3d string3d = static_cast(lsp); + traffic_light_position_map_[lsp.id()] = + perception_utils::traffic_light::getTrafficLightCenter(string3d); + } + } +} + +void TrafficLightOcclusionPredictorNodelet::syncCallback( + const tier4_perception_msgs::msg::TrafficSignalArray::ConstSharedPtr in_signal_msg, + const tier4_perception_msgs::msg::TrafficLightRoiArray::ConstSharedPtr in_roi_msg, + const sensor_msgs::msg::CameraInfo::ConstSharedPtr in_cam_info_msg, + const sensor_msgs::msg::PointCloud2::ConstSharedPtr in_cloud_msg) +{ + tier4_perception_msgs::msg::TrafficSignalArray out_msg = *in_signal_msg; + std::vector occlusion_ratios; + if ( + in_cloud_msg == nullptr || in_cam_info_msg == nullptr || in_roi_msg == nullptr || + in_roi_msg->rois.size() != in_signal_msg->signals.size()) { + occlusion_ratios.resize(in_roi_msg->rois.size(), 0); + } else { + cloud_occlusion_predictor_->predict( + in_cam_info_msg, in_roi_msg, in_cloud_msg, tf_buffer_, traffic_light_position_map_, + occlusion_ratios); + } + for (size_t i = 0; i < occlusion_ratios.size(); i++) { + if (occlusion_ratios[i] >= config_.max_occlusion_ratio) { + perception_utils::traffic_light::setSignalUnknown(out_msg.signals[i]); + } + } + signal_pub_->publish(out_msg); +} + +} // namespace traffic_light + +#include +RCLCPP_COMPONENTS_REGISTER_NODE(traffic_light::TrafficLightOcclusionPredictorNodelet) diff --git a/perception/traffic_light_occlusion_predictor/src/occlusion_predictor.cpp b/perception/traffic_light_occlusion_predictor/src/occlusion_predictor.cpp new file mode 100644 index 0000000000000..eff8921a897a3 --- /dev/null +++ b/perception/traffic_light_occlusion_predictor/src/occlusion_predictor.cpp @@ -0,0 +1,250 @@ +// Copyright 2023-2026 the Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// + +#include "traffic_light_occlusion_predictor/occlusion_predictor.hpp" + +namespace +{ + +traffic_light::Ray point2ray(const pcl::PointXYZ & pt) +{ + traffic_light::Ray ray; + ray.dist = std::sqrt(pt.x * pt.x + pt.y * pt.y + pt.z * pt.z); + ray.elevation = RAD2DEG(std::atan2(pt.y, std::hypot(pt.x, pt.z))); + ray.azimuth = RAD2DEG(std::atan2(pt.x, pt.z)); + return ray; +} + +} // namespace + +namespace traffic_light +{ + +CloudOcclusionPredictor::CloudOcclusionPredictor( + rclcpp::Node * node_ptr, float max_valid_pt_distance, float azimuth_occlusion_resolution_deg, + float elevation_occlusion_resolution_deg) +: node_ptr_(node_ptr), + max_valid_pt_distance_(max_valid_pt_distance), + azimuth_occlusion_resolution_deg_(azimuth_occlusion_resolution_deg), + elevation_occlusion_resolution_deg_(elevation_occlusion_resolution_deg) +{ +} + +void CloudOcclusionPredictor::predict( + const sensor_msgs::msg::CameraInfo::ConstSharedPtr & camera_info_msg, + const tier4_perception_msgs::msg::TrafficLightRoiArray::ConstSharedPtr & rois_msg, + const sensor_msgs::msg::PointCloud2::ConstSharedPtr & cloud_msg, + const tf2_ros::Buffer & tf_buffer, + const std::map & traffic_light_position_map, + std::vector & occlusion_ratios) +{ + if (camera_info_msg == nullptr || rois_msg == nullptr || cloud_msg == nullptr) { + return; + } + occlusion_ratios.resize(rois_msg->rois.size()); + // get transformation from cloud to camera + Eigen::Matrix4d camera2cloud; + try { + camera2cloud = + tf2::transformToEigen(tf_buffer.lookupTransform( + camera_info_msg->header.frame_id, cloud_msg->header.frame_id, + rclcpp::Time(camera_info_msg->header.stamp), + rclcpp::Duration::from_seconds(0.2))) + .matrix(); + } catch (tf2::TransformException & ex) { + RCLCPP_ERROR_STREAM( + node_ptr_->get_logger(), "Error: cannot get transform from << " + << camera_info_msg->header.frame_id << " to " + << cloud_msg->header.frame_id); + return; + } + // get transformation from map to camera + tf2::Transform tf_camera2map; + try { + geometry_msgs::msg::TransformStamped tf_stamped = tf_buffer.lookupTransform( + camera_info_msg->header.frame_id, "map", rclcpp::Time(camera_info_msg->header.stamp), + rclcpp::Duration::from_seconds(0.2)); + tf2::fromMsg(tf_stamped.transform, tf_camera2map); + } catch (tf2::TransformException & ex) { + RCLCPP_ERROR_STREAM( + node_ptr_->get_logger(), + "Error: cannot get transform from << " << camera_info_msg->header.frame_id << " to map"); + return; + } + + std::vector roi_tls(rois_msg->rois.size()), roi_brs(rois_msg->rois.size()); + image_geometry::PinholeCameraModel pinhole_model; + pinhole_model.fromCameraInfo(*camera_info_msg); + for (size_t i = 0; i < rois_msg->rois.size(); i++) { + calcRoiVectex3D( + rois_msg->rois[i], pinhole_model, traffic_light_position_map, tf_camera2map, roi_tls[i], + roi_brs[i]); + } + + lidar_rays_.clear(); + // points in camera frame + pcl::PointCloud cloud_camera; + // points within roi + pcl::PointCloud cloud_roi; + tier4_autoware_utils::transformPointCloudFromROSMsg(*cloud_msg, cloud_camera, camera2cloud); + + filterCloud(cloud_camera, roi_tls, roi_brs, cloud_roi); + + for (const pcl::PointXYZ & pt : cloud_roi) { + Ray ray = ::point2ray(pt); + lidar_rays_[static_cast(ray.azimuth)][static_cast(ray.elevation)].push_back(ray); + } + for (size_t i = 0; i < roi_tls.size(); i++) { + occlusion_ratios[i] = predict(roi_tls[i], roi_brs[i]); + } +} + +void CloudOcclusionPredictor::calcRoiVectex3D( + const tier4_perception_msgs::msg::TrafficLightRoi & roi, + const image_geometry::PinholeCameraModel & pinhole_model, + const std::map & traffic_light_position_map, + const tf2::Transform & tf_camera2map, pcl::PointXYZ & top_left, pcl::PointXYZ & bottom_right) +{ + if (traffic_light_position_map.count(roi.traffic_light_id) == 0) { + return; + } + double dist2cam = (tf_camera2map * traffic_light_position_map.at(roi.traffic_light_id)).length(); + { + cv::Point2d pixel(roi.roi.x_offset, roi.roi.y_offset); + cv::Point2d rectified_pixel = pinhole_model.rectifyPoint(pixel); + cv::Point3d ray = pinhole_model.projectPixelTo3dRay(rectified_pixel); + double ray_len = std::sqrt(ray.ddot(ray)); + top_left.x = dist2cam * ray.x / ray_len; + top_left.y = dist2cam * ray.y / ray_len; + top_left.z = dist2cam * ray.z / ray_len; + } + { + cv::Point2d pixel(roi.roi.x_offset + roi.roi.width, roi.roi.y_offset + roi.roi.height); + cv::Point2d rectified_pixel = pinhole_model.rectifyPoint(pixel); + cv::Point3d ray = pinhole_model.projectPixelTo3dRay(rectified_pixel); + double ray_len = std::sqrt(ray.ddot(ray)); + bottom_right.x = dist2cam * ray.x / ray_len; + bottom_right.y = dist2cam * ray.y / ray_len; + bottom_right.z = dist2cam * ray.z / ray_len; + } +} + +void CloudOcclusionPredictor::filterCloud( + const pcl::PointCloud & cloud_in, const std::vector & roi_tls, + const std::vector & roi_brs, pcl::PointCloud & cloud_out) +{ + float min_x = 0, max_x = 0, min_y = 0, max_y = 0, min_z = 0, max_z = 0; + for (const auto & pt : roi_tls) { + min_x = std::min(min_x, pt.x); + max_x = std::max(max_x, pt.x); + min_y = std::min(min_y, pt.y); + max_y = std::max(max_y, pt.y); + min_z = std::min(min_z, pt.z); + max_z = std::max(max_z, pt.z); + } + for (const auto & pt : roi_brs) { + min_x = std::min(min_x, pt.x); + max_x = std::max(max_x, pt.x); + min_y = std::min(min_y, pt.y); + max_y = std::max(max_y, pt.y); + min_z = std::min(min_z, pt.z); + max_z = std::max(max_z, pt.z); + } + const float min_dist_to_cam = 1.0f; + cloud_out.clear(); + for (const auto & pt : cloud_in) { + if ( + pt.x < min_x || pt.x > max_x || pt.y < min_y || pt.y > max_y || pt.z < min_z || + pt.z > max_z) { + continue; + } + float dist = pt.getVector3fMap().squaredNorm(); + if ( + dist <= min_dist_to_cam * min_dist_to_cam || + dist >= max_valid_pt_distance_ * max_valid_pt_distance_) { + continue; + } + cloud_out.push_back(pt); + } +} + +void CloudOcclusionPredictor::sampleTrafficLightRoi( + const pcl::PointXYZ & top_left, const pcl::PointXYZ & bottom_right, + uint32_t horizontal_sample_num, uint32_t vertical_sample_num, + pcl::PointCloud & cloud_out) +{ + cloud_out.clear(); + float x1 = top_left.x; + float y1 = top_left.y; + float z1 = top_left.z; + float x2 = bottom_right.x; + float y2 = bottom_right.y; + float z2 = bottom_right.z; + for (uint32_t i1 = 0; i1 < horizontal_sample_num; i1++) { + for (uint32_t i2 = 0; i2 < vertical_sample_num; i2++) { + float x = x1 + (x2 - x1) * i1 / (horizontal_sample_num - 1); + float y = y1 + (y2 - y1) * i2 / (vertical_sample_num - 1); + float z = z1 + (z2 - z1) * i1 / (horizontal_sample_num - 1); + cloud_out.push_back(pcl::PointXYZ(x, y, z)); + } + } +} + +uint32_t CloudOcclusionPredictor::predict( + const pcl::PointXYZ & roi_top_left, const pcl::PointXYZ & roi_bottom_right) +{ + const uint32_t horizontal_sample_num = 20; + const uint32_t vertical_sample_num = 20; + static_assert(horizontal_sample_num > 1 && vertical_sample_num > 1); + const float min_dist_from_occlusion_to_tl = 5.0f; + + pcl::PointCloud tl_sample_cloud; + sampleTrafficLightRoi( + roi_top_left, roi_bottom_right, horizontal_sample_num, vertical_sample_num, tl_sample_cloud); + uint32_t occluded_num = 0; + for (const pcl::PointXYZ & tl_pt : tl_sample_cloud) { + Ray tl_ray = ::point2ray(tl_pt); + bool occluded = false; + // the azimuth and elevation range to search for points that may occlude tl_pt + int min_azimuth = static_cast(tl_ray.azimuth - azimuth_occlusion_resolution_deg_); + int max_azimuth = static_cast(tl_ray.azimuth + azimuth_occlusion_resolution_deg_); + int min_elevation = static_cast(tl_ray.elevation - elevation_occlusion_resolution_deg_); + int max_elevation = static_cast(tl_ray.elevation + elevation_occlusion_resolution_deg_); + /** + * search among lidar rays whose azimuth and elevation angle are close to the tl_ray. + * for a lidar ray r1 whose azimuth and elevation are very close to tl_pt, + * and the distance from r1 to camera is smaller than the distance from tl_pt to camera, + * then tl_pt is occluded by r1. + */ + for (int azimuth = min_azimuth; (azimuth <= max_azimuth) && !occluded; azimuth++) { + for (int elevation = min_elevation; (elevation <= max_elevation) && !occluded; elevation++) { + for (const Ray & lidar_ray : lidar_rays_[azimuth][elevation]) { + if ( + std::abs(lidar_ray.azimuth - tl_ray.azimuth) <= azimuth_occlusion_resolution_deg_ && + std::abs(lidar_ray.elevation - tl_ray.elevation) <= + elevation_occlusion_resolution_deg_ && + lidar_ray.dist < tl_ray.dist - min_dist_from_occlusion_to_tl) { + occluded = true; + break; + } + } + } + } + occluded_num += occluded; + } + return 100 * occluded_num / tl_sample_cloud.size(); +} + +} // namespace traffic_light