From ab23b95f07cb87895eda8ff4c35e12ee487af49c Mon Sep 17 00:00:00 2001 From: Purdue RoboMaster Date: Sat, 25 Jan 2025 17:05:04 -0500 Subject: [PATCH 01/12] add func outline for drawing top down view --- src/prm_launch/launch/video2detector.py | 2 +- .../include/PoseEstimatorNode.hpp | 1 + .../pose_estimator/src/PoseEstimatorNode.cpp | 19 +++++++++++++++++++ 3 files changed, 21 insertions(+), 1 deletion(-) diff --git a/src/prm_launch/launch/video2detector.py b/src/prm_launch/launch/video2detector.py index eadd279..39643d5 100755 --- a/src/prm_launch/launch/video2detector.py +++ b/src/prm_launch/launch/video2detector.py @@ -7,7 +7,7 @@ def generate_launch_description(): webcam_publisher = get_package_share_path('webcam_publisher') - video_path = "/home/user-accounts/public/spintop/moving_but_no_spinning.avi" # example, can change to your liking + video_path = "/home/purduerm/Videos/moving_but_no_spinning.avi" # example, can change to your liking return LaunchDescription([ Node( package='webcam_publisher', diff --git a/src/prm_vision/pose_estimator/include/PoseEstimatorNode.hpp b/src/prm_vision/pose_estimator/include/PoseEstimatorNode.hpp index 53ade18..0c56855 100644 --- a/src/prm_vision/pose_estimator/include/PoseEstimatorNode.hpp +++ b/src/prm_vision/pose_estimator/include/PoseEstimatorNode.hpp @@ -32,6 +32,7 @@ class PoseEstimatorNode : public rclcpp::Node // Class methods void publishZeroPredictedArmor(std_msgs::msg::Header header, std::string new_auto_aim_status); + void drawTopDownViewGivenRotation(double yaw, double X, double Y, double Z); // Callbacks and publishers/subscribers rclcpp::Subscription::SharedPtr key_points_subscriber; diff --git a/src/prm_vision/pose_estimator/src/PoseEstimatorNode.cpp b/src/prm_vision/pose_estimator/src/PoseEstimatorNode.cpp index 3aef3a9..1b0e35f 100644 --- a/src/prm_vision/pose_estimator/src/PoseEstimatorNode.cpp +++ b/src/prm_vision/pose_estimator/src/PoseEstimatorNode.cpp @@ -129,6 +129,25 @@ void PoseEstimatorNode::keyPointsCallback(const vision_msgs::msg::KeyPoints::Sha { publishZeroPredictedArmor(key_points_msg->header, new_auto_aim_status); } + + // Draw top-down view + drawTopDownViewGivenRotation(_last_yaw_estimate, tvec.at(0), tvec.at(1), tvec.at(2)); +} + +void PoseEstimatorNode::drawTopDownViewGivenRotation(double yaw, double X, double Y, double Z) +{ + // Draw a line rotated from the x-axis by yaw. + cv::Mat top_down_view = cv::Mat::zeros(1280, 720, CV_8UC3); + + // Draw the target offset from the center of the image + int target_x = Z; + int target_y = X; + cv::circle(top_down_view, cv::Point(target_x, target_y), 5, cv::Scalar(0, 255, 0), -1); + RCLCPP_INFO(get_logger(), "Drawn coordinates: (%d, %d)", target_x, target_y); + + cv::resize(top_down_view, top_down_view, cv::Size(640, 360)); + cv::imshow("Top Down View", top_down_view); + cv::waitKey(1); } void PoseEstimatorNode::publishZeroPredictedArmor(std_msgs::msg::Header header, std::string new_auto_aim_status) From 79ff959914cc68d0195f69b3d655e00031e400fa Mon Sep 17 00:00:00 2001 From: Purdue RoboMaster Date: Sat, 25 Jan 2025 20:09:33 -0500 Subject: [PATCH 02/12] add analytic --- .../pose_estimator/src/PoseEstimator.cpp | 26 +++++++++++++++++++ 1 file changed, 26 insertions(+) diff --git a/src/prm_vision/pose_estimator/src/PoseEstimator.cpp b/src/prm_vision/pose_estimator/src/PoseEstimator.cpp index 7a3fa79..3df1d38 100644 --- a/src/prm_vision/pose_estimator/src/PoseEstimator.cpp +++ b/src/prm_vision/pose_estimator/src/PoseEstimator.cpp @@ -145,6 +145,32 @@ double PoseEstimator::gradientWrtYawFinitediff(double yaw, std::vector observed_points, cv::Mat tvec) +{ + // We assume 0 pitch and roll, so they do not contribute to the rotation matrix + cv::Mat R = (cv::Mat_(3, 3) << cos(yaw_guess), 0, sin(yaw_guess), + 0, 1, 0, + -sin(yaw_guess), 0, cos(yaw_guess)); + + // Reproject the 3D object points using predicted yaw to the image plane + std::vector projected_points; + cv::projectPoints(SMALL_ARMOR_OBJECT_POINTS, R, tvec, CAMERA_MATRIX, DISTORTION_COEFFS, projected_points); + + // Compute the Jacobian matrix + cv::Mat J = cv::Mat::zeros(8, 1, CV_64F); + for (int i = 0; i < 8; i++) + { + cv::Point2d diff = observed_points[i] - projected_points[i]; + J.at(i, 0) = -0.5 * (diff.x * (-sin(yaw_guess)) + diff.y * cos(yaw_guess)); + } + + // Compute the gradient + cv::Mat JtJ = J.t() * J; + double grad = JtJ.at(0, 0); + return grad; +} + /** * @brief Compute the loss between image points and reprojected points based on the yaw guess. * From 38bed5131dffa831f4426cf8b76e40dc0186a3a1 Mon Sep 17 00:00:00 2001 From: Purdue RoboMaster Date: Thu, 6 Feb 2025 18:30:05 -0500 Subject: [PATCH 03/12] add control --- run | 2 +- .../control_communicator/CMakeLists.txt | 63 +++ .../include/ControlCommunicatorNode.hpp | 104 +++++ .../control_communicator/include/messages.h | 64 +++ .../include/projectile_angle_convel.h | 189 ++++++++ .../control_communicator/include/time_debug.h | 9 + .../control_communicator/package.xml | 20 + .../src/ControlCommunicatorNode.cpp | 420 ++++++++++++++++++ .../control_communicator/src/utils.cpp | 65 +++ .../pose_estimator/src/PoseEstimator.cpp | 26 -- 10 files changed, 935 insertions(+), 27 deletions(-) create mode 100755 src/prm_control/control_communicator/CMakeLists.txt create mode 100755 src/prm_control/control_communicator/include/ControlCommunicatorNode.hpp create mode 100755 src/prm_control/control_communicator/include/messages.h create mode 100644 src/prm_control/control_communicator/include/projectile_angle_convel.h create mode 100755 src/prm_control/control_communicator/include/time_debug.h create mode 100755 src/prm_control/control_communicator/package.xml create mode 100755 src/prm_control/control_communicator/src/ControlCommunicatorNode.cpp create mode 100755 src/prm_control/control_communicator/src/utils.cpp diff --git a/run b/run index 8eb2c04..b00c21e 100755 --- a/run +++ b/run @@ -32,7 +32,7 @@ clean() { build() { print_green "[*] Building project with Release configuration and optimization flags." - build_args="-DCMAKE_BUILD_TYPE=Release -DCMAKE_CXX_FLAGS_RELEASE=-O3 -DPYTHON_EXECUTABLE=/usr/bin/python3.8" + build_args="-DCMAKE_BUILD_TYPE=Release -DCMAKE_CXX_FLAGS_RELEASE=-O3" # Add the DEBUG flag if '--debug' or '-d' was provided if [[ "$debug" == "true" ]]; then diff --git a/src/prm_control/control_communicator/CMakeLists.txt b/src/prm_control/control_communicator/CMakeLists.txt new file mode 100755 index 0000000..d72d48e --- /dev/null +++ b/src/prm_control/control_communicator/CMakeLists.txt @@ -0,0 +1,63 @@ +cmake_minimum_required(VERSION 3.5) +project(control_communicator) + +# Default to C99 +if(NOT CMAKE_C_STANDARD) + set(CMAKE_C_STANDARD 99) +endif() + +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +# find dependencies +find_package(ament_cmake REQUIRED) +find_package(rclcpp REQUIRED) +find_package(std_msgs REQUIRED) +find_package(geometry_msgs REQUIRED) +find_package(vision_msgs REQUIRED) +find_package(tf2 REQUIRED) +find_package(tf2_ros REQUIRED) +find_package(Eigen3 REQUIRED) +find_package(nav_msgs REQUIRED) + +# uncomment the following section in order to fill in +# further dependencies manually. + +include_directories(/usr/include) +include_directories(include) + +add_executable(ControlCommunicatorNode + src/ControlCommunicatorNode.cpp +) + + +# include_directories(controlhandler_node +# PUBLIC +# $ +# $ +# ) + +ament_target_dependencies(ControlCommunicatorNode + rclcpp + std_msgs + geometry_msgs + vision_msgs + tf2_ros + tf2 + nav_msgs +) + +target_link_libraries(ControlCommunicatorNode Eigen3::Eigen) + +install(TARGETS +ControlCommunicatorNode + DESTINATION lib/${PROJECT_NAME} +) + +ament_package() diff --git a/src/prm_control/control_communicator/include/ControlCommunicatorNode.hpp b/src/prm_control/control_communicator/include/ControlCommunicatorNode.hpp new file mode 100755 index 0000000..6c61598 --- /dev/null +++ b/src/prm_control/control_communicator/include/ControlCommunicatorNode.hpp @@ -0,0 +1,104 @@ + +#ifndef _CONTROL_COMMUNICATOR_NODE_H +#define _CONTROL_COMMUNICATOR_NODE_H + +#include +#include +#include +#include +#include +#include + +#include // Error integer and strerror() function + +#include "rclcpp/rclcpp.hpp" +#include "rclcpp/logger.hpp" +#include "std_msgs/msg/string.hpp" +#include "std_msgs/msg/bool.hpp" +#include "std_msgs/msg/float64.hpp" +#include "geometry_msgs/msg/pose.hpp" +#include "geometry_msgs/msg/transform_stamped.hpp" +#include + +#include "geometry_msgs/msg/transform_stamped.hpp" +#include "tf2_ros/static_transform_broadcaster.h" +#include "tf2_ros/transform_broadcaster.h" +#include "tf2/LinearMath/Quaternion.h" +#include "tf2/LinearMath/Matrix3x3.h" +#include "tf2_ros/transform_listener.h" +#include "tf2_ros/buffer.h" + +#include "projectile_angle_convel.h" + +#include "vision_msgs/msg/yaw_pitch.hpp" +#include "vision_msgs/msg/predicted_armor.hpp" +#include "nav_msgs/msg/odometry.hpp" +#include "messages.h" + +// using namespace std::chrono_literals; +// using namespace std::placeholders; +// namespace rmoss_msgs = rmoss_interfaces::msg; + +class ControlCommunicatorNode : public rclcpp::Node +{ +public: + ControlCommunicatorNode(const char *port); + + ~ControlCommunicatorNode(); + +private: + float yaw_vel = 0; // rad/s (+ccw, -cw) + float pitch_vel = 0; // rad/s + float pitch = 0; // rad (+up, -down)? + bool is_red = 0; + bool is_match_running = 0; + bool valid_read = false; + + uint32_t recive_frame_id = 0; + + const char *port; + int port_fd = -1; + bool is_connected = false; + + uint32_t auto_aim_frame_id = 0; + uint32_t nav_frame_id = 0; + uint32_t heart_beat_frame_id = 0; + + int aim_stop_null_frame_count; + int aim_null_frame_count = 0; + + float aim_bullet_speed; // mm/s + + int8_t curr_pois = 0; + bool right = true; + + std::unique_ptr tf_broadcaster; + std::shared_ptr tf_static_broadcaster; + std::unique_ptr tf_buffer; + std::shared_ptr tf_listener; + + rclcpp::Subscription::SharedPtr auto_aim_subscriber; + rclcpp::Subscription::SharedPtr nav_subscriber; + + rclcpp::Publisher::SharedPtr odometry_publisher; + std::shared_ptr> target_robot_color_publisher = NULL; + std::shared_ptr> match_status_publisher = NULL; + + + rclcpp::TimerBase::SharedPtr uart_read_timer; + rclcpp::TimerBase::SharedPtr heart_beat_timer; + + void start_uart(const char *port); + + void publish_static_tf(float, float, float, float, float, float, const char *, const char *); + + void auto_aim_handler(const std::shared_ptr msg); + void nav_handler(const std::shared_ptr msg); + void heart_beat_handler(); + + bool read_alignment(); + + void read_uart(); +}; + +#endif // CONTROL_COMMUNICATOR_NODE_H diff --git a/src/prm_control/control_communicator/include/messages.h b/src/prm_control/control_communicator/include/messages.h new file mode 100755 index 0000000..54d2786 --- /dev/null +++ b/src/prm_control/control_communicator/include/messages.h @@ -0,0 +1,64 @@ +#ifndef _MESSAGES_H +#define _MESSAGES_H + +#include + +#define FRAME_TYPE_AUTO_AIM 0 +#define FRAME_TYPE_NAV 1 +#define FRAME_TYPE_HEART_BEAT 2 +#define FRAME_TYPE_OTHER 3 + +typedef struct _AutoAimPackage +{ + float yaw; // yaw (deg) + float pitch; // pitch (deg) + bool fire; // 0 = no fire, 1 = fire +} AutoAimPackage; + +typedef struct _NavPackage +{ + float x_vel; // m/s + float y_vel; // m/s + float yaw_rad; // rad/s + uint8_t state; // 0 = stationary, 1 = moving, 2 = spin +} NavPackage; + +typedef struct _HeartBeatPackage +{ + uint8_t _a; // blank + uint8_t _b; + uint8_t _c; + uint8_t _d; +} HeartBeatPackage; + +typedef struct _PackageOut +{ + uint8_t frame_id; + uint8_t frame_type; + union + { + AutoAimPackage autoAimPackage; + NavPackage navPackage; + HeartBeatPackage heartBeatPackage; + }; + // uint8_t crc8; +} PackageOut; + +typedef struct __attribute__((__packed__)) _PackageIn +{ + uint8_t head; + uint8_t ref_flags; + float pitch; // rad + float pitch_vel; // rad/s + float yaw_vel; // rad/s (ccw: +, cw: -) + + float x; // m + float y; // m + float orientation; // rad (ccw: +, cw: -) + + float x_vel; // m/s + float y_vel; // m/s + // uint8_t is_blue; // 0 = red, 1 = blue +} __attribute__((packed)) PackageIn; + +#endif // _MESSAGES_H diff --git a/src/prm_control/control_communicator/include/projectile_angle_convel.h b/src/prm_control/control_communicator/include/projectile_angle_convel.h new file mode 100644 index 0000000..ed9f55e --- /dev/null +++ b/src/prm_control/control_communicator/include/projectile_angle_convel.h @@ -0,0 +1,189 @@ + +#include +#include +#include +#include + +#define MUZZLE_VELOCITY 30.00 +#define SHOT_IMPOSSIBLE -100 +#define PI 3.14159 +#define RAD_2_DEG 180/PI + +#define OoM -10 + +/** + * @author sidneycadot + * @source: https://github.com/sidneycadot/quartic + * @brief Below three are helper functions from the above source to solve the quartic arising from the motion + * intersection equations + */ + +static std::complex complex_sqrt(const std::complex & z) +{ + return pow(z, 1. / 2.); +} + +static std::complex complex_cbrt(const std::complex & z) +{ + return pow(z, 1. / 3.); +} + +void solve_quartic(const std::complex coefficients[5], std::complex roots[4]) +{ + // The algorithm below was derived by solving the quartic in Mathematica, and simplifying the resulting expression by hand. + + const std::complex a = coefficients[0]; + const std::complex b = coefficients[1] / a; + const std::complex c = coefficients[2] / a; + const std::complex d = coefficients[3] / a; + const std::complex e = coefficients[4] / a; + + const std::complex Q1 = c * c - 3. * b * d + 12. * e; + const std::complex Q2 = 2. * c * c * c - 9. * b * c * d + 27. * d * d + 27. * b * b * e - 72. * c * e; + const std::complex Q3 = 8. * b * c - 16. * d - 2. * b * b * b; + const std::complex Q4 = 3. * b * b - 8. * c; + + const std::complex Q5 = complex_cbrt(Q2 / 2. + complex_sqrt(Q2 * Q2 / 4. - Q1 * Q1 * Q1)); + const std::complex Q6 = (Q1 / Q5 + Q5) / 3.; + const std::complex Q7 = 2. * complex_sqrt(Q4 / 12. + Q6); + + roots[0] = (-b - Q7 - complex_sqrt(4. * Q4 / 6. - 4. * Q6 - Q3 / Q7)) / 4.; + roots[1] = (-b - Q7 + complex_sqrt(4. * Q4 / 6. - 4. * Q6 - Q3 / Q7)) / 4.; + roots[2] = (-b + Q7 - complex_sqrt(4. * Q4 / 6. - 4. * Q6 + Q3 / Q7)) / 4.; + roots[3] = (-b + Q7 + complex_sqrt(4. * Q4 / 6. - 4. * Q6 + Q3 / Q7)) / 4.; +} + + + +/** + * @brief Solves for the pitch yaw angles using gravity model + * Includes vector helper functions + * + */ + +struct vec3{ + double x = 0, y = 0, z = 0; + std::string id = "N/A"; + + vec3(){x=0;y=0;z=0;} + + vec3(double a, double b, double c) + { + x = a; + y = b; + z = c; + } + + vec3 operator + (vec3 const &a) + { + vec3 b; + b.x = x + a.x; + b.y = y + a.y; + b.z = z + a.z; + return b; + } + + vec3 operator - (vec3 const &a) + { + vec3 b; + b.x = x - a.x; + b.y = y - a.y; + b.z = z - a.z; + return b; + + } + + double operator * (vec3 const &a) + { + double b; + b = x * a.x + y * a.y + z * a.z; + return b; + } + + vec3 operator * (double c) + { + vec3 b; + b.x = c * x; + b.y = c * y; + b.z = c * z; + return b; + } + + vec3 operator / (double c) + { + vec3 b; + b.x = x / c; + b.y = y / c; + b.z = z / c; + return b; + } + + double norm() + { + return sqrt(x*x + y*y + z*z); + } + + void print() + { + std::cout << id << ": (" << x << ", " << y << ", " << z << ")' \n"; + } +}; + +bool compare_complex(std::complex a, std::complex b) +{ + return a != b ? a.real() < b.real() : a.imag() < b.imag(); +} + +double smallest_positive_real_soln(std::complex roots[4]) +{ + double soln = SHOT_IMPOSSIBLE; + + for(int i = 0; i < 4; i++) + { + double imag_order = log10(abs(roots[i].imag())); + if((imag_order < OoM || std::isnan(imag_order)) && roots[i].real() > 0) + { + soln = roots[i].real(); + break; + } + } + + return soln; +} + +void pitch_yaw_gravity_model_movingtarget_const_v(vec3 Pos, vec3 Vel, vec3 G, double time_delay, double* pitch, double* yaw, bool* impossible) +{ + vec3 P_d, aim_vector, aim_uv; + std::complex coeffs[5] = {}, roots[4] = {}; + double t_sol = 0; + + P_d = Pos + Vel * time_delay; + + coeffs[0] = (G * G) * 0.25; + coeffs[1] = Vel * G; + coeffs[2] = P_d * G + Vel * Vel - pow(MUZZLE_VELOCITY, 2); + coeffs[3] = (P_d * Vel) * 2; + coeffs[4] = P_d * P_d; + + solve_quartic(coeffs, roots); + std::sort(roots, roots+4, compare_complex); + t_sol = smallest_positive_real_soln(roots); + + if (t_sol == SHOT_IMPOSSIBLE) + { + *impossible = true; + } + else + { + *impossible = false; + } + + aim_vector = P_d + Vel * t_sol + (G * pow(t_sol, 2)) * 0.5; + aim_uv = aim_vector / aim_vector.norm(); + + *pitch = asin(aim_uv.z); + *yaw = acos(aim_uv.x / cos(*pitch)); + + *pitch = *pitch * RAD_2_DEG; + *yaw = *yaw * RAD_2_DEG; +} diff --git a/src/prm_control/control_communicator/include/time_debug.h b/src/prm_control/control_communicator/include/time_debug.h new file mode 100755 index 0000000..60a001b --- /dev/null +++ b/src/prm_control/control_communicator/include/time_debug.h @@ -0,0 +1,9 @@ +#ifndef _TIME_DEBUG_H +#define _TIME_DEBUG_H + +#define START_TIME auto start = std::chrono::steady_clock::now(); +#define END_TIME auto end = std::chrono::steady_clock::now(); +#define ROS_LOG_DURATION RCLCPP_INFO(this->get_logger(), "duration: %dns", std::chrono::duration_cast(end - start).count()); +#define PRINT_DURATION std::cout << "duration: " << std::chrono::duration_cast(end - start).count() << "ns" << std::endl; + +#endif // _TIME_DEBUG_H \ No newline at end of file diff --git a/src/prm_control/control_communicator/package.xml b/src/prm_control/control_communicator/package.xml new file mode 100755 index 0000000..fafb84d --- /dev/null +++ b/src/prm_control/control_communicator/package.xml @@ -0,0 +1,20 @@ + + + + control_communicator + 0.0.0 + TODO: Package description + ubuntu + TODO: License declaration + + ament_cmake + std_msgs + vision_msgs + geometry_msgs + nav_msgs + tf2 + + + ament_cmake + + diff --git a/src/prm_control/control_communicator/src/ControlCommunicatorNode.cpp b/src/prm_control/control_communicator/src/ControlCommunicatorNode.cpp new file mode 100755 index 0000000..9b48439 --- /dev/null +++ b/src/prm_control/control_communicator/src/ControlCommunicatorNode.cpp @@ -0,0 +1,420 @@ +#include "ControlCommunicatorNode.hpp" + +#include "utils.cpp" + +#include // Contains file controls like O_RDWR +#include // Error integer and strerror() function +#include // Contains POSIX terminal control definitions +#include // write(), read(), close() + +#include "time_debug.h" + +#define PI 3.141592653589793238462643383 // It was 4 AM when I wrote this. + +using namespace std::chrono_literals; +using namespace std::placeholders; + +ControlCommunicatorNode::ControlCommunicatorNode(const char *port) : Node("control_communicator_node") +{ + + aim_stop_null_frame_count = this->declare_parameter("aim.stop_null_frame_count", 3); + + aim_bullet_speed = this->declare_parameter("aim.bullet_speed", 16.0f); + + this->port = port; + + this->start_uart(port); + + if (this->read_alignment()) + { + RCLCPP_INFO(this->get_logger(), "Inital Read alignment success."); + } + else + { + RCLCPP_WARN(this->get_logger(), "Inital Read alignment failed."); + } + + RCLCPP_INFO(this->get_logger(), "should have printed."); + + this->tf_broadcaster = std::make_unique(*this); + this->tf_static_broadcaster = std::make_shared(this); + + this->tf_buffer = std::make_unique(this->get_clock()); + this->tf_listener = std::make_shared(*tf_buffer); + + publish_static_tf(158.7f / 1000.f, 0.f / 1000.f, 47.5 / 1000.f, 0, 0, 0, "pitch_link", "camera_link"); + publish_static_tf(0, 0, 478.f / 1000.f, 0, 0, 0, "base_link", "yaw_link"); + publish_static_tf(0, 0, 0, 0, 0, 0, "base_footprint", "base_link"); + publish_static_tf(0, 0, 0.3, 0, 0, 0, "base_link", "laser"); + + this->heart_beat_timer = this->create_wall_timer(1000ms, std::bind(&ControlCommunicatorNode::heart_beat_handler, this)); + + this->auto_aim_subscriber = this->create_subscription( + "predicted_armor", 1, std::bind(&ControlCommunicatorNode::auto_aim_handler, this, _1)); + + + this->nav_subscriber = this->create_subscription( // should not be twiststamped + "cmd_vel", 1, std::bind(&ControlCommunicatorNode::nav_handler, this, _1)); + + this->odometry_publisher = this->create_publisher("odom", 1); + + this->target_robot_color_publisher = this->create_publisher("color_set", rclcpp::QoS(rclcpp::KeepLast(1)).reliable()); + this->match_status_publisher = this->create_publisher("match_start", rclcpp::QoS(rclcpp::KeepLast(1)).reliable()); + + this->uart_read_timer = this->create_wall_timer(4ms, std::bind(&ControlCommunicatorNode::read_uart, this)); + + RCLCPP_INFO(this->get_logger(), "Control Communicator Node Started."); +} + +ControlCommunicatorNode::~ControlCommunicatorNode() +{ + close(this->port_fd); +} + +void ControlCommunicatorNode::publish_static_tf(float x, float y, float z, float roll, float pitch, float yaw, const char *frame_id, const char *child_frame_id) +{ + geometry_msgs::msg::TransformStamped t; + + t.header.stamp = this->get_clock()->now(); + t.header.frame_id = frame_id; + t.child_frame_id = child_frame_id; + + t.transform.translation.x = x; + t.transform.translation.y = y; + t.transform.translation.z = z; + + tf2::Quaternion q; + q.setRPY(roll, pitch, yaw); + t.transform.rotation.x = q.x(); + t.transform.rotation.y = q.y(); + t.transform.rotation.z = q.z(); + t.transform.rotation.w = q.w(); + + tf_static_broadcaster->sendTransform(t); +} + +void ControlCommunicatorNode::start_uart(const char *port) +{ + this->is_connected = false; + this->port_fd = open(port, O_RDWR); + + // Check for errors + if (this->port_fd < 0) + { + RCLCPP_ERROR(this->get_logger(), "Failed to open: %s, %s", port, strerror(errno)); + return; + } + + struct termios tty; + + // Set UART TTY to 8n1 + tty.c_cflag &= ~PARENB; + tty.c_cflag &= ~CSTOPB; + tty.c_cflag &= ~CSIZE; + tty.c_cflag |= CS8; + + tty.c_cflag &= ~CRTSCTS; // No RTS/CTS flow control + tty.c_cflag |= CREAD | CLOCAL; // Turn on READ & ignore ctrl lines + tty.c_lflag &= ~ICANON; // Disable canonical mode + + // Disable echo, erasure and newline echo + tty.c_lflag &= ~ECHO; + tty.c_lflag &= ~ECHOE; + tty.c_lflag &= ~ECHONL; + + // Disable interpretation of INTR, QUIT and SUSP + tty.c_lflag &= ~ISIG; + + // Disable special handling, interpretation, S/W flow control, \n conv. + tty.c_iflag &= ~(IXON | IXOFF | IXANY); + tty.c_iflag &= ~(IGNBRK | BRKINT | PARMRK | ISTRIP | INLCR | IGNCR | ICRNL); + tty.c_oflag &= ~OPOST; + tty.c_oflag &= ~ONLCR; + + tty.c_cc[VTIME] = 10; // Wait for up to 1s (10 deciseconds) + tty.c_cc[VMIN] = sizeof(PackageIn); // Block for sizeof(PackageOut) bits + + // Set the baud rate + cfsetispeed(&tty, B1152000); + + // Save tty settings, also checking for error + if (tcsetattr(this->port_fd, TCSANOW, &tty) != 0) + { + RCLCPP_ERROR(this->get_logger(), "Error %i from tcsetattr: %s", errno, strerror(errno)); + return; + } + this->is_connected = true; + RCLCPP_INFO(this->get_logger(), "UART Connected"); + + return; +} + +void ControlCommunicatorNode::auto_aim_handler(const std::shared_ptr msg) +{ + if (!is_connected || this->port_fd < 0) + { + RCLCPP_WARN(this->get_logger(), "UART Not connected, ignoring aim message %d.", this->auto_aim_frame_id++); + return; + } + rclcpp::Time curr_time(msg->header.stamp.sec, msg->header.stamp.nanosec, RCL_ROS_TIME); + float dt = (curr_time.seconds() - this->now().seconds()) * 1000; // in ms + + // yaw/pitch and XYZ + vec3 P(msg->x/1000, msg->y/1000, msg->z/1000), V(0,0, 0), grav(0, 0, 9.81); + double p = 0, y = 0; bool im = 0; + + float yaw; + float pitch; + float dst; + + if (msg->x != 0 && msg->z != 0) + { + dst = sqrt(pow(msg->x, 2) + pow(msg->y, 2) + pow(msg->z, 2)); + dt = 0; + float pred_x = msg->x; + float pred_y = msg->y; + float pred_z = msg->z; + yaw = -atan(pred_y / pred_x) * 180 / PI; + pitch = atan(pred_z / pred_x) * 180 / PI; + + pitch_yaw_gravity_model_movingtarget_const_v(P, V, grav, 0, &p, &y, &im); y = y * (msg->y > 0 ? -1 : 1); //currently a bug where yaw is never negative, so we just multiply by the sign of "y" of the target + } + else + { + yaw = 0; + pitch = 0; + dst = 0; + } + + PackageOut package; + this->auto_aim_frame_id++; + package.frame_id = 0xAA; + package.frame_type = FRAME_TYPE_AUTO_AIM; + package.autoAimPackage.yaw = y; + package.autoAimPackage.pitch = p; + // for safety this is commented out unless on sentry package.autoAimPackage.fire = msg->fire; + write(this->port_fd, &package, sizeof(PackageOut)); + fsync(this->port_fd); + if (this->auto_aim_frame_id % 1000 == 0) + { + RCLCPP_INFO(this->get_logger(), "Yaw, Pitch: %.3f, %.3f, FIRE=%.3f", yaw, pitch, msg->fire); + } + RCLCPP_INFO_ONCE(this->get_logger(), "First auto aim pkg sent."); +} + +void ControlCommunicatorNode::nav_handler(const std::shared_ptr msg) +{ + if (!is_connected || this->port_fd < 0) + { + RCLCPP_WARN(this->get_logger(), "UART Not connected, ignoring nav message %d.", this->nav_frame_id++); + return; + } + + PackageOut package; + + package.frame_id = 0xAA; //(uint8_t)this->nav_frame_id++; ANOTHER CHANGE + package.frame_type = FRAME_TYPE_NAV; + package.navPackage.x_vel = msg->linear.x; + package.navPackage.y_vel = msg->linear.y; + package.navPackage.yaw_rad = msg->angular.z; + package.navPackage.state = 1; + write(this->port_fd, &package, sizeof(PackageOut)); + fsync(this->port_fd); + + RCLCPP_INFO(this->get_logger(), "x_vel = %f, y_vel = %f, yaw = %f", package.navPackage.x_vel, package.navPackage.y_vel, package.navPackage.yaw_rad); +} + + +void ControlCommunicatorNode::heart_beat_handler() +{ + if (!this->is_connected || this->port_fd < -1) + { + RCLCPP_WARN(this->get_logger(), "UART Not connected, trying to reconnect."); + this->start_uart(this->port); + } + + // CHANGED FRAME ID TO 0xAA TO COMPLY WITH LEO + + PackageOut package; + this->heart_beat_frame_id++; + package.frame_id = 0xAA; + package.frame_type = FRAME_TYPE_HEART_BEAT; + package.heartBeatPackage._a = 0xAA; + package.heartBeatPackage._b = 0xAA; + package.heartBeatPackage._c = 0xAA; + package.heartBeatPackage._d = 0xAA; + int success = write(this->port_fd, &package, sizeof(PackageOut)); + fsync(this->port_fd); + if (success == -1) + { + this->is_connected = false; + RCLCPP_ERROR(this->get_logger(), "Erro r %i from write: %s", errno, strerror(errno)); + start_uart(this->port); + } + if (this->heart_beat_frame_id % 10 == 0) + { + RCLCPP_INFO(this->get_logger(), "Heart Beat %d", this->heart_beat_frame_id); + } +} + +bool ControlCommunicatorNode::read_alignment() +{ + RCLCPP_INFO(this->get_logger(), "Attemp to alignment."); + uint8_t i = 0; + uint8_t buffer[32]; + do + { + int success = read(this->port_fd, &(buffer[0]), sizeof(buffer[0])); + if (success) + { + i++; + } + } while (buffer[0] != 0xAA || i > sizeof(PackageIn) * 2); + read(this->port_fd, &buffer, sizeof(PackageIn) - 1); + + return i <= sizeof(PackageIn) * 2; +} + +void ControlCommunicatorNode::read_uart() +{ + PackageIn package; + int success = read(this->port_fd, &package, sizeof(PackageIn)); + + rclcpp::Time curr_time = this->now(); + if (success == -1) + { + RCLCPP_ERROR(this->get_logger(), "Error %i from read: %s", errno, strerror(errno)); + return; + } + + // // print each field of package + // RCLCPP_INFO(this->get_logger(), "\n"); + // RCLCPP_INFO(this->get_logger(), "head: %x", package.head); + // RCLCPP_INFO(this->get_logger(), "pitch: %f", package.pitch); + // RCLCPP_INFO(this->get_logger(), "pitch_vel: %f", package.pitch_vel); + // RCLCPP_INFO(this->get_logger(), "yaw_vel: %f", package.yaw_vel); + // RCLCPP_INFO(this->get_logger(), "x: %f", package.x); + // RCLCPP_INFO(this->get_logger(), "y: %f", package.y); + // RCLCPP_INFO(this->get_logger(), "orientation: %f", package.orientation); + // RCLCPP_INFO(this->get_logger(), "x_vel: %f", package.x_vel); + // RCLCPP_INFO(this->get_logger(), "y_vel: %f", package.y_vel); + // RCLCPP_INFO(this->get_logger(), "\n"); + + if (package.head != 0xAA) // Package validation + { + RCLCPP_WARN(this->get_logger(), "Packet miss aligned."); + if (this->read_alignment()) + { + RCLCPP_INFO(this->get_logger(), "Read alignment success."); + } + else + { + RCLCPP_WARN(this->get_logger(), "Read alignment failed."); + } + return; + } + + // Handle TF + this->pitch_vel = package.pitch_vel; // rad/s + this->pitch = package.pitch; // rad + this->yaw_vel = package.yaw_vel; // rad/s + this->is_red = package.ref_flags & 2; // second lowest denotes if enemy is red + this->is_match_running = package.ref_flags & 1; // LSB denotes if match is started + this->valid_read = true; + + // publishing color and match status + std_msgs::msg::String target_robot_color; + target_robot_color.data = this->is_red ? "red" : "blue"; + //target_robot_color_publisher->publish(target_robot_color); + std_msgs::msg::Bool match_status; + match_status.data = this->is_match_running; + //match_status_publisher->publish(match_status); + + geometry_msgs::msg::TransformStamped pitch_tf; + pitch_tf.header.stamp = curr_time; + pitch_tf.header.frame_id = "yaw_link"; + pitch_tf.child_frame_id = "pitch_link"; + pitch_tf.transform.translation.x = 0; + pitch_tf.transform.translation.y = 0; + pitch_tf.transform.translation.z = 0; + + tf2::Quaternion pitch_q; + pitch_q.setRPY(0, this->pitch, 0); + pitch_tf.transform.rotation.x = pitch_q.x(); + pitch_tf.transform.rotation.y = pitch_q.y(); + pitch_tf.transform.rotation.z = pitch_q.z(); + pitch_tf.transform.rotation.w = pitch_q.w(); + + tf_broadcaster->sendTransform(pitch_tf); + + // Handle Odom + geometry_msgs::msg::TransformStamped odom_tf; + nav_msgs::msg::Odometry odom; + + odom_tf.header.stamp = curr_time; + odom_tf.header.frame_id = "odom"; + odom_tf.child_frame_id = "base_footprint"; + odom_tf.transform.translation.x = package.x; + odom_tf.transform.translation.y = package.y; + odom_tf.transform.translation.z = 0; + + odom.header.stamp = curr_time; + odom.header.frame_id = "odom"; + odom.child_frame_id = "base_footprint"; + odom.pose.pose.position.x = package.x; + odom.pose.pose.position.y = package.y; + odom.pose.pose.position.z = 0; + + tf2::Quaternion odom_q; + odom_q.setRPY(0, 0, package.orientation); + + odom_tf.transform.rotation.x = odom_q.x(); + odom_tf.transform.rotation.y = odom_q.y(); + odom_tf.transform.rotation.z = odom_q.z(); + odom_tf.transform.rotation.w = odom_q.w(); + + odom.pose.pose.orientation.x = odom_q.x(); + odom.pose.pose.orientation.y = odom_q.y(); + odom.pose.pose.orientation.z = odom_q.z(); + odom.pose.pose.orientation.w = odom_q.w(); + + odom.pose.covariance[0] = 0.01; + odom.pose.covariance[7] = 0.01; + odom.pose.covariance[14] = 1e13; + odom.pose.covariance[21] = 1e13; + odom.pose.covariance[28] = 1e13; + odom.pose.covariance[35] = 0.01; + + odom.twist.twist.linear.x = package.x_vel; + odom.twist.twist.linear.y = package.y_vel; + odom.twist.twist.linear.z = 0; + odom.twist.twist.angular.x = 0; + odom.twist.twist.angular.y = 0; + odom.twist.twist.angular.z = this->yaw_vel; + + odom.twist.covariance[0] = 0.01; + odom.twist.covariance[7] = 0.01; + odom.twist.covariance[14] = 1e13; + odom.twist.covariance[21] = 1e13; + odom.twist.covariance[28] = 1e13; + odom.twist.covariance[35] = 0.01; + + tf_broadcaster->sendTransform(odom_tf); + + this->odometry_publisher->publish(odom); + + recive_frame_id++; + + return; +} + +int main(int argc, char **argv) +{ + rclcpp::init(argc, argv); + auto node = std::make_shared("/dev/ttyTHS0"); + + rclcpp::spin(node); + rclcpp::shutdown(); + + return 0; +} diff --git a/src/prm_control/control_communicator/src/utils.cpp b/src/prm_control/control_communicator/src/utils.cpp new file mode 100755 index 0000000..97bfc20 --- /dev/null +++ b/src/prm_control/control_communicator/src/utils.cpp @@ -0,0 +1,65 @@ +#include +#include +#include + +#define G -9.80665 / 1000 // (mm/ms^2) + +uint8_t crc8(uint8_t *data, size_t len) +{ + uint8_t crc = 0xff; + size_t i, j; + for (i = 0; i < len; i++) + { + crc ^= data[i]; + for (j = 0; j < 8; j++) + { + if ((crc & 0x80) != 0) + crc = (uint8_t)((crc << 1) ^ 0x31); + else + crc <<= 1; + } + } + return crc; +} + +int8_t float2int8(double f) +{ + if (f > 127) + { + return 127; + } + else if (f < -127) + { + return -127; + } + else + { + return (int8_t)(f); + } +} + +float quadratic(float a, float b, float c) // negative side only +{ + return (-b - sqrt(pow(b, 2) - 4 * a * c)) / (2 * a); +} + +int gravity_pitch_offset(float v0, int min_p, int max_p, float x, float dz, float xv) +{ + double prev_dst = 10000000000; + int p; + for (p = min_p; p <= max_p; p++) + { + double v0x = v0 * cos(p * M_PI / 180); // Initial X vel + double v0y = v0 * sin(p * M_PI / 180); // Initial Z vel + double t = quadratic(G / 2.f, v0y, dz); // Time to target z position + double xt = x + xv * t; // Target position when bullet is at same z hight + double dst = abs(xt - t * v0x); // Difference between bullet x position and target x position + if (dst > prev_dst) + { + p--; + break; + } + prev_dst = dst; + } + return p; +} \ No newline at end of file diff --git a/src/prm_vision/pose_estimator/src/PoseEstimator.cpp b/src/prm_vision/pose_estimator/src/PoseEstimator.cpp index 3df1d38..7a3fa79 100644 --- a/src/prm_vision/pose_estimator/src/PoseEstimator.cpp +++ b/src/prm_vision/pose_estimator/src/PoseEstimator.cpp @@ -145,32 +145,6 @@ double PoseEstimator::gradientWrtYawFinitediff(double yaw, std::vector observed_points, cv::Mat tvec) -{ - // We assume 0 pitch and roll, so they do not contribute to the rotation matrix - cv::Mat R = (cv::Mat_(3, 3) << cos(yaw_guess), 0, sin(yaw_guess), - 0, 1, 0, - -sin(yaw_guess), 0, cos(yaw_guess)); - - // Reproject the 3D object points using predicted yaw to the image plane - std::vector projected_points; - cv::projectPoints(SMALL_ARMOR_OBJECT_POINTS, R, tvec, CAMERA_MATRIX, DISTORTION_COEFFS, projected_points); - - // Compute the Jacobian matrix - cv::Mat J = cv::Mat::zeros(8, 1, CV_64F); - for (int i = 0; i < 8; i++) - { - cv::Point2d diff = observed_points[i] - projected_points[i]; - J.at(i, 0) = -0.5 * (diff.x * (-sin(yaw_guess)) + diff.y * cos(yaw_guess)); - } - - // Compute the gradient - cv::Mat JtJ = J.t() * J; - double grad = JtJ.at(0, 0); - return grad; -} - /** * @brief Compute the loss between image points and reprojected points based on the yaw guess. * From dcdff4f3aa403c45e9297e8ad08577977fa4aeba Mon Sep 17 00:00:00 2001 From: Louis Liu Date: Thu, 6 Feb 2025 19:01:39 -0500 Subject: [PATCH 04/12] fix uart and add launch files --- .../src/ControlCommunicatorNode.cpp | 7 ++-- src/prm_launch/launch/mv2control.py | 33 +++++++++++++++++++ src/prm_launch/launch/mv2detector.py | 29 ++++++++++++++++ .../pose_estimator/src/PoseEstimatorNode.cpp | 1 - 4 files changed, 64 insertions(+), 6 deletions(-) create mode 100644 src/prm_launch/launch/mv2control.py create mode 100644 src/prm_launch/launch/mv2detector.py diff --git a/src/prm_control/control_communicator/src/ControlCommunicatorNode.cpp b/src/prm_control/control_communicator/src/ControlCommunicatorNode.cpp index 9b48439..f9bd0e0 100755 --- a/src/prm_control/control_communicator/src/ControlCommunicatorNode.cpp +++ b/src/prm_control/control_communicator/src/ControlCommunicatorNode.cpp @@ -195,10 +195,7 @@ void ControlCommunicatorNode::auto_aim_handler(const std::shared_ptrfire; write(this->port_fd, &package, sizeof(PackageOut)); fsync(this->port_fd); - if (this->auto_aim_frame_id % 1000 == 0) - { - RCLCPP_INFO(this->get_logger(), "Yaw, Pitch: %.3f, %.3f, FIRE=%.3f", yaw, pitch, msg->fire); - } + RCLCPP_INFO(this->get_logger(), "Yaw, Pitch: %.3f, %.3f, FIRE=%.3f", yaw, pitch, msg->fire); RCLCPP_INFO_ONCE(this->get_logger(), "First auto aim pkg sent."); } @@ -261,7 +258,7 @@ bool ControlCommunicatorNode::read_alignment() { RCLCPP_INFO(this->get_logger(), "Attemp to alignment."); uint8_t i = 0; - uint8_t buffer[32]; + uint8_t buffer[33]; do { int success = read(this->port_fd, &(buffer[0]), sizeof(buffer[0])); diff --git a/src/prm_launch/launch/mv2control.py b/src/prm_launch/launch/mv2control.py new file mode 100644 index 0000000..70721e0 --- /dev/null +++ b/src/prm_launch/launch/mv2control.py @@ -0,0 +1,33 @@ +from launch import LaunchDescription +from launch_ros.actions import Node +from ament_index_python.packages import get_package_share_directory + + +import os + +from ament_index_python.packages import get_package_share_path + +import os + +def generate_launch_description(): + share_dir = get_package_share_directory("prm_launch") + mv_config = os.path.join(share_dir, "config", "mv_red_bidc.yaml") + + opencv_armor_detector_config = os.path.join(share_dir, "config", "opencv_armor_detector_red_bidc.yaml") + + return LaunchDescription( + [ + Node(package="mv_publisher", executable="MVCameraNode", parameters=[mv_config]), + Node( + package='opencv_armor_detector', + executable='OpenCVArmorDetectorNode', + ), + Node( + package='pose_estimator', + executable='PoseEstimatorNode', + ), + Node( + package='control_communicator', + executable='ControlCommunicatorNode', + ) + ]) diff --git a/src/prm_launch/launch/mv2detector.py b/src/prm_launch/launch/mv2detector.py new file mode 100644 index 0000000..a45e21b --- /dev/null +++ b/src/prm_launch/launch/mv2detector.py @@ -0,0 +1,29 @@ +from launch import LaunchDescription +from launch_ros.actions import Node +from ament_index_python.packages import get_package_share_directory + + +import os + +from ament_index_python.packages import get_package_share_path + +import os + +def generate_launch_description(): + share_dir = get_package_share_directory("prm_launch") + mv_config = os.path.join(share_dir, "config", "mv_red_bidc.yaml") + + opencv_armor_detector_config = os.path.join(share_dir, "config", "opencv_armor_detector_red_bidc.yaml") + + return LaunchDescription( + [ + Node(package="mv_publisher", executable="MVCameraNode", parameters=[mv_config]), + Node( + package='opencv_armor_detector', + executable='OpenCVArmorDetectorNode', + ), + Node( + package='pose_estimator', + executable='PoseEstimatorNode', + ), + ]) diff --git a/src/prm_vision/pose_estimator/src/PoseEstimatorNode.cpp b/src/prm_vision/pose_estimator/src/PoseEstimatorNode.cpp index 1b0e35f..8a51c23 100644 --- a/src/prm_vision/pose_estimator/src/PoseEstimatorNode.cpp +++ b/src/prm_vision/pose_estimator/src/PoseEstimatorNode.cpp @@ -143,7 +143,6 @@ void PoseEstimatorNode::drawTopDownViewGivenRotation(double yaw, double X, doubl int target_x = Z; int target_y = X; cv::circle(top_down_view, cv::Point(target_x, target_y), 5, cv::Scalar(0, 255, 0), -1); - RCLCPP_INFO(get_logger(), "Drawn coordinates: (%d, %d)", target_x, target_y); cv::resize(top_down_view, top_down_view, cv::Size(640, 360)); cv::imshow("Top Down View", top_down_view); From 76cc000a250b85382813c2951fc73e14d802fc69 Mon Sep 17 00:00:00 2001 From: Louis Liu Date: Wed, 12 Feb 2025 23:21:37 -0500 Subject: [PATCH 05/12] change pitch to -15deg --- .../src/OpenCVArmorDetector.cpp | 2 +- .../pose_estimator/src/PoseEstimator.cpp | 17 ++++++++++++----- .../pose_estimator/src/PoseEstimatorNode.cpp | 4 +++- 3 files changed, 16 insertions(+), 7 deletions(-) diff --git a/src/prm_vision/opencv_armor_detector/src/OpenCVArmorDetector.cpp b/src/prm_vision/opencv_armor_detector/src/OpenCVArmorDetector.cpp index 52db195..72ea64a 100644 --- a/src/prm_vision/opencv_armor_detector/src/OpenCVArmorDetector.cpp +++ b/src/prm_vision/opencv_armor_detector/src/OpenCVArmorDetector.cpp @@ -55,7 +55,7 @@ std::vector<_Float32> OpenCVArmorDetector::search(cv::Mat &frame) cv::waitKey(30); #endif - // If we didn't find an armor for a few frames (ROS2 param), reset the search area + // If we didn't find an armor for a few frames (ROS2 param), reset the search area if (points.size() == 0) { _missed_frames++; diff --git a/src/prm_vision/pose_estimator/src/PoseEstimator.cpp b/src/prm_vision/pose_estimator/src/PoseEstimator.cpp index 7a3fa79..ee8e54d 100644 --- a/src/prm_vision/pose_estimator/src/PoseEstimator.cpp +++ b/src/prm_vision/pose_estimator/src/PoseEstimator.cpp @@ -155,13 +155,20 @@ double PoseEstimator::gradientWrtYawFinitediff(double yaw, std::vector image_points, cv::Mat tvec) { - // We assume 0 pitch and roll, so they do not contribute to the rotation matrix - cv::Mat R = (cv::Mat_(3, 3) << cos(yaw_guess), 0, sin(yaw_guess), - 0, 1, 0, - -sin(yaw_guess), 0, cos(yaw_guess)); + // We assume -15 deg pitch and 0 roll + double pitch = -15 * (M_PI / 180); + + cv::Mat Ry = (cv::Mat_(3, 3) << cos(yaw_guess), 0, sin(yaw_guess), + 0, 1, 0, + -sin(yaw_guess), 0, cos(yaw_guess)); + cv::Mat Rx = (cv::Mat_(3, 3) << 1, 0, 0, + 0, cos(pitch), -sin(pitch), + 0, sin(pitch), cos(pitch)); + cv::Mat R = Ry * Rx; // Reproject the 3D object points using predicted yaw to the image plane - std::vector projected_points; + std::vector + projected_points; cv::projectPoints(SMALL_ARMOR_OBJECT_POINTS, R, tvec, CAMERA_MATRIX, DISTORTION_COEFFS, projected_points); // Loss = sqrt(0.25 * sum((x - x')^2 + (y - y')^2)) diff --git a/src/prm_vision/pose_estimator/src/PoseEstimatorNode.cpp b/src/prm_vision/pose_estimator/src/PoseEstimatorNode.cpp index 8a51c23..6f681f4 100644 --- a/src/prm_vision/pose_estimator/src/PoseEstimatorNode.cpp +++ b/src/prm_vision/pose_estimator/src/PoseEstimatorNode.cpp @@ -131,7 +131,9 @@ void PoseEstimatorNode::keyPointsCallback(const vision_msgs::msg::KeyPoints::Sha } // Draw top-down view +#ifdef DEBUG drawTopDownViewGivenRotation(_last_yaw_estimate, tvec.at(0), tvec.at(1), tvec.at(2)); +#endif } void PoseEstimatorNode::drawTopDownViewGivenRotation(double yaw, double X, double Y, double Z) @@ -144,7 +146,7 @@ void PoseEstimatorNode::drawTopDownViewGivenRotation(double yaw, double X, doubl int target_y = X; cv::circle(top_down_view, cv::Point(target_x, target_y), 5, cv::Scalar(0, 255, 0), -1); - cv::resize(top_down_view, top_down_view, cv::Size(640, 360)); + cv::resize(top_down_view, top_down_view, cv::Size(100, 100)); cv::imshow("Top Down View", top_down_view); cv::waitKey(1); } From a661d7632ae50dcc958d2faa5166d0a23c14bff0 Mon Sep 17 00:00:00 2001 From: Louis Liu Date: Wed, 12 Feb 2025 23:40:54 -0500 Subject: [PATCH 06/12] lock_in and fire bit --- .../src/ControlCommunicatorNode.cpp | 32 +++++++++---------- .../pose_estimator/include/PoseEstimator.h | 4 +-- .../pose_estimator/src/PoseEstimatorNode.cpp | 2 +- 3 files changed, 19 insertions(+), 19 deletions(-) diff --git a/src/prm_control/control_communicator/src/ControlCommunicatorNode.cpp b/src/prm_control/control_communicator/src/ControlCommunicatorNode.cpp index f9bd0e0..0dce496 100755 --- a/src/prm_control/control_communicator/src/ControlCommunicatorNode.cpp +++ b/src/prm_control/control_communicator/src/ControlCommunicatorNode.cpp @@ -52,7 +52,6 @@ ControlCommunicatorNode::ControlCommunicatorNode(const char *port) : Node("contr this->auto_aim_subscriber = this->create_subscription( "predicted_armor", 1, std::bind(&ControlCommunicatorNode::auto_aim_handler, this, _1)); - this->nav_subscriber = this->create_subscription( // should not be twiststamped "cmd_vel", 1, std::bind(&ControlCommunicatorNode::nav_handler, this, _1)); @@ -160,9 +159,10 @@ void ControlCommunicatorNode::auto_aim_handler(const std::shared_ptrnow().seconds()) * 1000; // in ms // yaw/pitch and XYZ - vec3 P(msg->x/1000, msg->y/1000, msg->z/1000), V(0,0, 0), grav(0, 0, 9.81); - double p = 0, y = 0; bool im = 0; - + vec3 P(msg->x / 1000, msg->y / 1000, msg->z / 1000), V(0, 0, 0), grav(0, 0, 9.81); + double p = 0, y = 0; + bool im = 0; + float yaw; float pitch; float dst; @@ -177,7 +177,8 @@ void ControlCommunicatorNode::auto_aim_handler(const std::shared_ptry > 0 ? -1 : 1); //currently a bug where yaw is never negative, so we just multiply by the sign of "y" of the target + pitch_yaw_gravity_model_movingtarget_const_v(P, V, grav, 0, &p, &y, &im); + y = y * (msg->y > 0 ? -1 : 1); // currently a bug where yaw is never negative, so we just multiply by the sign of "y" of the target } else { @@ -192,10 +193,10 @@ void ControlCommunicatorNode::auto_aim_handler(const std::shared_ptrfire; + package.autoAimPackage.fire = false; write(this->port_fd, &package, sizeof(PackageOut)); fsync(this->port_fd); - RCLCPP_INFO(this->get_logger(), "Yaw, Pitch: %.3f, %.3f, FIRE=%.3f", yaw, pitch, msg->fire); + RCLCPP_INFO(this->get_logger(), "Yaw, Pitch: %.3f, %.3f, FIRE=%i", yaw, pitch, msg->fire); RCLCPP_INFO_ONCE(this->get_logger(), "First auto aim pkg sent."); } @@ -221,7 +222,6 @@ void ControlCommunicatorNode::nav_handler(const std::shared_ptrget_logger(), "x_vel = %f, y_vel = %f, yaw = %f", package.navPackage.x_vel, package.navPackage.y_vel, package.navPackage.yaw_rad); } - void ControlCommunicatorNode::heart_beat_handler() { if (!this->is_connected || this->port_fd < -1) @@ -312,20 +312,20 @@ void ControlCommunicatorNode::read_uart() } // Handle TF - this->pitch_vel = package.pitch_vel; // rad/s - this->pitch = package.pitch; // rad - this->yaw_vel = package.yaw_vel; // rad/s - this->is_red = package.ref_flags & 2; // second lowest denotes if enemy is red - this->is_match_running = package.ref_flags & 1; // LSB denotes if match is started + this->pitch_vel = package.pitch_vel; // rad/s + this->pitch = package.pitch; // rad + this->yaw_vel = package.yaw_vel; // rad/s + this->is_red = package.ref_flags & 2; // second lowest denotes if enemy is red + this->is_match_running = package.ref_flags & 1; // LSB denotes if match is started this->valid_read = true; // publishing color and match status std_msgs::msg::String target_robot_color; - target_robot_color.data = this->is_red ? "red" : "blue"; - //target_robot_color_publisher->publish(target_robot_color); + target_robot_color.data = this->is_red ? "red" : "blue"; + // target_robot_color_publisher->publish(target_robot_color); std_msgs::msg::Bool match_status; match_status.data = this->is_match_running; - //match_status_publisher->publish(match_status); + // match_status_publisher->publish(match_status); geometry_msgs::msg::TransformStamped pitch_tf; pitch_tf.header.stamp = curr_time; diff --git a/src/prm_vision/pose_estimator/include/PoseEstimator.h b/src/prm_vision/pose_estimator/include/PoseEstimator.h index 6a2380b..0ad2d99 100644 --- a/src/prm_vision/pose_estimator/include/PoseEstimator.h +++ b/src/prm_vision/pose_estimator/include/PoseEstimator.h @@ -44,8 +44,8 @@ class PoseEstimator // Class variables int _consecutive_tracking_frames_ctr = 0; int _num_frames_to_fire_after = 3; - int _allowed_missed_frames_before_no_fire = 15; - int _remaining_missed_frames_before_no_fire = 0; // Gets set to 5 when we have a valid pose estimate + int _allowed_missed_frames_before_no_fire = 150; + int _remaining_missed_frames_before_no_fire = 0; // Gets reset when we have a valid pose estimate std::chrono::time_point _last_fire_time; // Validity filter parameters diff --git a/src/prm_vision/pose_estimator/src/PoseEstimatorNode.cpp b/src/prm_vision/pose_estimator/src/PoseEstimatorNode.cpp index 6f681f4..fea5987 100644 --- a/src/prm_vision/pose_estimator/src/PoseEstimatorNode.cpp +++ b/src/prm_vision/pose_estimator/src/PoseEstimatorNode.cpp @@ -9,7 +9,7 @@ PoseEstimatorNode::PoseEstimatorNode(const rclcpp::NodeOptions &options) : Node( predicted_armor_publisher = this->create_publisher("predicted_armor", 10); // Dynamic parameters - pose_estimator->setAllowedMissedFramesBeforeNoFire(this->declare_parameter("_allowed_missed_frames_before_no_fire", 15)); + pose_estimator->setAllowedMissedFramesBeforeNoFire(this->declare_parameter("_allowed_missed_frames_before_no_fire", 150)); pose_estimator->setNumFramesToFireAfter(this->declare_parameter("_num_frames_to_fire_after", 3)); validity_filter_.setLockInAfter(this->declare_parameter("_lock_in_after", 3)); validity_filter_.setMaxDistance(this->declare_parameter("_max_distance", 10000)); From 4f2ce8c2e74ab658c02956c7d52538e76718cf2f Mon Sep 17 00:00:00 2001 From: Louis Liu Date: Wed, 12 Feb 2025 23:52:48 -0500 Subject: [PATCH 07/12] print real msg we send --- .../control_communicator/src/ControlCommunicatorNode.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/prm_control/control_communicator/src/ControlCommunicatorNode.cpp b/src/prm_control/control_communicator/src/ControlCommunicatorNode.cpp index 0dce496..1b69381 100755 --- a/src/prm_control/control_communicator/src/ControlCommunicatorNode.cpp +++ b/src/prm_control/control_communicator/src/ControlCommunicatorNode.cpp @@ -196,7 +196,7 @@ void ControlCommunicatorNode::auto_aim_handler(const std::shared_ptrport_fd, &package, sizeof(PackageOut)); fsync(this->port_fd); - RCLCPP_INFO(this->get_logger(), "Yaw, Pitch: %.3f, %.3f, FIRE=%i", yaw, pitch, msg->fire); + RCLCPP_INFO(this->get_logger(), "Yaw, Pitch: %.3f, %.3f, FIRE=%i", package.autoAimPackage.yaw, package.autoAimPackage.pitch, package.autoAimPackage.fire); RCLCPP_INFO_ONCE(this->get_logger(), "First auto aim pkg sent."); } From dc0e883b8728da662f6b6f64639ec98932d8ffa2 Mon Sep 17 00:00:00 2001 From: Tom_TKO Date: Fri, 14 Feb 2025 17:21:56 -0500 Subject: [PATCH 08/12] fix angle calculation, remove uart read due to issue with read function blocing --- .../sdk/tools/QGeConfigTools/AppRun | Bin 14 -> 520787 bytes .../control_communicator/include/messages.h | 2 +- .../src/ControlCommunicatorNode.cpp | 30 +++++++++++------- 3 files changed, 19 insertions(+), 13 deletions(-) mode change 120000 => 100755 src/prm_camera/mv_publisher/sdk/tools/QGeConfigTools/AppRun diff --git a/src/prm_camera/mv_publisher/sdk/tools/QGeConfigTools/AppRun b/src/prm_camera/mv_publisher/sdk/tools/QGeConfigTools/AppRun deleted file mode 120000 index 2752bed..0000000 --- a/src/prm_camera/mv_publisher/sdk/tools/QGeConfigTools/AppRun +++ /dev/null @@ -1 +0,0 @@ -QGeConfigTools \ No newline at end of file diff --git a/src/prm_camera/mv_publisher/sdk/tools/QGeConfigTools/AppRun b/src/prm_camera/mv_publisher/sdk/tools/QGeConfigTools/AppRun new file mode 100755 index 0000000000000000000000000000000000000000..23669fcc177055df633c62b3860295b710bbb205 GIT binary patch literal 520787 zcmbT931Aat+Q)}-6+{{l74ZsKSHLSNw6rLi0)-R`rnD&HYFpZr7TPAJDHKGl6qHh{ z6)%?6wW6+wSH;yuyvm^%$*^wK}$Ra9`pZuCx#Q-#zx7a!=Kr>nA}e`?Wi+Hk+<%cUKvpKmQz)2V+dik;8n zdYtLd&UY*>W?lcBcpjs2c&hrTUx(!3I>!TQyp9Ld>-0~LmVW(H&mZ!Jcdm9mH_k-_ zcHu)A$A6=r2#c5J%U}_XSNBuzx4PeW*7eUzj$>5xPyM=Vx=y`9J^x34ZCZe-+WoA` z#dew+Q2*5H;i9tAnJFVKDl596thA!4`hx1zlnYWuTv+M5Fp2Yx_z`x(lxZA+UXBBZ zkmmmMh7I6+?&XueyL!zFcQqGJec|r3hi`L!{czqSy7&fqBc9&$_I&Ocyk_9(sQUi) zLERrv3Qz3r7-t)kSTn>GH)Ko?w`Wkd$)D#dpAJarrrh~Ox}C1=HRho=Yr51p2d-LL zkgjyEQPy>_9qzekiQT;@&ed&iN^$P-HREosZTv7}l}*`LQ`6;qWk_z^Emzv#$lv;G zw*to?rKZ>Ur*@w{`|0PjT2#|SX^6aTqWjd)TYoJQ$F+34SmP!1c`Ln_(z{;M^lNT2 zu&y^)=(h{~4m!S5LZ7c{$GG=vblgJk4MNk?q>Kd1LTdgJvU`usvW27f7z!Cz|});{;sXS*Q`!hJ*90ZspwJ`Wng93uX& z(0&ldKWfK6X`kp@e%6kUXrH*pFLeAXy?+xLbon|e&uOi^3w_4XyDPoB(Yrgn@#;aJ zJ+=XdS7m-*eFoxEi0@?MYMHU9eVe%NwCoA1P5 zj`e!xg5zG>c;8dI9^Jb4;=Enw{Cn)huWtXW|HjIHopA1rd0zw`wO_yWq-j?c-aPNx z^^=~yVtUQhDLr^y->O?W$A+Et!S!vuya~Zg{ufU=_5K%Ko=3-@IqTTI=ZDVQ``E;j-}?LJ zvz`e2?H{+yzOeCvSABzej>#SO%$~nhv|qHj>EJbE&$!^l#{KW?%pE@Of)BQBKl}4u z_xxw)W9L2b_NctV#LL(JXZgabTfVvRm-xfV50!&HAN0@$<$+V~syqJpmA<}@%sFk) zWyRfp>Hkjqiw)oP&3fhi)b{mXesSxtrCB*2?LXifzp?n-S8k~P;*_)tj$gdFblhis z?mXKz_1N&YyT4L7?dgd>_g{EpL*vlry&*@*JxBAqpMC1nFCRSa#TVXPw&26Z#;+J~ z@=b*sOMhZdEubiJb=Y>}{ zJi547n>+2qL;pD7`(^p1bqAWt27Pc~z4whH=VbSLwD;IdXW!r6$T;oG>n8O7eDjqb zHm=Wm{_5HXYQll!oH_R#I=5)gZx=V;v+k$opSsk0 znx}5U85F6COPL?ArC;K7aEk=U;i_tP2ySrL{djZr_%BQa_mU`L+GC zHw}E|s=b%k-nzQ)Jzw5eeCX02{xNc$v|HoxSK}0=pHU>tCjr>q(cH>mOL?KO`y22`2enkzpRsJC~a4Pxdm`pQXsn%59<3TtAft zv1Z{U z&l-#N`;tZay@}@W7h06tzb`fqe;;Ma%&xw*xbKNw&BJe_Nsw7Q!_PO@&!1qf_qC|s zJ*np9w#6d-2khqY?{%2#SJI@r#t$ zU2l>8VYF~zmfsYM^1tOA^YCjd{O~}F{^cQya#(2*epRx0z4x`SpNAcjUUA#c; z(X1RM&_aNjeiu#n&2*vbA2P_*DU^XE&S@e7WqBzc=LGrTKJ907Uj7w z%{-pL7Iw11qJCetu#*WE`VWeEy-%|6lM5{T`7IXx{t*kmbl^nu{N89Wj>@(eFI{F~ z4{I&T?NyoIlh&opl!d=`UxShp({kGbI-7;{DO)@zh%A$J2VCS-<(UMLE1^ zVduSR{nM;nd`kH;i+`|1dvCJn2T!-K!&5El@h6LM(JvO`hc!;~^q**hT4Odd#sXhmjWdJ!a95Y@)=NrDudic|LcldH5U)yXs@% z_Z$}Emh;I!o7qV&jZbJO(&^RBVxIW)nda$y+oC*gu}IH17Iw12!apn=WPab7c4AikIaKmgM4evaEy{Da#dtum(BHNghkRzy z?q0L-GaINp&Fp!uMZYljbo1~hoNTV2XJOArEb8|Xi*~xwBAzQP@_U>`epj7kp3c8p zq~~4Q?=mZ&IE(T>&Z58TVqu?8xy3Onr}l1^&ZjN(^V@ z$v}&A4zp-qJ?N%p>FI7^&j}Xszh<%SvDCt@9)%`4_XCS`cD3*WcgLB>|CmMm zS6kG}MvH#oB#ZuKyG6ZFGELjvgBIh-jTYmIM=j=GH(Sh?cU$PuQXz{bo_l z=@#LaSk(Ki7VYAI(>y&hEXJQ3EbQSEi}72Pg`am>wD%bn`T`66af^J7vIxJ)!rm^n zD2EaY|L?ZwA78TY&--Z|z|0TWEc&T=7X9fei~8MUksgvw?f)7JKm6%np+*>iq$W{^G6y=JEK*uFS>*=@xeWjYWR< zTeQb(E#?vDSk%h^i*hcu@T)&q)K~kt=J_qLxbKp#=HWX|GuKNj!Y{P&Gxu7w$4f2j z@Fa_LK4{TD4!0t+vQl4+}qbl|{R_z+zqE4(gB0+Sj`l{?<<8e6#Q_i~Rm(F^B^eIkv~@-)iG|KPpbV&eZ&#%)y7#fCr2 zjqu0QL#0&U^rC9z*POv>JpQ*`nxcL@p|$J$4`cOX+PKSa(Ay|#_5<(7hR@RKz3KB< z{c~+x)V3*Be?bf1wkuY@Do%~xZb+xUzpA_5iw(b2OMizvuPX zc#^d7mB*0IPqg^k-i!_3O{@2o)>wU{mj1TSV)Zb!M=rOIWAz1kKV_)LazzcF|7mRa zDTB0f*b}S2a*`Im!LHspQ`I{R`MOSPzbyuPYwWIu_wS31|08YO)ncfZBrRVphVs0F z`W+j68)H;+u_9k@XyZMb!JhN9@~<(ZXKuWjo)$y-Eamu5>lA*M7{-McGp2utbj(=xt{C2H8n>WYmc>Wmn&}b;nu3CDOy|LlX z>ZyiT4CQu<){gSG#fCph?QVAutsD&HHdGr=dJO4VuGy8{ zP+w=AsK(iwB+s@`F^@6~oyZ`u(XPd{xPzIkh`{&%fChCYgIk56fK)oduw1=@JE*>GR4X8)}Q zKQ>=)*Kfq$_h4T&oizr({kK7?Za38LgdwWlW=Q|Zn(i>P$KSMa_8a`eTReU{PFb-r zHa(|m?Yhxm{|mM9_ZZTdr1f8o275U16g8b5gFbq&syht%8cKsPw0GOS*!2AEOjUOo z%K6T-RlU*B&;CubAHP8lXzjY$pg*aVv%_%TllAs)$ZwgJuV#ZE-l&bcJcj<|6TSQm z?fnF;-ff2RdH6UjzlM1JtND!?R}x5VaaBVC4eQDf-Wx(?HHgI#?}ff3%bIX0fjiK?#bi`6eXSJiC> zd+ww6g9d*!Un{pZgMEIY=XdiMx_h)g9Xv=&kD(q<)Y92zD2EiiUOtFT=MJrY?S}Hd zRBMkNhIo$G;<3FR8_zt=Z`k+6>Q2p{w|yF`zo~_9GNk`8yP7YT!LCsF{gl4S7p-bJ zDB5eS<_8o*eI;t`w8oIH3e6vS4CV0g$?AQZ4CQ|t-3RsFWXSJ+%`deW`psIc{QZW0 z_9d;IHX8iHY3Hi(cNp5mb3IhO)zBV)*5@OJdB;uKc%a5`-|LUp(r+k-TQonAZ?I2% z*AMw^GsF|Gm78Lym#JF+)ok!%&&Fx@HN^jbmi`Wd{qNB1*=Fz?Jx^8R@f+IdKehb2 z4En$HafqRO{91pSZ^+jJTKlar_(_GnH=G?zzOuAvmN!_5?+Yg@d6~JB^NPFy@2t|w zpf`{^d2E@l!kb$#v&^gH<;^PhRpeC$3j)EsJSA`9+`Oq;xUppgm6hH~^>XuzXG}@U z&JB3ISCo3^IfobdGK1do%B+I4msqMoRYhvVvKanNyOo zDbbU>^Jn@B0!5R3MWw~1-av*{655T27X=DtO{VzuVi=J6Q9%P1Y#b+ZYorNU@6|?jkrDXFR)iRFMwX=w7aV&=`%9x5; zrgVGDGAoL_)j3IdQzwngzJf~L7sxE-d{6*SRb|PTs$kGpG1i&k(eI{Kx0cD|Io|nG zy=C5lO8xF>*;Fo(1WXczJz}mmK($;@c6o7erB}~kG(bv;w}5P3ucU}|IMf={jER!P z6$&(%(ePqlVO8bjuw>QnoY~`{L{dX}x?+s4S~YiLp2)Cs=2L4c&kYpJ&m=Q;j-XUZ z%k?B@!>nTpz!~sXQkCg#Ii{{-)#vRmc*ORJNp*Ikd$l;X8D@!YieDjPM zG2Sqx+#3v(7E+5%QeztDom*Pyb&ljas6f61LDV~FzR7uAFpn-RAQLR3i>U=f9L|Wb z&`LcX%?Fxzo|MuGe--()V2Q6NyUH8TiZLbADC3@!Olvh2rV?%4lmawQ-BCqSS4mED zQlXl3)mELUx+zu!D<>BO$eC4Ul+p`D~c9^q*EO`QF3XNfORx`4W> zf-s`$Spd}PTeyqmpky%(y5bDv#%%!lon`?$Hd70$el&=4vQQgC@A-4%v9@0 zFBGF+jb7rEO-OexBeO*VVo??k`{2pZu91vB=5#8%{3$fxARC-JwxqPINKFqlil~LB zQCijF&M2Ldla~q`nd&R^T6Ah?LOH?tW!@Zex*lr-SZ4xu6=ufed6fH#4S*qX43= zb!16FrQ2INtAsp!fHD~@(S{Dfq8xKeE2|31&{QZl6j`+Ek15UH?`d_*ORFsL&C{#T zk)5LxqKYYY&Pa~Gppe=zXCyLA{GBLrGouEh#Ta#xFgi{HjA7yS!2ZQ z!stfCdSV)afh@_k~kXdm@yn)_y6RdK7C&|G&BP2uwS( zyamyDXEM(_qY~~Ss$e9IxxLlt=o#d!B&JJ(-{p~z>ZhU}S|7gXeFN&BIyX5_?qrl= z0A&~u>#;Z;)IuWj4^eo!tG1l*##X%fxcU0)e&B zg~-APtahl*z4HvxiLO%fS5&_GpqA&`>O74aL@^C-=yti8`u$Whh2Q$tZoqu8yiox=DngCF8l4<O*vkFL7;%vT-bh$2_9MGoy)E~cCja!haYmvMYoF`c$keR z)iJc*ej~;;f@71*RGlJ=nWdtHBK^8P6f>K3aX~~Kg%cegEwg!im8HCv#+ef5M{+`9 z*OEGAOm870)FCL}L)R>d3u_-*w^$maA%CHXzQlGrj$Y!js ztg5^sc1-)He80XDLB0C#t{SCKFG~}0;av2T^1O>zwWgrUS66YS(gGaKhmj+*vD=^P z6ZGK)cY0TpR+f^#QzuiZ$r>kiq7QMVM5oSjb^lG0K*dnu&$JEG{ETdU}ohwZ=sL63Vi^gXDLNrc-Dh3grK z*}+s=kdPCDBwCih0*<=Kf@aN2KAo37%p8=nu*^rZc-okvjyW=fnv&#8qOs07y6!lS6Sq2wo?EYPnqq52m zm*y>sE*NM75i;Sa1x2Mkt1TX_uNwZl3%s4u<3x@)MHnxu{fBNHyu<=C)%GFCvqecY z4|U{9i<^<|SY6!eG;qOfsM={!wa807v0+%Otw}~2lD2v=!Rw<9fIz7}7K&RH{+)L^u&$o+2=7jsD7Nu>UBx$odX5=!~cl=KC|J|ZD4i~9#J8uz+i3%!4U4PGw z%vfk-t<|#CO19Qq3knOpeyz*W?Hj&;ql#L2OdUGZb`;q}qCIS}IA+%J{&)YJ_B-8S zw2zPrCR_oX*9e`-v^z%)ew>#!oPG1DHN~`8Z9ImBWKU^zd4ak`p&rI$8pBO(?G~o3 ztyf2THdr=lf$T#p0T~v@v{j%^!w51J_O@mxXxeSI))FlQXA;|ZX2dQ#?T#8(KUB+9 zmoSh?k&EA7DW-NEU3@p%cdUbQ4(H{E@c~~sTr>@8j7v%}{fpCCK~D$Q6(cl!>^yO@>b8jt1ccul>sdk*SW5f?p@YV|%A#S3z7FqMZKVqh6 zu{x+af7k&oB`b=GF;;-~{70)yF{5T}D<6}#vA!yr-^WDPdBPJ}arl33HIMMoo{&D~ z(md?%FGh_}_X@d+sKfC4X=8ybogclJO8e4ZyT`wNi<{fFMS zbDuN`(N)LV98an}sQ~S%^b5MSAw74>Y6|BUtJIN@-gS6Akob5kye4J|s!* z!Wl=i(UxPJ_{BOy+EDTNC+iRPne@0G>QnUdJS~*Fjj_3~uo&~_U!3NnOp}Z{e{W+S zqk6Tg_%j2$KYS`I;xL^fN@6$C+2@+2&QVCq)}`um6_FVt3Pz5%Men7PhHsIrx9aU8;pxlxmQr#=g=O!HvkulG)5wFU=?)=oSe2k5H%ngrt)qmKmJC~ z9F3XZc_jP44X^&((z%|tLrn?R!DrrQHX*vx~v0`BCQh#^46?t|+ z-|~vgon$|&KFd3ys#JT9cg7TTAA#He=Orb3On{!Mgj3`N3U$@R!J;Z4$B_r*oKCE6 zWR#Va`l&SZ4Nn9S5z%5a`48;g@e$5a+SIuTRbv5mt@QOFb&)5%(oa*6sp#9VgiqdU zc%Czro_nmQjP!YYA|^4Belmp~x|)?y?T>gX${jjJRW;0;I878lU9Fx_=9^hirlyz^ zs_udn&W${oq?VIfYTU2$gOci83Rmbk(^I2Hprs)C%$Qa_dZ}96vUQ zNY&eEf$;>2e1=uMgC3K9|Cl?{<9d<709NJGGRx@+1!_Dr89A{Y7d4_@doGl0&^k;B|7aKU*Q~YaKucSLQyP~Ew`^Sm|j$b2Z^E&#nA&# zV<<#44dl_ZNHei-RZPyoIh>wEYVu^1Fb{p#9=DrBD~VdtwQ{AMi@^Mm72aTZK_xx;!)c1SDMf)X z+K3!#WAseCei;YsTn@TfnU>KA+9O0=;+~N;E16v9@OgpKAU~jwD#2r;)tw9hcQ(%k zm##WxGpQnR)}k1a=uu5B0rTjid5bBaRDZx1^cDKFPA9g?=%$)Y#n>J_~pw%j-H2Rk+QuSS-sEKn39~=>EAS(>aFxu1q#{olzJwWP$ANPTy^?oPKUReEN*fEW>3+1Gr~|O81NO6 zW7F~*JiXk}58(o5S(>mu|JFi*cU7ZE*~N^OJBXg(%- zCV4KN^A^dBeO4NqSkcPTo92jl1vEeBF*P}5UV~(FbrgB^TEIG0xi;!nv*jEf^i2yE zr|MoqZ>ltYQUeU9$NMv?OG}gKfzAT{iiBt>!;A3!g%bT@&-l3>GN}<<*`B!>#AFkZ zhosdciw6CN-+Pe$Vnks99DvMuv>HajH<1HSOEQ&K>ShKC0`o_d`3kg+D7}>Q@v_e9 zoGn_KYD2}YH(DT`=8V*Or&bv$q}1}NvS4XCl@z%z-Pt*^d4V9y=ku!zP9h@ua)@ej z9HcU8J5+P<)?>+_3f1jR98nw1qGp6g#8pp9BSd<{TilU`gS z=}R~jc;Fhz)0*q>JRSv)pn)My(ZGjDnW|l!Q|80mOMkLFT4=nJ8S(5% zLGFEYcc5F6GZ~$fG&a49(i3TTW`z#1wmc1{@AiK{!YGJuXn32 zEOc^nw1rYujBX$)={kDsjlPXhrmf4lXxEb~U!3(wpP0z;jM>OM~-~faL4opreVJjYuPnCZ>moX>XBkmxDyN_*HAv zd;ds8)F>-`WwbIz^{n1OGkRwVTotChlzaNZ9<@>K8e-$u?S?MR%@l?Z{n`i(Sk!XR zdkD>^rNGeAD+^0YBc4ec4C%F>QeIi+_4-wBso#iJNbpo+MvSk6-)A@K)O_76T6NCw zsOxVL2ap`}(R3xlGgIs0bpMZO6^-qG$CpzNuBMtw%U?!wAFfSmJC?PFNk?RtiE1L+ ziqs+6|KMQtd$W^=6^X2;WKX6igsSyg)%(#H>o89vo1&*6NRzpWocZ+qrE0eNNH?oT z>FnIruB#$*o~zJz&$Ov(9?kAxJJGhDT0sp;?O`H)4MMQv#*U~qk`mrFGPqJ>g6qT> zERqiGJ2X81riVp&Ul>8@DHe=_MtaK%Xu%`Wk*M{RQc+btliaMq63Ee((_@rsHJXdTAS%u1~js9)?%rB(r_$KFRPTdfzOfsS65sm1zNj(9W|vlE(9S~&$nX>FXR zw+;ScNM=PT_jQ_&NE&|Kvw`kAC(_+S=UJ`VYpZ+1f6@kITS(=`g4thrd3oe| z8ikm*5$|=;Vx`_q%d8k=I-!v)gf7tiqod=bLTzZQRhldW)gHBiPa%8#6MjMq zP5nH53&Tr`Df$>%?FF>SAzKdJiYozQdt-%1XK_x)O!_5^3U!JX&Apm7)oQ8gBW*uw zX;B}ow`;CUwZhn$=%yp%8d>S5uP6tL;Yt_aM5K?AeOio#l~t1EiMU44%%N;*Ob|pQ zv&&UMOHuwHuLof%%AshGSB?<_{ZdFJ9$Hf9*9GQcBu2jxq6eUd_wowKwu4^7HRK6` zu@a3R0(sP(2WeDIF?a)k3SXY?d}D(`o)ata)f{PYVMVYka?)_~+4Qpqk#n4SzEIDB zo@}*?RWPv%`eMW9sXhR!bCtoO!t>5UiKL*^aljyjzG_Mf9osx&V=V9kxznBdwk2;{jlGx~G(qxq) zD=NcJ28jCv$e3vYK-#S8>O5K(qzCh9lQ%d&Z>~d4`UZB8#*Dt=qJsH! zFEt)cB;CKTB!Fb7$wy|j-_0qf{U4>WLd`28q6+gC(Kv)+m`QfPJt|3*ip0yOW=_bQ zauHpvOpkq`KB?_a@Q%N-ioYF;Ck85ta_Eb<^s6K6LTI;U{Jd#=Qthlwg2co?PX$yI z(a3?n4Q>^OG0=puWAlcSTbPiQIc98L(uL0C=;4US;qVKi$I+uC`n@5(Zu)eJV}vqx z`tymz`c(h*)RbK}Tv@)zE5u$8$(sQSYMX03q~z<61Q}J-7_IQksx5^}e__N=8qmo`+~j^y0Hf zmwpApD#YG#y*!&S&fypllgo{<#kd8MB^3Q$J)*IhA7pLyKos?|MJ zos589UFcu_c>IR4`u|Ju{AE7G~A$_&nM}gJMX1ms!LF^=sd2uo4K!Y zrN+TiOUcmtC^I$gUs_7PNOzo4p>fqfoR3$kiSg<}){#oTEs3}s^bQVP9t~F<2!W-0`yjzwD{EU-9`8=%D@Ya z@pX$iPd|}oxL?i(&0kz3fA%HCkSU*vl0|=zZoK@rn(LmW=DMTKT(>PV z*E=lq)_U{sj@!+3+a2b*|4wt=bC0?1xYt~_-Dj?MSm=!_&BHrHIajJh%zs^?ob!d= z^q?9~57MMwBf?J-;qyhkNZlpsMe24@{!-5uTMQ!i%6#ouLyhlQKZu)>`m%TBE0@vuehvDgpbih_>hR-F6>t7iiqa{ z5#A;2S?V=H51yjBSPBvH^!LT?c9uNL|PLT?s&-$?9=vQFsq6S9$4i_rDH z8Yj03oqifO@@f@2en(e-?GpMgB0X(Fr=P}+yh1{!pB9h2I)r|5L{*f-LZ_c@j=mm> z+AaOWcjOf>^ru96Y(l4>-i^El2%UcVIP$U!oqp;$@){y^`d=zUUJjwtPnt(wsY34| z>enT7`swM&%Pn;JY2V1pBXoO2Rg~#Mzf0sdU+9BG_!6NH7P?>PXA8Yr==77qkynk- zZ6aSwg?>&XH2r@$g#M67=L(^JDfA|xpDW^7E%YHmZx%ZJ)OqB!PU!dzX#Le9^z(F) zKDP?}e4)1r{Q{xy5;_g9Bd<20UldUlB_wpr1N2vi&}mp7c^wvdQbeVLRZ;t=pNNmV z;)OmUqSAO==*dDKAoQc6eC$FWDZ&pC`kA8M9YRkP;Zudq%R1UQm(UN3`?`fbO2p$4 z`o%(@F7!);o-g##LN5{er9$@${W76f3*9C38lk5PeW}pL2)$A0t3`fS2z{&w-z0RJ zc12#Rg`N>n6{T6|geBJ?{%_^m>( z65(5gK3C|wguY+I(BCZP`y z`T`M;UFdPbPKF4*yU-m%zh1S?Ko*eVx#6 z74f$SeW}p53cXI~twR5gh<}&R+l1aG^kpKRkkD&I_zt1hi|~hqew)yhe@5*;L6lFt z&>KW}o6v6;`T(KdA#}UYkBM{+5qhHt?-2TDB7CaQ?-b!(LSHU)x6tnrx<}}ZBL3+@ ze_!bNLjPLmB|^Vj#P1jSJ0g6w&`%WQTqE>*L_AA{ey`9Qg?^vVR|tKD(3^z*H=(Z< z`bwcU3;i3B{&hnCy9nPR^!tUrRp<{2y;bNtaV9}(f>g}yGhnTj(2w?h$&2$nSKaZxZ42g}zznB|?8v#N!wG>mq!$(BBYxjnKCU zeW}p53cXS2Zwh^d(6qWlS3H==rzD4No3Vo~4-xGSP&|8JR zOX%B$-X`=NLJtZ36Oqmiq3;yo4-0*_2(LUIwg2};_;{gzD#F`@{(%TTKqm2>m+|k6q~B3w?;t|0{Hd(EldlPZjzPBD_oJKMCC}^ut2;2>oZFPZ#YKNot3(2ofHu+V!7U3nsE z|M5bP7kV$D+l1a*=mUg)oY3t;zg_4_%E%g3EuMzr5LSHKMlZD-?{+rNULO)07ZlNz0 zx<}}L5&CqYpDXlyp`R-1t3>ESM0mf@9}#-B(1!}WM(AgV_?HTOuL$2L^nVC_h0uoy zy-Dcj34OKD&lh^L&@T}BI-&0qdW+C66#7=7UnKNap*w`WOXwd8y-nyVg&q>RQ|KK+ ze@*Czh5muim8YWipCt5np$`|jP3R+pK0xTnLbnS&Uexapp{I!O4xx_}daBS2;(El#<=|b-!(wQ&xi$(YnpWHw%5N(ANq5fY4inK2GRch2ARkR-tDIeV5S33%yO~6NDZT zx?AWSLQfRsd06O~BE0f+)cz+5JznUOgl-f1WT6ib`Wm6zg?^vVhX{R&&>cd5M(C+R zzg*}pp?iex7J9bOJwl%<^yxy+5qiGRbA?_a^l3u(3;hbAR}1}0q1Om~y3m&jeY4OT zg?@sl-xWf?N`!9``V6737W&mfZx;Grg}zSc*9g5u=r0O=tI)3%daKa$guYAY?Lu!8 zdcM#@LSHWQ4xtwa{jkty3SD_7YX3J2JznTP2;C<1LZJ^3dXdoWLiY-Nh|r6L?htxd z=&3@VC3Kh2ON8zgda2MoLZ2=4=|Z0)^n9V03B5$<`maJ?C-hxHZxMP=k|mY=J{@dlo&i1sY-64ZJ`=1kPXwO@?)VM)9|N|7+n7gz2Z39elfZ+)EzHBfXM>xW z2ZIyAP0Rzq=YSiT`+@%gu3_#CJ{Rm~jsp(?=QAJqgm@^}!+Z!l4D4dw4?Yj;ShhuLnE9t;}n|N#GXdHQ?dkX69Ak5#T1~ zmEdG>BlB`_3b=-O8F(bv&%6kn3eIO<08RsYm;>NZU>Eaj@Wo&U^Gxt1U_0{+@My4& zc`Eo)u);hMd>Odo7p{M>3*5#$3Y-pZWljQ*0k<#@1CIqaGYeA3O={VBQDL0^6B)gC~P+%saqSzzXv= z@a5o+BV7Mr54eqaJvbZO%Dfgl72LwS2Al(KW?lu(1vfFT1WyAuGA{>T0j^MF%rn7%1>2ctfUg1Dn5TlT1uM)G!Fk}0pSk|Q z`QSF@QQ!h_D{~TfCb)%p7`PDJ%sd!e1a4v;2=;;-nfrm!`GsqkdxK|z{mgM-bU@*J z<|7{ymx4XahrqMJF6RB&b%934z@Ax09Sw&=51gfxZ^O_KiCg$V_pxw z4&2JT790S#Fs}huf}5FFfrH>C=9S|qXo z7l2*Nv%%Mc9n3Sq3&D2g8Q>ehHs-0|8^H?mMDR`Ej-R;x!8PDE=276A!L7_m;6>mT z=3(Gka5M8@@M3Ti^FZ(ta3ga+@GamP=HB32!G7jA@KSI-^O0S|bzl$kA@DM=i+Mk| z9_(P=2fht#XWk8N0Na>%fNuvY%-g_sfIEKV`Uf|H+nCpb?*z9puLUm$w=k~(-vw@F zUIo4z+{C;Rd=I#hc{%uAa1HY^@O@xE^CIvHa6a<_@ZZ25<^Xsl*u^{>{CBW}c_#RN zu$_4Z_yMquc`EoHV1;=i_(5>T4_yD?CU6_`DDXqzR^}w|DsT()F!00RX6C`*N5D}QSxuLkEcANh#*aj=K^5O@vP#k?Q<1lYm65Bwz9&b%A^ z6xhbR1N<~tVcrIQ2Hf#qu77YdxQ%%|_*rl(^IGs)a0~Mq@N?j1=2hT-ft#3Df}aOB zGA{?e0Ip$P2L3nL&%6k{4xG=t0Q@4@!yEvw2fLVOgI@wWm}i1t2HTlufL{UIn5TkY z1uM)G!LNZkzUTS}w}9K2M}aqhTbYx<8^JBi!@!%s&CG+ro54-Y1HrF@8=3oo-vHMz z_XckP`RlSApLLH!-gSe*kV|UJm{cT*JH!{1MpC zya>DtoX@-f{4vrY1b+!`WbOz43S7h78~ioc&m0F1f%BP< zd_WuqdzcS__k&%``@!vC2lGDgH()#SZtwxHjd=(7Td=~s4SW#X(ZTf(?f|zjuLpkz zZe?BzJ_K%IUIYFf+|0ZR{9kYr^Gfg!;6~=<;2*&?%*(((f&I*jz=y&4%nQIjgFVav z@DZ?!c{cbLu!DIf_*bx$5R69)!i~)Rz<8t}T*KTO+!O3)jswSo^O=vlPuvUaVLk-z z4R$f_2OkG^Fz*BR0o$2(gO3N>n0J8tf)(a%-~@2Tw_N{VY|)3?nAd|(0Jk!)1!GG- z+`_yDj4k(YGxI7iw%Wr@%qzhsfg72ZgHHz6FfRk20`@a60uKP^GcN$23idDuzyrZ9 z=GoxWzz*h_;M2i&<{4mYRflcNQ^DAZ4lB$P!DoRx4siX0v6UQdV;%(_1a4(c0uKha zFb@Nt4Q^&03{C_$F%JY|i#XiK+z*T`;BXCdZ}7QbKXV*-2soel$WG#+U=Q;l@G!88 zc|Z6(u!DIY_>>$nrdzcS_ zCxTtf`@xgI4(5H}EU=wer;1;&2ctfU$KHwlPlyV{0g^Fi!+yODNnC=K2R?%O~8%JPKR@ zZe>ma&jhzH4+CRMCfv+C7>uo$a1--DFt%XAjm-VP*m?=qF!u&yYbESwjss)CIh@aY zWIJ&w*u#7XJR9s{-VdGwb};V)mx1lfyTRpP8}klu1z2I;2KIqFLR|k~Ke&x~Js4Xa z;a29g-~hOVc?}p_9N}i>RbXswgqxUGg0bZgZe(5###TePhIttnTMS`8^CB>|5W@M) z3&7YS2z!_VU~CP9UCgt=*b)dkm}i2q6%e*F&j8;5wlPly-w0NiCxUMRcYMwD53T{X zF^>Y@3~psk0xtr$Fb@OQf}5EKgBOFFmO50lpoqFmD6j0q*#U>mS?*Zev~#z7yQa zycWD1+`_yDd>6Qxc@_9>a1--N@IBy0=H=jf!8Odw!1sau%!|M)!1>Gzz<&dKm;>OI zU>Eaj@ZZ4>=9%F8!FJ{u;0M4q=BeO+fEDJ6;0M7SUvm9}o4{?%qreY=TbYxs!^a2xY_@U!4n=C$Cp;1=dJ;OD^2 z%&Wlv0yimaZv?k64+C!kH!}|gZw5Cp z4+OssZe;EUegj;?+#9?F>}QSxZw2QwA9mS?-Zev~#-VSbMUJKp>|&k`{sin`o(cXGY-gSU-UGHVPX&Jl zR+uM(_kue<=lTb?f!mlzfj|s6x-Vb&$?+3So9nAZ{-+=ARyTJ#*Hs&4RZ@~)lHt<1k zM;q5axC7kAydL}=xRrS=_z<{-c@6k`a5M8N@PENg%qzh^fE$^YgMS3qFfRlD1oks8 z0v`tFGcN%D4E8Vwz(>F?=Gow1zz*h_;9tRZ<{9AMz&7To;GR`x8iV2UzvPSD^$QaR zxa&66pR!~}&{w;$OR!Jv)?*zB8+z7;x&*I6ussM)kvW_{0&h&~Lbu)<`X{9{R6yG~ z1nG5~Ls!uHINdumg?4z|^|x`-irmBda9YRJwN(vv-@F+ay84>*zi#6Du8*f|z%44F zA=EFl-x*4$=8;*qnWD_9`%kE=7UeI<9^LXe8azZ2+>;)$IJvf^OK?v#!ByLh@wQSP z+h3v#w!cuEa2B>m@JPlt@u736dAl1<+VvJatkIBM_dPyF2O!b|8{teEraKR0)@{Gm zUANC&`$dN*H*-r%Tk9Cby=8-+Ken{(b19(?+RyuM@r8QS31^L?-w&KX4~R^2U*Mt- zckSW6?z%7Mo`%(Bek|mKYhJ^NV{MW2T(hYduSg`X;`}uC&EIka8;*9R2;6lY?hT>K z++E&qZ$BD5DH7XpdTa@2DHIRizh?BQlq;p`glTkPsDf(!nm4-lAgRmuoAA8JYw=5v zu*;OH?(KKcb&<%v!v)7$uL&=pYoh5%zcT%b^l7S9{@||LNrs6_=uwwZ>(5bYk9Bd^ zjZ3s8Ebi8me*Jk-kM0U-aS4mj{%VhPO<3|(SNeV9`eIxC_-?OK#K$Ht`GPKp5BAQg z`#SU*IfS}5aP&HAxxPFec8$Ft4(ncWAlMsbbsvYr(F1JkqbHF6dG!>egCeUA-O6fN zqCbloNlE%TJDqX9$?aiWVo6rrx43i>t-fY8{424BPG&VMOstNE`!=iYNLJlXp*#-q zNa9io;%>N~Q=*5;s-qUL8);3WQ0~Iq#CUhZ%ZW`CH2p<8{;umyf1Ph;)qNGZ1Veu*|vDzcYg1tLxhjd9;d>5g+{$;**J=u4{;x4@? zz+nz>5e4{)8Vmx|P&8_Q7E(ljM>)X4M8A4=QS8}S+SwBI?6}yoL$$Nj>e(K#XWO;3 zp=Q(ouOso%w5=fwoj}_=jh1!2bFW_4A5*i@>$-_zjIHY@I2NQnsa>n?mHG`O^d^;PjAbqPj&u=V zwH6>!y~Y5yY5`DNoGxR4VgzUyy_JR)uTm0~&=0iLt(T`>^wBmz?Qw5t2YM&6=SZZB zo9RknRM_)OQ#6u0StQVaH@o(UceJyZHM>DQ*`asOmXIID(KSxh%m6z$Z> zs7da8zJSh$CmlO>41U(K9lZ6a-VV0YcDQvrc$mW>3y&jQ!{{C~hSPkW>LWvqbOIi4 zz#p}PgP|p~^ok~9*DFJBGVC15t^E|5$w3w-4$`D4i;fhLp3r)we%b^UQzj}nl0Pavp?Y4sK42*T{}QMn?S=3 zarS#|VbYZv0=%vTh#350LxB6V08L~8F}Fxqd=lMDZEnZ$U`Mrv@ImT=ez)Ftl3}WS z-N)o7t?T^>4u^Vw7U3F3|Aof(ubxT?iTXb}fqGB<<9cr(^GChAtm}O?2U(ctwyyUH zXhdp{w=mJux!&(X<5au5+(ZxRo&H4X{bNeIsCR57qu$+W!D1&()Lol))}@|(CHCxN z+Syd~>?!m>8C{#OxbIQDQo7L*Vowbpp~2u_|eG+mP^_qMJ~5BUhuPU0y<`=>N9;pByjQ0IDD>RzYhX~}L6jixKY zP1cKVJINUaJK`Xm?$E=#h`;%xQFnVh#78PfDqJQ*2#pH{A?BkF9)kpENzd zQwSK};Asf>cRZERUgM@DXsO|Ga{CvZlx>+vCe8QA;b+wy2+yM%qV%-O+8-onUmpIR z8e{k<{*>a+ZTRyT{fQPF73fc)>2%xhD$*%dB*Tql(D3b`nt?PzEd#H&@70Yr{8wQq z;R_jPIvegvN73mEwf~+NZU;|+2cjN-2u*Uo-xLktuD>kW1j7ILP+rXKyP^A=%P~Ln z*xcQ*O6RVdU~|`<68`=(H~^YT9kjLYj>bom_g_L=xE}Ui9X^WqV&-?o@R9kIyY9Cf znw+MFdh?XKdk)`q^kP~$dNmOxAX1P)DVU~&8fiZrMPx@c+1w3u1PN9JqWF&C%SLY0>4IL&@*KFbZke0F7?K4mwwVz2jBt)M-4*13x0n z$U|?TZ=rK^ZRjFO!fOMdR&i`J=%67uN4R;f8VqB+673RtsESHqC70Le&-YM4^})6C zX`7v6tPj#04doN+LG=Ky!DSG<8u?d8e`DPBl@8nJ9 z1wV2mjN9m@RUUWkk#1Gre!r;^_MM(fLyQTue3@DI-&e1p;-lrK+HV}Z+JuE4TWA;! z`XXk9k-J)?h1}=sMVcBd(nP8vBz~%z2`c|Sp3;_8q;zkj zbfXByp`W5yUj6`|@N%JaiUg+~CyCMy>!Dfq6`6HE@&W}Kkn?t>eP9O=L4f*{|p>BW=iyO7o8}=@=tVpF3>UH$kvBfP_ zRosJ6i8YKqo|coHKZdZsPq#nA!6ih)_|Vg|V$TWULOL&+(^HUBDkytZ3vwp1MX5LB zD|0&~4Rp`@4nmXaxr7F7(i1Pwt6v1g-8mDjDumdZAD0)={f;nOMK@ z2b5aq2CY?aa;p}J);^Y8CiShzilKal(wT4yHB#s>wNzSti7izcDUk8vd3)6PY8V3h z1Y7$9T7CDYbGY_btPoI`#c;WB9gVU5kKW&8*8R#Y-5nZ+CP7mKTPFUv$$F_qUT3rV zDRcvkxwx9(9~&|8CZAw`m8M^Om%ikNsJ3vjE4M6~DSjPVP0kx#lEe84t)teD`;?02 zD2%k;Go*gZ>F15cC%YILd@V%UxqIe@!(H7=-b}cC9p;Q_r*|YQ{wE*Jh)-Djq9u5!J+O41Jo6D6 z=G32b7kyw6^Xt%d9yp91MgolpsG391P#w@1ExmsHkkQnY(=G9wZNlx?O&Q&f1w4p9 zx<3w=Tt_C2T6pnIss%C!54q2D8d_v-C8l=Z8CQQ(H+C#Gw9MQynQ(sUfmb6sO(o%H~O*Q^b>p$QzJD1n5<8)KJ0o+d;d#?d4q^AnV#p4^u-hv?#6 zn*rp45*8TYpWE7nIt-V_Om=Xn$Em``^~uf1`IBVh@4T13cc6cVO(CCMW1P$b^U%HQ zoiS?+O(GNJZ_;X(H0ej(k`ivYk_y$#nr4v=M6K!P&1&YTJGgAm&ZQ5zz!i{aXU&2*YCrDiDPi=Q5{2Q9?JY>3gxbA4S#zCpC5)F!Dqvm z`0ySaAUjc`3@yP;(MNMm#ECMTxL7+OlbM4PX`0>16QgjV0vSUmbu2XFI~>w__%==Y zDKtToUV}s_;mJV~iSS0laFRxkp+R)e{t7zz5cl-F|EKTPW!0aXPA#6?)fp)5_>T12 z^Ao!Sd+B|`CJKOdkXcB>^2~;^%{Cm-joPysst!+vkd=0zYC!vCYQLdPpJ~DT(#*6y z!J+Qjb_)ElduW)(KF)ZwysA$`x#W_IqkvT(U40GpCF;_8_@<4=j&bnz52EAu$l#r( z>gqu2udTLFB25OcqEMfqkk}`yVO*s{|$@?)@9 z?NJ_+b)kX6MjD}Ril@L;A8TcCsw|5>k+L9v{|DtTusz*a4lc@Gaie)jd@M?0A~pR^ zB~i5@QWDXz2MT9ruCGTpO42wr zNnU)^ea1;T7#hi`I2gK!QsJ(DP77M92K|PfMWS?TLHlSyyK&H$kd;?M)Y*o1zDw8E zZnimFU>0Wcvzw_OE9ijIn7YeBdN$u^ZPtCeNK(%HyJdA4O z+D$~4*wFo*MKs#N8cDQf_pQ`wwhQ8IcLKW^z#btCBuhze-pR>Xd>s`F z`yb~H+$fy}@Wpjk9_17+zLrm_^K~_0biNxB7amKec-4=WRqsHdkikx%2jx+W$H;Io z68$$7D=#n3vA6FvpUB zFXeAQLf-*B(KAZag`Nsym7ryG2D;fFn%JjM0c`%XR6DGM6D>Bu_qLQzUalHUr+>aKk zj?itnsm>}Y`8vK73~R*Uuapz;;XsrkkSM+gCO6mdbtn?-=;oTA*1W(j^#K83HXGQl zK?p%5Gt40wI+mdW^^KT|n|c)2E!*U{0k53Q_NINQoolNL&&20Wv~xvWD7`5r1o{!8 zRue9WrJhDUIsY)a7O%of;dnoIEf_nzju{0pnd=bLFERfa=4Tx@e=71rH*@}TX!d+? z)W4be=LoMC$net~nOM25G%HNkax6jwL>{Hh-@ua$bEfVVbCAFyQmyBmhLa=`( zG)l97X6=F0%6={JTG_8vcFoGF$a;+_y-fic;L`djlvfQ1QwCqAb4{`1vx*SQ#jAqM zZ+uX@OV+El(D91Qn(P`+`S=zIWsubPk(A_m5)vD?2Sw}?k#=&8;N9sAj5>#ca`Fn4Kte=M1Xc6Ny?0rKXxBy$@ z93$AnU1Uu@V-cMM>KvWg#h_Kb$XfOz5*JYcQLQCM_ob@HU!PbswJrfI7Uk_On>BT! zyW>HWy8l$5!)bQ6=aCn4u_MDD$1PwT1acX*TT+e0?+ojq?s|coj_PJDR>wII*{_u* z2V0u0#J>GE%Z=#3-JbdiH;01i392*94aDp!=m{PMSz@Qh_flZmFQ`l8^iNkwOHnYs zOWJ6T!r$6T#uPmJm=&)?fLsh9;hLb=Jr2EtEuhq0YWC^AKn{;yFT5kR?^IG1Gr0zg z8xF^>cSFtfhWU$Fs;2JXhwSKcW7p$CLwN%ymVB6Orb9x2K&LLu!01G2`w>Xsh+d}b zK&&RqMq@S0+8`W;V8O6zE?fuHUwqaZWFy+gu#(U}kgjeOJc+F^Bx+`(dR#wYeD1#( zd={XFfTl0U4%V<{62pcyJ_g9Jl@bjKYI)J#58@jf51A_IA5-?R~--oUBNCz!pF)NV+P z`45KrtoJxN&o%IX$SkAiqXIq^)C)c#qkvUmBl_mE{2YeQx~e-oVLQW}M^(X}Qsl2m zE}B|PB3voOU4C9S;0bc{4MquknxAGouAfmdFszFZ?9%?r~MOMn+s+J`s0?!(AHjCs2$o=j;Wh(p0@HIov#O`_URigCNO(l9MG`WqsfDAR_4KioyQ% zp=uCi{@8R0sBBbMVqrAk{}Y1(gr~V(&A}F;vMN4eBw#m>4iq6b}!ekJg)g)+Xjkl>Us^0?Bt5TTDUv|eOIoyem_2+{Z1LY z0z%vB^lu!&h-@2R{urA{0H2`&KI@=uq0^aq>o5x|E&Yh7+(lQ;1X4u;9AM-TK9#BQ}M#tPuhwWFJbozA6DUQ&KHf8@3iT^df_L#f9 zuIisjdQWXr8gx|*WykI6I^B&e_oE3be`XC8UFm^nxUoL8w){8LK zqdysXDHPq(<0`uFE7*$eg%FB=s_3?n0?=`bO1^Eb#fq96!VsauBC!6rdhS|epGePb ziAn6xb9sw^D1+MYwGOWiJ@+F!*Vc0x&KOfz#@^^iVmF%7A0uA)Y|mKy0g z{`pe#zbJ;mDOm5#u+18F|7GFOEe%-SW-UBA)R&_@j zCQxQ6I9Dtyt!T>#acPr{4)#LSfb4BfX^CwFLktQ0GYx7SaDi5}GJ0N&ULBa(R}0a! z5ili8IBtAEwmlV3kCuddqY1>ZZD@}&;U}tM`w`J!FK5HlUtd6WynawvQ3DmW6sy6S zG;>|$wMpK}za>&>{aZ?9zZT|d(O;8;DIK3h^gcA&6=q6n{Dd}JdnmQ?+LkMu`3t!c z8pL!e2X{DNmFti+ycJSN>~zl-=6g+Wx0t?Ht8KwS7W zxR+f}>Y|j|Os#e1`y3J6{Eg}kh)C!zft{|IHE1EW_Dc|ej{+22@+$bvmQS+eFC?`+ z%c*J}g~S9bYO@EWT{G*jG8LK#pV;N`Z%$MTk3v2q84CxF`Nyr- zj=67)blvAZ%UF2#KQapcQF`0Gp1Q(J_{0XDYAoz?_uZv;-hK0}^~r7!rHN{`YkuEk zWS%t&FP#_Mb}ziq9<%T~wRffM1F#L(>(P$?032m>#uZlVb5&4)EMAR2;gcfvI)4~m zwrNPBQ2rc)&tCw$f$K3^Q^3l1!HTh{080#U!uu+r2>r)ZoiYsRuIf&M@qo_JdR=~7 z47Kb7BzYt!pr%K+1)-|eXDC}_B)xWR+Ls--f{Ss}~zXNk>TXRaO z?nglH7%3Kk1fy;)DZSfRcJG53cinw!2FT;1-I_*;h4*FLJbKJOMrRmiDNi=-UStqW z+>!a*8TDRwX6bGBmDYLP-4oOh04Daa&w?o90D8)4C0BJ#St~t;mFiuvYyA9*tiO;P zHLw~iN(I5-&WDvTSm7qG zLSyurBi-#$#+O#?hcdH?DVYyj`!5+&$Hs2JP|5=!eUJUgi1VDfY^Z0k5r_p1HUiayvYFdRA@ce-Yn&uErl#rM>R!-5A4tjS-ohZF8#+X6x zX*eAorFU>ngx-U(#E{;-fYw%k0pcd&AvpCPND*rP`UKNccFM!&K0iwB^CHv+5*kz; zM85NE#5?79Vs`A^}yUyAai4)K=y^^1K3v$>u8vRI(yCjFg_2;q{N8Ii-O7rF2jl* zeXr}Eli+;!4D*#7;tE@2{_eS^F#D&7VG74a5N1cRL;cyU+|cF_ivp5$2>(U&nhApj z!uDl`D%PvAyMSYd!#Z>2SYFYM) ztGe*kHiac^3U6yuII2zI=r)D7mtIcupKTW0t2<@f`CY3&S3S~)4Gi4I;UGw_`Xv+QgDNUnq754&Dg-|;y#^48L<(kLNP4G-T zLc@(`8UGf#`u$#)l7~7iy=Hzso?dfbVYlDCW=;>hETjz-tA1rlI^L*KrBrsR0Fdl2 zDpNWjiSr@l2vjQUIey0@+I88yKjWqLyBQ#yGF6oHq#(Cg)Q~oE_XIVonKfiTXgcip^(~f6xi9yTEhJptQu8 zZvZUFxoc4by@E3MITDMIn48iUX=OF#`Ftjn%?F?!Y}m@bi10Xe)f@5@mfvSx^C!An zqQDu*DJuEKNJ0pMI{QQ0IycIjSn6&`ZkPf7#T2(yd^vk3Qu2I?#+uM*WZU#D%w~`; zY!D>yC$pLpxQ83`b(twIBgZD~v-lY$ZE1wGV@XU+Q`fX|ym-y+qr8YZZ09w1VyItR zz<#%#btywoJrz_QhNpSaQ2bp63M5zt$eV{ZlGjz){xy`(UQ?NJF_MJ5XW<9Pdnz8` zHlUBII!oxgSLh4F)IKAr2aM|ZEm2~W*?!kkV4R)s)_M|mtH;3Aqr6Et%kNyj$cHid zABv}cFl8Yi0N1bZVK!LBrznLo$Ke5)-=x12UUz{v`F4!`W3a)Gh+T9kXBTH@ zJ9!P=hm0z{zZfd^GuicHCyLozP?@s=3S3>v`}m7+%$%ionkjSe*QWeS{8^pSX8O5$ zHa?1Xq0Phi0opu-M`fpQ5UF2;JJ@nIIuDJ!Ju(l65{k^PBG|2>`2XWTJpR#vZUh^d ze|L&z^QZIgAb2JU?`?rMc{n<(HOEfhAv=cuPoc==rqm;i_~%pOe*qOdEB}4M68x`x zTjL)nPZb)#f*-;6FyNc%+7A`CKNz}@%2zyoZvpJOl)?B5T`cDYJk1mXe{KAF__I3Y z-;dh(y#Vim-?Q-p_&o!U%1%LK{~3ONr$#0C4S`Tmd_1@R82qk5$tZr?0bj@A?Wn$j z4nOUL=M#8>->F)MdkEPv{N9Dc+?3HsBYyeR_#Mtht^C1+CHO6Q>;ETyc_t+uzbyc} zE@dyYJ=h>~j^JsgD5`*ZQQFL()hPo^8^3GuF8E!6AHeS-JSsa~i0nVZ?@U4w{F>nO zD1LkHI|jdF2sXmMZzKQzz;B)t-j3f1Pw?B7Emn6r1KBbBwnt)aN-LxhzkF)^9?-{| z_JT_^ev`2Ep#1p%$iKF+hX{`OBQA%sCMuHnBOZL2Ln?%(bzg6&a?Vn}e2&;dtg*dSF-8RbTzDhcyYFQ>qNuKKPGWuE%P|Kq0Ea{3 zk1{e{-`;BMb6o4|`(DW+^?ghDfVwxDEp@>z?x;a(?4_^guNY7x6_rJU2eR{&r{!|Cpdbm#kLVPMdmVdxVwl|kB*vJ8>}{*^%(JIFAhzfPT_Q~NWuxqpT8e?)xz4z}7D@`TzV5*{fplt>sf7qmQ-Ec87ho zcf>y19roF*h<$dh?#dt${I-3zGj=Un@~idO-B9j}eRj~F+h<>+WeG?>05m&w`GJO`oS2#LqF)eOX~-oCEQ>FO;I~Ujt4bllgWWqpd9UJyVZ6K z5ld7bTuBK}&T`r`RKJ;#+;&(jgrBXPL}xqmc8cC`6NV9j4gkGj3qoOIdc)U9%uV?m zY1A9|)Ote=(jgxgB0=j7pMYqhH=rvw66;vdZ2cDtM-_W$Alc*J0h`-pWX0%;7g_Bx zZDJLJn^LD^-b9TkU3Q?H zrpwiwK8Ry@Nz-K=_L%D3CnC9}GN%eSj4{r3I!imU9~{h{RCgMH>=<40k(iruInqcM zJ~dr3kq)|aB`ndGFGT|py3}KD7*Chj{ucC^gKSNozaE!9m8=e)oBK5F0UmQdls<&i z*q+8ET>|03m_Ji@42O(%n4&A(1`@Jsa83_f%QP=+k)1vJchCpg1^!7-?H?(gZmY~a z2#Buqy4$(}VxGg1#lir5ale9(xykSB@i(^cnzy>!p*{kpaSTihba&|eDa_8LSHMJ@ zPIH&X+yJpbx5910-mZ#CoJ1u@XaRxE3-NFzU#ZhyBxYOzeq*7q+cs?lq!VS2H}Pk0 z;?}44)Y38fWA$?pb?1!-(P*7Vw4 z8vHH5CC-1tG&o%l5w#(^0%u~8g=vuZa+n51P6%k3Kc#i9>QZ-Sj^=?q0&->zoMYkl zYSbE_fx&!ZHwF*r{FZBG+AC60Jm$j#O_?85<@`o~k z%);ozELAJ1BXMUCEXf)0HZM%T-jq>@UU!CE?X^n{gkX{7Qx=o{vBd=DMy$J%st*w* zp<#Xa>md3exsEmbqbJd~O?F0xBjY(_gg;atJF0|w+%qla@J zpH3a}vIL&Jj)eC&s0m07tJwUrQbO0nt=I7O=jwI7=0yy%zHcrl#MR%9x%jtE&9YN7 z1?R;vO5~&H3F31v#sp?A`r|-(HwYyRU_>ZQXXEOc0%v|}A)q?~kEMjTev= zzy3>pJ+1pzN*V?hQ}G`igEyR*!T*`WT?GdK`>}1x$N2$$d;o%krgQbM2J*=e5p2tz z1+Ow!OjmH+4QOxB)?lFfZnqm2SOl59% z#vLEajcTzJz=cCFWH-k#!pWM{Gbmu=_&8T%O{Ay@_RZv8r*Cwx#NzT`-S8#ks%+qz#Ddf8sOx(1ty|^SWwhK(Yqr@!LEcP#7!=^ zYivRW?;GPL3(f(g#HGe_ij0yrSfO4TJuz{8? z(iW70xQ?%|NZGgDbJ1ZKLmrwXmXt4_;#szmtjJ+Di3r?}RfPa|Q?xPmf&r$gR;I^& z79cxWpMWNwXO=UjB?GHUO2t6_n0z94Ukb>t(u45iFFVF%7 zLcgLCVL*gdpuM<#>1GT#RE7ew-lCB6)afc@vZ7|Lz$;i+9F4zj=W6C^o?9uo4(4iJ zV6 zitkpd<$Y85Effm>$UmC_jkhAbD>>M5|E6BS&+r-~hIfU(XPJ+MpToa}?vd3AQQwVN z=hWfp?1Kv37)ix>Y3zxZO?K7F4jz0*kKztt*fln|5=EL4JBZPRbRr67|V) zM1j8ot$KWSx;x^%j!cb~7BoE;Cr#iDoq(bXT9qT7Ni&!rF5foP&IF&}OhZ8|`0;CN zFb+FS-BE?*Gj3B1|mL-Bn)XK1gJNV3R2AUzSxmgX=`f#9#c&n~(v!JW`Nw)`2 zp|eKmKx=5~Kx<&@fmUJLB5PoqY#_OUz)AETSKv>_yxMK)wOi6!f5VsD*563dmekhY zn5Fqp@^Gdi?{L|A!uCoV)7^z^10~ja^R_G^eO!er(+&T4=8GRu;odtkS)e1qblz zfo6%H2k{ey+Tb;{$X}a`q(g<~mnhuisSTs>@IUbCsXdIs!;k2nsrY$xVBY4kmufdB z6`7l{SzPom8e`<`VaQ(W(@zd;EbV}UC2m*sHSR<~C1Xn1XRw8iDJg4*WsbuV8@PHL zGNB41@E_=Ne<~O$Az|gHs?cF@up@p5awJ_-QoBrY}6(0c3(gga}zb zJwBfJf2xn_3F_YC*0=pb5+p^jh6y18h4?` z{J}MUqkm6~l4@(68Vk6^q{cWqq>hV`!;&#kVERx=C zTa^h8z~b~Nh?&}4j#V)+=5IoLaI<)G9>ZGan!kSN|4l3rUguLEAO*ptJ?+RRGoDhi zPX=Afz9R0A7}i9$52PZ=u3E@DlYnttu}?Wx0D9pKhcta=9amJZdw@C!K6lOkg!4vr z?3i?mC_JI%QvF+WfWvhK?h~3gCs61n;`)xMz;$%JwFa~_*Wm=8zb0v!0uWcx>ZzOm zz=7#d3lzqEZBF}j`tj`7II$3mFHVE~8s-KaU%cm0%%F%OZriU%J}2rjil~#G(K@); zuXF$0e*H7|me8E?AK`3v_}83wXUe)}rI>}y?FVVJA9UbKSDXO@LK?;iS;O-R;K1YT z*XLvClK+{%dA?`ZK=X6YwFAvM#{Ya8Jz0>wk2`&yPEglPLTxLh1-en!*Mt8H5@U^y z?cp^`dUDgw6JkE|zRrf3gb1_(pE<#8_U(?JFbE(ntny!xGc=;G0TIFG*5FFAIPT(HAu|s^|Wm~Btr)&?(CTJfX zk$ns=2Y^R8P5n|yZMacwr@jW#lOHjvUQv6JXA&yM8g>%b#yi%{STMX^Z|!R(8dMT$ zhih#A@;1x~w(;XJ^e(8_SJt+!e*xAKSx@Wwd-QEup_iv|e$@5v6Bm!#Jl;LDablt) z+^q_Xv8J!hpN<<;d1&-BTDsH--IWocOM-+i_p`2b(jWe&D1ZKybD965^SSwbuDCcZ z%NZ|=cWA!j(?a)wOJToj-e1o!L@gqm7Ie1{^)4U{JAoMJdIxk}E<`=f?XOpJYXDgW zgH~ZKR&tsctvn+S${yE3pR*s>BZ6sc~&7Cd^M8_ zEF>#;``TPEBt^sNAV$@ST)fKs7a@q#FMop|#af4R}>UooVV4g z!w;h2EOx3Z8pfF~VhT-vto9OFR>}oz%^Zup3T**V3_Nj6ODDy*q|I6rQWu@Yaq^Ga zjb#-OXPJZ;MJDDgG6W5Fb!cUms+mmC z*uQIzm>LgvlpX-w9C`pN1c6sB0@k$kS=FE!LWP09(>%0=J=OY1#Hkk4XP zET%+5MfIiKT(Pc0rQboFZg?ddTNr|-%9r3(GMEV1m1-3hN&|;oFua=#^M))?1=k92 z`fvu|Cok;bjKC;;!SR{u(sGV;yEsH33O!BVa{NbVNwMCks6jvOmvgta33DTfj1X6#Ty+y5ZU}TiM3Ll%9n4# zKS8Xan9mHW9;KSb-SG^6jymDJvYv)N6}DNaw!VyvSE|BuZ4iD)N1QYbZ(`Y?o!E{1gNuaj7iNj6>g13n4hj;&N`UK@57|P?m`E1pCJ{VRQQkL_5f&BH{5}!sFjl zlmTNsppFw`-TB0sTF&ayv&r5%I;bsF6+6<$zUxctD-M2sd_1bgO6l=oa-J0FaY1!D z``h~1{+@Tj{*Ig!-{0=&ul>;&;b*{K`>>6Xg6h)=|4m5rX85S1kUuUy{s4zK@$nx> z@=zE%GGQBh|6n$M;`;|6n{W#poI6#^dnFaO|Ea_GfZAWfyBXd^`iASnABXqG^quh9 z@apj9*!vJh*+4%oJyqjpImMl-h8UMnnLWpe4|=+%*2n7lqb3w{-0=fV442yQM7Ixm z0RK`vV>U27SOYJ)^^!_9` zAwA|F;la<9(9$dWc1Ll9l->_ru6#mwx#U9Q@x*bZZNNboWqMp(X_-6ztJREVQSP60d9W2D>W?9lEq-k%+hf~<>ed(xtg|6I}52?)3 zAKJCvVlA^le+Ft7WJhFA;EXTbRwjkikHCL4zVseZ3>(xMNp$#oBix~Pl;a}oQP;Nz z!q1x74~B3>KCBAwMgvyLU$1}(S6Ga9CRSdBH+X=-lTrOW;{VkFSW|ZxkV;&{GdR6) zoDKR1=3ty1FBe5%5q}voh~Jl)kgnbU=_}y5>`##vOvzw7R{s2eT-iv6#5OGJTCL%V zouT>>FIZ(Vw6ei^j+Ix8uYk+IA(lP>8<75V&@SRFi2KP)#w7>SaNDr!kt_k4;E75@A49a`^5SRU`})2joZ0wqt-KI)Nm9vyg{0 ze00J!scn#|h!nXbp{y+)m*N)cuQ*>Jci*N_KO%3>z@S_e|Aq9?krSgN0N=prVj>!5on+gr!<7RH2`Ln(kN}M_dOGCydI+`9JiwBDihq0> z4q~rx1v+B#i*6;KR57CI^HEZ#ua!FXdZ0&rlrnSExWt6eX(Bsh&5$+aw3rmaDf9-_ zR!9`N#6bpVpd;a}>SppJcNiI8XNQPr1tq8!<_I;;) z2m<5S_(mMWjM;}Wo$-z9xS)X>L=f5bp`O@WXfdSriqP(^;~Ufe+&=U%c>|+86XGP! zK4hQLirl3{^DU>Zx)l{FYRb|e4I(!>h(2Q52Ou+lR%v5(|9FLApJB z9Ahe*hrYzyGQrnOLum(t#;-4iKVS7j&|K-M3&2SH*lPbYoS*0fyMW*W*I8M`u)CPU z(x!w%GcY6K>(fqP^-mjOlniT!JN)5}S%;rEa@u{Jkr&2&y;s=lNAzF`xY0f$5$Vr79X~7k%bg{|TH*k6RG!1Z(p1{j-!w%Gag$Gj3>CbZhj4Wk1g3vO z)B2{ez4-cxPN(ffZY;sy-|+pA^5q>1;gv9~_s+z#v@863_;PDgX^LubKDMf^>HzcQ zI|Lu6=53hLu)LssQbP95?2RfL#PXCcmHGp%kEH(9MZsRI-rXqq)u`Qu+rPG{g%>B{ zX0XX#^Si_iRYu8L{|X$m^q6m3KYiXhp=_7AGTO?=IAdFvny02LG&e*zYGw9D$4lad z@aJ*!&#(qfiOd1)uP?7XgFv+MhW2w3y;+TrNfhKft7S^bUJky#z zP6%OPa%gp6Pe_h^lLtbkW^bed*h0r=`&YKf`(bj&BA7JFNNAYBLYHy=mj0YwllOz` z#Tp_VH>F(KQPh+&F36D;E_)*`zPV#GWO!6Qv3>pRm69LPhg_rN?H4)kFl7+uPZ!4(5%kM&8P=uQ%@M32OUvah+!O+Ak{OMQ@--qx>cokqeK$p&T&G#Qd0yWt4?nt~N5jVKIyDRIji3!(VM;6Wm z%Gzm^aW9^$<=aYi5LVvF`sLS6rP z33b!vV&sW+{Xa~o@BclqP~U$O*IA=}+Agn+m-=b@Vn64w5dNuGYJf6pu`TcpKbVN` ztLY>PO|+?)G)X6k0JULOwv=d-f!7#n7yyA?!l%In3cQC)f}f70)caqG{d_a_^ZnS*g|VNt_D@w#*3s=_7pTFit8R%V z+IJ#IbLt6bu6E&N$?Tb3e!^YYX)Bo6Yv+fW{I0jgG~8TgPR_Q4bI&~7v_ zxWbZB@_>2^^{JM=0&M`w_5-3vt1@ii49icQ0IMpesBKR(NLaLvkPibND%fLp342bM zvoh7EcVbi0gFX$+g9J#DWxec|S7e_dOUyFR0R2btv)JVr29WYcNi;=DjHHfaVJq7DS1edxm3(C*a$oOA?Jg-Qh>^Du-rQYWp$d5N5p}P?}c&S1af4NC9FU9Fo-I<~pgXmh=qH@6eKp^-`1p?1;46#S6C(cCJu zg8|$T*IZZ@o!x3Htr9ps#WL}9wHJPkvzCz(d3{8>dQgZXanZXa4 z%0b>Kt^S62CWFLh(Na~J-RfOvRr{Cj6W9^ybDJ29G#8k-oc$FFJ=MU`X<~uzBr<>?#3fVsQ1b3 z81%QdJQFnHK@ zDTTg3QG!^@Dge>P2C+!q8`LGl6MQ4MrD`Q_%3m4AO;XTP8dbUtEKPvHl(AB!NYZXK z$*%l6S0Pjh+l~Ev6D&GEhIfQ_hgCQn{wdrT-V}a4{AT#OX7)_k%OL^=YNN-5Ndvkg zVzm&)#r4iOLBp^%`T49>GdJzxB?cZ*$_EJ3*<3>ui6(0Z3{Foj-WpNS2G(N9Y zaR#3DDYtDc__;oBWvM#}b>yU5mh9WY6B&0h(Vdh~>WS#V_K`E$DIhRkeFVLZXE$b& zYSHs<2=l|K36%-PV1!f#8Y}F!UzTBSBCbt3;7$CMr`?jf)fK_sw_f;7FVFKpSOfx> zKH!}F}Hh6_SWDoFWr0r}u{&rMNx>(X5 zXAE=Tm7^eXTiw3YkCX<0d6!5Jr$BsyH(q1Q|0;HQ+^+`CQ{P-q?+=f+sf|d- zx$*Eu-A~3ljW+D_Yw+zL-f56C*6B|8FR}UI`L(+RJ#u~xz8=In4Y6aL9Ou{arFbON z34BCG&fcd@5@H*iCR7*23j1d$g6ctZ&WI^73mAi{Zf%yhfr*2dh_UqtnaN~Eg zU3$6f*mUXW>rBVKFcSGlV_yY2C}dp-ePdBkth-}m8P6F6`5Eo*P^5VlBorhhEKDdM z7esozLr~DjOSDh2JKY*j-f@M(`ocBHPO>e`p3C4`0QF9;?>h|bB}g!+raSQS^Brig zJ(4-{pJcVo`QSE3C)OeDSez{y0Y<9_t3wo0^gSxRYJ7jh_E{ggfw+X|gS^`x{x1A$ zoV_X(Mz$kfIJQ5w@^3+h4D(Cfm)^HT^ zxIR^9+}6~DTi^8l0k>(WH*x61?z_*Fu0fUYE=4gM z+Vxp?m79TUVx<{b5uCdRU5xLVxuxU9H`2g8f{ZUp$V)R zlpUOPK|SW+&`J%Z3Qz!PCK0E$mp6kVCbKv+sn<0WL3?m$l|Z?#$Y+f;07Vm{uu9D) zB+DXH!Y6!YUs0V=z|4%3kR;O zNpk?U55V@u$8~MqP>C8Wvif=q>#72PZEJ(Y-Qe3*wgx-L279PGJN-Nf84L&qTKDC6 zgOk6&rC8pt z_D$wN|NhsxO#l-L_#wBnn#Yj{^^~58+$U)~V8`vKm5K#qEie z^UoU{eVB{1WBc&TP~C@nr5)TqbE0+@0N(3t$HjKg#!Y~SvCc*M3ry$Q&CwXgZD$LR z8FC3PmaSG#{)D%8p?w$@-X7uG(4+R-c)smH9^4mLne5rF2BV|)Y>Kd1 z*UV|qA`#_Gy%W~XPIF3}W{jw~E;9dsbMA&37(g?9)aM^zjA46oodNf=6aySPtd z>m6+TovnUo&etjtzCql-ici_sCnmys`gz$ezpmsry`1Z#(4&8kW9|#Em&BoP85-sh zU<`LON6!>_-NUnMg8fI}1YnoY7SJ-*K0JrAZr(7$HDk4w9aMm$i)K4WS1g)k-{Lf6 z3H|@)pG@&L+{?o(sZHxS0}o zS(?`W4pKG`YFjwL; z3WBz!lEJg2o7i{zFiL=_{0IE%BVAU`CJL7Vq>&lL{$u4_6cetE>f15R1RIT_sQN?4hMB?LpUXHXdutUM+u8`UGn1vm}>iFo5dJueFIG;lx#->--U!HnkE zqCtsrWv=X3p-{eg9%G^P*;UGA5+4Cwz!7bi=e(iWA;T#7GIEarS%LOQT%o^TeL;bQ z*5IGJ#+`u_sW0{fLda0>W1;8Ve^Z_eKUT{IN7*e2@EOOMiLrJ7r`cPV2K5X$+OaCw zahnx`NW2C$Qh@DN*T}O`^?aRV*sr{J4>dtzNA%dB&{Mt`$8ha=Yi()=PNrDbx$3j} z=x^A0xCc*0ZYYgKfQ?Kw=|{YFKEk#|UjG0qJqPmfYr5G_@y>1)Vqj|SRgy_w`$)>| zR`1yP=OQ2J(b%<_c6xiHhqr}s>_#@-M6DM&?LA^oN-igrj1CNcjiADsaBd%8VNcvlPAjIEE2*=j4!)QRaa(){br4Q~u zhu7q|Tg%O83l=!;W~#AU<~ZKPGqSa;z;*)D%ISg7o8yH8P&htaHped=n=YGUlj$+1 zX>>pOAg5qgHp1H}D%0KGk7o#!k$AnxUibsp zzOWbW5ZMc7>wGKchY@HXvJd_qYZMy&H@-t3-HfkB+Ods(0MQ#Z(JaWP0(Q%jj8{309vqw(;cwc+~--)wL?0@dgJG~m%Oz(5u|IaHTc zpMrAXu)`i;SSdv(o$&nDa;}|f7O;a62Jjo1+r8JV4h`{x9^pdy+UxY>qPlka2Ns>-J$APSnL6d-ck+gf_PXRb-Q%1 zs=Ha%S}dAUiLTcet@qFPdJnK(aB)L4{};5zG1-0m7O%*s$5*%8EWcduv_C&l{xv$k z{zUni%(oW9rJJDU)1n_-JU?2tWqe=5x-ajYD1V*C0al0vHCDrVFS)~xX)W->7RTx=#VVseO{cMiMDgV^jLFUlQ(Em%(+ z`PU&o^aIxz&69e4wsQ8qfZ_iK!Y)**Gs!cKdRz0M-prJf@{QMVhVc%TE8HAntt zPTQb_1<2r<=hy1|D8-xSzl8iyYc7?+#f`^le=76G=>Cxvn)mN!4L`~SfkPiSX22U^CDFHz@5Dc?MQGo?#VA~^K;o7JzCe4FykE5E8m(}>W8T-k#Y zri8cHuo$N+fpg&}@PoaxFL7PWk%s=l1v|KySPi|Wk@q=&`}J>9D>O|1CdY)n1OgoP zH=Z92opzY3y5K|Pe=EET8!khyWCIhm*EK(H%J@YwO-Bw6TlsT_LhvIfhAL?){b#q| z$Q2%qi?XLJUs$DRH_aD5hlNp32a??(W5iY(Om+v0+g(_k8u-FB1KODcJK|2Ku-wz; zDE$-ium^JM;K)Q>Deuck<0Vr4{!^F-)eeE`s^w%N4Q9}iVr&MsL*rbBV<3p53bue@ z5hjrPllS;rB+92qcr1X*$Ue%^i+jKf+6)mJbYhF?opBUa{eW)<) zGglDRp^+GNaOf;FL{3H$fXp_`C-{br&r)yDKWs_v!i$i|I!-;2kE}l4laY=9K z1SKWF{O9TjnBmRAT&ck@hK^wJZ7@AGm~gMArh#LAB1SMIP5?lgEYJeb+Q9(zxYs7} zdj#c9clSme{CLvc3qNq(+;q8k20tp~CK~kufcb(;v3CJF^_QrvbJJXmW$SDwz2ed_TUeYzFqxRs#X6W-{(L%ZL zg-TiI6J3aMOGCvm35&^MQLHq#T zt{$8yBszdskm#}erY4w+4is6#+9B-t4T2YwXwI1^2qN=a-Qd6L2tu0!DrpBGm9<&m znp1E)z3LA*80dSfZ{=(*j*xm>vtCwqMP+bIhK5mjjt%QM%-j<;a?nPb!1u(1TU`{MY>qtU8c0K!H>L6#caE|&LZ3VXV-pbiEh*g`Uy(LM{ zp_wA6!#^O^a24)Rdj+D*a>z*QmHis5UHk&lQ}oU zK_mYnCzm;W<8sKf$T67HEiQ+gik#uham8|Y63>oRK6oWdL|P}$AZI+wH^g#iskGyj z*Thl{>q8O?IkQ;)y;zQpr=G*qrrE1H)j}{TU zt8(OMELAjA{6+L_T4-}-X<0_I>|Fvu`tE4)^4cT*8Kzzp zq)e((6Gow3Yf`1USAI12FX(j-2$B`I*XPnnZqgz;$K-ngAyv%TQcr zXfLCf@E?9lZi=p?tJMuKCD;oF2;a)b3BSK+OuZ~e|HC495vGh?9AeF03u~?-nB962 z{qxmt=jD$2uh^?!xzume^||Chq;kQdl;%Zi6wd{CLZrTf`ZgwQ4y25jCSuIyTFxtx zDfh%uF|S0Kuw}|Hj3NqU8_Fk;k3A?KT5yCWzyiqq!Wv-c9WDDgHLm`r(3KVd$JFQy z5fIw+N7QbJ)p`|-At{&BHhS9}zw#JRY?9V~;~2AAJZqc1*vv@>`>XV+ zuVn~H-4qU@$sncSq|Fri%PW>4- zlko;aB@#GgtxJX~YmsTY$)`Cb1)>nZHiq>g6ODS&-cU86KEM@+zu+z4vP6E;dy)%_ zf&u~pnHfIo9STOD^$}a4@OXX>7G1jx_bN#Wr|FOM`V(kTI5{_ZkV&7F6fI=agrAP-xQi2W13ifGt zVV~4I32ty%H?kC5fN{f65B6Y>hh!B69}~=!^nnoEgfB3zNDInd%N-fviLme#G`FJQ zQ&JlrqKpG?0GyGeRpsEs6=~{vtO~fxv$QorUC^1P;#B`T90|nrjzqhq2zCNLV`uCa z`q+{@Xo-5@7l4U*>s`~YMiGyH$_VIKFJoWhnlT!Gi>zskNGY;jq+%VTb+f*ifi$#? z!V(!`1~5Y~9}3GcWexyrEOvt5&qc-@WTZ-&0G3uDKahY&=qXv7`=T0rrK?nG4zhwv zS%;#2o0?BMZP4aPiL$Wgq@g1>^mWf?gF1{zYRBV}u8LFeO8=w(e6|!^%674MK)Akg zHhyZ?GqTT<7XyFsa<04(MR;+`OO}2)M_#(?m)`P{sb6}@3k#zTbU}d5&@T`McNgSOKtRyqkSR2{p(`m)Hj>7rslvM{s6d3cj6v4Jlzw3o7?ExnYC zO9H}4PFHo1!!SxHUu+L$kyX(uOV+Joe1>uyA}+?a%w6xQxD3^@*H#p_sna6CRWTJQ zHc#pq>cXrqvX+z8)$CVeY#*64-W8a4b_k60+c1aL#9J+}(LWEpG^~M$yTQ3c30mQX z9}HHbcgdut>iRrx+%AAvQqzD3K$ZC({D|0)i`&R+-9_cp5gQqz*iEX@L>P(zI*8B* zujNaLP)w8?L=fhW?iC5azHJ~{FwuPQBesp6%!=(R)o5@<5zR3X<=n_Xx7iO2Vs2~@ z>N61~G9b}r<=QS^a3+g-n!W%Ra}4Tot>dyY>adSvi*$M%I>t`JD9@<8i-CS^_X0K3 z*xuBYT>E`yhAjbtTC(^h7oSQMnkRem`okJ>Cx?6`hI`W=sEL*8ZsC`uoZ2Q<_#f3- z(s(qc3K+l~mS8GQ$Am; z%VI)l^@4alCe0;Bl=3D5SH*`IyuNMWP5i=W<~l~R3_fO1S;i~vIDrK*$=$9CoNP+o8QMJDp3hA`OOZvAsyI+g40jSzr zs)}U4WLQ$gwMnkR)s^xZnj-b0z{781XyZ}b(TUdV#8*JN-B{=~(7=v6cl#}uVwLr{onnNaPP{KKT z05EcSv_8S`v+b_D7CaVda1mC%@PF9W&hSAzL;!2y+o~mmZv|S^2+mp#cwPCXS1-0b z@e!!h?U5EaUmyMc-I1X~mM5%gP1AI$x(yP7TNJad2&()8HB`1Gkd%iu!5Kx?^J%nq zSnttLL6gQn>(!JrcxA&yVkbAOkGM)2)`V^1msKmVfWZOU7e1?1s3L&^h!s(9>GTV2 z$zn|XSOiSo*3weI=m{9|ae7juT#A;yiZcsE*3zF~!zwh(Mra$=QFY4|ka6WpFXn_P zyU9~N>5_!fPM%;PqI@Q|_tX_$!abMj`8zs=z*z7~#NO<=F;s`TTF!ZbH;k}>^UKJv zf3Xd0U{njj&-=0TweZu>7YS?6Z=l4#;_d&8)itbXXJUQQq0&crL&JL#Pzze&+a>5< z-86lPfmz`$M{jZ61A}ebM`Bc6y1CDmPP>6tu(1V_HLq9mDFe*07RS7Fz^aNR4#b72u_VL3EPk$GfUGAQWN*E|?E& z^i;k}6uT;@X0S8k0i(!zAqx-r^oTr{xQp@Recv1iF3FU(F<9sjHfj9105TXr{K@V_ zY*rs3Snw(h0Ks;+wnLXo&09U?lh8^eM&n^Pg0nC@|E3oH0}yFv%0y%;^;7?*Wd8vi z^l24M{RL~ce^ZA4K!z)@SC#;l{T``vQeA-tNqJ6V9;fsRI3ZkM$;f4WTu!I_i>R~7 z5>NZp=oeR8U(w z9HBPTO4}HD^Q41i4@U;Ae&A*tXaC8NY8_r2Ocbid!YBd~%%S?)C1vtl#up&)Xm_^B zY&TLobwXVzoR83IAwlxK-g+J3`o{I7=Ms%_0ka!?kMl_z(7VXV5sCO>M`bnz648aw z^|5{ws4xf`8Uw0h)oY20+)uQ|bNO{G@addQ>9_)^+Rw;^+D&P#*I{u^WuexaAcC3aM8H|2ZLdf<)Z|78sc8-vCewPMsp zwBxu;bvAL!bF#0>yPd(WLEz5o6-ZuN2Bv^1Yr4SXoxr!FUlgzhWW?>h=eroN-DXXQVfV>78LLdWD1lL(Wc zl;~!fOV#PJFR2ie+v$SZU`p>lG?S4S>fsyoc%qyWxE=Gvp{jadya<(W?tm3JYSP=0 z-4rV9r#aZ}JiPi!CQ|8nQmW#b)h~ zJfZlvxk>#_o`op7N&3iB^h_V8+Jnc4B1s2| z-nLPc#&Qu94W|GGidaaa=xA~rinihv=UB1Ky>khzT1(s+DC!GBugR|Q1@@E4!1`bA8idO@J$zmy~YULaP(K${W z8ZeT5RsnS76)@DDYL8KuvPbxD4#38Z9^tU~270mqEM*uZc}b0fK5jDsSg+hMZeQY_ zO1Y>A=@m$?tYT~kUMl5<&Plv*Lr_`8FcI|{bweN}mq1{$22!^CMWb#UlC-{|ngj*& z?3H4=`&}DP1*{d}h5Me!t6t(-5gO*{^sc7ayp1zpO<(}#lR zCDK>jz~^Yn(ZD=*2lKlaM%d=~=>el1!jS|)jBtq}htxLm!l(ht5K}X9z8G_UsClj%* zUe_G@Z-Oiqex8MY=Bq!yMhbUbVE4Vx0a`cfIX3C}y)3!_ufaYCU^F%d90>pDG+w^$ zc##dE^Bu~A)6yAg6m(96Uh#>S4R98`KZL(}y43nWPr7Q3f8n9QlH4a-m+(Dsw6Ds#MVdVu3d;pTykVE&S z{Jw-K_&A@QGY*=E&OrCt!d51d5T#Ws7X1Wj7GJhw7Z_fKU!kEGG@pItDVaauH>(-y zS22M?l&UpMv-CE`Fq7T-o?uE@f_wHJbUYCdVz;MPB8fe$VnyBk*8nZFkx0b|w(`$5 zlt-a~<_u1!ML9ZW5updBu$zdd4a0`d%is`?i#xc*jvLw-Vq3BJ3+-%= zME|&E^aeH<V<7X*4dr zU1^em&A|a#!NKh=9E=F+V4CZ(!62ZsyLs`|{E~l6t}Z$C-5*p86^}HG%4wR&xtZ$4|&YaCt*iXBqofUFFxi zbk`2|W_jFy!;S$|*nYq7RJ{9FWjQWuhVffY?G0xZMn(8Va`8Gp`1-O2$XWXaV9-GS zBA($-IeRg?Ve7_}{#`vPnT_gUW@1i%EJF?Npb%J#vV?psU;$A0@#uZku;S~>=M58P zS>Ws(T+w8hII}2U{G^Gp|q0>aI;L71NeK|y}|FbgB}(a<>EUBkL~0Z&YK z&$eGO_@aeeJGbp8PC|7fIFdr90cSc9aMJB8c7x^{n5ccUr(xd(%seS@nj1mLE-0L# z?j=KDHDSwIxy^{*2&dpxmRib`-(+uX!)2G6!{zpVpE?sj_1$nEijeH##wTGx0*sAY zclEqWH!2Y1Yv)1i10A~lID1>TI@+rN@dYks0o zJvv1C(60RaN#fw(E`i(N1Uw@H;5MIRpb-&X2lko&d?v1)Yd9CbYG4cpU0AoS!hIzk z`Y^Hb&4#(WSjO5+@ufY|D_W;5|30@7OH*#GMPL zR~Du7$L*Mye-VtM%K$V%&ExDezY|j=e(3S5T{5XO0ri|+j2=6t&#N2&;L$luN^b%z zUGV<+f;Zw71c-D{C1d$43bsNLzgY=hnvI&2A;f$9Tqh1c5;fe}k*zJ_IHw}eSAS~ZwJCV+dA4h#Z3+z_N-PD?LUtuItHo)drO2vG~5+PaTIvNF2E_S z3rvkKfU9kQ|0Oclbb*5S0_WNVW=A2sh+mE-%JC{Xw|WFjLh3^@>*c_@CsAgBzZM?_ zN4hKtd3#-t^*n@y)X8XwZng2ffW7DTu{^QIaXXn>Q8wJk2<~_{ccu?1; z#A;T5F!L9SCcZ>wV6*&e=09ZTbEY@TKZ*HycK&hN-`gJf2acSu|Ld9m67mUGj9^Xb zBBXKB8D!$LF8T%ck8Pnas=~}<`go-CeGjM_YUIup2;w||p6$TzJ%pbgfe)H0i~&p2 zr)T1vM2+8IWGDvL!o!!6=LP~BFiD~cl&^MiKI~XwkWu<1Y*zN3>{?x?{ z03Pko001P``pC0MEjkTonQybrCbZ%}Sub=x6tGPz#Hb_hY~~f%dF+KFuO;%rkCF^T znIq%>(e@_bQ5DPIZ~_Sg#G9yyagQ1mT!|6|1x#d{XwaY_sE8&^8vMn+_AwRc7K6XY zcr2h>>CkuCCb|&I$-#{l6!D4Xc*RT#11O}K*OAMYbn_zNcr>cynR32z6OjZEp1>Qu z+9OQ;DQM_;fxQ*X2eF-4J5Holtf?T~v4ibuo3 zeef)v6Cutr`xA9=WP$St)-5m*qrL%>Zn8P$!|2uXacJh<)AE$ z)lNwEm|E-((tW=@p(YeCI1iB<^~9xsj(EIbd5*~C=rTXfZDe34^$9NQYsL`Fe|DKI zpeT8=F`gf|Z5{#`%u*e!QwwBaK4-v%7-kc&j|@G^zl96)xV07_6Ih3|O2Q2G&$jd72K4IUE^2iP;Ocw`*=OWAEjs(LH0j3{1#G19`_i1_aMcbYFZj4T zF)`2I$nsvA(>&20xRa2&WXKt~M9mDOHB(3&ImLC`<`lzO#JYtvXh*Dbsc}MOn6i!v z-_|@Wv*Hmj@)G;h(wxW9@#qz7H=&>m4jLvVCaud&ZwuJgbPpqU3M2DSJ2sPo{-T;t~^uQHveFwA+-795`D@rn>xUMJV$u;0QP{i==hM^ z;dJ!jylTq7|K`Q*Xg7!zF^++`dS6J}0waXbh8{U~hbwHN4Rb2nFZ&-9s3D+l@jwy<*jhS*&`Yhfah~0;!KP6%T7i}Sk%QZCAerE9lmuCz(hBT3&J3zT({ zs8e%*kn3jn<=$RIoe*0K{)VVCo7*q9aUiujxB}-1%9k^qV_)<9M|g_e=-;M5t#a_| zsM7;)i;8oAbWqN7s7lFg*AIK{$0I%8LD;oA&$El|77X9>+N~&BU%q+RL%soUs(K2rtZ-E!l&P^ zRLhaBv|F5wP?7Hz<2%rMD)Zc=u@D`u7~i9m*l&&y?8G;tawu)CGro}=N-J0SV5t+p znA+4kIZgd;Up$1)n@rxak$q2>5~yn;fchgZ@B>N<#aB2uUdUbphpg)4EoRL)kzpdI zxbmo(yOSid;;5O2G;{S)Gj~a5uM&LqvO0EFj7@!YX5k@7>lClnTMbjoJ^+(;K+g|8 zUc_q|c4$iShdm({5`CEQJG1*x5sRn=b7dt|u@rr?+o3C_080buOAn=`&e`Xevu3dm zH+2q%Y+XwHvkL(((Ja3^1dmYFU=nzo-aB&69pj#i2Z2L4iY}|oPIglRUQnybBm{R_kTpP-Q7W5y1Nf|&2#&80wRZ}tZ@ChMymMcK4QaD^4uGMn0?nj z^mySwcmGzzjZE2L>IC1j>6Z)Lzs`ozn%g%@6%Mcf#@LQc32W2vMI_L4= z<~{rdiXc3il)1pg3%4r(0@TgZ$fTfS2y9t>+#>FwF=EhBBlENxPG@en;5S!IuC^lNJjml9})e8pXuGoWta!xH7N?57J@Qn4O54 z=lk~s=zs$1IF`$)K|!1vQCtyNs5q+w>+leGOeE!G!Cd?|1c-1Wr#}S{s>E=#j7=dS z@XEoc^-Rv6vJUW54ZZVV^lt}Q5l-@<4fODc)Vdv>K@D*Hf~gG#m1Z7BP|o$Y^Q8|0 zzYIX|9~V?w%eFa8Nw5Zrb(Ho@=k#W9zH7rTK*FM)OwBMG;nOe@Y8mXV>nGM1v;SZ; z&*vm%<}KZka&5`N4BJb;k7P%S?dd0v;S>jqjS6d7y|5vyY^v7jqjar81TVl zc5``pQytcL5*gKCN3i`*YAT;wo-r2YbO6nr5kjOD@F~TVG-u6ls)vb7f3k@`JuxLf zxFxk5%l61cNWoXHjB*v8*oDS3iR{WhuA3uQ(3mm3B-+sJ$W^WTxGKr+Z15Z1y)sC^*4FnAYDGzf`qRgd{}$PJ?vm z=7$P&XZ}?<*Av=cpec3EkN8SpD~-hmbNm_~3gj;RJI$^ValH*W1-VQ2q~oL`EWC5) zdGiy{m zN7Io2?!wFxq~l(fSb(3*=>&kaZUq1%izWO;`TDC0RdYH)dR!&tv8WI5v1p{y%a4if zcAv4iTIsR5Lu{^AdTj1ZlIyATSb!`51b9YWs6J!kzsP6*+m;|&H*7jsM`fi&Vk2xy z`v)O~wZv?C44a)|HZunXvlWS@a2bg-z`_hzHnv8=yXm*0$B4sIsMv9UzYcu(b^er-B z7ceO1TBl8hsTfZkgI{#XrCYGNCp$WlI$!-rQt_S6Nj^+*c#}Haywf{Wa{0A*od-#A zx|u{4mL%cXytu^Z zLq`-A3jE9rwWJR+Cn=i=kmxAFWI+XCOPT`ESWDt{H)b=sR0gtVkd}sB4C@u9 zFjtZ=A*wUyf);IeqL!H2Fl-(5W*!zNq80OR_Ec}~qjl7qr%t1F)S1WdORKo;Iu=x8 z?v`}C<2Ufj-zu-SGLHj+zz>iYgGHKG770-Fh^*3NRNE&o7urrSKlD+}rkSts#Npu+ z5J*Ry<~KyQgEQr&)_jGdv4a62kMqx&69C6}H!I}@lM|qG%icSHRO-`^L-yaoFMy?y z10%SNf3OW`g%CU%pMg72y#Sz6?je<<%A!8lbOt~G5p2k$T}WV=tTZAT8hF`04GBDA zpN0jx;R#yy`SHC~3W+-y*m3VtZFlTRI)M3b0Ksb%zbY6clP}> zR&(|Yg;x>l24y<9gIIw;d%Ol70A64k{tS}+OBgeJi%$$W$X(nL27-|;Z#H%rDg3Re z4Fd{iA2HD4cG#1MxEx(8_mHgtgw&{>H}50|sxdOgpf&}$GHSGq^Y>e6IGA|jH1J={ zcD}hC-X$q)Gs5>rpd(wY<~5{|`f<)_4e27rx6_=9!&+zwyH8fpzHO;SxdrcwR|`D$ zC)Oe`8G0E&53Av(gYcHD{Ip0IlCl5t5*B+5i>2Z@DjM01CD)i1DU>t20hqIq&t2yE zCg@Ml=;gFbN?{UU;PeO&fHQQZrob}iliwP%7eibY9P zRuD8hI-`2H{ZMx!2Z9TNYlC}(`=Za=+K;mYvg?nKk3$Fuw}f$E_EfNfQ&l-u1+f^Y z4I=1iEsQ6W&xIo}D?p#Oe7JX1mCTjX2U5#WS3sAOmSEn@%6Dh*V?yCK;B3xvx{B<{hgms@4nx!~ zRs0?)a752gQM)iNp`~HednzXPRqTz6Dm+twslQ<;F*a`i7Gf7sme4gP4TW=@a>}pJ zcsQv1RPswRo_)%1(&X$@eyj#2I-m|QjVj^iX<*?6bELlCopc6IVm_}cA=BwoR3W%w zC_@yP-4r7&w3*J%ushAjPV8o9w?s~8c}2!rVwy`aD8ShwXhfKKeIMJI%PGnKkUqE0 zG(wS}i9#5nGIgA2ySC=ChlsWit0@PI^``ogE+s0& zr^l(~qtVoSIIKq&q-erhsfgdPs(?uC44_F#&LSq`ydW*N%M3FelU^7J%QY|Ll7_wb zE4$wzG+=5%Ia^IcRk*lE)pR8b(A028pxbLTe=iIX+Y+h1E+|QNA@)EZKi`>+E~q}& zx#4+RL^)UaUNl zDRWjdzZ(j~D*8aA$k!7m(^TBPmteFL~fSY!`9)5yEh-6 zNuB5cQ>kUwfSL#JBD{uLtZBH@v#NWZOp0W!ZUN+?MRUBsh8aXF@i|2kvo<(4$QQ|l zJ#ZR8_Y!z?gbKBjal0mFZLsmmWjF*7M{|@`C6)}sGHNX*O13X5LI)2e&0a@k6yhX7 z9ACy~#v1F*IT9J_H5WS7_8V%(b9H~i_29!3{F84{!;5Jxm>JQ?VS0Ey@DHYN5e{0G zwr-X%obAk}9+6EyWZShl7ab4?$ZKlZnId!XB%KJ}1!^ARj182*DLpKOi0Q|jZkzf{ z0djTE2Tr!pv-Z?f5gaj}o@Ee%J*kr^3R24`hnA;@;kAupb z+2Y=uA=LgG!u8K~@DyL&4jo8A2HGc!)Dvif*7+mqS0g>f;vG~-@mvwK zdHo_;nLRTOwjCVI)qQl@esC#Na%Tn|FvUz_}BP86L*X)tJ<);ia0!)T8oAna9? zrN*USvY|4RXd0^RR5lb2_Xz0Rvr0X2iph!ll>zy2weJ?ClD3zFAKC1 zQpJ;^VqYk6XA`I7yWq+zRQ{9LD`qID` zgy(sB&WY>iarh~HbfEu1l9U!LlbFKth$`8LlL;c~|s90w?wEqD)Ng`#+F;3in2mG;vs z5yS4Gx`zK0{m&w12c&^ZIh9)br_lb$UN`&q%ic%{nmNg*eae~1tC^F~Qc(XA;4sr= zX4+xhpKzrZHzX|mrMdZ>qa&eHdqZx%(2}hbvbvcUqkMM`NBJK}fK%M4tkzTj$UN_(W0PsbI6Q*db)+UP z|2$B$z8+x}ood^2;y#C!gxPooT`k+x7Ao8b%K~n7<5JGHIzbm%`3NUm$Qj0iP2> zzMdK_XlYB(&)&>-OtGbiHQ5w4`&BFn+CHGx?8Ll7z{BHo*%or+Hn#s-#@OBlIznvH zC0vQ_o!hNigG`%)iRH-lL;#72lLd;1>R2f96M(*oII zK}+8G3CG>gGeR&IVeg{VbuA(p8WA%)_=qxdK;uo&V3|2U4h6pi8|Q^=5suCNMko>> zTQD&csdpeDR2il*JaPEte$L=P8DUlo;A+iZ;`D0G-SBUSsP~i42O^`lwivy&;ppvB zpA6e?2;!Et!Dbv@K)NwlBk3uZ(-xAC zgIrpv;R-!NqDq(p)|wOei1LR3as6*ZtT&GUF;bx%WtqOvAG0!91kjqvJiFF3$9uR6 zuY{e3U;c%9qp-tleO`cONUom8fSpb2X()qrI*d)LF2CVOXN#OhF6>|X?*|dqs zDecUTzLvx3+hLbyzERYJ%Q5BeN{_J1q>Frkm+@MO@ks7WjAvfMi`pwhv_p}HrPH!| zI!iIx4-7(z(hW~wUJt${cy>aQTD}1zoxn!?k#$$l-!=pEm!jK=h8u&FKn4Dw@_Y!m zo{a*~ADB}ZRe;pXV4duuo638w8S^8pm7fC27szR5TWd5je61`SLU$k%&kdoALfOFu znuA31smv_leis8O_%B=FWa7K%{%AdKBd5FnZ~6L}74@Rf`$e2);2}|j78~F+pPe>+ z*)QfnfwR5VjVOl()EkKbMykL}5a05w44flKnEeCkZ*#uD!M_uZvpFD%yF3F4KDc2p z75q8?1=P!+C2$>JV*6*rGvS+IG6>|Ob6XYQb0MAZtC?GovG^p(?a5CRux+I?nspm< zvDjuIcdXQ~q2rg=$hN>>BK)=dlW3AYy{~pi~-7b z4czAf_urqd={{G#Y~@P|U)Bj5=oHl+P_wHs29W~FuS2ur1Obj2=O<#c%HPj0`e#F4 zFQpe|4kpBYU&Du`A-6_DzNn-a$BvxmbGt;(t5eH+S^tcqy=qPC@7RuInG220Y(uf^ zO;?j4wB$Z)#`vTB>MYt-{LuGWBZUR5QRz(gXy-k-9R?aG8=ZE7`3fb3-8JTPG8mz* z%r9tiT>0XQf2Dk=Tb36oi`!f-;p^Y<=2KurwbLnxE)$ z^ijx8m#!H@wtDlnrPwS&QM$~-+(77NH@6f|w-hI$G&0&YhS57B6mPN==YxXfaT0la zUnzdMQ|12rBFc@^b1lW37>dV4C?;5ngCi7YkYXRDSYatXX(`UN6n!xi=ZSk4sXwyO z<`zoP`~$xlYENRXhc&x&>b44$C<0ccn|)8i3Y|2JHXXU+Aj`I=c^8Vwn585E)y_je zfG%$)0|RJ|?Y<$25pV--{thzAP4R>#DL1J)zaCWdZI5QXwei+;poQj1i$eY3J zE1CV4IQ^C80=~S25}9-C1?ZFfcnX&Bk9^kha`5L!`~=@SWM2YV?Dr0s?sERgrD{3Z z22J7Fn2_DOBTq28!mv-#kEax>@YTA(Askf=dsz> zY-0<;N&%SZG6Tz7pM1dzolON;Us-QjL$z3C!-h)@7#BV5v9eAGBn2xfb(xLY3@x+C z^@9JiCALlA!n4HI8a(v7lTEY*HnHGCj7fS|s1F??)(RwW=w@Gs@g(i@?3Vb|kb@0+ zc>Ic1!z8eUr7Y7M-8=n-I~$>cdNcP=R%v#Y5UMjjoDZXLT-Iy8zZiD}+=KrYWdPF7 zAJNZuN8H(Ejfuv(SK-tKbKF|0%&sj>AiQMSxU}4sV!ER!vpQI&-I# zeC+CXIgx+^L=)&f!~D>e{LEJ7cbPSK1wS&JaO8m;<>m; z9J>V{m-LoMw^*3>`ZBnL_zA}q&TKYZqV7k;DF5oVxQYY=8yf`!kKMqd$pgR6&DV2J z^GF%0ERsfzgJ0fZV6%7zG{Hf#NjR6)yvww#fQLfIdI7HM9@GkG5`ztTA`<@_$Rh*~_uoRtX^gqHy=ep1P<^vE2RxeFWX zdkS8?X^(jD^IDHJPpF2tm=Fzj&fqr|)|S59_s$yo+A-i|UAK-G7T}xh6A)fdDAvDgIi$K8$DTbr61KB;>*zthS)Yi9e#b zoPt^lybdXZUxpx3%T{5w4HKr!8jau@iRAx>^$|j*mOm>Kc+4+9ll74jygEa$Q+d%8 zDk}xl%hHB!HJ42r90lkeb0<) z&&$`}0wd(5WKZf{@a|UK=nc)?)B#BTbtY6k{x8zQ*mAk~>vsW@cD4u4EdHepk|ynJ zlje&_e5udU&X(yj7_B#R^jX^3`}!>H>~%iF##_LYEORIlOjQu81i7^KVe(sN`onXD z?%%P{awvzK&IvsEg%)5Kf}dllx8<*GK^Iw?nUW@Ozzj~32uqDQRBH|vV=$TGt#N@H5h2h)>P*Al6-=iWynXVB_cm*oU1fKoNp&Q;`BlnGduZx z0l$|17~(u@)8Dhd)A)R_E5fEJO!RR7ia&V_o>QNFl|I7lFnb$+!g~QRBug;cYFKV$ zpW?+p0sM>N5}gt@{z40%Yz;990{03cHD~f;7#oi)fRFqpT50DVm9ZtuQPWTyxRSGG zYOtY_M0=Ac+wioDUP?y-YVFVgaesOhP9%js;9N zo!4n3qt-kv5})|<7sT7M#56?i&LyGT4>+l)E+r2CQQf!763c=jjBY_bwd|ivcN)vN zW((vi-s)0j3OoTS!T?UE+d(Y!T`%@Y4)-|%ixV|c%ceA7^szbzD<$~6$6wHPaRp8c zr2^mWBS(yswE#qQr`}|S5yO@PeV3~O5C%aOH!rI@H$Wi$dxA3T(vt=&rloJvrb9U;d<$vLE5T4I7zoVWoCrK@1d_XJ) zhQEVj&oL;NLCF+W{{<3&$UgYFZ4q>JEs*B%A$IhguuOf(MnutwxemX9&S)OcbBKOl z(m&fve+{O3D0rfm{v4#m)1QPzjNt1!P7BdnNP1np^qx|BJ}+WjVw1yHkgk>~&p!K_DM zi)#2xerrrFyamz`kNPQC7u*!whZnlmR$zlhe-`qCK_n7s2jhxJY^F#|O0;l)Ld`f! zN$owdUjR;kU(Shr<9i8gejBH!63^WWt26r+!_v?iDmt}U)v0wtm-4Dnrv~<*=IyxG z(+)P$9%91-RWMSGW8Kn{Z3OKkyLk=J z19Lc5`ij;x;0*h@{_7L?xqdQA>Rx^zwd_%Fnss14{>lh%3OY`X^oA^;7i63POHy^_ zIV59aw9k+Ku!L(8p#oXV&G-K<;eXp?|M``oCql!yql*&~Kiug zO6rVH5URT*k$+bCss}KlZii21yCkKSoh8jLyCVdc5C11VcQ&iv%`RQ-X>^m37T+iw zl*%SKU>7hz`gZ=7uJECl$mec>32QL%JhL;1OMSW7_rv|m0Vk>^AYQ9Q-uo3YnhBq~ z%q2%HGTj!r7po8~((o5WM#|&IB-S6h*}X~eSS#3%-vQRme!toy*lMK33-&Qul6&$M7;<{rw44?bp>#Ls&ke5^- zv0{W77m0c1XSVdYPa5CV9m-$GOt`gQYI$GSLg~Rqsb$#ufa4ds4CD7WXCM*JBlsLZ zC9&r6VPR~S0}rxq>CL_cQw@l8;$wH(DZ&r9Q@tEE!7|g$g=np^hzQm$`Vvxys(1s< z$)<($y%=fnnwYW>BpePi-0W{zZ)vJbsXFtt(wWYT5S_=5N~b^Rbdr(oPO}`2FR%x5 zRY=&3VxZ$mK*P-(lvRap%fBAa8Kbu)B-AG?{W-nKns&wKtpM@Crm2>{ zcMURhm|1HMe1oPiHz5b}v;>?2ib${S@-bV`#9%Vmm2N(kWtTehK7MmYALey`sb$x~ zhk~IrGE@Xk!9*JmL#?A2N-eudm2v@PKigB&%<(ZI0rCX$ma3__fl|(;2C|EWwr!BRux;qDaUaXC%s~=*-b}{#BUKYr&@NS zxiHc-LFi?_iDH;Mh)Q>}C+RC^T|JQk-;9w?YS}>o(*kPokX!#<1s1P;ZdqoAILZ#A z1WUF%@ej0`j%Byp`fnNI#Bvi>;N@IE1TC?b!aRl6!W170EQFE5YcnIo+$9 zPbd%Drn(}F@uadXWChiggKg31IiC3f@7z^0SPJ5F_f&w=G4%)e-$8=4)Yuj|BoZ~z z?^&eemZlqLYK|=#CO$;m6Ax-Y>jHzkS?YytTH}uV)|*oNs&sHGDW)@vfUxj~9iBt6 z5TAPf(DI9Wpp!5=c;+?X_k+x>Qjgh%pQ#rcluD*U3&Btsx$Yr}y0uT%X0X&;Zx-~0 z^@3NSfYtj-P?AVM=yVCYmumY~<##iFOR&zCQ1mEEn4|@lb3Vm!J`382w&MBtcg`x? zNLk!MwxcM|q0u4p)~BS8IQ9xN%oa5Szw{hA7+aU|JYzU$1VV2`vg}DKkOyk3t9?o{ z?eP@6J7WK+wLwtI{O05nhTC3v`$WEEN8TwB-s(&S^2C9lKsn5YOD3kNFji-N#*`Nn zz`#a%sx^~lkdg7yRxopECQ~>6#?`>4K#6aBaF%icGo5F|@MmriHA@=Z<7g{9Qdtgq8tz4Ot<333I$~nfezKftj9~9P} zg|%hDP{NfQ(O{r}zB4S_yj!LC9S6=87-CR#Z1Qzg1Jh3JIsrf^xZMxh$g?D zVjV1>MXl~K4p&@&IaGEN)SKaW*OA4ecna^z`{rZMOI;O}r)TU~Gblrc0m`H_6@`)V zS@>m1^Wd|YeikX?{j)_-=1g>hv=3^cN}0V}n5{Rhi033f|MY*<#LEn#SWP&LwSX6l zWLe3-!*E&nj;3)EuZIZC`sa_z&*&h3>y01p5@B=NpV+VPlOSs%V;l2kv@iXF8EW8=`VmxLsN=8wp88WGyBm%LI z4gM~-mo}AM8zE5$Fwr1pa~A@t==V}|CyZ`+r|H1;h=Ge;i;qr`q^OjzugvB^Y9($VG!7LQBe z2n+WquoV&5-7kk>(@lZGwp|KXGlLCnUYbJo_Rdi}%`jU57t03SN9G z8LI|W4*kKkQTP!f7pV~LqX`USaqHb3+6`P z077KcUm}4>pTaY%&MZd3_N-~yt+^PWK@KZu)-&ZrIKeA0xu5e@Ce8#|LOd%FcnWR{ z{ux9=Ss8pOHlB|0tM@cCajZ7-feJ{o->;Id=jMVhSZ-*0txV~-^^Utda31Rm>Y47J zV9j8aztf$mWpz{?`mZ!9bg&P*JqMfjlI8d)4ZfQuOEG7WqcO}+oG)`n))r!6(8$EsT&UjJ@Bp<+N2lj3);i3Qof){xjjDc~^#hB;>|U0vegZAp z6{fSTx)qCNU%mR ze$Jl0ILt|{xjKpygj!{p;9PVw)`H)|hQw_$$?Y%VbUZX+(WJ4GDED+j!uLoZe|Zw;N9sl)xSK z3lyf6uHj{nX{Em+n9hE~=Puyga^^-%jcE+kUsIhlslchcui`Fy25Pv`T6`urZB&(!BP z_x`ur@P4{Z=x#__pUo`;VzJNW<=c9apvE^`YSu2mV@myfXLAW23Tk-3-5 zKgtgjp5t^&@l~^rLKXH-^LNFl;Fh%L^9ph2oc43rNX4z2E2%^3C}C9J)IGJ!}_&v#&Af z2od`HUAUZ;a{C>g%k{v&G)<>tqe?o>Qla4Sm={47g#^C z-=`=K7)9^0sg8Jun|Ol%3dgV6EqeH0OQl3;R$}kX=wj@r=HyfC+3wRWdN(*NRR7d1 z`WYGR;`?COh^Un(mo`TIhp!rJP2I3Oe(g|r3dW)|@JkbUTtP?*$&Xl^X&=Q896N>R z#)u;f>#G=ZggwLGF(xX;LdDp| zAAE6P88oLT1|qFLnSWS}L5lITVyuk8Fzkb!;{L?=QADaSZ4{%AV!RcDF-I|m5aWG| z(LgcIQ;d-@7-fR7sDx$zyIO-xz~*qarb+Mx-2zG*OWjD$-doNT(>$ z6pJ+N4OQ9zMH;6_fAYtpv|m1=3Kq%e7$sd{>qgcy-Rzqb>8lu|8H!Y8OG>mzf36jo zPFJM&VvvR_(rSyec9OEULXiym92ni>F-Tn%X`MxS*&;owNV62_#u%jI6ltSHy4xb% zrbr_d>FgM!A2E=FBDPwjFGvGseXb(qDbgSO@o4WoMKTuYpjG)^2D|Ysj3RvzgY=jp zrJ!SAOIn~vH6Mv0-ibl#ph)Q!=^0znSVekYk%q+}r6`hw$5GO)7O96K6)Dp7 zF-Tv3Ac~M9xqy^ukxo;j97SpsgY>#0@p}NuRBL70#YwfBeT*U<=8s2v_bF0ai!|RN zeXK~|eJG096ob@8k#a0jxkV~gq{)gjBL=B{n#km{NCg(jr$`Sf(sMCLYZR%#BAsfH zPEe#P73uyMqzQ`D$0F@~O)K{&nObKzP^9tv@hGCdBK5aOGcD3oMf&0cQN+nHC0(dU zgDuhsi&Usc6BX&an34{>FNzpqk-Ax=YZPgKA}x+VTB=CHEYk57si`7eqDX7_a9o>7HNt_nxsf86zTdHq_Y*N(jpDDNDnB|vx<}% zgS309C}N^T>S&R!P^8-wDJ2GJt|CpcNKGtKq9UEENSk96QL0E&EYdfxs3O*4A`V6D zeP0x@GzRGgMOtl`PDUDou>S@OmK;aM@ zi7YeQut*0nMTShLDbm~+q^A@q1<^VBh|m9}>@8QMT~kF7 zOJdmTqDbi$=_QNwj3RxkNE2g_(iDlyC@d+FdV%(CRit7?x<3YK^LwHQpG8_r8bHca zB%dN(6@&DyA`P}kFI%KqZcKEuPf(=v7^FuPX^2I-+ak?Zq@U1%qbJ-FqrLWuRAP}X zwn*iQG*yun#UM3Sq)Ll4@nw~%K#>X+X+jLrhId5~lPuCX){IV7q-zvua17FGiZsO{ z?U|@0?OY*>XsSq8#~=+>q}3MbR&ooK&s3yuG4+HZYNx&A}gn z-v__N!utB)SHUlWp9en+RtHxGmj{;ymjoAKujahqr}(^Z7CtYWj?W9H;q$`xg6{<1 z3Qi8b5qvH9O7Ne-mxB|6FJR66S**D`L4R;uusm3b`9dR~U#FDKIZYY9w=^NqGv(ua zXg{Y!m@4upt_MX8m>c38E;)gVlN|)W+~@qm z=TC{go(vz5rua%%r2w#K6O@6OCg!o==YKfAMZ7E_@Fk2SGJE9wh6k(WJLl&*Ntr15 zWX@Sq_U4vel$ltVEb2xk;qq_bxn4NnMQ@&v{0> zEk(7rBg}^C3cT{7x5)nqzk$I(3C-XB+x-3bRt$fKUWnrFzg^y8wlJ?goVfCQ1AdiB zG-qy3V@%zfan}c|11Gn+1J|V?u0IG`&3BIR4H$t+81QIHclTDrvy=WtonrIo&W3qz zv&(OAnT41tlue)o68wZ!BcemNsKDYUi{KQT9DCh#IcLZlZA6p17bN+$beM|q8>-0!}8R%D~0J3P4 zOzSU-OzY3`IVboAX0|s1S|M>Bu#K6!XGvopWDL14e`d)|_Uc$xG+w zkj%)1nZM)+;`1EUAx?X&{9^urh9&Wd$XW(tMNVpGCpQCoH4EGM*X8=Z&DxM#x7X+7 zVsG0Yn6&#hurbjiv|CzulHhl~dT>hNDLw~B(>C;7-6f%D58Jv#Kyv%$-hs2khTs&V zU54{joRj}ubT0itw0{~A2yD?qt>Lr~g^7cDa2;+(gtzi|sC+kbO}^V^ zS@(833(vz>6*i8CFxW9R+Pa!Ex6H|CVR5XVWQ8Fav>PQf=;gHg^d+Mz1+YeDD9Syqn1F|C79i?EGhW zPlgO}^8Nvz26;P(B+JdWc3iOg87prgkj$Aj_fwnu)k|^m(!O&2-)Pv4VW~Kefhxon zb8|W7L2TAoQf5QT8;}dH(F5MQ`4{Rnw!&+)Z;;=vmf@+t8mB%x8tL5!tjKcWgvxW9Z}7D{QrN`T>MsJ1^1(=8)miK>5OIAdA+hk>m^O`emfJVfreV3( zZqQLzK|NCuM8W^uVWYy*c)>@m{|{#<+wHrp_riCUwsB$CUnDQo3zalQk7LA0y}Y zi@!yq)37853g#UY9_R=T@qIq%j}11!R$ z);)1XF1n~E5YBC0;cHls=3L>wtTZPH-Ic`dD*@tM@H zWZt)u+`F)w0R^FvC)#)O_4(~~McQ?1ZPzjmwC(y>DLABGTtimNVcm+Ssq-AP*PW&h z=m%G6d*=5HdH$#i&KP9j4kE^a*mX@srTUz*(7Q7@$qd5Me);aAv$1e_;aWm*qZ2n~ z5yzxs%tpi| z#YK_-6Rwx!w_$~G33fYSy$k}$&W~!iPxAvhNVzo@qWk<8njbhlbFP-_uyW@f1B7|} zGoOFVt9}-keD3FLuvdfIuoO3O42NQ#LNUmaqY8vN3FQn|C<}7D74xq-Au%&JOBZh>a*l@f zxZwlzLHL0*vlrbDsOZICagu&qAw|9NnG}UVNkr6pEjQ1iC=$pzfV}}(pJi<@#XwT| z-r{^UQg}}WY24&vNzMNN_S!{>*TNF)NP=#MUDHsV2dVCh=_H-u3U38%1+PL~92XY! zN-Yb^8Y1XK*c0~|Qpya|RHe)~dVQ`PCwyhE7AZ5lQjW$zg5^w|Ej(mcDWzh~i@;Ms z=W_<&3=I{2s6#@+k{r?U11-&K$RsP+H?q>qK%0UNrdFdYY$I)}?L`JzW%6b|0#$rm zpS3{`Hu-A2a`3%)`dV|Qa?+BW=yr}{-Q?3q%o&cPNcF5{{|d(U+SOhk`o+b~z!DRO zvy)T=b15B%+hG{heKlL+V%QKfy*$ka6VRo36VxDQOXO!rU9X3JR0W?(iy4~EZRR4W z#E0DEYgVz$2QYcyRyi6oWi~CrA1M}qqBh9Kl>h(*y&K0i{s-F13D(@!(G{aBl#4An zY=n{KD0OO5#v<2Eer~0xqOF(tMKUD7eaN#y1i*lvN}*#3zMAUtkR-dsScZleIfI7f zCV#&|`)R`}?ovakCRfF4^~BbY#V@Hx)AF8eV`sN9IAa z0d8^XDab<$!eW;~nJV^u!p!itlq^PI9^d7MxGhei$RgTNr2bFx_6f_|C|cetX?|{U z>t!Nu{}_3nl=w2@Pcuc{{vmmPXY1s`JLD}wperozM0hjE)t~Z?fWxP}0|j|#|FFC- zK#MBxlh(NZ>+%i`%iBVV2-j~nTDhB?uvFw75+ko)h7&mdjLV(Q@F5|26Ro@%khgq_ zN8Twi;~GAM@{UIbKzR!VdFYU^yl+8^DzBe?HthMoF7L3gyyr;~VR`S>&SwTT+T{Be zlt{yXM~axV#9zU!&eZ|K_; zoYguTE|%5$noyY~<%BfwnGQ2rLw4;L=4t}wt{56{RPbJCAmUst?=RzB9Zxa(_s}Sa z#~t0F;*4D+;!KPe=Qp}0h|`>mxXB#=2sSNX*hMvBj{vAWSb5bRrnw9xW+@;#nQHSG zDh?`}gfiIM)*JdS&|<>T`L&ktfyj)8MY3M&JV^HhX);LJ?a&0V^~FB}%%pON<}9!%VNO!eoe_TT2O;TO zXrT%y(lh=7>9P8rAY(!*AY-(UW7^Rb@Wx0okemWeQ7qxS3g}_kd=kal?8RfqW=eR_ z`;3e)W|0p&R;V_&u~avC=zI}>t`hZ%|0lf_#5qgp5<(m2Bs6OpZ)+Iuk2GEkz0eBk z%}H$U&H_Txcn_AU@or@>&vB#(WuF5r;}5e}i;f$06UE+w5~R7wFJkr&eN};EOzqsJ z?2(bSrkF*z**AE(5r66kD!IAea&wb%BNUYz8IgdYgW*ARzoRg8fikolVt}F5@eF;& z&JFtd{e4O!5UQ^sw0N+Y0}elU$D^-Z(mn-}9IhUt`kEmG94R8CFQs%#n8StAXrfhC zq3vWF_A-LQb@3dYuN;yWpSg~uV7sxGp<9$8qLQI2EkkE2Lqajk5T=6(W@UIde&JCV zs#Cj7Q-(IiGxQSO4i6gV6{Yj03PVpLWD~Zil`_LvKvXjHE^L;D_6$KCM<|9F;%v{f z2{ZIBbeqTITA9I1SbHZegcfLZ|Au8E9$+A;FMc5IF z9+T3;ci)6hR2P&I;V9e+zbO`;y3ZD#Ogv9R>7`&*uV@(p5f)iuO1Uhc0GQ@IjBTSu zP8K1OKl((-?~Nzl+>&pv!drqE#;J79>SNG2CxK7t63ZaJ z*3SJ}@I;Y7e04fa+D)E`t$AoqDe(n=&&~~^)xS%?4hB@UgV>`U-J*m$h+S+Cfd2~c z+CA>~BgL7efKq5Duz}LjP+GWysDFx3l6LeCV&pI~kX+3zaSG?{AX-~C`;bk|)(&D9 z+P4b-P=t@LX|@|KL@xtTFq9rI{zmq0+Ist&L+=nedo6SjZoQ4^q8&kHb1|@Ww%&CF zbsV9n>_~s`BpkGIQ&T|z(Mp(`Y1Dz6JaC3^lM&C&brEg`n}?K}j$Uq_l*z{eqLQ22 zEH~FGH$pMQje1)XR?iJbVdxZPXehRVK|L+w8JfpVSJgAb{D>eB)bk=RDa zG0%D3qo*qRC`Yi#(`48s&B#ws#}T4lJqcSEh1q%@?lD$R{gkbjv4aR~<;1h~H=Dk) zRYA5+SGM-N=3%RqvPEpN)zq@}?>B`lAsSYdxS)v`L8z*Zl*jY5<_V;^$!{TW0iJyE zJlz-JsggYTSr9JO^76#^HB?1x^7J@tl&b2dJPA>+s)Vh?FkAN?g{{k#t+fa&fUSaf zwl=U=Q&rJ-ntx9gwwAx@QPmNd1qe3Ts)3o3t!jcgjt~v2O8T^i!sGU@%Lo(g3*LB~ zMI>{V3wY`i&r`<;Pm{<~KjrCCFHiR?PsAoq*IS-0SDu8ZS5?B+cW~fZgYA#PR*JHf zsBHC*XG{8LRn-)-RXs^mHSraXs=k&f!vbQHtxsU7RMo2lbsQlYRu#S)OEA}ld71(T z8mp?pB2m?`C=aR{9M97U?9r7cxYh)7x$>0c<>?ybiP+>R!}64(JPA>+s)Vg+aIdPW zjsA`JLY6P2X`C+M4)uRM;93dK3 zRU;BPDa=zb+-R(-@|34*F^2$8!{T`|>?D<^Dw5-RDtP+gpB|o?D^J8GPy1mK_O)KNie*A0*kr4p zWvi>QB}BujYD^-(!J8>hHywqiGnA(%FjNOm74barU{0&5btJdtHR0(ac!+TK7myi) zV3VgcuvDt*V}d%45cR4`*yC=3y4jg3Sp^KRbS;vhj(g{@pR05^FJ zhDk8?8S!kbW4DQ6{lR~M%xPro3?-wmGOYg%{ROb+0$ZbAK~xWVY9<_gO#l9aQtSyR z*1~zm^nGoaWhm2TN1|Sj09ECgP|WOE9!45IAY}VufCYZ4;-zU|DPJIzX9h#s;kfrN4 z^=668P6V8FItjMRI;{{Yv!omkhcjgqBbt??5J3DR_JRuH8B0%;R7aHKu?fKMVNb3N z8ECLaoh@7_1HeuG7kYRL z=QXT`mdy*p#r8n4b}be6apDCfZuOSfUoEwX5@eQ_;K%H0A;%_$DILWe1HGC1;4V~~ zwbB+uu<(3uff6l5hmZ1%5=E_t^>dr0J4WdeLZ@wsaPqXI1md{aS3%KXk5wdd6d^}T zy5$kIq>e(vky4aJnUU@yhXv%ddxS$<-_wYK_#}E+@V7Ufzxi|jmeT=Dvx$_`V>*IOc?UhL z^4_343DJo4!4 z5Xp_T4E@?8YAJ&AA(TO>(ES2HdUQ=(N0WDxFUPSTkUJw@?jPv!Aa^1PPzQCsl2KT3Q2WtG0J|lywcDe8!62D% zbni6l9w~MN4^2@xuQQSU8D+XJgvms@yst@F~=u6^??#p_2lTXy5hr}2C3f&77x!g|T z0TJ5pkcOU*o-PA511I;~IAn!}f}hA-W&sJ($xXOdom{a{nI+|TID8lKX=55si`Ja~ zx_eei7klf9Y_DeW#`<+3jf?_w050laLmwVCetMI$k zRgsUdFPg_v-QULx`tgi^z zLut>5r~QPb{f5#O2&EkwLU#$1pN63=%q~iU<21-Iqe7UU8(%;RTR=w?pawBe$tbKC z#AWbgFo-IuO!li}!978@OgOqV>{Yq`ggII`uQj|$&j^LBc{)rc;>~9RRV!mN2Cb0C z!$=d_s+)W_$bz5M@zVG#@XBu*Wp zRQDxo)lJ@2E~?uIVAP1WDIH56jY`S(6LkS0RCPV?2q$<{_b>(#=$YzDtjdUbip-Y; z6~xV<{z`E>Lyk%jO8P|x3j&00mrTZ3s z z5w4J-#R5wr?5P*gn1KII1b=Zl;giIa9f9|>RVK6}5@Wq>5_A=h;Z zRiPjfrc%mDo>a8U1ohE-lmU{{_?3)rH%hAZn0ANXY#DuA9g2I+5s0f5hvdxLNRf{p zYD|+)<(O4-7K-E!^}wxQX!MFcfD3(Sh)dk@K~ON6fAA&3E^{K|3HTh@we^!M0jOQ( zL*gR6NYX6^F0HRM17PF9A6b__l;er#{3$)T3VS8faHcHI7bKhC(P0~m`@1vzJ)oTFt5eIR1yY? zm$DiX2CgTjtOp5$x<+!XxsxxwqF~78>f4dr(bBn^Fj-MBM9pOKDHi5sA{-k9LplkB zIUr|i)tY^!c;QWb5!ngTm#BKp9`?TwW@Q{qTf%%~=}aTcQ27#NPcloCv?;B~tH%*)bZ)n=DLk!h8`0 zL-JLGnIp-yW)@$j#=)FM)aNbCvxF&+gE`m-$q!qY2MBXl9LzU_xz56LBTR=V81mej z$>$-N%)Lc~lcQjm+>9^{ES-A9Bm?_#6=Fno!VD(rPm)|~HWOxj9871z%(pO~66V7= zm<+G zU|3cOlOMM*`)7)`SISPhl9UOt=JqJ|w2Z*o@FA>>U);EM% zBgwUVFr5i=l_b}i zEBSJ96byNuMAQ}*<^;ktiGvwIn1AE4Q8HIM9527fi?<)_Lzpiu%;$tz8VA#cFz;KK z_XzV^984Nv#v+-_l@jL3C>XNvAd~O5Ff}*frB@UTQGJBzD9IRq@+B({=53;$V(FYj zm}8@0SQg{GfdhXiKSPNSz)N(!|M(P=H%KzZKYUpk2h*0QA6Yuw?;4mK1;eslWb)G% zrZEwUqhKi45W)?H(nyL6K3m^NdC^k+)S9y;$RjM=3_~&HPiX>P81B~N+;?wmX1T1(NQogtB}d} zTbNx1c)24ErhqVAEzEMlw2OjaSr-xJY)QuVzkE3{4yJ;rNAxCcb7&Y|e#c9+>^qpe z$-?v|!WU66EUStzb0it#AHGbDgE@_;&kLPe^DJS?qhKieFeX22VS+c}<*qoGo`kv1 z!c-HcLmW(N!klMe-XhG&76u1wEDto3ms-<=VD-P_DvXWzL$R;qpQ{3&+1KR25_zgM z{Xm4%!&_K`?<0|?i3KKGIDBP}`*`{j1oA(jpcev^^TKm1>Zy1SP7ORn^YbzczoRrV9cqVft z-<@m9>qjP=vu;09?+nKsj3b-g9^ia~=P>|=|04H;+4D;d`9}Y?8WU^h#-ylwz~&+? ztE#$lX0tRr;mWD9W%%V`$G8sV4;)!EkLeKj@IK!(-+A^E|mzqN;gLQ#_MvLz z^^hVThbcG9cgr#-fmGIKc>})17whH{NCkike9k9wR~QszV*Rsb2twtx_I=_**QtFy5N9~GxJ>>T+ZV{25iU`IkP_N?El^jW98sH z5T37=+j|~@CkghFibcF__vWn4Kaa+Anu)C2=kP#X@6;#*sJ!$Sri z2Kn%0ZKz7K?=DtF;iYEH0MtLf;hu+Zbyn393D?|% zuC8=ZiG<4f6L$8MJhDN_B2C zazDtQ+jOp|3sAoBU0y|}p_==6gGl7o-v`%ywhew{s=A@*C(;M`d!JU_ja89Q-I#xU z)!kC;uULNIdrY@O^18_ZG-@`}>T&%WByw{PLUTC14^6uRbHg}PSbkjiQwKcZ~{)DFq-_IldVH`w++qymQ`gLOM z9(#wSrqku%eu>*iKPgib<(vOi-ObzIc?D;^^Jwz>_R_F@{?)#ve_rFO`_;Gfug1Ps zJeaUWoIlC)&GeIQ@{cFd!wpZLUzm#fcyO2*_0Z6~ zBf*(nW;beAESemq2?`G~*lE6j?wR%==2bp-LE&GBD1HO&=Nza`Of5eErQ)eUD(|J^ zQ&MUgS0 z7qCWffaSkY!&wIg`8)N;(Gr6@R}2_ZUCIjNKb);(9)mCHQnsTIUz19e0p(1X8?sP& zy^x7?Rvywn#m;g~@4$2#Rru!XqMNAkklU(M7E6Ck0&7Wf8k3%*LzAg)Q2Hy_ed0*q z6xy(y54Wn6sz4zNitzjK*Ma@eq-jAT(aWPYcjsfRc>$(?`$0e@Jy3^vpuLY=-!Uh) z@2eVJyQ*vAajUvENLbaiVS`m&lkl62Hq@;@PQoAL@76zc&WehzjhIl;wQ*Kej6H-8 zA}bjMb8dyIWB>WC7$hI%^d>Ww?+`ny3Wx8B96t9E)HCMam>WSD3bi;=zgRxD^^0wa zQolum{J%@x<{VhX$}Q@MhXzF%r8^UgaL8G$8H&kBu%r@|%C~zsHF*T3qK2i;yBz^! z;dj9r+fE~muC0VilD2v#2!u592FF#R}pL|C@A(GE7BtZ z!ol9La6}Yii5h$FHG+b@V2LfJsnMv3;2~%x*R#Y&2hDz>ZOUNk z&N2r}YrI1(NOxMS2fxKF5meR@NWwdFpxN~u0Max;eX~y@p|78~*ZKaQf7@vsvWo{{THBwYm7@LU8)=Z;&WdiT;7ev7U7gDL~#VoD?M(=0@<0 zTn18btEb5sGbY>A{u|QA)&(T(%tXC`4p=qS=J#!mILviIbiW6k`nGaVx!XbM6URtl zvjEklu)(vV24REEW{U2V+YJbtZ6L?Z+Sk+S>fRC~-d0{))jF$c-AG;4x9}3o^4rR3 zU$f4vSU0ueTV2u}bI#A^>7y&WzXfcln?2&6cx{}3YdQWnL_Pg>Sdc{qtM@|D4!T(z zxp3i4>&yWDUg^X{9(ZVKhcSl_M-{c2&lA-Z{6}L1YB7w|aOLQP>uBfszq9Pz?J7kv5XF@VGr=*pijv7U7k<1ov8gj{fO zD|{)>dJgAVXQr(Yr^Tyrf;~8>7tBwjuEQ7zr3^Ds~!( zk+&BkpKS+B$hQVE+V!_US*Cdv&CNlsIxoA>S5)O3gPGw-PaRc1;e>82(s%X^uvPtmHV-twG6N@2(yBDxX!RHCR&6wHmkis zz7&&3(l-G0bQpu#C#Jpz>o8HuuiwyMvGT)3Loi5+i7-FpWLRfb;u%5`jxFbp4^10H zVIAbb$!E1vh4)xN&dl^@N1apkzed4U_>M8q-i%K6w}s8{8Lyl%6PRTz=Zu@k(C_gp zYG3>J4M~skfzF&#tNv2kpLzg|RPf>yxc8d%>=_0$CWkSolLG^E zpF$1!3!|46Q8k_Q5muc@DX*;-V4c;VT4aE(0lw^Xs=Pm2zF;)ZYVA`!tzqF6BuV(< zjpGKr;SXa}*W>Sn+k~BFoy8eKbs$3+&xNV{UQ6ptH)NEH^v@=xeX3h<`j~PBk!Xv7 z{z#t(>yy9Qgio)zeO>s(B%k3DY_B5yqoDL@c*8RL1D&7gZJsj1;KIBE$ERrgw|N#LwP%7yBwoq?ohsROKF zHn&e5S0S}?dF#yF)Xo*Hv#hTB*eC$Gb>`=hI;%6dN$vbv>VQgYQ5)?^{{g|eYezs5 z2sw1q4!7iAjm4G z)k;%P@@?y^J{6$|9R1T?V<*26u3P)3Rq_{&;wB`!J$e@J3dDYS)W+Mjt!Lw9l1kw0 zC)Tsh;X=Fxrm%);Z>1DMbFg@ZT(6EPWw&Q70&pG#GoMJUg?ZpzO3h$r1|m@Psdc8+ z@s6ELsJ%hfJWHH^EP520AZbq0cpEz)*%_-FNzWUbs<{>Is!1@iUFyyHVy(Y^%yY$sUbEk zfP_W{>@>i26Lah|GsjLC8WY%I57;mkR@)bGD{=HD+jjy#TagC*BzT+QrxxlP@iPZJ zpyDS4rGSo3I0^i;c^%VE&O(y6$gy%2rxG!=2pFm&>sM6kmxv*!A{a8-BN9)wB%Urw zJe|>ddjn5`-(XMat{eD6k}XiA`y$&8Q#50eDiT#eFgJsB4=pg^14Dv072s{SN4mwt zh4+t1ipho11Wbn5R0}#1AEyb7(?%rnZQYLSp2N$P9CQ-1juYM+)j0@$mviiHeV-Cn7|&C4PZxxhH2x2jwepgjE)c2#4vne zocD!nJCdXcjf#nj((v~T>p`ew2LY5K#1LYmfvs$(jY!f0caDm_FB)dBFM%w;Tca?u z*1`vYa7ca)lS7p6jQ*(yhHVtJG7gdQ*e7ioUPEUHK*LH#G}vO?cBc5ael-LcJKfg7 z*IDM+nIQO@?mD{hIisIv(TUI>y5G=6NP7F)XxiMz9o7n4CHk+_l&Q=|{4)Z< zzpo+e%=$%yo*8$pB>{kyl2AJOts*9gfW3@Ro5!Vffz|Z`Ax+YTRyRbX-A=;z%7gKR zfVA$O)HH}k=dgdKzk>9%KpPQb=dgHn5f`p~*seMJTnI3H-xO;fU>dw+eM)sTgdB;; zE;C+D{ZM#g@I!A|B7--ID%s5;6V3sMFEljPR{Mpt2*=lWEa| zQ4C%98q|y-ek0%BFFLs@aN{65(4qspRUMy@E~RzYHil2x$~fQiRuHF!RW^n<`!A?XR_ggkJ2kzED(>^STP*8Ee*s$*(E8%0|KNynX#rMEYf7onyU zs+9bRb!MPfl|aubf!Z z*Xk7hRskxm;HSe3@zWM?D)Qy=S>ptChHCO0fC>7oeDVIHlIPgKW1O zh1CrBu+D@Te6n1*OF^xkCI1wus}q4z;7@cg$Q5c#sm$29r{4uR4Akh4xno!|zZEx& zNHAW!XGx^DWuhXfv020@GtkPk^a-YwmX~Q>+jeZRRmu;Zc)Wo zYee28zDD{$cQC$U%Su#Bqz3BpvsHZq``)}|73(;6vp z4XY{s!>|op;I}34>vpnW9I{o!RR-cx>m2q1FT8n>|9b7mU$=|7Rx5C3GTzMhH*{7D za5kWGE?;I^eOd>cG9H|gz(tr-qHzJBkHD#YYMcGYFMLzlr$+dze9{JGBph5K3LpO`+Yk)r>eWw23SW1t0&X6>{V?FfGPR2q7hkS$@){BjJ5K2}*s zV}9YYBvfNFXIW2xz*9J9ZqcQ{SwM@@^MXtxh0GU~UgCfVnL=6;=UWtTPb~fL!}g@Qc57 z){CGDo>;eNvkWC7b#G3^>By7UFsgERf1)E$5l{gi=Q7&Iz{em5GkomAt}AoArdb7x z9=$yHq`Q~ivzA_uGLomNd7(jRho*bgFmESZv@$~bI?^%vi%5`o&4H=TcvWFNdr5JoQRQL}$v5w#ga|wxV=2W_uBx~#n1l?rmdx!X zVY*rBpWYZlu9ZLjmIrvc;jFXr!CwRB-S{%oYEn&u{&^es0yi~r0o+u-;;kuPEY0o&;;&sLb%e~jHzSW{#DGlP4`tTPeW zCVm=?L?5dtq%qw2Ea5(oJ4tWTi`x?X)Dg{>#!qGFpMFOwf{ZQUSsrcYTKxz$iBHdX z{R3y6l^%Z$@O;3RnN|)p4Dh^!djZeWxBxt}aZ0UI71?FMb1AnX;Hk4SgXbMY&5FP? zhMQI8R0F_E!n1?B0iMC;^;e1d0-kQ%LuQ>8$Tq>VArgJ8-a;C~lg|>KmARAjHs!c2 z0ng{K)L#vrMp?=B5x#}Pz@&_mAm#HNT|wc5JyOOpfX}U8n@WI-jaYh=LqrmhwYP%O zrupc*+OwUF*yB$eD?)tmY4yTOruy8tK8xiemuZB;mi!^g-!_$Je@m5()%D%&gpED` zBRCNayvw~{atLBCn0_+Y7yH7n3=7NmyuJ-acN_)r*wHmxS8-COYaTw$Sw|73*sHjFf_qifOqX!u@NXH4dgptSMz^zSwkAF+D}ctL64ssckX zC~Z0mE4nZ7hq(!RaYHM(78iK5KzM@SO#)c3^#dr)_p9}W@)V?+h*lofI{RD809rS0E7&{nfIj}ak zJ)z-RJ-~t@421`R&*}FIzshQ26uUDHqGLSxh~Zvf@6OoT_h2uxX?}%U`8Z`cw8rn= z$2Jbp-UBAZbgS`$%Z@57*ynSF{!zX`ud^2F}p}qHHdtf+Y zd(AD{(^<9`$L%oz=to$#*UMS7wl%PB2%iv=&o%xX+bYD@ zdemV6rC+SwTWM7aC#@T5s`f6g?*K4?yco~HD)GyvJ28^G7!N*|m4GP02V(?v< zl5tY{_ix%85%Pjb%QWQX5UD28VBLk&_%N~Gavz>HM`M0-g=JWKKP?r;E1!Xyv_epQ%+ zU?Ar$KMPbkOnMq&@-0)P2`06eX49=Mj}R~!XaW`5IwAvpJl^Eyh343?@e) z=>e1MVP-Ii5E6D0H>(d8EGm_n^{i2r?e!GxB@Hyfq$@BYVd91XzbZ`Z{tQe;044$w zhKHMP@`Uk%Ge&B9o!c$MJp9GBV{qNu4#;JSd8EJAz#KB6h+3LK20QXl-K(N(#adE` zv6atRK|pFTKrV2LMxwh78Zv8!_tB!6V+_soI=3WHjm@OXW>}`^XIM0oWZBF>+00nk z%(f!Ubdt>olJ&J{rmAH#KLV~8jf-q1x=1s`wibwiNAp}XsbbmIvY9HlWdK%VQZbk+ z{zLtTonbHtf6C0Bxzz~E_Z<+Y;7qghQ=DD{@eNsN7KR2xioHnrF#CGW-)N|(#!t-h zXK;RE>GeZ7zkKQW{+$1my)iN9V*NMfe7u#RwES|M52;#O{)2|d|FZP_Q=Gq2tVuG^ ziuJ#q^H*V6s+94~;QS2Um0a@pLpfhldcHsBb3Cw=`i(i?uXOm8<9rpbC5-<8xU1k+ z>Ge->ez(%|*K>Y|e1eSQ!8~3zfLp!GXKWvMs^7y4AxLV5By7ur9bK4Lc)jp}*n0Am z@AYpOYE|GO7cvSD;3M>VO!lDs2))_8_z1n(z4!>d**!i&U%1Y6Uyumj!^|HqoK-M_ zQ&e~qjNv<@yOUwG&rA1*VxE-c5BagoVqfQ5FzCztp=v1n>i&>M-}W6ej`yEDhCeg{ zj9A2zAj#rhQ_u%$1NrLrmieIqC~*{Kfb+7WCMYdI!!WF0n+M4X z6idI>u$P1zthKQ=tlT`(KVr22plGn!C+#i%Hgg@;AM)GGyw#C_j_H$8*?RUTxa8*B zgJkGEpz2*tfNuE-MjkIvxgsM6PMHWp@RMG*kbzb2BMQtfZ1=-OIH4JS%W=N(`4#p1+QNsX4ECS} zT?oRu$Q^zrI=muM3$ys7iOeu-Z$G%AAYbSU?0+jxPm4IeCDWVSs9BVTWzkude{qttvIY}bIP5R2h zmS}|)Gp=Xw&l};^1b5|$L$FXca;X~*5q?PLC1#IyCDeUpdZS*C*7*jV8$+g30gG$ ztFW6?c{aha>0!9#?+pW5%5nbVf0+MrltR%zsjj+!wa~B01w5yJ&Y>f`9~84L;_d4! zdMmUHM(}=XIg!&aO<)yQHbf5=Bh+P@3BE4;0n8V4kTZyfH%Z7;c4-|fS|4rMdT;5g zS1)-o8slU-8TvN7qwbu(4pUFMRW)>m*|62D#x8O=1ZUI*cP*XF)54*}w|i9=`X3mb zbeX@?SWK^PHPON7fuaM*DPsrkS#+?+v|CDnug#lU#2%EwH_Qo!)(WN;JJY`QS-Kw7KQHB9z#Amiek6R%L z&4_tEZY2#IXL412#B=(E@OJs#bRgwXKKey$Nu*m%>@NsFs6-}!78XrAS~gt+w}6$8 z=}mMF0KD|?dZ9DKXFez>Ek0xZMNz~8x_|+S_`PL*4%ZY8c*LZuPAgYmkEt!)YD_;y z4BT->jEv6=WB1-jT=y+q)pNpCML2*rQ5^5e?08(7E+=|mmTEZQec?~Za6os15R~@D zb<6e+iT2FG0X+dp2^wz<_*Grsy2ZirD&c_7*v?g9a!y~7sW;uKVP8S4?9r*j+C?a5 zRaot^bb1%D)63xi6HIp0;g-C1b~l4bf9Y>>vwB}<3nPqMTejC&v}YC$Xe}@@$wz#p z8xQWaW{88J#4aou0<^bCLIZeS(;^9QR`eA_5~5fJr~f-4{=M$>#xT?C43Zf1SDk)a zHf$LNkMy^znveG}8zxXjhG#H7Wwo8|wM@3Mo=>``##ZjJMlm@39&egAv)OXm^LX0n zUOi+p(M6hBE}LNqqJL~L8g_imMzc{iQ&~21wxQ){ddX&(-t~bzKO+(bST@5r!Dvq5 zu@8VINg~oXsVcG=fy;l2Yn3*hS;FQEgX*o%1X0}Sp9QSIN`tmD`0o!O849kI?!TVm z{Jy2F((^+(e`e|9^XL5jrNgf==f6=pe9CeDrqb&_0BIMr zDLwxb=YL!J_}6p(@Y3^VaQT>pAQPPoO?X5rF;Nvcu)Yli+KjEXy4 z%+xUs83jY}#}p6XHGZ>rK|#AB_bx^5`RRXCcUUifGgyj)4T7D${y-d?H>rxfqxvb( z!D6QY7_>6)w?g^)vV5W}|A|HUbf^hadH8zm?llRyL3p`Eb!?-k z$hI7w;Nt=n`MnU;xhqc6=nt~3#T$q%=R5mFa)XrL%V|5O{9fLA)*KYai!0tYz3(FB zpH-573`+AyS8b*PbU|q~f?D|`e-o54zOs`1m3;8gjGiz)ShKyViz>X;I<00+s0W*?MO%Us+ZZD`>>X5%JZ6#odL!UJTxoOz?Jv)lnwAdmsW) z1m6CAgLQw$j?ycA1RAUB-+Tz z()uaq%VU6eji(7=+h zwSof!Io<_&l=H8EThJ@;Q&smR$NnV!6{Xi=@Y!jCPj#3~Wx~e=9)1b%xh!_v8sJk1 zZD@i|Iff6Tt_Xa}P16Ub)wU@CKDjV31ZZjkaso7F(um_VCVJlo83y>on8OG3WQSdI z*b>F|26C9TaSejEAnme;xIO?PX}9YFSMzRGTp2SLKi4Q%8eCA~Uqz zQ+}_IJfUDytb891_(S`KK$^r4=ovKb7L-;#$j@r+-KL6mC@#9=0-MNFCW2>foUa5! zLs9XZGm0C6QR-hg&9$H#fF$q_5rTJjh_t_fri}7cr4RKi+O(cM5%tc)5#x3( zJ*yPwpJMa<&d+GiTnGD?Ip4h{*fWzVmuk;kM{&@n&YXWipFvEL4ODw(6mnU-YfScx zh6_}NIn#gz9Gf%ZZ3TE#4)4Lz-v*aLukfpug3hqMggsMnTmy780#ni52nws65mfFv zZ}$p-_sR0w++LBUO)})C!L<2Snl@h>OdF#fH@8#fEL7>Xz+t|izk<&e$a7Abq{ou& zpf^Q7CD=i#elLcPjVAhQ4^>>l97Kjv@Vu?K=k~e$l3j-Klb~|B++vZS6ck#^ z`!jH4IDMyVhwDK<-`&U6Ku3oACq?d8A28$>oDo+_QGT5LLU%nG%ZQhBxdqR_yhZbi z;Xes)?lbro?V)PR#Q(dMxcBMIC8~c>%-;RFqR>Z;VedMm{8n>X9qeM#eXrWDLk;pI zMPJKE6q0XX2S4HRd1iL-En%-(*c;~Z=DwA{|1ER>rTF|h80R+vs>4<^eu=zih!*!pahGLir;oFE&IMt)uUOI&ka; z7iSk2F2cANaMji2$e34h)nd&flI)8XHg3D3PH^RINq+xZ?MV&T4fOlB zD`xPquqW>!r&N2g1Gu@kJqi6>o9)4t@TRm~5DD;pj@U|j*2~Gih@b%i1nF-sWj)!d za&i%6jQEY;eS;hqzR_sG$&kkd6}}btDMrs-P4HI`YAF-`E)ZBn_^X)wOaqQg@c*mv zf+t1oH-7&B`S%aj;d!TE!}CtjA2-EAu<1?-IQI#$&%^scPyGWy3Oqji%a8vce%o3j z)qV(JS^ffVvh=6gckuGgazU*MlfMTZ5RCF4!h6{85Sv-N>-iaoNDgPA1TKsH$|>cQ zfQXUFQN9{mH%(+>{Ai7>yQ8g#qphbhAT%)!kI$Eo(=jnd8xs~9TS8W+P;H6nvGGyP z+VNT?SsUqtQP{Z;c6IU^I>~*?WWMqoia)J}PIhZ2&Xe36-KW^|V26yfYv+sq?p~t2 zMd87&ZbM~xQK_B%5NG>I9#dYq^hjlNXd+$^;Hz;<81JXJX=6r5B*rIe?d%nIzBXJY zMZ|^oiHV8}jkODl4o%dwaEyu5+AFqh&bIE(wjR!a6!dY2M7-poV`!4LcSP7&yX3ee z)QAYznAhO>xEss$L9>?S3=MO!BJK5wjn`UqF2*Xy=hiPgp?5@R_yqpLLr*ljaT}8y z!}ICZ->Gw8f2Tfud-SwZUs@3#XH4(Vqeowh^t^fN3YN^s+q7T*@n&bGV95&o-o1)j zBBs_eF+M6WA}PsE0KuJsW0@p|uk;ED9T^cjsY+OUYy}T0%}t z!tj{5v7xas;UZIxs`y{X7ka}ixt`&Av@%?YRYH}KN(9b*@prtUH7loHa{Zd>4bE!) zkxIOhsDz_lqT-|^q3#5<6QTGjamb0om7l1^^{bXp-?IN;Wi-YTg<3^_Twg?i4H;_x z(W3ttWuoX!i`ubD2>wpMeX`k1xPD3F@1=A^>Cs~Rp`xaQ!~i7*v*M9RXgoT$C~x7$ zM;{%|UzHu)vtV}mqhovWvNq?<&Qf}Hj_4R47a0@PH$FZ#Ns(ppQa{wM-=^sI97n-N zM;GVKIgmF$+i;)1YI@$Lt$A77^46r~9p0+s%|2N0;qHRv2OiDXnYUqu^6>EVf+c%o zT}3~4N8Y?`d8t|X%l0Yxt9D@k4^OPmpRrddm_8E&$y>3_SIJ+vP=8`y-kjNadyXi< zJ$;qD-5D5i{(|j~*3Ix$c=WRm`YI1k?8#qpMBJvYmp8~1lQOiKmy!Nx>pmpz&%xl- zOnLWc<*dBvN0mpqR1CwICGHGadD#mw@w|muYOXOst&4%Aug_bxFK_j9wG0nVO;d{* z;B0YgJ|&9`IXg8;AgW;c+Pv&7<~=OjDAUwp^D^_NGh{?h`V(vN7i`W?nVmQ1kfA_u zPZjs}!tWfqF_nP{*Et=IXrN%hh56P5B>v3^WDzlrvQFKFWTWlbM%3 z_fhs%MStQWF{b=wbCC#~9a^a0nyTclTVJqaJ}@h2V*WCXU9)cXid#~2{J3tR<6}n0 zOpFlXPMa7L6%~;vZn*Hig?XZIuv$1K&RAG~VtL+zwP>lgA+tNg59GQ%P`{^OeWscd zq3s)=fYgHN)AQzLBefToU`n^3@ce}tk2Ym1`HRyZ9$O`aWn(2UE-E%ADO%~92z?M8 z6Bm&bq3HK!6->vgtG9!KA0FNzf$OZ;COfPDL7Wm``KcLs^VT{m@~m_l+i9F8GA1^{ zu7&gHv618Km3-aeyra__E4E3N9cx_2LnSGB3zy|*rpoCk!2uzGN{4=Z1}V1T&gy@~ z*42HWQ)zz`H`i`BE!M14n?VG zlzx3XIr%6)uI^4AP7&JZh{QMu`Iv;Up3uQzPNCu9tWy-j*-c?J9HDWFQ(T?JKTQie z*743mTi7dc@mj?xOmP_*6X!BA6p$_=CR7OW40&iJ{!u1GBq=UQ6OvrQVndUXTreCL zTQ`@{+GNEgLL0{S@%tjTe7lDOFKoIFW58U|6e3(uTqys-jLn zltB9E(4+v=RjfOy7Y62gcsM<8{t=M#)1xz#j=^!5L2PV9Vn9fU5|h+DUTa8E zdL>6BPB7f`iO_0c5GE;x`<|iNXvNlT2-1@ih8Wv$ju;=IgoMULC5J{uC@x`2*ywPP z#_z!@*uI~|cJ^X*LPjOPqJQ5)#m&2@c2E&28N{d_)MTOg+_Z_I6M|tY_=jm@#sb>m zcD?#cNYX}(1|NzHUtdF3One+nr6e|gV2|PLQGceq-P7Z`r^nZRn>rnT?Qx^YTe$aO z&StP=-qtiJ9i*gqm^~+N@fKBIONnQW@ux@Uvsjp$uHUUlWE`R2>f>qP? zTV|j%#Asf|UVt!v(X70bg?XDk&ex^uQ;t16c0$&Dv}A4m(o|v`r+Z-CCMy9yHe(rJwn-%i$lQgQ}g904P>Y!BB zHx%#{!oRx|{@p_3Aixq?OF)h|LAb<4Kw8AdCAlbJ(fqbKZ*Omn<`t{7&_skq$7`BE z@ifs)o@}^-GHb#tmB8<*b4t>*SY^(V~X%UB==;9WyRqNo$Z?wRn558=u@RbAm{w8UF2$H5 zq!r{HCi!U3`bQaa@)j-6U!790B10<2N88e1U&}6IB7rveAPi9`cLX;y$qAMnPo69h zBTx|*s^y|D1-Qh2%a$!)skEYqF3@>f&8t(*S;79`8I(3Ytg|ECp38sSOT&617t!EQ_<5V=8VVXL5$T7CFb`}HRF>AGL31zP zo0qXAPs)_pnGbW80|87DJgOYh9nVXJK;b9?#_?$V9{7+(kybE$B^p92c}FrI9>xd`Jvur^x~6*F z-n`An(3Z4)%#GTI$JXVi9DJ0s^-<35yo?W@9$m`_;rSg(LudJ`cI55R={L?c_;tc8 z<=Kcy!zTqUWB~!OyuCU3y5rJ#HMBAJ7^ItO#p)Mi!Sj+8^jUlJj?Xf;xbkMF$}Cgt ztq7hi>hImH-v+OjgKroSqx9wVEdwehA}vB>2059^C`-hvY303LQgV2_CMj9NN%qC1 zDE6xt@nA)4LPE*Hkd!yJZbmEpzj!3QWPGrxWpHUym5~TAMuExW!hOd@$7mxsw#dI; zospQ(A%1*Q&gF~Y-sYvD)j2?Es53G?F+3vC7vW${QanP3n#8D)c3vKih*#o|yO+DY zUlkcMcGAWt_-f!BM~p{TRZ8l{*H;^(g_=`?prSEXM-Bf+J4wkSA^Nn5@v%k8{VIHR9zPz`F z%|a37ZIV1PIZm70#LprY447GVHWJmtq5&*3OlnkA7AY$R79Bq}B5{(bv;mWhF&{5r z%)2FH%nOh%b6Uk3XzJw^+A=cI&p7g{8X5zPCEPS-urz~Ct5z7CySq95Sj>3ndFS5-=>|!&#y{!L`+n)*4M)ocr=M@<{V%HDDh;v^z;PRY9q#L zov?lr73UiUnG%s$On~$<>(kdaEIK)Elu^bxA^IAVoaBpjCV1WE17d>Fl*z-bSk^NU zN&*=d6RwT+^+7|1$pMbTacqIydBd~&$gjPavZTaK+wak(%>nEdDH0tq+k5;S%^+T)NVyIY~ z!t2fOD{1{l_Fuey2Qj8`XjiU9l~(^{>rcZK4>4-4&yQTGKXv@$%+{IIvT7OgGuN+X zmY~*`>t``yr7aM1jlujo;V-Yjng6){%h&%(swrD}wfa2;)WXa=He7T4lGgtsfvrTW zznQPu4Oe)j+49Hr@c_EY3aBGxSxoU9Mjmev9%~AB<;gk@1w)|I6vqT}*-Nznng0S#{3lXRcqvEWsSU zk_%&iCvy%}AuKC#eSVfz{k^2t+{*w5oB>wNL;6d~vzq0FF_Fr24(&#f5 zIN+6jRsM7XeI`L0nE$x{((7CHUt0ZFoqw=`XXlFi{>=RUO#PDOmz4SDLnv+j%*Tnq zc?|StX?qvA9j^as@~?Q`YW>paF9EWysQ#3cXqo}{U*B|Vp}&jbKLB$YD`pg-bjPfC zcSV0OyJTFI{NwgZlAkY^U*4iYuK#lRBru{?a z<1gO6+3<>8a{IN-QeQrPmQrPn*sL*Ja{Hyxf63#wl!9Epj#-m0AD=44`a_PFPWNh) z+QoowhXE%l0SASgp z&+$J?$VBiEOYQE!@My7zF0qsmbNhde|4VCM9kJ#4&$lnVG`633pWe&h%sVd zfAP96AHSvj76OWp)`&?4a{s0I-$nJmslG`@asATaS6crj8N&5Tf}bV+Og&4eoBneB z(&)D&`^VH$QA^0wruh}O&uY3}m+&?$LQ>~|-U#))=Jk@&Ynd`rr z{7eFE6z4du|MKy({N?(^e_X#L`Ywq-ir1F>U6TD*G(J#LT~6cvOPYUK_PKeyhU=TR zt>RxzL?QNJk0{#g@ICUupWcXnaBS%w-!gD#vY< z_2coCgujx;R#H1$zcl?=QX3tib>l%x5hB{fV;mOuOOVVF2_m4b9!(9L6^e4-fG!m{~n*7xQM(jZp z-7|0A4%aVdmZ0*7n<0(!|2+ShbRE|(iT;Z6e`!4Suk~+&7uPqNp3y&6(>VX-@NcOW zFLvho{~G?iL|a_Hr1(oOr86+sQP_ZypvWlDV?6%Fg17jG&Bx)Ik^Ib07@qmj@Wy3L zL}DTyhzhSFGqKCLNHW(mtY4SDnk1JU6|+?`b#1K7HH-gScZ@1?-BIb)M=WG_iw}`wHxADte4u%4Z)>40^(I?wy zCCOKQ>LyOaPo%^yjXq1O-$UtYF_zN$f4O{=GKA|}nYF0Or^r7c|4WO%lpO!=4!+Yu zYw`NWD8zgj9`f0zM6+?Imps1G{G*cF4;I>mebh*_Dnvbiit1ORwLi*#2^JZ_(-@Or>!w(Iqk8|M}DQBfum*mkS<2xnd;XVT! zn&%``j#V9ZjuQ^SZXPdvYp0IpD|KAIwD}kHUrVz2UakMKpP&4n$zQ6a91lxewUvwWm%t+4 zZ>q2nXl@89craV0@LB!U6sZ+)TR~02xwWBo`8pd=WoVC@+40?7owb^RI0SR^$Z9J)5D+@l}f)4gP;f##?c#L&l<(9ayj_niZWt^yx+D&QKllTeS1TG2SsVNx}3rSh0AZVRg~`c zaHTQa11>KrmRIc1#&jGE87?P(xGC~u4*2i*{q)mMbo=&gI&?cKYVcI?z3%_#*G_v?b(}Y)ufL`rfBccS{r~&D90I@p{yW_O-j*$0N?~DP z6wPr_|I`N=ZqfY15|B2#w1jT<-8 z#~*(zXqRdDmtXK2-2eNP2!Wq}{+YIK+fGA<455x4I#6)u&eSzHm_mYrDY#Q7K?5Dy zwI~0!?Wi^I&WC@ycH-z15I_N_!)b1AZsg(VMZsOVP;6|hzzySS)v8rOb}&wvM~@vl zCV2PAks|^}d-m)RcxIe2-7H(Sj210gL}_VhG;7u@(awYk6DTPuiAIkeO;J%%6go1L zh7KJ{0|ySIe*OAU&z|`1Td!U;Y}hawGiHpSg%3XXK+sNBRu-{LVA^9E|G%Gvz^}jl z3cPQl0f1jf=O79J&U{yyTdp2ccWYF^E%ju(!J`%jla)RXr^DOf+ z^YFNF<0v5^f!=@reTslgVSEl6G>Cek{~)yArgdv_b#bMpO>O9%ciy2ob?VStb?ef* z@4ib-n>41{wd+vhCQT?LB!uGQ<3+n4e)yrFKh_tlr@sIG`~THCf%PHF+wjnl)D8IT z4pM$y>BB$_;a0!^7Xk!C@rF3DI#OBXGqm4IVL`h3y>mx*!l^d9J< zNB3@m9=Zj0p>CjyuArl?paoy(ixw?fP$Nxa@`BD7GGwrj3CzP&uxC=fK|ty|AHG%JDwzlNy>I#|EhB|}( zxbJRVf}x*$sAjEN^iG2YxQC zv3&0i{XVc?Um6`91ALDc_)eWQn>MdsPdm13rCpE>ySMM4ts6JdwoRL9@9sU6opqRU z4j-XCJ9i;(JFN#yr%jqn{rmJmdm+FeWbmF$|^30|&Vy*gE{T$w6XtVk6qR3NL0R#XFN4c~s7Y(PiO4i4lA9n%Kw1fcB> z&_}^&BRC+Cx_0UeItUOl>8-clA=_rnNz=3`HF#G;KG03!;o&rC(j*~oHf`EOnVFfC zo0}`_Q?@<-H~hZ+_FH;CI$GepPmi7y3*MVCWhzabG=-Kd`hfNUznKR=rX9fhiDSp< zeC~PJ-(S-A1>Y0<0>AzG8~yg%Z^Bk*yZUR`RhKVbqT|^)bZGwpN`b6kUD7k8n~(!c z1Hr(H8}va_TN|oduO8I{F0HMtsZyoas3LG&sZu3+?X}m$QN5Zq)kB#^pp_=z`$ml# zl3lZA4&(w{db_!km%BUUyf?LlE#Tj#t-ya^ zhmL{Z&ehYC+&sO>)x(1vKsUB_c0v}|L8tWV-(TpTxpU_VTZH`#_9s7wFUxfO zKkau8{_-H`)`5NcQe4dYG!eL;F?Aa4*|n37K%O50&wq3GuE6)N1|EO$3-FHPm!DsN z=l>>nUgRO4}s0E$= z=9_N{d0(|^RjO69meA`=0}XIAh1_P{-yAe!4;pZ^wnHHf zehK?2EN{ApbfsqY4&(uw!_5o$hd<&9nc)mNXo3D&HoSv&*(Mn|awJWJjk93E0@|=) zgYZSpojWJ|(*G%b!db*_h7KGgcz+yhukp#_Xnv{=I6p|ccI#< zz;d4b11ax+$F;;epBe9}9^f;VXBznN$DioQW?Af#bbW|4`-(AS_@DU>@bjVQn zbBXY$N6{9&;! z7qx*6*r9!U3PcR56YPKXKkOYH$pd}3!x!}6!`laRAZfq_a==CC15a^wboCJa$vcf2 zfj&HGIAAs&z7WT))~#D7bOOhlId;i#`TxW32gKW>BO)nm=rCfL&$wTLxam&VyNvr^ z;P*03GtWN<-#&-zW|_`sRR>5p57{o{y~O#87rzM^{}_D!@KFI>yYUqrK6Zw7?#rQ_ z2aeL-tW%VAESHX+zDy_1U87Uyui<=!vX7smnbT%c|K9KsIZn{E3o(y2flXc?z8c4H zs=+6C9rB;`fJy_e!{4tD`d~dEY(eM&N5}y7C%hobTLPCHcWe(Eko|xF$d(Y`-vKnj zc=v>U@bqaV4mUFzU|AsPfN25p0Q6w*=qzFtjbL}QLpvOo;Mg+9n>miH>V!v+9{oq_ zgg^fHgC@hK8G@ME#N@FQJ1UkwLfoAF`6HQ!faezi_pGZK_iXR7&j0!OFG8L(zJG?z z_bX`q7vP)e;AiAN`|&w_|KursmsdbXPoAe;`wr95Qy1xY?sYnR>M9*LdXYXpc9HfT z&ZS)+pQb%o=WyiGp3F0}DGT`C2C;~@(U(m#Tk4Kj)ELAfId;iw54(5o7O`ty+u}8?|HR)8#AF7r zE<>E0;hi>b9{jQcv=jJe8;#{Yud)673uFLn_Md)w4t)OtI(RN{{Ty__IA=O|j&#O- zLE&T4fByt{KS$el9Ry!rrSsQs(}@f4`A%M;O?!^h@^uGk`P#j-aq9uvwmXM*0q0qu zhs>O_wExg?+I#RQeYAEn4TJCbUcde{1hGSJ;Gi+bXjl&*hRb@N<9uujs5HPf!E3M& z*+*nspfU8dql3MW0iM7e+X6nY1KL0ius_%(s53dj_xJW|E&1Od1DNMMS~5MfGSUF! zo9Vy_wgA(CIB;zT+4L^^stp>F3+zRXO^!!gn%5)Nu3bw908d^MWu3tK^FQTx^Q)U8 zh8vAoR|4X*6DLfhoUBX{qkGD0Ziss`?pg2u@Z<;J|3^U+Y`3utcn-e*2{>omGrvDW zxx&Xk&}U!VqO}`#P|nG-bmj9qbm7xGbo!HX&+h`S><`qgQ%A&xSnjJn zff@^}0^Pv2z`M}X%^){ef4DlkkSFlt4ZYnOcx?y#ckUD@{5@~1QF<}%4Trl=OJNf* z{=FazgdBkVpvnQJ1@&M$aCCL2=FkZZ8#jT!sG&B9H%23N#%mP3uC!P02c>q`0g z`Ty-Yf%SPpTpUHgr)8ZV6Z1ZOyni3;?+@uAY;pF@S!O-M@qIxd=-{cK1I91&IpdyX zz>nbnXOIbcl=&Wff9UWDTC-srUAX!=ox5_AE?mDuCog_UoA;ie6&v=`x~(76?vGE= z{;bn;NVSO%%2KOI;^`*fg&ff&S z7{}}1Vq36gO=0_0Hpl>TIlytlM&L=N7eNE;4H`jA*-%kzC`!n3p@qi7lQxu zALa|(|M(1c`y;)?Iq>}ivf$Y>`0tPfpM80o9(7{1RoK`~>{|IbHn>`!#NVBYc6|-+W6q@7$*^ZhZs4;3nl>`HC)n zdW)`nahG=NJ%o6~U>XcP(5Gh)#Q&R9L-4gK16U6*zpFBUX~4?h7qG3^05s49K7pN` zv!fJ^c0oJ;q*(hY!BR^+V7B`2YJttb05JzJH`2fcM8w zo1(rM*BX_p=nd5(jd?) z+bUj=-x|n(x8V!045(F0#spXosJ4Kh0j2{SZ@=>ne1|4vgEa-VAzgqQmH}>{gAP~= zV4d9(y1=J(8=Tt+TR_zXUa%8bCoumDpMd3ncPrS0IKwV8^FQE4RpY`cNh3) zo#5aCo#5a^4Pb}Xhdl6w-+@n837x?E6?mVDy4QgBF#Y}S_%!yv`S-`)|De#&P#S@C zc5T8Kij0a8_TJi$R#IVsUhw|CJ9nu7I_e4J`ThIf0{7U11KTezPcQU4(*fIfUwn0k zZhn1_<}F+f8}4H|e(ow|owz_*(C3@>odWK2Vefwm8GnOvf%j{le+?dg09k*FR;}Mc zQST>^e}^C(h{bipz5uMtar{@T1-9=Pr z-1`7WOb1@zc~2a|FEE@vSPuxFz~CD|7PvwtI7250+`D^I3)qs*9^T-2rUlRj&JM5* zn%db*odB886*0~@=w9B#zwd;P>wvpV2l@iY{Q|ms_W^y6v9TTS?RVha+jr?}$m@Bq&(>|;P1*3_ z4`iRgkxQ#L@1xy^&OjF2fK7+}eqVk~Ujgr5Le^(2UQWIH4S?O%8GA#z(tzH5XdsTE zugff1o*J0Pi*6Hh4{dW4{9LZQ7Avd+cZG)`Qw&eaHv*%>Q1k+CUFT z|3LVLEgAm?TJYlfK9B=myWi56 zx9-yTNzR@r zA0v;LXiAPxptw=*qufx~fjy}i)&-h^pEQ6a(?H#N^@T1FG{CW;B7Wi9$mg{r_6u1L zG>0AO!9Kmv|82;(Z3pN9e`@ULN)4Ss6M8I#`>J@a;>?*d#ePQKJI(vg zc(3b!m7g#UaccIVcpq0}WDIQqt?fXp@-p^z-TV3u=-?Jzy?hnA;B)#0_xFKwrU8}# z4}o{4fnz65;W$Id6H{m#_*iZa^L^#%;V`xn5D2m7a zzIeo?$3tF5jSQoakPr5d-;6`vJNT}k0qGM6d!PpFfg&`(a={ip8T$k8Hqr>2zzzD^ z4f3D)-nVUgfq&aJ0aUZO3)N@>o$cg7?*5&rTVL#5>pOq~LC0(-F#cH%aEyp)z=iz+ zVGsBSdw~5!wgY6G$dg*I3;^C+2s_bT+_R2o?ughCY=Zg?8cCgC*nc(;{@H4SpTMyr z-jn=SVn?gitfj%wH!*-|uipJ=)k?^2#3gQH?e!A&HC@6w{HIs0(Ko>L%`d*B+;h2f z{pxkt0pAF|zYMxKmwOTGTc1X~f{c;t+ZX;~O0lg>i-f-!YT` zoHPCt5SQljj46|$zed7$i6(FC>EQhtHt_2jg9ca^G=#6uy1q_b85=O_0>lR@VXs&t z$XvD?Iflq_0VmjkjDKImYZ(82?E}bltd3gDTuYkXp;XJ!Q_#U%E!@btE%uG|#op5X zgD5a47_u97BJ2W>maPT&N1(#)mj&AoT*<05V1Z`~&y$aD%VtO3knbr6KeZ z`w1;!bMRhP)(NVg!0QS8yaexq|Fibt6ZrDI!F$8N`y;VlHEdWY9o&mO)bKxYPoJVM zv99|CV$^3(ou%_F)3l~12PgpmACQc%Mj&32P%v(Ymc4pC9#ON2T z+=lxPX~VXIBEJ9m%{%bdj!?&rov0IRsGgAdy`b-VhjgbNu=n_y_56_j1Az1Q1m81F z#)OR&x<2mxXuz9LVZYEQio+g6Uc+w=JI)RVui>*j!27lu zBL4O^@XKq3>=(QNzJCq4w?bT)*N$zmM}YkX-Vf{u8N%zl0{@@^KmP!7oV|wZ4%{S% zt)GyiZVNRTJeumb`%w)Wd#YpaO3i)!sZ-DX)T`e>>Il8i(yyJM0qG;kbwiE~$apcw z3nc!fjVS#A_6_VIdpJ(O_;2Crg*Y6MGjj7A&NzmoCz&W5?*!@#8qKb`4#_xIdbmO~;QOr|XDO zeFoZKS+HmC0m{reLQ%2Fv6+a%W$sd1zIq28ICO$8BNlM{^jX0ho#D&z z9y{JI+@(_|!T)`Fbcg)!1>Wy3bbTafk?p)l*n3gHe@r;jKqTaT1o)nD9)ooW$@gP$ zP68~L9<+$3iMfELo58PQTiOo%(+u`p(`L{Iz^?|jKF0`o4CXCqz~8are%oXPoK8} zvVSdY-*cEworRpZ_9=Di-b<{lvCq~Cv9)0AmkGgsuAcCD`@!~Oe{blZf!I?x1af=? z_&!|l{b<;CtoK>=GtOD=GruP%#M8LM1cCFhiDSe%74JnH6&Xb%hYceK_T>>@V;bPS zo3@|<8`$9Z8+g z3h}A;Ap=h$=>C;h=Q)IU|6Z{Nlj(qM zfSjx>+KP3*J-c?%aqQ>41X*wba$&=UO|){=I(k2T94%S3ofdq!iDoTWP195HY{vTC zbmZ7Mx^n$<8a#A_@XI>3ZAYE_J5U$+PQ1^)2W%$R{T#nz-(LFnZ0EBcj{?6l-lK)S zPXx~KW_y}6E}5oI7*8`nyQwKNY2o~Nw0J=}%}tp>v#}p{jQ^$k zscH7Nf(Du%c|f*@?~9{(=3U5xThwCL4RZYOFxe%fQiD!?sFs5V)dU?hbn_wa0PJ4{ zoC9F@__Rj+3UYvX-_?ub$EG!8wgcp0@DmL_0q;F!{M&<`Sw1jr*xEZnCty!9<}(oM zV7xD#_nz^y3B2#DEW2nMy}ntQSu}Wf1kKPbrL-mMDRt3WN}QNRX^Yp>&izNk9-ax4 zriyh{-e1eO4+JkU{#oa~l z?EPk0AnZcO0*=4dgS@Xw$NnAL;`CO~79skkbPHOamP{k-Y)`wnsn%jDH-> zaNX<(=m2`5S=L=@e&9CQ@BWM&SLTp?@&alUGKA{5`ckdtSOWwdcytJ+pq{;@zW}|! z>&YA|z|Smx z_0?CU+JvJMwUGUTVEYe7ylJR-CTH~uJm0i+GxqKuq+{7fMEsX+!R1Roq|Mm#mG$u< zu~xZz*KX_sT0#pJE~fC9M4AaZZ_dKiGFD>{}q|wec;=0FdZ~I3>v`E zoMi#%pqbDM-%zuIuo3orL5{0WP>adSNYf{R>Up<^{|KIS@gk3oLC_0*C;qsT- zL;o4^zClBzobB1GFTEc#3eQ~3#Irct1W#?-vPC?*b71d2+6&&_ws|Y)V+E~VwVKwi z+dzzee%`PDpy8A}C6y-6T0~P}??sQ9MROtlx9>ZQy?a-vCww|@4^L``^|L_ih3X1> zkN0pgzS&-zJZ>!MW~I=Qg$rm6?AR^9C)3-G&0A<_wOJy+tsBl*E^v0r(FY=L{*9OirAJPT*o1I<|u7_M0+*n%E}ZpZ>1 z9J)jHd%q;d4d=*V#u~C2nn3maI#KNwu2c^(1ef-mC;+xm$IiiGZIR^x+k#>p8F6E0 z!{G$n3wwb5LucS0_5jN=;UhR<52}L`HEZD{)|S~vh=iS-nUyJ?RV``@esb$BbU(*e zLg9<|K>TzPO`bFn_}@b++r%{R1DQ@g+TDoc*_HLY|`3skbeN`>7-qjv93fuZ@o6S$1D{!?8&jPMo zvXnl;I>$#JE~8aAuZR7z8GZ0`V~p>09|7mU^Cr;2rnPHm{i=_!7QGsH=Q3+ib{%K~ z`AEx{pC$$sr|A@7@m2JFE5c89+O-!t#42kwPVVETZLK)wyj1@;*Z!A95z z-*Mwba-6e~nng~ghJk&lwzD_Ybp%e^bfgYldqN&`74c?a7kIEvU>acikk=3lu|lB( zcr6(*0^q(m;*u>u4{TRDKu$ErGcFq2X0!o3R1*Ks*>za>+5`Lahwkr9i(o&^gUsb; z@ODF=?%lN$G_al403Y+_rqcX*Y4j0nL#Bguh!-th_yPO{_+{}EX>{^TiW@hVhJ}xz zNi!GH#_b0v2XVl5@SFJgnwF5EtoJ95O&0vT7VRuvumJLU0j*}4g1rxn`*k0!!~y&Q z*Q-Dee7z3%UWf90y&kl%X2o*i^~gooQ#*6&6zow*gsg)e8$OakM??bep@?N5b_AU= z1ipk5_@DRbh@&NFz#DtH4SO`?IxO2%Oal&(pEgtncK_?}2RRnZF(41@18D=huQh!C z){xis>rPU$9N?YtZ@{@-)_ve#r31DF39RzJ*N#+Ts00_PF=*ZA;#* z@Z2}*jQNnk!?E7j1J5%?z~_hj{b)I@S+#;TfX`L~=G!2L*8=9e z4ww%7^Rq4UQs>eCWA8n{v#hec?{ChG&e-X_CM1D`BqR_>?>!`tLJ|^s@4a^m2!a#~ zA_5{JSWsu|y<#t8ucKH&5$p=;%vta6zwhS`5phP(IP?0Qcet+2exCa&N$&sZYwfjG zEMMVb4kcy%!G4L27(dtg51C|x!GFb?O?Evw`MC?0xbu~&sY}P_5#I~n%eQQHvil?Y)rNgliGOTF?@;o8kQu9hIhghjc2grh$ zULN+c{~Zl@exZvG=o+>|Oq~ACBqu9|jU4*}{NMZfJF6N!!G^;lnc4X^ogN40oPD;l zr?14O+PrC_UC6yxt?x>(-gptd+{R0|c7d}I=FFZ$-PH`M9Xi&=PF=`8$x15l)h8{m z3oqGW*WYj(wOEPh{qB|o&y^DATSINjhV#!ues2O>VZGj6yMXh%js8TJ+L2S>n0ZsvLfg#cjR14EFe}qW2wa?rQ3p)>n%Jk#j+~LSaNnT zHQ~Ma+lDyZ7RzT7iOI*Ke|o8ACm;*N*E-iFT`N5+8jye35zL#k;4Dd_Cggy-a<(fW zApgOidW6nb2>*Aj^PQ}Ecy|V0=>W+D*#)7{f#ihj#E{#;p7(aT?LBM)=;8MF98CoC zUSBta-uSwOU;V6gz3>(bpS8|{t0!2?#9V7ij5(wiy)yE8TXsPawrCbP1#(K*iTa&Y zTPVzB^GQEM!*5<3iNA@sVJ-LJ=zq7ox!?L%_jhsi4Dg?eTwXMP0djq_tLwjF+vQHy zUjUCP9=HPeubjg=;)2V0yqub#g5G^?BsDn0#?G`p{f1dt?W zp`o$Z0X@MtiI_t&=Xw%TRL7xO9%{Kn2hf05yXVE?91S1`TDR|L4evjv1bbRZo74Ri|7fNaCy+umnE1A*nq2Htn`9^`@O z;CYMOaHmBqxY$Al&#>0%eXMC@oCQJSDS5?~S6oUBLazJWJ*?3M-0QB+W|aTn(X;4c z0Q&Igf0sS@l*_SH5_8GUD+2rZ^kE=&M1AKbWb|d1UTWL1sn;U|)~q_$7A;ytUD6`z ztQNB`wq<86wcdTok^3{PddLJz&n9j=coI3^wbc6DNPIuX;ol3sD#FiKY<33gOuk2Q zU<~@EcM-iJihEOc6+-UiL_4_w=l7a-uv42-v(Yh(JbONJeuNF5IL$`STwn<~`Ib~Q z!LkQUBCfp529F(J1IG@sp~MHOM-Q-?=_{>d=tP@5Zyv9Wqb|70;m^!tVmI_0QVf@s zKnx-QdC)6~+AZ{gtKUK=#F8(H#x_)pC5ZS?6JoWSWaknOh?Lw!F2!SKDW@m@Uc9KB-Qe09&fv7M zLSjGa%W>Rs$AkX~c5=gJc1rX1)}UQyYtgx<^{uWUpH^6kgzZ_+}m7>O-H9l+QT!>Qo_KjO`**-6dJv{Zc1 zWNfMgEMOSqao?xXITe5zLMsKX&X(35NF+~f4zd`rzKu#jt>vf#Vkga4rc zFmrhOxWnhZUr>j?Zv%p}(*sWa3-9*>xO=-t1IPsF26RcV=-?J&2{&RZUiY#^Y<+~> z(+=x0eyO!DsldXMhB6SFbRsb)i=j2&*ykbcSPM>-Bcc)(Rhxm^@d!5UZ=D=gs z+~=jp_-**pn`DC_1I}A_zFi3JXP>#0GaoCR>|c(3FdzLqbNVc>E4IPI##+sgah6?J zX}JaEHf6?QyJ*wpR*TGzNALH>x+Y~152Y(y? z@BH)D*=p?WC0y58=Edxa4b7Xkz~&(Xvao}PjF?~*{YRn~i?Pu-8#wnY+r0G(S392w z-zUiK!q=)MpI=OlM>&4=g=#>YJqFt73XlEfH@~spQiJ)26Hl>|n>4r6TDP~x!4cF| z^tATGx!Z(MixWreE-}`+r_nPm8+({|SuVDJVs4Jb#3Sd3n}$Xrvm>af4y9%$h+1xR z_yA~4_{YP)S^RwE|1ZNjO2l5eQPpfV~{=eu({FR(r zWFdci!8+arc9H>iKnKzR;Og{&(*d4LaQqJ~NC$+-?sNPv+g}U(Z$E;+XrK;%Veg(x z4u}Rs3(x>dzN7OQ{)CNi<|2Mz< z7M(qUeBV$@PRVq!(uMQqIo-eUq6;1V8<7L&u3BYhkz1KFXSU6nJ(Dv_b8X7hX*PY@ zG|nxQ+CccfxO^b;v;-Y9(iWY*!cIS9sq3whgm0CCY)|5MQBFTQjh-s-yL9f{}WCI|EA<(!M{l-@Q0pTham^rx3Z2AdnW^+9gp_|cnfpqCkE)EzC3U=AUi>{;OPd>ca*L8oJFp`(;^pdvFPg2*aGy< zBWJC=lIqT?kjM4^z4yr%E>EPsEt%-EMGNNJ!ufNF?_cO-zhXS{_t#NxcsBO>^l9{Y zfCeT_o^0dCPb9`N)XJ%Qs~$*vy^vfMIj-R&CvX<)LaVH-vhKvC;_*RJu&pz=m#Xb> z_`_?u9upgbJ@4_p@c-R$$JvRefPb?V){xkB(~wAO77}iaT7rFODEc?v)o(PVCZkEq z=GbMdmMw_WP|pYcO|3D>qN^~(oo&C#z@3qpfy*u6XigmbapGO0Cf+hHe1+ec7 zrd?P*Eoc}1k`a2JhyDA=1U(il)RzI!)2+w_R(*L8Bp*Te2YiLPJwOMt5yEc3R^0WX zMUPp4P3zU3sTN)9X#M{lb-T6bV)a|gg`Q`SH(z=tecABMFCp$C+wWpxFXz#3Lw?>F zXPjvZun%=kX%e<}5izOC{)4QddWfZ@)1$4p+Qy8ZX6rBB;_BtQVms@6bsRcWG2de3 zZW{cgyl+ozt6uO`6MQRSuce&(38$WBr^x4S7i7)Jk)77OrJX`9rUCC$-IiiF;l%27 zuA_B(&iA!zLoHNWYt^AWxtk8;af#LPz81XJnz(l~_Q&7>sudn;N%(xlWo1^39on0` zLt&p1%M%?S3vvsJkqrTQKqjQ47gF%Ab~btsxhn-by-O z-K23N`tGzs1|(49hwTgxslS@e*+=73%jOgI>dkQ6@#Nf3X@KqD${Mu~vSytl!M_Fm zU;{g~abs)LqN%lN-_C-N`<>|96B14x4>YFw*v`n2?$A>zvRmgSYO5>B{fxHpqer?k zETe}H=e0~?6IE{Y!49pX1M<$Qu4b_KnJq*Qv&)x_5G3u8Q6}Q#N?BR%?IE1 zCiw5O4tMSaLu4@+hYEN313VZ1cj20o0gfg_1D?I;XaI~uz`oNRV6WxqVXvbF(S+lD z;qI1?w{~F-eeixqCyrM9*QFEQwy3FRb1p5_`Gfu$^=kN_{=a*u(^QRQU;g$I_~CT$ zRoq`a9WEyKEB;?kJXZ0ZGx7O!MpgEo&Ma%Cr)R_agRG#W5_>s^yzvm5F?)f{ox8x= zapp=r_L{-B?a|5N`99#1m6B#z@RVY~s;~5U-{JrJ-`k0&HL_D$l7nv_Y|Y7uorW$D z|DV>li8X?r8YAnQwQfy*rmg9WziPB}PDix@i|5gE>73=Z0lK|>8@&au+GQ7@%cS2_ zGnzrnro4)HBCDdh7CN9-w>&@x$b>?CC(%GY`XN{Lf#j8Zed()YVn#mx#7UBh%ent= zIs7}`>FIz@cY`OkfM`H5p*k86O=vkk0UB_0g6x+(kPYat56}RQgSA8pVC-l@yX*zG z2XGeljs|24c(hRGH{vr!O*;YJh5egOK6Am`xy1CA z;qQUJ`l%B0mCrBxZ^`LPY~g~1tOYi6)-0Qb{g;CtEU%)sZ$V#bTyt#zvG^rtkoy@h z*n*JB>Ypk)2n`N$H6DGrrXo$4Z0KPCE+!KiEn5fe!x;oRg1;AqLdkPHou0 z$&wa)UxzmIZt4_d-N@M|_UumWSh~yaUb2zg;FY^<+m5SQ*U&FumtDSNm#sQ?t&1%V z=5No1Z~N77Hmtwa0BB%v+#zYykNG-hCE+-#&}E{{xG?_XCSzMc?y*MICG1`=NEacR%mjZ!!02ePpq$ zE_Z$4*#Y(RfhQ9@{DrrR8;dp^{`}m)<0CWxJ)j%9PF;@eLe32vK-hP8_+2z4QB*oUz0f!TSprEwpLVr`veqJ_Xow zeaib|E5Rq3eQX%M`08~Rxbt}}nl`2PS|fLcB8=Q)K611adn+|5$vuuIMs?DOC)MHq zo8SDGtGhm_L1R0$RaQ*`%LH0pWA7lZ4qih7}0@;LFd9oFITS}iw?EZJ){|_wa9^w9>#j$#Ue~E+-3|Z*W8(2y15_fWM;whrMSDcszfE z|AVk2bge7;zgKc5aybn5F)K@bB{#S1Od-9*>CpGl&ZxR${K`}k8LDMD<|7PI+yWjrKPQzDh zi417nwjF1*I$9=lwVXWU=50G|%Vprd4eU8*c*Qk0*>yME2fZ${@gqmMJdosm?cm|8 zq4=pov4@7bds0QvIVk`{aVST)zx3oNDPR#W3~4)~wp>3{TW6+S}|GO(a`Ip+|l-|ky$W5-Xi z3)XL-r&^drgoRlbY`}QxD>AX0mGhVUPX>Sag2MlV0RD`naQ2^KzYhPF`19m|Lh&CP z!uO|weWTMFxc8{HXPb7|_SgrZ03C4t zt)#3UdZ4$93&{T$|0kE%!uQBpun$A-$3O6)TfLA0q5;W)?#Ge?P8I}cfya*j?}G*c zav3KlLqJ25qRv?E>ZjeiZ$Iqi zGJFiqZA&X@H>AZD){y&k} zk818hiQh$akF~ZT9r62+2Mroo6Lf&iXh%dR+AwM)W~{!(R$ud~-Sp6YyZebx?cS$8 zwfnT5{Mhb$;voA0yXUdJoM9hB?0+P2%53l*=CB_$e3T6uHrfV~D;U749WoqwFx>hN z8sc&!(h>d84YF;@po3CmK`wD_*@2nJ|18P>egiG|9&EV#_F5!($3X*eU@qQwGC#J&Vtu;-avG4wEuT6_{%TO0UO1^l>1jbmSX>#kpJ7Lr`n7yupWDQ z4K;ZyRxEe9pGAunTRwJ?@XyZc!?~DrE3Fu0(`L>k?sq178oxW7o{IQn^8FS6%O_`A zfuAK^AYU+++?x9E34igwcAdXzMeIhgs(5_$HsIf|Ik^CA!e-Ec@K4ODv_-3~w}l(; zunjl;#cq1^BfI7CkL~s+KCwHW)cV-&77aXk&~Cctbz;9dFFJ_WR36yl3yv7$*5DDN zZ3uc{FtjmvxM*P{GC{gwh$j#DOl8er{9EY+&T$o#c>JHI*fIQ1%p(lmm(3^r9tW@Y zWN8=gJ2~L+uWt(+O#_}B@Oa<11<(Wccru`l4!~IQ!07<=fYS@`dVLzu>yrEOMTCFX znJbUNKjjDZzwjS|yvxD<%OszvTFJH4eqFr&d}@A#{}yt8nvb%97|=T604wnWPj@mv z_!pOQ-ZiI)b8%_hr(rf@);ya!ZJIkX8%h0)WI!VM2g!Wde>#hs4E8?$t%wWA@AGBA zA2@s6A(V4A*etTM+lO_shRrL51A27mU9|hhqPTouAOZR(xFF6nwkO8s>B?CNrupSLa7X+4X z1IP}L90A{woTCHnk_m$( z3x%f@?Q$jYS6ZdJz1v0klK|k_Fzb=bl`U zJ@`FcAnctk@Z^Ae!5-KGTA~AI8?tvtCuqfTy(@GPCK_d7woUs6=;UK@Zduw>zUckbiTE%?*aeF*`b-XeZxf`$_f>8zt<=K?C5Ss7-CyyrtF1H!;xG~gEYLYQcP zJ(NAnZ-H_`m7^WdpRhwYvRBT z|Mb2#b>TK-JH27=ea5bO=rz`Rb}cmUM|6SkzZKj6mWSS^hsiL`0ZyWCP?odt1`h{+ za2NL88qZlpY9Gf)7Dx_A9(a$3Knt=Hr4vf1i;g9SrrMBfWWQ)2e&__S^KAT{_wTm^ zuuc#i!27-|aJHbM0Z%6M3ebS)MY6!R2_5b~kOT4!eVgE*(+RQ2fJp2{VXxI0tUJT& zVFA9^9t!qhtnQ00viNlIzh?uw`W9lZ!vBtYA8;bz9r%AZ{IC4D&KnNI4_>@zp{+*G zU$Wss$NxL8xZJj0>iK~V|CQ%B8BjnhSMjopoZi$$Wjb4F!JvPu76}7{Qsfd^u&jD+f)1Pk}L0Vb&aEj z4Y#Zu*?#DKczf8GiQqk+dc{dLeC&803xBRlANae|4dWdx)DSPorRFw{-cs_Ta`HX< zKYsXRC;JuW=?N|g4}1g-hz$i zl{~Ae8RX)Fwa}3IYKMcN=IZo<-+lW}_P_i;_129=Hz+>r@P`J3|M9;+f%tzDYtVu- zmmQ+5MNov32eSX0V+ZIwUSejsop~;OXK#4SuD$(9yZV9W!2ead_K|nMf3Mw$&wu;V z`)&SN=eyWOHFHTy%IIl;zbBp^27im+M?eQ7$4zi_Fml{P&aJVa1y3G;Jv1Pl(2xA4 z?50%J27!MTG30D~frL?0ts7YP5Z(_SutbNw@E08fXyAeUjt1lt__{zbLO)I@nvfi* zFAI+NhevdR?11{RK=z>U7aeqg*S!^x1=t5&?!q5AeWS&Le_|>j8N4&ShIqP335!1kkWC-}F7R)l{-M!BuoaED!c<5Tnv{Il&s2VCe&K7myLu#EV{fm-ZvRf$fa`jCb~5A^7*UgfTPWe^37R0_Q}ByLM>6$pW7SJUQU& ze@_m0KB2DZx$hrH9ypu8*9HELOsMZ8>Tx7KqTat?)dOE#!MGpIP;b8^Tq#pnat22{ww(}|1X9*ZuMA@ z{ul56?l^M4Cxdlk@_mh(TeF}Z)-f`b$HKpXH7Aew`{RF4-9>-SlRiN2u&3?1+n%xO z?q)swqFw*^U+l&w-?dx*{DEC|!=qMPQ|o#FWKtWZ_>OG3AtU7bVe^5jhqq*auonJ2 z9y_V-y6k{z;=>ua1@4ScGVuu6PpTEjDe7Yh2_(Ku+XLa8W=9$j(zdv8-w!@sLu^j}CEp!O7Hi2a%KQg8dgA9^r6Stw%1tv(9+S_EQar zWP@+}IsAWjJbJzA;HfF}by zn_!#`fL{9at8%qdvBavwBd}$W0lD}}Ir5h#EC8Fm7DMhwHed1s2Q39%os6vZWWh)H z1pD15W;y}^?;{TD{-~Pmosj&rC8j$J{D&XG%Kk(?l(+PF?!vIaV+>vO2pC!96n%q%D zfDXdhdoA7U@jp5s8QxPZlgc7 z4S)@p4)2taM^)@U85)ppc*OUY?RO$_zL9kb$7Ynw%1F27_>m`5BX9~!btIbYH)7me zyYj}T?V4Mkw;OI}PQcwS+8w)JwA<+cf9oSJ+67y8na+DIq)su5xMmf8zw&(If5mcy ztrznX9ViwgzK8#j|Jr5qDL1IP5c$llh*2c*JF8cacqorNSst}N3DeKQ|KDfbz+d@( zhdp>CfrlPzPXKG#gYn3I$%r~R;P~Fd+~p1U9^Wo-wBhUuUk)6@CO{^{@V!U!2A+=~ zIUpI(_1*&(zibOVDyUyd&oy^uo%mbtiduX8r9JlO3-s;&!kb&IK8>S@f$OZS&d2x0 zt{*dMq^ko_9nB7O|J9uT){LLct9 zmyV+LQnR(h|C#8{KIl&M)0h1(+VJuJFZlnr#CA_O=_GpGp*N^o?~HzE+`3gA{!O6` z;Xh;cne>r-)ULkaA^OPOYddz`V%v7ooAion$opQ+`PI>!Eg9!zzs}Iheitt*rYrmh zEBAxV)f|`KB&i+ z&H{9eS{GUNR zb0)Rz=>D?W5%$8K5AD@=zdxt?wwrHpHlSu4Ma9HgHM#wnGp5^l#CtE@bcwS86bHC` z+oi+;kpY|wS_2If@&3{9+6a6l`O{O#{b;65I&!jITkc&*2y>OXxcRE8|CRkG`(HYs zKL1Pq|Ney2;PnRd-#v-^4`<%7+Z(lRUB~~*|2D)9oX?q)t(Whh)?+)r$3}8eoc&+I zc{I);k091FWx{yQ4Nu}+7yc$bihR^c;_;#0^Unr)!4!BbB??P{b{Cmq9Coq__+@Np(+B|N?!d;c=}tjG@7MjU7> zabe{Ht)j`vT-E^LeqsQJB9CQNX%MkgSz)T?Ub5b*3@ z<9go>M~A5fw5Wh{aOi2(@+t45T2HU;YXG)@^1J8*@_VZL&~?>;sTQ=TPZ{w{&dw39 zZq>G(HKc|q1;4K?a-a+LOfs@jb;9|ad5K$m0r4Mdc%XsqEa5NzPrkqSzn9y&=Fi}MbdKNFYGz19N_=n z{RY@W&+V}f4}ShV{M8d=6nIN-YL<2)vReIMPG8JfP-?-qY}!bFpPl3bsR!76iHik_ zE=Gg>P<*V($lLLgr;-1i?Pjpgo;lMxVmE2lYL`wSt`0yoAO++Zbq+9|oNzb%|5K6e z%KiE=0M&k+cxrPyrCEDx*rt;;=@{zxUp;tQG;QpB$}(s!Gb@u`Z0O`LuTM*J@X5=| zbFu!pvu4omm7fJps^KfajuW;O=z)IJDton`wN57VgDzALE?chtCD_3|D0og0#e zP+vfu8EX$MhNH(+|5rerq|RI?EyceEXJId#glPi!NXC2m-ID>5`%X3lbb)*BXyHh# z(2p0^(E&6e{{J5S!v4qbcQkO&$$}pIeBqyb&Nj{{b51ot1CnV4rB(LF`<}MXzxw)n z`0I)0(T&F*R?qdQZn0KYR%WxNPvflL63zi=#@|lY3&zC)l@BI9JQaIiF~h0oifQ=K<7(Cih_fOJ44c7V=*tIwnALE^A8lpD~TR>=V2fBYYq&vgQ4e;Tx<{y)eX zfPXXaKMkFrK1@xTlLv$!bq=H%=YN{FqAzEg)~=6h8o46Pq*M<;oh8>9t{h}o0rrXN zcvZ*e)%aF9d7#I_+|~M0$E0%~It!@yzWV<(Yl+_pZR)&uG&N{#+O?(sZ?wa|P&J{P zmB?7V)ADwIXc@clwHysdcgvRZYp+u(0S0MXE4*8yx&gj{~g;er^n+~^Z_|x;z8?>4XPcI-#;6V+^&&nS z8z2pPU$b^S{JXgRFY5EFGhxyPn!Bzzk?>btr~LmvoNy}jf9U+C?K%I;d7jYDt`D1L za;VN%^VyS;O)=0=C;E1(FO%kTXa==rQ!Sh~hZ#+=(7b%z9O6>>u5L^C`scnR7qoK8 zU+ElRdbW4&PyIhSN6_y9xvzR-%@5Yx&kn@0H4{etBNa!V6&n=)`!rBLHtc91P($k5 z0e+51cA$KN^i@|_Y5;$oXOkSr=I?!y-mAy@r(V&L+d3zs^VmA;T3Ol8rqNebH6f}6 zx{hA+mtzO0CQP;AiU*dLmD)t?E%lCFxY#=*tiF?DMvrp&z0e>q0z2jVR0A3Z{;CU- z{V)4Kb9zra@nrfgpG^LrGak)2+t-4#e4P7gL4BBVgrcKXob_`vym_oy9$K2?Egxh) zXHk|xry1CMn#Y`&n(Ayg`Mqi2>!11d&VA>(YvPF%2fXEmtLOe`}$uvO9r@Ik69l62f+VwdK4fF!CkzdU1uIN z$MeVjT}Ka3^=4B4?3%m;9=X z@XF~rIRIYbV;_I%0ojGJ3FBBjef*&Xy+`!n$pg`dCrf;JqFp*&`0Kogmk;o4f%>?| z@SS?@d_(s1mD`a2=rzvgiw8slgYbF&-oKajeq)xvK+L3_!JC>ia0$KO~s* z8{jD%#nDGFJhl^_Jy6xYsftmhC4QfF73&58!{aPta2|fJ{*A zE+K%wPXjJS0RDaqz{B3t0kQ|3tPjZj`q*~^Z~wV_56?5sxr{yqh3?#nbewt?48qU- zNB>rC*o+@Q9DLv);z2z*GnZ`>cs^(LOy)o^cgE!ece+@R;=%F*tEsWnjPoVgmcGZ>g%rled_%XMhsfL-gQ>EQ)rmi_aC369r|6fADUxl=nT5%gr9g4 zy=P87i9Te^4deIH`DD!m7xqaBw&tAGE9p+j9CKlvofptJMNUFCQ`7T(tE2AvyFe*pRH>J8AI)e#>d z2wIT+=AI+x+oDI>Vw1FP<;{F(1m9~mteXJ@??*>PS|)tn4S69wqgZx#bcp(u%l{Yt ziUG6^3UU1bJ2TfS`ilE4^?~;+^&$C!p8qf0mDg82Kmxn)?{Po)yVxK8IXKG?P)w*7 zbR+vfu_DogiwP<=q<9ectG+Of<>JB6KzAN@clayb^L^PL6}XaIY<{MZ_|$RqKe(Bw|^UO*X%FN z{Aqzr(Ht8?bD8T;eUH9_Jr3O> zneU$)74E*TC*7|cfcQQ-u+q=Dlsa|cuk&gw^82dw`KkZ5-Tg2+V4RDwmJ%aLPNnxj zX10q9&Y3-n9sz5p4<#my9FQ-t0lgr*Pd31E@Lxl}IGr0`PT!bG#N?YIW81cF1Nv+J$3XhTAqR#Iv5CZfRhzt?o>U`;4|9F_ z8-c&(cF1;j{vtm^y#XZKg}1|8yRHXtS3iHv_GsLwF=x=JFTmf^tcULKdR~WHggQ;gmN4WEasfR`U{xvL_S~}a$x<1=ehai z^T`XZko<=R6jPKQIG^)_@+Wk5S2h2dsjVD97Ce=wdy4;{+Azrh)d*H%Z)g_9pqd)T z`=f@BurVV?(KD7_bo3^iIc)EHX=u()dc)S1JVVO1uYdHgxB@Hmh3u*+?>}m z>!}%jrgVOzdiX0At(lSH_mm`jM}EgF^nEIMt5p2ff?U~A%qf9J(cSUUp`?E-m98$AAjEmh(L~{p0m}ms8h=>DE4aBp@ktMemef5lRfl@nzN98AK3Pj zu(>1yH9sR4dtxAZdCKHT(7-zEfz8MObO3z09Ni!rKs0b3cxf)#InaRm3WQ;IHE7V# z%~n-Si2OnM0*bRKH>??Oy$cGhocpW!y~75<`^f#F*nHWXuN%mi}maUn`7!2(-v#!1AOMCOn)`NJkm-i9ROZI!R+vopyuv3np zKK`=%;#m&=0PcF-EztvyolF7$I37E>@9_8ZzOdJ-AOGvZ=TedX*}WCp?n5lxqXE@F z{@j0>4KQxvRGT$*s!br@lZ_5kt#B4Jpm|eMrcAQ6=h8Fc5`018#HtNY4Coy4va7&M zHKVE*S$poe^o*r%DcGHgylvOEjgz;^1?wKm$J0z_(LgaYAepZjwCdfsX4Oht!?}Zn z^X9?NZC#8;eYsUHz0I9p+%qH5X?J@W14Lqd=UuWy=124WIlFrIC@!d;K$_?67P-7qU+_oEwf~?0X1Kt>!S76nOQ$kve&?0%hi5?o3jCY zIS{Y~eB002|M040hWKCjX-NktPvq5;N+$$#1h|U-6+`r7fmin>-uL-mdlza^lb3I@ zEXV)qVdKdG5C8x6Vg1Sbmw)|ln|b*SiJHB2GsX8D5#^WvCHLtry>jbqxpM@5_X+;QC>;*zw*DWdu3R|j>Lvbhg#Pw9;J`d z9t(Fkdsr#1@5y@44v-HZ-#}RU_)E4s{SK}=_b*I^e_hQ0*F+;n$B#t=-tutwYzI#s zNDc`9gryrS7dp-3>{1@}%Gy=;{y+WqH}XS^nBz2U@?@Joa~5YSCb$@34);tw*)y<@ z2Oz5_j-NnZ*jX-TuoOGsT>QWb=p}RswS(#-AzM&&Wb)xdg6QFgZKk;_>aDF_{d4*5 zv+yI<;X7<0zNp^RvgJMO8@svPp6rJP9QNR^oh3hBbRZcZJs_N=_Z|OZ`zyxm(|}~Z z@(4Qnl!gr=T`yT*K>R76y%bxt0vkkUhjl(uedLux7ygR>MlRiH5zBX3)P=WMIP<+a z-TAh4aTw#n!T*WyzE}V0$pF~^iQw$FP!~QcyudIfshj)7*3likpIXziw1M%Bc6LO|<0%t9?GwC5I|6mS!eB7kT^jzdTKuQ|D zS@K^j-`s>Si-yl6mY0>K>q^&X=Wqz^;`yifcu{`Td+ zXiT{z?ZV&Le@&a%xY48Ndz|fTj~wieVt8FM2-K%Qy^3r3yDEuGl=9r;f64z!hkwMy z_gMIjXDs}x=a~8U7y3Waa|!t_TTZw-{NYoFJJ=^VyU)X4I^EOj!vBcv=jR3Dz*06{ z4``x0SUMXYoFn-jVIB(hov8iqpvCp}thPLE%if0fx7+=(C9T-P?^#Byik|7%0jgWp z**E+7;{OLEvuOD$S97IVe9{N%uci4hLu#p`f^X8nP5JU(*wTsEQXQ*Oq^Yly;=>F3 z28{#!5B5!(fqye>K6qX;oRu%uE_u)xpJ8A%eNSuX>%s5Sm*2UR7^Lu*|6f6kk>U^o zv2UxOgEH_JO{8YfCk=U^`x>_M&#upA$c=mGxA+dd7rgw8biZf+fjJn84pisiVnD(j z+VEq4o?eId!OiJ)XV>eo=hKPrRny`8Jg!CY`EWij{DZ-}BfGF~=hi`oeVg6z|3e2Y zb>&w0pWao)k^x>Hvtgsg9JBW02LS(r3uiO$Y4Z5-;Mdokv6L)WK)t={#}uzq%uumB z$py{b5>J&9->I&k_j`YD7RSUfV{PHwIn3-t$KxYzB&IiU(nNZ@MtU}UQ~Y^+tETK8 z9W-;h_*>5<=RGvlDmc;ud*mCN1l#9LDo5w}0-pGB) z`f^q!*w<7thY}y8rmD*N6O$|__moBqq@<#X83g4PM(=gkpOaop9qGLj!dX1o=f3?X z+$HN}{|R&9@A&?oz+bWbt}NO2osa_^SsjoS?b+MH_ie#mtK-9;SlWt9ERT9d%>yW) zSEYJd4kKswb7z7dixkd27n_WFo0(Il+UTLfsTnJ>p`5u`v2>}OORb3V@tWNz{V;6; zb2y+2&E%aoW2T)>Uho`Zg6pvZHeef`NuH>j`>h`PE`EdF7DkfY&W~#npo73J8_&^0 zBgO4K8aSc zU-gUPf6gkfpXP8E{`2tr=EB=LccC0@I&m_^h}3&MIK<1jcAz#Vi1?p!ux*r^0e9tW zTZ2)nHto>UtzFDc{<`$G=eP0L$pNs}HMi*X4t@A~!H@rXHezG0%kHOU41KSey`A{E zdYqS?)Zc6<}SbI@J9~7{~pbF{O|en@&oJhKaU*^c>J&2 zk7B&a@pO6MV|2jBbuyp>G$Omd^TW^q_~(MZdRI#Bdo}BQUHs>lkpJojE}r*!U%Fs6 z^dS6oU3tTS)YR)NQFvrDd3feehB9LtUR0e`TXOGh!QSQIm5ar#_2T>WMOl__lf@4MPs7pSa>tmGlv)q)%inGcx0@e#+9g-)YEz6qaPW zkG*uhmiXS&`99D4{O?_Nab5X;d|voF8xS0OKm)$rSEmEGuGoO|fF}dw^L=a~tRSv; zpch0t=tD9f;!*g2&1Ei5>G~MM{{{Tc!$yw#MfAV&db81?k^!3IId9es)-14}Ve@Cr z#)qGQe&9UF#EI}!r6nXLQ->2xzKou(%9}t3nycN$?H{lbh?r&l-=NHxIwEANr;oynTDF3Vs&f zOXh19k!lQt_YnAfsCZvCEKBcGk95t8=-ZFFgi+(IPwg3zv}@wcb{^_us(-s5Zlc4q^yCm=&SAJD_!^9AG+9CUaqo+ondt0$H%|$S#Q)0GD>v`$9XNLb{>TK?bF>WPY~{l> zlU`76PqF~)CF2$2l^kecnBl`+J?VV@mNoQ4UXBgZjI&7Ur&S^TA3w{osrl~x*vHlzS(~$)d>eSA za_>`wHM_$XSzVt7ym+o?gzLOtF(5Dghpy*ZPtgL`g|+xzy1>PDd93;X;qTdo=mVZd z^E?8*ubzNiu6~i;(99O$dm{Lq3f63OzN*6?8Yn^r{8IMcx%2||^B6dRCE5DhGvH{TY`T|kVl*wvGC!O!c2Z4g8qjpkE#1 zkIzMCEnT$8F2WDpM!(B#)V8jnPu@IcT~rJhWWnK)%pM?i&;i=&L2h{K&6fDYrc}W&>msW;_Z*F^!f^mWR`X}YQtHfoQDZ!HhWM{ z<|!}RU>PreX-ThqWvS19X{k?sZkf&PE1CZ;?QTC70Nr$cw$6H>spn}v4mW+9QxR*nK^dd-J- z?`7e=QYrzBpx`0o0obOZ55)VTgH*8cYyhz5HQ55f-Q#)hY>0Y^CE&x0-^KUR z1rB@Uym!r$2YM}zYr?S~WY@VzBPjTTMJ;4BM zRA1E!ytQNxXh{b*M(@ktZ-y_B$oY>m7S40$(Uv2VgmKLf`qA*W#zGSz@Nmb@%nR;9 zy|=KA0&8#%?Ve!aDOna>Txs!RW>`A?g7UWBXuWTE*vcMz%PL>{-1@)$omIche7rs1 zSpT=au^RT8J%_#LfxYt0Z>-N>4p{+okoodgmI)nXJpL(X0i+K;vO?-X3*hH0mggsk z7Q8+|q6gUkvj21@$kXqh%ujGwf6O(>eRe)`^m6v0XoS_eYMeD_*#;ZBqjf;1M$TDf z`73?=%RD&%EolDtFTwws5v16Ubic5dtk?6|it#xcz@r24ys*|89mxghj2ZeIYuY4e zVIp;2^mArY#%GfJdeP2Ipd9QwLnJ;~5 zna_T1>5qS6+0qA(90JpSDL>Q z#Tk@NogejtmMF+y60O<=XwUuGvD~e zvcWuu&la#33x6J0aJ|p#Ut2zOko6*T@XY6y1s&v}6C52t3wg)}of%f_$k~MGi3EJe z_`njL!aN?@a9H!$(F0g}a^VR6dc7B)Yd>m%HEs*<6Z23#V)vR6R=j$Pi~lKRCE2f< z#i7*y{Sx?JxbA$%yVJl?SS#Km{6z~hCiB?Q1#`a95z+@|EnH-)$^CA+aJ_BEw%$ly zU$r6AnIk%cJ`P1?{Vb0Dgke!J^nCA1oPfHju_uDf=0TgW@34*8_ni#@=YH^WzqbxsC3v_6Hrj=AA0C&0VLmH6fO86%`54#7 zTaUfx->`d2G?DJsVavh>$m095`QAKif+F72hwm(9mwizBI(h**$Uz=t{rNM?gbwm$ zA3TaofCh3L9iR))4N2IH9t{Y4J^sY;zj$17z}E+fq6=P^Uhrjv-qUH}20OJGzAt*N z1GZD_u*p`k2K$wXSx}J+A_*%)-SIVAli@o2rQy1(Nc$pb*9V3|88`XpP&WRRHFVPHUEA*dt zrcK(k-R9A&ZplmU*y4R(+td&LYQx@#m*4poJUuyGfeaQu3uDRbaxm$$M|enH3nTHf zuoQ+qrr+O>g}eXWqj!CmN~|n>V|fzu9x=(N}8( zHAf}P9Zs~6@F;8737nbZ(>@fe(a#;a##*QDNfw#LEG_0l_nkD$hOJ(2Q+EEzX59a@ z&3$>VO?&4H8}t5Q8~EOLR*8Nt$MzD|(y_u;GTf8dp3D{Bz@G~=gSpW^>vkLh=OQ1#R1pUsE2Tm_II>1gu z9%LX7avqaRAXZPjCX2Xzs-ppFHy--b63O8uLKhC>fb93>e;sW&8o>`_24#!PGJ2*k zcO{n@D|f$Reb-#-az9S@gTL$m)&Kkw_=|oXdGs->Ax0h?97-HdF`G`-K14H_qpZF7 znR)cFIpm(k&9H$h*4gB%Z?YNpK4G(8eAi~a{kcup_bnKIYvo|v7ffYK^<|ZEze?+N z?jg^M;b-aD9NlYHeVm2G(Kw~<`L2%FzlSmJJ^K04pFR3@AM^UV|DH5{PCCE4?1D_b zJDVk0kj;{fC>bPK(3j=x#J}+T)kBu|%9oadJji$&zwxn8@f$svkjtLMN<}6lfqxRb zp9Bp^H|V)9^Xu?;{Qrsb4?Ayt!h)7;x9DBZyZ4qN|JAF)^(*l4NB{rrZ-4t|+5dZ= z-~HfjdcVxEl0_@5_L3`Y^o{r1P5M^7xnMbv)_wslWdaTOX&RcVX_YqhCvbr+;v*9*rGMFPmbeS2;do;cH)8Hu50-g)c4b>CY_{S&)Nn$baH< zBhZ1PfsdUm5G^E&9>6?NI-yP`NIx93NM=BX?|i|X50>00TTTAASh8R7f6oSx z{r5}b?-RqjUwva6-~Yk}z42AR&JxZZuEM;xa0Y+f3-LxS_d)kb@-sECJgmRZ&qv?y zV`206uKiM<|FQ4!uS+J?`3F4qeFXiDx%}dAK$bXYEhEWC1tBG_4prsTu2?5 zVt_jT^RL3+r-Osvd}likd}9OOhW3%$(uclIOyh6&^|P;s#oIr|bAJ!lpZc1Q&p&#< z|2}^|*87k3TK#L11+ouC2cie*1m8z+euCoz&j<170C~VY>5E<{#9zpIh4ljQ#HYTn zG~xgF=a#GW7&P(dXO0G(PLM1BV?Fk1LjGb`dcnug`!gMXvuri>Kk&V3Kx6~-CJv~c zm;Y+~eLDE^yT94h2cd(vpnYgPkH1rV?&E%}`&<8-e_tJaa3B5G{OkVnAJg?mzt4Yv z{ry<)Io7rMpZT%J^*@&ee+z%nLI(OElfONi=h6u|JkDd6Z6IG%woe)NM>cK=@*wXu z?1z_$CqDm`r9lVjkAGp==!3i`zOWoK*4GKnM&#beXDo*%N{|P+*oj%#2WiidXClXx zA^ed8c>#Hlft{F!ohVx|89LCC-_UC}G(l{s-zxYYzAs`vZ*Oe>-rzrU#Mpm3{yrUi z`R!lrs<#hV^-Bkw&iC%`QMOy1ZFht|>f=!V9{<>N|2_We{_bD@d%NCyw7mIy??3vr zWBn{=A7UG(YatJ0A3A>#yq#@;O>`t~5bzlTbWjW(WJ3p;FB4Z59bg+|2!Cinbl}MY z(SU44`3`~ zerf&A*~nQH&9G*kIdwqA^exf(-@pF#NZ;?DirK&7ec$kV{OK?6+py>M5=%W)&n`SR z9r*Y0$L@3e>%ZiC>wnkLkLy48f4+as-~H?U?)i(v4P+Zg9)Pj45wQtmAIMHBf*zdD z2!ALZBKx2eS}!EWBpWgPMdZP=9vx&!7CiX{expYR*^hqi@Gn`l)r!me!}pc$%#zNn z%Krbg;P2Da;cvdRn_hX##y_>4YP( zBPR>MTe3ho1^JAk1NjPyB`Stg#@|~Ipo2`&!86bS_=^tm9UXjb<$wOlgnvmzfBM{3 zJ2{|zDE9xa4S$~w4jnpV_rCG2O?&AB%jIuR{T}{D>;(UQ`}_X{<70jHSl52acmJc$ z{n+d7I)9@VH}Gr&$%8EHgZeoIClA2g%PV+vAfK@e+aT{X;$#7Nko_!iW$@2^;!CS~ z_G>GpPN|Q>Uppwo$&(XD?@}Byil}^ZTv1IL@jhF>(c=o{&z0e!GP;?-jP|NH6S&ALx zKnEGv2U#!TGdxS2?K%9+k(_a2j!9W%4fE@(S=6`>8}oPjzxo*b8ust751v2xh0S^4 zeJlJ6zA$tk+uYq-c%=UQ`#Fz~g-zWx?&m-KU0~^dN8R@xH&fhQ%`E8)|7*VGci;Uw?Ejxd0K8dx;muDzw`DKAXQkBVNj7@8_`CS7 z{^KKj`1kPBYjqd~u=q#s_g}A1OUL>S=__|V@Oyc-zwAA)rcC)R)r`1W0ro0ztYoir zyI13&{I{P2FXy`ITdMec^-CXH&7*Hx#jg8o;Kf&3zd5H{QNLR25uZj+>t3!Fs3|pp zE!uQ&^;5l=U%u${Gk@-F|5d*KE&7t3107Vn{-yJuojj;_k9|!2y*^GpcK>Mi+lq&f#tqKe9UuU>(QT=&&q&L74tp9%U}n#)nKTa!%Ed1Y8US8{lHn+R@5!!hz?o5 zS3b3}hhMjnYwmGpIx}XRZb{X{EjGKvx>NfW6_;$$ar7XicBWg8Ui80Dug|s|wF}?a@9K4xYn2Q=8rS;x>9wPuAN~GgJr}-p z*TGv@D~_$7CpnZ4hN>Sd6|V|UFjmcQf9)(`F0A{rguBC=_vvv3b;hbUt$hANE4%a0 zR=oXY%Q<_!rA(Y-JxgmWIxWY##wA);>RBVfHk!xX=s6ojoli743-fM0sE^~hcJ)2) z(KEr4ne|*=-QOm0{$lf`TkWF*-n_^E>An6nf9~MnZ|&keAK74X49d5AbRb&zAwBpw zdi)Bmb$Yn|djp?!SSyZ?PYyv7wdUVU+Z9H3$Cz?dCM(n@Mw$8qs|ri90ebD1>-2UdeOJMr$tc99KjwL%d7%cH@B;Y zeUkM|PNlyCXIP2rEIebWUA%d#-F5H%_R8yju`j>+3SaO4Zmjp;O*03+K1{CZkPU|p zdJ`{^@92Dnze5LJyx+^+OJ1v%OuVf8{9x)x9fm&E{w`eIW6lHwuoiFk2jiNTKd~xi zk(V)_vhbpvmb+xNrH!6y@zkNmrsrE!Jm*Wg!@Hb)63&`+7#Z7>IR(Ny&UAjGYd5aN zbO-xbba_upV1|1!vka%tnP=x+w9#(5?GAhP#h2~Fj}Fw$ao4^6=PUdE-H82be%=?@ zxHmutWA=RM@~nOgLG?tky_}5=PkXi(HZ`(ZX8?q$&Up-BAL1~^zhak-T?-%ABCBh8 z@4#0-wQ4Y~_|tCA6kKWfr?0V$u`?~PtOks8IX{+c5n$UDJFF}CX`Xdd_c(`TH?WV4 z(fkP(*hho2u#QV$J}NP~v6H6Q@|CM?`_8NE!ABmmH_+LK4j=y4+^GNM-+Bl-xZ~qP zHfhfn*v!aZFs=f3o#}Bp+3lV$CEOjx+OaEZp513v_q||c*WPW#>$h9p;+2-hIg*~7 zrH)R{v`8?HME6FbccZk!w~=5hoW;{!k=w#mD=LvA5oR*S`7o+y861+5hEaV27!By!+#?ZQL7Q5HI=427>Rv7xr5Pc6G(gk67Q! zZm@z?8!U6iB1;}P(t6P|FD8v1CcUt$v8AHHPPSGQwpBECv}Ceddd!OIE?(}APL4PA z2v?8b8Ju@o$~noauD#YCeE4B|fA2o~?DNlmvHIKp?U?;5{=RRRef7i(FWNxjAc@%p z)-666`HZ~0X%^lC4?WC0>FsvoEw|XSFTCLV zWcg12`S+hY@W1^IFnjwy|Ne6a{&NTZa|ix&2mW&h{&NTZAG-sc`Fn@3?qmJt|Leg2 z{9Eg7_5c4@*g^84UVZgdyA`{83unkzuU>6ySeg}c_0?C~4L96i_uY4&-GBf6ZtbS$ zz!OhAVK2S(l70B$hxW}k-+b@a()WG+_1AXr;6dBBZ=b#X`s?=m^UvGUPd{ysJ@%OC z^Y`9+uibw8?RMjhH`?{rUvIm1?Xv5xyUsN4Qm;Mr)Km7}d++_~YvjK7hyRQx@;!Aw zmeHqMGyOEPAwM_A&AZW@GtIoyo}QZO_QZq)Hy@$4w$|nn>(FeUE%e9x;~)R%uzCFP z$K5@C^2sON{k`X&d+ZkQ)V;m($}4Rvz5F+9*x+V>sfVIw!s>f8D|iC)L&nh;T>DJ= zNG#=d+DPvR;jZu9zkmP#syK=Mrpfe6(ToxGOV?bXD&mBibLeJ_(2rWPuQdNiv#>N* zC686W92(7|3uo3;Ja`PIAMN7Bi`_ll4BzM;YuB7D@sOLnOivxnW1U1_mQnP*8$^#o z^}WpFyAp_Bb!Fy~`r`)EGcPoho_q91*X*OwqnW7;4*Jg9ZoAE%d+s^=;)^eS28I3l z-YQwKg!|El`>VNf>g%rA1@q|>r+)Qo>1Df-d$$GJ+ra#Z^XNk~mwPvu-UjLwtoZ<% z4WK!dadB}L%zf)Y9I$pkt&Qhq^GwQT8T9G!ad zDQ*U4F!x$>CN=l2ASc^O3X3c)CDrw^6b@NnK9&Ah;GT+LeVggot+_m@$te~}A7RY|ijIk~sHiA*h@PFI_0I511n=#J%;_G@Oy$^EH)l`1_%(|`^FK?#whQyY zRlgEV9KH+h6&^A0&@g)Oo=J~R$+%l@z15z5_F4Pvv(NrrxAJHI9Nqhiv0*g#L_N;t z&zWnNqBC#5^)`E)o++Px`Wg598}EMWp0o7atwSCj4wFM*0S*Vq@xMe|@~&HNG4)c@ z98%3D69ysBwPxCC?$wDWo@ghrG}E>f7_{ZOX03*Fgs!3KsEBZjfmg%>nsMo7?$MuJ z`bKk)$*kRK1Z@lq_qn)39gZ_mdkbQH> z#T%JJR7>x%Df9xJYrC$x%646S4YuZM&OQ{4%T9Fnn0x2zVJ`9po^Egl{jN&Ya9gV649P%TIda}z=>gubYK(Jiu{F1X+VyOzA- z!{inB?%n&V$s6lFYp#-dJ1$zV$gaT#yaRjt0JUfCUP8~h_wN2XTIW79^hG4+1meq&Wz*CSWqcaq=!^U z2mw+^41EbG~nVzk5GH2TneE%A}H8l5cef}kw-?SHBLf;&H&bI74Vq10{wO#aJJ8m(!?9R$vv z4vNC>f%g;LQXe@=-&Bu^X2iHXR_(V+2A&+)UyoovmKuuybW$1Q9n0_b!k>N|PT-Z? z>jCW4<;$1ds#A_%&Nb~=;4Cs?Ao9u@S!q79-!mD~~ASTAy0mXr#*yZZcV6TB3 zszp*qtQul$vg#XTm#eUL^f(whUY5V5ev=L8sXhc>diLzuE}oXp_rV7r{I}^OooACi z=$_XZ?#W*0oHe!yoqrRZqcy4VCHTwke)*-=!Jnv&{Km=P3!dMkhWPv|mu$n9op$QQ zm+korZ`!`&7wl>9e)6d;_RN|+wtdfW+jID|oqFLFJO2E6JNDdpJ9O%T&6vH2_$|xD za3T0CrNLPIBZUeTa(bxXI*@*nE(&6;gklFGz`JIR>XtyfEgPWv?3yvLP6k>B)u=h} z)ayb36vDxaC9}*g7Iq(*Yfj4vU;>9kXpGYmP&T8}`hqjka^& z5j%e7RXcj-HQT!XdE2z}nC(39oEAK`uF9s*ehRf&VESC4Qp zT{U9sC}O)vFs$k1ApB$88W8@ftqQL}Ef)GnwRR!kui<1sjh%E-IpXcI{Ox-9XUZvw zdwv6P=JDgl?L9F0XP$kPpWhuGv!2AYUAuO3I_K!YgZB2-t9G6L>x1{+$2a?seByQc z=%Y{E{J(MIGy9OoFEfwlFJ5jt_8zspM_;gAhtJrWZ6|nq7Ttfro;&-Rz4H27cJ{(W zKKHb>X_v=6WmsxzJxi+t#~Sf!TwD@-nsJs+Jz^I)Zdx>LYO!EfjvnCRxpn-;_ZPY? z1D`Gu@3q!RC2*>O&I$*&7;x6Pfhh72k<^q&A_s@Pvjw$o+kg(K7EUs#OubZa zSU8WVcSHsu^mYxX97?a|^3I=C-f$GT7v=Sob5)*D`PqNQk77aD+%Dv|W+UgP@x`uQ zxoq#^r@w;?-hcN!dmkD2@c-zekKN;om#)~nMNiv?t$S?;e$D1x$87n!own~7d1Ca+ zE0^A~^RK-@4ekufptfH5pO%?TEV~)pmE`JjT8T3Rez>-6U7S&$oLzI?6JMmbL;dj8 z%MklY4+(4eL%;w1AMUIJ)`N7AhCiQ`PZWtis@N+U{9`z`p}yA%DXE;@i$xE~Cd49x zJ9asoGa#M}YC0LH*3`qF^?*JKhD*VZc%u~Gqb546YqxGTiM-45<;$H;dYv4LeDGiT zqq*N1&ext@yI3A)%Ga)5WzVt3E~D$NzIlc5mR-Ag&5d{7e#fqVaNVx*{QQMi@mp5f z;^iA{%kJa$^x7S^VA*kIb6g-dq%+Pk)9{Z?zylD-Ax>oUPX*yoT#QcTxA8=j^% zIhNPH9X2Nyo8QUtdi3eh-Fk74ZFs*r{z-Yiip~~4j10sDEg2{_^Q{5-NM*ra{Lj)u z;;QxLe*!Y#90qlPb?7Osn){^MsTNtwTMrTVL|PZsR2S;}BCP{&?yII-y2#T@vd>=3 zP!3)b@tLGCkED~tIimfIW8}Dg>0ZNGa`@sVZU^V?5pFjJOT>xk0*Ip)1_3A6H*=w&} zbl4v|e#(ZAo`gTY7wmW0r0I+8sa0FBvFEX^7p-US{#F;g-h?^dl+hf1BI%qQ`ex^n z!|TAj@6=A%cf#hd_PTU-ysF}1?~4pZ3>j?Q(S@y=H+T8VN`V1Z4j;X=bWtfdQ;HIs z`TWwm?{+r24F0NyxY8o%xF&T^am}K=DuvQau-4L)|XuftQ>}qB#xzuPA6%fNckk~>1iz}PW@Xy1JPk! z@b|N`bKp^$ZF|Un9NM?f4ikSLK5)?Xk>@;o@Q|G%4peX8y?giB>NOi|=%|Ud;OR{^ z6Aq5?(-ztKEqlo6ylO*+jUW$39ymG0%Waa66!tBfG$EhCnRW2&3@@M4^~`zU->+v6 zhr8n%fMZ}Fxk<@Dc_;Z}HHcM}&j}*dt%MyEuT)ul67ffgC-5F(1No%lgIDfO{-|_& zt;8gYNvv&wi}sk`zPGK?o~up{!RueL;K?hkT+>cgG%V7J1y!}Mc=qWUc$~o1i5KLb z3U}e}Yy)<|ixVV+d^uN4d)Ri9a%12bjx7P?n2I6%R@2lpV_?yJht2~|JWaW*-1zX+WpKP_@ zSPxuw5d7aYzrF9kXZE)F@403H+pk#g#+NN*`ev(;)5nTci?bqu==fU6Ry)11C8L*| z9N_NqY_o^I&foarw92dn*=KRbNCwhV{=tWM9 zMn9dY*xj`&m)q_g+imBz?c{tm@qCr7WzSA~TU)nmwRN1~nlpES^&2|QCSz+yOqgq9 zrz|9gbHFxl-NimgEsMvWNM+vDXCF$~iw8-5PA9PMg^m<&_GrGBuwFQKjxBw1fvti= zL;v^Y_3OBY(myVr!+nMl-&Q8C78DxBe1lsHeN+a!{4nu>e4@LN zfp|E@k*!=qEOS8k2Rw5a?B9h~@E!B#>JO)!KXUNa16*^PUbT=p+pSXG2rCg?$BM$? z5D=YUNevnyhcp*2RMi>QYVuF@9oSEB@q*%JJtux+Erehj^xcBsWfFIhI6`}|mbDIE zef8BJ!teSQh>J6$aWk7VVWO>G@eF&2Yi&Jy5}T0C3UU!^SFdsViW@gfR5r@%)v7>D^`>#)vOId@@ zycQd!u>skxd}^7)e-%EL9liRPloJknmRyDH#0y z(MJ{GToM0XC)T?5c+`{2_w&c^{?ppw>u0xUWgRB!OWjK-=4!u8f&I0zp!!4FM*O2|hkwb^roEg(? z9=`Enet!viZSnkh_6#xI3ii%cV&j*y|F@FIE0!(g^~FvGD_IA6U7w!{r@Z_i&41E?mhfNwJea==_65h=?zum*(3&Ab=-Cv)~&I1#9qsor!$_I zZnLOeSiEQ!K1e5Z|fzE-UIaO51c&)|3K_PRcv^5;tPFd9_OqJ{w&*d5FfmarPgg=lbLJF z7B6(%CkyA#x2Ktt^T1~Q+<7)1{3f#3{@A$j^xtZ0UHXi$<~iN0W0yg;@Tqk+dhA4t zKquG22kz0ii#<7Kw$n43!{XJP5AUdS&&09g;8Y%BdAXge8~LTIR@oK_uS!DQ7S^KY z2n$V2x7I@+x4JFbSnZ~5EUs|}OGy`xc?;{3+mRk1HB9-)NcOp0UO!6b*Oa^Q>|y|R zxlBbrEA-$)9$&7T|FxO_;J^Mw@PE&Oz&KDNe;w%R>;baz-wW5QhB#+=z2ctt8QAOH z*UTSV9kTMYg-lps6c$pzuJ zK2I!gyzKST8`?PX+^W@iO7oNT{|tI~Ci8#N#ECYBnBdV7kJ^9%1L=#<({eiXh5xQS z92Mhi^@eTa8sn`xy0|WDU?h9FlOG#r3+K$SiQ^u#T;{EE!DY*0BOmdzqGdwS)1@tw zSi50nGh!a}X<{SmHEOEWYuePtJU-c)wP|G|Cr!5IU58qG`1M-x+3w^D{+)(98&MiL)Fg&Tsn?M2m4LsRF9+79w>Gp! zBWwcqb>_r{JHYb{%~ zwvOojMlEvTpJ;7k##5U%%>cCgkRsblNf-D))>$G{og+&!1?rKx;rUsJIvW^G5|IgZI%*ytfN`u^n5z?t)dGxy=H5PPEdg z&8-wRLcIcNlh=)jPjd0JFP9--=`r-I@8|lTzO%L+^QFiat#CAs_=P2-Rjh;|Gvjg#j zKYAdBeGlb@wP*PI`yR0S9)@ePB6T>#{?+4aS=D&|u1CdXNqb(Nak+8SiBF536A zhS^;$qdn`aT~}*PT-c2qMJ;k>@&%K~X(W&nibD=D_*%+wMv~X8iQlVrpxB^1d5S1L zpM-9RPpxl$TVFH31MfQ>r1|gDL$V2yfxpu~KJ2B3g!T2?_&YgBALYxTBHSo`JNf*M zYxu7CO!N0z@ZeciwqaX)Br=g$uC|56B)GGnzCHiP&?UZ~7vKBD@q(w<&#=DK;D|qX z@uDZeevZw?XPGv2sy&WO9ve57TEO1uYj9}Q)>>reSz_%*)}`A3n=^lj+xL#qJ_kCu zX+|S!M7$-xzbHA%Nam#5uO%+Mr%++|yvkUSO2mlxbY%i7z>P-CS&P0-i7^%jmsd3Q zta1b#w%F2gfg$jzQ42&qGdU&2;U9zUuS3qUw(7O`KO~3v6#RQ9heUGyaoA_|jH0HI z*i14>sza?Qw$g9M8&(1Q{n0n4ei~Ih z@c%7&v3m;_u?I_+vtr|QrK|+GOXU;A5nY@-XDRY& zsi~!;?dudJR|;l0{u)PzM<#yFD+}I>f{izp|#{>w^EDx2)WO z>sA5$D>1w^kZ%tphx~OR{QVsEp0261FCYJX9{%3kXHD$(WZ>t+zTj1I*zt~4CeK$L z+vL?=M4|uh%>Q-IZa4YVX?4?W2=n|2@LvM%&pa*tKgULl7-7S~UcOI%oNxw`wD;6fotyn$FKgwetY-tz`vM1Sf;!cW9}Vl zKQQ;^KX@aDijskw`<^V^T5!1M%ZB$VXt>wjwUEb_5g)`k{3U~N7KFpqsrfn#Q*8RUVJKZs4=}5qheEC&)xA89=D37EKA1++mf7@wZf+U)Zw>Hc#RslEM(L$Q zt%HOl=PMP122S4@{{u%lZn-qcXHkKI5_oG_2R?MSh z=Jnu#18g38{~2-uONe`)0RKsoCOZ2&5I*59UAj8HvwG~`#l+WV?~{7CVI!FFKu(IeK z)$arag;-tWH){^D-^z9Nj2r81`RWa>4yGl!q=uPIt!3*rjJDQ13mLS^LJnE3A9EvO zhX(AeX+3ByBx0ZA@%>ZM(k-6-{0ax(bNGiG`N*mt{n%=7jW{B1r;i=KTNu}>8b>~{ zYDYiiGoM<-(HmTESRiuntpkU>@RuxvKiGRR@XdYiTAt4YGyfxFsVQI$s0OB>{$IUn zmE~k*yS>o<)YZP&or^vA96BzbqTjnV435Q?=8S3(T}0z4}w9*T>3~EM@nj zOH_mDa&Gt0$GLC=?~;OFw+ zOP*d$4GZ&r!%p@wkJ#2-&r=K0#hRh_n`gDLoc0~@13F-fI#{cmHqJL~LGD~~P)}^d zbmB#mU5F{;H-Cv}bm8<~%{*@g552AzaMn=KJ0?8R|tP8&L+8yU?|8pPMkr!{; z(HC!U{nWPazetXxoi#$YWVLN?ZFBRiO@~g_x_vHk$mKO;!9H@UoVMgfvc2Bq&01Pr z_EF;bPRZoU;+tfF{RifM_(SINM^;nA$$+(xzYa9_Z?A#;bs+rRKnB6^pm{R*5dR4o zxFPH%4^KDAMpR&wXOu%;!H+Ek|3t6mqE@Z%&HuIJm$QlMlknX%|K~IRmo8r9@L$Yz z-n_Xs1|R6rM@L%w4jml+(Xq9u&B-F)Gv4WnD)=v|zmF#GmWIvKK4UDpN42mIJ@}w; z-qOk7frkpSZ(9kwn1l?7ftmk>AAG>Ak!}O$+NgzlY$-XG-Df_teJ|Xy{V(3KgD-yO z)3@Wu`|zeI^^ZA2TukqvN;!q9AuN@$bGu`-!$6-4qvy* z;9uj|Ct!a^29m{3>7j6Rk@Qalx+wg}4KQck-yWU}{F&=c7Wp#pbNFLt_JjYV<=~&- zd;!(H{80a^-XVtAu{ZnO3+BynxgYudvcWq0Hjdb9EJNqx8Z>T3Y?FxZnL|y(BvHlBZgGGvx|EO+J_=6?NgFo-dZ_<8M=YF$o)ZAxn z^^rGi+v!hj$C;b9ld<=O&+Om}H*GSUi?Y4-(dlh-JClFvY`LAgIo{z_#Gzs?Lf{g3^92;CDAU5mL8YegR6Yzz25%oh(Jfw@N@%VeX2>d072xkjCdmwqpM(Zlu z?9W`+(Ax0dk4!Xpy~^WjU7t_oNuGse8cx z#0EUWKGc#Wi=6*6iTqC+-9Px(j84Mm6aEt{oIF=>fWL(^|D&td!2jgzA%0&BYeD(A zV(f_v|GR$6xjFQYANd6JJS$R)y;|@u4*q|@FU{#T$!0IzX&a8dV(U-7ZJSPgY+Fx% z!W#I*c0d2Vb?DI9*(urB_TZdLzOG||k=v!alYy>!zb)&bWllSnhg4puHhy!h>`oTu z=J_WU#oUhq>)SHmv9Pa^zb5`#2H>A>53~j}q?4*?O&q&nLEsz!_L4(@lZBptZ2s7b zuxT4u^C{q-;ILOb{uujL`Z;{~u&XZ%Cs*2*J%Gvhn+vhKE13JLy?UBBY$`F?&1_4*~a769^2Z0oI_6gPT&mo z-FmYB)|$*~c3E>@_y?kM0+{=O=%_&OuR48`MJJ@N29g*FE*=~_ zZi=fFf9>LHUXGa9pcQ`T@Zm#k-rU*bpO-uRFC8R5bQ1V?>e$I~ozzOK$2Hr=a85@x zfkDKrRjX8Sxz7~-enb5Kc1ff7?!7UCf(699WC*B>ZFBceikGuE~fw_Nm1<{CzUO9v6^-lf`X)^s&=N z@{8{HMxQudVCf^RgK(}vU@hEr74E)kwV9i#eG&f24Dw=0?2k;HNA34p)CRt3is_TE zQSvPY4;pAsJWg**_8ygkSh{S9>)S8|{JU|czgeps;!5IAct=K(kB+KY1N}qIeF$gR z(LX5(@$Rg9EWUpY_QF()qq9PH-F3J9;r^oJ8;VBN7u$wy zXKnM|^S1dI=VMM^w(V!%1OE>#uM210vAv4BWP97AN!d_SS=VFmk)} zK=-sK)?we5T&eQY&JO4H1}D$fMx)DXftgPR(npc7!HZiMYkm&Xzo}fY=D+5?H~;VA9AiGBPN*7ToiExqV*-(nkek0QR!QRq;_nz&#lM zNY{wjThKYm%X<4o$#omp;*I<47^Ivvh)}rmUe%C9ub?>XTi{8Y0PhYYF=iata6KB|9a^G5;SvehC z-0S?$JkRfu59I8y(?LC)Z>0EGHaEC3^&iX&#b0%)--+!y7`#42r+*0MpIR*VYy6cA zj(_q!o8ajp)&w!L*2VW_;Q2|i&Ed`_-?7ahhgb`Y8gsW&dqh4E9i&*K1^N43C(qfn z4?cD__z7wgI+E9~ioI-$FFJ8N^-v4uQDe2*)t@isjKL!0p**N+eC1oWZr90Fuh^V? zj6Zu!ioukBND}_Czv!Q8`S>gM^XuQ-<@UqXgWaDz^+V)5?;|(&5Tht@!J_56Z2gYY zL}|I>(rYxNik{@}!1js`1-J9a=akUV_4$k}9YmRT9MOO@<7&s2yqP`2! zs?TBlyZI0PvcIZF5dIaYUw)t%wfkUSm>LoFahN#^pKHw~#zyi!>*>9_#zu}FOI>15 z>S8i1lU#!KAG5VzjO?X{gnxT-B9cMd+)geBAwJZaSEf-QIiM1{qeX z&nT;kt`Yuj{)2h6>~Q`%&}))QG@p?zkZ)ShKlS-XKHv0v_BcO2@Zm2#6pDh`l zST<`{uV*xA;r3osSYjeUaw*Mn#ndt2%sBOR2* z-udK-<6SOvJ@s!o2cVps_9T^q=!uQ!(Wk!+q=skos8JSz|F2#Qm01JIxut@a;xCj8N3yXHE$&zz?O~!JPEt6+7s<31P6!E|0j?U;AB!)d7#0Q zojwu%n&Z+pn&;lg$6xk0$%OhYlMt!tKxKta*j9Wt|SH$^9z^Rxc9aul<)_{|EN>?msyH|K7so*#E6)#mbha z9>v>#DUSYeeMyjEY4+KxR-+F9v7l;*BKbZkdKT~m7EOXVf2Y2Lf z+a`dc4Xe*!pH%b!Jrli}q1c(&|~A`sw8K+22Q3rV!_;{y}Fes*-yxSJ96gQ&D$DI2Qk_ ze1!^}1rBqv5&o&;pR{_%Kel?Or1xc8J%2{mSg;cQK6~Klr#rrp@YnF-1I5Q)jI4bG z$-p=Ng}0LdSLG%Y55z9qW$|^$$vga0tqc0KVEw005UMX!jeQMtNQ)LNtY4qr)S%2T z>7bR%pKS=Lr&Otuu6IMJk|mt|Ru2K~fyIIM2x@j8W%%>^$_uJ~ME<1w_*m_$DW+w(Iuqu5AyF_ zkDYtPdUfwXPb%u?qGPQyaq+0pBZ&bPIbU=cI!Ja{`(Ojus~k)IL3_jFxklk@2tUOD z3DMO4lYfv+7Osy_Q=(pBl7p|0QW@rYg>q%hpU+ewc8&%|)%L3=*5l+_)i*2H0Ry$;ePvy zzI$>9>$fg>1NH?O6Q?}>J=}dy{_}tRZ=3x16V?Mg6b*(M?4kDO4A6{ekGoiSB{`wR zOV}5t9<*Ki4mOtFQOb*|H-h|7VH*l&arizu_o6ynCj;c7I*7_(RfBwy_U0Rqqi&`% zkeowmPyLE=u>Ck=^aQnD-8$!ScBQQO1q7LTk_cm+H&P!ZT?2VuiM65gUuDqu#qo6> z#J9cY-h1&kD_AVCcL<*e!ym4RO;9aFdZQ*5)nkPDk6vKm+h4Wh6U1QoF>lQyAAV04 z`SQ`VSO>BT$`$$iBhLm%23~H$7mNA!2z+y1SG}fd{DN&B{>%gE(Vv?ClEc+&*PPF- zvxYjiFI_Wo#4u`d=h!NA&~jn|=^&l69F6`F{!_qg3VX!DSLbfE_oX@r^yYPa9#5|Du}fybig}&+H5KGuiJSk1RExb)KsX_P8uVXB~yLJ8#Eh_0rSX zmQtnYN5KAqdP2yS>kMk0lw_y#Yq0mA+M`(VBho+G3l5+Tzg$3|g$#MzVh_J#u_r$D zd>__;bWjv{$re;U`k}M6p5F0ng7lK~QFMM>a3^PqKa2j?+>c-=FRCHj!+0Lbh!g&) zs@3zx-@;!qn74Q-=iqv}^SaUK-fZxCbi{D#LOB~DJHQ&4H+QZ((=-X}m77qVXwM$q z=@Isji^CF_gDL3h`sfs${ZbEsZ17iYu6Nd*vmWG>JGA8-7e3g5u@gF9 zT@w5J2zEt2jr<~wN6=?F?^ps|_As9-T)2omfRA-AbH6Ik=&Apc`7GKE4xXuyWlv%I)ix~c}x zg}t{w?BVa$0JgU(G7FR3p4>*QY<>KP`s_p3wMmap6U;yPbM4bx)@{HL{Lwt8OI7Ec zm6eS@G{)`AEayzc0`e2;$2oy{Kb0D3^|w{+uHs(xE3A%9OduDhT6FElH%d>pW~_l0 z`0?(1H#w(Va!Kvmwd1_mBQ=(i&tG4AOi@^rF`Rs7_ zu$Oq=(d-wMCPrmdm_vlas@Fu(39SyhdYW^B{XM>h<;@`lJYTTI%;x%&i6NHh)j& zNu}$ZT)(mSPG|_xSLa|5=6CqQSp*dL#Vi z4C+ic+`mqo|Mb2d2J9vwc6en4}nRhj8}nNGw8Oy{xA8c$~} zsE$#3Nb8`Q{BL~9+F+snhUxh1vMn93x1)x`c{u$E7jHkHd7M8agNM*7g_++)iy;TF zE|!mban^)}>V<^AdeKP#wB&Cp7w+r5mr4z!&fKd9oZ<%IU#?PsJD1_d{#(eF^A?WY zi6R#Bbc%Gp7ZXG=|AlkG`7hlgpD2YBO@lb4*2V&6_#h;U@d3{(AQ_bY@F_!y;oP)}pU;U4BGRv$SxBrZ-z?&B-%>ulFXtmY+D5(W;3hWYl8U?m}Qlp z;tcAZt5#V$2V6a$#*=}Q1?xf>3xB73u)Q^SF8phPXOsrdHH5wP-^25 z_}ESJ=UNT?>k@yYA%ir|#E1j)ANl$G+rQYng^O+2pn=xEXD@ul_SS?t*I4Xp47rL_ z^m@xy+13vk4H!Di`d~M@<3F{_?Z|mZVo%n8UTy~)H2_P@8y5{k+vXG!r|b{;;YklMIx*PR93BZEpCa zRh$)i#hs6+KwWc~<~#T)4)EojYoW)r77FSfpYE>##@@VUo`bD$uf~v$59B>R@^0n0 zmgBWDTuUFnX^${!EZh$MP1u)cVrk@e{!#oTt26ZXk*}zJaOy|WlUhajk1g>lrPtG_ zpHr_#t#|cn%gmt1Myo9JP%l?IK9@D2^ECCTVUR8_TBMlknNe6*Wblxi>xI!hS_|Gf zkQ`(O-2CTvN)yMqJQ27nm(c-#K>uewbdCBmDQ<7V8k4W9|6AuJHBZF(ram)OW^B$s zr}7?WVC3h6zw|%&d-*qEuiUiv+!uRAf~T-|_;VHRS`WHvNXG{wM?dC%dEPIJY|1c% zeVG%VS=6F!^z~@!a)8PsPGP_6AN@J~(gl|fRzDu~W9vqYtiA!tlMTWasE31OqJBw( z`u216Wd}U`U41&3 ztFM)OeCeR}_)e|JJ2%Xq^TJ*8zBRdX#dU3osb%Mt*H-OSL-q!$PG9fp5-L$2Qu&Z) zd!_$5a-}yrFhlZfzhcdKpDO+5bT89ewck0Jgn%qDc4RZX7UrUk8aWWuw z^7-$&Iz9BTd>KYD)&#OBthE5i1tBJFXrCs>M0^LhCv%`K|px z+2P>>2f1}1zexSKwO6Qfal!ceIzLp7eOJk#wDS5chkzW&9jITGWa07$%xlS@7}z`f z!CLik>ZK&#zXU-$}ZFP`%4cR8QmhrO=gtlV3a%RP8GX{Uq0*N4B>fqWvx zTvhp<;NzcpdWdr|WmN-o>N86Lf90Q)gVj3tCHD74dSJOZ&)gqI?pggvMhs>TjOX$x z-I_o?U5M4j1n|19V#sPWOTx$-a<)F`gUE^1?T@+@E_b4-H*-@)gMejVx0bfRE9Nn65IUQ^RYoTy4PygtB<&S%i ziyp*!lOC5Xl}*h?->6<-DBoiO`BLSbv=1@-(UI1x-vH)&8}>WuSw;Tu66L6OtQchB z6Bk;{D}S{37r(I7=Wkj1b2lvQ=D&PU`9YEB6v@Do z1K0fL&L85l)fkmIM_InpNGsE%qxo%n!;-MS4KkZL8PxxU_`gUGKBs$p^Buk8=Dn_i z2eV%_^tL>N%SdtyBZ&pFo44e=I$Y49Rb9?r=b_c#T0H|xA%{}VK9nKPR>~ei-#mcM zFNfYzf2=9QX(NUVr3dv8@=D{}Uh`o7pU%v2VVsm!-y&k-$tzd4N>%865>9`MX!brE zG`FY@-7SvZIH?QPTBCz6Ta!1xvHFaZH@>!nSH7~u7e2SN=RdOsr*5z(e8UpK*S8+L z`7i9zPd?ni-qq}$&=sE^8ED>XNCtYYQJu$?*PXROk5q7LFR0rHOI-9U^FGtlLEt}S zs#p75aDM;2$HIRgex`h%p#%E6d9OL|lY!QPa36^8DSO}sb!%golcPtBus&d>Ui=Z& zYr1uyJXkU8fJTwx9`@2zscEU4wS1IVZiqWiRHs2B3n!oER|T#FdQtg>Qd3f$Uct2+ zSX8^N7CZPcOPRgg(l;Kl#z$VW<`-{TtGEAbSqxoUUh_tatGa$`&ENXg8X<>N)JRRiZfDEFU(~%lZ1~+;B+3k6+br2;PhsE2F}{yLNP%k=-5)6e7A_jR>^st1%WjWhz#(x^vfpzjS{SSC=~Z@8th~Y%QFBN&bIddO`Mfau|dR z^jxy=&G!-5;R&O?{$lDGq`aKYr}pUG*IMMX<@`T=9q4miA-D>C9jaJ`%ADPZinBz{ z5;X2T$lA?VV4c_Rv|cA(wtiPWwVoe*XKmmA&RT$TbFg*u7i=@HGKYmTI11-PMm!_# z>US2)(A9hFy_UdpeMT}!;dj%JK|0sQyw+6f0Xd{0hm;FnS_zq2b~+Kf zYk_|>b~Fm#NxH_v8Qc}y{s4cyR&D!bYHZ58K2YU@DqH%K8}WS_fxmZ7{O9EVe<%ZS z0*<2IR`^cE*3DzjYbiCMstKAvKNX!%)!D;T@(b0d|Emy8KLP&`E5|wO3Ze9jj3p0G z&!#5*hFja&ORf9%!#3djH5>TuSJvhFch;Ku+#G$;LOKF`nh75sH)PZWCm+r}Y~#Sv z_c*q|W8Z5(yv92jd}qmAB?GO6dR!YaGLfbJzlN8;wz`tT`7fR}^NaGCNyjgSF4i1ADCmppdt+-05E z6KjD_tvb>mdYqN>hqI$nh?S*pW&r)^;+j(j*k_2fCU2d)X1jGg^pf?t^pW*=?`v!O z9`g;1g=sF4^lv>cC==gfCxdI>*&TiKE&nHW zng6#DL+eWGq2XoL!^J;YGIB^h^SRZ*UrHs8O-2rJj9Mo(guUXp{56m-6SpRK>^Eth zl}yXBh*i&9Bk))3CHxfwOnUqu&;R(=!_~L0vhO>>QakmqjIqng3J%@%)1if8X`ipZ{WOKmOWsuYK+2j^=O!a8B2J;=5}u*Wq50 zxXKRtaQ5Npo0GohzvTK$|Ay9+r;qggyrDT!havkcoz$4og!dYAFLm*iQeN}qko3Zr zR_Dx@mU=p04y*^^?a9K^L();o6$R4!L~%i;^bhl2HDHQ^C;k)g_sQW~YKC@v{uj%A z$J3{pM{#^_Z``qkK74;EX1?G5XI>=(%?s(fBp#=rdn5*mnifzxvEiyq3u8l0!1X*=Ka6&rj0YmW^)8dyU>iK5u+u zNys7LEcW4rKU$sB-g-!U{&P!^jd1os`bq2HrZru%72PB3>Cw^{{XgZG>wh2KKXv`{ zfBrAq{=qG4dl{dB@B4G*@XuHmzvOQe{2hJYMC^0owZB+0GW7f;@MiAIUv+ZeDmi2z zhdPqOtE`8!f3y_zQX1=_4tgmO`;fqzh}XJ69!(c-0e4~F-1PAylEXKD{?7J& z@R_x{_zCms+uOd(-<^*>8~iiou(0#t=erjC`#<(t!T0s}$3Ek&1+53^B%d7ciO@^3 z(cXIS>_dY$@r_^q+LB(uKCm8AkU?G6L>g-%`FZ@<=f1RN;|H(*)$jd42i^X? zAH43xZJxiX_`|c&ilM#rAfHvfwCqEJEBMa&a!5M+73<-TP7d|BHeI&MGMdp}nDgK| zzy9Ab|9>bm$>I2WAKT!!nG<~9A7b)T82s>ax1WRY-~1iD{{uXIzxz|K``-6m-QVZ$ z+?K;z-|^kG9=^d>^45d&l6+Rh4$aU>^)7#FNteE{7%WLHQMYT=28*yEz&B z#pxs22QO~8BL^n~)^;}dx8}3W7(Kuf6zy`Q_Q`@5f(1g-t=6{*lK&{rA5A|LSl0J}W;}u|g_-kn(%V z^EGBDZ=rat74K#9Jcr+D!_YP7%Ac&|l1*^*gt{K-ssqSG4&vYXpYkJ~!z;J`XcON2 z)Y9MllO?$M?Zd%${rP_6Ps!o0*VvuEt@ph5y_~6h&{T$UBFghMVJJ7%@@;Zd%>Nb) zJI z;Q!wDxN`Fgn|k%8HGGr(5$@lIrEd=Up8uSy?{|FI`tVn7!#9^}gR63T4Y_9Kwp!oX0I#r%lgYw~XB{S}OB8dE88k>)hXJq&Ky2@{6H0V=avQuJ{1L*rO1? zY6N}fBctfc9Zf&B_(XSRLbmXK^3Qd6YiGZ6i?xkk=j0$++>ytRX#MtItToTGd7KTtSsHo|f2QTd&#cMu*R8?&gO)n$8H=aCdrVHAMbu8W zu;>J<0=|{2QNznzu3Syr7jRX<$Uwm%O5Cj@Mo(Jp3)cEkI6wNIGn+?wMIV9y0+&1 z>`S+-#mUQ-x%sHoo4?vp9-U&boqAi%22HK1<}&lx4PhNFo)M1^PyNfoz*^^co6`?r z@Cf+UmOf?s4asYE!V* z{-XB2vKX4nIbfY5jL{XXU%P27na7Pc9J0D|Ryd5~JN2^2jOG>|mts|faYU3ikE@DD zC&J@dV{VK4D~_`REvaJ}ICQAZU9ix$?bu~!&t0%j;NSf&zjwg@n~46hZ~YayjV(96 zwvJc7vK-<2Iy&mi+tz%~ie@!_fs*Yib^&BhbY@?kJBp zC&Kk4SC8Br>Q?%*$3K7JBHIDi*0~EW+s9!1&*YT-Wq15P^S8dmer?{h$I|iTLgC~J zMMsDm&FO~f9uJ9n?W@mR6lajs4>zxS51T-p$}%{Y_8vHZuDD`1ZvHqIn(kVD*}s4O zHUi&#`>n0rwAuA@Y{$9r;q2>ApEbv}vrl*W#j|$pop)~Q;=lcu{`%d2<=idnY8-af#@P7q?K>pW6#u&!0{=ahk%TJ>F_j~{R65abHvB;r=2RW-fpB^d0 z;ZEx3c&w&Sm!-3+>(;Ha9Xoc|i4!N_Fu!WIZryU+pyFs1fA{6fmmROYI79dD-RpRC zSJN+i*|KG}m~(#5JoAkE{R{9x|2=NqU-JEb>F<2_;fFSJ`gD4=H*{yxT5t}nA@zPb zqgFc^PF3OxUEMiluIi~I?sDDR2KY_I(YbKpLU*=Ty*0$WAWr8j&NHNOmS4S%BJu6S zE7hu1D|;M%Dsc?I@x~j(CExwhul-;CJ@wRCw|1>N52JG$s?nRtS)T=*4PQpx<0^bl zar%v-9<_C=EY5@1cjtpcsk4r#QN!I|2YMMbqt-f!ns@aM(wPr;=9qeT^>+#5+@N|q zs;`1D)VX~1`RmMiEcGfE-}UwD*MG6!^-Dp}{2McBl(pmR!$|6b78A=HB_DAr4b*EJ%--HXn$-$yS8_01~5c?|XTt3=JZk7FPT zoDw09H8JsQJ zxnrkYyLyfL{np*{H(!6_azEdG^JlJl?OV5A-+Sj>_Vf!`gz<1FUS4&-S7HDsgF)5y+n2YG11YM!um+(e4DsH z#XT8Lj4i$~@qmi=S{$vpoE24H2I)@e(;w@3^yP>ZSh07hgKr z{^_ef+1G#ihW@S$F!+kcH$VH_Ub=A6j+{Je&+a*4+xDHbod=$`-G@%wGpo0_GetTh zuii51Eug;8;wI5tP`@Ufqp!w&MbV$joptBTYZ&Lc#lPo8HZNjvw#<7|U*b@%a}HgD=1Q%D(#QYv#e%_62MI!Yh|- z|B+L6@+|%J_nfk&t9B7P?zNr!pMx{`Mca4yd7CwNvFp#H9x&=NqMiWa4{;dWbC2s~ zRhjeV>g^H}73JoDWbb%=xPQlQ#d9AIsq$HY=*xBt+6T<98{}+0yLk&a-*WeS>x)0ydmns6zTuc1ICjR4zrelkIzgZB z1Gf9%^LFOkMSJ!2x9sIhSM0g77kU3R&TbBIXP2e-)!#ttKpZy0;6cuYmuGGWgX-wZ z_*gilxL@&3s@Jsm-XfR_%KLjf@o-_IQ^bQ>DM&q}LS6sJS#S*Q-o4x2MGyay9Fyj~ zdTjJS->pK|zH#xQU4QR=`{=`u>^kEHYg=>u@>_4)s`XoK&*A56_mLNE+y2vb=)_BQ z=KLi)b>^JSoc*Nr?mN)hx6iXi)W`g< zT@V%;=6cOkNA6MN*~Dw(anaIu7tXbC@@_sJ*pP6KBV3%w;ulj-#r~XAkRNsOmK`@r$-x8AgOu3fWt(dX~K_W>AuXm7rC4bG;Gwq^GbTf23?ZQ6O% zUf{k@pMAyghGZ}w)r+T1%U1NGQZJ;o^#5$@WS@r*AU#m7dg4 zAb_)V)mR7OR*xpfrT*gTFQ?wK(g(tznsQ?i@WECSCowhX*vSy`yy8eM&w0|i^nVyf z@3{5r*V`+vyy9%t&%r@`kaOvqr9MO#Uw+wM$Hu>T`HEd(ynXF$yLj<+Tf6>Qduq)# zTeh09a*Lbm+jen&gC4HUIfK%IoSg1Gmot4G+qU6ce=g_8J6j)my!YpfgZv0_*OukH zckvP>+*xpM9(Z#==aECS4&41GS?MtDGbYj0XC|>u8XPUL=tR~6d2I2MD>tYS;xG^n z)m)F{Kx{=0*vtR)t%<*7CwA}InnW$}O13rl?>)MHHkK^gf)tOK{Nmym2B)7Dsp9%HR|%|r`~qURO8 zM%4E$A`*U8Y@^3LD$aOu@=7m=H$EKh$*T0F@u$yXl;gORoj85^w6otoHW%cJ>-@3$ zLY_Ky)Q*r#J#qAy9cMhpKG(s6hv64|!WJ&yY?Ed#vrWwXbsM+1o(%P{R~ht6Xr9^F z+Trtb=FD#QyiV?nq3*qZ@1C4*>1F*n%dT@n>LVy#M)jku!1+b_y6VaB+uz>p`e5js zoYuX#76VqCF#p|f;jVqb{02?85^?pcJZFevYQy`-UXj*=IB9=<|X<@*#Atx?9)owqea0+r53e?ZMaEzICf@dv>es+q=)^&U?}x zdwd@J9*b@6;j}95^xT4jgV#$K}Hh=a^ zch*_)Qw}-hNfLgQaTYArZ_qm=Rk8p-9(%pY;^Iv-!{xli9(q~#{n$%Mu6df0et&<%K;7qYFP|rPaM@k2X z&nXu92CP2||B#Q%9Sruq&3w3Kftz2oz{#tvOrv&IrY8JzNpKP-)pq`({DV+*V-?ne z_}WA0&lgxF%>1brspubMojBVsz3BTHH+{A>Yudslpffkn6IC1)3y9;FEf!z$Q*f0| zux@=hZ#7`7O`bu|{y7Wi0Tw~;!3>+u-ospcL~*f;^M3hK_;r>L!!KFFV}74_{>i!Y z5TiHcNa91;m$uoh*;l5Q9kFgz{9YfweL25Mu6McaU$!qcxsC;Fx&V(W9L9Tm7+1D*-=2olFy0?{%PJwe7J_4|ios@lW>w)_Z3PmSy{;nFY%U?Ljn%0l% ztJ`(!O^n(ae%5(#^uf)c?>uk5&6zdZ_3!T0XQ1Wv8fH1UeeJ20o8U{O-y^c0Ml7QH z)cw!rv+A=rj&oGQI6vMMA1bpMJ)}GIv__03o%&cr3jBqQTDe{a)$wm4onIsWwkC6- zI`g0kytt*E{Jr~6wSX=3wc-8)ng0RYvxei*-U|n+xUwA%ytnPL1wXmZ{5rwgh>i%0 zgBOGOp!@ad1g!`8(4p08+7{-#elC7^)AiJ8*RBJ(jVI{I{fy(LnurfDk@H~k1zP5G zv?i_ctXpr^z++P!C!V;l$8v6LDrb4s8$kV-i(Go z-to5GyI4-2k=CYDXV>2*ihHkxeHYJrjTrehs_m!_k5Ujl4l2M~mcY7BHUF&_9dD_J zfyX7T`}Z&qmplB(a0H4E(+{3xfAP03J!bxWrdZk9nHI`?P>+7uOz8$+46$j;v+n-) zo<2v9iI&!beYAzhU+3QD;76+Goor#}Jid4PZuI(SVWY-Pqla=cxY#4`=UX~mr?{mC zaq3;@?)!?;57;lvV(8lylgha`&hgiwr+(cQ^{$nLuPcXoeqdME~k+am#fRw*2PTQkC{BF9QqDs!GK z04``hY;q+x{}Zr*>NhQZXK_1=yHEa}{C&kX;#ZBYQ=eV~Z<*hIAFsJMoxS__NABMJ zOZNFg^S}+bg~i(pPq28igVvn0;E8K2D65CF6Ur-W+`QS{|5M9XSSI}oTrXDgOp6vi z>G)BH4Toj*cPYf`WS^)Kt?AX2?{ZcaM-_pwUefPL^)x)fT z^X)VbRHG4(uU8%pOVSi-@> zK)eIu8EA|S(ixVzoU;|*KmtB)LV6~g&fKH8W$4|ip6FqR81%)}@Ol$_yfETu^W#2m z5AIu!J>BSG5HN3-#}|z5_1(YnJE@$Xew6txe(WXa0LRZv|ITj2!S&(RO{&w#MvWOy z&*w^3u54LLre~<~l$!sF-<|yLy&wK-{CWIY^=$qF{(LEVK*S}~wq+|e+s5t3$qSve z1&i0a9B~#rQaSB&;k#(>_bU!-uT*(>O+$}-_&u&Dckkc3e{r&i zLl(|V=0c@?;w|-tFsQ(Dah3+m-9g{`M5kjmZt~{;Eab0#QjZR&_a?FzAA)$%CXiFn znOybtN#_2CKROCNBKR1QXA1W(-6tMu-KXwf+ywH$#j&pYf26EG{S8;!3g++r7sNMu z%MQPI)27W@PHwoF<53jPXxol(jJ6l2A~@ucz2mA^sbEsOQg{NB`+b z_=%lala0|;jjjKHL5_z&++*Ux()t%KnRLJIUwuBLSBjP@;dDYdzfc=FV>6s@Z#%w8 zaenT9;f4(vKAwGm=8o6%HqT@pyoR~Lp%XZC)@O8r9w&(!8_2KKR6>q~vj&kdNC3_di z+)Mv{eUSfr#|N;8buf*5xAq>?-?C1<#_0Y&Zavq)Ul#{+9qd&kKJWv`{nx*~%kkpG z5U&+3>2U&-t615_&)npAH#eU8$Z?yA263=ntC!Ifo|H`M*|V1gvi`+=ndIc3f*(}f z@c@bktN0e}=>Md9r&ox23cCCEFwi;>Z_sVN8u~kWbHUSx>Ko;_61i`W zJMm)+U3L`v3ST8QHlszhojCoXZQZubaWAW%)im~PR4QFM$=Uwq z&KFRwUR+GNfAwJ3{VR7R4vu>Y(c7s^75Gnr==WEccrMhQUVF+m?T2^o`8RCG+3PlO z=2H6NXT$B>(QzG0{vOAnxDLf}*b^O?ZSsv1n3D5G6de{08M>WUJ`R?EGZFUjgsVD!oxt;lb>;{S;cTrseB|G)M0Uvw>d@L_t~ z;r~R}N{09B1>3w6?#o?ASPLs1A8JE%yZCdZ?;PKv`h9Z$TKkQgwRAb5D#WMiZJpS@ z2lu1(@AVQ?@2J}tur54(zDwLlBdxnbFCl!i?YcNW#aR-VotSgM;-tS#P=rNx2COfT+CmQ z_(1$hy8i@XX7O72?q59zS@8eMwpJBv`llXFQg(cUq z*-KX0%`ZKkwiVcb4E(N4^43pGd)#q@iKFvLuxLjvuSf5GHVFBvA9Dcyjp9FX!ASld z59e>lU$VDb0uG*H#kv1Njw3)kJ1P859rA>U#dOIg}8R&Yc>i#8n^$Lq-4&0ds1#kc-cmF<{AbqI&M+c~vqA=9_Q2-lB1=yLKuKbrO882O<16@8va6x zG;o)$*WRY`z!6{?$Q;xCr@||j2A6@4pGkI5ee2XaP#Ea3=7F0F`S&l5gF9=$<1i2g zvImi?pU1BjUl413{A4%xegBMNeycV?z3{~qy_Ou;d-a(u|Lk17F^7y~f zf%1K;kiQiV%>&GL^|gPvI9xQPN}0HSw6Cf6#M>~EeFgQYR<1)_nc`j25bsZ9tr%0T zUcF#Tmo7tXL{;{|D$~=yp4IL*#%dqA4yTFu06cDGgGgn26S#k$|L42^t$Po+-m{6wV#we@ZVs%3CvV=oxz@2`M|%u^So%=h zA61y6%72L$vP|jH9tRJ8PdWU3>4)m%HkBJ~oRLAFvPWI7>>$-Mpw~4V?+%|)4%`o& zS^}GKFS%dIK8XBJI6kIg;soShZTlrlIqva>h)cvLYw;tfA5X2@>%qgwrp{s14$8{{7;Ol4S_1YH(x_@yOXx_U%vOJDj zb&}XpTq$*J%d=kouOJ4;&YX4q4->hc*4f!^9f&7UzJThL#np=_B z7WG^gADQ<1%79b&yv_7{;NH;nj?0Amlg+QieLKCF-$&8Mxvl$mybby5UiYtF#*wQ} z!dC*nSz5i@`Okv)|G#-MebLj7J4ZfPJMEuMpXPebs}^e#Ic)8xssFt40OF)lEG&Kz z@sOw2#s)3mhDO0*|#m)Y~?KtH)d6^-vWC)w%!LXYQG%M0ksg?6BY+UB3P%MPso$H*>wT|OhnozeIQ^@A1D z`3Ar@#0(eOzYTmzim*RGop&|pN2qg;dlBsa+w}Kgo&%^0KF`>S zTCJ#`i+ckxxZ`*$hw_721pe3-j%?*eU(nyIlcH@HF_;hct==h)_02bAVK%x|cS>ch`J5PbZw|ARRn^_U&) zAV(&A#`zsJ;c;CLJ$i&13z(0a(td}100RT)EJGcj&h>Qu1GIk`Wk2o@Q0pD@rlF?z zPB?pOfe)C{*53vChdNe-7>d}TsOd9&KFs?t{xP2cj(N&cpwnX-?Z=DK&;=WRvmf458s2c9(T~P;j~70pZaO>IzaF%MM3PIv zpP}``{{Mabn`!r%`(ar3XS6_3n;5ZxYOsIh6%Yjf2CUy}r*+UVch@S2+cCpjO=;0X zAIEha`vcDX%b?%md(@f7JbC-TuZY^t1`r>@dNu#CW}3s=f%@7y(Ef&|mP8KnI?93; z9%^di+&0taf3_brgr{@3OxuomET{|mJnCj|c+>;&gATF|K8xQerF?6s*ZGaqHTk*j_)bmYIx5Lxj{J7-Vw3e&%nnHddYD9_`CUkru~D#eoBKH+McQd z*#Bca;Cr0wouEG`z+RdU_O_J%G3@bJX6gavILy_IZI5_1%sK3d^QoIFaRgr)=GwIc z-!J;T<;0?@nV12` z7WI=+djj=sR2xy3Zj{mkK+gG$1^{YA?Eu?RI}o*@sCodsK!w+Xpic){vd|yoVO&T- zU0}QatRMTkcI>o|1Q2L-4HrIH>Z3%LNqp$<^Hbw)E0@04yO+}AmU5Kh6Z zMDgrhYW_#P%Cx`O|NdMLh>%Pt)a^ zwh^`MrZoembvAyq=f~gMb*6p)?oMfJ{P-QzGNd#Nf7IWMrYhEh>U+?5eubKapr!gl zpG^YnMSZ+!{o3jJ5CV({-?bM+@pcKd_Tl{ZueAS6U3{OIB-uTq#I6bTv8J^+u`N+g z<=@f5`#YQe+0Rfb3i}S~HJ}D4H74M*ChBOSKG&;nWCvlkX zn*jYm5p5_h; ze*5XPR-u+2wEsWf|IOI@S9ipVKkn=&w(q-tjDtU)*Z#_mpKblC_doyc&+mV(2h?`P z@i?PxitDBt)Pwvx(Bh}+0dxb)28m`$8KqUHp=0phV*gCNAg;K)Yk(YRg82yg;Xl{3 z`SW`Et2+2+-{YA0d5*+-(11F?oCK79-#gepR1JZaMFFLgrKM-|-)jF%Jz#%$-8V!I zHh_jNRS#(Azc=^)Gh1hVKBH4J^O@4Nf<47fc;1YjrxBFF1U~PA`q6m}>!Yy^`2Hb} zA=v+~tba3h{U`U@{vi_3*hl353;h9YobL0}b%=A#&l+ADjbInpJfq!(8c2GeU!q;n zOw`h!5~Y*ZiM)3RkvF%6xc?3!AOv};Io4D8df(O7{wHSr+rRU1V3>rq3{qorx-a~* z{xGduj2hP}U?1wi>B8Lr?$bI>sOJRwIPZEPFULEgdOe%SMJ5m_H-92(Xb!l~9fTjW zZ&3ec6KG|L0RB!B;!94h?j$<)1hwur0dMht`t{{I3foH8w#KJ4fIgFidvWe5DRiazxeLm6ux5% z#BmTGBLp!&Kd|0iDU?d{|MV6)H{8GrH=@YRY*_3Jm}^QX^L zJ=X$HJ{7pZdm)C8Iu(dlXNTAW#$GYMJ0tif5vw2oF@40d$$*`TfK5Oh3iNYtf|xww zfKkH&u~Op@C;#tywYIiW`LvEeU1kC2x}&4x54r-=ngXadQVV?r^(9mx4z&Sd=*XX4 zxL_e+gg6U3_!$v*uo-Xz5)ebBG&mrZF0>Wa6|jjL_*GKU(j)-V)8_y&4xpGav%HF;e6l01F>67*91s8}y6#KGz4 zfj0s8!R25JC$tITDa4@OE3+d?m3R#7N zKh3cc0UM?{lE{-q4yr1|AEP0rkDT$Jd69qCxezPo4Dp|An6v9@YAJqnV?!g%4Ijv@ zlzZeFXdfg1NA`K;TXORBIV!$~d~kD^C-<0|P<&`d-~=NNRui7f4lyx|6)lFbfO-HJ zLtF=AK?vp@Cim_?1dQel5_{%4=sA=C-p!xVvC)MXr3u97ki%|g zZ3Wy`C_BXcF=wNVr6urJVLpXeAm)8V8x|~F2$(2VzrV4kDW0kT=Ox4|A_0 zrO(3y>lR{?FmAJ8;UWs7!3+2v#LBL}Q%Sh88VL7|aY21!d!2CnTjk^*BmDmsq%9gQP_ zq46Xk@hXu7UX41G-4f#C7ETe0nLsj3AE|*D4Me zyDOO>*DGL95l1Njb-h0IHE;!iHw*kxuzKmmum-+yFi_`nS4yD1JU;$xF8Tp;nl5j_L^DHq@d+qw9Y_zO3PCd3v{ z1K=cJXX9hzNCIF;kt2#c*mJ(!vshwQ4K$ThuJU`EeDj$AWN|+yUjkS3AvL zg&4$!AG}RYxFdI!1HN0IUPrj2(#SdkJHij~Pf@_9&*)oVn_%uieBH>%q%;=dfJ>eT z{Q&ov!H0v1&0agAx7&s|0zVmfd@Aw^WZxbuN<#&C#0!_LB&>YGL_t%N$O5-WeGlZ_ z1njYfl{?Y3u%R$Zh_#o1H5c)jTVUQt{-FT0g*4#gI3Ij~^8d^`MBe2z_YOIC>yTdu zJj3-F9|?DSF5$5BBK-1@D^XmAvcm}C`S^-Ee-ZFx=Ab1MOHP4y4{~c!bHEJBqN=fr z96S_6#9*CATs>Y~Fdk`OU0u8a@KW4@kkgWztQX`X8(>~!}~{{5ysFFD<%h; zQD}!a*n#V=AoxY36@fqbun~ALSpMk?+WNR{{0| z_6KWVed2}rW;?8%+JJ$;{L7kvgP^#O;NL*ps|46DA|XYj0jIVuw~27%BH!nAke`fyVH2@*w{WVA;+BAHxXZ^H#t~umt{@8Su}bE}%_!08Uf}_=g<8 zzd%eiatshxJi|9aZV6t$bF8pErg^CAa)5J%<%c#z4QPBJ7S_nP8r>z#l-#SRdVNXD|uMnL-NYIiH~0> z(Sv%ou-*sPUf>ZRkIoW!mF9pS2b`;h9^r?2N31B8AMx?OVZ#AGiI_kE;Du29Am9mc zVYwkr$bp=x%g>+>N>kW;oIhiuqKO*lR>Yr*BT0!DDUKj&Nyy0WBz6uiL=gHkmR||* z{>Y0%eWL{n7gOb5#tax=I(l;8Fz87<`9SWLc9N{J4!~9KCA&<`i50}vr@3%;lr6}Q zLH@Ihwh_huqPSmZ17Lptk>h|E-`_Eg(_F7jXR8opmy{V?=d}Y9zMT8%x z_zkGti2Pm!6-~hNIf4EjKS6FE@|uz7io8bJc?$?LJMfv9f!6@#501PAe6H6dt+a() zxnBWiV?*Ha*;4$K86MZ3efudchq#n9eLXAhSH#mAEY ze7G3Q0hrfzb5R?GGeg|r&+Rb7yTbnT8`lKv5CpCfZ+<5cy!nFKKj9jfQBXo2!nsog z<~GFEUjdFK@=S3JFx(9qK~Vpw`-M7qIQL`ukyo?;`aD0(_e)j)o)R#WNwHGuJDO>u{?|6tu4z~4h{6(RT=JB+QMzqeE6N1Qx`oqvRUn(20!853B3 z9M{MfLd@_cuwm1!N^1Y11#A4gTlB&*$@Xu;ef%88Q#}FjA>{CYHqq+NyWMhOsz;;_W(5qp^l>*^zY-a zpS%Hk$aCk;P#jNpz?>QH+C_1DBw-)31;#PX|G&~MAd6SBQJkJNus0TkHsXPCVh#I# zMQBSk*yExNGdy>Bml37^^F&W;roH*n`sLi(=!}KfD85`>wq6S!IQ@|VIUI#fSvany0!Z8p19d#%0EVdE)p(w23iu*i>;v?W( zP<1`skFXu4v53=Hb8G`#ACPy2<;Ss%So3WuFM(^KOpMK^=YK4JFZlc&KxYH_rWC*8 z%4KpKFy#lp-;Wx0A~4tE`ii`2>fuVe5;H|J%;*+GS19Fh>xGf(IRdhd4$LpnC|~rcDzKO z{$&)DVQ$`sMgQ&f5YAdUTH2JR>FJYkuot~Rf`LDG9QXl}3e$#j~S@ zu?d{pEGeH0`VbK-$_nkV7S6t`U?U5h9hU<>7I`2NQ18ftKz$4`IGb?Es*vqPEr4YM z{5zBp$1H_|rN#la!F1okKC~IeFXCR2>#!}k64pRfnA7(ER(5EfcvBjbEz4e z3*%ugaRT;q$AGI51!n_E@OcP9-6FpgISq)(Mtzq+KVQIlYXZ-Y;dd?r%MY9OTt~KK)lp-XDl3!|`ww1-Tg5x_8n(hUQ+~8zOG*`R71UvG z;P4OS#}A*{Iv_@L5YA3Y6b?BIxE9FIh=qN1IP@o8*az{!r2sbQzjmG!a?Zc!Y~Kz zhW!%y>CjH(k)TG{G@c%?=eDQzpn zH#_XJgZ`lp`#TLvCk@wrHkeNk&y6^4#4%HN_7#X{hqV~mf{A$*<)=a|GsLiCo$m(w z(Z7ToDCGF>0RA50*Kxg?#;*U)Tl}s3P-Y6V4z?jjV;x{t@!FE{n!;-CgT2jPy)J`) z<)FtjKKme?B~f2d0`^_&@SFu_-_>x<;L?$IF@wiOoiX$gVmXZr4WJL|Q<`Kr&XMcj z4(B4|i76k62kdn>g*l$VUe939f5V+anXwIK`VcSFKSyR0*_Qr_!kO7Q{&o2;flejj z>b(I&i`ZgsxO`wOwuZfcsOWak2;>2cK)_UkuYA=SI75OB$R*PNzu^Jcdt;2r+RB=k z!x?Ee?4xy!jES<|F0vK&okEa5Y{!!Zz{5fQ+R`4P065th>@@PmaQxz!MVv6^az?B$ z-UUHlX|>c&vgKq7@Kbfj-<3ZJ{19GH4(vl{1I7ao3yppgY!Ac>Bc7iJ)+@%t?nSZJ_FvQ5$X?~uLNa8oZKJFIfI}2tGjdq;0)pS z5Oa#{fp)0Y3_%W3$jMvUOXWlsr!coa?11;{BkvMf(0)L!$={WKW?Z*^pCIvH#~@eU zG`1CSuK#X1|Em1>{WNYA?f)G|jr~fg2JnH9^IRSkJe$Gpx zb3TP^141)who?6=0r3gUzwzJw8UxMDT)@Fw0uCPM zewn6H-mhh^1-o0a{mFc4SY31;1}O4Do)LfxVOQaewQz?t6~&I!)2M-4q5N{XT1ym;|~$|Z3r=@J!J zz_^ILy*>EH&XLB(#{W`Z`T&?AFW3u5hJ}-dfEg%%UPkgDb{*vB59f0^vJK*mh@Cn|xO`Iqx6bi>}%*ZUADguFF~t-+iT z--d=sJ)HZC0FQDzy@0~g#GO1xX&<2P3h@uC!KWe&{#(?6K)eQCi2vaOJb@JWz#^lf zC>$1!`M-OiPRDJCUAM!W`t@r!%n3cD@Np^0dGvzH%kdzmm|RG@O2VV#p+8s?#KNEk z|2)8uAWs>6P+K96h2S!93;;|3|5SNvs@GF=f z7qJG2TS5J72RN@_j;TLlgMAJiB3A(iQu_26)!#DiWr6P>bgfe}i5Z;FQL7%Gjd%{! zXLkp^4&)VF}`Zq~xtSrq(N8%|~r4l7S0D5D5idKoI7gWB3y7aRBmDGlSO z=xBmiHhi_f-PXnyFn6~pj6+VL%CAu;h+sk0U8=Gp=N2Qe7Ypf`68^mQ(tJwu({ z(Qm&2`us{})J9>V)*#eBUjGnuuCD|B!u~Mf-=RvjKwMA&V&jzFJz_2Z|FYk~5%QDt zlgzwAIKR75I)^^t@OHr9Lpcy{fOYcW<43UbJcW@s z2O1d|->|iFg7}0BXaQ+KTkoO#i406EgcmgIrQv*`4|sNcTX#wWOal5mVhIrUhHW7M z?T(u7Gn&7sd5keqjPI_$`<`$eP9pr;=42C;19<@NV7z;SZbuksSH=Ne1ohkvjLd** z?F72To2l3k#-$f5T}Bu=Kxb?tA7O{*tOj4t4v5>ygU=Q(DR__L4z;p406T(Ovlu_0 zj{E-{H-|Vn=qz&|ze)Z7x9@5|C(s#i6`&IXI0cN4D=2G1E-w>GI}c+c^B}IUhygSK zm|4ggnD69Zo(q9Jkk5&nAU@Vc_(2N-bxwbd z7js>I0Xb46$XmcjIsgtd9QqY%czS?8ML|Uyv`KU+&9WWf6UUhRN|rUC)eV0B&61#Z zlTI>=>%j-_PsM?a&G%5cwCdXWL|O&34lsU-{(bPlVVnrHv@lLb#Y!=5jq&T7l~k-6 z?Wfk2V@Jt_g!7bsAZll-fgc$)qou*OjJYn>13riWe3n|f9ZAZwW|CR<6|h@-DgK7# zUOOtLh+42xs+!=>p4Puay`z~jP%#E52QO%PV*Hu=&Krv7ayuoJ_<~OrwTCVPPAC9; z8mbTjM&BsLl=1nPV__K+==4G#GzC5G0*6>hY$e_(8Y z($sD?_bO)K%n9eG6lC2MLWiMPlPlkiFm&Mct%u=m)6trVhSL)XGC#1P#qx zz(D|h6=Hgh?nlYp+!rJ)_AKa2n^3V|)P%%%7~*GSbPOp?Kg!<>e%qP2-PRv%fn~sW zk-*&=z^}-WYiSQi8RWRohWNwv1?%M$!Km|qSx%TTWwpU()GfF&@;nt{*E0sM28 z;6FqB!Y+uN8^L!NbHx~(Eaa_0zx;IU?f3X0)&mvygy&PbIvF(td1VDpr*Y1x-*GrF zfYOr1d^8xN;)TD5x_PLTwv++%Z(x2|3t9=N^@7@qa^P>5S5}4bFGcw*Q3FvPa1F8$ zyTKS4rS$~O5D zy%_XGWmwyjIGE#ZC)kNPQ5ZvXhV_dP#v$ruU=9$R z^AV4VYaxXDqg zS_FL7SPqPL2!Zc+6WEWjj-Q{8Wys8W2zj)uDQy?j)!PSiy*>EaQ7Z|3(Mx~Cyig+s zV*#iuhQ3_`9ne34c~IKY5iomA;Mbhi{lRg7F(ZtRqQ(sm+}Xh2ygu_i6|1Ou|GWM8 z{375Fpnn#%*i<0Cum##3{o+ipzRvjc(Vx!@pSQ!BL;1lW{$LJ1TdX7H{hmYue5~lZ z$Nq;t@aZ_uw9k7JJf8#gMIpYWqM`l2*rHvnJdomWKU=tas` z{Kw~G9e}HXlnjm&=ay;h2`Tt{f9-eqbDs?QjL>(CzB=TWD^?FtS_2ff9{i<}F#c2_ z*7Rr3$1>mxia|>HzZ1Jp-~R3AV|lSI(BFpsmYq-z^cO0;0e>NI+?8`a5Ou(8&CEa4 z1OMV5^b1rCjuN*f^g;dmb%EuWsS8~whc@{8lx`M7tVHi`?fvJ2)URa`Mc~!S90(*bR`x{S#*R3F26}i@47qhDnUugew!NeCzcu&b zC*VZk-#>lkEJ?q2pH#p(svYpt|Lm;yvn_vc2mHVAk<)wDoD~-jCUl$9CR9HeNzBjB z&2R9j|N0BdCrv%A*}u&Fg<;{kZ47!>=kb4}-*>IQcjBY9$n!4O!O1?U=Pu{Z8tPon^QLE~4U-)jQWiaZxlWXJ zRm752+thfaN7nAhnonx3gtYZ;;Lw|VNOPd8ebi^g4w^!SN>$0$Ek}kGlrHVQM0ZK` zyJkP(5?ul~pTB!4&3dxnB)itO4Lf<%llEQMmcFWgPUNzE`7!|uj)=YAQ8@3ue3I_r z^QFS8H@++h%@?TK{9wVi2$|!u4mR7iFZgDBCeK|s+JL=d+@3b+g6X!>C(oJG7g%pu z?#lXLl6yl`WyMpW?57F*oVL5KpPnSkxXXVX7hG2#b?565zS9Ar;=V7##Jip)@L$a_ zrFD4~p-}rd?8--)$BuUiUB<`Pzx2+_EJ<*Y$`4N z`S7eWG~dpTNAtKe*QJb~`O2O2F^hz|r=C50WwZN)2h$1TBZE%=_(hEe?(iEJti=G=yg)vi-1o@ta4~C>{OTXPWtX|@j_6gFZK1O_ffr4 z$GL+tWAfy=);D)%6|5zW;XjFp=o%uZj}^)mhu zy#|X1kGo&2p0L-^cU~tnqPR^m_i?xv*p#uFYBmoh$&}RYcisA_z*uRZ)kU#6qpi_4 zbu$-NqVF;PdZk+NB-Mk7k9R^Zb%;OUC$8Dh_Ojd+B`mfl6G7 zMGJ45O;xUp3!BdOapNSN`sC!r2WcbZ875b}I24rK6SzNX;^>v8rp5J*XV0;xB3*&WPMb_v@MEby4$Jt-{NW_OBfG_xM;jS$j6lsdh@}=(P%O&Ca@zXDk&% zSKse5mux@E8L(wVT6T@PO{&~l$!4jzxbcJ+C)?tb%-%FPo{aR|de|n^H)Q>d&z)I? za73P{Z)463=}lV%hw&$lqg_aIZ4CZNMljcVrCmQD9#!E>G8SkpLUqs`^Eo6$^*Z77uUMQUCMz{74s>(9&$_sk?U4vi|HBh@nZzK8 zL2=t6#x--d2hKYyd@RZ`)p;aOzvxE7h3~<$->DQHLTalbD*=%XJcWD`sEUj^;;X_ph*#q>g6reaQQT58G|#KgJo;b`fB+N42g zJKOhdg*x}_qTkhhQ}t-)ba0*jZRtAeBVMc(?)A1Lc(?tn{ROw_vLbIJFD2LdXZc;f z;*c5pmMN6GS++0hLH917k(#7T+QZp~;?L&lJ8!Y;Zhm0JcH?89*ZckQQM7OFIi7b; zG3t*M7+2!rYR>6?aeDAXT>y8=r1V_gyER)fKPz*-u)1SinRhU6<8X-IZR`3ihn?s8 z#;3Gg>&jMdIz)4Avfd%{_{W2DW5=Qn9Iv|mc3AM-1Nr#LpxX@-W!ueG(KpHGNSBF} zP8n%%{x6N`GI=G3v3-PFLEXz)68o%X}6?E*q-MnKDSz|NASJzI~vYf7y z_EF1s8qaMre!TD--=3ZJ`y8F*Vwcyv+As4#xlrszHJx|KcoMA-|@jLpM*&6L$rk(?sO%-9x?eiTvh0p+R`x}V|Geu^%o8|iS{s&Mn-#)XRqvb<#Z={e&M>FnfTgkQ_6+L*e$I4 zs{*qH&J5~wtbf{)&v-YH?F)0M=Y8(%l38!+1pGYnPn%b%58vLt$941N2-=;ACidqR z-)1SeGCr|ChN-GFB9n!_Y3?NfRTlL*T(!4bOMht(3gzR8pcVI6`7HQLSMkk**)Vj2 z_LT2e+eO2BF5Bo%@B)whiE-Bfq=fJXqQJ$H8 zuc^0t?Qm7DT_*cD&C$*D+V`exyVRa1y&ccEu)r}m(06^Ot&r4G!<4CY{Nwgrw-zYh zHQ!V{EG&?7&R|1VWJaETTko@5zL)mvJ9VtvJo9^gOxv zU6pOMw%2VDN4A*nnWLrs79Lwt58B<}85VpvD3p?YakJ6C30yUs?akfnI3Qt}muv`e<981b;ZlYb;CGs5R0r zo5~$&B2jgBSscgOwQUiJ`2$XQf}G=Wt6fz6K81hT%gLtXBJ;rmCfSY4Ym!AyyI-Gp z>bN`oQSaXM%pt6+qqs-gHw(P%E#LU1=~ZR!2Lt#1`x`1`TMlkoZ%{FM!#>rv=Z+Bv zW0msWWv)!JQ8I<=9{Hw z8->5s@gy`Ls;__jI)_ykVmZFd(Wxuwe6fD@ig=lO#CLCk`4?Elz$ zWrds3;p3%eCYA15o_M^j=puh%LDH}JN9r`8%gzlgo;$j7!fnZ+dG8h%#fzL?5xhF{ z)4ZVT^Q!}|dYksOX75bee@p_LeSiBpGWSEzt53Sebh$H^)!AvE&b9iG%%3aNz;ZKT zf56$6X#NueF*c_rPD~61(VSePmAav9ae;6zX$wwpB0tgPLG&tJ}i-52gZH%WRTYY6|#-vj&A`JT`PnI(4DIZMk;C zon=+J8bhbf+u3BLeb~V_{v>v;-pTac62whXr||i6w_sI?^e(;A=R*g~P92+{m_yLSbcgj9-pJ@QEKDqpQJ$0j;oE<#ed*5c%Gz|o}EoQ+%G`e5;9 z^5T-BO_kHy!G{~SYLmvYp&Z`MGv%w!R;xaH|H0z&lvnA{_C2N#J71)&lW8cu+?f@y zc5rv{7H#r|VW{c;y^ziEBComazb|eX56Cz^=Eb2PAb;2WX?bLYO%%gzlTk6xhfODQ zLJIbz93P{VxO$Uq!vXPA7b+rC9=2RsAv*N!lIT>ZfN1}BGf~?QA0O_0EU5NfrNfKW zyI0yWqi6P#v=L_;aV~emS^@iynR^pnx2@h^D879&W4wToGoQ50LXo)1i_)&o}zl!o(lhVi~89Ln|Ytrk_`zcYbgE_3^SA z>8IRb=QfxsJaZF1s-dtsaYOwv|3h&{$7ny?cF?Vm&HQX=-136)*|}m5dIn=1J2AmN z)+3&wnS%F>MrNG}FuUd;(){R-e2WI@vfEcUKFV`(KJOuDm8$clg>`acjdVornpf$v zLy0^QN0VDP2Ale=&!^QT`^aq5@e5z`(7J)Q+%ZPXcaO|RISu#tQ=CH7wEuPuy}D+o3aJKL2E? z+SmOutRhAve(XxRfNS#pYf@{gj4HoB7roYNks#!;NWeJneMaV|{FS;!ik)Q7v9ar) zg|2o*53jO5D|Oo-;JDSm&g!wyut&dSN$*$j*~7~7peJjs-Re~;fhNj*l5qza3Uqrm zG-SxL!QobgZ6v43^}u7VFH*L>6WpoZe04$T2AbP==@#@Y9T-?;STodx{I>Hne2;Ac5b8bJ9gMA=CbsH#;3R6nxDBG-!vZoYjr@UU0cXU z#gC~gS9{gIvi>M?SIe5|-~yiSA^thcV>P85z1OZf`8{&F0-FQteDif3_3ut=9l82o zpL0NU!~@s92lBJOu?2h&c$7P0nS9Dn?VXR*!e7n>*2n0GD0$4!m0n<<%N;mn6;}3W z_jnmN5Hc#&xd)!@J~Z2VJ_$KF>HhgWof2U%XIW8fG=E~*j$657-MvpA>{RgE^iH@w zzR}4f^yK8L59>_Er_9;EO83{Epy_1u9qi1UT(0x6qs>(1-N?FyN6#)g=qa+!hRsi} z-Ot1D?dRD;^m_R{w2y}j`0Y6-ZHpT-%KQ)PI-IKfo-J}G_-dwXO~@l3$?b2P6NA}g zdk$PVu;D^=baI>2uZJ?0g~wzhN`2b#c>5f4@iX;`vft>fwr~vPuo
*tH}eL=_d z@Rzy}YvwDLMwZ2+gK37lFFLr9=$qD-d9nvFX%sHKRz)5mR z+CbSXAhmmUI^*LQx4e_)m+PG`?fbIFbgV|aF#nm1J`uCST>JR*%Tk9M(jGmW-SIM@ z>{i>{l!e20m)2~|G+(UNKS!rDaoav4tqa%anQ!eRn-uBvG)G^rVG`3HpJ$P*zqfF~ znaewp0%EeHJD;>xInTeDbyCW|AV4qdjwG*)WQu6IG26hoj^S{&rCQy#s^6(_#zBt|X6ouINQq7ks19X}{85z;!NXXV+`p#3@UuKo<&k)UbMjC_ujqEZ#Js&rmLKP!zp+-q;l|CYdO{ZupI+RV z3A3o(Lf8ES)`C(i*Vo7WTq_^wxwTgCrH>>u_UdkI_ z$)^~_eXWQ6*x~b+B4QV{hsXtdxFg8nK3biAnjGq9@N9Z8KLSU$-GjdT#T%c^t);tl zfN;b;TfMq2bZI*cOiLOGc19xy#D~NCWn*>|!}R5M)Gx8=d{eSa^L{awxVS^QcV%IA z=SSs?jUiHb#~8*oH`SQr+NC|DUw&&yI`9&|*rUcjE)zd>Pw{(qY{2q0 zV_$b0e42grrPb@>lZT@p7zFT)GmSV5@4rs_kN+hX|=IztYS@9 zt<=>`OL)F@s#Pr;DZKM+_eh~~=ae|-D2wZvV3C*|g-d9ji@&RDh_L$j_Ue?NZRyub zp;uyrzwCcn>YII(#N?om&6%?(&!tIp*v+-LgS7 z0p?1+$u?Yv*6vYDN*al==Ag5mEmYXEvfYn!H2m?zobTFwqg(%Rn?pwz6*?zsOV=qe zcdHMaiMgAcVyZ4M)s(l<4OX5S;;T9(!CjT_d;NCR`4tmcrEMSIwxtY=at?`|t`c%J z>$Q1Po-puXew(`4yXrQd{N!6z=kpy7oz=bQ6*6c*232ZHRu7A(jbwbW)bQ>(S$V$H zJ^s-^*`QuW-uv=%A!4oGULAR-BodGKRq#}`)+aZVpDTsG$CD^>tIBj>)NIK6wr@kS zsB?eDEh*=r44#YS$+O+d+P2qhXYj>seC0fRrv6kFiCNM@YreBj zZu#I2{S@I1Rr9nyR<2BNeRa^ez%W#jzq9sgf8)>xqJ$!z~LXKmFp-LH?@($e)SKFXh9+arI}IAHYkh1$>I zvmb6zdq4YV=?Uk#ZZ${F(G+|2vb~IWu;x_EYEScQI=!m}abB;8=uept!?`Oww&<@0fdEd1cAbAKjY-o!{`b;_Nc+Dav z8B*ygE~DGLJy~LxXM2|M3fl?Mmg8)*$AccXvRn+#BbASAs*c7tuk2B3xi@JMZXMsx zKj2GWe$h|F`l5ce`O%!UX1?4*dMTr;l%8%VJy1MpH^h2&8RyeOkNTC?Z1As&9Q?@p z?2%m92wTfTdWEU`oAZT=J{5HBPwx`$i5V407)$PNJMhMgI2ZO!iPU9rn`fwJ3r={S zx27%n5X02V)>KjBG+Mu;@l={0gx44^&JL}2zIyRVvqo%M$b%1VEUmOA>jp1MexZ}| zjo(-+(@pg9Z%KP;JWpsXv$w6~7oYV^uj%`eJ!=gLS4dRms6D-Be!0vXeA1>h;eKn( z7jd7tVY#A>$?eSXM!8Uhn}+_E)0((On(e=t27F!JdZ3x5 zS;R8oh_BxTf#f4^i{^3G_n+gL-RkmowaO`Jt<-r;9Nc5utAtPJuq=tU6hGW+xkt4~ zv??t9Tv(hBU3K2CZu1WM(`G+YWq!`IXah$ye@9!y%L&iNhgMxKO?;Wnl3$oqsqRP5 z_t~R~E9i-s^6r4^aLmwqAC#ood?T%!gr%!W7LLwW@K4Y#b>w;GbG_9*Xmymbod5UK z6NOc|{r;`aikst}b0%`-pMBLof!=JK6zA^ z@q6T@I|lx#2^{|6DctPryOR`y?rs)aT$4Ab`_lhXoX*&xL2bE&k}GFbmu(+gJLbJ>OFft^^l&0FMf4INnLN+fI(&7d%kST7=_qh!Vw3-l z0@t(j9+VS?#gQGjuuIi<8EKv;9Q+9xog7U_PAJDH{JIK}-62!tRi%QVxz% zzH+nCx(#OLYl95ZZC<%0E0!+z@*P#WJn=lgD$XV(-&QHZrpj$~kVLVJH1;Eg?J>&re1MKHvxqSlq8xsHhY5LG}9TAKrxfEJs*uiv>;S>6R<2d*!5ZKG!xKmw(k1-YcY{cdD2BR;rm)S-J%L@UdLfdv>oLCb~3lLmABEqopg`J%d&*xF0GMq**B+wCunDos{m9X0tbJflD1_#@v!k z78Ppt2+5da{Yp4b>*ZJkyP4~=t(h=iT=)Vu+;U$t4C3~%m2hqU-n;gtY;E&GAHQ9L zbW#CAzg#O4|8|$IrdWE`mwcDun=0&C#{I7a5)PUOzM_}zPA-=xwOXCev!CU%wf=G; zk7jMw`0Uz%Jx{z$uS5Lsq|bc?RY}Lt&xdZ;Omg>b2r_d%I(usN9;a{BQ;e&evOJ0p z6^(bg_xZC8iEcV=ZNWt#`jdJ0?FES2uJS20Af z6?_*^Z?ApZ=YKi*b3sD#Cl(W75f|2-ai1o;v;BQT^JpxjSccCwKk5iyRL?ft&+svq z$uNH?^3vB2gEggj0b!3ufd)TtND1R%{WOBjbt6+R13sn(i>9XDt0>&% z-_cUsnPcU*nL-FSQD>bClO!Y|i1*n}3e^nHl+mF-#^7vQS7Z8RmPS!lGEe8Svbr}py2_w}kWg0Y<9^n`D_jsSBc;_Z42Ac)I3Mu6~5o-0=k*Pw7{l z-Z}hOnGEIM+=V~@G?)S&ZuzQKZXLeW8=hFUjz*NQZ1jpMOlGvmRKx9_ghW-u`< zsWD(0^jy-*{7L$2*m>)ZSu3Q~`c|wQnP-qPwoJU~N&e@6OPS3|^9P^Mequ?k{i_U*GGhx$knrP zOb&jRd@^*OtNw7`T}H#a0n4IBnJ(ojvsarvGB;Y;H304)58myumDWb|Iwc%I-mck`SC?z( z7ush|aR@J@7>~EZtr2oM3&Z@{u&56Ty!n$#l znrn9NS>HC>MPtjR0=X1r8~4Z%Fk0_5S2B1xFeSfl~_lvLL1q6p540;_+V^}a;K(ZXU;E5M}j{zzC98X&Ut3R z?87`UEA0eXyB?pvdTt=lj_yoTV8`M!uV)?RS-kd4S)g6S=^p>_=TmG9i_&;!&Dz=h z8~DhV;ps@Do66dtxjW{~ou?8Q^U}xpQb>dB5(e$`Bx$XsT~7v<^DPJq9W%T-Z(G>9 z*W#fJOXZi8YbHwv81Ty|_jpbXUbv85U*FYz%_L*CFk4|yk8Ab?@7@;`=S2n^PH^s8 za3Ujvb9daeZ*Cb|&NZkf+>}l`Xb{(PCDF#ZFQAuQWr%2=J}1&fF7m1b7oNV>Vm)P| z5?7hSz;i(=J@I5e+qlvsyN7~++^rod47nqGHr(1LukyEq)a++gWf+Y;u60tzmvPAD z>=J`xdybxMFc?^}fcb7y?%B4Rnh)nMwc$26)8Tk>{ylyM1G+i=4HfRyH&!cnN0kbn zoHsYWTxCj_-TKl^VT%$Ujw_QJd|^?`4WoXuZ{EdT z#qQM`jvY?jeyxlleYJj>7XOlODHV3CkGbUti5Fcgf=Vl_ck_8iS&h!K!hZbnC7?Di4e$dny?7LVWdGdJpqI8_Y?%_<(yE z&wgD_SI&6$t4ln7iIlZ}x%xgWebK_cxp}jri}=`So@EzBk>Z2&qmLdgFKOI$qK50} zWdQ}rFukxb20Mlhn|VC1MICj;Qog#?)qKgjS?R5NcJOwRu*H|cmqVK_>a`Sx3(+=f ztqbttO*7^QThE}*b56Tx`^U?R*cIG0>aQofixlnF6%$-0=6u`DOur>>`F2bH@6J8r zFE?zuVPSH-xiDJjra*v~m06krgClpH_Wc{}GOyC%w`n!%Jrmxgh<3BMn^m{wseH=2 z{lweQEQ6IM;%REH6@T%E!~MTlEq-?K*EoUj6z>b$wLPwtCbet43ch?}c7B-_H@PRSH-=OOdD9LqeYUQ2U5f`(+E=EqbcSYbfg4Qb$6`LY zX}n2Kcy>kf1+6QqN1KG*Q*X{^fwvPv_H4AcNF$%#B<(>P!FG46g+_55&A`$0Uz;`9 zrlvmUY25dZt$AtKsH7hk!n2p9PnmhaFC2?y-vqqr@sqacIB?SDidZ+TtC>f0o?V%@ z{`tXF;WiupQRjs5|HaW&#x?c6eUTraQYs)QQX+!VCA|>>A_5}aEg~h|j1WO;gmi;~ z(v84i^yrj^4XM$i2g_&w=gnT6opYV-bFOpU_x+9QwlRwkN*36aeYTxRXAZ|`V2oew z>xQ4=v$ayrhh;QOOEspa#TZ#xLKITGVd{->I$QEPuz>0CGrqjDN?Bx)E>-OY)CAp& zh;8L)Q`OX%mnzIr<}LDiFOb$R1Dupi7W*ziK*c|mgv6Z{Gb6P$$4T-PIdNiwthES% zdR4eTn|NndvtBy}GkE&`eNoSy_rIt29r&KTQm^4G|MWc^N&KOL^QR`1y#}z=*5c^@ z66-DtF^))HRfR6}(W+FkO|S2}1A&{q#-|Yw6tK1Ko6B(&k(4Gjth=j0;=c_K zwIXTE+tbf}{K5k#arEu?=a>er3-ke@R)bv;4p+vziT@)mxvQ?UvU7Jka0;gdpq!H5OkFCYwuI zuqs!XN&*XeS7pg-!~@x6D|xxq4(uV|c=Pe|Ffm4Y5wzc7Tk=#Jh*TTzti78ba9$9d$#dGa1%#GeQ%h=0_Snm~5%UX6@)K^)s^yZZ;s zTWIKVObrp;T5wjHxam%mLXlA}6GbP;21IWJjRw=dE)uKdV?}AdF;!Iq!~5+EHB$Z9 z$|m~budbvzFg_#csFR6|$!lN;4N|N4H;U>Jw(2r0@{ky(uqKO<77yWu*YIg(0d782 z?5Jh`oUP5wFY5>Ix&qqv(M1xV$9}_YZ7J@kmO?Di*Dg$&X!o5gUU0Y4KFhHDSZMjpZK0ne0r1$b|1+WB0Lp#+c-JP&c+GmnaG*vlaZ9PFBhP z`7&uQvjM2eW?t>k=q8s*V=WL?y(iHj^s>wIY57NuV}`|P7=ba~P|y?t^9Kf=Yrn6U zTVD5~XZyPRI(&j?b^=c%Zi{vakY{RsL1Y|X7o!e=dVd>2u;`(!4Ah6$ul+}wwRCme zr&cu?f@8}at)16)XRw+_Q?>knil0=eqaZajr7=v<=|G!EyW{3JO2Kf zYJXcpxi@Pj2q+8m!?QmK7A_}Ri98e;AwyHKoyGhTJ_t(+zs+!&w6HMmx@`D!c&QL4 ztSv2QlKG)E)*qHszD)n+{ZYf@55|N0C+Um%o z$=v8TMq6Qve{ozstNx>$5q^j1VA;52;Ms7+nRn=j5M!*SZ>(9fX`}Rgec*tlus^sJ zC~v+nS8x?y&%M$Y`3^?B^_1MOzDu`+>u|zF=a27U+U77n`u)R&k-4hNLvv*@aZoA# zU$A04d!7}e_SZM2&1ztP`n;z5(ln2#$4{e-%fpMC3cO~Mh*oubFw=YQyL1Yb{`bYD$r)|(Zj~hnKUos~i%<0HI8m7G6Su4XyOjQQ{Ds^% zOfQ|h$GYX$?Xmf#W+vI=uJE#5*@NJ^!p0%PxA7eb<~#3p&&Yl5On8>(E0YiOE43nX^QDG%-~HZ5+MYE#k!RFDa0QOZj8o0xsC!Tp-{ zp?n4Q`VR>?E5Tmc-v(K)teVO@0ROSZR?8jQI4XoVcYAo{Zo7uY3XH^-1BS<=?BMEV zU7!Ww$U|yLr&Cc2WIlaN&+ylKXheZ#C&84Ph_6u##cFYbh+2a{;@#7~daYc^f^z3O zCw7ya;0}dJnzIiHkK9i@K)Q(|Oh(I2@a>jgpIV$>1$_qWWIJDq{`j$gqE_N%mp#v| zqG6=aE8R?*0L%KxD2NS79vqy9Kse+V z9GQJvtIZB1bg19k%LpjzZsTLxdZpI(DtrhVE2bhHEe<0L`jq3$)N|DrNvXW}YtW?t zS8MARdq)P(&6wyA;qPL+SBMsryAllg(sfQWcrr>(sJ4$ z*|CwH2N})>480Kt8C3 zS|UN8t-^VJXl8H>6)MSa^(IK|;i3tSn?P^SF}vq6jN{9Shq~MAEw{BUFK;$`VbsNb z&B@-Nnpw@rtXuqyyuc^j*`b=)%eDAIA#yCuOD*T8PhA{>S*2@_MNT;&SI49c+oX%? zE)evc_iKHKMT}4 zL}I&dC>3~~ziagU8p`+P)%TfTYJ(zK7e5uHyA?Xz82~a)pOL3_2&b#yGr?Xo3zh_q zQ`rxH$B&NRJHR=21X5{0LuI1ArqQgO>6UnYWb+)#6b*+OF_JP(@b-uOD4^UG`1)>8 zXxk{%TTQokBX8T}S6q2BtKd?CSC7=HcUX~)3O1yuww9^UJ(oKxOGZhTQRa4<%WeIt zwy9=|1?0W9q^S%egPL5FL``f7Uu^k{VFs(>gstI@fdSAlN6#B=Ci(M`-TF-QL5JH1M@DG0jenWp*a@4~$w3N>}1^l&g+`-lii z$K;;`IJRNX^VQQ?SI~ovf;HeAw0j_|R10bi;eQc$`4yY%Rlu|J(DWqUeXv5cZNsJs%|U6pH@ zyo*C2fEg$Fc2sbesWryiFWG?_r=tybT&CNB8l&uvBCD)+pyh$c2W0_z_f>UY3=ExW z5@RkV1Y34+FcU|tsP%0N;ZV)_$X2ps4jC5lXBk!aZZD61|D?1np%im6g}~gR;6`wG zgt)F0A~>wOgLCnfn&DXd1+0yKwbcX>pgAVTNKYZJ)>R5l$F)koUvKU&+mKsZ>2HYfy(s#|TCVrhQcP-m+aVrY_PFJhC+FWrZkoBg*A90)id zBTpi~fvzwLisdwt(RVwXuO(&RnRx-A(_?&V7&7Z*DQ#e0ot1L|sQtdE#6>QJfE46K z)t5Nft^?Y}J@o+0k6DmFygq{JL0A6TT-Br9xiQPqn?r`F&xl;z2MRHZ|G^P~`%1p- zZ`{#mAig)(AIq-S^mS)Tvm)GFm#ev35QKY?P^g)uBJ618nkF?o;s(yDzE35QZH9%D zYMszUmXN4$q&#HsHXaXn;DTjY7J)raK}`$55>tM8w>^leRv{SFcbEGEPCrD8akT z$;vc#WY#ackl9v!#RF#JiOh>Ws}pWaNhE7^fsfNqTG6xrMFyHv978}*wP!k)S0TVm z8vUBi<>t@@WM3{ld;^k-dP{6H(4K)vFqM-Vecz&hhQFLl=nk@8`D3AkHHxGp+H3@d zihM52$s=RBF+sLsXZ~mF0T_WkwErD~g+?5mdG9sCU37J#EnRv zA|l*M)DAiQR(LeQ{A@FHyJm+^_h0Dt^pw}{*0;84kWznXDW2-bUzy;yR|HJPLe+;XU-JAl(#JTNDk{1YDRVVu%9yt86 z>_}Ded4F&cTSvVQ>Of84mC}1hWV8^|mim%SkqgY9X7?045h3aJo-l^JffSHSGphd-n=?Jl0u=~cU7^zKJooyo1j;|jnUfh@>!W@fg0@ z-d+)THN(6?{u3oLGGBkAn*o;<-F5~uK>fI8nQf;%~t=^0eFq#)ul zBp$s+B&o0ekSY9s2l%l($96;j91(=Kv#+B(t7dk-$3v5|Wk zgQRZana{A4qtgvdmDJQ#!J(EN}VPQ%}ylC=AfkeJ80&9@APt6 z*0B0qDflZ0dZH#cff#_HnnE~EEo~Dcg4g50((P-WT2@F2TH(!NKHW6Nt$+tAciPTX z=y!4IE^q&Tcq{{{AcM!^MucVtbKEih&`)W=H|Ru;ibl@*U0g?ooQ97qvaMf zo_3Ry>)*R1N!a^lDAnqJmjDmndxWEm=`6zfi}FWinte$T+W6yM7zxMsAfmt^}1=R`LUlce-WS1{HAI|wbW{3!BCe9J)8KZ zVw2j>H)gKa95hXzLOx-!#&Oy?zF`R(EZ8ViL^U$XA@dSOKKSayfz zhY7%d{SD-c$SP9W5(_~kOgG)`v%8V%QII}MTo{*1@V<&cR6&r*Z3o?1v-!QVasWb^ zauV4G|HP^PyFNq0wVa7XL&J(PO|VjxD_YT|QhEkR1RZ<%Wm__vd9*&Vj|nMCWSdV_ z=TJ~%57=ahU>=6zfc>YGgk}!8A zz9uH%!_+zO-xpUR`sWhBK>HDp`1|*ryriL&;n~3l(#i%iehxhc7r!#{$u?wm)}4LH zO@a5QUax}z97r>}#)w2RnI9f@DZ=`{tbwJR#7k~)@UTD1eLwHGaz>&pGftqQQT~MD zBdrzLX!{y)+?awiV!oDEdnEZpNw?*wMhOcDz81M$Tb(4k2-r?DH%O@2kVp`^T=%?y zbPq6gA78=xvvE2=c6NURA)fBnH7z3(z*-m9S$tTo69;81XFRU$w!(3=Dx z5r-7G^i=W(pQ%oApP(0z7h86nWdgo>&xK;|>(RE!_)}Pf{8P>&&Rep|r~kMYqw->a z{s0|2;R8Ldf1e#!Zg~M2ui+W}Kw5T6H>7dE?ebv(ZaCWW!NJ#d2hUpn7fHB0`<+#a zr9>$W47xmRJtT6$4m%dI!^??jYwL5opF7^ zPr)xVzbfYq7yQ|VD~m5%U~L`|j9B5mVka57N7VLKW6ce zB{>%i>&ZY~S9x-)U+dpD7VjU)7Vv7FCY(4qReYOWSsQ@`F9&JQcT_TV@V&8*7XX5m zDmQFsNGNaI^~v@uZ8G>FVcTKLmNX_ffV1ZPZ6Du7OV96*z;Z8a7PAO(Wqfa31XTlg zSRtwfFcUzx9~tqFtE;+<1+xDB()u#UJpt*t_&*THCAtP)LVFLOzq*Q^dEmhlCV)5z~cuP@h&qa5PIQQRD^z%gr!8;rZ^;QV?Q z%8{vx>s0IqC%HgtkRdPs@(t}R9!HQ!@u$aU0++c=$5{#~hvE4S`$)ZYlcvzi`=t12+pTnXTH#FWC&nu9tW8yt195`^J>2Eiud<5 z1M*S?&f#(jkXct!K$KVdRs%Yjq3c`#o3CS{P!V3BgOwy5Znio*1GM9_3(zJFfk)dx z&kQF>a!`{86MfqO?f?6(;M6%3j+_Y{o51Ggp=AcH4#u&$_Q7+f0KbNyXN3P9{{MR~ zk4@AQ&z_U)dBkAZ9-@qy1iiKZ!*kAv`tOyRr!(($YJcF z=n9(jyXST5DmEY8f5?S$oJjY`JfY$9`_}WCTq#3j2u3Z=apz5tlAn@0L_CE%wpjTg zOEHc2z2MtYCtN^zkr_Zd(J+8O*Y_i)v@1(>GdEtcaF~bEZkgXJ`<2%tRgY}d&yTjF zsSF#LPc4&49ccTnq%R47}%^{08Trt5ZVP1n~` znZ?gl#S^#x7dOY#RARI7_lQ$kmlJcZ)5C5j=UJ-0hNO^qiyffB73!(p-?FZ(CXy40 zZ%MDq>S2&+p0KX>y2Qr`r|F29Uw|@`n`Jht+Imw|l{@a=L(U(LKHpI%=>d$6+XO-G zl&Zq90LB>l?0|2@!evUr+NtBYYGcx4itT&3>ALUX0P9j{rWeVZlV{5KI|UBw+Hk{# zkn??gM^nP0EgE6B$#ZiG{x6qOMOq8<`B4*6LUT(ZenW!kEQ|@CU`Ibt>92uOVVO78 z^G@>)rT^#iCw|>C_Jol^NH-oS@h5)9{#Kc;k#@t^+^;9OrQ4!|Z$Xt0MT`_dJqrdI zXLXT3(4tqrNPgnoM;edLv!80M@@mY`zkl5J%HthuEa>-@aPhiA{>(4tG7~-R-v6{` zUTfRQVdCmI0vWvpMlbSYtemVgvxPLyK>V*q!!@aNh_9lt`_fgiUQ4qZjf`Glg-}}+ zqA@{=1u9bJm%I?npoCpqDL5ADi>$B+V$#rfZo&!la8juLMU>aYW;~&{zo#st-Ta;S)c>busxEcd04OTlto@znv!-{xY^`p6}xp_So)##f0K}(vp0_lZg#?a4=)jC+SWoS>m=a|U9 zrZ|Zp5w}BEiGb*auNksQW%ojEOor63U#EZ-c5}ZP$Y>p&bJP(c67S@EVuHJifMzb5 z-d_B^hIYY%HecrvRKF4ZM9E}MDQOl42FURZ>PkelTwh6PLH^H6OI6T#yLU85R+l%w zW$BOPz97^KSQP>@=D~#bRNL00Ad9wJ93{JEqzsZP!p7C{-X*0$(hhkKWw)z)WL6FJ zIcc)wn{3(fQV#B07A|_@H0HWijg|}CakME>G2p~!4@|l+H-c5wP(6C&Ufm*{g280`XuG>RvgJg+DQ;X>vW&gV zfa3WvyM5vPk0^@+l~V<41xiB_y<3OtBT?2Zl^g@VZF;r!*d3T}Z45-QXINQE(>y%o zcaAo|{*Te!RUCh{^R9Z0#f_xVT>%>@B9i?HK8)sBm)wvjXpYOX6B894#*)7M?etdbBf;x!2e*DH}yfE|HdaXatOc$)3 zH;e2uD zWdTq2)7kxx#R0nG(8ZIUT0{SwF_^aA5%@<5L5m6Hv0?H{?Tx9MhdFFs_Oi7Wf6#;n|}rLypur4kq~G3c!AZ=m3xvrTq#Cf9nOYZT(1Z~DMdiYo`YfdD z)R)S%!h6pMjQY4@gv8@{gzcxqb!})sE-FFY*IlWCUNNsfFTnxyy8% zH&|C|gwJ{{tnJ11Tk zC7hIr1T)2eTbdnto>kj#@MEOcO$SeVfc7%w^)rpks=Cia+aJ$y&s(6mmMa=QMGFX* zVD{V_!JAh$$7{HMR>WZ*b?~Rn5#jzTm4z#E+)1<=%n{*7J&ZhB1>NDp4nFj{nB|xR z5QH-DBkX?J+XKaXl8-nY#l}^w>2A>9T--`YMW=+5dqG6bdg$y1HbpR?lc)itl``R4 z9p+fz6t&I&t|GnZ=v~uZPNmk)^3F!gYB^t;v#gevSF%H8w@rqrPBoOElJ4ABu3$Wa z-aV5_`~4UQ*ktB6^dCePIB&M2BwlV?(Sgi=@NtUR=UVr$Yt#}Lm<-Q?KLsQPh1lZ>ubztSU3TO+3nKyr# z26p7kNHp^Yx}2(mO9%_xo!8ssKS=Tofo0~0ttrFsfO7t=ZKV&T3a6n!5spLurLu|E zFyEKCWo;(|cuNay-4BPV)On>IwdW-AXII2unp~;oG%EgTDl&#IR>pF(% zIn}-LmMb37%cnuUH#k@&W!+4K7Zydf?PxBxc-+OOotC!C20i@)O!Behd-3?X-+J^Z z=id9~c~eu)yXMKPcfN`V;lPhl}gFZ^~u9Jmeh7dGyhBrhL{ZF4rkwvd&ee?evza$LF6i_z+#? zzXZ89O26pFT$0obwVnJfCgn>Tfn`pnNl!+YYHMCYv_3yh+pY*2;CJ z7I!zSI!z)`Kz3n*wu@q59(r=J;9vSfftC@pY>lwa=5erNXv$X1Yf_xaVx-@c>-`pZ zV9cWS&5Q76SI{$sz)i|8$;|%n#-ZN1u3D9~w!kJ{KKg`@s~D>Le83JCagPCw3_KTF zT5F_-QT2BU-$+d^tW#uLbkl_1KBK}igm)Ld>Z<6bXm7unLJyeC?D)5-fp2q4{V)O) zUth00)SG1-UN~!L$j-4c>$WkmVrO<$}6?e zjV=D`7Aq-taQ7p#|J^~MjLa*p5*v~8edIIs#E+wNf?-H&2*c~wwR04;A6~Id8BICb z=;(j{V_)WE{I|G#X1*vS1nc%p+%dGzg~9MJnzqmm*6_pGs6|jM@$VLK1B{=7f|kDv;HuhS;c*eAm#?(l z4Dwp1oZ6!5f4w->wkDpqrWa5;*DLzA23}|z+MB@8MFI_F*Ic`zE zsaLwp$>6bS`iSb#X~QUp@Rb$t6b;AL{X2jFUl^LJFSVeJ*B2cnNo0gtv)cvP1Q=Ky z0JYmR!d|*9l~p1ln`AIg#`SmWfk@|b15zw=RfFg;Ww~T1p%a@}>+^v#=T(Us@uxG7 z4m;#LMeU{A-+4%m)V`7YL_tj*Na~DVa18U79>czQBScitl{NzpAbMu2^_wvAw3Q1$ zkEP}=Ylj>h*l0gyRG0_wJ1x&`M89;Ex4-sGs5C1haS=WcVrOE8)!c&LC@wa!`Env$ z3->=dMd3kZG?N2CIQD&K@r=ZaqvCRgd{wMRDC;@BeGaA8BPl|{lzE|#GrdWNDYx_d zr_ByDsZWG+jZ-Ls;?c{#EOuu()`R+;$ew6r19iZTgzKAPzBjY7#>*1=*#tvd z;w%JFW$IJ2h3bbvhv3n{f7{sXlg)I?%Vf1uQ-r(|pe74X*#mbN-k3S($h%N#<$U-b zn*a5~7;XyEO200rm7RP0qa*7}7rA|}821t)0Ous!QCzMiHWivHtQfj!(vT=(7REI8 zX%5#19`AnFfl*I~Mm7YnpgH{4eo4=4=*|YR<(5W?Q#eMk+luDZA{2ry>qwd2+XF8R z;gkX&m=$THp6QoX!Rkjx1>@&!h4poh;71ZnxdP=&9`ZY3nJ>Wdp7FaXlj@ZpNd<>u zEBpZ?2}b^OO#+$|0GA{Rfrg+WNGYpD&Ku{Jk>hnI@Xmn}7=ZcBm6)-peN8v(B(LAu z6!vjtL93^?YU93*6$MFr+3meZL{CxgzSZ$yQXR4f1Z!nOG}(g=^qQ%dUc0~5CL~U0 z{`bnZ_#%tFvSq5J%j(Kwx4oO zP~?vvDDoxI+VK$FiOwz#l0Fhj+|_Prm0(i+{hf0}IIq8T9*Y7hZ;#4o!yY+v?Ck6u z{!k)Mp&|{3Z4BeO;bjZxzahv6xM~vHlk4V1f({`Y zfJt!&xUG_G9R;`j2?=G3wRK({T#c*;OGJ@xP3hWN{i zJ$ygr%PhLk8F2CUcJt9R@hF?<)t2zHmG8|bbq&)>uI5`iU=Q+_OYiQs|tWt08$ni;^c)IPN#G0|Vz3mK}W zmax=~OfW-uw7D`X>&`xiR1(frC&AgNE($l6!<)3aW#P03OOr*4ApF}2TP=f`cG=Zt z>Y}b^VSi)`x#!6KhfL?`G+5Fb+pTp~9iYC@{p3T3eCE0uC!zhY*(rQRe$dg=1{2Eq zkt{L=Dm%bV!S}`#ut8O{%xWq1??F%FFU6x+GH0X8oCg9|x&4nv>GAD;h*trZGFdMV zZ)D)rf$f4#d;4ylQO!JI0@eb{>Ww;gE?;z@6oYB32PwT=vY*QwjWTz7UY?y##(Hy;y^ZHUd56AG z@__mbSzuq#4c2avd@AYJHqLAmuKsQgFo|v32UynwJ|=~Rx{hY%9R&1zSv9B6uIt`i zvW!;+LrV&nZgy~?So}D#I}8|0T6?IjaM^yKC~4g6W!ySRUF+T)3gozZ7w})~X_pda zEN_eXjw4gf8no)q=MigNCI|^Xi zjMH0!w9AjBwc4Xu^yH?Jpe1q-LMsZ7OXz1O?|t0l1=%JrnKu(u<>))JIi@8$WflZ*?a%xVt=y) z=NBt>mGRr&5tzyRV&VSJn2C*#QkaaV{Rm|b=jT*=(g`oOOgoM$X%7Q(?)$TH(;PB~ z03$}!1%<>dd}Ln+DyD4XUue|!n!i>&8eOJ;?+gCt>eRDr_^o9&vtel=G`>KKXAW#z zo%Dlwf|Ens_K+L+gY7u4xX`3Q(b&w|dcu4nCve8ML$Ffo+k?XlnnRd;I8KW8B6J4C zwI25b(Y4mSY!Yu|z1G#mBEl(+LAUf8nsv3n>9Vq9-!bFO7w^+ET@xT$k^!u$*aSRD zaAv#736X?&OK> z!AQ(=vI4g{UcaInj(^W__mA1i7r`yh(_5w-K0!Tb6hkkh@z`CvW3wdwds0`*H^v)^ z3-;<-@-f*h3W+UaD`-`06wUVyvG=OBn2pHj{l6w-<0~2bjv?&OMlMMo+J~~w>rvZ=k_d0%64^B4wvTfq8LoF($JNB1ZD9T_b+M)3GhF555V<` z7&f`ng9bAu-X+%vT`w!0I#Y>leWWiFJ6@S!Ax|!wdu-O=hbo9onrJ_6UEH5X18dTg zj$e)l7QxK2rL9twGx#miqaBq>@9NaMthEB5EdO|_&;H8hl?Q#6oK#C! z>vvYkQ!x3L2IVzc&r<&3@AE2)zPgNC!;Yjzu8~`S3WE`1<)_s)4&!YL+VAv!ho({^ zqUZBg|1Y?nw~z_wWQg%q`I&NJ1akus(_d2#TAT6HP>-;tj$Vs zCbWM!w6A5xt|IG#glTU#%fU(xJyUw^+{!6hu zD_vO~zN6;-L-*|4CMpoGQK|vVE4AukukP#MEtgk8Y6-)j{PD{}=tRS~65Mx(ryh6S zA`LURe>kr*A|L!iBem%*<>>yCO^y+r{7zQ4K^~G?KILR1L577KX&etmxTG{S*`IEP z9N=T8QFAFy?Usx`Xa1YyKuKXy{e2MFY3<_HBKfO)g-tfPbdEZ`GOM#nuP?Zv(=+IZ zXY2h$_sXxjSy)O}b#|i$dZ!9Q#PYTVD?mPDtA!jM!0Vsb{zwux@zX9LPCkMK#OQF| z%d_m;!P&_?U{zuM!^0z|LuRb<^t**e)N&5eW#qyBW5)%u`o5hIb+}+F)XZpTbiZC^FAB0| zyR%#^F#p=G9$)`hFK>8F=IR|+byR@G-|AJX^y`QZW2d#|IybYj<^uBe{>psXGjbO* z-ETV*tjKd|=hLUOQp|O~^2!Oh`ZOzRoh81VtS&DAr9b88g0Xs9Wu0NXk8)FaTW))r z*o?zEihuZewjJ`-=O$4Cg|6;qZD2SDKDYZio^85jNlmC+9$joLbo+nA`Azak&H`I* z&B^>vL>l+6j1PU}+qOFJWMsy$TbqVxAFnwO$jievmg>9}#e9x?A?LR@zh5JTG*oh< zC$c<^N#pV)iSaAAv|AR9&##n8)~hdgF{00unYYm3$w*$Ee_j6ae~Q%!W^N}FRmu5B z1!m-D2Zt>jwxVwxuBRA&p1c*Yzb`Agemiqs)n_mFe8lf$fHg2Nj+XU&-@@-2+5F3R z3fMy7DO-qNn9=_p@0{yaVW9gxT_uVBu~);O>(K_{QJc0$(3v`C3z?_p4OC|ZlI3(l z(B`qqdG3=*ar*!`IHu^Iw^>zOrQ%CDZ{vvpGOtlo;6<= z2&52u<8Yy~vuh|?us=`i6&vskhCsDA+Me11IOl#8n-j}t4qv?1{a&Y|XrvC&@*3S5 zPD2OU@yA`w(Xwt&dcYB-pnj&H%n%K*aOOha?n|a0gPtx=>>oHk@fx)o^v7cy@wShR zYC=~~a++Kt<zvAdC5swXm5(zBfw2x6eU+ zk0oI%RfdOpa|F*V9E|D;`UDKl=j~kmShoD`dodra7-w(HlzU=T_zL&8ZwO4tSAWI9 zjHw3XhvA@2gO1}fKE5||p?wJvG^E7Y7Uhry*wQ=!r52yJP3^WtlTe0b-AQuC3Bs4^ zgetqvSf6o{+RdTP(Ehr$z(GcSnsiPn-wXRzodQ9DIfFv;*9)482UNLMx{RA=5dS-A zTdbTjJLDaKuFWpM1IkI}&*T3gwQ{Sy_^3&LGa)$mNn%#rVJ7!o_nVH?j1&O^!kxu@ zDyT>o?&@zbCA>FszE$%I4bM(wnFmJ|6k({u=uD)ly&eeRa`*b2Kl?gG&0GkK7xNj( z>y-?cy`AfCyXApA`a|vv%(ZyqwB^kf*Dxq%+afp|#b$3v%&Bfi*>Zl7@x(pPZ+`HGHGB#b~Sy*xH7a3w@-j9ky#|9pMe5e7BVLB+sJTa(s z{vxa#^(S_aF?9Z^mHi#x!|k}&{}R+}Aba7DAV&8X`cQ$x%v7(;RdMtlOdh~K$=gOP zs3lsXF~3=Ewagk5cqTjUg>67gMa)00>LH{l}#=8f~xXizOI@{B!_a*_L-FiikVT~%taR{lmQ6wfEj))oII ztWgA${bQa>id~W4WD_Y^_PSY%-zD%*;Hya|h`u=m8*r^laHgw2IXso>vb`yav?-Wfuytvdh0vLNv5lX;1qJi8CQ%r_i= z^tli8RdSW6IZz#U3qU4#ZY*8F&t&Dm73IPNB`1^T92d=eY4>}2ne$lXe5KIKv!Hgp zvKn#>@ge>hEKxzHx>FVkNLy?i?>wP%OcS9TKFw6WW9Y~rzNsN>3w_TK8D(BgzeD5= zzOHV25uF$Lm16;S-I`7a9q{$r^B%@xGo?J>5>IUJS*RFQ>o#I|e;EBb&ZYt|1+Lu1 zvsttgKJNDN2A@0-_?+qvogK^)|8gx>0>{L4BnLt_e8}zAcVL@u4 zl|H`6pZ>u1;X^3JIc<)-Oh&H!@2NKD&8B(zW`LjMr>pUwFJ0Tx6RwNK^Y}*4M+5S1 zf1iJvhdb|6`EI4j*kjJk%@8CP5Tc{=sF3y}eSwvU_Wu1POv~elh3C> z6cNR)%kq`<2=CP8X?lL{4R*=w?FmyT@YsSj{C? z%l}Gt%sU=CI8CkvZExHF zCOKE1OrEH7FSj_4^7ia-zb}e#XICE$C-IAup>l-ZDZkqJqeJ@MykregIg%2{;@_MbMwy(f>18h?^!w>PSlmC2zh?4t`sA;9NtY{XIcLza zEBiL+1_a+cLB;iK;Qs)}Ksdj*rq0ON#Ow^Re8ZBGth=ub)7N1xfUYj;6dSvfotK|J zoscC<2wA#Rzjo-L(YE<~g`uaxZzMK$1=Z7PH*==`4ZCA)je7X>x@EMUf8{y<4*!7I zSl>B0oRdHv9$B8T-if+168?>);d&a*dY@V7xvTgvvhp-;(j zqn-}dpEjWFD9oG4W#_X~tf2Kh=RJcBpiSc65km`S6KLBHN=1wxRP>^sA%hdBFnvQM7#?4G>AI7TyN4k=CX6JRjc}ZUE$x3 zF_X6WD@iIHIeu}5%jJ6R=lkwE!g8ql^qP}YuW-}0_uoHuJZu)m zbEB_vc=&4C2A@p_{WUA=2yM@TUt~EV%IP{A3(ioLEBDGjI75fEvac`u)+bm$>%MX$ z?svMrRz;Std{5p9ZzS>~4IYWX__;82m}lveO3fUM|oE)n~03yX;&%QwH_bp7&E zaNh0u>-RA~NwfiN!5UGP>$GvYZuu#)+@vpj-jNr52E)=1_5R*jPlb6IMLQIG$&h%YQ`sWPt<_V2OY&XDvoA(P(QgrLc5nW!D9LvYFG{CRwFxzAzUju^IDmQ13fTV* z1la$qfW2Pq`ASmXxttf`{h$GCt2HQTreJ@~?1LXF;I}2|s@L^*v3Cj?HAu+ zjYmg6{e>PM+k3`FGSz|dqe^n!x+`;p|8J8fhi&)Z?P5gt>-RstUVDx2_4m9%%Ex}Y z%XPzI;d524+?!NCKWn+CK6Ppi)n#%6#wSir-o@LnmQ<_u(*GnWyu96ey@Zexn>1_o zuBM+aL43p$dG?6$e#AsQdzO&t)APo{&CL9R#el;(A>B80=so#)w2@K+qew|v{*NqID3A>uHo%S@H?TMs_??z5 z|C1-~oK^n-`TF+ zI!%_7S`_~M%my|E`$!^YXscGgdH0(T2NU~Hefo$vak+Gy)5ja^7nd)8*T$l}TQA{} zwQIlnGh|V>AMWwS+k*Xn*Dj3=8KUnWHE5v6pu+hoz0Wo7UG(?sHYn`DVqQWlh!!pW zW_u>9SL^#Iqets8utW?f#C(g1dGsSGWH#7}aSa>3bq2Ob-F|n7?d9P8h|4r#0`_n8 z7)+2=@Jp6Ej1A4Z^@3R9uv4K=BNjr77C7sp(Q#0teAj6I)c0NCGhDs;g0Dku1BDHz zUAy<(h?|V}BqSX3+VRuU5QAtLlTqyT%W~g;h4S5^good}Ld5bzEP#d$JuD_l<;wb5 z3Fu7q>Mi?~s&>UqTd`Uz> zRCr$PeFd0RN4E7Fi4ei1X?J&bcXt=Mfo`B1cWvC=-GXaEaCedbNgzOiLjnYiCnT9n z*1vY0dubwXCNq=w=DqiKec%4-+;eZ=?mlbnwfC;7Q|CYGTYal<^{u|uxB6D!>RWxQ zZ}qLd)wlXq-|Aa^t8ewKzSXz-R^R?Fx1K$VUyO+fiS+Yxc8!h>wQ+QGe74fd>lxkK z_3i&+i;uT{F3{H{BqYFNet@6*ZC@XE`1p9h*T?O9A1~L>gZ#bj`*^z@4)pWfGhRmXQqxy{c%Xo zD0FNSgrdwqB*ge2G{6=9-Y&{~yJw5+YIeL?r@>)XGhJ$S$O%b#B^P5tUh z@oSH-<$v+*^*ns1tU%Z2=%vyw1%L@WmMh(w1r zp~z14Lrk~_g8khPAS59{e7!WHczHO(+mpSgE2tvyc6a{4%ggm!A8*(D{(c@G`1^V7 z3<~sG9_a5~8y*r+9TMUbmzogm9TOANvS-hpF9P_3?oY07|7tsRs`8o7FSif;;&S2C z$5+#Ce|s$k-(3r(h0~&Fv9tt&pNwy>r_-`%Irv_YqL6(FzPnL@?{5^-igZ@U&lKZ} zi^aJ8P65sx%)#N!nb@!}1#`y5VPxNEbZHxg+%!MLMR*~^pK9Xc3_mYt5`s$N<)+Bu z=f!X%B+(PaQ%K_W8PC5L>hE(T(9dIONU-ljs!LT=cwkmcSfG1Fe!gLLc6I}*$scw9 zVtxC01ODR=H{U9^{On@Mz{l4z&OE*v|Ks-x@DN%szGq)&b+6?;&EzBO+3DTxo2#8(l7YU1t;4|gZ3iPH~!|I+|pk8@#xzI#K0d}hUj z1r3Xe2r5jDkBBWSOtP%4?b`VNOMp=hRs`ONW zt3M}0ojv_t9dWdC8cB32a$Tn)*Ar#z$w!>vCj{|wr13RXBf#68y&K8H zoJ5X&JxLz7A42@R?*#|?z8xMM@LE_%;MDlo$i8t=;c01UG43SCv${+6zrU?ro892b ziGsvW&u1?C=4!%c-(8C&Aio4u0jC4?Zvp>n_Lu9Szj|IH#M9rUsfYgcch^Nl!l@oq zk!x`zKoZZ1lBDxEo0dl+h>-}Yrz!H}@-uw@h8$*|>5d11GkmV)LQ|%pMz! zVLijqp(F@d3Eqef@kFSf2Lh=cL6V?)lN3x={e8UP@8?5e_`uE85jIxle>FEVy5{NX zl&rgi|NGjybvb`}b61Z0y>r>4zPOZl?c1wSKYV{x1L-FKJazo{>}hiRqXZFq`e**L zpI6_l>$P*gmW${~!f-?IwQwVZpvmhSS^Qj9K!xrqT>9c>X3=!^8^xJQ)*1= zv+L&{Bpv+bYV`La!}<%WdUa8MX+H<#Zvpgl|Iga5{runh&Zommoe4RpAlD54oKS}^G z{ri%i{DrFU{dJwm@l}R3nuL#kW+8Z?Ca(xt5B@S6H!JEut~+xSWb_FU8>T z2a$MuoK1> zIrfGmb3eaediyPa{5|_;zT@wK{EvO7gdORH+ycD(zcc~<3Fy%TJC2s9fd7tFi7H#K zQ3bAK67)m``Zwpp@zvP~e04esU!97<*Qb;5-p&%_XC@*)JB^l(ye#%4KtVxvnC_DQ z`RvH5Qw^vAlOL6$-{V06>UIe~;hjxl~GMW~LFW!p7mv6=6 z>VZP!XT%ZsRODrf>4=b*6{5TR|Gu_;QF)8&Co=Ls{UG7BZ>~mst(8|#0r-=P^`G0* z7yswSe-9Y_`+x6qdi%A{{nnqYGd<{a-p*u}z-r$9_=&d@^sAJ0iTUE~VwdUd7o+jb zg-CpLCIVla3Mbf+1U*)P{>7WI`23AXe13xOoruQ8eMQJgOGIvF3UV`2m zx=6eh-x<5F3h-KN*OEN}oeAAldi&*geDeW;KS!|N4#($jg)49Wg5Lf)LI3PT6h1p1 zMhn&KL?}Kv8i)(KvXPmZh^+KvWT(;C3juPHqa~#rG6?d#uje!|3gy z1U!9$^jne&A0>}maN6GSQp!^mv_4bc^_ScQT ztHB_>+-oJB-rKdLj-?%em%$;CcNN=N-hC@FPjCPFTok>Xz@HSEr?(S$vCk;+pB@X< zfIc3gfdAxZkj?_}=&%p&?{#MHhfDi&Sog;xgCxjIO+XfjkV6$nPe`!U!SwsKA1_UN z?$gU{!@s^#wD9rOj1M1QOZ%%TSComoB~j{43G-W2fvG7!IR z`sDH-{rPmTs?c1(XPeIOnl@x|?(j`(Q1GaerH#+3tENK1-GDhZH50*DG^ zr6(aXDcVK{*}vYx!ovP+YiS#0XJa)xA7N`GFAvbkyXNWQ@t;b6gai=d@!kC%IJepncXqon1i0hM{!B#x0Y9DIpUx1F zNlW^@2oMz&4=I5ftQC9oa`)MZ)E~UYg4$`nZet|0ug}@D98*# z=l1a!H7ExQrj=mJsvkF&Ecg81IyW_h%UGV+w3X&vGM-m~0$fJylGa-_sNIXYI z#S}?o7*$9jB@_YBfvhLRFM;~c?P-EM{j*P3CQr^i`K$m>iNCIS{P&8ida2jqyP7Cc zbV4gHMkbF&4vVW5-U$ z)Ty&EckUuAT(|_YX3fU9v18DucTZGRwnc7s8WIyC5fcI3Yhh7+tH9F>+8omdq-{o=u%__E!o&%XbUt`ZBIAvHMQd z?gBdPQVP92f!CK-$1+Y3+po{nG0hjlA zPK?J75Bnk~#sEgG8Y9Th1JxxyBtRN&h+la&rrVx_0gLL+8#t z(5-7P@EF~@^+q?E9QWwnSH14uqYrxa=!<~^hGF>du^2aQ3TDilOR`MIm@#88WZ(dF z?^=zj_T|XWO+!L#825xJdAwgzWVC&i{ zoIcnYH_mj&XV<#p@kgETms=J1{=-75NUlbX>(Y}TN=1Yq5`P7tc$z4Pc(8c07Gi!* z5N#S*|C*ms9xqmx-04T_zN5^mGL91e_;LngdlF+iYxFbp_LBrzKtGX)hsTrf=s1s$ zkqAe^@Q~gvUjB$+J`%7MxI8}M_XK23?)B&EJ|pC~vdt5=W{qJ>)wQ*;fRnui-r1T+ z1<=43`Bx?+_dftGkjgJ^6FJNs=KLKW;J>EL@63iY^;o7 zXJbMoF@uK_3F2vkh#+Sq$9bWBX%zbRNWr9$*;qUy6Fb)x;O%|IxO%b}pI$7+LyV#6(eqC@jI4pM0l=U74sdfzwJjeGVcXF9SGQIj3dy661A)Hcw)E9KL#w zpq~!MCyeKh=;Z>svSYFI@^B_?q4ZoDWBem}y#W7^ph_~Q2lxrliWI*_0PVeli=AO+ z*a&WPoW_k_hLfW;j&F!l@-JR5C13`LApP$W0&)wAQ@V8NsR2(97mx4LdmwuC>QC_d ztK&W-Lhs)F(VORbPzeO&9yB3Cj~-NtE6tzP}piiHHXj@)|u01W6BiYddxv0_FP_N-0BxdZ9A{dNw%xTGV*4UHsP zFA5@RBF4~jO;eWd7<#_FnoXI{pv=eP>-VGa<-3gQC&LJOGyzY*gJbmgWAS)!l&{6x z4~INu!FWJGA1d?Hj3t~N=ueLNDHYI6&avnFb>_qKzSug`K@q^-)&i!+1`M+ncyC99 zB7lINE#6N8WGMpt4hm3MSe`82-m_;v4d`BC0{j5 z)t8^?k6}YcQ4#teJ2MYqp`q~c_JoVG103wFVP|UzYin~@TA0#|VQyvwGgC1`m>3(v z$gm|^wQP#!%^RUbi>C1Q^g)LXT`*Sy@GrNW6HykU(T#`W{q+UOG}JMUeMM4#@+g@854QhS1w9 z+jT%(bPRmGy%_5q3Ahcctt??{Wd$1>b68oK5_Dr7=whvD#xON8grQ+;szEENK})o3 z*_;GuhL$9OF^OSsXNQ#3O!VtNn2OUKdAa#W&&WhZMiz2&3Q<~GL88>4AO8+XV8@Ie zkMZLtvLB5>1BIYn__vjztT-3RiBU{iz2W69|X7Yjf@@x=3 zKc$s#65AgsiBBMiQ3NU!4-OIRLrm;cA40Hstg{D)NCF{%5P`rx5CYKT_#p}Kh@=p& z7m%f{*8tau@QAM;9`@qz@lEjO%)jo2U~L{Stf{&3PNQ`EH3Y1S@uQ@!B5tJKg!rniGOfN@8txXAnQ$mu0Jmd zpokEH`{MmN0z4qNLIMF_54w1~9Ba9OrU(jrMF0<;bH)9A4mh{g0T(yh;nr?Td~(bY zA5a0ZGgCDJ&_n?w9HgYg{_6y2)22tXTT#ilo&-O} zYbPgLdb<@pT;$yh<^)}U7Bgo|7l}9JvBZ88BTBuIfd;tpcmcfyrJu)&0CL=%;EOfW zl%QoZ7#bMB($XCE_Vy%$4FS%hcMnEUVG%MjvZ(|b8FJX?c@k-o#i;16@FD-C74effu=NO>b9yO9QlOLCMn^t_Yy>_y-5Q`58H;=O1<@`1SU$R^7Fy!Z? zBR4ArQ%HaZM=0q8UNU(B@;;?p5rDvI1d#JQR^aRNfu{)|NubC*2_W8ou#Nx^#LJKH zScsq}0M9)*ANpH)~4Zn>0p~ zCXEyUn(}q?W?D`l38SeARfhzyu(0Cy8^YVmmx|S!WX$0ON#_MgM`~&YiAy46(bIDZ zR0t>~5t!^Mg~-b*P>K-|9-@E1(jJ+AXpLSGo z0CQa2?WfiPDCrj!&{5D+^LOcIv{5Q%uh&Q+2+8EF*&z6;~_XXQWf zvXqoGCAo4=;%mFM9UvqcN}|XJ;nZofFlzJ|f{~&U!j_bBiSL@+6L67woyRwCO4ETa zCg3-2OacfANCp)O__GF76GZ}3$v4bZZ@}s$z#mHUQ;I7X8^x<-__rO)I+4!I%v>bIB_hB-0RH|y2&5$@ z#4@HbiDC_|W~7*yq@^Y!HYN&@VPQy&Po}4}Rb&`4WF)4~n2SY=m!OhKmt^!B__`Rc z16+B%c)NIhW4&nvXvT9A4uk+I6etoH!h}j7CdVzQFhYi^s%jD-9`W&s8VM3pn6Rem z)F4+8TofQPGh0;(5n;@%=~Y=7Ntivz6W3m|#pPG+aP@UtlE4!8_S+G7ssNQh16;y@ zD1i`wJwcb_e>wylcH?;`zHd+Pt!ear%Kt-x|L_pOKTJDftcY-NmnX84qt#jfiT|m| zamxNB0&K1gYuvG2{#<(d7d@Exb*$=4xom@oh)4tn1tTOlfF6^_Y`PphD6{?g^~31V zqgYB!#ry?xF>l^HOrA0ovuDr4D=St|DT?91lFi%GgFhdHEMDloeFtLru+fSLbLK9j z{N@ojBOUM}@tQSh+>oB%P=PMJ5TJ>8KR?%;WYJ1PjR38gTL|!Cax5y)j3LCx$QW(g zR;s^0G&GE)6fz_!LZqc;Dn*doKzdQIa1uZ*vC2rs$gVy(GT#OJ=DOnDbxydp!v-H8 zuqH_KW_=h?@n7%#Iubk`0@Q1*{+H~&E(z33M){tUfr+M;jL~BzQc?V$c)oz$SP?)#*G$x)xk?DNYCv)TQ2(0)j@Z})c(}VDG&qn7P>e2Jx?+Ff}z5)zvkMP@~68;CIbH zE|W0>mVy%RHILUwAf#wcatQdE_iJMWDv^}ZQI(Z4p3qvWDrhbEndZzh8Z~MNODk&> zG0P943WbD(QOUxn2oZ`9iHXTn1PNL3h>QqTIe-kUdV4ssDrpK2S4X5pJK&v-P9%Uc zLx7K#1JL{LDI#cOxO<3U;h?{=hXlS(1tb*c!hlW%9`LjJia`-TC6S^g0>17uJbscZ zC==BXg^*mq73a4y1f)a|{8*$CcmZFI|6u}j>5$>vy<4wqGUC^!O*>wgPchPAaVyqJ*( z1cWH>6Y%3mECF9)aR!q|ZBV9!GTok)!(>dHG!0di9aUl{pf_tO;A^U&PZCA;Wss<~ zfs}&c^)im2jV*`@=)J!=tBR&fCL8l_dFiDW;Ymdjumb~wl?5@Rg@=;_kum)Hq7fPr zj&PQ*Ss5uR4-nujEoC6f2riCR*t5hLcMdT|3jqk|Jq0{_0xQS&o)AD&hC1(-FrX1Y zsel4lKBG4cd{t(u_kC6Mp{alXt~2reCj@Z8`EB0J0V0&_rzFHEOHPRX#|SW~e{vYh zwA(U>B9iaz?ZpJomsx!}s%vU6a?}_sShN&Nm#@Ga#`hUBXJPp8;f(tuF@F45O8qo~ zKbhfR0%LoBdZmH7@XpR|l=L9R{V-nOSbA5Y0zH*+Hz_HNF*l2`w}A1#NR8jOt!S@g zdfd24YQjfKOcxgyO1>`Pqt~lZLGgO!@h#Q3f}xQC!;1_j%TTfqppFEh0L@q~Hf`KQ zg`pQ-Xg~rcGR{XJhy(}-2vlkyz=wqq{BVW{6`o}LAQ_$>&TzE1#>+3i2uC|h>|X4K zJL1JhWms2aU*ui`UpwY`zP^8u#@A{T@F@b+$vaKw@tVocYl-E3D#ZPR9yA#b5RVt> zm*c06?;mo;``i7P1BBE2qY1o#ui0;&3#jc9ZCc%_!_`h5yP%+;h_V=jFnWNDiizY; znlcTGmoCThS5{)-!i7xO<`JOr%;bkC@Fz~3fGJG)MvNSV5hF&k46`6Wttk1f3j8oi zY;1kzLnn@o(=don;|@I(cgD*`lX)QBqZ5{b|VIXMOJ_4S3H zUjW?QJrx;3L&Fsr!kO!c0?7EfueUpFZ7tQzq@RZcPH*(U-D4pt0o1%+=lS&d`}F!c z6(ER;06K}6%0R$p*pN6bB+#k``Mj7fzfaD|&v|R$%lLy*3i0-z6TqF{;fnWn1R*sc z49W3Pth8uxQAlF{TL*&vP*qhut-89K8V&RI@qb5uS8#Q_v4H`7yXKj$2oWdm4TYa~$uOI(r ze?{8R&_Hd5jX8jyk2@?aOyJ~TjjrWP0(TOe;}Oc6g#aq%6F}+jA0(i(y9a&w+MDld z(*AS~pbBSwrwyLRoB=UZ9Xz{e+m9wnX>!-Oi9-y6k?8wg*X z4-N_?A!2#)(^MTUAwWM-BMMMa-cIEp<>l?sv11Je4b)Z;jT|`^Ztm{%ZUb0Zn!(!2 z3^vx5^iC_-*;&EC!4~%RHn6j|QsWA?HnP^hQVli<5eyj;Le(lvrPQIk!MznhlPua>dPq%+!yC6955ABY-j$_XT)) z?W0TpeFDB35TZ&DaDC>l$-QPu0hDQ=-#b8%RTvQOuOonxenki&fjcg44?%KlDB@!y z5FZmkr42^{`|Q6*fZo*^o}D^%eb~NzCxkK)3Jml`d7BC*a6K@N-aLQdVys-Xh6GrN zB}J(rs1~U{48#V%Vws!PRBYM9J{CpW#>HPw{ySq0`&CKYL zW|U<^#%9K9Lt_}TEHmSITU&dTD|mbRAvidcNn)(Z6J%6TX7kG1v_+pj{V;mecnla= z3kQ390&N9XXM44<#Ld--;5orndf98o!&OZ~i@7*E!qL%=f15SE*c`?T4J{-oWGN}R zfJ`V!*=J{K3ui|s{v9rg451`I76~B3s{?AnadNE-&c5o3E4%&h@v&IkKPt0y3*HfSZKo5XK3MId=k%13iE3;wJf0d!IWIDMF04jncMovORg zv#kiU3%ynC=clHiec20%gMxh7`_X*h=jToHWFqGZSCYiu-d4>_N)jnb@B%}D!9N~Luq4*&yR3j8q5{vH9! z3Jcxax9|8(aZww!L@PQb3Kf*_0j%Ap&zi%S{|eTuS;xe01;JmWq<<*Ema1UDfW8D> zR@#hUC>TgG4Clr5pm&+_0y~ia9t0s&DS(rs8v%4xBoL2pCgs@6FQXYtGMVucS=QI< zq7KH!rtFPjz+)2=iQ}e<7-CV8k?7sKABK+@qlRl;Tpaj&{0LScBEo_gYJw5Nix3qR zs`ZiVc^nxYjIeOl{lWf}crPl4gIZ_Uiur^LGD&GEC8@QwHNy(S2}vLdpe?gXK>wOp ze7H9RcMr!C{3LpRxDI$B0F4TuhI*eS0D;w)dOrc4`GJ71;=eA3(2__^`ZWd6CZFyd zaC@Qx3V4xyCH+Exx^Qr1XD|s6gm?lk|8I;CAS#T>cAT9K?w_`M_wKz^S=n)IWo0KO zd|?O+4q)spLC;=&FmC)rRqCx-yFrmaz@NWh0cMgE#l^+w(4i9j`}b8OkSd^Gzy9dl zxho}I=KpO7v?E+yJO~P7K2^Y#Y9NYWZ|{s3Uw8q3`qQ8A+%tbhgJ+*X>qalZwAo8A zGiV44lV+-flgwSFb)6YTBsP0`daBT3X{o6}QeqNBwQ7fsVsa@VCJ52|r{fs^k`iN( zln_gm(xyfAH%lZZ#Zu*BnIuKA8VO|%;-?0;tSrqTOUzzoKH$UH@9gBvgwmY3gDrD_ zK=tz({H}i0@dQ7Pai8E*{spin;Ok74ddv+J2~>>NOTF%#@_4<8dWdN`gOYrjB#q+z zcj@`}2)srB_os3Jt*;vp(y9R=Kw5k-5(s*%5P&8GsA^X@hH(FMQ%c#Ta^%R7rR~~P zeNn=MOJZa~LOg-3riYKj#K}_?@T*qS`z7`-S&F&y=c`07DKQaUyLP4*c1Pbny-0-q zOaw=(+S$m+gx+HdTRTTevk$#6PQ`R@FF%6l%~)@aKmPHLiU804Sx10|FT$Jzurh1} z8*?e|G%#eqr=>v){*07!GPEl-KM7)N0DC)YBqb-SiK$+F1}N!IOo&#X%ZivRxko-b z9R)cV$j{AWrICR=9_M9e@V!*!)rqW;qo@`>EbnB1r&+VcBwi~;C<_Z#5v(9&u0w9L z5CT+}N8#hcQLOtTRJJa$`mO@Z7ayxQFW#;ZKt}#V4V2d_@WnLHwQ&F)_&V=@LL!~# z-y^^Re4XhDKo#KoVjB3`5U~*A^3EVdfcQvJfH36{($5?>;OhfB*ZwpNkO0qDwy!)| zRaHZ8h(>^)ud4U^_8+JwZx$_C#@NrqkJ-NvL2CZ#jQxX$3|0#~x^?S}ZZ#dyt9ut! z3JxDWf)ejSNfr6DqvX4?X7}SoPDNlq2xDsyy~|Hc$jGl368xDY5PPw~^Jv!a1sJv@ z0W4(BzadLBsnJPVj zBq)dkkhygdpgcc}Koc0s?Oio6ql@=X>Uy2r6VxYiPpN{XU=#s z_J1ymAUr+XD36IOxymti+(ax`v;>QmF2@RH{xa}0U*wC6F6EdNB5zz{bW-#d#MOca;F9Bxk@sAeg0KsCxY}f1ZeQ=vuN<# zvub$PmZe-|cpxmTj98+{#LvqlK@&XBzD* z1*x6AJYCdqvJDeU83!>kG*qLY>UOK-I22}v%CtH@I?Bbc)vCbtp1jRuDHD27x7Vn1V03E5g{tf z#Zv(eZ(oBuSKiyIgI<&W0RskCR#kOUWAUDzZYuNd#n?Y_;uMwni}bHvvjNMNGyX4L zgt_zPVH(T7tgLLbZ(o6q1ixKL0RiZUp+jp~5*9O2lK~jX)?HY7Nd*v~2p|gJ>nn*@ zAnWdzH3j&CD8L`_97BMGxiJEK-5D|%do2wq{W9V6G8#8(iUti{ATc7bV(|iOTKx(( ztXhusE0<&4ie*?&lfI@?C&*$I883)u603oqgYr@WUsi9yQ~9q0Uy?u#d@TVK&v(TG+QS1bxV()7 zhzL*wh*bm#Q3QBn?}`JCYFc*&LD}A}o-VhIqceTBYpI@==mUnPSaOi@=TDuK1V$ z-K7b*dIIQ^J*nx%+cm56_`7n<@StV+66*zU0bV15swRGw09x!E~xe{vSzY zAq3d($ljR*@J3u@0AdKfSOhB`2?fXZY{cy=XK?lW8`@q$Lk4!MZd=j*uZ0CAOn^KX zSF_Ng2jlpN(e(5MD(|gClU0K~%*+kYqJ=E+ zYRE9q1TVh$BHW$qab)E}oZYq-=XPwwxjkEO?$9<|cw+~yy}b*!&+NtML4DO~A6e(0 zmXe4Hs#9Bff4hoO1$;*W-${9XxdOeqV>^uiv>I9mzF$#NsK)$d(#OTwNewgw2KbQx zacX^CR!S7E?sCEHeVz&|Q2>3c*L%K}-RnGE-z$&T0Z*&*dXauPujK$*{I8S$`v>df zUwbX2levHS-CiUB$*|v9tx*&b$SvY=RDc+kyHfJX?fX&eYkPOV*%LeQ_VJxV6af}b z%9~kH(OwO|29V(uZQG%5-+pRQ$D+l{)R3=8|H4I!)QXd}|A?pWcew z@9xB@ovWGbl|YuRC&tI2O-a5YY6q&7c(|DIcAfXvbZDo6Pa=qQ>Zp;Rv?xanq&Pd< z!OPo|xqt_fSyqY)q$fq-(l!^|*-wxNV%^OilI&@+FQuObye`)32iDNB(Xnd2J2xj6gDL+bM~}tA#Y+_dmakaB~#<;75`_M+Ytb`*`~^EJWxOAWSU)k&qx>{b!bcfBK`Q z053Io4u(x$f(a8pH}e*Vbv1#x5ec9Y!De{zg_mGq)Eb*748_S;*Ww*Y|2um&;k~09 zaPf_exOwt5+NM| z&llvRtKGO|9YlaXD;W|Xg_fQag$u8{YJd?ql?19Rzb@YEC0{?LuX(y2c=2+n^`#f! z<@l#w|8wB$>V1)ZRvvtPpI(1YRweJHNiRfT|G^e7MSv)VvFOl1gogwW-#`@SrQo#{ zv#@F9GHt`i-aY&5kefNA+!1dnuV{nXVZ$l&lT`Wl%F5LY15^NJ|04g>rcYC2{W8## zot2Kfj1-0c zPywE2CD5|b3$S7d=w#9yAr3|`Y9%XxH3fL-#g}1bWPp`Jd*Il*6*$ct;GKONaQ^5z zTs^)4x8HabcTc{K`)}{S-Zk@3EQ?9nbwGS<6xuV>?~;={5t3d!-&NKK5yd#||=OqrUMK_3BLV!clG75D=D)8G?qbxsGo zoReCg-y!4tdf@ePuLoX%tvp`m`8@X89zTfowf z$=}pzQ!#q9Ur~19hGfLnG1AM$)F^55(27q;EShgz!T^yEd#3X5ydjX=TjxxuPpyt&{fP@IVyHTnDQ2-`jvJ8yC|71`{z*jL|=k?0lOJJ=o*wDDyT=|M6MP|nfc`N}&fOI<2npDq+vJM4Fh6>|cs>ab z;;%@Mot}V+qlPUd^xA0PkRij+rmQV5xI63SOmy$rTTS`Soxe~c0F%HaOP6By+&Kh) znp*QWiiut&D+RgrD3djDD9Mw}(x`j4&KN-ju#&rcB?Pbp^kn?^_6|^SUvdCR{`@Kb zKCA+4SSIQTAR$0<0ND?~-Nk_f@la);QR`+*1ZBRyDNDg7FllXo1${eU(~NO=bJtp2 zr1yVF0^Fqn+<#*;39tqCPj18gQ@b&HbS*2I4r;BxjQVwGtK|Tl=-C|wY#r!wEct-S z3s}-hFQKA};J0VuSXP{eq}WI`%P0#gQb>R_65!-IDgb3z$vMGS*}a%9-aqkrr2?AQ zt8>31^;&ZGl-Cn%y=g0dH1Nd)e7y9IbAQLMi$BbkBKOc)1FJS_>LiICe&cdWglT`d4K71IeDl4@+ zPe_1ZRu9?Cj(c>i!KjfVbvb||lR;M|fKu}Z@ehbpt9@iWKwzMj2ug{lCxBKB{1NuH zmi$9~5gO(Xdj|`&Fwh9lkOXMdkO`up0hSN$g0&L|mqHgzUL(gS-D^&mit`RR6kOlNg_7WDv2)cv`8559vp*`~kv5L|H zb&It;7)mLCkboiJjWse5L^;;w0Sfpdn(Wtky#TKr*VXqwkMkMk()EL^x)N&kci6ESAo7|MJtI(6!VbjE#Ia~|U3 ziQGgIfK|YR@nhBexsbrYUZ!UKRmQI;fGh%)1W>90naGh6P)`8K1#GNL)x(v-m{)ju zI-!-J>;b?KK<|HvRfB2kR#-ECvNKK5w(UndFQxZXvKs;P|x*mL;$LmADPvl-3)_r>4y*tiSq^%*`>+a-BqW*_F^|>7~LPQ&#uMUHRJH{kxlsItsVIEA#neN>1`h)+;M!Q$B+nF~~s2$B=DC-9;S;^{I(+=jrHv1}|WDPS3xi{gSDHJ2c_ zT1zG^!^CQBT|y)dEM+2gkaobCC7;A~J>cT)Ix;8)_+_kDQvby3wVGb<+d+vEOW+Jq`30zHG^f!LH-86BfXdo1o5R#!JRGJ4;QIrM^N~0#tgF+My zLS)FCv1AIRD2a;9MTkg9g(ThT{=fTnZ*KHF&+qsC-*cYp=cba8Bn+ zzWK2EW}3lZ_gyiSGxX|X=ViaG7Yl2R&y4c>Br@jVn7tZh8g(MeOfurX&HnQ1n!oj> zW2e?e@#OEL?)|pNCtJj4LY<1Otx>D7!SGozI@_gmcF##WT4%0*dxk`ExXcEjoUoMI z!K*eT4OJc_rZxn}ag~ofLA6TD__mLvImGBr)&R%p5-^u7xni56t+h+{%J@?{a z%j5a}t1shCjdPYXGr4N7Z3`2;(x`EtZVYX69NRUSRyNK2yxYy@yLai0st%bWsr$>N zHO0g3<`TTsH#wHoX*Iq$p0sC9`Qg<^N?Q-LzAaN@qz@}LvwJ$o)pe(v zL6!5o%tYR}s_!m}YE|~)8_HBZOI}>j=uXvOG|g~p^W&Ag6e_jM)%49rr7*z@k=oH8 z4)|m~ZMyT&d-+EXN7upA)~Q~U^Lqb~&$@7x;HA?ceAiUZ+<5a0-z;01UH`*sry^gn zd$aSTofZ6LnPyi^1it1CiIFHu5cW4)aXKXYAmu>DiJWyi*_Da zqivpE{OTUQ3VZ3a-074(dp4ffKEZK{U{3pvqt=(TJ*A$WvE8_%TwJUvNKR{R&nvT8 zle3P+y5C9*-mM_+BQd$6-17V;l?{7SQYubvC^~=D@C|cUS>CkwY40e8sr+&}Z=Tf9 zJAw=6%zw3dQO@q62AhvL+b>9B8rM9F-lb%pI?rp8RYJEM&w|4tYBwY@52Obz!aq55 zdyM9}Fn5O`CAF@7s<5=3HZ@L}-=Rr@N_#-%)xOuWo^n+F`Iq}|4r*nc__#hMcB6x6 zeRsI1rh)Q-Ny@QXlq2(&z9PD*Y38gEN|z%i*160b5n7-$eDl_nFiD*& zT^C%QZlR=9tGyhv4i6E+D%Wmm|H?xREK2!cyLOY{i+vGOHSR}dizVHCnuzvx?Q-nTS9aFS$rJP9ovGcWXz zvFU2pA2nr_CJQGPOxXV|T}mSM?7oxA>l!Rwe`zJ_?%O(Y)-sDL`^QvdikUAJ#d0Gd zA>*p-!o`${g7%>)qOZH;)1_25#s&&kub6%KSz*?(xT7Q8US6H^DqmnwHNoz zd_O-lRKwV2ciZN}wdE_+ms=?oXT|iqTH|>CeZ^c^bRdwXdiX7t2mckBKT# zX%e6D!$#@B{O4aJ`2lN;k$nC@D3~HV_FB!-%a_iQ>L}c z-XFbuO_IUgsO0FDY1`M@Rooiq5s>o??_7Mo37{6w8OWI6x!J_t)9o*yE*6ld4?d5UHF?h7i4%$Hc*yLaacW3)%W_5r+ktl zFRohkF>_~7`PHc1b7sy^U4P<=Y|>V#afyyc+htRo##cX2|9*a3TSGuVW7Td=J@XBC zEO2tglr+663-h;u(YH^|i*_F3sI5Ko&hQhiRn989ljN=>_e9!lp$O(aRh}w6Sz*gA z4_dNZ)8TovO=}tBWhpUFH7D={eY_!IF3|B!s&+jCU2TVea2F%v24XzxaMc~2kn z`uW#1YT4)GP2(dQ8fJS)+rEpg!YSRaYu&rm7{4~Gdw9d{nZnjDXJ)&_CvBA-_Iy=q zoug2|9o~kV;c0PZ-d|H)?7H~}o1KanG&HqxY}l!#YPpSvcxQYP4Ye=|R>n!Ua@x^n z7w(9?dE0dCDOIR3QmNZKRmHMvSBAE>_Bg>q^Qf`0ieK?Ern5Bu0qR3l{zqfw>7E9y z88?a#jwp`yY^*Yx@@D7KLIs6E%9)}URNRi88S-weN3pn^f$<7q{P#go`hk@DcgDmD z3JMPP@w4*RNV>>(NGM>1sMcbKa0&M$`JCyiOuWaJd@iOg6(3zD{PD|sy%GLPRITJD zQgs|YN?JXwRp-n6`TEe$s0#@)!gYnK#x@`MD1g^kS04|zGj9F#_R7=A(SjFV70-&k zRb10j^+R2(YC)~{hR-iNec#WTyLb8L_$T#ymophM(M1eKs2iPb!Wz^Ze+jHkJiAu&xW=fS zFLtftJ0h<)pDwAbd;dP7S;DaH(8MpB#3gp*>fKxDXFGFy(ZO^Lm#fq$9x+WR+KT+( ziTJcz%$@D;t}|0CH{V#JZv8F#)3zsy_bRoAczoVcYq>GTApj@qQeveJUFl1F15@nB zWId$`G=_9CdcGMy9)8ZGwWOpZ>&H*B0tp*rI;udxNn!n^(=?4QHbpP*NKPFS)Y^7# zgHO(ku3`-lv6k}GDWdycOc*y|f>6yBL$?ECliJ$U(pKL-ywZE{mh_M{b+0(Xy?DNc^Qdw0#n6wBkE zyc?fiR2AE_BFuloB;pG}r+XYM%O+_m*2eO6irEl#vi zk!RnlG57ZBUWyQO5tP=hi;ZE!lEsxeiuO1ELhyX`a++C_hLQIXaRQRWDqnWFLT=kP-6RTI0K#q(Bb7HU={O0FWp~$2o8gn&!_<8KbuY~4>^`ue`?ESoI#me13 zx7G@blo)+7EoyzDPN&*lm$6vS|0XpWTaZD6fB=?Gu%@WB9>i zE2TOEJQKd{wMA^8){< zXw=F}O6SZ&5-*<$4JwR{o#lMo@5-jC^74f{VslIFc3LkUQ>WJ|pCXq1EINwXvuI!2 zWbMbpG}G!9QhQ_tWfW*tVfkeR)P3!;OW%|Rjk0~cCN?4C%h!gix`_-n7@zfhT@ z>FMA>3m!RMp<*jtQFbELvCID5S(n`xQjdD}%%>eF67F~ymKV~MN}=rk_+nO+ooun@ z8b1|}dg{fI!B3lhO_H)TXgP4dvvbFYQ%lViM`>&wJJ)W??J;(9*E>tC7pzyvjNbjD zZp=PK=216&(SQ#d?3G=l+dW@am`~p>VexiY!8G+Tyq(WhJv{QU>+FVfRiEh%l`C=R za7?*SvfSK1?)h5F*=bYnPSXkU6WuPkV10T_mvpGQ@w~8Q6uj{GYco%}>ecbJqfO8G z-4p1z@?zEVxE1e?=^s{C6+Jpf&}gM|j0 z<_V8i9i6@q$jPArgKvfCvlPGn)nm62Kc ztz~6ctmJ??Di{^tL%OzAme4p?2-(vOS-i|j;H*} z+WHA6!diDJh4FoU>Qg#tx#%L@^ttPJ^tO(S6%4mGkd4(j?|QHF$mZ>4OKjuk?>nWO zXQSWtv1-uh1i$I$E{&a?y<*FmjAxI|cfI*2uj)GJ#8F55Gsf-p8_IK>?-+@C4J%DL zuwLp>Ll&dw!#$gl*YcB-8=P*eKN@b|J~mx{)glWysj4XD(10&7+bmD<%schuLR(hP z()fh7+mD}LG8imBN3`ofp_+Kj@;S)`J#uYvadC>7yj1z?V!@#WwQ`?|bqsm#C&)`Y zs9gF~rHtNiY|Z!0rMXGTSLQ6JKd~{^WpkkP!j~QMwJFq-@9c|$%%We*b*Qc@yQ1Dw zc;elG=?5~)HMfo9;gMLpD=#uus_Xr;-8W|JesRayyPcwM`N2k3zCz&o*(t-CJdVoE zpQUANt$U`c<7cOcHBYTg^aPwYzIc{*^|@I1>W*(rAy>8UP9y4@-}W?Qi`ISlvd?Dt zh-ah6T@M={rw`_xl|J*r zSl4Z15)ZCCrR>or;<^01^zlW~TDMQOx2c5gFFb9wRm;;><;Fydxryzc=SmiDD!(^Q z?xsnNh3|CnVbvohKYhEyYT2Ww4)X4NDp9 ztQRHDb8Vyq(;h4us;WwDK4>8GlQOAJYSfd5K6YvnJ44&spMKiSr=V~~_9y>*W|#k( zX02w2_O@0tA(`>959Eq+yw$17gX7mtuG?|hqwaO>o$qgd;n-wUTV&1RRw1pzqP$2? zsq#xp7B$*9##*i)(^w-q|LmDzBN`G*@*L#9I?D2F$)e^@V=jy8!MAavv&T{DuZcvD znMO$RGj#v@!D-S=Zu(mItZNwU`t*-L8Dgtn6JkF#YL=9w=K8E!B~attd`n_v zRsq%db&RX&p4JcfkJEBaXG@Hbw5>O6omih*l|s>`@~Ph_JhzZ?{Oi2UAFVFeoXm^# z+adPU)K}X}-^N+TeSdR974=O_kijAWEhF>9kx2q=F4~h`H6M*pipt()aJ3|KOjttG z_m-cj!HX?uA}z<;!cr-IR@--6xnrNM*)ri^x1XP1&ym>9XD`I=mtFQR0(no6~?wcF5swP!F zeTM&_&YFidrF2?9QAIHyZhW(yQW>+5zzE_so~X7Gu;-R#s!(;-^#9j6+6D_Zd=V&WmykN zU7n|_=p&qO%6WOHr!e2WvlJ~#kyxxZ!R5-;vVz!=btyx}ITuf;`F^{)TGMN|?2B7C z%scNUZ*gCtbd80f{a7Deiedh$aqFwH4^PmNpqkw~kiK=0I)3#gXs&JTs-$&K)mN1V zOh{~Am9W=3^lF%JUX7}L&Sk#sa~3!sDLoN5=wMsWj=W*PcN!uDE+tVGQyaxJ0!`{R z!+8Vk%}|# zhmVg|zo|Otq!!$$cH>oom8#E;{qq>-Jf6+pzre`6>E_wd*L)j`WTof%4Ze2C=XTMn zdCGy7Q=U%Szu}^AdXuSSjP7=QCr0N|wU9QMR~nI$SC;QyW3H$^Y0)svpoYY)JLXXz zCGX!KTU)C=%i7X*Ma=B?JKUa~Jv?rGn*Y)Zbh)^}EkVt-Vk@uxShhyCr185E#kXPmW{Z{3w%vF~MF{LAlqmCt0) zGqR`@(Fs|1(Wlhtmi4V4ZSNFQ?T)3pq;3`*Z9My{_r#asIt}h`e^B$&(~gLKA2F=t z^T)5=6;^VNOZVS*QaBSeeb#g}M_1Rqi!X+1@qhO5DF_WzF<4~OV{plJ^5iKNV(P*Y zN~Nc=y^6Pu4)blQ9u@rg%pnM0Dwj{$Rf5W=ha}qAU3KrvU|8o1)ylZQ_ z%7(RNoxOSY*Q2kWCVxK{@=K#)^n$c4%2LrNus0r|fR}=FlZhEptxYzP;eNg=TZt4pRl^)zfQE+U-|A^hLZqf6tzsdGLkZ z3C-HKm!K|*&77h8>Af8MR-de|8JlSs+A z!#;H#55&}>ntAirHAvqth!G2qc+g}9k?@}je z;r(A(t?WUEs7tBW@2RKIPOeTDSt_DZc7Dq{*(Kjbx6?0;Y&B{=^LUZW^F@xiT1zKi zeB)fa%ig?h!OzCw3u5<9YRrtD9Ol*AYh6aT*PQ1LlQP&RbE9fMu)fF;Li*CG3l)B z)zbnwKF{ch($)NPXP++GZ#wy$(-+Z-jG2Qx#4B&4ytG;S=A}hm=tqs&XO?e1LJPU; zvU87es))>I{u%fh`z_VjnyzrVK5-*O;EDf}GZTosdvEn^5WlxqK-DS?s)A9m4 z-Iw#_mjtT@D$zt*f8gcupY2tma~HQyy7%bFI+yC))rZ!&y0&fDy!l4>$?czCn>P3C zp6y+$R$NhWy8Mfzzwq~OkN0UB?@}s$Gk$`l0JJ1@*8bY>4}VJ`^SyH~B;a2wP>_ z-uiLs+1EFf8F_2J3|dsMRyu5*XL0rOm}+KcXj7Eekf4;o3C9o1*?}7-b zYIc5-a7#hLx$zsd+Zn^gl?9#Cj!T@`z?&Q6ykBFl_IRyx_jHC#Qf&G1e8vKioR8gm z#s%muD2>|vIysE$oM1C|u91Aq%vrOR&MNSnIC=MVPXT$s17m_yBBy-6>^e&(W6_GN zx#^yso^>q~Y@WKWd!b|0)b79O@X{Hy;1%O0mX7_k{7#w4YQ==jnJ4)at77-3ORRSu zyxwqs@UQK(r2SKQ)mI!k9&@(n_~Xg-9$zDEJid>uG#Pw9L+awEmPWTP_;>(Af3$63 z)OOSHTefUD`R!Z6^%HM&y)0H7vUE`JU<$X`m;U-bw(g<)`iSm@)F>OCs2|^!)^>L| z)m{%Ab$LN&e30-_=aLdFYVJlLXPUbC;~H@I1+!@|~({ zoq8nqX^W#flnKE;?3W=X76>#P|Ya)wpI$h!W$lER1BK2DS z664$ji&yum&#ua++Lt%+g^&0ym>-;f@nVg=X`;;m)mh$4oqT*=oA5t~im=IbzVm(g z^5rwOB$P)r)m|B;9++kB#3S4=?M7wBW#2E)H|6=gAL(7&A+oOJm4%RR{qtEGdFzG_ zZGK(ceQoTi`b`?wyLv+MyBpS4?3pPZCdIt2--Fh)$deprD%ZpyIkB`WW+`e%A#JkBiT4e-REm|b&C+IgjX}g%k@&Q$LjKQr_%J*t3T8Z+kK|l zI`#%Hzhn8%(bm_3#Jpd2N{)Sbb)ibUQ0aX2pEC^{6IWRvo`u_Zoxcl=X zN}dh%{qdI1R?UB;@rTNrPfb1WI%0S5hwAzHVF5!IdD zl7A<);9Cy=#P21Chm7c$BGoeL)K&$#SD#~|8l);2F1JN%u2gJ!5)((MNqksosweD{ zyFqjjUveNd_j2adH`=O!(mG<)_-ExJ=c)U|6~_lpD*st^R~=t*nqrsDZ>!**Mm1~R zH`+`7FtfDe$df_B7Kis*M=_77EB4GY)#j;>veOH_H(|7O(4DtQYwHypzBf#%&UrH{ zwT|BWGOVa)c0rG9Oix@luSRHxh<$kbiE%|%_Tk&6Enp5#8dH0_(!;9t&5y}yd0}&x zO|yx6besOB`_XORH;oqH}xt~xFv!>YdOlBwGD)uR?InRqXMt>oCf^GvDxES&S! z{)(_I42U`T4X2122h050w=T>JZ=bSvL7;R&*bhB#?-Z43(|q1nj$?chl)d}?;>bdJ zc;)x^XU98@4~aiI(a@>0^EnRkEbkVcy*QcAVQx?^=yu6mQc)_pX2cp{NxG;INCbSB5-Tzu? zW&b84yYSuT`@^S?nXVKbP_KT;(>h_L&FnW_FDCf@su-2`tyysI{JbI8tfzRcP?xy& z^o)$`)9JQNMb~Z*eN(XgcI*7|+dogpeRwtJ4(;2NhM~88+dJm(J(y}DIZJ!W+Fkn= zxis4wzf0WRdS}M^JtwEQkDM9&Mz90x$LosgH5M4Wz3!>`@m*Qsi%Q;alB0MQX#S)K zhD=R8Et)#g?pW%r`it_<_MAB3GV6}qXF*!WM{ zb#>*<+aor??5orBcvTj{g~wbV(S!`RB#Jwx$QdPNj*(rCYNdf1JFyg?3%{U>%OYKu6uDi>B-m2Gi7f|9GG`gUp4#9neqJRqHc@xecCO?-+J%O zzF?30;?gh932wS{_IAv(r*Df+d92-g@U6h)EwMJLtL~RBUGpSGqjpL3uGKwPu7xRY z&W%2IZrD57G`~#`g{M6Z!P8U)o5y7H)79lWI%z`VtAYugKfY`V{H(gF=Ao7K7(26~sO~4vnm%?Lb$*c1x8|z-L>Aw7We#8CnqvfNo^VkLs>X zCS?mxO%Y5iFzT?q^Qr>eaNO+-b2Cr*TVNd<3r$g~K{ zzPo5X=ww{aYPrPlQW1YBVDJ3yZP<#1^c*P}zB6=UlSN?Ni>w=CzJ`aCVt8+9^4NWy z^7_z~icfdW^Cvd`S|$|C&p+X!#b(ddlkW?pt~B}aaIC2476DPsdB)0iV`5s2H~7le zg(f`<^+|~s-MUTby;6ng*z}Cu6`Akm1~2UydbcsEl-elR zsuJb;%fKho%VR z#+|1lMm83;ARO57nO-9CLD~mEU6j zK!0aFpC1yg-+eN6OD)59$7ViQxs%C!o*(jkkHm-(TV0hRW$xGP7$SwQeI9LZ8a+RJ zxcC&?ldi*`Wxt3YQEuh<L`H;uhlo4U;V0>(GsP3D_Hp2y7HUbpFR2T z{-Bv(RH4RAy)laNIMTP!(A~dp-@b{LU5DCSTr>TCbzWe~i4*Sh@&f5nhIDE7q6?LY z4E~PJl^bJP@F9?|w{~6h)x^HHx<>uM_Xz7lhIb@NLKh?kUawUUH?FIHynaV|BklUO zC589zEgNI&IPG(j^x?? zgk76%mAnZ*!l%Ce*G-zqK6SB2$L`;(y&@cAClMYV-*=0PmriwbbPT*^*L}e-qMQFZGrypqz-zmL>E4ku z-S9sVZE{ks=T*{+pD`pS&G)I!dGKM-nH5p^27Gsc#!ETPou@bGTXb&kSa&2<;M^MV z2UR&gb}5vWmRD9Jj_W9x=3aR0diRkOfvCOn!Y-{`vgA%tNy$60w5Dlt#)}sjENOcT)i>FC!UWGz3nn9+4;o-{1eBoopN@5O0TA_`(b3RS67G^ULqddy_=sJeW_>O zCpW2}5kv7)T%M1&)Qq<=Dc(55!ytA3nH5r=vuDqq@8jsW_El9?t7U@t6usP%wvJJ8 zr+gOpytwQWwe8@I=~JhkjgFq`q7ktvx@W^zhW^BJNAA&ugq8$eZc8j!@Gw%QF3Pc@ zJ0U6Q{DrGQVtO;5T1Ir74P{jSA7|Ki1`7q8uz zU&k_sE*~S4wmeRdMBolCI%y{-B(WnTKX)HQaM6hlIKhh@S)%U}q~q@IZ zxO=(y`2-S6nLeX`3EXufRUrMuttUboC=mM~f!HIb-#Pk{;-Zm0{bHoUk4(d-DJbJ|8o_~9Z}AaqXq2w_z(nL_B? z^&vlxL;`w6&nnQ@*)hO{;*UXK=I688&&40&f*d^qdubK{jsb!G6#rfz#!h;jydg zqw%ZtW#E?jJN~DB{%_kq$ELXLpV$r2?|<1pXDo2W1IPdTu6?f_hjJ0J*m0s?ZoAFo zqH|@ZZ0DkL>PkrATy$=|ui>I|>&~8w&YgcTo4!PE-BOm7Te|rXuS9H}ZP#3u-e>(B zBlm;D?;{dX(`WrDiCw@y0Cye#AG1O?!4NicbP(& zuD0YKQn-Y0MI~=_F-33*;G*DaECF(bKkHBW=)cAcR;< z>>khXErx$QlYi_YCH?)ibc z|J>R6O&y)wu-@e!9asuEdg3SW`mcrj1AKlvyMA*(-(rfalKxyvv5Ud_sDDYV#a+w} zTol-y2rfxnGPo3RDdW<_Wq`{Jmo+X2TyD66amC|G$5jRXMj~T?z^yZqEQX7_{R6PD zNNh8pc;SxN7qLlBe|dA!NMDh>K3p`8o%?aoIQ1a?z>&wXb24-}G-Br@1mfb*h#itL zg1BhHh?5Y4i<6II2ccXvjtzuy(KziVK9jL})QwwBc-8 z92ZRjaS}G+;_!0TvhiFrX_5(HD=tnx&e$bL${J`~|5qAGC-TT%f)giwPvRrs6UZ+{ zk~q1ro{lDYN8%dArU6)ij8l%j2qBMTL?Cod|B?G_E;_mAgiJ0v+3Rt_W-hu6hX_pK zqH}D9B&T!H$8hD3=c3DU(YfVtm%E!QKewC%Ty&xXPB_Lzm*EhBC%NcEZ=7(Ri!R3@ z0xxmVWw_|YTy*qHU#Q@sbL^TV-sPfm``bb;I=A0G!$s$eOCpE6U%2<1+ZB@7_g`y_2WAlZT5lg_Y{$=Hld`?GvmO7~o^>;)?BnTVDoN z8Ykm#G05iP$Cd4mQi!C1O8PATlgB!Lm%d{D;9u&y+RxGXk7Q0Ym$~@4yN3J|tJZ3F z?*K~||A2qWVBzwQNeexF{9W|i{an^LdV2m7zfqvqDm_1}#<(;5Zdf0+-%_%7b45sh zY_9wqLkyjKytSMH+=H+ubEYh@2=Nba@v>wmsH?M++qov za{+!XF1@Qldv`D|WcTh8%Ragx$df1}k>cdz8R+HR%lNzACO%G%p4__WHL~e5|FA4B z+Z!m#?ZXC2|1TQxvz$4Mub2^-0P2(Ty*aKa$wV! z5O?jv^4IMCA}0YxJ{%&2vWCQ6i9`Rhzqq~O9~0C-UCAmD{rOjkBq5n70D&Udt6`o| zymK`$&|T3nk~y8sc*NDJI+>bS{G>nVWHv6OPzr(8pqD+wJuv=tCo_lK1EZ0z5tt6_ zAatN)T_>{&s0eHX#=q@ks==9N0nLDJ^(Y4z|E`l6jLt}J=wwy{vp#e(6|o@*ZU#Tn z6_sbgPsm70}6cWWKyt*ar=&X0;}7R4pjTu$;<<$1M7f!K(Y{T1WE!WJCGk} z0JH{LcXl$1fMvi|pc|u;sf>+A7SIe>-POrV23q%^e!w!I2p03!JPf8AFdZ0A?x_rB z9xxbK4J-q;0y}^L*rd4eGMENHNj?TM9as%40|pObFh#KVj0Y+L%LEwAXkfY!WiZVM4r4Ggfmx!E0~8pJa^TS1MxY+R zMsWr+85k^qdH@9^!4IdDHhXn1Xr(8}S;E2nLhD zG{^%Q05yT}Kx<%@GU^9Zn~wTpQz5CsV5$MtfM&pIU^=i7m;+Rt!C+Pa4S=n{GN2k3 zv1&6RkKioG16l*~fNsDlU@))|7!Rb#pxrQ&i*a)-+b^v{W0<&QkKuKUGP!X6% z(lyW?S>&G&y#XZ`ARjOtm;=lMRsjvP7);4=C>N*(%mP{it#yzO*a7Sy>AKMGc*xOX zFtdQxz#?E7uobANk8uxu~% zrVKgzV9!7`U@|a$KguQaOz=-fzSBqt=H)<7!1P>{uLAj3AQvcb73sjn5~KswZi8XgGVC4LU#0mVnkm zIEPY&o(2Q4i4_=vvnZe%&;V!+bN~hegMoR#WMBs{kEGMPnAN~)paA+gZz#^OfCeI6 z%xGZQDDV+IOLsA|fa$;@pulLHVG%t8(}7vQYM|s8)B}1p7>jc-U?Z>^=q7`6vMG=w z3wc0;ab3(Zaz7sBPDQyuWuTjU7ty?G0#(c4U`*!dIPH?aefF)kAj}(p&XzZP%RpI0a^pyfWg3cU^*}h zm=y!LK!NqB&wS_=s0l0s`U0)vpkH9t29yg7-h^@&puBk0li(J#7pRzs{?bJHR`3JU zfeyejU^K8Am=5d!<^ct^p`KdMKhOavkc50dH((|(9$1BZ@q3UT_gTPdU^TD<*a#HS z244p311Jeh23GGyK41s1gQV|6zJ*8!DgqUOnm~aA&;z*#8X#ZUNtBEG4qzUkpF;US zH6VF_Yygx5x&f7ec|bQ{888~y2uug6okqU_tAS-e#WUd7g+734z&xNCuo~zF>;Ogs z4bGxmk`8Po=|BNJ)H@qz$v|tM8oAE_KhO;r53B|j0Xu-zB>f!tfoebjedrH}Z^=?R zfWbh?T<8gC4a@?j1B-wL=fO|zfg%Rb&jsiOC<$}`ssV$6@xUBlI;MWFL;e-$3-^k^ zXrLM}9q0zk0|o96SM~?1Iz-d0n319 zK*?+12Py(Hfd;@lpc}9X7!Pa&Rs&^Bk)98~0CWTT0<(beK!F1A1FeD8z%ro7BGltL z@&id2-U}3-P;&}Tun5nn!TbWrJp3YrjwKAmzO<7$iJgbQ!1*Z@Ii!*N@kcsYYYPfp zM2{|MG*ozMtv?0#-1w-14x@Ll0?;}OK#)Urps)lY10)G`LyWD8wY98)nfTg>8(7x4{1Vl zHPE!^ipYb!;L)ZFXbF?T5a7O8&rDm3JDFBIklWNNH<7AEm)yv!MVE=C8PSUpCsH2> z(Pco>>d#N~F&uoFXwPUOkR1qJ33LO{2XTl%(oP+Aeo;b)yjZFUU4X<92%j@MotqEc zO_2j#4f5=$sORc`YrhU@zYg7(_ZZJVG@q1HLF)IUlQ{};PMC>EBIstIUq+l}!qJCW zpFVWxW>lL$v_bl`1bo%t8v~?G?&aG?)ul^rCH<2~LmzD9)1fQJ4$^~!bRoL34qXu% z=I#|s$Qg|GWn%A@Mamz%kz0g4a_VSvdgZ?H{ zD5So_dEx7x!G2i!?3MqQy`#=-d)J{y^HA^pLw|cho-^bHS9dbYVOX^9ngfp?mOPgI z=+iTKsJH$>9`E>pElYl?|qisjX(%lHbh29s9rU?g@& zqrpcZzb9$$apXrIagRfNx-zdgij`UTdl-`Os{uX=_U7hz7#w*SS z>=ExB=hT&)fi4G98_Eqvx&z|037Qy;#1{kz(FJscSFke@IRTK9gM9zwFVfiQ*fR75 zBL6h#W#D7^Z*JWy+tMW$(nX+pmcMz7d{xMYEd_<5PZx0m-5F6Lw-IzIvF`*dxS+Ma z^zz%^>eGFx-2F>ufJA8{wn0p zM0T2JZ@t+4Z9w{4pY*p5U6bnbM}MPth(1feul%u-iKRKaU*OFIOoWZlZViy$A>9n= z@~|h;=B-rJCy`f&$i@hc6+^U6XePEa`6#K*qyxe%Qxnj0ePNUcGX-#{<={S2^7C8S$Sc;L8Eu7SeCJy?g`r zn-Q5O7885+`5)MG7vwg6Vb9yFdCQk=rLc9BTY_`}oPAv+_3g$2pOwdqE<<$?Vp*G( zuv>3LN0{`32`0UC;<_ExX@zKyL({rLP#2&+0qO z1nj;uWZOmP-)6z`x3%Dx#F^b0cE2Z4Ee2Ryuzh1P5AWK4(HYT)k|6pIXMVY)o-Dhz zB6f{=nY!%{vu4>14fzGWb~3jkJM9515%uTpZ}>kW?rB$F_^)Z0HJ*<^jsxVN`}+d1 z3un-+L02JmvA$P6+b)dA`bn3ppJ3Y?2eI0SWe*SUp@G|I$XP!Tx%rT*`Mr~QgV_6m zesWpsGL~FJB9~=v`t%$gUcZ6m_W4iJ&z?e<|Jpj4B+dyW9tV06=x|ScfzbD|^K;Wp zK(_@w2lk{_5kyXFn^Qb=EfolB^?uz9fPD5TR{_^)Mo6_s^_eleHTHp91{<#Tq$+H3##Cv`DZ+}nL7Z;EojC9ue zt_KHKtn~|AJk~FE?3sbcnMud^L%xChJkfg>j-9TEcyB#iIn`jTx0_H-EBJG;PNI!NIV^vS^*Z-Hp5>1h5_>hGCsTQ6 z{l`9jIEvbfat-JVrY^n}-doZbMwv9~sbxpl@Rb>C=k@BmQ3cv3r#G15e129L8X_khc6WCXDEmgN~zqvTl;`Mz0Y1W6&w0{pq9~O`t1+J`#ExupQ7t z>>xvW5nt5b?O51rnYLh^Neo4d!SaW_ea+JSZ(C>WAy|E_hgG}IfEv~oM&~U2OYuZc zX^^iB`A-q=)f47Z_SiP0=kSGdtBHLcK-ygazH0D|A$;sW+MNh`9q257B!&kaf9M|F z_di;PDT!hKhi8}E>o77tbU;@IU4@j%8e=YfF)>@pqGEu;jAWr>yf3 z)*e=ep3Fnd{A(v<{|7~%J;4xtb&>XsW-!Mg-fJ&?=E9mkN{}9p^k^j0y3n59`NM)W zbFgP3B1cCY^+Uda^iJ$M-k8V zWfAYKuYI3gu=*eAYDib;OLy)|Cwfdnx&hKpq2p+)IQ{d-JjLoC);w)QkLLZS{Zik$ zinOl@ax-Pw{zau%F8BKIf8t+EAZMlo&NCq=5^)-1I(I++KC6I=mi*DDdcrtkA_tLu z2Vq*mwvbT^d5Ys0%v8jCZSjw`{@x=kfnPC)pZ?n+>kvPUj4(3p19zA@MMDzy4*6(t zUr<8K67*!y-3ax!kHP$aHSbcoB)0fill8L50pgIq3i)jaiM6k0ohh2*paFvi1RQLU z@=haPUL)hL=NBb}AM`1NpB+g4TF@Io2lNF(Zv&wf^ih4(UcWY23i=0~yFH|Sa-hq6 zWY4F+>$jLLW6!A`>m14i`P7illE`KG-w+HHJz)zpmgvP3>A^^k=u0=jA*KP2P;}@5 z`oh*MBxwjUaqUI^GUTr%gx}?wf(gGTOwHIOwNe7>K0=Vw~+G;Us) zB2}v|yOuE7f%M8@TQn&*AN)n&kAknDZ3qAFK7<{{(pF+!TqDFiGiV7Dy_$@KJ-~js z*K36C3_2Mf6A|YGV(;Og=Yd{Kh$w@7rUpCVezri}+iTpgUF2b%jp_bHVeOkMAWsc; zB!P2Z3O1pC?U{b>bFJYmd0$Wmnn_7zde0@LVITtX3}z4^plt3lXqL|*B0@Ed?%jrhF`Wo{YVzK9nW1V&U_9>?H=wZCZ124S$?Q`Pbyo;0v-scc|HbFXNI)lke$~Et&N1WKQ z&v41gs0F&?KEuU=h1lOa@K@oTEAIK7$n65X40Q5*j;nuv_l*T))<7mGeXdozcLF8+ zL~h3n1~UPIX+JpQY~heWhDp5JXj}Ob2gUO9M)6J+ahgh@dI{l4EbGw|3rW4gN5ekm zF#7#pI_YN(&^1BVB6icnk!wC=kO4=oPAoswYpMu!@l=Wpk=r}|D!^y0&geZyg&Y!C z?FZc#bhgW7(Jk@!2qcZfgUr3>S32M~_`zVBP!7!=`F@wxPq$c&^_yDBi8iq-8Xi2g;$6tCh;!Kn z>KW8$58A@N<9N)>;?n@1!A}O$iSVIJwmq7Xxfs8yz#ik;!izakWFz$r0ADotLi_Wf zu2>(N^)VU>Ya!mdSnhj1!_q7GtF#%+Ij9FMVKTeUf6O~fD&_}+sTAI7-rkvq6xLh* zUc!%eYwy4@&{DYg`{oy8Ok6*Br)pB8AV8JYJH@d0iJi=p!}AF%22-2euYb)Mzt;eU z=;61RG5+2_7^CtC&bX9_JiOEE4yQ`siQ?tll<1Njk4 z$gzbSiVytRV943lPhYI(bAP-yrBC*;a{L3%+Z;E?I>)^Lxdvej=38FK73>{H|I)W6 zEXkYrZ`!5|j@bZ&(|M46Kn^4HHgq+}LJfFaG zY1$*mVfk^R{_7%M86IM;hQhq^w5cLCSb41^_w3_K*8JKAImw&)_cPJ!1<>O`e}(6P zv~T_N3SaQo`)Ee=94haG|IjNLFM}sgC?cs0rVd%Zs`u0DZ~MmCYu|f6zO2U%0}L8{ zmL6=0yfnPqPwYspSKdF_kr{P2)QR4Kcj?9@_wa-Na=&&BWQWG&{k>Ga0mm)-6c>GrdTC(c6Mcfg zZ0CbqYVUmemmR|9*!sfrXDY81IY%4l^aAooAni?qT*Yh#bNXP&T@JY%`!VCJtKs&F z&|GUYSAvf;w{M?f3;xH1{~GqOq#uQQ*DwF9_j3d3ojm*fvo}~f3R1tB*dTZ0WB*En zeDdP@K=T-J4H6h4{bn*l;c)N=fWNv3=M;m$KdqPlU-V{%_se*h5H*0IVTEiv;J`-0 zdU`yMF80qWfm)D(l6(8D4dthoGMH8ZD1TnR@_*a;Z$FM_;WS>Cf&E9H-ibY!OoIQt z$6ziYdN1!M_xHHumJ7dhjkN1u{1TCS1ah;g7|eOZ-&OUKJCOb25e*M7-@yBye)ii1 zxiYN`=2$Jr{n$_L?|t%b`^EDxUS2Def3NRMqGPxuwMPu5AJN18-sfKIH3xRRu{7S% zXmsDs0t^V!xZZ&;N4bkhrj6ct&xx~*VWrbBbc>Kq?@Ryvd_wO3~=rP@v5V{HW{C=zaf3qhlXq-5uC( z9`gmv6Q^6x4J_|hsJv9qM^fd!&c=UJ_HnG@1nWz?;Y_XlD49>onD4=ScXqpTQ?R~r zs#o`<|25oYtYCk;byElUw`E!RJgzg_-6Fjd|74 zjq8nmfzUKOS?&$E>h?%EbM|g_YkA&|9p*}n_VKC}?;FZ|xr62MSdNDS)Qxk`zq&Hj zmHi9Yzd=p;S@xmNwFUXEj_o^#yi~Al(lUKpIG&Cz&sgX2JWjivSaWlA)l+GizB4Sp zg5~?OTc?koyA5;6_5R~#TU5$j!AtnqoBw@2$o}L6>ubq!J7s_J6t~!O^Vs11NrB6? z_cpYA3;bu!j;XCr*>_LPw+hh5W9zm5MxV^* zms#K8HfPQ*X1C7cbeYFN-zSvi`aa7KYJ28vx|Emi!f#W(K1;nN?arKiobTQL;&@g4;yzuyL&ndtWDwLZnNJ;9 zzKZ1^mGZZ;Jh!WH^3hPPeD8di`}u$tpz@XFeRrJE`v#X7{pjm_{cGu$hfBWi%vmq%kp0du=Yy(F%UkJx0{+}xqt45b zT3>MtaX0e*JBR0Kbj>BhUBi4!=Ict9^V7O-+5!H7;bb2d$$ZiMXU_g1*OfClR<6HT zH*ndGlixGs%I}=yJ4AlhT3%6Fmk4e2`j_<_=KR>jI^9okC#~86e>`#Sy*KA8wc8xO z2w%Gis`Rs-9Fq=}Kljz7U;4-K6h-=XWVcS|Gd$P3FG4_aDUvl`s{F8d;F<-{KUB0h{e_%M7@580Or_P*xi^nN#mWWz1JG&&^Wt&!Zf+FrUcZ<}Z;v zE}5P~Qa|$-nw|!?aR0&KF0>pT;c&6fo}Zpx%qKE$Er;RE`zQ=PHo}PI!ehzn` z<*<*#$uk^7I=?_j=)d29WBiupg8zfim1u>^N5MQz$r_>X0ojvPV>&O(}cxk*t9QM*Yhd7=<8y#XqBK_(R?lf9za`QK)kVqZL!MhJcx`=} z^#uAnModhg?_$K{1R5SIKIOP##i~Tw8_%tj6LQ)0m+>JVVyBb3iyIoYslDAyy2k7#XJYia&Y65W;7GLdvLRO!%01)tG^iTq-hT6JnPUQ zrC8&-mlEA7*12S!^TB=&@uiE8br5Gl}cY+or{Q?34R0qmZ1**j`0MP z_}_P)aS(mver0?V?e(yZL!Q~r(~*=H){SUPxM1hBa8VjXABKxnQM4vp%#NZ}5iOY? z9i?rJlt&LHi`MioBO7&T0%K$Gvy<*mAbL*hb@Iu2Vy%;QJMuX$mWY!Qt;9wrEp|lB zb<$eoZ1YQ*ZzG0!XrDvu^3X`9*yf=HPO;HLo1Nlq5B=m6UwUY`Tl!9w=CU^VckxlF z;-pjLxM`V-ou9e{zvg*bI@vqA5#v?jbq7sH!mo{ErjaOfQXB4ix`;oWG(&nVc8DLG zd=dydzjlc4o%FZkC8Z)Vf~ni19^`tV?yr$5yNMBk@*E;Z$bhHaw9_G~-SoRdEOyf< zm-PJ|1ue~pl<7+mj~g9PxA6S~BF90`H&ROLyj09NRN{=8#&yXh-}mQGv5(3FNU9t$ zA8^?sK~YUOWcxZpXe`oWRgLs*cha5QZFUnUoitU7e&7&?oU&~a?RAKQPCDfnaxQ)T zhMDv-dr4bmEx)}{&Hc4k@cl@Kct_9@hbR!V%OR!&AIZhFrpecupTfmCu{ z0%IpQcyYbQ(d2I@Hv}yhJ6UqyI-0!hqUqog3LRW8=xdi4E$APY_{B}b1N6RFpM&-g zJ0oSHHb>G*hnN$|D#Xl4I_(gDL~z9y8zSheOO!_Pw}oPDB&~9bFCyuHTg;E7i5{^q ziV8epN))a3h)GfOrAOpM(Tou3E(#I9Mbc*F{whT5jpQ%vZ(+VlRsl{`OcS0EyeL+< zsMIlntqhjXsJ1MdE)F28l$5=o;%1b=?}L5K{sK1943Nq>e&ZKFb6L%C6hO81&j!N2MAO{l1hq+deCwn$nO zsZ*LNQ}L+S;-bD{y^CHI@4M)jtUDu|f}hgNatc1v9O9UhhB`;+s(;1Jv9j_m zchf*|#!Yh_FCUd1C<`uh3wCl21ke7+1n&197SGXOEud=i)uNB7-5cEUFp`_ZP%r(9 z9X-Y0UYZ~c;QryXmsUyVR)_e@OUI>?OX;MS-jPXM>=b`^X|HrvI>m7wZ=^X~Z-3`t z(plybN4-=nog>`hH?K66Xr){H;-w1dJn9xddFd@#o#zShqn9>G=T}1f;H9(DIo>0_ z_tG-iy{++x@4WPrbpGiP2fXxl2s;;rh;O~LOF9pR$PsQ-C_5*Iim$x%nRIRm6??sO zOgdi+6MMWgU-r?(VPcn;_DSb2VPc1u-Uw%BLAcoNrBdnK6E3!T>9ll?i4dE;R3vNs z7ZGBkmwu4W6A@y)m!`?u@ouD8=cVn^xj#~@@zU@pc20^CtGx8FbZ&?eUwG+=bp9PB zKJ(JtXm&1%7N2D|7%e{b((5tooDm~F^3rPQ+z}&|d+DTf=EjPpJd($<^OIPy z*h}9@XH~5D&`bHUdwQpiSmdS6()o2AvCvC7b=f(gu6Wl=%cXN|T`}KFKTGFdb;Ubg znpKaTAJh|by|i08zpp1|dug;B45q}1Szh{FI=9A&v0U=fIW%63_R<15JNPJGyzZrM zrSsQ#F_QB^wrIY%YR4AJYQh!y9Vh+c;QbQj8g-oP=3;Y;l_69hwsVdC%Oehl(C`qk zHH6*|;Z-zCz2m@06v`t3(bM8+n5v}X9OAbySsi}~qfZ??DXDOXpTgwO@?#jyb@H>~ z?N0GS7wvCKt< z$dAP9IiO$gGpsJWo+#ish=a?Y%Z~FZ=pXw`zr<0`$H6kh07tGv@N+mGV)WVEsGk>I z&iA*8txj6*5EV}P(Ghuy^F`)}4Byysk&L##nBZ{m3}LCmwcZiF!y%_(N)1mDE=aDv zBQ}vkUM+5P+$!4AeOimwQQuLg$|+7c9g|#Qii_sTbaS3b{bwC*pFbEeH=YhfiUsjB zH0oEuH)rdL(RJSF`*uf<<74T{TwDPY#YWS_(Kj(7H8M~*{m3#X}0kr%>)_!{Sw zP&(rlbDGj`LQHE)V?5&1rgF~lUQ^k1bIT2x;@|)|VdAT%R1hWuf5;tjQ`!_JHa4Y0 zVPb7lI>JUq(CBbc9!_h+rOb>7sb_hF$Zbm7BgF4b=pe6tn$YW!f{*)M8YNaF(GSu7 zg-LWQrXjm`#){*O=~%3okwj6cos-n^O2$@VK?tSaG?xbhhj=rDKIU0q2vs`7K9B5&z73)AF7agu zr)ZD!qYxS+D+-6bsxhNqjCb**>9mucxo)hVCpJfZ?j%RYT?06EMM%U-b-o@Wsrv-?oESX`e*MTm9vX=B6;2UCY52admpK8=>a%A>{G7tz|7>)Aaqw(*|& zv^7@zS)ZoW5lb$jm30K4UjKt~|5fJ_j(C1uIU9RlPJg(DzU{b1OpWF`%KHO@#cR=W zFNEvLMn}VK(K1I1qxn~!l9}1>yy0zL_qe3*uiRE6X|lVubi1$E%=Jl#-=k=)XvEA< z;_*XK^m>StoE0L*#?S`k{v|}@#n9YP$$u7l#W&G(G*nb`)ee)PJ`Q{8tr%Jz-jLl@ zoMK)H$=N5H_@3i7c04MMM$j|j=LlNkXz)V>9d!Kb%Ltm`66`K^iOmr_Yrmh}TioLN za60Uk{0JdtM##zftO)v)r|1#1Pl)#;=tm(wh>$aNWB)A9XmS6RX~=U z-oMFXdIGI*h+zqGNanfeUgv1X>3BNM>%({&?UqexnOm+#cz5j=FO3nRJb||Gn$SxJ z#Z@~JWRJ(YXkU1)V5ZXJpPfLJA=39uh?tQ;3qzk`_tLP2Z^hF;VdCdFnxj?)%fjP$ z27W4B&aHWHoaCiRkz#Q??Tf6>^0`ssF!#5-$Cf~gV@4Di2J=#!L zy7$+;>itB@uP4SO(kJz#5kJ)vV-o2H^pKCo_+_8Z>&R!tPcC|mmtHPek4C#?4@p$* z5L4Zh>lD-7G}9?&$}Kf9i#G*i^W>E#Z^q5yxtm*-<2!D-VxG@CaA><-Zn>COkukrA z&>xN?Jk>bLE3^>Gk@LF(x7Zg#U&}Xmxs11m$aVCx5V;pg^oI~%htOD$?38(q$CE*i zC=a1;JYsi*rOF-cMqKMbfuqNf)CN+m~ta&qm1uc zx7Z&+$K7I7Bz-6&StG<(5pq)bc?7-Y`HaJC4H1hY>H84zVI;jKC%$imibauJL}DQm za`E<7m^jU~E=*KJP`+HOy%#QqMp8+*;9u|99iiun-#OZ_&;4R+3_U%{u`Y%;dPGhv z_ibWSEblOh&thn|Q}EAloZwBf82ZT7jv1c$E{~R(vNT#6$?geU&!cI9kS%-ycib_w z&?8RA&?=9ph@tr*lG(%-^S%YQ%~*OfRBB!nDpqhy3>7nDXmXfjio!%;EUgO@vtwyb znAFUR&p%mnxHuk7o5KA^qGk188BOaW8Z&<^LX3{4p^;(>?{-8=$=#7ncgE6~D6t@x z)<;d%`!0`P&WXH9ZoRgZd#+uitB=^=mWz3I@{Z{m-j{Nuu=@`lXj-lT4zKWIKEoOS?L9yIJLwR-Qk^6k?{*t$y1pVd^TLteB zihY9eo#H1!@AHyJ$bp!EeHh!o>4&)>^7RRyspraAViRMUlf9{Oo{dlJs!R~6On8q;G zB_=T}lnGeL(`$Bbc3sYI^0>vq*Btb=n?rE)+u6OxEjBS6k+qU1NXyy%rZi(NFAmwg zSa7hPh1kXJksc1ln`JxL&3zrO8I9arp?e78GH1^6vYOy|3?;Ub@5 zZuq5AWJ9<(`6_)EK3Ij05XWAXRb|(!yfvZxzlapuUgh6i=qLSmM~M$#rDIXzy;o^W zwDSKjT8w>_Hbg7`wJ{?1RXP|Wetd;a#VG$-vEtw>v?5mdFRLTgyh3~Gh|gc4BXuS_ zq|OQT#H?4SsGgYi3T>;W!c^B2r-#tQxHi&%f1IcuLTBT|-XZi(yx2KJ?jA^wjqzgX z5c)bkN#0ELiVucRu~#K@r&mlELdU&g%n%xvpoHfph+kf&<@#oQf~b6%zDZCarzMK@ zFVoUQ6>>+SSp6~`OB8corm^*vF-z-LprokU@0kw#pm{NKDx411A2 zzD)V=y-fTwnEt#>92iW~e2OaeiLVFKUZ416FrCrVl!l^sFn!!mOdd@88!D+&4aLO4 zG`*2HK8Q*hsf;<^NE{hNZ(c68528hvtGL!)E;bFKa(#37a|K~Mg+CZ9mtvEe^KD$==Z@E@f51=F0D*tiK#NGk4 zsF~O~fOa%f{uRx{(g8H$I^{q2I`P2(T6>+CFn|tUr~FS|C&mn*smaR!qh#?*fBG_6 zRQ9Jc$;yB1^PMfqQ2tw6h$a2#Xba{4`i){zKldsG#Qf*!tDD4}=jrd8 zl>fMvV%YPvxTW&n-ctONMO7`ufh>N*O!?2fS$v&E>uy&5-`^}g$)e${L~#}^Xr=r= zY9%IT(Y{v7|5Ph6F^i_(B98Z^MYkybFK!V>`cl~~sxnS!Ew=Zi_ggFB4XwqdzVuUT zv9K?Vx>Zs0ZWV=nY2B@2WM8VdwV~`k#@;4|_NDi3>nU#vZWrJ8p;fnw{e9@`+m-&` zZx>(mp<#Y?^Oj$%>_hMRRb+?#VtOAsrF}-W5&3;+dK)G7aT{^6H|=br;;d>Tj`gND z+KOGh>Akip&OL3#w%&B2t@6)nCqC>=i`$9!deg3Uiu%2s7~7jB-XU^(Q}G>2<+?k> zkG<%}JCy&hJH^3XH1AHarWb9zQ&B(ODL(H-qf*7JUi5yd3i3&+nAVHFO;!GXrHa$f z(X_in^>g&aU5fhlF0uDH`sXgO^EsN+UIkg)UMzi%cC}ajzqc13JVz7n789PMd3P)S z;=9F|=V<-iD*d_lh+m$ix%Ui`Ik(_mQTZ%wyjQG$mJZ*msNXt>)z8xS`^4O5Y0-V} zsXo8*e)0CRH1Yw#58$UhpmZ*LK%DAHpFW^;o_;`l)03v8DFc?JiSnMbCry0Rla8dd zkkNejpjgtA${rMxdeScss?5xPNR01E%O6s4u6$S=?Lpr>EPn1m)ekHG*^h|LJ*ec7 zLS?}5M@4B5dNWwl>uwh#he~gu5S*fi(x(JOuDk>lgGqA-D&q@%9>-3i38nf zQb+N1clw}XD{0Nij^dN!Uo%w# zK6_e>$fW&Gi(k9Z$)~TA0!5v~kKL%W(@G`qdS|h%8-37OY-FypR|*{IEQ-3($Y-vR zHzm)Ah27}8XT(2U>C7|Vt1#oco#dB`c=i+{pAH;$w3_dflN&`zTK+{h<$JDDE?R)O zU7gWRaoR&$oMLQuHNhie*xgE`(j%ISl(DqrP0cji%Nh9%;&!#k z$x#h;%ALnFBj3fqQsnd8ZV#QOp6vv;%Sd`eitow;`r$ezql16 z=CNHdMeOEms3!wm*K(VKdW#~S_Q>=zU4Yz~$Pd8eW0J3UDnzRPqM0BzOTlTs>6d4Z(vR&bM(PVnhNJhRDZxyyoK9{X#@_JpC-4yzV*?Peq~p z=$0Qc@KdU-Ve+Mtzh&ml43}@5Y!2tlTOT2xmwm^(#{4Wzo_@ACQa*P(5cx7^O_bQ_ zr5Q4p7DS8v@$|iP9*ve2<2{*S#WCVgJpC@6f5*rwF(-B*zxl?QbhXO6+Y4R%O9%5@ zG{+&>`6)l*=C?YOoA>jE^OF`-<*OU9iss@A7u_Mn`F#|2a-bb9xn;1HpHe$L%Rg3s;wG*2Q_AG(^w>5a^ou*dP^Xmyh-zAUupE0Ym5b- zwnpEVAilKi`o7>B;7*Ns2Q?DpdFGPha95{$-{5J`L%M-K_7kkgiz7QwDpI z4{CousJ=)Q_dHyGMMe+YT z=_A;igL271yw-G?`|h<)Gc>F{CXd$X%UGq;SF&1T>>8x^TBNVp|4#Zc{?X-8V9EvY z+gY4LsdipL`B8V<$)8#MKn0Kd6R~aw|{nCZDzlv1klf~u?hqku>>GUIhi&)KV)di-nY^*N75~QaB zn7m%6FS)(8D+`#0apywQXC1%jpkLXX_aDZu9Q5mc#fuI|JC+m%Bu|J zLBmi!|IPWIKNR)FqcIKTZt9a2t1hs9Wxav=wOQAzG++U+2v`BkLcdpp`F;lalM7v6 zlwlp=GxKws^+grp%Rqd7j1PXSC$cdAj)gwcKPSU3Uxi<1k#&86d(%Icn0fpfEuV${ z*SfwaK>TIjX}JP}2xr$n#~#%3|7m@Zg>_LDZD)_118l%YMuZqe=Lzdb&pz2*RY&`UN~Ry6tp8-FXE_7>VV>`Vg|0P|ka z_S35x|EJe?eq%4thj^`an)|~>-Vpx*lk;`@N}#s_n7mb|r)Vt72lzjoz7p7*11$Ov z>FW`5VdWP)S*I@z>B$0?0BMp=pAYyyoj$*@7w9+f+LTLC?1iPT3h66@-sEjMJvl&s z0q%ijenVz|3jM=>b^OUN{UG|s3h1%h-}st=$XDsTC zoqSH+3#*@b({%f*g5IL-x<2xO$SR7oMH=&f|JUnhGSZpz|MU83$~6b+DFXga*Uy|f zy1rGQo~D`lW2vAH+*@($)!M`G7d5MWKaGzYlb7*t%-?DR-nYbdsqxQ1^*8rJaL>=d z)Kzeo#z@>xS?yP@DBK@Hy|0h^s^PkQT#Wlz;6*^f^NR+!4+Z}5&)L4xImPLhKtlcJ z@9b~$E0+iNe}?P(aNN&tuN@J%PXxvT4Y-V>K-=fUePXh9#Nj>!m;lU~=vOYoZy2ZV zjom9?Xc**8{QsQQ>FF_6%k$#^l|B=W`$cu1I8yr~`2Sf*o~iTQn!xhaennLRtAU<1 zev+3Lm;_7#rUKJ}nZRsdE-)Wh2rLGc0?UDwz-pjpE#e0z0aJjfz;s|HFdLW)%m)?% zi-D!Ua$qH}8tB2g!wXCTrT|lc>A*~2HZT{M4=e;0151JBz)D~>(1UfO7nlT00j2`e zftkQ;U@kBpSO_czmIBLxmB4DCXFc*Cm;_7#rUKJ}nZRsdE-)Wh2rLGc0?UDwz-pie z>p(9s377&*1*QWtf!V-ZU_P)ASPU!$mIEt+)j$vCQ(j;aFa?+jOb2EHvw^w5d|)B4 z7+4A{2UY^Bfu2pse_#?Y1(*s<2WA4Zfw{nZU?H#=SPCo$RsySm9?U1az$9P_Fcp{% z%miiwbAkE5LSQkl6j%A*~2HZT{M4=e;0 z151JBz)D~>(1Z1l7nlT00j2`eftkQ;U@kBpSO_czmIBLxmB4DC2m3`{U=lC|m zW&*Q;xxjp2A+Q)&3M>a!0;_=@tfRcZBwz|K6_^gp1ZD$sf%(8fU@@>1SPrZNRs%gd z(f)x+z!YFAFddi)%m(HH^MQrHVqht-99Rjg270jH<^?7JQ-G1(pLVfz?0{_LIH9Bwz|K6_^gp1ZD$sf%(8fU@@>1SPrZNRs%iQ zfA<2DfGNOKU^*}pm<`MY<^v0X#lTWvIj|B~4fJ4t*$YeprT|lc>A*~2HZT{M4=e;0 z151JBz)D~>(1U#&FE9z10!#&_12ciyz+7NHun<@bECrSWD}mKO5BA5sz$9P_Fcp{% z%miiwbAkE5LSQkl6j%7nlT00j2`e zftkQ;U@kBpSO_czmIBLxmB4DCrvl?2FbS9fOa-O`GlAK_Twp%15LgT>1(pLVfz?0{ zo`ZRTNx&3fDli?G3CsrO0`q}|z+zx2upC$ktOj}xBK^Q5UfIUvDuBylCQnK`9O7h{VUhEXqMdKN=^Hk zCtrWl^~u*KQ>`E^nzd}!;@a9FnsFG#^Pz722lpP(`5DFm{WSJ4uAY4cbnBNz&HD5m z(5+dUws&7UpmTTJb?-B<*)s!s_Ud|V&#u%=-u39*zXvtzI=Bz((>S1?_Q~$nuYb?J zeQMowV!wXfdUcio;L7SXfSUE})06)X=r)M|XYvjE_3heuKxb<9{D2xg-FkG&?AN(> zw@y8}vKn*8`nz=L)NN3gZdn65aY}l1)9N~P?$@vLV6D!$pY6f{rCwd~C82?Ei#z_Xm|YS4XTqC(%|FAn$exc(V_gI8sa9g9IDbsvE{>3A3+i;y2+<`iEP>n|<1xi8{R5*OlQT`Og}DJaf`SX`j5N ztoBP_R6rMLsQHiVsJS1_uE6jmtNqHa1mS%?bzAc<7A}Kt@_k_Vii3V7QE^ZKIpv4; z0hbA9sA=p73~%<~5AlhN@(NS`&;7I7U%*~6yq0Fij<)yzl!|=<3D_fj{oo_I{p^z0s^zs z8vkZX_y(PI_y(PI_zz_V6L4AM|Cart`OoB%dG1j)T!;Tp>Hmqt#sq{n&qer58D`J7 z*J}SCEF;rz;t$1hmC*lU_*0hf<~s!+!pEA1#&YuVssHExg>dB3QWL+~-%sXG^W~L> zily()rN`t;EQb%YKWA2^3YRlWhsaTP=l+@W8;rMvCp_2T@9b3|pNR-6OgMv=TEhE^ zbo{;|9p2jhO*muG6&zl2CjEYdZ-wv+nixrqzS_5RCE`!E@Fu+Mp93!zSC_#$d}rc@ zmx3vXzqt{Fr{%U*+X)OGyAt`Ityv$#B>pq$H`PM+FTvu^OO~T5pUbgILCrsF{52jy z94@x5rPF_&kBfUNGtLKky4Vske%I#RHO~`k^McHHTbuXPJa4SchmaW`YxALG#=Y8n z7@6^`HqU34P4ov+%I)HrfEj-RJzYF1S*6^~m&}wfQ(Q{bFrCo@)BL01p>=$@F6ZG~1I<^W9r* zK9NknQ=6|(ra!68bE`J}M1Y5jE+*6d189!70hxAPo4+LRR=H*U=7WpRT0P|4!x1E1 z^_h2aITjr9*9y`Me1(N?1K#=_;bY7@0_-&HEK~94=kx2(W4=%1TXjw4{|-98yjCzD zEM2Q?_}$FQbon|;i-|BDqwm3&fN!pRd7i=sOL=-+%l8292cHH0N$~BNSLt0RQ^?;T zf`1PD72wTyJqCJ8o@=8dT^N@NAfE+!)4#0)@3ZJ}bGTsn5YN1W+gC|UJEgx4A8979 ztHJxg%lV$X+JMiA*79;5C$Gnum-$eJ@A=HU_hlP?7I;7Ei5YIbQ2HBC#a^91oE&xW z!GS^T=VRA`@_fW#P(GYHeVP9m81GCzw*;R9-p}FXbuaV5^6g2;m#oxwngQl{#a~P< zp~u+&l969hTb|Db4XS^pkzcLlt#(#`H+HUPdDR~MZIsqrl1JaeAwA|YKd&~z**T>Au za?e4#a6*qM_X6;KczkK2$CP`;_S)rW%Kc`Wa<5olTmDBI{eRo=@&LnN>1x8fY`^Ba z+NMa?z2MDvwynYUw9)gb(Sz?-(@=5W0dKx%od-SZZ1jA^ye!|05?wB4q-o;OcAD=; zM;SZ8o9{_`89SK|mfj(dH{WT>dAz)4gE!x8zOQLM7a_QwGUio#SyS82i+K7c^RwnV zN$9x+d=9>wG5W{t7+$;LZ1m%fPR&(X$Kk=DRa9Ui<^ze1~Sr_i`Qx zg4xrGc~wu`sVc@E$hQpe=6f$W{>dxHM$csCWxl21`>kVIoDLg3_`XLTODC@wo@lH5 z#P>d}(Y}(I4`yd7)Sgq2 zH}Az8J(u!6mrR#=Pu}Qh&3v$QJpg(0{<+c9A3WiGU!&&@8$An|m-%0{wRXKdYxLl~ z%p&C5mAnt3?1X+(Z|`G1n4R5?d>vg+{)C=4z?=6z$AOpCD43q*O1>^7VqXH{v_|p4 z=gGnJY*+H<&wKgIOitJN^XDVX^Dj`HH$OiM-a4PJ8%b2x7#D!oFyGL5F(sov4~1WQ zB_BmOAL{%!VY9&d*R@fS9l3qVE06ivTu=OGw0wI_6CavO4S8Kq@J6O$a(JAU*HQ51 zeO|L(4dE%KiAziB|4kGhMdthJp74CeM*a=RR~+;!$;Z$S_%fF+v6 zyxgO)UaM^M98f&>OAU3r{2N2+ai=l_^|_z=AL z?$`tQt%^S{T5|H1fwVtkjjo3ksE0|4KVSZS8-4)vWYy7n#yE9YJ|-(@{`2YPDqeG* zM+Zdp8}qW(GvgCfzqG+hhOQD&mZN*zs#cRRk+sg zS1eI{0^}Fz`o?1Fx=Zo=dvI(0U^MXg(yE@A@AE;l-ls$K~GjQo!;@#^S6zB1D^UQ`!Rl* z{--7Ls(-sd>oNU9C&-sPt?O+|)c;Y6=jR&h{3b~XKLuZlUuwzI$qyZ=RC3#>xi>+wf)J&G*bEWMl&!uQ@Nw^oqsud|Mm-UpD+(isy0UHC?{Ej8)esHuB%t@JFF13;T78 z99mDkM$&$s?_s~!W~1kG@aEhbqvxcJ{546z?df8}kF()F zR(uqh^OVeb`IwFTwM~M@+rfsWX1Ek{#IQNH^a_{ZRFpw;XkqAk3hdUw=n|= z6IbbcE5Z0;#-oRrm+c}0{SQx9)RoPAuy!#TdMYqp8$G+3m+id*<7PMLIjQvHCIBL? zM!YZU^5RW8bu|TV&b8X(*1TWw0Se&Ex8YaW@JDU@g!PfJvo%k&g5^V38-50Ob54Y@XSw3}IXKQqG4>o`UXFLZ zDVa*NDe8mgIvsD#c|TCpO7Z;Lvv2DBd=&f>;4@y)JU0h*4P;)Xi(Kv0eS7dFN**@> z@FnE^N3weA}@UdQ956wL1sEwZ3<~rVrYHcScM_o@cUkC0$7|OhC zkLJ9Df5CG*^Qxc0`jopDbyZ4vxC0@97oL(g=cX9H4vOb|!+B~?!y^~+<~$c8zZCLC zZk^tT9NK3$^L4o1R$%|ur0Y+}oAXaRP*lH#E-#AHdf04r-O9YG|08t$H}ky*AfGcv z=UWou9S7c=2i*aBJ^*iR7uysMp#V4zdFy;N;YOWr<~(N;T7c%Gl{)%EQTr&iP%yg7Ht)VGn)W9%?k$h<7~42%m+;c*;#{1bKk zOb4HEvzE^hx}P!aqBHZs<_W`@SL>spS`Sa>)U`_SxCwv?!*BKnu>8vdt#m$^^OB5b zPv%v;mudYby}3%B#}VxNnRYrKyg4VjD-`W#Ue$l3%f#OF79FpN&)`Gg&3R0Qe_8Qz z9Mt7v#=+%~H|Gc%`2&zQ=e2c*M>XV)oWTaIgWGev;<;bNd@l?Ex-c)(RbYAU_5t){ zS@QV+^pxTKlm5`-x>d((&IdB~v<7eP4fc{e_w(jlY*~lpwN%OTK4i7dpX(zvzu!jB zNgF=qHlz#BN4UDG>j~y%eItz5y}-Y~yln60TxL^GURUxE3V^waJ$a83QIn>2M@6t=xg{b{u)j?CNm#wJbmBD*OKO6pl4pSYpg^4 z@K0uk%pX7YLz;u{p?D&nCEjTv z+kLhDV}%aU3w+g!T7M%b%4J^0TXC{>ygO|4pSIzzyi4bUb>4dqc=J0Q9+Ypk;!SGK z;au=F=eok{8|GzyYtHdD{q0f6n{#-LrW@O9d#vMN2gMWRZ1o#ag@Yk)&X+fN`xbaV zp8I4Y)KciFrG#(3wBhOQ;N{iAhVRb2EEk_;{;*idb9+aBTNnAc$3~Cq9vyFmCA}$% z=Y1H||4B&5eay>sN&(K}H}!m=;;pIWUuA`!9Ly8AnW$@?;`u#UOT4R?m;GVv&APt5 z2>B}JRsBbQW#YZ%UgX<0KO{BuQasO}E&D3NjC?I=9`9`UpKSPO?nq@FFy}}cb?w2| zoZkqKp3F=83y3=|zKs3LlswPhhU@ltbA%4?7xd`6bN?^BPsf|J&3}$$*KLaD`2+gZ zp74DM^0kEdroe{(6ncE|+8+I%=pf|Hxz$Erqx+>jye_y?OE!ncEzHaG(qFn9&G?eb zd_(5V`TVhvpQiK}t>gCWOwt-JWy;|th{O?BpcE3@r@X|DGPc4#f9#%X*$LXQZX156;@Qr(v>r~5x@Ivi?a9FV zEnM8{`W5m8kLh&10>18}h_}oSMngNp*J6o!*zi-CSNVYFzoxtnDfuWq7eU8c7yAAJ zZ=F}v;|0E&7vVfy?(Woe3wZN8J!Tw#47~MueLwKA+jaij06o*0uLE}=lt4ZMzpuf~ zR$bpS-zZQJZt+;~@=CJd@3rAaDW3BO&vQ-w%(9U$l|1)L=6AZBuqUdc&NtsQ)Cbht zW{T(af~9<)GxC=ANyb3ln&e{0mn7(NTmpdu%=?0T@Afm~v+z6=(@AnZuI;S&Q0qyD zo!2oh$M>S^wEaz?|3M|s@9kRb9|t`-cu&LR+kD7d?OzMt{9b|a{{wu9MZf`!v=e557#h0tTp1vh$1!KYd5tYTj3PoAUm z=MVJr4S1n#>WtAL@m9ri{!G&HF4WIXHu6K5m-?$(XnFblp}dwbFYV`F=2iE`{=cC= zCr0Pbi;%zUXq_QjK9o6hx|~SY{mje$-26V+F$C=izQFQc&{*bGxm%vUmn(UG zPtsy%a)y>Kz;hoz^uNTsw5J5`X*7a8g^;hXyf;+^-jCS)UX5 z=U+2bj3!<8FmJ*JWCQh4JnyGHr1NdGL;KD&dMwY^RzbetS}orZ%E}?{A6YxzQ;;{m zpJm2{%eaG;_L$$@F*bDpZ|)7gY{M^SUZ&TF_jpZuzhPd^ht2P7CPL9srH9)i#*2PP zZv!@4mWvPju|`jK@c!Lxl?FfbEN5QLhdnwUdb_lTeBDT-o$>ODaTL1o8P14YNoCu;LYzw82LC};LChAzb^!FdKSF7H#mWLnV%Wh zFY>|TD;s&wvr<3r(|)e&iHWxd%DCHRbR zT@SBAz+=oy`wRZm_Ou6o>vO@&@nIYORpwQf8P6M0xffsn7lep)uHlI$lMK{F46hZXS3BGEA=Eor4-U9E#K7gr*Mc~cv z)0+NdH}led!gE#At}lCDmv0f;%eBaduFM<)v=MlFmH4k z9TM+VJdacLwVfy~>SZJUD)Tb`3(o3tOop;e&{OuZ)?@msgaN_hy}|H%{Lr9bvf_Dv z8|!xud{=-szYosCkh*?1dT?(bdZ6yN&F^BG`g1w+!SW$h@f@#ZUiTz;^E;?U&nq^1 zX4&u?z?DJ zmsh1j2igJs0Vc{%=?-%~gF zKf*@;0vmpt;(6Wopte5;as2?k;w#N(As-qJ3ZAakHvA)sXZ={WntUDs-uzzpyNEZR zd0D<0PCdSu^8F6-)_r>#EbZZT`jT#UZrFJl_$u_nPDI?1d8xky^I@ZZu9All0Z_uc z%x4pjz+}i< z^KAk1GF=sx=VHepZ+@T9=)dYEJuX=HweDbE>A~|RGmcDPUfOSd&%Og}TCDg01L0iD ze6V_ZSn-^n<8^+T{IBi=#isx|_-!Dm^UeDGdv_&YONF`_ z!hEoF<=MzDRXmShV|BThIexKy!a}caUXTpTWLuI`DzO&w@9<7i~1&JPiF0=COWw3}@b?(a1_%#=PvG&F`|BdQuAcJWF{UQ9M64 z!TRe4D2pB*T>tfo=l%AuHcGM+FXQ#$`Ds)5 z?KbjX`U9l-bB~d*e}K*hbSHF+(WAD9sljf)|;W{cWt}Jb~Ge&%r)`saKza&q&bq{6TnB zGcW6NiDh5+j7O$8B4lmLQk^Ao&$>K=klmOW?Xhm z(&?=L-vRbs&b*x0mEgUvWbk(>dEU3R=+6dkNiNN_;a4*+%eQQ?t`BcT=#WR4m+8u| z?1SC>X7K#!sCceT>$IK}7%&9#ITkzLfqVtpwMp+b=4HQ;jOUUje=4BInlATS+MWW7 z{>I>~^0$I7vB*EGc9JbF z=W9Wpu;0}ZB5~7nx(dGW*9z1Qe36BJ34Do#F9csp3Ez||p2x3htzZ7$gS-yd$e(6j zrq^dV2dw>cZKn=>?tc%(^Z1VSubGDrv5|ileC$5|IVJ2`$GnU;2k%|@;2Sd|c)X2l z_*-oFr@^OL;+?>}n&;sAVzaL}Tgmf01kbs8!Jc){lVQ>GGkA#AKuccW%X*t*k?+I2 zOfMbP{f{3ZK8AdrMgDv6HHzVIysh;VAm5Chdzm+FJTT1DkoQ@>bAQ)HexnUv3BF>V ziBZRL<1C~L?ZVXa9Ol)00Pm?L!l*fl542FbSK08t+3*Pk!P9$-4gZAVc|Rdr_rty1 zI^J=R_kZix1pb$RPqXmHm{;$&VBTxS_r%#cy=i~=m4=Vhe?Iq~c{yHN&(V5B$wMdr zUbW#DF<&P@&N#P2KF4BbmEw6Gi1!0c-4JuMJ=Sx&8Zj@+s|@q2T@D??V~RJiox}d% z3oP-DV_w$tl8AOn*pDDzL4Vc5Z4}cG{Bh>hd7Rfh5z$aVe zm)Xc4u;C*Lb$!c7*7g)QbWGPM-Wn@^ZvuHg+VABMc?Ntkz85p~XOxYeGVnPT`y=OT zd(ytq_O!x6>o&!oZ%>8|{{r)}J|`dZt3b^Wbfk^^eCB2O7GPa$`p*+ep2zW~+8(oS z>E#8TY^Sjv&71e!S~9QN9rhbdzcdW;S;)6g*i+1Wu>Ry1B@dwh2zyu8lQK)bB{MJM z^;_O+dP&LiJmD&B=X*}AY&!EYf2{A%e+K;(7X3d!55?&A_!trp@t(FPz(nP2ZukTK zT3(%*mv)k;o#IVCzsJ1lpHsB{hY)HHcxea4>x$Up#v2UqXS?h^!xA~ zpsx-6j|!qec($hd=KVjJ}jfaE=SAzX6?aS&u{MrJ&3LbMljz{ z))Uh0C>%bMAfIK4cax2tLpHo?skEQxOL+gJ5%f0zpJv(D@`Jbb=NXFU_p2@TOaWhH z;Wt80K?_~a|AlyeWnR_?AD**!1b@@A;N|#`4d2^_f5V1fWccs=h*86D%u9O+@58i* zZ_DMu?HOppFS6lFCC~fPe(b+-Ggnug;^6wPV_w=*0DICP|DuvVf8XP6@Ya6pGw>zH z{7M75dHPcEP#OToZTR}Uz>(u-2HsD24PkC%zHUHx9yWh1{{@jTC2 z(^g6Lg#16u%Xq7<*F0|{sOz#7!Q<@?zQ9tx^A*qQLCm*JK5PK*8>aO)aBBUIk9EA( z^S3Wyz7A{%gyzi4d?>QS`waL%S?L}M{dqU*crVknBNrL>3VU0C0752db-%&Yy7F`4Q<3w$Q?!P4~#Ef)Ux0q~Ch$dy z$4vn2w&6XWpk84C*}`A`sjkmC7GHi6^1GqOhxea5g1_uDU0zuh`PSfL z=V(3kAU{Cz+@F-7y%-xlg1q${)NP7K-~gzGo+9kqaC1}F?Vkrv*OQ7re;+;@d=Z{g z7&||Jo~(m@tr-8SnOFUTWgKtwg{}{=7>`UleVTcb#y~~c;PVdp18G`dBfkUstY|mwp5K4;Yx4*{ln7>U2-LhdOn*`{74Ab)v4_`gQBxv;Tl@ z{W=Zk-Kk5jzJ0p&ryx|PPF?$U>fWpGGo5>N>N=orzy6&%4;(~Y`u5K1)onnxuFY<` z@x~iia}c3UnLYdT?9{nmzs`d@b?Y;r-(bq@*SUAMPF)A~?md`;1l)CE$pN)Qdw1^H zr&*V*EPC*+ZteQ^$?Vzvk-mL<^;cA zlRMqlscX;vS$+F=yYr!YAMSkj|I^x)cDIcq+x(&&LA$@T7bWfS63KGXGxLRqmS~F| zNmMAxvFF#nTUZMK#fa(m-kcdnqDT-ZRNcC@U@`f)OUvqGhprmTZt=p`quIPF^X!u6_h<5}tF%h{^k0*Y`Myj)cKaA+wRleG=l{JG!_QfDn{U6*cUiW4%-*WS zK{&vcp z??vCAiJmC7$tKwy_N$9SRTbOYVv(-rS%tOC7vHnx@BnSPLw%J`Ao=Flv{dJJb=VtMuEYjs=y07Nhc1c%Z znc0F5?Dr4ZtG>xA$%h@%m_|gO)C`9U&%L`)K%o9A^D2ADUMACg-bwP@i22NyFf|jG zSjaNHO`o#$U-|MS(^GbrE>@UBC5!UPyZ6~+nPu!EIsOH`Ujd;~Kg59jsV33xVsAV` z@GeQ@Xzg#$@XAciZ$*dZh<|c+x%zJZ?H0z&jXxvPRaLnO3D#mZ&(_(Zx+|916-2Oj zQ7`_l!{({@L|TV^x+xY(C_Wf&uLCLHWL26#!l52$Pw?yLmAZX%P4un2Yu(KBy5=|h zzWhpgXWDu4>FUnj_vYTdI0w>9n{;2LRlbn-fihT6rlZ-Hr@t{VbnPA9P5rBXNnhsE z>8lZ&qwnulrSARNw|b1>4ym72w|ez=HFx=7-kfb2wh{j6D|bg`(u1X;$H|cibAeqI z`IQ`2%}%3fv?9Xq>0c{vO@n6(9$X=xP`_{KA+-aKE~n@8f>($yl8=gY0sXd4biFI( zoA{#Zf3FuXHsO&$6aREIdp$FweC9p)Act$`&a5dLoD{fN3m%;dt}pB6!uy`)g70gs z=jx~Vl3!VKYyW$FYhOXst2FwdzE0lO%B!3X{;j&H*^73xb$Sv%GuPGM)P5@kqE=fI zTmUu;6!||F3oD*nEW*dosGY7-k`Y}a$6jkw=-0K+39qhuPJB)B>EZltl1%QefYcRi z*MDog^ySm1`Q$NqJioY|;EJpN+@IfFU*b{^NH6^lU>(Zp!>*FpGx@v7w}1Tc`S$wa zGUe>0B zDgaEcr}F#%(lUR|6Cciw_E~kaDfltDzxld;o%DtPw7{}r@I$R%f*}FTtTB_1 z-$c*btn}G+%{cM7g!l?DUJCb=KmM3i$$-8Wg8(}TqdBE1J!V1WPrI`}i+y#zTmokA zar^suBKq(Q7QiC<(}{i(IX3j0F+7f^GA-Y)fP=kJ%-`XaZ64t^T`!8Q=wN2Z_j$~B z@M(}$6ny|7@r_UzL--LD?tlmH0-z51Jm zXztwKuZo}EAmeS?9R%*kmmBAZ(9O;yviz23KSl2q|Gg{9>d06l({R<%k~N-1=4*`U zk;ryprba!@cn6}tDGvMW4vv9-96=%a$e*C-p#)c}yXx?zyx!S+xk9EjoN8XhtsnafqW-DcQd>Vj!mEFi%HsVUfvhck%B%l;axc>U!nd(9V_ z=ziH{TLRql)x?Om8mx07&X#4dGZWvLU73Hm7eAZ*3CX(x+7@EJO3Q4SY!85^=89zT zmL^Z&Dz?cYtrn|4{KH~u@itCfwp@vR zr(q=mQ(|_RCXKqC*?m_1EXwajpA(}sk=t)BV1h}6ZqxVTPzh2=z?2mf@%}C?A-Ver zF+pzS9NjcBbk!6#Lvc^`vd8%mQ+9*T&!1op(?vz%A+;(KpJKBCJx1a~s&1LBueZzW zZF&v4S5uqDQ`Z)usQ+sd13HWxnn`aP(w zh0F=U7^+7K>}2Y+!*9J?!>iToEOA_o;^|s0ArWfrhVb3Xd@%t(Ihz90RoX0$*gvpM z=n^|&*w7qv>30&eUJVF9z7RQeGiSE$Y<9WI7T>WwffBGkOW-f?=#wWqx%b1_V-B7ZTM~PF zoy}K8h1=lX3P*Y7{wC1&qC-@Sx=>?HAh_a9Y4o#nxm16Vc2R$^&Ca3iuh9eSgtB9# z7H$xgkr0NW3HUfmH|u?^-eJEQU@p?qy?7Yckh|3yCH1h;eg{&sdZtJI&;3-?AZlZq z^=+|JwB@^oNh_bzMdq2kFfbv8(9mi#Xqo}WkKWQOgc!o+!L!*CFIiOi^SicGSOM&q zRk3vAv#TdMg(5Nui#Pxfz-A!pmDT_BOolH+e{q0ITTY8T!W2L#>@H*|9W4?G18LQk zyY$#5eXg?gI^2|)n#dp=w?H&lXOhPo2tA?aiC(WM99j1@!2_p&Xu6!DH8%Ao`h^&0 zZ`lHRWD1;!-87fZnp>7=%@No->|V-rnN3JY^cJcUF6|8Ih+Vgn%oD^{Kr)os4q&t> z)0Yebmb}Ej|DE(cA_j*Y0`U)tp+vM z`yH?$r1;CB+8wI1S#`I6ArObD8zTrKzq>77q=)cUIgHtUGW$)77V}x%646WpUMEr~ zdwAqG@f%oo1YP$~sR^b;&D+N_l1c~P2vf^A95dLGsS9_t5@xLpd(Xw05Jf}HRzEZOcVb2j4C21iW+-Q5#Ih3q#dq=Z~S^#%J zdKRWE3b#3-5g) z%8mBDX`<%4bV2SNgJ{FqMTtxa<(aRG63aZCT^9IDFUfwtNVm`NWCqw6Z&)dI<_S49 zP(gB;u*aum{t7%ge#o9>1bjgGHP2eJ8|>EG_$Gs9ufpts46imToXO*8@YQowM7_A7pB#mM#_ zc%_G%!Hh_7f65%X5wvYBIVPzN5MUrFIcFw6c5~#zC((oZoxOc3kxWETDMnBB+0gr# zu9o(0*ko-&hHF<@`#kZN;UVAl@V)!%72^mrt7 z%ujvaoPuU9Fx1yl$RY31WCcYmxcWiLWsc#9O=bzBj>i2#!U(y(b6QJ&tg?M@Fp zEA9_#K&~<@nwVKAAgky^N9RkEuA9!2&BiVT2rT7dD_=p~-im2MFvI+=zeN7IHMBIP zfq&$TO|$Jsm)RD3u3o^D8)O_yvQn$RJvS;=CwTwA zDL1;MY>FmFeuQ1{GI`te7U_;nQOie+n-#htCSYqvKhttc{?k7*vsgp!-Ec2bQ4ihO z`ECb9DlH^t_W_*$!m1ABMs60ncXHdE8dq%K;0N(S&i4Q9_E z12s8nH{dFaqvSY$aL6j7fVky=`>#n;?0?-668Myt8)$Bj(UHceooE-;5Q>M}B2k4? z*)A&8!&J|!cZ#WI;31vnbsIwyHH%lf)41}r!cX+vw|t*tqB(#X!2E0vqKi1|JVU`& zia3z}dj%;lGnBc<^RuMsj-uq*lz!~M!+0;9)9PA5t|W!bm3;(qbN{wW2q}wb@SY*Toi&Ouj!Ew280Rzr$IfiIj7`3deOpp@ z%4a6-SxzJU;a=2SdA7tgmFztlQV^PXsnlzq&tcGPnSjmq?|MWz1Og z7UdVCCiw5YEeEOCm_UwU+9w%OL1DKtW1e6C$AQ46893z$scZv8TVWySM=;$wi%AA+ zzC2@3&XZgQG6pEV%|JX-QqL=jRTvW%plF{z3G?|>`Le+Tj)ijL(!M1OHkEhuApgiG zf>tDIianJR4Zx^G>|{$xH-O!8ulacG0H}M0;-UHlk_;TpcLJT*at98ZKxw$4hE&sT z?GssU+NrYKxn(^#LO;Pel25fEZ=xdBXYYKW_P z&kj38QR{=OzSt)sBt@-{VCGx7M{-j6{2jl0XC`gXZBgv_vbgDSSi8}c@x9!-C1@$v zqei)AFp7qKczP%rtf z=qzN72(i{?8EFC89_&)6|9ZPeOiz`P@J+~*5ZG@{b+3rpbACL>4KxVr0%Dd4gOVHT zWW)McsF2I5uNdD|_N+=wWaKCo-kt(uAkhJSk#UD-v|NW#6XNhZMJ9v|o)x{N=VPd> zBedZ7K3U;Q_-}y)Z$IWo;v= zBk*GMjI@ngDAcX6z|7y(f_d8F4B4AHp_Pb1%HHD^Ibz+QBaEiCtecbihV&&V9z1kQ zT%-)*B6=(Pw8#JoTa+5=V347=NrBCQw1eUuTi6c9{tg(+Pmz!huBDXP0^a}x7?W%) zV#CYZ(cRajiCMZf*dHUH_Bm3pR6><~4CSt9l20aDa=qmld$tXf{dU7(`i=bKhvKJ> z`+yh5JzQkbB-Rn)gfR}Y-jV%#KwTB(bxe>Yd&I{;l6d)5FFPn6iIB z`veY=Bd%GNl0S{2i%5dYH?(|w6p0YjbV22zd8UCZpv_blWAL0*mo;A()&An$RDK7U zT+#M~lz1^HFv^n^$)}V~IF(pK68)6YDN)sFnh3B-^rO0TnK4@0KBzIELK*qGUT}!n z_fva4F!+2zy+797m;uecTOJ(znymlu7+IZcPMFEPAg6_fv=-C=gD_1L;Pd(1di%=L zS-Sn#e1AyS$Pxh?h3#PZe3%rVcrw8DBRe2y>y~vh4f#_#+-6c`XvIungie|RWj02R zJP2KnqBCpE;9G-AwS$iYuuI(#T`xqBOBdb8;x65Pzeh8;tTfJpkxXk*1`G60;eyrD zp7oj_9rO$2A4xSM>YPbYT4FGjr9Vnwwj98q$zk+U^<<#PD#KHiq^E2tA5n2&lbjZp zr0k(USl8}bwptWIFv6j>w%W~D1S^M1LZnGSVdn@?Vfltxkkm{ro z1ENrToh)EwD$q^5v6XT#)Ee~AkYn~cdkDI>x9adwqLLWXY;_G`|#{R4=>x1#QrGbs^5ndqiZ))N!M ze2e-;RgpbApslK^92s7RAA5szVo2}dS7Ym_TcvXcp@x&Wbdg-*zI`&Gqm$tWBzqc-Br&;y?%gR@67 zHbe45HbJlhG9={moRI?+`Z=OoIC|(9bH5-VCHxlWM%N{y^odXke?g%vK}ruD6<%H_ zi!g2y!$ro-LCgcx=?}ZV!!ON@B+Gq~fXQC2snc*6lZ(lKM0GK!%L;|B#4>*PCX&s} zLK*0FgGfASELoD|fd`BEYjBu(2`e*aGK>5gl`4~vFe8o}>H4ORRzpg(ldfZqHrOel zBS2)R#Ax}xO*dXti2=_b3d$#j#NF-p{>raxXHK#~F9^v(;#eF-8Spkv;<(9t8=yT* z7mI9%4eqAcO^XmJ_M!J%B(JCD5z*V57sEcLK*=OB3m(hQ;DmF?oHv8SrgRx3@gLVF zV(b;OCohQCs7@Izfx)l|cuHVUQ>x>}k1H6d-Ar`RlzG?JSWCLbEf(nuw}{?vl_V+* zi62qLkV1a$dJ=S}qr08`VMlILwxm9C%3gcUtbhF(wZKSMUSYN5wM`VqUFMN8v%U{h842vNkLeL!_m9M zOH90i0eS&Og5F2D7F55Vo!D}agC^;VX7v9{<{Oj<#^2Jh9W@b=EY__8wN{72a*lN6 zr&LAzfK+NfkfTY4hy6Osc0Q=3`iM>NS!_Z@2MraGtw~8JWZS3c`pT2XLgtSuog_;- zQOsh1oJ5bZy={UOWi8%)OFmDMtLypYmv57Y|0L&^H?l?&hDFt_h)(u~{J}eF-U#zy zwwK-IEd>tU;Tm}3cvp1KqOw+5rDoDon3;3-JK%0=qAi1G>WImd8yL=-{SUp+^8K2m z(G5`IM3%{ir-w@^RZ>Ji$Gs8i81C2~lXvUR9@1rAsG?e~zwKg19{9)$h)A(nOx&y1r46 zhBXeJ@{Ji#!L>Z2>?{?^y?paFvvRATQ`^igVL^{0NYh@B(zz`Yr>(NQ;by3Suy!A#)-uQ6sY=9nD)TGO?Lqj!= zD+MZ$i`^Yn(h~1i6HT1L|2E%CmZ#$YD9hj@k=)CoGa)p%m#7}66xqpWDIAS^M8PYC zpbg;&y-0&lAG*h4Ui=*uPd0uDWuY~NSz;DkQOOf1f~JNkA&+3+&$?8i55jx1K|5#N ztt-ep_X9pG0O07yaL6ZSqPCpke$)Ol3`XF`gq$7uLG{G~2#xp?Z*{b>Xz0a4z1P3e z2~H|~3`W#b>-8BR5xa|Rh~i^IhRQaeX;qank1*QLr!-qTsPf!QhhJS#wy!=>Ue8eD zJfNx^d|Y9Ak}LFAqYmO6@H4bB-tO0MN+>Op*i?})+4XF_k<1{T?5C-CB*ie_-&03% zrz%Y~N`Mb6wg{mV#qRxjVWydCPGiCv1CYUn1YBRV_U4I3%&60-(y8RXslVLTLM|nR z#Tz>0jdAAMQZ5d5TPLYyzRqNzOLE+D0kxA>Ujc21EYX4AfX3_;Let3MRG#I8wtF=? zJ5DNva-vAY=m99|4jy%`3!a&Zq86VeVzCC>2lOaX&)sC=nPG;PZ(}`u$fzGy_+piv zB*qvVk7)vIP6~)??3E+0mns9oZP`+F^_o?e+JV7a#jh>Rw>NlS{TPNiq)_RVjNn?y zHU{JuRqAqbjRp+&ZoK^h``vPyMh$cUSf5|)DYE5s)*)>xu(&KYMX5o0b=S>h3`L<@ zxj1#hqxEQ6ri1>lwCF&0*dXW8Nu|@VVY5rGRn;(>?718wMX5KcV};w&f*MS=6xD8%s78x0g58v-#E_++ z{)0=jo(!>x80v2kl7#NWsXh~os}DI{KVTcW+#L6wOr>@rp+ezogTZAEj6Q8&!#pz? z3bTkkg=H`ZrPp`|jK!$hgp7?ALAtu1zC=r4lTc)1Jf#(68%Z{D3{ru5Au3|55gnlf zH{uW^gRTB;*Kqq2S+{^>Y`SEo8cPK)5lKQk-|O)@ z3_(H2xT27+#S;~|;j|0J`Unnmy6Pvq#eRiN%?v~UdyOQ9Gte6b;Z3h@-w$zmN`RpS z%=#WKNwJGyO6@9jwVhP{=QW)(Y9k-+@F9(OTdGCTAc#aczOy|PBFDHUr4K$F2J}@4 zoDX&cs~^TuFO%-EUM4NyV9-QcTT*;b70BS9OrP9}!-1^lmHmMC(G&?4SyQUR30o*H zW7;stF2_+vQe6EhWqPsEwvr}QnOy=mM6DxvUDzuoah`)r>p^J|ZaJT#sY1x7l}8MoJKBs?PWUKTQ$+{}z>v)NM%Xc0ef9F~Z)}U*gCbN2^ zraVF?px0K!HD@}Q`zKHPJzt9G;7WlOCzie9=T~a0&-S`Y=cj@$q66p}CZVVVqH`aR zK`74-yLjiA#D6{F64cwVI0&7LL+r?x?fRX!S5h>)@yuh4>Hu^75q!`sF-%t=MrCZs zcMYL%ZOAI<87hln?$WpL{4Ar3n0`D-80_y*A5DA0>K?U4JlqzADxIBh6m&B=2B?9J zgX7-_P*5>yxX&o5MfF5C0!0xDu6(-{a_%JO=}f+F*|k4(_Txfk7ZnTcmIvTvjKdgI zi-8u0fNO*A_1ZqNc){a_Hu4Bktf`HWj@iLGr1sw&|9TE%-H~UWI+J|%k)y4EJ=9c_ z(RR~~-YKRShP7Dh{6s4=1y0~XiP>NFpZ1q6mD}iO_69LCHEg5kgX~2?$$o;P1aqFG zM9oupV2l>XdVfu-AJ;i`IH23C$|bHI_C;Aa4RKXM7)m61 z$edHGbe}n=_^3H=O9Ay7D4>=y*>AWNWU|Juh>e3uXXAdA-RK1iv`dC^CJ|D_A zN?tZ#8entEiq0zMxu5cM4#f`IL)Vy*GqXakcUo$+q3L`DZ&~l=T(^j?`c>OY+Uj%~ zl;of34>$Mv>==w(ZUpgpT|A}0ZFI7XyUM&EoG{zPK%E}O2_1{XWn~KC@Hh$COB2FV znR#Q3yBNBLXOZ3wMIW_Z6?0P>Fl`jS`3uZIREo{Od6j@1e^lC5{T8Epfev=XHHs!GyJ9$Q- zM&q(~Ko{zN*}dIz^9>sw+VWQ2rbG*0Sdl7(U7-&`ku0I&X=1NNC$Z3Z5zf8qfG*b& zrl=N=xjv;LS3}pQ#>mt5Qe83p<;Fv6z0v{B7G6>#aYR3)cWS{#hU~7iy$&2U7}h!k ze{{^t5Q~!FYC>F-nf*@x1LLoH^s^PCK}eG3=t_s)AX74NKtn z%7Y}iN^vXpC)cyIUz=`&eR2Uw<$y%dfhbL{)k@|ofMVvMK+6gxfYWD$qbcV8(c)l-xO&B@u zg|i82_X9%BH8vc)%EN4b0StYiJuL*`q$w0KojYezD|9PcAT@qS%D-OGFIbhvT_PiO zpQ$4oe4<3OI`6@~wLG@{dYj8Oc*J-*@n#EndVexs>DJ>~cjM-)o=}j@G==z2yUpYc zcnldyAvCX{87b;5BTlE(CE%AnJcbCv&nl}2lod)6!UAh-Lnkyf;X0c>Mc#)z?-bYT zN&!3D788cf;8A9)NquvrNN`W3Mo31L_EV54L5>D>ETsx*WU59z^lG($+Dj^aO%rX< zLhB-(Fmr->v$Y2Fq5%lB#1w-jatUqA0}84Z_y2t4(FNA$~xoSA{obQ10lBPhH4lBzYodub&3Q}dx&$8y>=v+&GitD zf7p|MEQ^>J%uYiRz02rehyjkV#$RqQX85E*3v1swB4zgkL3MS!+TaD3xp6?#*K z^il^|c&eynZ-yoi6YMM3@X3U{d@-;lnbY>Q&OYTrVqVN`YQm&$T9rLS@-tvN3On=} z>)1H%Uv70>s7lZ?nob+>DT!Jdn;;QOFRCeWWyQ7JC8d_cb;)u@RApAqV^ORhaU6Ax zmLX>+bRW0^!Q5Hs6<)`omlr@kj#;FvAr%xLp?ep?=R}U zxLu%~nT!R%ZWub$^C(X2c;*c6S@yO=BdehQPmNpH?ebQGpR)qRO+o%gT$Un%u{=VZ za{pO!SGV`$>$cQx`!99AFEBC^<8^p16QBu2IOV2B-J@; z;B7-Vxy5KyJ94~Nubc922NJPAe?oWi$KoP;kieQ6X=7u!rf97AI6a=KX1$*GNa z%Q&am69yfdF5PZZTesT>)kfp0Fgejwa@H^fe5=^o*bQ^CuhQU&2AqOh4-hbj>`9&P zQy5%5sAR2{$gbCv{uB}^x}CSlzxall(r2`8)a|^9^?3XSG*7ucZ|PJ1D$p!E+2^Dp0UJfr?F@TWczx3pCJL0deD8h}qV*IsP4OzXybUda4z9!< z2Ta+m15CeYdKS(w;&COg(iQ3!^-+EFJlYt}r$Hk%RW7T_G~7hF9VYtV2V@D?9L;h6 zU;6i85ht$`G57%^ghr0207ASYT{lk$TTon_fkzU3K6xbQ`y zECZc9#)=471exX(ib|$Ykd;y>h{dHEGM(k3aePm<#BZ`1%wFp*&%mf^M775um@i=t z|AuB^-e60;Ic##7J-zv>=JMYxs;DunUZSeZ9>(gD0SV>PdfBuEnAK?cTH_`&NKC*x zSHL}4BmD`9<5C63c7PxVM$pn}Y9f_<3qWqmpOP>-G5{;}q(8hk>j$*#h<16)+3GgT z78FM8Wk~t2iL~@&JQu@ z`p{5xZT_{%-v(ppso$5UDY1spQd z=EdE+YTb7-IH${CCbt0p9L zV6Z7;aI!+}Qq)!Gr~nndG+La7r86Wv;cPiI!{dyW4EnnQ+;OVgceo;4I#?i|PMrn~ zTzZ!p^9!^X=I=32s-rxq(0Az*d?zjBWt~@+oxx!r7q|lC(F^P6QJVnKqTa!*bZql! z4Wy(5y86^YedA@D)#kb9bP97E?xwuBD4CTvrs(QiPL^)ICs1wyvy?vJrF2lhORlvd_hO5nBj!l=C~e9b?%W7;u^iDrC9V) zt&o+^FbR7S8MA0G4)}k`IAWtwk>s!1+#A>-XW?7E&wXB)VXR-qk6S9XQIlf3QA^VU z3@_g)(MP6-GvzVFYg2~n1m%3!2$d#PG7076`s{a_pvfLY36EmFF$7Gw7^VTk!~Q<&8GH!ca1`_AC8Cv zymM2-T%6OKQ@BtXjSOjJ&-aTwuV32Gq#MzwW0n5FvQs}(y0v>Jt8$1xRp~d#CDH`5 zLblnvmB9Z4gL3}@ literal 0 HcmV?d00001 diff --git a/src/prm_control/control_communicator/include/messages.h b/src/prm_control/control_communicator/include/messages.h index 54d2786..f86cc8c 100755 --- a/src/prm_control/control_communicator/include/messages.h +++ b/src/prm_control/control_communicator/include/messages.h @@ -12,7 +12,7 @@ typedef struct _AutoAimPackage { float yaw; // yaw (deg) float pitch; // pitch (deg) - bool fire; // 0 = no fire, 1 = fire + uint8_t fire; // 0 = no fire, 1 = fire } AutoAimPackage; typedef struct _NavPackage diff --git a/src/prm_control/control_communicator/src/ControlCommunicatorNode.cpp b/src/prm_control/control_communicator/src/ControlCommunicatorNode.cpp index 1b69381..d4286c1 100755 --- a/src/prm_control/control_communicator/src/ControlCommunicatorNode.cpp +++ b/src/prm_control/control_communicator/src/ControlCommunicatorNode.cpp @@ -60,7 +60,7 @@ ControlCommunicatorNode::ControlCommunicatorNode(const char *port) : Node("contr this->target_robot_color_publisher = this->create_publisher("color_set", rclcpp::QoS(rclcpp::KeepLast(1)).reliable()); this->match_status_publisher = this->create_publisher("match_start", rclcpp::QoS(rclcpp::KeepLast(1)).reliable()); - this->uart_read_timer = this->create_wall_timer(4ms, std::bind(&ControlCommunicatorNode::read_uart, this)); + // this->uart_read_timer = this->create_wall_timer(4ms, std::bind(&ControlCommunicatorNode::read_uart, this)); RCLCPP_INFO(this->get_logger(), "Control Communicator Node Started."); } @@ -130,8 +130,8 @@ void ControlCommunicatorNode::start_uart(const char *port) tty.c_oflag &= ~OPOST; tty.c_oflag &= ~ONLCR; - tty.c_cc[VTIME] = 10; // Wait for up to 1s (10 deciseconds) - tty.c_cc[VMIN] = sizeof(PackageIn); // Block for sizeof(PackageOut) bits + tty.c_cc[VTIME] = 10; // Wait for up to 1s (10 deciseconds) + tty.c_cc[VMIN] = sizeof(PackageOut); // Block for sizeof(PackageOut) bits // Set the baud rate cfsetispeed(&tty, B1152000); @@ -166,19 +166,21 @@ void ControlCommunicatorNode::auto_aim_handler(const std::shared_ptrx != 0 && msg->z != 0) { dst = sqrt(pow(msg->x, 2) + pow(msg->y, 2) + pow(msg->z, 2)); + dst_horiz = sqrt(pow(msg->x, 2) + pow(msg->z, 2)); dt = 0; float pred_x = msg->x; float pred_y = msg->y; float pred_z = msg->z; - yaw = -atan(pred_y / pred_x) * 180 / PI; - pitch = atan(pred_z / pred_x) * 180 / PI; + yaw = -atan(pred_x / pred_z) * 180 / PI; + pitch = atan(pred_y / dst_horiz) * 180 / PI; - pitch_yaw_gravity_model_movingtarget_const_v(P, V, grav, 0, &p, &y, &im); - y = y * (msg->y > 0 ? -1 : 1); // currently a bug where yaw is never negative, so we just multiply by the sign of "y" of the target + // pitch_yaw_gravity_model_movingtarget_const_v(P, V, grav, 0, &p, &y, &im); + // y = y * (msg->y > 0 ? -1 : 1); // currently a bug where yaw is never negative, so we just multiply by the sign of "y" of the target } else { @@ -191,13 +193,16 @@ void ControlCommunicatorNode::auto_aim_handler(const std::shared_ptrauto_aim_frame_id++; package.frame_id = 0xAA; package.frame_type = FRAME_TYPE_AUTO_AIM; - package.autoAimPackage.yaw = y; - package.autoAimPackage.pitch = p; - package.autoAimPackage.fire = false; + package.autoAimPackage.yaw = yaw; + package.autoAimPackage.pitch = pitch; + package.autoAimPackage.fire = 1; write(this->port_fd, &package, sizeof(PackageOut)); fsync(this->port_fd); - RCLCPP_INFO(this->get_logger(), "Yaw, Pitch: %.3f, %.3f, FIRE=%i", package.autoAimPackage.yaw, package.autoAimPackage.pitch, package.autoAimPackage.fire); - RCLCPP_INFO_ONCE(this->get_logger(), "First auto aim pkg sent."); + if (auto_aim_frame_id % 1000 == 0) + { + RCLCPP_INFO(this->get_logger(), "Yaw, Pitch: %.3f, %.3f, FIRE=%i", package.autoAimPackage.yaw, package.autoAimPackage.pitch, package.autoAimPackage.fire); + } + // RCLCPP_INFO_ONCE(this->get_logger(), "First auto aim pkg sent, pkg is %i bytes", sizeof(PackageOut)); } void ControlCommunicatorNode::nav_handler(const std::shared_ptr msg) @@ -274,6 +279,7 @@ bool ControlCommunicatorNode::read_alignment() void ControlCommunicatorNode::read_uart() { + RCLCPP_INFO(this->get_logger(), "reading uart"); PackageIn package; int success = read(this->port_fd, &package, sizeof(PackageIn)); From d49566d564d4619ba010abc24d604277d3636ed2 Mon Sep 17 00:00:00 2001 From: purduerm Date: Sat, 15 Feb 2025 17:30:18 -0500 Subject: [PATCH 09/12] fix coord system definition --- .../pose_estimator/include/PoseEstimator.h | 16 +++++++--------- 1 file changed, 7 insertions(+), 9 deletions(-) diff --git a/src/prm_vision/pose_estimator/include/PoseEstimator.h b/src/prm_vision/pose_estimator/include/PoseEstimator.h index 0ad2d99..d2cbad8 100644 --- a/src/prm_vision/pose_estimator/include/PoseEstimator.h +++ b/src/prm_vision/pose_estimator/include/PoseEstimator.h @@ -94,15 +94,13 @@ class PoseEstimator const cv::Mat DISTORTION_COEFFS = (cv::Mat_(1, 4) << -0.1088, -0.0721, -0.000847, 0.0); /* 3D object points (measured armor dimensions) - * Coordinate system: - * - * +y (yaw) - * ^ - * | +x (pitch) - * +----> - * / - * v - * +z (roll) + * Coordinate system (camera is facing us): + * + * +x (pitch) + * +----> + * / | + * +z (roll) L v +y (yaw) + * */ const std::vector SMALL_ARMOR_OBJECT_POINTS = { {-SMALL_ARMOR_HALF_WIDTH, -LIGHTBAR_HALF_HEIGHT, 0}, // Top Left From 020343f0da9ee31a768594be8116d53025956e28 Mon Sep 17 00:00:00 2001 From: purduerm Date: Sat, 15 Feb 2025 17:44:20 -0500 Subject: [PATCH 10/12] no more | param.get_type() --- src/prm_vision/pose_estimator/src/PoseEstimatorNode.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/prm_vision/pose_estimator/src/PoseEstimatorNode.cpp b/src/prm_vision/pose_estimator/src/PoseEstimatorNode.cpp index fea5987..e371fcf 100644 --- a/src/prm_vision/pose_estimator/src/PoseEstimatorNode.cpp +++ b/src/prm_vision/pose_estimator/src/PoseEstimatorNode.cpp @@ -61,7 +61,7 @@ rcl_interfaces::msg::SetParametersResult PoseEstimatorNode::parameters_callback( validity_filter_.setPrevLen(param.as_int()); RCLCPP_INFO(this->get_logger(), "Parameter '_prev_len' updated to: %d", param.as_int()); } - else if (param.get_name() == "_max_dt" && param.get_type() == rclcpp::ParameterType::PARAMETER_DOUBLE || param.get_type()) + else if (param.get_name() == "_max_dt" && param.get_type() == rclcpp::ParameterType::PARAMETER_DOUBLE) { validity_filter_.setMaxDt(param.as_double()); RCLCPP_INFO(this->get_logger(), "Parameter '_max_dt' updated to: %f", param.as_double()); From a68b4af0921e45c58576ddaaadc26746ee87c920 Mon Sep 17 00:00:00 2001 From: Tom_TKO Date: Thu, 20 Feb 2025 01:00:30 -0500 Subject: [PATCH 11/12] draw top-down of robot (scale maybe a bit off) --- src/prm_launch/launch/video2detector.py | 4 +- .../src/OpenCVArmorDetector.cpp | 2 +- .../include/PoseEstimatorNode.hpp | 1 + .../pose_estimator/src/PoseEstimatorNode.cpp | 67 ++++++++++++++++--- 4 files changed, 63 insertions(+), 11 deletions(-) diff --git a/src/prm_launch/launch/video2detector.py b/src/prm_launch/launch/video2detector.py index 39643d5..b1c17fe 100755 --- a/src/prm_launch/launch/video2detector.py +++ b/src/prm_launch/launch/video2detector.py @@ -7,7 +7,7 @@ def generate_launch_description(): webcam_publisher = get_package_share_path('webcam_publisher') - video_path = "/home/purduerm/Videos/moving_but_no_spinning.avi" # example, can change to your liking + video_path = "/home/tom/Videos/close.avi" # example, can change to your liking return LaunchDescription([ Node( package='webcam_publisher', @@ -15,7 +15,7 @@ def generate_launch_description(): emulate_tty=True, executable='VideoCaptureNode', parameters=[{'source': str(video_path), - 'fps': 4, + 'fps': 1, 'frame_id': 'video', }] ), diff --git a/src/prm_vision/opencv_armor_detector/src/OpenCVArmorDetector.cpp b/src/prm_vision/opencv_armor_detector/src/OpenCVArmorDetector.cpp index 52db195..4d95529 100644 --- a/src/prm_vision/opencv_armor_detector/src/OpenCVArmorDetector.cpp +++ b/src/prm_vision/opencv_armor_detector/src/OpenCVArmorDetector.cpp @@ -52,7 +52,7 @@ std::vector<_Float32> OpenCVArmorDetector::search(cv::Mat &frame) std::to_string(_frame_count) + " (" + std::to_string(_detected_frame * 100 / _frame_count) + "%) and missed: " + std::to_string(_missed_frames) + std::string(" frames")); - cv::waitKey(30); + cv::waitKey(1); #endif // If we didn't find an armor for a few frames (ROS2 param), reset the search area diff --git a/src/prm_vision/pose_estimator/include/PoseEstimatorNode.hpp b/src/prm_vision/pose_estimator/include/PoseEstimatorNode.hpp index 0c56855..b1991d4 100644 --- a/src/prm_vision/pose_estimator/include/PoseEstimatorNode.hpp +++ b/src/prm_vision/pose_estimator/include/PoseEstimatorNode.hpp @@ -33,6 +33,7 @@ class PoseEstimatorNode : public rclcpp::Node // Class methods void publishZeroPredictedArmor(std_msgs::msg::Header header, std::string new_auto_aim_status); void drawTopDownViewGivenRotation(double yaw, double X, double Y, double Z); + void drawLineWithAngle(cv::Mat &image, cv::Point2f start_pt, double angle, double length, cv::Scalar color); // Callbacks and publishers/subscribers rclcpp::Subscription::SharedPtr key_points_subscriber; diff --git a/src/prm_vision/pose_estimator/src/PoseEstimatorNode.cpp b/src/prm_vision/pose_estimator/src/PoseEstimatorNode.cpp index 8a51c23..e3fe120 100644 --- a/src/prm_vision/pose_estimator/src/PoseEstimatorNode.cpp +++ b/src/prm_vision/pose_estimator/src/PoseEstimatorNode.cpp @@ -136,19 +136,70 @@ void PoseEstimatorNode::keyPointsCallback(const vision_msgs::msg::KeyPoints::Sha void PoseEstimatorNode::drawTopDownViewGivenRotation(double yaw, double X, double Y, double Z) { - // Draw a line rotated from the x-axis by yaw. - cv::Mat top_down_view = cv::Mat::zeros(1280, 720, CV_8UC3); + // Define image dimensions + const int imageWidth = 800; // Width of the top-down view image + const int imageHeight = 1000; // Height of the top-down view image - // Draw the target offset from the center of the image - int target_x = Z; - int target_y = X; - cv::circle(top_down_view, cv::Point(target_x, target_y), 5, cv::Scalar(0, 255, 0), -1); + // Create a blank image (white background) + cv::Mat topDownImage(imageHeight, imageWidth, CV_8UC3, cv::Scalar(255, 255, 255)); - cv::resize(top_down_view, top_down_view, cv::Size(640, 360)); - cv::imshow("Top Down View", top_down_view); + // Define scaling factor (pixels per millimeter) + // Since Z ranges from 500 mm to 4000 mm, we scale to fit within the image height + double scale = imageHeight / 4000.0; // Scale to fit 4000 mm (4 meters) in the image height + + // Map real-world coordinates (X, Z) to image pixel coordinates + int centerX = static_cast(imageWidth / 2 + X * scale); // Center X in image + int centerZ = static_cast(imageHeight - Z * scale); // Center Z in image (flip Y-axis for top-down view) + + // Define line length (adjustable) + double lineLength = 20.0; // Length of the line in pixels + double robot_diameter = 150.0; + + // Calculate line endpoints based on yaw angle + double angleRad = yaw; // Convert yaw to radians + + // draw armor + drawLineWithAngle(topDownImage, cv::Point2f(centerX, centerZ), angleRad, lineLength, cv::Scalar(0, 0, 255)); + drawLineWithAngle(topDownImage, cv::Point2f(centerX, centerZ), angleRad + CV_PI, lineLength, cv::Scalar(0, 0, 255)); + + // draw line of typical robot diameter + drawLineWithAngle(topDownImage, cv::Point2f(centerX, centerZ), angleRad - CV_PI / 2, robot_diameter, cv::Scalar(0, 255, 0)); + + // armor at other end of line + drawLineWithAngle(topDownImage, cv::Point2f(centerX + robot_diameter * cos(angleRad - CV_PI / 2), centerZ + robot_diameter * sin(angleRad - CV_PI / 2)), angleRad, lineLength, cv::Scalar(0, 0, 255)); + drawLineWithAngle(topDownImage, cv::Point2f(centerX + robot_diameter * cos(angleRad - CV_PI / 2), centerZ + robot_diameter * sin(angleRad - CV_PI / 2)), angleRad + CV_PI, lineLength, cv::Scalar(0, 0, 255)); + + // more lines of typical robot diameter 90 degrees from the center line + cv::Point2f robot_center = cv::Point2f((centerX + robot_diameter / 2 * cos(angleRad - CV_PI / 2)), (centerZ + robot_diameter / 2 * sin(angleRad - CV_PI / 2))); + drawLineWithAngle(topDownImage, robot_center, angleRad - CV_PI, robot_diameter / 2, cv::Scalar(200, 255, 0)); + drawLineWithAngle(topDownImage, robot_center, angleRad, robot_diameter / 2, cv::Scalar(200, 255, 0)); + + // armor at other end of these two lines, perpendicular to the center line + drawLineWithAngle(topDownImage, cv::Point2f(robot_center.x + robot_diameter / 2 * cos(angleRad), robot_center.y + robot_diameter / 2 * sin(angleRad)), angleRad - CV_PI / 2, lineLength, cv::Scalar(0, 0, 255)); + drawLineWithAngle(topDownImage, cv::Point2f(robot_center.x + robot_diameter / 2 * cos(angleRad), robot_center.y + robot_diameter / 2 * sin(angleRad)), angleRad + CV_PI / 2, lineLength, cv::Scalar(0, 0, 255)); + + // same thing on the other side + drawLineWithAngle(topDownImage, cv::Point2f(robot_center.x - robot_diameter / 2 * cos(angleRad), robot_center.y - robot_diameter / 2 * sin(angleRad)), angleRad - CV_PI / 2, lineLength, cv::Scalar(0, 0, 255)); + drawLineWithAngle(topDownImage, cv::Point2f(robot_center.x - robot_diameter / 2 * cos(angleRad), robot_center.y - robot_diameter / 2 * sin(angleRad)), angleRad + CV_PI / 2, lineLength, cv::Scalar(0, 0, 255)); + + RCLCPP_INFO(get_logger(), "Drawing top-down view with yaw = %.2f, X = %.2f, Y = %.2f, Z = %.2f", 180.0 * yaw / CV_PI, X, Y, Z); + + // Display the image + cv::imshow("Top-Down View", topDownImage); cv::waitKey(1); } +void PoseEstimatorNode::drawLineWithAngle(cv::Mat &image, cv::Point2f start_pt, double angle, double length, cv::Scalar color) +{ + // Calculate endpoint of the line + cv::Point2f end_pt; + end_pt.x = start_pt.x + length * cos(angle); + end_pt.y = start_pt.y + length * sin(angle); + + // Draw the line + cv::line(image, start_pt, end_pt, color, 2); +} + void PoseEstimatorNode::publishZeroPredictedArmor(std_msgs::msg::Header header, std::string new_auto_aim_status) { vision_msgs::msg::PredictedArmor predicted_armor_msg; From bc57506c0f517e2ca47808d2188346ae56165b6b Mon Sep 17 00:00:00 2001 From: purduerm Date: Thu, 20 Feb 2025 22:54:50 -0500 Subject: [PATCH 12/12] change optimizer params to dynamic ros2 params. change img display to once per 100 frames --- .../src/OpenCVArmorDetector.cpp | 22 ++++++++------- .../pose_estimator/include/PoseEstimator.h | 8 ++++++ .../pose_estimator/src/PoseEstimator.cpp | 6 ++-- .../pose_estimator/src/PoseEstimatorNode.cpp | 28 +++++++++++++++++-- 4 files changed, 49 insertions(+), 15 deletions(-) diff --git a/src/prm_vision/opencv_armor_detector/src/OpenCVArmorDetector.cpp b/src/prm_vision/opencv_armor_detector/src/OpenCVArmorDetector.cpp index 9d50242..f5f6d23 100644 --- a/src/prm_vision/opencv_armor_detector/src/OpenCVArmorDetector.cpp +++ b/src/prm_vision/opencv_armor_detector/src/OpenCVArmorDetector.cpp @@ -40,19 +40,21 @@ std::vector<_Float32> OpenCVArmorDetector::search(cv::Mat &frame) // Display the cropped frame for debugging #ifdef DEBUG - cv::resize(croppedFrame, croppedFrame, cv::Size(WIDTH / 2, HEIGHT / 2)); + if (_frame_count % 100 == 0) { + cv::resize(croppedFrame, croppedFrame, cv::Size(WIDTH / 2, HEIGHT / 2)); - // Create a static window name - const std::string window_name = "Detection Results"; - cv::imshow(window_name, croppedFrame); + // Create a static window name + const std::string window_name = "Detection Results"; + cv::imshow(window_name, croppedFrame); - // Update the window title - cv::setWindowTitle(window_name, - "detected: " + std::to_string(_detected_frame) + " / " + - std::to_string(_frame_count) + " (" + - std::to_string(_detected_frame * 100 / _frame_count) + "%) and missed: " + std::to_string(_missed_frames) + std::string(" frames")); + // Update the window title + cv::setWindowTitle(window_name, + "detected: " + std::to_string(_detected_frame) + " / " + + std::to_string(_frame_count) + " (" + + std::to_string(_detected_frame * 100 / _frame_count) + "%) and missed: " + std::to_string(_missed_frames) + std::string(" frames")); - cv::waitKey(1); + cv::waitKey(1); + } #endif // If we didn't find an armor for a few frames (ROS2 param), reset the search area diff --git a/src/prm_vision/pose_estimator/include/PoseEstimator.h b/src/prm_vision/pose_estimator/include/PoseEstimator.h index d2cbad8..ffc60f6 100644 --- a/src/prm_vision/pose_estimator/include/PoseEstimator.h +++ b/src/prm_vision/pose_estimator/include/PoseEstimator.h @@ -35,6 +35,9 @@ class PoseEstimator // Setters void setNumFramesToFireAfter(int num_frames_to_fire_after) { _num_frames_to_fire_after = num_frames_to_fire_after; } void setAllowedMissedFramesBeforeNoFire(int allowed_missed_frames_before_no_fire) { _allowed_missed_frames_before_no_fire = allowed_missed_frames_before_no_fire; } + void setEpsilon(double epsilon) { _epsilon = epsilon; } + void setMaxIterations(int max_iterations) { _max_iterations = max_iterations; } + void setPitch(double pitch) { _pitch = pitch; } private: // Class methods @@ -55,6 +58,11 @@ class PoseEstimator float _max_shift_distance = 150; int _prev_len = 5; + // Pose Estimator parameters (set dynamically) + double _epsilon = 0.4; + int _max_iterations = 50; + double _pitch = 15.0; + /** * @brief Functor for the loss function and gradient computation. * diff --git a/src/prm_vision/pose_estimator/src/PoseEstimator.cpp b/src/prm_vision/pose_estimator/src/PoseEstimator.cpp index ee8e54d..91545c3 100644 --- a/src/prm_vision/pose_estimator/src/PoseEstimator.cpp +++ b/src/prm_vision/pose_estimator/src/PoseEstimator.cpp @@ -39,8 +39,8 @@ double PoseEstimator::estimateYaw(const double yaw_guess, const std::vector param; - param.epsilon = 0.4; - param.max_iterations = 50; + param.epsilon = _epsilon; + param.max_iterations = _max_iterations; LBFGSBSolver solver(param); LossAndGradient loss(*this, image_points, tvec); @@ -156,7 +156,7 @@ double PoseEstimator::gradientWrtYawFinitediff(double yaw, std::vector image_points, cv::Mat tvec) { // We assume -15 deg pitch and 0 roll - double pitch = -15 * (M_PI / 180); + double pitch = _pitch * CV_PI / 180; cv::Mat Ry = (cv::Mat_(3, 3) << cos(yaw_guess), 0, sin(yaw_guess), 0, 1, 0, diff --git a/src/prm_vision/pose_estimator/src/PoseEstimatorNode.cpp b/src/prm_vision/pose_estimator/src/PoseEstimatorNode.cpp index eff1f2a..4b06faf 100644 --- a/src/prm_vision/pose_estimator/src/PoseEstimatorNode.cpp +++ b/src/prm_vision/pose_estimator/src/PoseEstimatorNode.cpp @@ -11,6 +11,10 @@ PoseEstimatorNode::PoseEstimatorNode(const rclcpp::NodeOptions &options) : Node( // Dynamic parameters pose_estimator->setAllowedMissedFramesBeforeNoFire(this->declare_parameter("_allowed_missed_frames_before_no_fire", 150)); pose_estimator->setNumFramesToFireAfter(this->declare_parameter("_num_frames_to_fire_after", 3)); + pose_estimator->setEpsilon(this->declare_parameter("_epsilon", 0.4)); + pose_estimator->setMaxIterations(this->declare_parameter("_max_iterations", 50)); + pose_estimator->setPitch(this->declare_parameter("_pitch", 15.0)); + validity_filter_.setLockInAfter(this->declare_parameter("_lock_in_after", 3)); validity_filter_.setMaxDistance(this->declare_parameter("_max_distance", 10000)); validity_filter_.setMinDistance(this->declare_parameter("_min_distance", 10)); @@ -71,6 +75,21 @@ rcl_interfaces::msg::SetParametersResult PoseEstimatorNode::parameters_callback( pose_estimator->setAllowedMissedFramesBeforeNoFire(param.as_int()); RCLCPP_INFO(this->get_logger(), "Parameter '_allowed_missed_frames_before_no_fire' updated to: %d", param.as_int()); } + else if (param.get_name() == "_epsilon" && param.get_type() == rclcpp::ParameterType::PARAMETER_DOUBLE) + { + pose_estimator->setEpsilon(param.as_double()); + RCLCPP_INFO(this->get_logger(), "Parameter '_epsilon' updated to: %f", param.as_double()); + } + else if (param.get_name() == "_max_iterations" && param.get_type() == rclcpp::ParameterType::PARAMETER_INTEGER) + { + pose_estimator->setMaxIterations(param.as_int()); + RCLCPP_INFO(this->get_logger(), "Parameter '_max_iterations' updated to: %d", param.as_int()); + } + else if (param.get_name() == "_pitch" && param.get_type() == rclcpp::ParameterType::PARAMETER_DOUBLE) + { + pose_estimator->setPitch(param.as_double()); + RCLCPP_INFO(this->get_logger(), "Parameter '_pitch' updated to: %f", param.as_double()); + } else { result.successful = false; @@ -91,6 +110,9 @@ void PoseEstimatorNode::keyPointsCallback(const vision_msgs::msg::KeyPoints::Sha return; } + static int ctr = 0; + ctr++; + cv::Mat tvec, rvec; bool reset_kalman = false; std::string new_auto_aim_status; @@ -132,7 +154,9 @@ void PoseEstimatorNode::keyPointsCallback(const vision_msgs::msg::KeyPoints::Sha // Draw top-down view #ifdef DEBUG - drawTopDownViewGivenRotation(_last_yaw_estimate, tvec.at(0), tvec.at(1), tvec.at(2)); + if (ctr % 100 == 0) { + drawTopDownViewGivenRotation(_last_yaw_estimate, tvec.at(0), tvec.at(1), tvec.at(2)); + } #endif } @@ -158,7 +182,7 @@ void PoseEstimatorNode::drawTopDownViewGivenRotation(double yaw, double X, doubl double robot_diameter = 150.0; // Calculate line endpoints based on yaw angle - double angleRad = yaw; // Convert yaw to radians + double angleRad = -yaw; // Convert yaw to radians // draw armor drawLineWithAngle(topDownImage, cv::Point2f(centerX, centerZ), angleRad, lineLength, cv::Scalar(0, 0, 255));